From 7cd36b6d331d2f793c87ce1b3f2e2f5f8350011a Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 2 Apr 2020 12:07:30 -0400 Subject: [PATCH 001/243] Initial commit --- .gitignore | 32 ++++++++++++++++++++++++++++++++ README.md | 2 ++ 2 files changed, 34 insertions(+) create mode 100644 .gitignore create mode 100644 README.md diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..259148f --- /dev/null +++ b/.gitignore @@ -0,0 +1,32 @@ +# Prerequisites +*.d + +# Compiled Object files +*.slo +*.lo +*.o +*.obj + +# Precompiled Headers +*.gch +*.pch + +# Compiled Dynamic libraries +*.so +*.dylib +*.dll + +# Fortran module files +*.mod +*.smod + +# Compiled Static libraries +*.lai +*.la +*.a +*.lib + +# Executables +*.exe +*.out +*.app diff --git a/README.md b/README.md new file mode 100644 index 0000000..8ce5935 --- /dev/null +++ b/README.md @@ -0,0 +1,2 @@ +# Core +General robot code shared between the "BIG" and "LITTLE" repo's From 191dc0531e9a981f083821c4c3c80c8a3df3989c Mon Sep 17 00:00:00 2001 From: superrm11 Date: Fri, 3 Apr 2020 17:16:35 -0400 Subject: [PATCH 002/243] Finished porting PID and TankDrive classes to VexCode --- include/subsystems/tank_drive.h | 74 ++++++++++++++++++++++ include/utils/pid.h | 74 ++++++++++++++++++++++ src/subsystems/tank_drive.cpp | 103 +++++++++++++++++++++++++++++++ src/utils/pid.cpp | 106 ++++++++++++++++++++++++++++++++ 4 files changed, 357 insertions(+) create mode 100644 include/subsystems/tank_drive.h create mode 100644 include/utils/pid.h create mode 100644 src/subsystems/tank_drive.cpp create mode 100644 src/utils/pid.cpp diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h new file mode 100644 index 0000000..584cb07 --- /dev/null +++ b/include/subsystems/tank_drive.h @@ -0,0 +1,74 @@ +#ifndef _TANKDRIVE_ +#define _TANKDRIVE_ + +#define PI 3.141592654 + +#include "vex.h" +#include "utils/pid.h" + +using namespace vex; + +class TankDrive +{ +public: + + struct tankdrive_config_t + { + PID::pid_config_t *drive_pid; + PID::pid_config_t *turn_pid; + + double wheel_diam; + }; + + /** + * Create the TankDrive object + */ + TankDrive(motor_group *left_motors, motor_group *right_motors, gyro *gyro_sensor, tankdrive_config_t *config); + + /** + * Drive the robot using differential style controls. left_motors controls the left motors, + * right_motors controls the right motors. + * + * left_motors and right_motors are in "percent": -1.0 -> 1.0 + */ + void drive_tank(double left, double right); + + /** + * Drive the robot using arcade style controls. forward_back controls the linear motion, + * left_right controls the turning. + * + * left_motors and right_motors are in "percent": -1.0 -> 1.0 + */ + void drive_arcade(double forward_back, double left_right); + + /** + * Autonomously drive the robot X inches forward (Negative for backwards), with a maximum speed + * of percent_speed (-1.0 -> 1.0). + * + * Uses a PID loop for it's control. + */ + bool drive_forward(double inches, double percent_speed); + + /** + * Autonomously turn the robot X degrees to the right (negative for left), with a maximum motor speed + * of percent_speed (-1.0 -> 1.0) + * + * Uses a PID loop for it's control. + */ + bool turn_degrees(double degrees, double percent_speed); + +private: + tankdrive_config_t *config; + + motor_group *left_motors; + motor_group *right_motors; + + PID drive_pid; + PID turn_pid; + + gyro *gyro_sensor; + + bool initialize_func = true; +}; + +#endif \ No newline at end of file diff --git a/include/utils/pid.h b/include/utils/pid.h new file mode 100644 index 0000000..8ea3178 --- /dev/null +++ b/include/utils/pid.h @@ -0,0 +1,74 @@ +#ifndef _PID_ +#define _PID_ + +#include +#include "vex.h" + +using namespace vex; + +class PID +{ +public: + struct pid_config_t + { + double p, i, d, f; + double deadband, on_target_time; + }; + + /** + * Create the PID object + */ + PID(pid_config_t *config); + + /** + * Update the PID loop by taking the time difference from last update, + * and running the PID formula with the new sensor data + */ + void update(double sensorVal); + + /** + * Reset the PID loop by resetting time since 0 and accumulated error. + */ + void reset(); + + /** + * Gets the current PID out value, from when update() was last run + */ + double get(); + + /** + * Get the delta between the current sensor data and the target + */ + double get_error(); + + /** + * Set the target for the PID loop, where the robot is trying to end up + */ + void set_target(double target); + + /** + * Set the limits on the PID out. The PID out will "clip" itself to be + * between the limits. + */ + void set_limits(double lower, double upper); + + /** + * Returns true if the loop is within [deadband] for [on_target_time] + * seconds + */ + bool is_on_target(); + +private: + pid_config_t *config; + + double last_error = 0, accum_error = 0; + double last_time = 0, on_target_last_time = 0; + double lower_limit = 0, upper_limit = 0; + + double target = 0, sensor_val = 0, out = 0; + bool is_checking_on_target = false; + + timer pid_timer; +}; + +#endif \ No newline at end of file diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp new file mode 100644 index 0000000..54d75ce --- /dev/null +++ b/src/subsystems/tank_drive.cpp @@ -0,0 +1,103 @@ +#include "subsystems/tank_drive.h" + +TankDrive::TankDrive(motor_group *left_motors, motor_group *right_motors, gyro *gyro_sensor, TankDrive::tankdrive_config_t *config) + : config(config), left_motors(left_motors), right_motors(right_motors), drive_pid(config->drive_pid), turn_pid(config->turn_pid), gyro_sensor(gyro_sensor) +{ +} + +/** + * Drive the robot using differential style controls. left_motors controls the left motors, + * right_motors controls the right motors. + * + * left_motors and right_motors are in "percent": -1.0 -> 1.0 + */ +void TankDrive::drive_tank(double left, double right) +{ + left_motors->setVelocity(left * 100, velocityUnits::pct); + right_motors->setVelocity(right * 100, velocityUnits::pct); +} + +/** + * Drive the robot using arcade style controls. forward_back controls the linear motion, + * left_right controls the turning. + * + * left_motors and right_motors are in "percent": -1.0 -> 1.0 + */ +void TankDrive::drive_arcade(double forward_back, double left_right) +{ + double left = forward_back + left_right; + double right = forward_back - left_right; + + left_motors->setVelocity(left * 100, velocityUnits::pct); + right_motors->setVelocity(right * 100, velocityUnits::pct); +} + +/** + * Autonomously drive the robot X inches forward (Negative for backwards), with a maximum speed + * of percent_speed (-1.0 -> 1.0). + * + * Uses a PID loop for it's control. + */ +bool TankDrive::drive_forward(double inches, double percent_speed) +{ + // On the first run of the funciton, reset the motor position and PID + if (initialize_func) + { + left_motors->resetPosition(); + drive_pid.reset(); + + drive_pid.set_limits(-fabs(percent_speed), fabs(percent_speed)); + drive_pid.set_target(inches); + + initialize_func = false; + } + + // Update PID loop and drive the robot based on it's output + drive_pid.update(left_motors->position(rotationUnits::rev) * PI * config->wheel_diam); + drive_tank(drive_pid.get(), drive_pid.get()); + + // If the robot is at it's target, return true + if (drive_pid.is_on_target()) + { + drive_tank(0, 0); + initialize_func = true; + return true; + } + + return false; +} + +/** + * Autonomously turn the robot X degrees to the right (negative for left), with a maximum motor speed + * of percent_speed (-1.0 -> 1.0) + * + * Uses a PID loop for it's control. + */ +bool TankDrive::turn_degrees(double degrees, double percent_speed) +{ + // On the first run of the funciton, reset the gyro position and PID + if (initialize_func) + { + gyro_sensor->resetAngle(); + turn_pid.reset(); + + turn_pid.set_limits(-fabs(percent_speed), fabs(percent_speed)); + turn_pid.set_target(degrees); + + initialize_func = false; + } + + // Update PID loop and drive the robot based on it's output + turn_pid.update(gyro_sensor->angle(rotationUnits::deg)); + drive_tank(turn_pid.get(), -turn_pid.get()); + + // If the robot is at it's target, return true + if (turn_pid.is_on_target()) + { + drive_tank(0, 0); + initialize_func = true; + return true; + } + + return false; +} \ No newline at end of file diff --git a/src/utils/pid.cpp b/src/utils/pid.cpp new file mode 100644 index 0000000..84331b6 --- /dev/null +++ b/src/utils/pid.cpp @@ -0,0 +1,106 @@ +#include "utils/pid.h" + +/** + * Create the PID object + */ +PID::PID(pid_config_t *config) + : config(config) +{ + pid_timer.reset(); +} + +/** + * Update the PID loop by taking the time difference from last update, + * and running the PID formula with the new sensor data + */ +void PID::update(double sensor_val) +{ + this->sensor_val = sensor_val; + + double time_delta = pid_timer.value() - last_time; + + accum_error += time_delta * get_error(); + + out = (config->f) + (config->p * get_error()) + (config->i * accum_error) + (config->d * (get_error() - last_error) / time_delta); + + last_time = pid_timer.value(); + last_error = get_error(); + + if (lower_limit != 0 || upper_limit != 0) + out = (out < lower_limit) ? lower_limit : (out > upper_limit) ? upper_limit : out; +} + +/** + * Reset the PID loop by resetting time since 0 and accumulated error. + */ +void PID::reset() +{ + pid_timer.reset(); + + last_error = 0; + last_time = 0; + accum_error = 0; + + is_checking_on_target = false; + on_target_last_time = 0; +} + +/** + * Gets the current PID out value, from when update() was last run + */ +double PID::get() +{ + return out; +} + +/** + * Get the delta between the current sensor data and the target + */ +double PID::get_error() +{ + return target - sensor_val; +} + +/** + * Set the target for the PID loop, where the robot is trying to end up + */ +void PID::set_target(double target) +{ + this->target = target; +} + +/** + * Set the limits on the PID out. The PID out will "clip" itself to be + * between the limits. + */ +void PID::set_limits(double lower, double upper) +{ + lower_limit = lower; + upper_limit = upper; +} + +/** + * Returns true if the loop is within [deadband] for [on_target_time] + * seconds + */ +bool PID::is_on_target() +{ + if (fabs(get_error()) < config->deadband) + { + if (is_checking_on_target == false) + { + on_target_last_time = pid_timer.value(); + is_checking_on_target = true; + } + else if (pid_timer.value() - on_target_last_time > config->on_target_time) + { + return true; + } + } + else + { + is_checking_on_target = false; + } + + return false; +} \ No newline at end of file From 0c07c0e5b548116708fc03beaed8b13f57edb5c5 Mon Sep 17 00:00:00 2001 From: superrm11 Date: Mon, 6 Apr 2020 13:49:12 -0400 Subject: [PATCH 003/243] Ported Splines, RGBController. Updated TankDrive for Vex IMU. Update Makefile --- .gitignore | 15 ----- include/pathfinder.h | 27 ++++++++ include/pathfinder/fit.h | 13 ++++ include/pathfinder/followers/distance.h | 19 ++++++ include/pathfinder/followers/encoder.h | 19 ++++++ include/pathfinder/io.h | 26 +++++++ include/pathfinder/lib.h | 10 +++ include/pathfinder/mathutil.h | 20 ++++++ include/pathfinder/modifiers/swerve.h | 13 ++++ include/pathfinder/modifiers/tank.h | 8 +++ include/pathfinder/spline.h | 18 +++++ include/pathfinder/structs.h | 43 ++++++++++++ include/pathfinder/trajectory.h | 17 +++++ include/subsystems/rgb_controller.h | 69 +++++++++++++++++++ include/subsystems/tank_drive.h | 9 ++- include/utils/spline_path.h | 57 ++++++++++++++++ lib/libpathfinder.a | Bin 0 -> 31010 bytes src/subsystems/tank_drive.cpp | 15 ++++- src/utils/spline_path.cpp | 86 ++++++++++++++++++++++++ 19 files changed, 464 insertions(+), 20 deletions(-) create mode 100644 include/pathfinder.h create mode 100644 include/pathfinder/fit.h create mode 100644 include/pathfinder/followers/distance.h create mode 100644 include/pathfinder/followers/encoder.h create mode 100644 include/pathfinder/io.h create mode 100644 include/pathfinder/lib.h create mode 100644 include/pathfinder/mathutil.h create mode 100644 include/pathfinder/modifiers/swerve.h create mode 100644 include/pathfinder/modifiers/tank.h create mode 100644 include/pathfinder/spline.h create mode 100644 include/pathfinder/structs.h create mode 100644 include/pathfinder/trajectory.h create mode 100644 include/subsystems/rgb_controller.h create mode 100644 include/utils/spline_path.h create mode 100644 lib/libpathfinder.a create mode 100644 src/utils/spline_path.cpp diff --git a/.gitignore b/.gitignore index 259148f..2a49557 100644 --- a/.gitignore +++ b/.gitignore @@ -7,25 +7,10 @@ *.o *.obj -# Precompiled Headers -*.gch -*.pch - -# Compiled Dynamic libraries -*.so -*.dylib -*.dll - # Fortran module files *.mod *.smod -# Compiled Static libraries -*.lai -*.la -*.a -*.lib - # Executables *.exe *.out diff --git a/include/pathfinder.h b/include/pathfinder.h new file mode 100644 index 0000000..3645908 --- /dev/null +++ b/include/pathfinder.h @@ -0,0 +1,27 @@ +#ifndef PATHFINDER_H_DEF +#define PATHFINDER_H_DEF + +#ifdef __cplusplus +extern "C" { +#endif + +#include "pathfinder/mathutil.h" +#include "pathfinder/structs.h" + +#include "pathfinder/fit.h" +#include "pathfinder/spline.h" +#include "pathfinder/trajectory.h" + +#include "pathfinder/modifiers/tank.h" +#include "pathfinder/modifiers/swerve.h" + +#include "pathfinder/followers/encoder.h" +#include "pathfinder/followers/distance.h" + +#include "pathfinder/io.h" + +#ifdef __cplusplus +} +#endif + +#endif \ No newline at end of file diff --git a/include/pathfinder/fit.h b/include/pathfinder/fit.h new file mode 100644 index 0000000..9b19978 --- /dev/null +++ b/include/pathfinder/fit.h @@ -0,0 +1,13 @@ +#ifndef PATHFINDER_FIT_H_DEF +#define PATHFINDER_FIT_H_DEF + +#include "pathfinder/lib.h" + +CAPI void pf_fit_hermite_pre(Waypoint a, Waypoint b, Spline *s); +CAPI void pf_fit_hermite_cubic(Waypoint a, Waypoint b, Spline *s); +CAPI void pf_fit_hermite_quintic(Waypoint a, Waypoint b, Spline *s); + +#define FIT_HERMITE_CUBIC &pf_fit_hermite_cubic +#define FIT_HERMITE_QUINTIC &pf_fit_hermite_quintic + +#endif \ No newline at end of file diff --git a/include/pathfinder/followers/distance.h b/include/pathfinder/followers/distance.h new file mode 100644 index 0000000..b3b1ab5 --- /dev/null +++ b/include/pathfinder/followers/distance.h @@ -0,0 +1,19 @@ +#ifndef PATHFINDER_FOL_DISTANCE_H_DEF +#define PATHFINDER_FOL_DISTANCE_H_DEF + +#include "pathfinder/lib.h" + +CAPI typedef struct { + double kp, ki, kd, kv, ka; +} FollowerConfig; + +CAPI typedef struct { + double last_error, heading, output; + int segment, finished; +} DistanceFollower; + +CAPI double pathfinder_follow_distance(FollowerConfig c, DistanceFollower *follower, Segment *trajectory, int trajectory_length, double distance); + +CAPI double pathfinder_follow_distance2(FollowerConfig c, DistanceFollower *follower, Segment segment, int trajectory_length, double distance); + +#endif \ No newline at end of file diff --git a/include/pathfinder/followers/encoder.h b/include/pathfinder/followers/encoder.h new file mode 100644 index 0000000..7268d2d --- /dev/null +++ b/include/pathfinder/followers/encoder.h @@ -0,0 +1,19 @@ +#ifndef PATHFINDER_FOL_ENCODER_H_DEF +#define PATHFINDER_FOL_ENCODER_H_DEF + +typedef struct { + int initial_position, ticks_per_revolution; + double wheel_circumference; + double kp, ki, kd, kv, ka; +} EncoderConfig; + +typedef struct { + double last_error, heading, output; + int segment, finished; +} EncoderFollower; + +double pathfinder_follow_encoder(EncoderConfig c, EncoderFollower *follower, Segment *trajectory, int trajectory_length, int encoder_tick); + +double pathfinder_follow_encoder2(EncoderConfig c, EncoderFollower *follower, Segment segment, int trajectory_length, int encoder_tick); + +#endif \ No newline at end of file diff --git a/include/pathfinder/io.h b/include/pathfinder/io.h new file mode 100644 index 0000000..bfd37ce --- /dev/null +++ b/include/pathfinder/io.h @@ -0,0 +1,26 @@ +#ifndef PATHFINDER_IO_H_DEF +#define PATHFINDER_IO_H_DEF + +#include +#include +#include +#include "pathfinder/lib.h" + +#define CSV_LEADING_STRING "dt,x,y,position,velocity,acceleration,jerk,heading\n" + +CAPI void intToBytes(int n, char *bytes); +CAPI int bytesToInt(char *bytes); +CAPI void longToBytes(unsigned long long n, char *bytes); +CAPI unsigned long long bytesToLong(char *bytes); +CAPI double longToDouble(unsigned long long l); +CAPI unsigned long long doubleToLong(double d); +CAPI void doubleToBytes(double n, char *bytes); +CAPI double bytesToDouble(char *bytes); + +CAPI void pathfinder_serialize(FILE *fp, Segment *trajectory, int trajectory_length); +CAPI int pathfinder_deserialize(FILE *fp, Segment *target); + +CAPI void pathfinder_serialize_csv(FILE *fp, Segment *trajectory, int trajectory_length); +CAPI int pathfinder_deserialize_csv(FILE *fp, Segment *target); + +#endif \ No newline at end of file diff --git a/include/pathfinder/lib.h b/include/pathfinder/lib.h new file mode 100644 index 0000000..4c15a58 --- /dev/null +++ b/include/pathfinder/lib.h @@ -0,0 +1,10 @@ +#ifndef PATHFINDER_LIB_H_DEF +#define PATHFINDER_LIB_H_DEF + +#if defined(WIN32) || defined(_WIN32) || defined(__WIN32) && !defined(__CYGWIN__) + #define CAPI __declspec(dllexport) +#else + #define CAPI +#endif + +#endif \ No newline at end of file diff --git a/include/pathfinder/mathutil.h b/include/pathfinder/mathutil.h new file mode 100644 index 0000000..99cad7d --- /dev/null +++ b/include/pathfinder/mathutil.h @@ -0,0 +1,20 @@ +#include + +#ifndef PATHFINDER_MATH_UTIL_H_DEF +#define PATHFINDER_MATH_UTIL_H_DEF + +#include "pathfinder/lib.h" + +#define PI 3.14159265358979323846 +#define TAU PI*2 + +#define MIN(a,b) (((a)<(b))?(a):(b)) +#define MAX(a,b) (((a)>(b))?(a):(b)) + +CAPI double bound_radians(double angle); + +CAPI double r2d(double angleInRads); + +CAPI double d2r(double angleInDegrees); + +#endif \ No newline at end of file diff --git a/include/pathfinder/modifiers/swerve.h b/include/pathfinder/modifiers/swerve.h new file mode 100644 index 0000000..0168e0d --- /dev/null +++ b/include/pathfinder/modifiers/swerve.h @@ -0,0 +1,13 @@ +#ifndef PATHFINDER_MOD_SWERVE_H_DEF +#define PATHFINDER_MOD_SWERVE_H_DEF + +#include "pathfinder/lib.h" + +CAPI typedef enum { + SWERVE_DEFAULT +} SWERVE_MODE; + +CAPI void pathfinder_modify_swerve(Segment *original, int length, Segment *front_left, Segment *front_right, + Segment *back_left, Segment *back_right, double wheelbase_width, double wheelbase_depth, SWERVE_MODE mode); + +#endif \ No newline at end of file diff --git a/include/pathfinder/modifiers/tank.h b/include/pathfinder/modifiers/tank.h new file mode 100644 index 0000000..1653b6c --- /dev/null +++ b/include/pathfinder/modifiers/tank.h @@ -0,0 +1,8 @@ +#ifndef PATHFINDER_MOD_TANK_H_DEF +#define PATHFINDER_MOD_TANK_H_DEF + +#include "pathfinder/lib.h" + +CAPI void pathfinder_modify_tank(Segment *original, int length, Segment *left, Segment *right, double wheelbase_width); + +#endif \ No newline at end of file diff --git a/include/pathfinder/spline.h b/include/pathfinder/spline.h new file mode 100644 index 0000000..1bb980c --- /dev/null +++ b/include/pathfinder/spline.h @@ -0,0 +1,18 @@ +#ifndef PATHFINDER_SPLINE_H_DEF +#define PATHFINDER_SPLINE_H_DEF + +#include "pathfinder/lib.h" + +#define PATHFINDER_SAMPLES_FAST (int)1000 +#define PATHFINDER_SAMPLES_LOW (int)PATHFINDER_SAMPLES_FAST*10 +#define PATHFINDER_SAMPLES_HIGH (int)PATHFINDER_SAMPLES_LOW*10 + +CAPI Coord pf_spline_coords(Spline s, double percentage); +CAPI double pf_spline_deriv(Spline s, double percentage); +CAPI double pf_spline_deriv_2(double a, double b, double c, double d, double e, double k, double p); +CAPI double pf_spline_angle(Spline s, double percentage); + +CAPI double pf_spline_distance(Spline *s, int sample_count); +CAPI double pf_spline_progress_for_distance(Spline s, double distance, int sample_count); + +#endif \ No newline at end of file diff --git a/include/pathfinder/structs.h b/include/pathfinder/structs.h new file mode 100644 index 0000000..89ecb8e --- /dev/null +++ b/include/pathfinder/structs.h @@ -0,0 +1,43 @@ +#ifndef PATHFINDER_STRUCT_H_DEF +#define PATHFINDER_STRUCT_H_DEF + +#include "pathfinder/lib.h" + +CAPI typedef struct { + double x, y, angle; +} Waypoint; + +CAPI typedef struct { + double a, b, c, d, e; + double x_offset, y_offset, angle_offset, knot_distance, arc_length; +} Spline; + +CAPI typedef struct { + double x, y; +} Coord; + +CAPI typedef struct { + double dt, x, y, position, velocity, acceleration, jerk, heading; +} Segment; + +CAPI typedef struct { + double dt, max_v, max_a, max_j, src_v, src_theta, dest_pos, dest_v, dest_theta; + int sample_count; +} TrajectoryConfig; + +CAPI typedef struct { + int filter1, filter2, length; + double dt, u, v, impulse; +} TrajectoryInfo; + +CAPI typedef struct { + Spline *saptr; + double *laptr; + double totalLength; + int length; + int path_length; + TrajectoryInfo info; + TrajectoryConfig config; +} TrajectoryCandidate; + +#endif \ No newline at end of file diff --git a/include/pathfinder/trajectory.h b/include/pathfinder/trajectory.h new file mode 100644 index 0000000..fe95373 --- /dev/null +++ b/include/pathfinder/trajectory.h @@ -0,0 +1,17 @@ +#ifndef PATHFINDER_TRAJECTORY_H_DEF +#define PATHFINDER_TRAJECTORY_H_DEF + +#include "pathfinder/lib.h" + +CAPI int pathfinder_prepare(Waypoint *path, int path_length, void (*fit)(Waypoint,Waypoint,Spline*), int sample_count, double dt, + double max_velocity, double max_acceleration, double max_jerk, TrajectoryCandidate *cand); +CAPI int pathfinder_generate(TrajectoryCandidate *c, Segment *segments); + +CAPI void pf_trajectory_copy(Segment *src, Segment *dest, int length); + +CAPI TrajectoryInfo pf_trajectory_prepare(TrajectoryConfig c); +CAPI int pf_trajectory_create(TrajectoryInfo info, TrajectoryConfig c, Segment *seg); +CAPI int pf_trajectory_fromSecondOrderFilter(int filter_1_l, int filter_2_l, + double dt, double u, double v, double impulse, int len, Segment *t); + +#endif \ No newline at end of file diff --git a/include/subsystems/rgb_controller.h b/include/subsystems/rgb_controller.h new file mode 100644 index 0000000..de9144b --- /dev/null +++ b/include/subsystems/rgb_controller.h @@ -0,0 +1,69 @@ +#ifndef _RGB_CON_ +#define _RGB_CON_ + +#include "vex.h" + +/** + * A simple rgb controller for controlling the arduino, which in turn controls the led strip. + * Sends binary over 3 seperate 3 wire ports for up to 7 color modes, and off. + */ +class RGBController +{ + private: + vex::digital_out port1, port2, port3; + + public: + + enum rgb_t + { + Off, Blue, Red, Green, OrangeWhite, Rainbow + }; + + RGBController(rgb_t starting_color, triport::port port1, triport::port port2, triport::port port3) + : port1(port1), port2(port2), port3(port3) + { + set(starting_color); + } + + void set(rgb_t color) + { + switch(color) + { + case Blue: + port1.set(1); + port2.set(0); + port3.set(0); + break; + case Red: + port1.set(0); + port2.set(1); + port3.set(0); + break; + case Green: + port1.set(1); + port2.set(1); + port3.set(0); + break; + case OrangeWhite: + port1.set(0); + port2.set(0); + port3.set(1); + break; + case Rainbow: + port1.set(1); + port2.set(0); + port3.set(1); + break; + + default: + case Off: + port1.set(0); + port2.set(0); + port3.set(0); + break; + } + } + + +}; +#endif \ No newline at end of file diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 584cb07..d667386 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -23,7 +23,12 @@ class TankDrive /** * Create the TankDrive object */ - TankDrive(motor_group *left_motors, motor_group *right_motors, gyro *gyro_sensor, tankdrive_config_t *config); + TankDrive(motor_group *left_motors, motor_group *right_motors, inertial *gyro_sensor, tankdrive_config_t *config); + + /** + * Stops rotation of all the motors using their "brake mode" + */ + void stop(); /** * Drive the robot using differential style controls. left_motors controls the left motors, @@ -66,7 +71,7 @@ class TankDrive PID drive_pid; PID turn_pid; - gyro *gyro_sensor; + inertial *gyro_sensor; bool initialize_func = true; }; diff --git a/include/utils/spline_path.h b/include/utils/spline_path.h new file mode 100644 index 0000000..73de506 --- /dev/null +++ b/include/utils/spline_path.h @@ -0,0 +1,57 @@ +#ifndef _SPLINE_ +#define _SPLINE_ + +#include "pathfinder.h" + +#include "subsystems/tank_drive.h" + + +class SplinePath +{ +public: + struct motion_profile_t + { + // drive_pid controls the speed at which the robot drives forward, + // turn_p is for turning the robot based on the desired heading + float drive_p = .1, drive_i = 0, drive_d = 0; + float turn_p = .05; + + // Maximum velocity, acceleration, and jerk the robot is allowed to achieve (Jerk doesn't matter THAT much...) + double max_v = 10, max_a = 20, max_j = 100; + + // kv and ka are constants fed into the spline system, and are multiplied by the + // velocity setpoint and acceleration setpoint inside the main pathfinder stuff. + // Generally 1/max_v is sufficient for kv (does NOT work for ka) + float kv = 1.0 / max_v, ka = 0; + + // Time delta between loops inside the pathfinder calls + double dt = .01; + + // Misc robot info + double wheel_diam = 4; + int ticks_per_rev = 900; // 300 with blues, 900 with greens, 1800 with reds + double wheelbase_width = 11.5; + }; + + SplinePath(TankDrive *drive_system, vex::inertial *imu, vex::motor *l_enc, vex::motor *r_enc, motion_profile_t *motion_profile); + + bool run_path(Waypoint *point_list, int list_length); + +private: + bool run_path_init = true; + double reset_heading = 0; + + TrajectoryCandidate candidate; + Segment *center_traj, *left_traj, *right_traj; + + EncoderFollower *left_follower, *right_follower; + EncoderConfig enc_conf; + + TankDrive *drive_system; + vex::motor *l_enc, *r_enc; + vex::inertial *imu; + + motion_profile_t *motion_profile; +}; + +#endif \ No newline at end of file diff --git a/lib/libpathfinder.a b/lib/libpathfinder.a new file mode 100644 index 0000000000000000000000000000000000000000..f96adc441fd3bad6c48253e7f03d119a70606a7b GIT binary patch literal 31010 zcmd^oe{j@CmS2x%1Of>&ti>X)WP1Ps@>;MXA+T6eyTgJFtneK+(<(xE&Z*XUt9i_NT#W&tFMXH z?x?G&iA170$o-8(>K`+3B+|TGDYZeV;G5aM`~Os_yZIhHrWC*0chcX^KUPY<-3W8P zXU;0c@7ay!JNElZ@r(aPyrXF#-qY3F-qhOH*WWgv(jIN?{axSj!%el0PfPD}J?#$M z)-{l5>1}nr;{AQk^|ucUGEMmMR(b>_}i&``dpe8LnUH=RPOMAApXZ7|xn_34@`>go> zppL$tp1$v1!?MabS0WP+xw4qB|!BP$GTccLf13iuSw{7eftDx2Fzo9CwkkO z`diw%T6zame{Gv;tL^1?Y*si2+tj&>w3Jet*hfy)4+Gz`@hrP)Yjh7a-t{U z#>qf%1H2-qbAGP9x4mDNIPGWSqu+HaWxDc~J{hSsb=$XY+g`K1W?SY6t%*jrZ{Hq? z)J3<~nK9kG{QFNFcrp+OV4xZkP*o}oDK)lC`xn+}t4iIcinXig+EWv1-{xP0u3VU? zhr3=CPlm!TPL!zUr&bSMnm*S3+Vr0ezC9EE+rODvg5gKMk-`6<;XpL`zKSOQVj%j< zzd~X+0pC#S&<#u%%ZYc$iHov4JG$X&st|Z80zBZ(etq{1_PUz`?=t>80I-;orS|CfHbR{2DjF4`E^tZkQonVWW)$|D}x6xNRobVB-u{!jE{{ zXO;;b;lb@Qg~)Gg{nb=~N~VJ0Wa?M9Z~ygtpdsb=n=5EY1-p^2EmtARvy5(}vlr9ByFx_qD`;(n2MjW%whrRU&dGn%Hh&YG6CE^8h=^qJ64q3oe6Km0T-WuJ|pf6$c1 zw57t(0qPvLuwh?Ubmm^3x&up;;ReW;K4lV5J{-n}es}S!OK1M);E!jPp&t$bz7}~u zHNUPQMfY{M=hhqdwYBiK?(1;RRa*ab@E3O_{5LeDWQ@;89Jk{?w~^zjAvGKMI5mp6 zw_uOKo?QzVc(-6n8nf#VhA}q^d_5+Yq|=<+)Q~F27%SI(apTOB>>p^;HI^o%lNp<5 z_4wwzQx+|rd=&Fenbf_Tb?4YTJF`a50e3Ff7|Q1_(;Uk50Lt-zEl1@Y%JCrbco4Yk z&+KRA8ux`6GpAsFL-;7_HHR_4G6te&CRpaONV#sWpn4|t=eKWvvKndV`48jcVYXek zd~yu&ZdLvyMO((9?g!`In^IoCo&CBQe=6qoSN02;M~+4>dHrG~%M-b(+j|T)+j?{@ zV9;R<_B`y-b%4>Pqm_VROWV2a&-#cz+fCdY>uhuO1=5y%VH9bwFO0$V_l40A@XRfLt^)P7iux*2uEN!sTwln+sYRoUD-<+LUJ^11@`$iS$ycK<;%IO;thwH;) zGeu6dk<|yhv zhjBZGF-MxR4(vOuQx*CS+mwChr|3H@C&#s{V|#5{E4X&+dAEF;YZ=!D&arz3w_%Mu zJ5z%4JlXx&jL>8S$|7qW$7e>L!@A|oJ-WlC`(5l(;Q1?op<#Lt(S0R2M7Q=28h`D+ z;<&9p@o0Vw=Ai`kxdNmybZO{dP^mJ&pTVvq0vMJk?Y+Bqe>GBt-w62l$dk|Pek4-2 zWyh8pwW}7PE$uDGx>TSF&ceqw?@~*aFWprXSXQvS;0vMB!0N!7U|HaSz?TZjgAXlP z7f@RUP90CQ9D|+cH+HAE`rCW9B-&3V)RwlEM2p&TY+yib+4am*Tj0kS3^!m`+ex*h zweR@xcI+Is^!6p%x9t6mf3z7Jkk)P!r6rN*?>csZn~Z$T!$1T{SZ!_U@q4n!0Fu;`TFjS* zlN0dbr!|E31fImDm*71Pw_A^sPCZBismC|rX1=;Fz^*`~FTobWFn))uE&kix#GSBK zxKY=*i-$SGGfazS6+WQ};Vz`-wx;0G7Mc*R1Pu{|2gaiMB0kn5jE}`})7yEUQlsz_ zBk2h&w(B2Ke{);>X$N)9(>}qB92g!_m|GkZ(B-<~CF(gePEZx<@N@)l{Ei8tcd}k- zvqY!Qv22Vw`o5FTGPgac?E;30u$mGZ8YQ_^c%u$v;n^hIuV|t4Y+x!frn@V zruj1HsLcartbQ3`>^1b~oJyGOM3}a!FzXayICXf0HsDGNS6R5)!d-o7xj+QQNbl-* z)Idn*%I!opux&?u-m-xMm`7kd*}zJaTJ~eyTNYujP!cYlECN5VerGZ@5c%a_mB6hc z?@!Vuk5L5v;u}@TR6oMRzd-yeGyQ|sUvOog$i0>1%Y9%O@+D7J1pb9~32e~sCi4tN zTPM!cBvWDd5hiaOjGi7>(Z84sV!srI-xszfQ!E$#nTC{=>F6{dtN3g1LabL%B~xxW zW{Wrfq6~ZMI+TO^{i;au3tyJ_+CN;kmJ~N^5>XWIR7Ox)m zPT;BNPc%+};M65kdn`^2_8tc(XmNtr_Z_e}`(Ph%a6%Sm-Fe6>hR>zeUrwe@QWj(L zDU|R|gm<1ztv{Jeea8u3BH?=weqcDY{%|staKe{H&rDQCP;Rty8TRtC#qUkAjl$SR z7J)WwqX^qbL7o#%-r&BSc3HT15<~B1S-5<1X}D$L`BlkO1^fs{6#7eeXk3MVHu-IZ zvI4(i1pcuD6Or+riB+I)xb93U`n5BuaCI^@iZlz<#qnVH56784(+Gs0pI{z3ef9K> zPc1(yyk`;08peJ{`cf&|5OK-#az8@;Sa97ozgv9S=W`D=uNqQe^pP>x+4kaL^h5f4 zdojBgr~HlMs|a+-7B8EhKaFOjaRg}`1x=b!hLUK*L^IM885Uvo?*M2Wg6!=G`nygy zYQ|O^ZKcNm#>-KZljG&^2;z(XY(@Kb)}`l>2>M?PeI&yEhk2x@(##`I{8__9$;g3; zB7FJGCr^A0_|e@H1r7I4i~Cya{gk*18ej7KL)~fjlEJk5+UYd@^N52-7@ISRs$vbom%oit$*B*#--1Iep$ zon7n0!&trL^V4$ebv`_d;afgGj_cX=K0L}l;itzX#?fUvjyQJqV=RR*jusp5>>H#v z$34&Eu&r3m^w>YyuiW{-?O%a%&=~nKF8dkd{`T$LU-Hip?;^oh@Fnma#8-{42;Zjx zrAF{Qq2+o1d5B$omv%otO!oqLo-5nS;(pSkvmh?hqP*{}0kGB){E$q+s!9EHB%VF4UiRzQpr>f(916_%(zTWEZwD7_$60pobIa9+j_PcGT6Dra+^?$)vcJ!WD*vHnkvwHqJ0uanj+4QjasBT_W=Wc-jhh%uRTLLZ^6f~bNCp(12&0EIT+z52wOw^qxd*q zz5$!zov=A?MlE~-Hs?=)PXp#W%K4J`7hyL8-ecicVRK%sLL7$w5nwUQ52{{zzU5lM z@SjN_Y=-}Le4K~dYgHNE14ttI^7Gf=X#UwFK z_(9-fvY>4CFm1p+79O_nWedM;;g2l*sfFh)T#8}J_|>$L-X04dwQ$11=PmrYh39BP z7R*6gf%T_~HsCtiSfCDC_^5?XT6oyPNejPa;SVi5YT;Q6&s(?*{haAn(nk6*3m>p> z6&5_!qZIv{GUjU9>p&maK};1#to<_mE3wYd-k{V7?Tt!ZxA2sOd4R(3Fl~faS-9T9 z2QA!e;gc3VXW^uUuUPm)3tzYJ2vo@`HYqhvy9yuXIhHeG?MiD`S-aZWQES&(yWZOD zLzIPUgY^RB@MPzn3?1t$no4~cG)0%v;T0B+SQtgo{!we!(FT6Kg*lfIj#+q*h4)$b zfQ1iQnCmq0k64&|KcW{jJ!~V!siMAP(ez2lAEw zVeiEBxL1-ialGQm6Lor#)8nRW7bYVk7bXg@msu!J6#1f&E3!<@(F>E*y}Pw>q25$b zU7iXqq9>(g8jcPE>E_CKGw2q1X)=L4NiUpdzsd5lKBU+E(1&;!`WAbktK-*6q^_aH zh5Ug!hI6Cen)R1MvuBs@1R=x@MmYFV6_8fqtg(7sKQH#W+$V z?z=hXiIMX8_bTUsM_x$s6THXaho!+YbEpUBO4b8TuO8oon{k;x&1IyQZ4Yt?VUh>& z{-YF>0E~pS!i~DdwI_avw^abxg6G$p_yzDZV_|UxkG7i?*L5bsEf7D}m-S~|g~o8I z^QdGq9o9&C0*meX-^(6Ek0D9StDW)S9t7$tj$z@`hI^9CaJEd^EZifo=cP>$i$3>Z zG#t<5xi?#Pk%jl`Q1e4Nr57^cd>uZ}cNM^85q&|mx%31|k#B`LYfi84s3hBo>nLl$ z^__GhY;PIJvWheBJL|*OZj0u9=3QdQow2SW+l;l9`tY(w6piD&)6v_N^@rgf$=>YdJVz|P3w)lp)M1T~IiKr?3v*qj zj-S>wg+3q45rzz1+bECLg@;}r;n3h2t84!lbY+cR-`?&YnK&BP;4J|j^U&)RWSZI5 zS&?za{(qq%>VFNo%ha3n=!Leb)B2a2px6H+=)4v&;a{J%u}3$!dNu) zI{P`+AHD7@oU+3B`JgBk*k;g+Gy~~8{=v@&g@pkD4h?Z>{CrR@Jn|uoBWphKDw%*a zlDwY}szU(VQSuW!KOb}v^{59P>%rBQc&xLZ4?2K=eE6Ua$p~rCNdB#GgRCAOM7(_X zpnnCteE6W9kR!yA8F?V`5G+PEKIkn}ZWv)=qf4vzVP4i!5*XIv0a%LDs$el%)CxX<;ffpN8b%ixsItdDXDZ>t94K- zP?=7YtpWu39&Ip?uUPmk3%`sy5$`S9z#E|ryfF*UT6hTbqwG)XTT+P`#+B)?PiEu! zNKfL4Z09&6ktY&eJ;DSo#sk)DughDuQfd0o0v=F!7s?B?-WYhSvdslI_EbJ`56EORjm0yUg+% z#(rV(J7_~4F_Yf1|Ks!|9k!K1x_X_o=d#)lKkOeoTm7-Me_hWt|Dk0BTqn4X5`(E! zn+0p5-PbI(HpZN^n2><}wJ{f7)W(r%k$B8g496Rde{DPfyfXMpeuC#;8|zUI=CRn? z$n%?g*2dqF3|S}`0bAk5IErge{17jnwed&5%V%xm8N(28xi)ft%=&W9;VOZAJu`}B zsL_Mc<#W8WQ_4-?Ue-ppjhGA9>t-gVjhnhzD>G#R3)jlb@FlvvIA)D8>AxW$@?-uS z%f^`STLOBmVm$6f=D<9;c1FCk44ugniXq)8gD37me8i8z7Q^s=jF07$aOEusvRGy= zf*rU~pKBH5djnY)$f$mXK=YCn_nX|kwF(On`-rR4UqlqFX)GV{($5c=Rcf&{YHNKB zZtv49F8?1h>`Try>J_XV7oqp{a=3W%l}NFtLx%HUPX>Px`e>BtpU+dKKL%aIdFUqT z`-HH0mvkO_PWnzNY~IP7hb|QFXwJdrolWkWsS7*@Tl5rPw)s+biRTH6=`Fc>Nz`S1 zg}Q{0$A9GLvT_f~^||21&C?~&Q|tsBNB!l^0?Jy<{cYY~FUETTl*RMgh2mhmvM1#|V(#VjzE-D)JMh@^|MW$32NNR|YyYKb%qce)OaJM+ zNT2sqS)XORXW4yrhWlxKPubpYUW0P|bnt)8T>R>qnJS$7u>QKfi{MrRcLi|G+XU%! z`DQ^CXkSg*qtEEO;kX~Y0(IwEh0w#zm-id0fZqd~@j7AG!)}93IRWnni+pMhZmsvq z{)N6Y2RqKZ&_{Z*_7S7Q8dv3$CD5ZRc=5f@7QTmI(SN^f`&ZLpjX#(!CT$xx%#;A{`|H0kkr6)l1JM1SqpxkBxesz4SI?CATHh99EL3E`z-xFf!~vS!-2H7XPR?J18X_PA;$v7ENEAV``x?~#JV8vCv-nl zyIbEOsz#fzuk+ml&S%V@iS;eR-=hI&r63PBcgM|{DC1JUl<9H)NC4*CJ%zd3D>rCi z;+)lcqcCxB<{Yu(BY}7qzii&3(0J%a=8cYxGezh-e*F6}C$iieFA+PQiu8EdK68Zo zsO}f=E&|#Hvd7hy&Xiqeq!T_po&lq7eA|L@^9+CBN&lh_a7Gy7EGS3!52o)&o?I`? zdjw}^mizP05^p);t@6by@yA11I8G_+_m_inDCg3}&es`_?ZvUkvU5zcy&gb&RVz;i zSkDczZ%xaMy?gxVCfa1|6~A$*;Q689q5pE_in%4M^?`%04HGllo|60~`B2JSDqvTG z;i`iDdEQ%I)J!IcU}TWA{d>zJ5RC1EKWT@#Q}d~ew!y+6r#2rtY0-nYH2%G1F1#pk z83*%;HpHVYjTkhSHvYZkJn$k2k^BVDzqd>}^|+JVwF10wK6}gmm-qIQs4VxE+#9gI zwEcU_w}9{_{KW`;1Qy%%zn8sbrrgv`&Fm#b?rHKXlx(%l^XJTP0~blBLaQ=;SMEyu z^m`Nj{LDs1GRY=~rOc0p^8xpQn>1v8NXM_?V^|qFBEt`xApOhmf8v9G8?c^JP!!@* zKES!94Ikk@@ZrDega3^Wb~k#m`^@roUDhq8z9paDDB|9{dD2dcU|ZX}dU&JV32%kE zW}c7R9dAEA(4N4?7|-~%8dXf_P@>M<%YJ0-5NJl-M!qXS`+L^z;hc-Ttk%7xjwWbB z9nEHpUFvYsczaFBfC0s zBj9^wKd=+)oU0?Z$F6&rTi;=r=uqtpgYR{8&(;vEa!@w0?JNl8<)V1RtiE?nmvt#cI*yt{p z^J9$*-m|a)IMB6QrT4>WUAyAOOL&6|d_VS6D;oH|6WsdEKcj2MeFED;>(qgN8ryW$ zYa9COyI|n&bUC3*NnJZr<}*4B{r@Im=_k@h?p4<=hVjYu`}4}{)S>Ep`$P=q7aBjW zQ-=)`*_g$6op+tIm=4IRji1-ag%`DPBpKpyE)yf=^Yc2Rz~dSu`3at%*WuZ074TS( zJMlW7BE5WgonJ{oZ2=|!R=}7Rs>X1&?dCnLbTm4FIl_Vg!%2o7HF`Jm5)Q zhac<9`ulku>cIa~_=}PB1Qy%%zZYJoSQ65`1{pC{=2Lr{EhgTI(9$8yFd9)@i$4)xyYQQASb(841rL4%eXnK}Pbd za~_eFiKv+94OD?&k~fq1CQK>fSCGenTn+R7m&i9M%9&w@U{ilizj+C{C1ufk3#KGo zuH`bN;1MZfb!9NF48?WpF@>LNn5aL`JViZdkbWO7xBMgoh9V!HBJM7bNLyAHKTnYh z&(Bj3FCU)b9PsktDN0a@e0YjikX}AK#lO!{-&WKeK^{**ynJ{H44S-nigQ?YBOosM z37%u;;wjz$59RLlr9BWO!?^zU!c#2wrN(l7=rKWV>W0T)c-k!FF*3u=yN4XB#`x1) zTwcPyLBll2b39@|{mZZzK8CfyX1KD8yvK5MG-bSB?>%szgRO9G17yTQ@~R4LTw#?D zJbnX((ENtw-RaMHiD&8dG5o%M%W^DwW?r`~Z+SqNgW4|-0I$I}%MO9pP~bH};5CZC zYm|W32w`3im~%axp^e}8L+~8hk8iw0@a{Iw0E0OH!FzV&!P?AoFNRlgKF8iw;_#fr zJsT685O8F_$a8X@zwlk>81m!$b7> zPEfsyy9no}=5fv^cND_WVegK@O7-$o(ND@Jcj8Sq;;_smtIT@CH(_+W!Y}E!^%l?| z`uun>oYe6SV(%V6T*CUSlhdm>hV4JmEb-{2z6ta3peJVjtQdTN%a>P8kzrOI0Jo4$oxH z<;&2YhN!o(vx#H$|tDHmr32>_rhrHn!Xi8pRzcatV z;P8z3kATB>&*fZ~@3r$Ri~Vemjic}`)EdZ;hh+zyNzWfh?yDbCgt?wG$TK|E57u=&U$0o)X`*KEp@TZ;+&pL5#eS@@zy!~dK zrq^zq8=5hSHBFzTXV4$=Idkre|FMDg(fS@}bN9?~7t=y}`RA1+=G++DF@kbsX_JgH zf+o_Bs3-9EL7QQ;lbhx}w-@OOJ*up9<=L%6SFIa?F|+UX?d7bWdyXEpbgsvqL&mY& zKRK2KHn{2e!hL(mb?em;KOflj`134#>oq5z;zl~$=*FYXiTJjEbHM$A+OP#bqI+Wh6jZ!=ThzD@gBIdS3t!2c)1-fbuLZZYiL z_F(Tueb}E<*K6h7beH&$eg#RT5x$ooPpY~gSqi1OD%I<(a>qlO@4m=p$-ubkxZvy2D zf^T2A|B(HNk$*pq^!a~qc!v8p^4D&AXLko+{!b&`+1=4#-P!K!qWo)+j@D&GxgSIM zo1A-?3pS5uF4_*&L)fgyz-WmLBD}HTZ|D&E#xh! zXA=R^V!Y+JlNQqyF2m1T=E95GI9OJ+As+J-W2WAP_rv&qL|AsoPw@P_7LDZJ3OAC7YftR-~yFN5~;p0z%Fr5TDWY@hp|QRV;7Xl1z^3?0(_2p@T>aoQ+M66EoCDSJS_ KfXBg}<9`ED4F!V$ literal 0 HcmV?d00001 diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 54d75ce..b2940a1 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -1,10 +1,19 @@ #include "subsystems/tank_drive.h" -TankDrive::TankDrive(motor_group *left_motors, motor_group *right_motors, gyro *gyro_sensor, TankDrive::tankdrive_config_t *config) +TankDrive::TankDrive(motor_group *left_motors, motor_group *right_motors, inertial *gyro_sensor, TankDrive::tankdrive_config_t *config) : config(config), left_motors(left_motors), right_motors(right_motors), drive_pid(config->drive_pid), turn_pid(config->turn_pid), gyro_sensor(gyro_sensor) { } +/** + * Stops rotation of all the motors using their "brake mode" + */ +void TankDrive::stop() +{ + left_motors->stop(); + right_motors->stop(); +} + /** * Drive the robot using differential style controls. left_motors controls the left motors, * right_motors controls the right motors. @@ -78,7 +87,7 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) // On the first run of the funciton, reset the gyro position and PID if (initialize_func) { - gyro_sensor->resetAngle(); + gyro_sensor->resetRotation(); turn_pid.reset(); turn_pid.set_limits(-fabs(percent_speed), fabs(percent_speed)); @@ -88,7 +97,7 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) } // Update PID loop and drive the robot based on it's output - turn_pid.update(gyro_sensor->angle(rotationUnits::deg)); + turn_pid.update(gyro_sensor->rotation(rotationUnits::deg)); drive_tank(turn_pid.get(), -turn_pid.get()); // If the robot is at it's target, return true diff --git a/src/utils/spline_path.cpp b/src/utils/spline_path.cpp new file mode 100644 index 0000000..705269f --- /dev/null +++ b/src/utils/spline_path.cpp @@ -0,0 +1,86 @@ +#include "utils/spline_path.h" + +SplinePath::SplinePath(TankDrive *drive_system, vex::inertial *imu, vex::motor *l_enc, vex::motor *r_enc, motion_profile_t *motion_profile) +: drive_system(drive_system), imu(imu), l_enc(l_enc), r_enc(r_enc), motion_profile(motion_profile) +{ +} + +/** + * Makes the robot follow a predetermined path defined by point_list array, + * with list_length number of waypoints. The first waypoint should be the + * starting position. + * + * Returns true when the path has finished + */ +bool SplinePath::run_path(Waypoint *point_list, int list_length) +{ + if (run_path_init) + { + // Set up Pathfinder's "EncoderConfig" struct that will be fed into the path generation + enc_conf.initial_position = 0; + enc_conf.ticks_per_revolution = motion_profile->ticks_per_rev; + enc_conf.wheel_circumference = motion_profile->wheel_diam * PI; + enc_conf.kp = motion_profile->drive_p; + enc_conf.ki = motion_profile->drive_i; + enc_conf.kd = motion_profile->drive_d; + enc_conf.kv = motion_profile->kv; + enc_conf.ka = motion_profile->ka; + + // Prepare the "trajectory candidate" with information about the curve (max velocities / accels, type of curve, etc) + pathfinder_prepare(point_list, list_length, FIT_HERMITE_CUBIC, PATHFINDER_SAMPLES_LOW, motion_profile->dt, + motion_profile->max_v, motion_profile->max_a, motion_profile->max_j, &candidate); + + // Allocate the memory for the center, left and right "trajectories", or paths. + center_traj = (Segment *)malloc(sizeof(Segment) * candidate.length); + left_traj = (Segment*) malloc(sizeof(Segment) * candidate.length); + right_traj = (Segment*) malloc(sizeof(Segment) * candidate.length); + + // Generate the main center trajectory + pathfinder_generate(&candidate, center_traj); + + // Generate the left wheel and right wheel paths from the center trajectory + pathfinder_modify_tank(center_traj, candidate.length, left_traj, right_traj, motion_profile->wheelbase_width); + + // Create the "follower" structs, which contains info about the current state of each path when it is running + // (e.g. current error for PID, whether it is finished) + left_follower = (EncoderFollower *)malloc(sizeof(EncoderFollower)); + right_follower = (EncoderFollower *)malloc(sizeof(EncoderFollower)); + + reset_heading = imu->rotation(); + + // Make sure this only runs once per run + run_path_init = false; + } + + double lout = pathfinder_follow_encoder(enc_conf, left_follower, left_traj, candidate.length, l_enc->position(rotationUnits::raw)); + double rout = pathfinder_follow_encoder(enc_conf, right_follower, right_traj, candidate.length, r_enc->position(rotationUnits::raw)); + + double in_heading = r2d(left_follower->heading); + if(in_heading > 180) + in_heading -= 360; + double heading_error = in_heading + (imu->rotation() - reset_heading); + + lout -= motion_profile->turn_p * heading_error; + rout += motion_profile->turn_p * heading_error; + + drive_system->drive_tank(lout, rout); + + if(left_follower->finished && right_follower->finished) + { + // Actively set all velocities of the wheels to 0 + drive_system->stop(); + + // Free the memory allocated in the last run + free(center_traj); + free(left_traj); + free(right_traj); + free(left_follower); + free(right_follower); + + // Re-run initialization for the next path + run_path_init = true; + return true; + } + + return false; +} \ No newline at end of file From d3cabe7ec2598e7923e0a467fa5b173049fd4eed Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 17 May 2020 14:36:43 -0400 Subject: [PATCH 004/243] Changed includes to relative paths, added core.h --- include/pathfinder.h | 20 ++++++++++---------- include/pathfinder/fit.h | 3 ++- include/pathfinder/followers/distance.h | 3 ++- include/pathfinder/followers/encoder.h | 2 ++ include/pathfinder/io.h | 3 ++- include/pathfinder/mathutil.h | 2 +- include/pathfinder/modifiers/swerve.h | 3 ++- include/pathfinder/modifiers/tank.h | 3 ++- include/pathfinder/spline.h | 4 +++- include/pathfinder/structs.h | 2 +- include/pathfinder/trajectory.h | 3 ++- include/subsystems/rgb_controller.h | 2 +- include/subsystems/tank_drive.h | 2 +- include/utils/auto_queue.h | 0 include/utils/spline_path.h | 4 ++-- src/subsystems/tank_drive.cpp | 2 +- src/utils/pid.cpp | 2 +- src/utils/spline_path.cpp | 4 ++-- 18 files changed, 37 insertions(+), 27 deletions(-) create mode 100644 include/utils/auto_queue.h diff --git a/include/pathfinder.h b/include/pathfinder.h index 3645908..e366d05 100644 --- a/include/pathfinder.h +++ b/include/pathfinder.h @@ -5,20 +5,20 @@ extern "C" { #endif -#include "pathfinder/mathutil.h" -#include "pathfinder/structs.h" +#include "../core/include/pathfinder/mathutil.h" +#include "../core/include/pathfinder/structs.h" -#include "pathfinder/fit.h" -#include "pathfinder/spline.h" -#include "pathfinder/trajectory.h" +#include "../core/include/pathfinder/fit.h" +#include "../core/include/pathfinder/spline.h" +#include "../core/include/pathfinder/trajectory.h" -#include "pathfinder/modifiers/tank.h" -#include "pathfinder/modifiers/swerve.h" +#include "../core/include/pathfinder/modifiers/tank.h" +#include "../core/include/pathfinder/modifiers/swerve.h" -#include "pathfinder/followers/encoder.h" -#include "pathfinder/followers/distance.h" +#include "../core/include/pathfinder/followers/encoder.h" +#include "../core/include/pathfinder/followers/distance.h" -#include "pathfinder/io.h" +#include "../core/include/pathfinder/io.h" #ifdef __cplusplus } diff --git a/include/pathfinder/fit.h b/include/pathfinder/fit.h index 9b19978..66a10f8 100644 --- a/include/pathfinder/fit.h +++ b/include/pathfinder/fit.h @@ -1,7 +1,8 @@ #ifndef PATHFINDER_FIT_H_DEF #define PATHFINDER_FIT_H_DEF -#include "pathfinder/lib.h" +#include "../core/include/pathfinder/lib.h" +#include "../core/include/pathfinder/structs.h" CAPI void pf_fit_hermite_pre(Waypoint a, Waypoint b, Spline *s); CAPI void pf_fit_hermite_cubic(Waypoint a, Waypoint b, Spline *s); diff --git a/include/pathfinder/followers/distance.h b/include/pathfinder/followers/distance.h index b3b1ab5..3779549 100644 --- a/include/pathfinder/followers/distance.h +++ b/include/pathfinder/followers/distance.h @@ -1,7 +1,8 @@ #ifndef PATHFINDER_FOL_DISTANCE_H_DEF #define PATHFINDER_FOL_DISTANCE_H_DEF -#include "pathfinder/lib.h" +#include "../core/include/pathfinder/lib.h" +#include "../core/include/pathfinder/structs.h" CAPI typedef struct { double kp, ki, kd, kv, ka; diff --git a/include/pathfinder/followers/encoder.h b/include/pathfinder/followers/encoder.h index 7268d2d..7b42d8b 100644 --- a/include/pathfinder/followers/encoder.h +++ b/include/pathfinder/followers/encoder.h @@ -1,6 +1,8 @@ #ifndef PATHFINDER_FOL_ENCODER_H_DEF #define PATHFINDER_FOL_ENCODER_H_DEF +#include "../core/include/pathfinder/structs.h" + typedef struct { int initial_position, ticks_per_revolution; double wheel_circumference; diff --git a/include/pathfinder/io.h b/include/pathfinder/io.h index bfd37ce..ef8d40f 100644 --- a/include/pathfinder/io.h +++ b/include/pathfinder/io.h @@ -4,7 +4,8 @@ #include #include #include -#include "pathfinder/lib.h" +#include "../core/include/pathfinder/lib.h" +#include "../core/include/pathfinder/structs.h" #define CSV_LEADING_STRING "dt,x,y,position,velocity,acceleration,jerk,heading\n" diff --git a/include/pathfinder/mathutil.h b/include/pathfinder/mathutil.h index 99cad7d..170c625 100644 --- a/include/pathfinder/mathutil.h +++ b/include/pathfinder/mathutil.h @@ -3,7 +3,7 @@ #ifndef PATHFINDER_MATH_UTIL_H_DEF #define PATHFINDER_MATH_UTIL_H_DEF -#include "pathfinder/lib.h" +#include "../core/include/pathfinder/lib.h" #define PI 3.14159265358979323846 #define TAU PI*2 diff --git a/include/pathfinder/modifiers/swerve.h b/include/pathfinder/modifiers/swerve.h index 0168e0d..58eaf28 100644 --- a/include/pathfinder/modifiers/swerve.h +++ b/include/pathfinder/modifiers/swerve.h @@ -1,7 +1,8 @@ #ifndef PATHFINDER_MOD_SWERVE_H_DEF #define PATHFINDER_MOD_SWERVE_H_DEF -#include "pathfinder/lib.h" +#include "../core/include/pathfinder/lib.h" +#include "../core/include/pathfinder/structs.h" CAPI typedef enum { SWERVE_DEFAULT diff --git a/include/pathfinder/modifiers/tank.h b/include/pathfinder/modifiers/tank.h index 1653b6c..1b8b8b5 100644 --- a/include/pathfinder/modifiers/tank.h +++ b/include/pathfinder/modifiers/tank.h @@ -1,7 +1,8 @@ #ifndef PATHFINDER_MOD_TANK_H_DEF #define PATHFINDER_MOD_TANK_H_DEF -#include "pathfinder/lib.h" +#include "../core/include/pathfinder/lib.h" +#include "../core/include/pathfinder/structs.h" CAPI void pathfinder_modify_tank(Segment *original, int length, Segment *left, Segment *right, double wheelbase_width); diff --git a/include/pathfinder/spline.h b/include/pathfinder/spline.h index 1bb980c..401cde7 100644 --- a/include/pathfinder/spline.h +++ b/include/pathfinder/spline.h @@ -1,7 +1,9 @@ #ifndef PATHFINDER_SPLINE_H_DEF #define PATHFINDER_SPLINE_H_DEF -#include "pathfinder/lib.h" +#include "../core/include/pathfinder/lib.h" +#include "../core/include/pathfinder/structs.h" + #define PATHFINDER_SAMPLES_FAST (int)1000 #define PATHFINDER_SAMPLES_LOW (int)PATHFINDER_SAMPLES_FAST*10 diff --git a/include/pathfinder/structs.h b/include/pathfinder/structs.h index 89ecb8e..63451c0 100644 --- a/include/pathfinder/structs.h +++ b/include/pathfinder/structs.h @@ -1,7 +1,7 @@ #ifndef PATHFINDER_STRUCT_H_DEF #define PATHFINDER_STRUCT_H_DEF -#include "pathfinder/lib.h" +#include "../core/include/pathfinder/lib.h" CAPI typedef struct { double x, y, angle; diff --git a/include/pathfinder/trajectory.h b/include/pathfinder/trajectory.h index fe95373..b585167 100644 --- a/include/pathfinder/trajectory.h +++ b/include/pathfinder/trajectory.h @@ -1,7 +1,8 @@ #ifndef PATHFINDER_TRAJECTORY_H_DEF #define PATHFINDER_TRAJECTORY_H_DEF -#include "pathfinder/lib.h" +#include "../core/include/pathfinder/lib.h" +#include "../core/include/pathfinder/structs.h" CAPI int pathfinder_prepare(Waypoint *path, int path_length, void (*fit)(Waypoint,Waypoint,Spline*), int sample_count, double dt, double max_velocity, double max_acceleration, double max_jerk, TrajectoryCandidate *cand); diff --git a/include/subsystems/rgb_controller.h b/include/subsystems/rgb_controller.h index de9144b..0f4ce73 100644 --- a/include/subsystems/rgb_controller.h +++ b/include/subsystems/rgb_controller.h @@ -19,7 +19,7 @@ class RGBController Off, Blue, Red, Green, OrangeWhite, Rainbow }; - RGBController(rgb_t starting_color, triport::port port1, triport::port port2, triport::port port3) + RGBController(rgb_t starting_color, vex::triport::port port1, vex::triport::port port2, vex::triport::port port3) : port1(port1), port2(port2), port3(port3) { set(starting_color); diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index d667386..7218ad1 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -4,7 +4,7 @@ #define PI 3.141592654 #include "vex.h" -#include "utils/pid.h" +#include "../core/include/utils/pid.h" using namespace vex; diff --git a/include/utils/auto_queue.h b/include/utils/auto_queue.h new file mode 100644 index 0000000..e69de29 diff --git a/include/utils/spline_path.h b/include/utils/spline_path.h index 73de506..62c2631 100644 --- a/include/utils/spline_path.h +++ b/include/utils/spline_path.h @@ -1,9 +1,9 @@ #ifndef _SPLINE_ #define _SPLINE_ -#include "pathfinder.h" +#include "../core/include/pathfinder.h" -#include "subsystems/tank_drive.h" +#include "../core/include/subsystems/tank_drive.h" class SplinePath diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index b2940a1..96f203f 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -1,4 +1,4 @@ -#include "subsystems/tank_drive.h" +#include "../core/include/subsystems/tank_drive.h" TankDrive::TankDrive(motor_group *left_motors, motor_group *right_motors, inertial *gyro_sensor, TankDrive::tankdrive_config_t *config) : config(config), left_motors(left_motors), right_motors(right_motors), drive_pid(config->drive_pid), turn_pid(config->turn_pid), gyro_sensor(gyro_sensor) diff --git a/src/utils/pid.cpp b/src/utils/pid.cpp index 84331b6..bcc17fd 100644 --- a/src/utils/pid.cpp +++ b/src/utils/pid.cpp @@ -1,4 +1,4 @@ -#include "utils/pid.h" +#include "../core/include/utils/pid.h" /** * Create the PID object diff --git a/src/utils/spline_path.cpp b/src/utils/spline_path.cpp index 705269f..7c9da0c 100644 --- a/src/utils/spline_path.cpp +++ b/src/utils/spline_path.cpp @@ -1,7 +1,7 @@ -#include "utils/spline_path.h" +#include "../core/include/utils/spline_path.h" SplinePath::SplinePath(TankDrive *drive_system, vex::inertial *imu, vex::motor *l_enc, vex::motor *r_enc, motion_profile_t *motion_profile) -: drive_system(drive_system), imu(imu), l_enc(l_enc), r_enc(r_enc), motion_profile(motion_profile) +: drive_system(drive_system), l_enc(l_enc), r_enc(r_enc), imu(imu), motion_profile(motion_profile) { } From d29f83f7dae71aac2c8cd86aba590daae1c4183e Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 17 May 2020 15:47:54 -0400 Subject: [PATCH 005/243] got rid of DUMB ERROR with WRONG PATHS --- src/subsystems/tank_drive.cpp | 2 +- src/utils/pid.cpp | 2 +- src/utils/spline_path.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 96f203f..1f5b412 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -1,4 +1,4 @@ -#include "../core/include/subsystems/tank_drive.h" +#include "../Core/include/subsystems/tank_drive.h" TankDrive::TankDrive(motor_group *left_motors, motor_group *right_motors, inertial *gyro_sensor, TankDrive::tankdrive_config_t *config) : config(config), left_motors(left_motors), right_motors(right_motors), drive_pid(config->drive_pid), turn_pid(config->turn_pid), gyro_sensor(gyro_sensor) diff --git a/src/utils/pid.cpp b/src/utils/pid.cpp index bcc17fd..daa0816 100644 --- a/src/utils/pid.cpp +++ b/src/utils/pid.cpp @@ -1,4 +1,4 @@ -#include "../core/include/utils/pid.h" +#include "../Core/include/utils/pid.h" /** * Create the PID object diff --git a/src/utils/spline_path.cpp b/src/utils/spline_path.cpp index 7c9da0c..991a479 100644 --- a/src/utils/spline_path.cpp +++ b/src/utils/spline_path.cpp @@ -1,4 +1,4 @@ -#include "../core/include/utils/spline_path.h" +#include "../Core/include/utils/spline_path.h" SplinePath::SplinePath(TankDrive *drive_system, vex::inertial *imu, vex::motor *l_enc, vex::motor *r_enc, motion_profile_t *motion_profile) : drive_system(drive_system), l_enc(l_enc), r_enc(r_enc), imu(imu), motion_profile(motion_profile) From 552ddc7a4e0d39c474621f427c8ea3c9b7e05ec6 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 17 May 2020 18:30:13 -0400 Subject: [PATCH 006/243] Created example code for tasking in auto --- include/utils/auto_queue.h | 0 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 include/utils/auto_queue.h diff --git a/include/utils/auto_queue.h b/include/utils/auto_queue.h deleted file mode 100644 index e69de29..0000000 From 9a1f054ee9ef856904637b71b265c60bfc0583ef Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 31 May 2020 20:01:47 -0400 Subject: [PATCH 007/243] Removed testing code, added generic_auto to core --- include/utils/generic_auto.h | 40 +++++++++++++++++++++++++++++++++ src/utils/generic_auto.cpp | 43 ++++++++++++++++++++++++++++++++++++ 2 files changed, 83 insertions(+) create mode 100644 include/utils/generic_auto.h create mode 100644 src/utils/generic_auto.cpp diff --git a/include/utils/generic_auto.h b/include/utils/generic_auto.h new file mode 100644 index 0000000..3674c68 --- /dev/null +++ b/include/utils/generic_auto.h @@ -0,0 +1,40 @@ +#ifndef _GENAUTO_ +#define _GENAUTO_ + +#include + +typedef bool (*state_ptr)(void); + +class GenericAuto +{ + public: + + /** + * Create the GenericAuto object + * + * Example: GenericAuto auto1 = {func_ptr1, func_ptr2, ...}; + */ + GenericAuto(std::initializer_list states); + + /** + * The method that runs the autonomous. If 'blocking' is true, then + * this method will run through every state until it finished. + * + * If blocking is false, then assuming every state is also non-blocking, + * the method will run through the current state in the list and return + * immediately. + * + * @param blocking + * Whether or not to block the thread until all states have run + * @returns + * true after all states have finished. + */ + bool run(bool blocking); + + private: + + std::vector state_list; + +}; + +#endif \ No newline at end of file diff --git a/src/utils/generic_auto.cpp b/src/utils/generic_auto.cpp new file mode 100644 index 0000000..f3d0976 --- /dev/null +++ b/src/utils/generic_auto.cpp @@ -0,0 +1,43 @@ +#include "../core/include/utils/generic_auto.h" + +/** +* Create the GenericAuto object +* +* Example: GenericAuto auto1 = {func_ptr1, func_ptr2, ...}; +*/ +GenericAuto::GenericAuto(std::initializer_list states) +{ + for (state_ptr s : states) + state_list.push_back(s); +} + +/** +* The method that runs the autonomous. If 'blocking' is true, then +* this method will run through every state until it finished. +* +* If blocking is false, then assuming every state is also non-blocking, +* the method will run through the current state in the list and return +* immediately. +* +* @param blocking +* Whether or not to block the thread until all states have run +* @returns +* true after all states have finished. +*/ +bool GenericAuto::run(bool blocking) +{ + if(state_list.empty()) + return true; + + do + { + + if((state_list.front())() == true) + state_list.erase(state_list.begin()); + + } while(blocking && !state_list.empty()); + + // If the method is blocking, return true because it's finished + // If non-blocking, return false because the list isn't empty yet + return blocking; +} From 054a3441a5a1461d4b4eaf138e5d2175968e3b50 Mon Sep 17 00:00:00 2001 From: superrm11 Date: Fri, 3 Jul 2020 13:04:14 -0700 Subject: [PATCH 008/243] +VS Code configuration; began removing pointers --- include/subsystems/tank_drive.h | 10 +++++----- src/subsystems/tank_drive.cpp | 24 ++++++++++++------------ 2 files changed, 17 insertions(+), 17 deletions(-) diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 7218ad1..7d300ad 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -23,7 +23,7 @@ class TankDrive /** * Create the TankDrive object */ - TankDrive(motor_group *left_motors, motor_group *right_motors, inertial *gyro_sensor, tankdrive_config_t *config); + TankDrive(motor_group &left_motors, motor_group &right_motors, inertial &gyro_sensor, tankdrive_config_t &config); /** * Stops rotation of all the motors using their "brake mode" @@ -63,15 +63,15 @@ class TankDrive bool turn_degrees(double degrees, double percent_speed); private: - tankdrive_config_t *config; + tankdrive_config_t &config; - motor_group *left_motors; - motor_group *right_motors; + motor_group &left_motors; + motor_group &right_motors; PID drive_pid; PID turn_pid; - inertial *gyro_sensor; + inertial &gyro_sensor; bool initialize_func = true; }; diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 1f5b412..d6f548a 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -1,7 +1,7 @@ #include "../Core/include/subsystems/tank_drive.h" -TankDrive::TankDrive(motor_group *left_motors, motor_group *right_motors, inertial *gyro_sensor, TankDrive::tankdrive_config_t *config) - : config(config), left_motors(left_motors), right_motors(right_motors), drive_pid(config->drive_pid), turn_pid(config->turn_pid), gyro_sensor(gyro_sensor) +TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, inertial &gyro_sensor, TankDrive::tankdrive_config_t &config) + : config(config), left_motors(left_motors), right_motors(right_motors), drive_pid(config.drive_pid), turn_pid(config.turn_pid), gyro_sensor(gyro_sensor) { } @@ -10,8 +10,8 @@ TankDrive::TankDrive(motor_group *left_motors, motor_group *right_motors, inerti */ void TankDrive::stop() { - left_motors->stop(); - right_motors->stop(); + left_motors.stop(); + right_motors.stop(); } /** @@ -22,8 +22,8 @@ void TankDrive::stop() */ void TankDrive::drive_tank(double left, double right) { - left_motors->setVelocity(left * 100, velocityUnits::pct); - right_motors->setVelocity(right * 100, velocityUnits::pct); + left_motors.setVelocity(left * 100, velocityUnits::pct); + right_motors.setVelocity(right * 100, velocityUnits::pct); } /** @@ -37,8 +37,8 @@ void TankDrive::drive_arcade(double forward_back, double left_right) double left = forward_back + left_right; double right = forward_back - left_right; - left_motors->setVelocity(left * 100, velocityUnits::pct); - right_motors->setVelocity(right * 100, velocityUnits::pct); + left_motors.setVelocity(left * 100, velocityUnits::pct); + right_motors.setVelocity(right * 100, velocityUnits::pct); } /** @@ -52,7 +52,7 @@ bool TankDrive::drive_forward(double inches, double percent_speed) // On the first run of the funciton, reset the motor position and PID if (initialize_func) { - left_motors->resetPosition(); + left_motors.resetPosition(); drive_pid.reset(); drive_pid.set_limits(-fabs(percent_speed), fabs(percent_speed)); @@ -62,7 +62,7 @@ bool TankDrive::drive_forward(double inches, double percent_speed) } // Update PID loop and drive the robot based on it's output - drive_pid.update(left_motors->position(rotationUnits::rev) * PI * config->wheel_diam); + drive_pid.update(left_motors.position(rotationUnits::rev) * PI * config.wheel_diam); drive_tank(drive_pid.get(), drive_pid.get()); // If the robot is at it's target, return true @@ -87,7 +87,7 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) // On the first run of the funciton, reset the gyro position and PID if (initialize_func) { - gyro_sensor->resetRotation(); + gyro_sensor.resetRotation(); turn_pid.reset(); turn_pid.set_limits(-fabs(percent_speed), fabs(percent_speed)); @@ -97,7 +97,7 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) } // Update PID loop and drive the robot based on it's output - turn_pid.update(gyro_sensor->rotation(rotationUnits::deg)); + turn_pid.update(gyro_sensor.rotation(rotationUnits::deg)); drive_tank(turn_pid.get(), -turn_pid.get()); // If the robot is at it's target, return true From da407aa51acab39770b6f369cdc3138b158d6fb2 Mon Sep 17 00:00:00 2001 From: superrm11 Date: Fri, 3 Jul 2020 14:45:15 -0700 Subject: [PATCH 009/243] Split RGBController, changed ptrs to refs --- include/subsystems/rgb_controller.h | 45 ++-------------------------- include/subsystems/tank_drive.h | 4 +-- include/utils/pid.h | 4 +-- include/utils/spline_path.h | 10 +++---- src/subsystems/rgb_controller.cpp | 46 +++++++++++++++++++++++++++++ src/utils/pid.cpp | 8 ++--- src/utils/spline_path.cpp | 38 ++++++++++++------------ 7 files changed, 80 insertions(+), 75 deletions(-) create mode 100644 src/subsystems/rgb_controller.cpp diff --git a/include/subsystems/rgb_controller.h b/include/subsystems/rgb_controller.h index 0f4ce73..33dfb80 100644 --- a/include/subsystems/rgb_controller.h +++ b/include/subsystems/rgb_controller.h @@ -19,50 +19,9 @@ class RGBController Off, Blue, Red, Green, OrangeWhite, Rainbow }; - RGBController(rgb_t starting_color, vex::triport::port port1, vex::triport::port port2, vex::triport::port port3) - : port1(port1), port2(port2), port3(port3) - { - set(starting_color); - } - - void set(rgb_t color) - { - switch(color) - { - case Blue: - port1.set(1); - port2.set(0); - port3.set(0); - break; - case Red: - port1.set(0); - port2.set(1); - port3.set(0); - break; - case Green: - port1.set(1); - port2.set(1); - port3.set(0); - break; - case OrangeWhite: - port1.set(0); - port2.set(0); - port3.set(1); - break; - case Rainbow: - port1.set(1); - port2.set(0); - port3.set(1); - break; + RGBController(rgb_t starting_color, vex::triport::port port1, vex::triport::port port2, vex::triport::port port3); - default: - case Off: - port1.set(0); - port2.set(0); - port3.set(0); - break; - } - } + void set(rgb_t color); }; diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 7d300ad..28de064 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -14,8 +14,8 @@ class TankDrive struct tankdrive_config_t { - PID::pid_config_t *drive_pid; - PID::pid_config_t *turn_pid; + PID::pid_config_t drive_pid; + PID::pid_config_t turn_pid; double wheel_diam; }; diff --git a/include/utils/pid.h b/include/utils/pid.h index 8ea3178..a2ef91d 100644 --- a/include/utils/pid.h +++ b/include/utils/pid.h @@ -18,7 +18,7 @@ class PID /** * Create the PID object */ - PID(pid_config_t *config); + PID(pid_config_t &config); /** * Update the PID loop by taking the time difference from last update, @@ -59,7 +59,7 @@ class PID bool is_on_target(); private: - pid_config_t *config; + pid_config_t &config; double last_error = 0, accum_error = 0; double last_time = 0, on_target_last_time = 0; diff --git a/include/utils/spline_path.h b/include/utils/spline_path.h index 62c2631..05f0988 100644 --- a/include/utils/spline_path.h +++ b/include/utils/spline_path.h @@ -33,7 +33,7 @@ class SplinePath double wheelbase_width = 11.5; }; - SplinePath(TankDrive *drive_system, vex::inertial *imu, vex::motor *l_enc, vex::motor *r_enc, motion_profile_t *motion_profile); + SplinePath(TankDrive &drive_system, vex::inertial &imu, vex::motor &l_enc, vex::motor &r_enc, motion_profile_t &motion_profile); bool run_path(Waypoint *point_list, int list_length); @@ -47,11 +47,11 @@ class SplinePath EncoderFollower *left_follower, *right_follower; EncoderConfig enc_conf; - TankDrive *drive_system; - vex::motor *l_enc, *r_enc; - vex::inertial *imu; + TankDrive &drive_system; + vex::motor &l_enc, &r_enc; + vex::inertial &imu; - motion_profile_t *motion_profile; + motion_profile_t &motion_profile; }; #endif \ No newline at end of file diff --git a/src/subsystems/rgb_controller.cpp b/src/subsystems/rgb_controller.cpp new file mode 100644 index 0000000..17af7b2 --- /dev/null +++ b/src/subsystems/rgb_controller.cpp @@ -0,0 +1,46 @@ +#include "../Core/include/subsystems/rgb_controller.h" + +RGBController::RGBController(rgb_t starting_color, vex::triport::port port1, vex::triport::port port2, vex::triport::port port3) + : port1(port1), port2(port2), port3(port3) + { + set(starting_color); + } + + void RGBController::set(rgb_t color) + { + switch(color) + { + case Blue: + port1.set(1); + port2.set(0); + port3.set(0); + break; + case Red: + port1.set(0); + port2.set(1); + port3.set(0); + break; + case Green: + port1.set(1); + port2.set(1); + port3.set(0); + break; + case OrangeWhite: + port1.set(0); + port2.set(0); + port3.set(1); + break; + case Rainbow: + port1.set(1); + port2.set(0); + port3.set(1); + break; + + default: + case Off: + port1.set(0); + port2.set(0); + port3.set(0); + break; + } + } \ No newline at end of file diff --git a/src/utils/pid.cpp b/src/utils/pid.cpp index daa0816..cfdffe4 100644 --- a/src/utils/pid.cpp +++ b/src/utils/pid.cpp @@ -3,7 +3,7 @@ /** * Create the PID object */ -PID::PID(pid_config_t *config) +PID::PID(pid_config_t &config) : config(config) { pid_timer.reset(); @@ -21,7 +21,7 @@ void PID::update(double sensor_val) accum_error += time_delta * get_error(); - out = (config->f) + (config->p * get_error()) + (config->i * accum_error) + (config->d * (get_error() - last_error) / time_delta); + out = (config.f) + (config.p * get_error()) + (config.i * accum_error) + (config.d * (get_error() - last_error) / time_delta); last_time = pid_timer.value(); last_error = get_error(); @@ -85,14 +85,14 @@ void PID::set_limits(double lower, double upper) */ bool PID::is_on_target() { - if (fabs(get_error()) < config->deadband) + if (fabs(get_error()) < config.deadband) { if (is_checking_on_target == false) { on_target_last_time = pid_timer.value(); is_checking_on_target = true; } - else if (pid_timer.value() - on_target_last_time > config->on_target_time) + else if (pid_timer.value() - on_target_last_time > config.on_target_time) { return true; } diff --git a/src/utils/spline_path.cpp b/src/utils/spline_path.cpp index 991a479..4485100 100644 --- a/src/utils/spline_path.cpp +++ b/src/utils/spline_path.cpp @@ -1,6 +1,6 @@ #include "../Core/include/utils/spline_path.h" -SplinePath::SplinePath(TankDrive *drive_system, vex::inertial *imu, vex::motor *l_enc, vex::motor *r_enc, motion_profile_t *motion_profile) +SplinePath::SplinePath(TankDrive &drive_system, vex::inertial &imu, vex::motor &l_enc, vex::motor &r_enc, motion_profile_t &motion_profile) : drive_system(drive_system), l_enc(l_enc), r_enc(r_enc), imu(imu), motion_profile(motion_profile) { } @@ -18,17 +18,17 @@ bool SplinePath::run_path(Waypoint *point_list, int list_length) { // Set up Pathfinder's "EncoderConfig" struct that will be fed into the path generation enc_conf.initial_position = 0; - enc_conf.ticks_per_revolution = motion_profile->ticks_per_rev; - enc_conf.wheel_circumference = motion_profile->wheel_diam * PI; - enc_conf.kp = motion_profile->drive_p; - enc_conf.ki = motion_profile->drive_i; - enc_conf.kd = motion_profile->drive_d; - enc_conf.kv = motion_profile->kv; - enc_conf.ka = motion_profile->ka; + enc_conf.ticks_per_revolution = motion_profile.ticks_per_rev; + enc_conf.wheel_circumference = motion_profile.wheel_diam * PI; + enc_conf.kp = motion_profile.drive_p; + enc_conf.ki = motion_profile.drive_i; + enc_conf.kd = motion_profile.drive_d; + enc_conf.kv = motion_profile.kv; + enc_conf.ka = motion_profile.ka; // Prepare the "trajectory candidate" with information about the curve (max velocities / accels, type of curve, etc) - pathfinder_prepare(point_list, list_length, FIT_HERMITE_CUBIC, PATHFINDER_SAMPLES_LOW, motion_profile->dt, - motion_profile->max_v, motion_profile->max_a, motion_profile->max_j, &candidate); + pathfinder_prepare(point_list, list_length, FIT_HERMITE_CUBIC, PATHFINDER_SAMPLES_LOW, motion_profile.dt, + motion_profile.max_v, motion_profile.max_a, motion_profile.max_j, &candidate); // Allocate the memory for the center, left and right "trajectories", or paths. center_traj = (Segment *)malloc(sizeof(Segment) * candidate.length); @@ -39,36 +39,36 @@ bool SplinePath::run_path(Waypoint *point_list, int list_length) pathfinder_generate(&candidate, center_traj); // Generate the left wheel and right wheel paths from the center trajectory - pathfinder_modify_tank(center_traj, candidate.length, left_traj, right_traj, motion_profile->wheelbase_width); + pathfinder_modify_tank(center_traj, candidate.length, left_traj, right_traj, motion_profile.wheelbase_width); // Create the "follower" structs, which contains info about the current state of each path when it is running // (e.g. current error for PID, whether it is finished) left_follower = (EncoderFollower *)malloc(sizeof(EncoderFollower)); right_follower = (EncoderFollower *)malloc(sizeof(EncoderFollower)); - reset_heading = imu->rotation(); + reset_heading = imu.rotation(); // Make sure this only runs once per run run_path_init = false; } - double lout = pathfinder_follow_encoder(enc_conf, left_follower, left_traj, candidate.length, l_enc->position(rotationUnits::raw)); - double rout = pathfinder_follow_encoder(enc_conf, right_follower, right_traj, candidate.length, r_enc->position(rotationUnits::raw)); + double lout = pathfinder_follow_encoder(enc_conf, left_follower, left_traj, candidate.length, l_enc.position(rotationUnits::raw)); + double rout = pathfinder_follow_encoder(enc_conf, right_follower, right_traj, candidate.length, r_enc.position(rotationUnits::raw)); double in_heading = r2d(left_follower->heading); if(in_heading > 180) in_heading -= 360; - double heading_error = in_heading + (imu->rotation() - reset_heading); + double heading_error = in_heading + (imu.rotation() - reset_heading); - lout -= motion_profile->turn_p * heading_error; - rout += motion_profile->turn_p * heading_error; + lout -= motion_profile.turn_p * heading_error; + rout += motion_profile.turn_p * heading_error; - drive_system->drive_tank(lout, rout); + drive_system.drive_tank(lout, rout); if(left_follower->finished && right_follower->finished) { // Actively set all velocities of the wheels to 0 - drive_system->stop(); + drive_system.stop(); // Free the memory allocated in the last run free(center_traj); From 643614a5a595c0fb2149b881408c06f5ff8319c6 Mon Sep 17 00:00:00 2001 From: superrm11 Date: Sat, 4 Jul 2020 16:48:00 -0400 Subject: [PATCH 010/243] Began swerve drive integration / documentation --- include/subsystems/swerve_drive.h | 38 ++++++++++++ include/subsystems/swerve_module.h | 77 ++++++++++++++++++++++++ include/utils/vector.h | 75 +++++++++++++++++++++++ src/subsystems/swerve_drive.cpp | 61 +++++++++++++++++++ src/subsystems/swerve_module.cpp | 90 ++++++++++++++++++++++++++++ src/utils/vector.cpp | 96 ++++++++++++++++++++++++++++++ 6 files changed, 437 insertions(+) create mode 100644 include/subsystems/swerve_drive.h create mode 100644 include/subsystems/swerve_module.h create mode 100644 include/utils/vector.h create mode 100644 src/subsystems/swerve_drive.cpp create mode 100644 src/subsystems/swerve_module.cpp create mode 100644 src/utils/vector.cpp diff --git a/include/subsystems/swerve_drive.h b/include/subsystems/swerve_drive.h new file mode 100644 index 0000000..7b2afa2 --- /dev/null +++ b/include/subsystems/swerve_drive.h @@ -0,0 +1,38 @@ +#ifndef _SWERVEDRIVE_ +#define _SWERVEDRIVE_ + +#include "../Core/include/subsystems/swerve_module.h" +#include "../Core/include/utils/vector.h" + +#define ROT_DEADBAND 0.2 +#define LAT_DEADBAND 0.2 + +class SwerveDrive +{ + +public: + +/** + * Construct the SwerveDrive object. + */ +SwerveDrive(SwerveModule &left_front, SwerveModule &left_rear, SwerveModule &right_front, SwerveModule &right_rear); + +/** + * Drive the robot using controller inputs. Deadbands are automatically taken into + * account before passing to the main control method. + */ +void drive(int32_t leftY, int32_t leftX, int32_t rightX); + +/** + * The main control method. Takes a vector and a rotation, and performs vector math to + * calculate the position/speed for each wheel. + */ +void drive(Vector lateral, double rotation); + +private: + +SwerveModule &left_front, &left_rear, &right_front, &right_rear; + +}; + +#endif \ No newline at end of file diff --git a/include/subsystems/swerve_module.h b/include/subsystems/swerve_module.h new file mode 100644 index 0000000..03ca41a --- /dev/null +++ b/include/subsystems/swerve_module.h @@ -0,0 +1,77 @@ +#ifndef _SWERVEMODULE_ +#define _SWERVEMODULE_ + +#include "vex.h" + +// Gear teeth (input to output): 16, 35 +#define DIR_GEAR_RATIO (16.0/35.0) // ~0.457 + +// Gear teeth (input to output): 21, 10, 12, 30 +#define DRIVE_GEAR_RATIO ((21.0/10.0)*(12.0/30.0)) // 0.84 + +#define MOTOR_MAX_RPM 3600 + +class SwerveModule +{ + public: + + /** + * Create a single swerve module, made up of a Drive motor and a Direction motor. + * + * the Drive motor is the central one, with the Direction motor being offset. + */ + SwerveModule(vex::motor &drive, vex::gearSetting drive_gearing, vex::motor &direction, vex::gearSetting dir_gearing); + + /** + * Sets both the speed and direction of the module, taking into account how the motors are geared + * together, and each gear ratio. + * + * @param direction_deg Degrees of rotation for the module's direction (clockwise positive, from top) + * @param speed_pct Speed of the wheel for the module, in percent (-1.0 -> 1.0, positive fwd) + */ + void set(double direction_deg, double speed_pct); + + private: + + /** + * Sets the direction of the module to X degrees (clockwise positive, from top perspective). + * + * If set_speed is not called (even when the robot is not moving), then the wheel WILL rotate + * despite not being set, due to how the motors are geared together. + * + * Calling set_speed(0) will compensate for this. + * + * @param deg position to set the motor, counter clockwise from the top. + */ + void set_direction(double deg); + + /** + * Sets the speed of the drive motor, taking into account the speed of the direction motor, + * in percent units (-1.0 -> 1.0) + */ + void set_speed(double percent); + + /** + * Grab the maximum RPM of a motor with a certain gearset + * + * values are: + * RED: 100 + * GREEN: 200 + * BLUE: 600 + */ + static double gearset_max_rpm(vex::gearSetting gearing); + + /** + * Improved modulus which correctly calculates negatives + */ + static int mod(int var1, int var2); + + vex::motor &drive; + vex::gearSetting drive_gearing; + + vex::motor &direction; + vex::gearSetting dir_gearing; + +}; + +#endif \ No newline at end of file diff --git a/include/utils/vector.h b/include/utils/vector.h new file mode 100644 index 0000000..8527b2a --- /dev/null +++ b/include/utils/vector.h @@ -0,0 +1,75 @@ +#ifndef _VECTOR_ +#define _VECTOR_ + +#include + +#define PI 3.141592654 + +class Vector +{ +public: + + struct point_t + { + double x, y; + }; + + /** + * Construct a vector object. + * + * @param dir Direction, in radians. 'foward' is 0, clockwise positive when viewed from the top. + * @param mag Magnitude. + */ + Vector(double dir, double mag); + + /** + * Construct a vector object from a cartesian point. + * + * @param p point_t.x , point_t.y + */ + Vector(point_t &p); + + /** + * Get the direction of the vector, in radians. + * '0' is forward, clockwise positive when viewed from the top. + * + * Use r2d() to convert. + */ + double get_dir() const; + + /** + * Get the magnitude of the vector + */ + double get_mag() const; + + /** + * Get the X component of the vector; positive to the right. + */ + double get_x() const; + + /** + * Get the Y component of the vector, positive forward. + */ + double get_y() const; + + + Vector operator+(const Vector &other); + Vector operator-(const Vector &other); + +private: + + double dir, mag; + +}; + +/** + * General function for converting degrees to radians + */ +double d2r(double deg); + +/** + * General function for converting radians to degrees + */ +double r2d(double r); + +#endif \ No newline at end of file diff --git a/src/subsystems/swerve_drive.cpp b/src/subsystems/swerve_drive.cpp new file mode 100644 index 0000000..d32b052 --- /dev/null +++ b/src/subsystems/swerve_drive.cpp @@ -0,0 +1,61 @@ +#include "../Core/include/subsystems/swerve_drive.h" + +/** + * Construct the SwerveDrive object. + */ +SwerveDrive::SwerveDrive(SwerveModule &left_front, SwerveModule &left_rear, SwerveModule &right_front, SwerveModule &right_rear) +:left_front(left_front), left_rear(left_rear), right_front(right_front), right_rear(right_rear) +{ + +} + +/** + * Drive the robot using controller inputs. Deadbands are automatically taken into + * account before passing to the main control method. + * + * @param leftY Left joystick, Y axis (-100 -> 100) + * @param leftX Left joystick, X axis (-100 -> 100) + * @param rightX Right joystick, X axis(-100 -> 100) + */ +void SwerveDrive::drive(int32_t leftY, int32_t leftX, int32_t rightX) +{ + Vector::point_t p = {.x=(leftX / 100.0), .y=(leftY / 100.0)}; + + Vector input_lat(p); + + // Lateral Deadband + if(fabs(input_lat.get_mag()) < LAT_DEADBAND) + Vector input_lat(0,0); + + // Rotational Deadband + if(fabs(rightX / 100.0) < LAT_DEADBAND) + rightX = 0; + + // Convert input to a vector, and pass into main control method + return this->drive(input_lat, rightX); +} + +/** + * The main control method. Takes a vector and a rotation, and performs vector math to + * calculate the position/speed for each wheel. + */ +void SwerveDrive::drive(Vector lateral, double rotation) +{ + // Each wheel has a different rotation vector + Vector rot_lf(d2r(45), rotation); + Vector rot_rf(d2r(45+90), rotation); + Vector rot_rr(d2r(45+180), rotation); + Vector rot_lr(d2r(45+270), rotation); + + // Perform vector addition between the rotation vector and lateral vectors + Vector lf_out = rot_lf + lateral; + Vector rf_out = rot_rf + lateral; + Vector rr_out = rot_rr + lateral; + Vector lr_out = rot_lr + lateral; + + // Set each swerve module to the respective direction / speed + left_front.set(r2d(lf_out.get_dir()), lf_out.get_mag()); + right_front.set(r2d(rf_out.get_dir()), rf_out.get_mag()); + right_rear.set(r2d(rr_out.get_dir()), rr_out.get_mag()); + left_rear.set(r2d(lr_out.get_dir()), lr_out.get_mag()); +} \ No newline at end of file diff --git a/src/subsystems/swerve_module.cpp b/src/subsystems/swerve_module.cpp new file mode 100644 index 0000000..d1f27e8 --- /dev/null +++ b/src/subsystems/swerve_module.cpp @@ -0,0 +1,90 @@ +#include "../Core/include/subsystems/swerve_module.h" + +/** + * Create a single swerve module, made up of a Drive motor and a Direction motor. + * + * the Drive motor is the central one, with the Direction motor being offset. + */ +SwerveModule::SwerveModule(vex::motor &drive, vex::gearSetting drive_gearing, vex::motor &direction, vex::gearSetting dir_gearing) + : drive(drive), drive_gearing(drive_gearing), direction(direction), dir_gearing(dir_gearing) +{ +} + +/** + * Sets both the speed and direction of the module, taking into account how the motors are geared + * together, and each gear ratio. + * + * @param direction_deg Degrees of rotation for the module's direction (clockwise positive, from top) + * @param speed_pct Speed of the wheel for the module, in percent (-1.0 -> 1.0, positive fwd) + */ +void SwerveModule::set(double direction_deg, double speed_pct) +{ + set_direction(direction_deg); + set_speed(speed_pct); +} + +/** + * Sets the direction of the module to X degrees (clockwise positive, from top perspective). + * + * If set_speed is not called (even when the robot is not moving), then the wheel WILL rotate + * despite not being set, due to how the motors are geared together. + * + * Calling set_speed(0) will compensate for this. + * + * @param deg position to set the motor, counter clockwise from the top. + */ +void SwerveModule::set_direction(double deg) +{ + + int modpos = mod(deg, 360); + + // If the position is more than 180 degrees away, then turn the other way + if(fabs(modpos - direction.rotation(vex::rotationUnits::deg)) > 180) + modpos = mod(modpos + 180, 360); + + direction.spinToPosition(modpos / DIR_GEAR_RATIO, vex::rotationUnits::deg, false); +} + +/** + * Sets the speed of the drive motor, taking into account the speed of the direction motor, + * in percent units (-1.0 -> 1.0) + */ +void SwerveModule::set_speed(double percent) +{ + // The speed of the Drive motor is influenced by how fast the direciton motor is spinning, + // due to the way they are geared together. Therefore, subtract that RPM from what will be set. + double rpm = (percent * gearset_max_rpm(drive_gearing)) - (direction.rotation(vex::rotationUnits::rev) * DIR_GEAR_RATIO); + + drive.spin(vex::directionType::fwd, rpm / gearset_max_rpm(drive_gearing), vex::percentUnits::pct); +} + +/** + * Grab the maximum RPM of a motor with a certain gearset + * + * values are: + * RED: 100 + * GREEN: 200 + * BLUE: 600 + */ +double SwerveModule::gearset_max_rpm(vex::gearSetting gearing) +{ + switch (gearing) + { + case vex::gearSetting::ratio36_1: + return (1.0 / 36.0) * MOTOR_MAX_RPM; + case vex::gearSetting::ratio18_1: + return (1.0 / 18.0) * MOTOR_MAX_RPM; + case vex::gearSetting::ratio6_1: + return (1.0 / 6.0) * MOTOR_MAX_RPM; + default: + return 0.0; + } +} + +/** + * Improved modulus which correctly calculates negatives + */ +int SwerveModule::mod(int a, int b) +{ + return (b + (a % b)) % b; +} \ No newline at end of file diff --git a/src/utils/vector.cpp b/src/utils/vector.cpp new file mode 100644 index 0000000..5152024 --- /dev/null +++ b/src/utils/vector.cpp @@ -0,0 +1,96 @@ +#include "../Core/include/utils/vector.h" + +/** + * Construct a vector object. + * + * @param dir Direction, in radians. 'foward' is 0, clockwise positive when viewed from the top. + * @param mag Magnitude. + */ +Vector::Vector(double dir, double mag) +: dir(dir), mag(mag) +{ + +} + +/** + * Construct a vector object from a cartesian point. + * + * @param p point_t.x , point_t.y + */ +Vector::Vector(point_t &p) +{ + this->dir = atan2(p.x, p.y); + this->mag = sqrt( (p.x*p.x) + (p.y*p.y) ); +} + +/** + * Get the direction of the vector, in radians. + * '0' is forward, clockwise positive when viewed from the top. + * + * Use r2d() to convert. + */ +double Vector::get_dir() const { return dir;} + +/** + * Get the magnitude of the vector + */ +double Vector::get_mag() const { return mag; } + +/** + * Get the X component of the vector; positive to the right. + */ +double Vector::get_x() const +{ +return mag * sin(dir); +} + +/** + * Get the Y component of the vector, positive forward. + */ +double Vector::get_y() const +{ +return mag * cos(dir); +} + +/** + * Correctly add vectors together with the + operator + */ +Vector Vector::operator+(const Vector &other) +{ + point_t p = + { + .x = this->get_x() + other.get_x(), + .y = this->get_y() + other.get_y() + }; + + return Vector( p ); +} + +/** + * Correctly subtract vectors with the - operator + */ +Vector Vector::operator-(const Vector &other) +{ + point_t p = + { + .x = this->get_x() - other.get_x(), + .y = this->get_y() - other.get_y() + }; + return Vector( p ); +} + +/** + * General function for converting degrees to radians + */ +double d2r(double deg) +{ + return deg * (PI / 180.0); +} + +/** + * General function for converting radians to degrees + */ +double r2d(double rad) +{ + return rad * (180.0 / PI); +} \ No newline at end of file From b61b99f186269a609906bae169f93c4e6b9070d2 Mon Sep 17 00:00:00 2001 From: superrm11 Date: Sun, 13 Sep 2020 14:16:08 -0400 Subject: [PATCH 011/243] Swerve driver control is now functional. --- include/subsystems/swerve_module.h | 4 +++ include/utils/vector.h | 6 ++-- src/subsystems/swerve_drive.cpp | 22 +++++++------- src/subsystems/swerve_module.cpp | 46 ++++++++++++++++++++++-------- src/utils/vector.cpp | 6 ++-- 5 files changed, 55 insertions(+), 29 deletions(-) diff --git a/include/subsystems/swerve_module.h b/include/subsystems/swerve_module.h index 03ca41a..723985f 100644 --- a/include/subsystems/swerve_module.h +++ b/include/subsystems/swerve_module.h @@ -72,6 +72,10 @@ class SwerveModule vex::motor &direction; vex::gearSetting dir_gearing; + double lastStoredHeading; + bool inverseDrive; + double driveMulitplier; + }; #endif \ No newline at end of file diff --git a/include/utils/vector.h b/include/utils/vector.h index 8527b2a..b45227e 100644 --- a/include/utils/vector.h +++ b/include/utils/vector.h @@ -21,7 +21,7 @@ class Vector * @param mag Magnitude. */ Vector(double dir, double mag); - + /** * Construct a vector object from a cartesian point. * @@ -65,11 +65,11 @@ class Vector /** * General function for converting degrees to radians */ -double d2r(double deg); +double deg2rad(double deg); /** * General function for converting radians to degrees */ -double r2d(double r); +double rad2deg(double r); #endif \ No newline at end of file diff --git a/src/subsystems/swerve_drive.cpp b/src/subsystems/swerve_drive.cpp index d32b052..a016850 100644 --- a/src/subsystems/swerve_drive.cpp +++ b/src/subsystems/swerve_drive.cpp @@ -1,4 +1,4 @@ -#include "../Core/include/subsystems/swerve_drive.h" +#include "../core/include/subsystems/swerve_drive.h" /** * Construct the SwerveDrive object. @@ -14,7 +14,7 @@ SwerveDrive::SwerveDrive(SwerveModule &left_front, SwerveModule &left_rear, Swer * account before passing to the main control method. * * @param leftY Left joystick, Y axis (-100 -> 100) - * @param leftX Left joystick, X axis (-100 -> 100) + * @param leftX Left joystick, X axis (-100 -> 100) * @param rightX Right joystick, X axis(-100 -> 100) */ void SwerveDrive::drive(int32_t leftY, int32_t leftX, int32_t rightX) @@ -32,7 +32,7 @@ void SwerveDrive::drive(int32_t leftY, int32_t leftX, int32_t rightX) rightX = 0; // Convert input to a vector, and pass into main control method - return this->drive(input_lat, rightX); + return this->drive(input_lat, rightX / 100.0); } /** @@ -42,10 +42,10 @@ void SwerveDrive::drive(int32_t leftY, int32_t leftX, int32_t rightX) void SwerveDrive::drive(Vector lateral, double rotation) { // Each wheel has a different rotation vector - Vector rot_lf(d2r(45), rotation); - Vector rot_rf(d2r(45+90), rotation); - Vector rot_rr(d2r(45+180), rotation); - Vector rot_lr(d2r(45+270), rotation); + Vector rot_lf(deg2rad(45), rotation); + Vector rot_rf(deg2rad(45+90), rotation); + Vector rot_rr(deg2rad(45+180), rotation); + Vector rot_lr(deg2rad(45+270), rotation); // Perform vector addition between the rotation vector and lateral vectors Vector lf_out = rot_lf + lateral; @@ -54,8 +54,8 @@ void SwerveDrive::drive(Vector lateral, double rotation) Vector lr_out = rot_lr + lateral; // Set each swerve module to the respective direction / speed - left_front.set(r2d(lf_out.get_dir()), lf_out.get_mag()); - right_front.set(r2d(rf_out.get_dir()), rf_out.get_mag()); - right_rear.set(r2d(rr_out.get_dir()), rr_out.get_mag()); - left_rear.set(r2d(lr_out.get_dir()), lr_out.get_mag()); + left_front.set(rad2deg(lf_out.get_dir()), lf_out.get_mag()); + right_front.set(rad2deg(rf_out.get_dir()), rf_out.get_mag()); + right_rear.set(rad2deg(rr_out.get_dir()), rr_out.get_mag()); + left_rear.set(rad2deg(lr_out.get_dir()), lr_out.get_mag()); } \ No newline at end of file diff --git a/src/subsystems/swerve_module.cpp b/src/subsystems/swerve_module.cpp index d1f27e8..fe76a21 100644 --- a/src/subsystems/swerve_module.cpp +++ b/src/subsystems/swerve_module.cpp @@ -1,4 +1,5 @@ -#include "../Core/include/subsystems/swerve_module.h" +#include "../core/include/subsystems/swerve_module.h" +#include "hardware.h" /** * Create a single swerve module, made up of a Drive motor and a Direction motor. @@ -8,6 +9,9 @@ SwerveModule::SwerveModule(vex::motor &drive, vex::gearSetting drive_gearing, vex::motor &direction, vex::gearSetting dir_gearing) : drive(drive), drive_gearing(drive_gearing), direction(direction), dir_gearing(dir_gearing) { + lastStoredHeading = 0.0; + inverseDrive = false; + driveMulitplier = 0.0; } /** @@ -19,8 +23,14 @@ SwerveModule::SwerveModule(vex::motor &drive, vex::gearSetting drive_gearing, ve */ void SwerveModule::set(double direction_deg, double speed_pct) { - set_direction(direction_deg); - set_speed(speed_pct); + // Don't move the direction wheel unless we need to + if(speed_pct == 0.0) + direction_deg = lastStoredHeading; + else + lastStoredHeading = direction_deg; + + set_direction(direction_deg); + set_speed(speed_pct); } /** @@ -35,14 +45,25 @@ void SwerveModule::set(double direction_deg, double speed_pct) */ void SwerveModule::set_direction(double deg) { + double pos = direction.position(vex::rotationUnits::deg) * DIR_GEAR_RATIO; + + // Find the degrees of the direction module between -180 and +180, with 0 being forward. + int modpos = mod(pos, 360); + modpos -= (modpos > 180) ? 360 : 0; + + // Delta between where we are (modpos) and where we need to be (deg) + // Normalize the delta to make sure the maximum movement of the direction motor is 90 degrees. + // If the delta is above 90, then the wheel will go to the nearest 180 from the target, and move the drive wheel backwards. + int delta = deg - modpos; + int normalizedDelta = delta + (abs(delta) > 90 ? (delta > 0 ? -180 : 180) : 0); - int modpos = mod(deg, 360); + inverseDrive = abs(delta) > 90 ? true : false; - // If the position is more than 180 degrees away, then turn the other way - if(fabs(modpos - direction.rotation(vex::rotationUnits::deg)) > 180) - modpos = mod(modpos + 180, 360); + // Slow down the drive if we aren't close to the set direction yet (use the cube of the error) + driveMulitplier = pow(1 - (abs(normalizedDelta) / 90.0), 3); + + direction.spinTo((normalizedDelta + pos) / DIR_GEAR_RATIO, vex::rotationUnits::deg, 100, vex::velocityUnits::pct, false); - direction.spinToPosition(modpos / DIR_GEAR_RATIO, vex::rotationUnits::deg, false); } /** @@ -51,11 +72,12 @@ void SwerveModule::set_direction(double deg) */ void SwerveModule::set_speed(double percent) { - // The speed of the Drive motor is influenced by how fast the direciton motor is spinning, - // due to the way they are geared together. Therefore, subtract that RPM from what will be set. - double rpm = (percent * gearset_max_rpm(drive_gearing)) - (direction.rotation(vex::rotationUnits::rev) * DIR_GEAR_RATIO); + //TODO take into account how the RPM of the direction motor affects the RPM of the drive wheel + + drive.spin(vex::directionType::fwd, percent * 100.0 * (inverseDrive ? -1 : 1) * driveMulitplier, vex::percentUnits::pct); + //double rpm = (percent * gearset_max_rpm(drive_gearing)) - (direction.rotation(vex::rotationUnits::rev) * DIR_GEAR_RATIO); - drive.spin(vex::directionType::fwd, rpm / gearset_max_rpm(drive_gearing), vex::percentUnits::pct); + //drive.spin(vex::directionType::fwd, rpm / gearset_max_rpm(drive_gearing), vex::percentUnits::pct); } /** diff --git a/src/utils/vector.cpp b/src/utils/vector.cpp index 5152024..2600606 100644 --- a/src/utils/vector.cpp +++ b/src/utils/vector.cpp @@ -1,4 +1,4 @@ -#include "../Core/include/utils/vector.h" +#include "../core/include/utils/vector.h" /** * Construct a vector object. @@ -82,7 +82,7 @@ Vector Vector::operator-(const Vector &other) /** * General function for converting degrees to radians */ -double d2r(double deg) +double deg2rad(double deg) { return deg * (PI / 180.0); } @@ -90,7 +90,7 @@ double d2r(double deg) /** * General function for converting radians to degrees */ -double r2d(double rad) +double rad2deg(double rad) { return rad * (180.0 / PI); } \ No newline at end of file From 6861165985388e6a2f6319d97ef6af6defbd5b9e Mon Sep 17 00:00:00 2001 From: superrm11 Date: Tue, 15 Sep 2020 19:07:44 -0400 Subject: [PATCH 012/243] Initial testing for autonomous swerve code --- include/subsystems/swerve_drive.h | 14 +++++ include/subsystems/swerve_module.h | 17 ++++-- src/subsystems/swerve_drive.cpp | 85 +++++++++++++++++++++++++++++- src/subsystems/swerve_module.cpp | 45 +++++++++------- 4 files changed, 137 insertions(+), 24 deletions(-) diff --git a/include/subsystems/swerve_drive.h b/include/subsystems/swerve_drive.h index 7b2afa2..54aa97e 100644 --- a/include/subsystems/swerve_drive.h +++ b/include/subsystems/swerve_drive.h @@ -3,6 +3,7 @@ #include "../Core/include/subsystems/swerve_module.h" #include "../Core/include/utils/vector.h" +#include "../Core/include/utils/pid.h" #define ROT_DEADBAND 0.2 #define LAT_DEADBAND 0.2 @@ -29,9 +30,22 @@ void drive(int32_t leftY, int32_t leftX, int32_t rightX); */ void drive(Vector lateral, double rotation); +/** + * Autonomously drive the robot in (degrees) direction, at (-1.0 -> 1.0) speed, for (inches) distance. + * Indicate a negative speed or distance, or (preferably) a direction of +-180 degrees for backwards. + */ +bool auto_drive(double direction, double speed, double distance); + +void set_drive_pid(PID::pid_config_t &config); +void set_turn_pid(PID::pid_config_t &config); + private: SwerveModule &left_front, &left_rear, &right_front, &right_rear; +bool auto_drive_init = true; +double auto_drive_enc_reset = 0.0; + +PID *drive_pid, *turn_pid; }; diff --git a/include/subsystems/swerve_module.h b/include/subsystems/swerve_module.h index 723985f..4502e6b 100644 --- a/include/subsystems/swerve_module.h +++ b/include/subsystems/swerve_module.h @@ -11,6 +11,8 @@ #define MOTOR_MAX_RPM 3600 +#define WHEEL_DIAM 4 //inches + class SwerveModule { public: @@ -29,9 +31,7 @@ class SwerveModule * @param direction_deg Degrees of rotation for the module's direction (clockwise positive, from top) * @param speed_pct Speed of the wheel for the module, in percent (-1.0 -> 1.0, positive fwd) */ - void set(double direction_deg, double speed_pct); - - private: + void set(double direction_deg, double speed_pct, int power=2); /** * Sets the direction of the module to X degrees (clockwise positive, from top perspective). @@ -43,7 +43,7 @@ class SwerveModule * * @param deg position to set the motor, counter clockwise from the top. */ - void set_direction(double deg); + bool set_direction(double deg); /** * Sets the speed of the drive motor, taking into account the speed of the direction motor, @@ -51,6 +51,13 @@ class SwerveModule */ void set_speed(double percent); + /** + * Get 'distance' from the drive motor + */ + double get_distance_driven(); + + private: + /** * Grab the maximum RPM of a motor with a certain gearset * @@ -59,7 +66,7 @@ class SwerveModule * GREEN: 200 * BLUE: 600 */ - static double gearset_max_rpm(vex::gearSetting gearing); + static double gearset_dps(vex::gearSetting gearing); /** * Improved modulus which correctly calculates negatives diff --git a/src/subsystems/swerve_drive.cpp b/src/subsystems/swerve_drive.cpp index a016850..1c6f99b 100644 --- a/src/subsystems/swerve_drive.cpp +++ b/src/subsystems/swerve_drive.cpp @@ -32,7 +32,7 @@ void SwerveDrive::drive(int32_t leftY, int32_t leftX, int32_t rightX) rightX = 0; // Convert input to a vector, and pass into main control method - return this->drive(input_lat, rightX / 100.0); + this->drive(input_lat, rightX / 100.0); } /** @@ -58,4 +58,87 @@ void SwerveDrive::drive(Vector lateral, double rotation) right_front.set(rad2deg(rf_out.get_dir()), rf_out.get_mag()); right_rear.set(rad2deg(rr_out.get_dir()), rr_out.get_mag()); left_rear.set(rad2deg(lr_out.get_dir()), lr_out.get_mag()); +} + +/** + * Set the PID configuration for the "auto_drive" function + */ +void SwerveDrive::set_drive_pid(PID::pid_config_t &config) +{ + if(drive_pid != NULL) + delete drive_pid; + + this->drive_pid = new PID(config); +} + +/** + * Set the PID configuration for the "auto_turn" function + */ +void SwerveDrive::set_turn_pid(PID::pid_config_t &config) +{ + if(turn_pid != NULL) + delete turn_pid; + + this->turn_pid = new PID(config); +} + +/** + * Autonomously drive the robot in (degrees) direction, at (-1.0 -> 1.0) speed, for (inches) distance. + * Indicate a negative speed or distance, or (preferably) a direction of +-180 degrees for backwards. + */ +bool SwerveDrive::auto_drive(double direction, double speed, double distance) +{ + // Null check the PID config + if(drive_pid == NULL) + { + fprintf(stderr, "Failed to run auto_drive: Missing PID config\n"); + return true; // true to indicate 'finished' + } + + // INITIALIZATION + if(auto_drive_init) + { + // Turn all the wheels in the correct direction before running + bool all_wheels_done = true; + all_wheels_done = all_wheels_done & left_front.set_direction(direction); + all_wheels_done = all_wheels_done & right_front.set_direction(direction); + all_wheels_done = all_wheels_done & left_rear.set_direction(direction); + all_wheels_done = all_wheels_done & right_rear.set_direction(direction); + + // Setting the speed of all wheels to zero will still slowly run the motor, to make sure the wheel is stopped. + // (running the direction motor affects the speed of the wheel due to how it's geared together) + left_front.set_speed(0); + right_front.set_speed(0); + left_rear.set_speed(0); + right_rear.set_speed(0); + + // Make sure all the wheels are done turning before continuing with the 'init' phase + if(!all_wheels_done) + return false; + + // We're using the left front encoder for distance travelled. + auto_drive_enc_reset = left_front.get_distance_driven(); + + // set up the PID + drive_pid->reset(); + drive_pid->set_target(distance); + drive_pid->set_limits(-fabs(speed), fabs(speed)); + + auto_drive_init = false; + } + + // PERIODIC + + drive_pid->update( left_front.get_distance_driven() - auto_drive_enc_reset ); + this->drive(Vector(deg2rad(direction), drive_pid->get()), 0); + + // Check if the driving is complete + if(drive_pid->is_on_target()) + { + this->drive(Vector(0,0), 0); // stop the robot + auto_drive_init = true; + return true; + } + + return false; } \ No newline at end of file diff --git a/src/subsystems/swerve_module.cpp b/src/subsystems/swerve_module.cpp index fe76a21..18bceb2 100644 --- a/src/subsystems/swerve_module.cpp +++ b/src/subsystems/swerve_module.cpp @@ -20,8 +20,9 @@ SwerveModule::SwerveModule(vex::motor &drive, vex::gearSetting drive_gearing, ve * * @param direction_deg Degrees of rotation for the module's direction (clockwise positive, from top) * @param speed_pct Speed of the wheel for the module, in percent (-1.0 -> 1.0, positive fwd) + * @param power=2 Square / Cube the input for a exponential curve for more lower speed control */ -void SwerveModule::set(double direction_deg, double speed_pct) +void SwerveModule::set(double direction_deg, double speed_pct, int power) { // Don't move the direction wheel unless we need to if(speed_pct == 0.0) @@ -30,7 +31,10 @@ void SwerveModule::set(double direction_deg, double speed_pct) lastStoredHeading = direction_deg; set_direction(direction_deg); - set_speed(speed_pct); + if(power % 2 == 0) + set_speed((speed_pct > 0 ? 1.0 : -1.0) * pow(speed_pct, power)); + else + set_speed(pow(speed_pct, power)); } /** @@ -43,7 +47,7 @@ void SwerveModule::set(double direction_deg, double speed_pct) * * @param deg position to set the motor, counter clockwise from the top. */ -void SwerveModule::set_direction(double deg) +bool SwerveModule::set_direction(double deg) { double pos = direction.position(vex::rotationUnits::deg) * DIR_GEAR_RATIO; @@ -62,7 +66,7 @@ void SwerveModule::set_direction(double deg) // Slow down the drive if we aren't close to the set direction yet (use the cube of the error) driveMulitplier = pow(1 - (abs(normalizedDelta) / 90.0), 3); - direction.spinTo((normalizedDelta + pos) / DIR_GEAR_RATIO, vex::rotationUnits::deg, 100, vex::velocityUnits::pct, false); + return direction.spinTo((normalizedDelta + pos) / DIR_GEAR_RATIO, vex::rotationUnits::deg, 100, vex::velocityUnits::pct, false); } @@ -72,32 +76,37 @@ void SwerveModule::set_direction(double deg) */ void SwerveModule::set_speed(double percent) { - //TODO take into account how the RPM of the direction motor affects the RPM of the drive wheel + // take into account how the RPM of the direction motor affects the RPM of the drive wheel + //double speed_diff_dps = 0;//direction.velocity(vex::velocityUnits::dps) * DIR_GEAR_RATIO * -.2; + // Difference is negligable. Not worth the effort of getting it right. - drive.spin(vex::directionType::fwd, percent * 100.0 * (inverseDrive ? -1 : 1) * driveMulitplier, vex::percentUnits::pct); - //double rpm = (percent * gearset_max_rpm(drive_gearing)) - (direction.rotation(vex::rotationUnits::rev) * DIR_GEAR_RATIO); + drive.spin(vex::directionType::fwd, percent * 100.0 * (inverseDrive ? -1 : 1), vex::velocityUnits::pct); +} - //drive.spin(vex::directionType::fwd, rpm / gearset_max_rpm(drive_gearing), vex::percentUnits::pct); +/** + * Get 'distance' from the drive motor + */ +double SwerveModule::get_distance_driven() +{ + return WHEEL_DIAM * PI * drive.position(vex::rotationUnits::rev) * DRIVE_GEAR_RATIO; } /** - * Grab the maximum RPM of a motor with a certain gearset - * - * values are: - * RED: 100 - * GREEN: 200 - * BLUE: 600 + * Grab the maximum degrees per second of a motor with a certain gearset + * 36 : 1 = reds + * 18 : 1 = greens + * 6 : 1 = blues */ -double SwerveModule::gearset_max_rpm(vex::gearSetting gearing) +double SwerveModule::gearset_dps(vex::gearSetting gearing) { switch (gearing) { case vex::gearSetting::ratio36_1: - return (1.0 / 36.0) * MOTOR_MAX_RPM; + return (1.0 / 36.0) * MOTOR_MAX_RPM * 360.0; case vex::gearSetting::ratio18_1: - return (1.0 / 18.0) * MOTOR_MAX_RPM; + return (1.0 / 18.0) * MOTOR_MAX_RPM * 360.0; case vex::gearSetting::ratio6_1: - return (1.0 / 6.0) * MOTOR_MAX_RPM; + return (1.0 / 6.0) * MOTOR_MAX_RPM * 360.0; default: return 0.0; } From 6be79ddf6606e67730f3a1724fd0f78c933b533d Mon Sep 17 00:00:00 2001 From: superrm11 Date: Tue, 15 Sep 2020 19:38:19 -0400 Subject: [PATCH 013/243] Added mecanum drive to the project based on '18-19 --- include/subsystems/mecanum_drive.h | 26 +++++++++++++++ src/subsystems/mecanum_drive.cpp | 51 ++++++++++++++++++++++++++++++ 2 files changed, 77 insertions(+) create mode 100644 include/subsystems/mecanum_drive.h create mode 100644 src/subsystems/mecanum_drive.cpp diff --git a/include/subsystems/mecanum_drive.h b/include/subsystems/mecanum_drive.h new file mode 100644 index 0000000..84bbd9b --- /dev/null +++ b/include/subsystems/mecanum_drive.h @@ -0,0 +1,26 @@ +#ifndef _MECANUMDRIVE_ +#define _MECANUMDRIVE_ + +#include "vex.h" + +#ifndef PI +#define PI 3.141592654 +#endif + +class MecanumDrive +{ + + public: + + MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear); + + void drive(double left_y, double left_x, double right_x, int power=2); + + private: + + + vex::motor &left_front, &right_front, &left_rear, &right_rear; + +}; + +#endif \ No newline at end of file diff --git a/src/subsystems/mecanum_drive.cpp b/src/subsystems/mecanum_drive.cpp new file mode 100644 index 0000000..8f60a91 --- /dev/null +++ b/src/subsystems/mecanum_drive.cpp @@ -0,0 +1,51 @@ +#include "../core/include/subsystems/mecanum_drive.h" + +MecanumDrive::MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear) +: left_front(left_front), right_front(right_front), left_rear(left_rear), right_rear(right_rear) +{ + +} + +/** + * Drive the robot with a mecanum-style / arcade drive. Inputs are in percent (-100.0 -> 100.0) straight from the controller. + * Controls are mixed, so the robot can drive forward / strafe / rotate all at the same time. + * + * @param left_y left joystick, Y axis (forward / backwards) + * @param left_x left joystick, X axis (strafe left / right) + * @param right_x right joystick, X axis (rotation left / right) + * @param power=2 how much of a "curve" there should be on drive controls; better for low speed maneuvers. + * Leave blank for a default curve of 2 (higher means more fidelity) + */ +void MecanumDrive::drive(double left_y, double left_x, double right_x, int power) +{ + // LATERAL CONTROLS - convert cartesion to a vector + double magnitude = sqrt(pow(left_y / 100.0, 2) + pow(left_x / 100.0, 2)); + magnitude = pow(magnitude, power); + + double direction = atan2(left_x / 100.0, left_y / 100.0); + + // ROTATIONAL CONTROLS - just the right x joystick + // Ternary makes sure that if the "power" is even, the rotation keeps it's sign + double rotation = right_x / 100.0; + rotation = (power%2 == 0 ? rotation < 0 ? -1.0 : 1.0 : 1.0) * pow(rotation, power); + + + // ALGORITHM - "rotate" the vector by 45 degrees and apply each corner to a wheel + // .. Oh, and mix rotation too + double lf = (magnitude * cos(direction - (PI / 4.0))) + rotation; + double rf = (magnitude * cos(direction + (PI / 4.0))) - rotation; + double lr = (magnitude * cos(direction + (PI / 4.0))) + rotation; + double rr = (magnitude * cos(direction - (PI / 4.0))) - rotation; + + // Limit the output between -1.0 and +1.0 + lf = lf > 1.0 ? 1.0 : (lf < -1.0 ? -1.0 : lf); + rf = rf > 1.0 ? 1.0 : (rf < -1.0 ? -1.0 : rf); + lr = lr > 1.0 ? 1.0 : (lr < -1.0 ? -1.0 : lr); + rr = rr > 1.0 ? 1.0 : (rr < -1.0 ? -1.0 : rr); + + // Finally, spin the motors + left_front.spin(vex::directionType::fwd, lf * 100.0, vex::velocityUnits::pct); + right_front.spin(vex::directionType::fwd, rf * 100.0, vex::velocityUnits::pct); + left_rear.spin(vex::directionType::fwd, lr * 100.0, vex::velocityUnits::pct); + right_rear.spin(vex::directionType::fwd, rr * 100.0, vex::velocityUnits::pct); +} \ No newline at end of file From b0191cbe0254fc492961f9829b2bd2b58c5c00d3 Mon Sep 17 00:00:00 2001 From: superrm11 Date: Thu, 1 Oct 2020 20:35:11 -0400 Subject: [PATCH 014/243] Quick commit before I break anything --- include/subsystems/swerve_drive.h | 10 ++++- include/subsystems/swerve_module.h | 2 +- include/utils/generic_auto.h | 19 ++++------ src/subsystems/rgb_controller.cpp | 2 +- src/subsystems/swerve_drive.cpp | 61 ++++++++++++++++++++++++++++-- src/subsystems/swerve_module.cpp | 1 + src/subsystems/tank_drive.cpp | 2 +- src/utils/generic_auto.cpp | 23 +++++------ src/utils/pid.cpp | 2 +- src/utils/spline_path.cpp | 2 +- 10 files changed, 91 insertions(+), 33 deletions(-) diff --git a/include/subsystems/swerve_drive.h b/include/subsystems/swerve_drive.h index 54aa97e..c0e97a9 100644 --- a/include/subsystems/swerve_drive.h +++ b/include/subsystems/swerve_drive.h @@ -16,7 +16,7 @@ class SwerveDrive /** * Construct the SwerveDrive object. */ -SwerveDrive(SwerveModule &left_front, SwerveModule &left_rear, SwerveModule &right_front, SwerveModule &right_rear); +SwerveDrive(SwerveModule &left_front, SwerveModule &left_rear, SwerveModule &right_front, SwerveModule &right_rear, vex::inertial &imu); /** * Drive the robot using controller inputs. Deadbands are automatically taken into @@ -36,6 +36,12 @@ void drive(Vector lateral, double rotation); */ bool auto_drive(double direction, double speed, double distance); +/** + * Autonomously turn the robot over it's center axis in degrees. Positive degrees is clockwise, Negative is counter-clockwise + * Speed is in percent (-1.0 -> 1.0) + */ +bool auto_turn(double degrees, double speed); + void set_drive_pid(PID::pid_config_t &config); void set_turn_pid(PID::pid_config_t &config); @@ -43,9 +49,11 @@ void set_turn_pid(PID::pid_config_t &config); SwerveModule &left_front, &left_rear, &right_front, &right_rear; bool auto_drive_init = true; +bool auto_turn_init = true; double auto_drive_enc_reset = 0.0; PID *drive_pid, *turn_pid; +vex::inertial &imu; }; diff --git a/include/subsystems/swerve_module.h b/include/subsystems/swerve_module.h index 4502e6b..41bd40d 100644 --- a/include/subsystems/swerve_module.h +++ b/include/subsystems/swerve_module.h @@ -11,7 +11,7 @@ #define MOTOR_MAX_RPM 3600 -#define WHEEL_DIAM 4 //inches +#define WHEEL_DIAM 2.75 //inches class SwerveModule { diff --git a/include/utils/generic_auto.h b/include/utils/generic_auto.h index 3674c68..80e4123 100644 --- a/include/utils/generic_auto.h +++ b/include/utils/generic_auto.h @@ -1,21 +1,16 @@ #ifndef _GENAUTO_ #define _GENAUTO_ -#include +#include +#include +#include "vex.h" -typedef bool (*state_ptr)(void); +typedef bool (*state_ptr)(); class GenericAuto { public: - - /** - * Create the GenericAuto object - * - * Example: GenericAuto auto1 = {func_ptr1, func_ptr2, ...}; - */ - GenericAuto(std::initializer_list states); - + /** * The method that runs the autonomous. If 'blocking' is true, then * this method will run through every state until it finished. @@ -31,9 +26,11 @@ class GenericAuto */ bool run(bool blocking); + void add(state_ptr); + private: - std::vector state_list; + std::queue state_list; }; diff --git a/src/subsystems/rgb_controller.cpp b/src/subsystems/rgb_controller.cpp index 17af7b2..63b8f73 100644 --- a/src/subsystems/rgb_controller.cpp +++ b/src/subsystems/rgb_controller.cpp @@ -1,4 +1,4 @@ -#include "../Core/include/subsystems/rgb_controller.h" +#include "../core/include/subsystems/rgb_controller.h" RGBController::RGBController(rgb_t starting_color, vex::triport::port port1, vex::triport::port port2, vex::triport::port port3) : port1(port1), port2(port2), port3(port3) diff --git a/src/subsystems/swerve_drive.cpp b/src/subsystems/swerve_drive.cpp index 1c6f99b..7907d50 100644 --- a/src/subsystems/swerve_drive.cpp +++ b/src/subsystems/swerve_drive.cpp @@ -1,10 +1,13 @@ #include "../core/include/subsystems/swerve_drive.h" +#include + +using namespace std; /** * Construct the SwerveDrive object. */ -SwerveDrive::SwerveDrive(SwerveModule &left_front, SwerveModule &left_rear, SwerveModule &right_front, SwerveModule &right_rear) -:left_front(left_front), left_rear(left_rear), right_front(right_front), right_rear(right_rear) +SwerveDrive::SwerveDrive(SwerveModule &left_front, SwerveModule &left_rear, SwerveModule &right_front, SwerveModule &right_rear, vex::inertial &imu) +:left_front(left_front), left_rear(left_rear), right_front(right_front), right_rear(right_rear), imu(imu) { } @@ -31,6 +34,8 @@ void SwerveDrive::drive(int32_t leftY, int32_t leftX, int32_t rightX) if(fabs(rightX / 100.0) < LAT_DEADBAND) rightX = 0; + printf("distance: %f\n", left_front.get_distance_driven()); + // Convert input to a vector, and pass into main control method this->drive(input_lat, rightX / 100.0); } @@ -127,7 +132,7 @@ bool SwerveDrive::auto_drive(double direction, double speed, double distance) auto_drive_init = false; } - // PERIODIC + // LOOP drive_pid->update( left_front.get_distance_driven() - auto_drive_enc_reset ); this->drive(Vector(deg2rad(direction), drive_pid->get()), 0); @@ -140,5 +145,55 @@ bool SwerveDrive::auto_drive(double direction, double speed, double distance) return true; } + return false; +} + +/** + * Autonomously turn the robot over it's center axis in degrees. Positive degrees is clockwise, Negative is counter-clockwise + * Function is non-blocking, and returns true when it has finished turning. + */ +bool SwerveDrive::auto_turn(double degrees, double speed) +{ + if(turn_pid == NULL) + { + fprintf(stderr, "Failed to run auto_turn: missing PID config!"); + return true; + } + + // INIT + if(auto_turn_init) + { + // Wait until all the modules are at their 45's before continuing + bool all_wheels_done = true; + all_wheels_done = all_wheels_done && left_front.set_direction(45); + all_wheels_done = all_wheels_done && right_front.set_direction(45 + 90); + all_wheels_done = all_wheels_done && right_rear.set_direction(45 + 180); + all_wheels_done = all_wheels_done && left_rear.set_direction(45 + 270); + if(!all_wheels_done) + return false; + + // Reset the IMU rotation and configure the PID loop + imu.resetRotation(); + + turn_pid->reset(); + turn_pid->set_limits(-fabs(speed), fabs(speed)); + turn_pid->set_target(degrees); + + auto_turn_init = false; + } + + // LOOP + + turn_pid->update(imu.rotation()); + drive(Vector(0,0) , turn_pid->get()); + + // when the robot is on target, we are done. return true. + if(turn_pid->is_on_target()) + { + drive(Vector(0,0), 0); + auto_turn_init = true; + return true; + } + return false; } \ No newline at end of file diff --git a/src/subsystems/swerve_module.cpp b/src/subsystems/swerve_module.cpp index 18bceb2..25e1e74 100644 --- a/src/subsystems/swerve_module.cpp +++ b/src/subsystems/swerve_module.cpp @@ -88,6 +88,7 @@ void SwerveModule::set_speed(double percent) */ double SwerveModule::get_distance_driven() { + // return drive.position(vex::rotationUnits::rev); return WHEEL_DIAM * PI * drive.position(vex::rotationUnits::rev) * DRIVE_GEAR_RATIO; } diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index d6f548a..12e5805 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -1,4 +1,4 @@ -#include "../Core/include/subsystems/tank_drive.h" +#include "../core/include/subsystems/tank_drive.h" TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, inertial &gyro_sensor, TankDrive::tankdrive_config_t &config) : config(config), left_motors(left_motors), right_motors(right_motors), drive_pid(config.drive_pid), turn_pid(config.turn_pid), gyro_sensor(gyro_sensor) diff --git a/src/utils/generic_auto.cpp b/src/utils/generic_auto.cpp index f3d0976..b74804c 100644 --- a/src/utils/generic_auto.cpp +++ b/src/utils/generic_auto.cpp @@ -1,16 +1,5 @@ #include "../core/include/utils/generic_auto.h" -/** -* Create the GenericAuto object -* -* Example: GenericAuto auto1 = {func_ptr1, func_ptr2, ...}; -*/ -GenericAuto::GenericAuto(std::initializer_list states) -{ - for (state_ptr s : states) - state_list.push_back(s); -} - /** * The method that runs the autonomous. If 'blocking' is true, then * this method will run through every state until it finished. @@ -31,9 +20,11 @@ bool GenericAuto::run(bool blocking) do { + if( state_list.front()() ) + state_list.pop(); - if((state_list.front())() == true) - state_list.erase(state_list.begin()); + if(blocking) + vexDelay(50); } while(blocking && !state_list.empty()); @@ -41,3 +32,9 @@ bool GenericAuto::run(bool blocking) // If non-blocking, return false because the list isn't empty yet return blocking; } + +void GenericAuto::add(state_ptr newState) +{ + state_list.push(newState); +} + diff --git a/src/utils/pid.cpp b/src/utils/pid.cpp index cfdffe4..028e2b4 100644 --- a/src/utils/pid.cpp +++ b/src/utils/pid.cpp @@ -1,4 +1,4 @@ -#include "../Core/include/utils/pid.h" +#include "../core/include/utils/pid.h" /** * Create the PID object diff --git a/src/utils/spline_path.cpp b/src/utils/spline_path.cpp index 4485100..aedbb57 100644 --- a/src/utils/spline_path.cpp +++ b/src/utils/spline_path.cpp @@ -1,4 +1,4 @@ -#include "../Core/include/utils/spline_path.h" +#include "../core/include/utils/spline_path.h" SplinePath::SplinePath(TankDrive &drive_system, vex::inertial &imu, vex::motor &l_enc, vex::motor &r_enc, motion_profile_t &motion_profile) : drive_system(drive_system), l_enc(l_enc), r_enc(r_enc), imu(imu), motion_profile(motion_profile) From ee5fa13baddf029850bff5557966baa5d8102ee1 Mon Sep 17 00:00:00 2001 From: superrm11 Date: Sat, 3 Oct 2020 14:50:19 -0400 Subject: [PATCH 015/243] Fixed more include problems and vscode building --- include/subsystems/swerve_drive.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/include/subsystems/swerve_drive.h b/include/subsystems/swerve_drive.h index c0e97a9..2427458 100644 --- a/include/subsystems/swerve_drive.h +++ b/include/subsystems/swerve_drive.h @@ -1,9 +1,9 @@ #ifndef _SWERVEDRIVE_ #define _SWERVEDRIVE_ -#include "../Core/include/subsystems/swerve_module.h" -#include "../Core/include/utils/vector.h" -#include "../Core/include/utils/pid.h" +#include "../core/include/subsystems/swerve_module.h" +#include "../core/include/utils/vector.h" +#include "../core/include/utils/pid.h" #define ROT_DEADBAND 0.2 #define LAT_DEADBAND 0.2 From 4307fc84de7f9217ac395e6711b2fa9d23d38b27 Mon Sep 17 00:00:00 2001 From: superrm11 Date: Sun, 4 Oct 2020 18:31:10 -0400 Subject: [PATCH 016/243] SwerveDrive::auto_drive done, base PID tuning --- include/subsystems/swerve_drive.h | 1 - include/subsystems/swerve_module.h | 12 +++++++++--- src/subsystems/swerve_drive.cpp | 15 ++++++++++----- src/subsystems/swerve_module.cpp | 13 +++++++++++-- 4 files changed, 30 insertions(+), 11 deletions(-) diff --git a/include/subsystems/swerve_drive.h b/include/subsystems/swerve_drive.h index 2427458..286c385 100644 --- a/include/subsystems/swerve_drive.h +++ b/include/subsystems/swerve_drive.h @@ -50,7 +50,6 @@ void set_turn_pid(PID::pid_config_t &config); SwerveModule &left_front, &left_rear, &right_front, &right_rear; bool auto_drive_init = true; bool auto_turn_init = true; -double auto_drive_enc_reset = 0.0; PID *drive_pid, *turn_pid; vex::inertial &imu; diff --git a/include/subsystems/swerve_module.h b/include/subsystems/swerve_module.h index 41bd40d..171b231 100644 --- a/include/subsystems/swerve_module.h +++ b/include/subsystems/swerve_module.h @@ -51,11 +51,18 @@ class SwerveModule */ void set_speed(double percent); + /** + * Reset the drive encoder to zero + */ + void reset_distance_driven(); + /** * Get 'distance' from the drive motor */ double get_distance_driven(); - + + bool auto_reverse = false; + private: /** @@ -78,9 +85,8 @@ class SwerveModule vex::motor &direction; vex::gearSetting dir_gearing; - - double lastStoredHeading; bool inverseDrive; + double lastStoredHeading; double driveMulitplier; }; diff --git a/src/subsystems/swerve_drive.cpp b/src/subsystems/swerve_drive.cpp index 7907d50..4b1a3a1 100644 --- a/src/subsystems/swerve_drive.cpp +++ b/src/subsystems/swerve_drive.cpp @@ -103,6 +103,7 @@ bool SwerveDrive::auto_drive(double direction, double speed, double distance) // INITIALIZATION if(auto_drive_init) { + // std::cout << "Init-ing" << std::endl; // Turn all the wheels in the correct direction before running bool all_wheels_done = true; all_wheels_done = all_wheels_done & left_front.set_direction(direction); @@ -122,8 +123,7 @@ bool SwerveDrive::auto_drive(double direction, double speed, double distance) return false; // We're using the left front encoder for distance travelled. - auto_drive_enc_reset = left_front.get_distance_driven(); - + left_front.reset_distance_driven(); // set up the PID drive_pid->reset(); drive_pid->set_target(distance); @@ -133,9 +133,14 @@ bool SwerveDrive::auto_drive(double direction, double speed, double distance) } // LOOP - - drive_pid->update( left_front.get_distance_driven() - auto_drive_enc_reset ); - this->drive(Vector(deg2rad(direction), drive_pid->get()), 0); + drive_pid->update( left_front.get_distance_driven()); + + fprintf(stderr, "Distance Driven: %f\n", left_front.get_distance_driven()); + + left_front.set_speed(drive_pid->get()); + right_front.set_speed(drive_pid->get()); + left_rear.set_speed(drive_pid->get()); + right_rear.set_speed(drive_pid->get()); // Check if the driving is complete if(drive_pid->is_on_target()) diff --git a/src/subsystems/swerve_module.cpp b/src/subsystems/swerve_module.cpp index 25e1e74..7e143f5 100644 --- a/src/subsystems/swerve_module.cpp +++ b/src/subsystems/swerve_module.cpp @@ -66,8 +66,9 @@ bool SwerveModule::set_direction(double deg) // Slow down the drive if we aren't close to the set direction yet (use the cube of the error) driveMulitplier = pow(1 - (abs(normalizedDelta) / 90.0), 3); - return direction.spinTo((normalizedDelta + pos) / DIR_GEAR_RATIO, vex::rotationUnits::deg, 100, vex::velocityUnits::pct, false); + direction.spinTo((normalizedDelta + pos) / DIR_GEAR_RATIO, vex::rotationUnits::deg, 100, vex::velocityUnits::pct, false); + return direction.isDone(); } /** @@ -83,13 +84,21 @@ void SwerveModule::set_speed(double percent) drive.spin(vex::directionType::fwd, percent * 100.0 * (inverseDrive ? -1 : 1), vex::velocityUnits::pct); } +/** + * Reset the drive encoder to zero + */ +void SwerveModule::reset_distance_driven() +{ + drive.resetPosition(); +} + /** * Get 'distance' from the drive motor */ double SwerveModule::get_distance_driven() { // return drive.position(vex::rotationUnits::rev); - return WHEEL_DIAM * PI * drive.position(vex::rotationUnits::rev) * DRIVE_GEAR_RATIO; + return WHEEL_DIAM * PI * drive.position(vex::rotationUnits::rev) * DRIVE_GEAR_RATIO * (inverseDrive ? -1 : 1); } /** From 7c1753ae3606109d4ea1b8d9330fa01e17b2a022 Mon Sep 17 00:00:00 2001 From: superrm11 Date: Sun, 4 Oct 2020 21:43:32 -0400 Subject: [PATCH 017/243] re-tuned for floor mat, fixed auto_turn for swerve --- src/subsystems/swerve_drive.cpp | 30 +++++++++++++++++++++--------- src/subsystems/swerve_module.cpp | 13 ++++++++----- 2 files changed, 29 insertions(+), 14 deletions(-) diff --git a/src/subsystems/swerve_drive.cpp b/src/subsystems/swerve_drive.cpp index 4b1a3a1..c916e8c 100644 --- a/src/subsystems/swerve_drive.cpp +++ b/src/subsystems/swerve_drive.cpp @@ -34,7 +34,7 @@ void SwerveDrive::drive(int32_t leftY, int32_t leftX, int32_t rightX) if(fabs(rightX / 100.0) < LAT_DEADBAND) rightX = 0; - printf("distance: %f\n", left_front.get_distance_driven()); + // printf("distance: %f\n", left_front.get_distance_driven()); // Convert input to a vector, and pass into main control method this->drive(input_lat, rightX / 100.0); @@ -122,8 +122,11 @@ bool SwerveDrive::auto_drive(double direction, double speed, double distance) if(!all_wheels_done) return false; - // We're using the left front encoder for distance travelled. left_front.reset_distance_driven(); + right_front.reset_distance_driven(); + left_rear.reset_distance_driven(); + right_rear.reset_distance_driven(); + // set up the PID drive_pid->reset(); drive_pid->set_target(distance); @@ -132,10 +135,13 @@ bool SwerveDrive::auto_drive(double direction, double speed, double distance) auto_drive_init = false; } + double average = (left_front.get_distance_driven() + right_front.get_distance_driven() + + left_rear.get_distance_driven() + right_rear.get_distance_driven()) / 4.0; + // LOOP - drive_pid->update( left_front.get_distance_driven()); + drive_pid->update(average); - fprintf(stderr, "Distance Driven: %f\n", left_front.get_distance_driven()); + fprintf(stderr, "Distance Driven: %f\n", average); left_front.set_speed(drive_pid->get()); right_front.set_speed(drive_pid->get()); @@ -170,10 +176,10 @@ bool SwerveDrive::auto_turn(double degrees, double speed) { // Wait until all the modules are at their 45's before continuing bool all_wheels_done = true; - all_wheels_done = all_wheels_done && left_front.set_direction(45); - all_wheels_done = all_wheels_done && right_front.set_direction(45 + 90); - all_wheels_done = all_wheels_done && right_rear.set_direction(45 + 180); - all_wheels_done = all_wheels_done && left_rear.set_direction(45 + 270); + all_wheels_done = all_wheels_done & left_front.set_direction(45); + all_wheels_done = all_wheels_done & right_front.set_direction(45 + 90); + all_wheels_done = all_wheels_done & right_rear.set_direction(-45 - 90); + all_wheels_done = all_wheels_done & left_rear.set_direction(-45); if(!all_wheels_done) return false; @@ -190,7 +196,13 @@ bool SwerveDrive::auto_turn(double degrees, double speed) // LOOP turn_pid->update(imu.rotation()); - drive(Vector(0,0) , turn_pid->get()); + left_front.set_speed(turn_pid->get()); + right_front.set_speed(turn_pid->get()); + left_rear.set_speed(turn_pid->get()); + right_rear.set_speed(turn_pid->get()); + + fprintf(stderr, "Angle: %f ", imu.rotation()); + fprintf(stderr, "Out: %f \n", turn_pid->get()); // when the robot is on target, we are done. return true. if(turn_pid->is_on_target()) diff --git a/src/subsystems/swerve_module.cpp b/src/subsystems/swerve_module.cpp index 7e143f5..613a2c3 100644 --- a/src/subsystems/swerve_module.cpp +++ b/src/subsystems/swerve_module.cpp @@ -65,10 +65,11 @@ bool SwerveModule::set_direction(double deg) // Slow down the drive if we aren't close to the set direction yet (use the cube of the error) driveMulitplier = pow(1 - (abs(normalizedDelta) / 90.0), 3); + double setpnt = (normalizedDelta + pos) / DIR_GEAR_RATIO; - direction.spinTo((normalizedDelta + pos) / DIR_GEAR_RATIO, vex::rotationUnits::deg, 100, vex::velocityUnits::pct, false); + direction.spinTo(setpnt, vex::rotationUnits::deg, 100, vex::velocityUnits::pct, false); - return direction.isDone(); + return fabs(setpnt - direction.rotation(rotationUnits::deg)) < 2; } /** @@ -80,8 +81,9 @@ void SwerveModule::set_speed(double percent) // take into account how the RPM of the direction motor affects the RPM of the drive wheel //double speed_diff_dps = 0;//direction.velocity(vex::velocityUnits::dps) * DIR_GEAR_RATIO * -.2; // Difference is negligable. Not worth the effort of getting it right. + drive.setReversed(inverseDrive); - drive.spin(vex::directionType::fwd, percent * 100.0 * (inverseDrive ? -1 : 1), vex::velocityUnits::pct); + drive.spin(vex::directionType::fwd, percent * 100.0, vex::velocityUnits::pct); } /** @@ -93,12 +95,13 @@ void SwerveModule::reset_distance_driven() } /** - * Get 'distance' from the drive motor + * Get 'distance' from the drive motor. + * Will ALWAYS be positive. */ double SwerveModule::get_distance_driven() { // return drive.position(vex::rotationUnits::rev); - return WHEEL_DIAM * PI * drive.position(vex::rotationUnits::rev) * DRIVE_GEAR_RATIO * (inverseDrive ? -1 : 1); + return fabs(WHEEL_DIAM * PI * drive.position(vex::rotationUnits::rev) * DRIVE_GEAR_RATIO); } /** From 7afd089f008ccd932e60bc13dedee54213a7580b Mon Sep 17 00:00:00 2001 From: superrm11 Date: Tue, 3 Nov 2020 22:52:12 -0500 Subject: [PATCH 018/243] Added auto_drive to Mecanum. No promises. --- include/subsystems/mecanum_drive.h | 30 ++++- src/subsystems/mecanum_drive.cpp | 184 ++++++++++++++++++++++++++--- 2 files changed, 194 insertions(+), 20 deletions(-) diff --git a/include/subsystems/mecanum_drive.h b/include/subsystems/mecanum_drive.h index 84bbd9b..6472b5a 100644 --- a/include/subsystems/mecanum_drive.h +++ b/include/subsystems/mecanum_drive.h @@ -2,6 +2,7 @@ #define _MECANUMDRIVE_ #include "vex.h" +#include "../core/include/utils/pid.h" #ifndef PI #define PI 3.141592654 @@ -12,15 +13,40 @@ class MecanumDrive public: - MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear); + struct mecanumdrive_config_t + { + PID::pid_config_t drive_pid_conf; + PID::pid_config_t drive_gyro_pid_conf; + PID::pid_config_t turn_pid_conf; + + double drive_wheel_diam; + double lateral_wheel_diam; + + }; + + MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear, + vex::rotation *lateral_wheel=NULL, vex::inertial *imu=NULL, mecanumdrive_config_t *config=NULL); + + void drive_raw(double direction_deg, double magnitude, double rotation); void drive(double left_y, double left_x, double right_x, int power=2); - private: + bool auto_drive(double inches, double direction, double speed, bool gyro_correction=true); + private: vex::motor &left_front, &right_front, &left_rear, &right_rear; + mecanumdrive_config_t *config; + vex::rotation *lateral_wheel; + vex::inertial *imu; + + PID *drive_pid = NULL; + PID *drive_gyro_pid = NULL; + PID *turn_pid = NULL; + + bool init = true; + }; #endif \ No newline at end of file diff --git a/src/subsystems/mecanum_drive.cpp b/src/subsystems/mecanum_drive.cpp index 8f60a91..d0873d1 100644 --- a/src/subsystems/mecanum_drive.cpp +++ b/src/subsystems/mecanum_drive.cpp @@ -1,9 +1,53 @@ #include "../core/include/subsystems/mecanum_drive.h" -MecanumDrive::MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear) -: left_front(left_front), right_front(right_front), left_rear(left_rear), right_rear(right_rear) +MecanumDrive::MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear, + vex::rotation *lateral_wheel, vex::inertial *imu, mecanumdrive_config_t *config) +: left_front(left_front), right_front(right_front), left_rear(left_rear), right_rear(right_rear), // MOTOR CONFIG + config(config), // CONFIG ...uh... config + lateral_wheel(lateral_wheel), // NON-DRIVEN WHEEL CONFIG + imu(imu) //IMU CONFIG { + // If the configuration exists, then allocate memory for the drive and turn pids + if(config != NULL) + { + drive_pid = new PID(config->drive_pid_conf); + drive_gyro_pid = new PID(config->drive_gyro_pid_conf); + turn_pid = new PID(config->turn_pid_conf); + } + +} + +/** + * Drive the robot using vectors. This handles all the math required for mecanum control. + * + * @param direction_deg the direction to drive the robot, in degrees. 0 is forward, + * 180 is back, clockwise is positive, counterclockwise is negative. + * @param magnitude How fast the robot should drive, in percent: 0.0->1.0 + * @param rotation How fast the robot should rotate, in percent: -1.0->+1.0 + */ +void MecanumDrive::drive_raw(double direction_deg, double magnitude, double rotation) +{ + double direction = (PI / 180.0) * direction_deg; + + // ALGORITHM - "rotate" the vector by 45 degrees and apply each corner to a wheel + // .. Oh, and mix rotation too + double lf = (magnitude * cos(direction - (PI / 4.0))) + rotation; + double rf = (magnitude * cos(direction + (PI / 4.0))) - rotation; + double lr = (magnitude * cos(direction + (PI / 4.0))) + rotation; + double rr = (magnitude * cos(direction - (PI / 4.0))) - rotation; + + // Limit the output between -1.0 and +1.0 + lf = lf > 1.0 ? 1.0 : (lf < -1.0 ? -1.0 : lf); + rf = rf > 1.0 ? 1.0 : (rf < -1.0 ? -1.0 : rf); + lr = lr > 1.0 ? 1.0 : (lr < -1.0 ? -1.0 : lr); + rr = rr > 1.0 ? 1.0 : (rr < -1.0 ? -1.0 : rr); + + // Finally, spin the motors + left_front.spin(vex::directionType::fwd, lf * 100.0, vex::velocityUnits::pct); + right_front.spin(vex::directionType::fwd, rf * 100.0, vex::velocityUnits::pct); + left_rear.spin(vex::directionType::fwd, lr * 100.0, vex::velocityUnits::pct); + right_rear.spin(vex::directionType::fwd, rr * 100.0, vex::velocityUnits::pct); } /** @@ -29,23 +73,127 @@ void MecanumDrive::drive(double left_y, double left_x, double right_x, int power double rotation = right_x / 100.0; rotation = (power%2 == 0 ? rotation < 0 ? -1.0 : 1.0 : 1.0) * pow(rotation, power); + return this->drive_raw(direction * (180.0 / PI), magnitude, rotation); +} - // ALGORITHM - "rotate" the vector by 45 degrees and apply each corner to a wheel - // .. Oh, and mix rotation too - double lf = (magnitude * cos(direction - (PI / 4.0))) + rotation; - double rf = (magnitude * cos(direction + (PI / 4.0))) - rotation; - double lr = (magnitude * cos(direction + (PI / 4.0))) + rotation; - double rr = (magnitude * cos(direction - (PI / 4.0))) - rotation; +/** + * Drive the robot in a straight line automatically. + * If the inertial was declared in the constructor, use it to correct while driving. + * If the lateral wheel was declared in the constructor, use it for more accurate positioning while strafing. + * + * @param inches How far the robot should drive, in inches + * @param direction What direction the robot should travel in, in degrees. + * 0 is forward, +/-180 is reverse, clockwise is positive. + * @param speed The maximum speed the robot should travel, in percent: -1.0->+1.0 + * @param gyro_correction=true Whether or not to use the gyro to help correct while driving. + * Will always be false if no gyro was declared in the constructor. + */ +bool MecanumDrive::auto_drive(double inches, double direction, double speed, bool gyro_correction) +{ + if(config == NULL || drive_pid == NULL) + { + fprintf(stderr, "Failed to run MecanumDrive::auto_drive - Missing mecanumdrive_config_t in constructor"); + return true; // avoid an infinte loop within auto + } - // Limit the output between -1.0 and +1.0 - lf = lf > 1.0 ? 1.0 : (lf < -1.0 ? -1.0 : lf); - rf = rf > 1.0 ? 1.0 : (rf < -1.0 ? -1.0 : rf); - lr = lr > 1.0 ? 1.0 : (lr < -1.0 ? -1.0 : lr); - rr = rr > 1.0 ? 1.0 : (rr < -1.0 ? -1.0 : rr); + bool enable_gyro = gyro_correction && (imu != NULL); + bool enable_wheel = (lateral_wheel != NULL); - // Finally, spin the motors - left_front.spin(vex::directionType::fwd, lf * 100.0, vex::velocityUnits::pct); - right_front.spin(vex::directionType::fwd, rf * 100.0, vex::velocityUnits::pct); - left_rear.spin(vex::directionType::fwd, lr * 100.0, vex::velocityUnits::pct); - right_rear.spin(vex::directionType::fwd, rr * 100.0, vex::velocityUnits::pct); + + // INITIALIZE - only run ONCE "per drive" on startup + if(init == true) + { + + // Reset all driven encoders, and PID + left_front.resetPosition(); + right_front.resetPosition(); + left_rear.resetPosition(); + right_rear.resetPosition(); + + drive_pid->reset(); + + // Reset only if gyro exists + if(enable_gyro) + { + imu->resetRotation(); + drive_gyro_pid->reset(); + drive_gyro_pid->set_target(0.0); + } + // reset only if lateral wheel exists + if(enable_wheel) + lateral_wheel->resetPosition(); + + // Finish setting up the PID loop - max speed and position target + drive_pid->set_limits(-fabs(speed), fabs(speed)); + drive_pid->set_target(fabs(inches)); + + init = false; + } + + double dist_avg = 0.0; + double drive_avg = 0.0; + + // This algorithm should be DEFINITELY good for forward/back, left/right. + // Directions other than 0, 180, -90 and 90 will be hit or miss, but should be mostly right. + // Recommend THOUROUGH testing at many angles. + + // IF in quadrant 1 or 3, use left front and right rear wheels as "drive" movement + // ELSE in quadrant 2 or 4, use left rear and right front wheels as "drive" movement + // Some wheels are NOT being averaged at any given time since the general mecanum algorithm makes them go slower than our robot speed + // somewhat of a nasty hack, but wheel slippage should make up for it, and multivariable calc is hard. + if( (direction > 0 && direction <= 90) || (direction < -90 && direction > -180)) + { + drive_avg = fabs(left_front.position(rotationUnits::rev) * config->drive_wheel_diam * PI) + + fabs(right_rear.position(rotationUnits::rev) * config->drive_wheel_diam * PI) + / 2.0; + } else + { + drive_avg = fabs(left_rear.position(rotationUnits::rev) * config->drive_wheel_diam * PI) + + fabs(right_front.position(rotationUnits::rev) * config->drive_wheel_diam * PI) + / 2.0; + } + + // Only use the encoder wheel if it exists. + // Without the wheel should be usable, but with it will be muuuuch more accurate. + if(enable_wheel) + { + // Distance driven = Magnitude = sqrt(x^2 + y^2) + // Since drive_avg is already a polar magnitude, turn it into "Y" with cos(theta) + dist_avg = sqrt( + pow(lateral_wheel->position(rotationUnits::rev) * config->lateral_wheel_diam * PI, 2) + + pow(drive_avg * cos(direction * (PI / 180.0)), 2) + ); + }else + { + dist_avg = drive_avg; + } + + // ...double check to avoid an infinite loop + dist_avg = fabs(dist_avg); + + + // ROTATION CORRECTION + double rot = 0; + + if(enable_gyro) + { + drive_gyro_pid->update(imu->rotation()); + rot = drive_gyro_pid->get(); + } + + // Update the PID and drive + drive_pid->update(drive_avg); + + this->drive_raw(direction, drive_pid->get(), rot); + + // Stop and return true whenever the robot has completed it's drive. + if(drive_pid->is_on_target()) + { + drive_raw(0, 0, 0); + init = true; + return true; + } + + // Return false while the robot is still driving. + return false; } \ No newline at end of file From 34ce775d4456298c0592f6065183f937df5a1ce7 Mon Sep 17 00:00:00 2001 From: superrm11 Date: Fri, 6 Nov 2020 14:42:59 -0500 Subject: [PATCH 019/243] Added auto_turn to MecanumDrive class --- include/subsystems/mecanum_drive.h | 59 ++++++++++++++++++++++ src/subsystems/mecanum_drive.cpp | 79 +++++++++++++++++++++++++++++- 2 files changed, 137 insertions(+), 1 deletion(-) diff --git a/include/subsystems/mecanum_drive.h b/include/subsystems/mecanum_drive.h index 6472b5a..398b821 100644 --- a/include/subsystems/mecanum_drive.h +++ b/include/subsystems/mecanum_drive.h @@ -8,31 +8,90 @@ #define PI 3.141592654 #endif +/** + * A class representing the Mecanum drivetrain. + * Contains 4 motors, a possible IMU (intertial), and a possible undriven perpendicular wheel. + */ class MecanumDrive { public: + /** + * Configure the Mecanum drive PID tunings and robot configurations + */ struct mecanumdrive_config_t { + // PID configurations for autonomous driving PID::pid_config_t drive_pid_conf; PID::pid_config_t drive_gyro_pid_conf; PID::pid_config_t turn_pid_conf; + // Diameter of the mecanum wheels double drive_wheel_diam; + + // Diameter of the perpendicular undriven encoder wheel double lateral_wheel_diam; + // Width between the center of the left and right wheels + double wheelbase_width; + }; + /** + * Create the Mecanum drivetrain object + */ MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear, vex::rotation *lateral_wheel=NULL, vex::inertial *imu=NULL, mecanumdrive_config_t *config=NULL); + /** + * Drive the robot using vectors. This handles all the math required for mecanum control. + * + * @param direction_deg the direction to drive the robot, in degrees. 0 is forward, + * 180 is back, clockwise is positive, counterclockwise is negative. + * @param magnitude How fast the robot should drive, in percent: 0.0->1.0 + * @param rotation How fast the robot should rotate, in percent: -1.0->+1.0 + */ void drive_raw(double direction_deg, double magnitude, double rotation); + /** + * Drive the robot with a mecanum-style / arcade drive. Inputs are in percent (-100.0 -> 100.0) straight from the controller. + * Controls are mixed, so the robot can drive forward / strafe / rotate all at the same time. + * + * @param left_y left joystick, Y axis (forward / backwards) + * @param left_x left joystick, X axis (strafe left / right) + * @param right_x right joystick, X axis (rotation left / right) + * @param power=2 how much of a "curve" there should be on drive controls; better for low speed maneuvers. + * Leave blank for a default curve of 2 (higher means more fidelity) + */ void drive(double left_y, double left_x, double right_x, int power=2); + /** + * Drive the robot in a straight line automatically. + * If the inertial was declared in the constructor, use it to correct while driving. + * If the lateral wheel was declared in the constructor, use it for more accurate positioning while strafing. + * + * @param inches How far the robot should drive, in inches + * @param direction What direction the robot should travel in, in degrees. + * 0 is forward, +/-180 is reverse, clockwise is positive. + * @param speed The maximum speed the robot should travel, in percent: -1.0->+1.0 + * @param gyro_correction=true Whether or not to use the gyro to help correct while driving. + * Will always be false if no gyro was declared in the constructor. + */ bool auto_drive(double inches, double direction, double speed, bool gyro_correction=true); + /** + * Autonomously turn the robot X degrees over it's center point. Uses a closed loop + * for control. + * @param degrees How many degrees to rotate the robot. Clockwise postive. + * @param speed What percentage to run the motors at: 0.0 -> 1.0 + * @param ignore_imu=false Whether or not to use the Inertial for determining angle. + * Will instead use circumference formula + robot's wheelbase + encoders to determine. + * + * @return whether or not the robot has finished the maneuver + */ + bool auto_turn(double degrees, double speed, bool ignore_imu=false); + private: vex::motor &left_front, &right_front, &left_rear, &right_rear; diff --git a/src/subsystems/mecanum_drive.cpp b/src/subsystems/mecanum_drive.cpp index d0873d1..962a3bc 100644 --- a/src/subsystems/mecanum_drive.cpp +++ b/src/subsystems/mecanum_drive.cpp @@ -1,5 +1,8 @@ #include "../core/include/subsystems/mecanum_drive.h" +/** +* Create the Mecanum drivetrain object +*/ MecanumDrive::MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear, vex::rotation *lateral_wheel, vex::inertial *imu, mecanumdrive_config_t *config) : left_front(left_front), right_front(right_front), left_rear(left_rear), right_rear(right_rear), // MOTOR CONFIG @@ -87,12 +90,13 @@ void MecanumDrive::drive(double left_y, double left_x, double right_x, int power * @param speed The maximum speed the robot should travel, in percent: -1.0->+1.0 * @param gyro_correction=true Whether or not to use the gyro to help correct while driving. * Will always be false if no gyro was declared in the constructor. + * @return Whether or not the maneuver is complete. */ bool MecanumDrive::auto_drive(double inches, double direction, double speed, bool gyro_correction) { if(config == NULL || drive_pid == NULL) { - fprintf(stderr, "Failed to run MecanumDrive::auto_drive - Missing mecanumdrive_config_t in constructor"); + fprintf(stderr, "Failed to run MecanumDrive::auto_drive - Missing mecanumdrive_config_t in constructor\n"); return true; // avoid an infinte loop within auto } @@ -195,5 +199,78 @@ bool MecanumDrive::auto_drive(double inches, double direction, double speed, boo } // Return false while the robot is still driving. + return false; +} + +/** +* Autonomously turn the robot X degrees over it's center point. Uses a closed loop +* for control. +* @param degrees How many degrees to rotate the robot. Clockwise postive. +* @param speed What percentage to run the motors at: 0.0 -> 1.0 +* @param ignore_imu=false Whether or not to use the Inertial for determining angle. +* Will instead use circumference formula + robot's wheelbase + encoders to determine. +* +* @return whether or not the robot has finished the maneuver +*/ +bool MecanumDrive::auto_turn(double degrees, double speed, bool ignore_imu) +{ + // Make sure the configurations exist before continuing + if(config == NULL || turn_pid == NULL) + { + fprintf(stderr, "Failed to run MecanumDrive::auto_turn - Missing mecanumdrive_config_t in constructor\n"); + return true; + } + + // Decide whether or not to use the Inertial + ignore_imu = ignore_imu || (this->imu == NULL); + + // INITIALIZE - clear encoders / imu / pid loops + if(init == true) + { + if(ignore_imu) + { + this->left_front.resetPosition(); + this->right_front.resetPosition(); + this->left_rear.resetPosition(); + this->right_rear.resetPosition(); + }else + { + this->imu->resetRotation(); + } + + this->turn_pid->reset(); + this->turn_pid->set_limits(-fabs(speed), fabs(speed)); + this->turn_pid->set_target(degrees); + + init = false; + } + + // RUN PERIODICALLY + + double current_angle = 0.0; + + if(ignore_imu) + { + double avg = (left_front.position(rotationUnits::rev) + left_rear.position(rotationUnits::rev) + - right_front.position(rotationUnits::rev) - right_rear.position(rotationUnits::rev)) / 4.0; + + // Current arclength = (avg * wheel_diam * PI) = (theta * (wheelbase / 2.0)). then convert to degrees + current_angle = (360.0 * avg * config->drive_wheel_diam) / config->wheelbase_width; + } else + { + current_angle = imu->rotation(); + } + + this->turn_pid->update(current_angle); + this->drive_raw(0, 0, turn_pid->get()); + + // We have reached the target. + if(this->turn_pid->is_on_target()) + { + this->drive_raw(0, 0, 0); + init = true; + return true; + } + return false; } \ No newline at end of file From af78569170a0cf1776b1ac7032505f5ba3595a20 Mon Sep 17 00:00:00 2001 From: superrm11 Date: Fri, 6 Nov 2020 14:45:09 -0500 Subject: [PATCH 020/243] Fixed feed-forward issue in PID --- src/utils/pid.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/utils/pid.cpp b/src/utils/pid.cpp index 028e2b4..c0c8727 100644 --- a/src/utils/pid.cpp +++ b/src/utils/pid.cpp @@ -21,7 +21,7 @@ void PID::update(double sensor_val) accum_error += time_delta * get_error(); - out = (config.f) + (config.p * get_error()) + (config.i * accum_error) + (config.d * (get_error() - last_error) / time_delta); + out = (config.f * target) + (config.p * get_error()) + (config.i * accum_error) + (config.d * (get_error() - last_error) / time_delta); last_time = pid_timer.value(); last_error = get_error(); From 59f2125712287b13066b6a0b4057eaa429170f67 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Mon, 24 May 2021 22:06:16 -0400 Subject: [PATCH 021/243] Added the Core build system --- include/subsystems/swerve_module.h | 4 ++++ src/subsystems/swerve_module.cpp | 2 +- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/include/subsystems/swerve_module.h b/include/subsystems/swerve_module.h index 171b231..e93d077 100644 --- a/include/subsystems/swerve_module.h +++ b/include/subsystems/swerve_module.h @@ -3,6 +3,10 @@ #include "vex.h" +#ifndef PI +#define PI 3.141592654 +#endif + // Gear teeth (input to output): 16, 35 #define DIR_GEAR_RATIO (16.0/35.0) // ~0.457 diff --git a/src/subsystems/swerve_module.cpp b/src/subsystems/swerve_module.cpp index 613a2c3..570c6d4 100644 --- a/src/subsystems/swerve_module.cpp +++ b/src/subsystems/swerve_module.cpp @@ -1,5 +1,5 @@ #include "../core/include/subsystems/swerve_module.h" -#include "hardware.h" + /** * Create a single swerve module, made up of a Drive motor and a Direction motor. From dcb96b3fab76c8919b52a1f619c0391720657a30 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Mon, 24 May 2021 22:06:16 -0400 Subject: [PATCH 022/243] Added the Core build system --- include/subsystems/swerve_module.h | 4 ++++ src/subsystems/swerve_module.cpp | 2 +- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/include/subsystems/swerve_module.h b/include/subsystems/swerve_module.h index 171b231..e93d077 100644 --- a/include/subsystems/swerve_module.h +++ b/include/subsystems/swerve_module.h @@ -3,6 +3,10 @@ #include "vex.h" +#ifndef PI +#define PI 3.141592654 +#endif + // Gear teeth (input to output): 16, 35 #define DIR_GEAR_RATIO (16.0/35.0) // ~0.457 diff --git a/src/subsystems/swerve_module.cpp b/src/subsystems/swerve_module.cpp index 613a2c3..570c6d4 100644 --- a/src/subsystems/swerve_module.cpp +++ b/src/subsystems/swerve_module.cpp @@ -1,5 +1,5 @@ #include "../core/include/subsystems/swerve_module.h" -#include "hardware.h" + /** * Create a single swerve module, made up of a Drive motor and a Direction motor. From 24f62629fc2c999d44df9c1471a50f4007120bc2 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Mon, 31 May 2021 18:06:23 -0400 Subject: [PATCH 023/243] Finished async calculations --- include/subsystems/odometry.h | 87 ++++++++++++++++++ src/subsystems/odometry.cpp | 167 ++++++++++++++++++++++++++++++++++ 2 files changed, 254 insertions(+) create mode 100644 include/subsystems/odometry.h create mode 100644 src/subsystems/odometry.cpp diff --git a/include/subsystems/odometry.h b/include/subsystems/odometry.h new file mode 100644 index 0000000..5481146 --- /dev/null +++ b/include/subsystems/odometry.h @@ -0,0 +1,87 @@ +#ifndef _ODOMETRY_ +#define _ODOMETRY_ + +#include "vex.h" +#include "../core/include/utils/vector.h" + +#define DOWNTIME 50 //milliseconds + +#ifndef PI +#define PI 3.141592654 +#endif + +/** + * The background task constantly polling the motors and updating the position. + */ +static int background_task(void* pos_ptr); + +// Describes a single position and rotation +typedef struct +{ + double x; + double y; + double rot; +} position_t; + +typedef struct +{ + double dist_between_wheels; + double wheel_diam; +} odometry_config_t; + +class Odometry +{ + public: + + /** + * Initialize the Odometry module, using the IMU to get rotation + * @param left_side The left motors + * @param right_side The right motors + * @param imu The robot's inertial sensor + */ + Odometry(vex::motor_group &left_side, vex::motor_group &right_side, vex::inertial &imu, odometry_config_t &config); + + /** + * Initialize the Odometry module, calculating the rotation from encoders + * @param left_side The left motors + * @param right_side The right motors + * @param imu The robot's inertial sensor + */ + Odometry(vex::motor_group &left_side, vex::motor_group &right_side, odometry_config_t &config); + + /** + * Gets the current position and rotation + */ + position_t get_position(); + + /** + * Sets the current position of the robot + */ + void set_position(position_t &newpos); + + /** + * Get the distance between two points + */ + static double pos_diff(position_t &pos1, position_t &pos2); + + /** + * Get the change in rotation between two points + */ + static double rot_diff(position_t &pos1, position_t &pos2); + + private: + + vex::mutex mut; + position_t current_pos; + + vex::motor_group *left_side, *right_side; + vex::inertial *imu; + odometry_config_t *config; + + vex::task *handle; + + + +}; + +#endif \ No newline at end of file diff --git a/src/subsystems/odometry.cpp b/src/subsystems/odometry.cpp new file mode 100644 index 0000000..2a3197b --- /dev/null +++ b/src/subsystems/odometry.cpp @@ -0,0 +1,167 @@ +#include "../core/include/subsystems/odometry.h" + +/** + * Initialize the Odometry module, using the IMU to get rotation + * @param left_side The left motors + * @param right_side The right motors + * @param imu The robot's inertial sensor + */ +Odometry::Odometry(vex::motor_group &left_side, vex::motor_group &right_side, vex::inertial &imu, odometry_config_t &config) +: left_side(&left_side), right_side(&right_side), imu(&imu), config(&config) +{ + // Create a raw pointer containing a list of all the hardware pointers needed to run the thread. + // This is done because callbacks do not allow class member functions + void* list[] = {this->left_side, this->right_side, this->imu, this->config, &mut, ¤t_pos}; + + // Initialize and start the background task + handle = new vex::task(background_task, list); +} + +/** + * Initialize the Odometry module, calculating the rotation from encoders + * @param left_side The left motors + * @param right_side The right motors + * @param imu The robot's inertial sensor + */ +Odometry::Odometry(vex::motor_group &left_side, vex::motor_group &right_side, odometry_config_t &config) +: left_side(&left_side), right_side(&right_side), imu(NULL), config(&config) +{ + // Create a raw pointer containing a list of all the hardware pointers needed to run the thread. + // This is done because callbacks do not allow class member functions + void* list[] = {this->left_side, this->right_side, this->imu, this->config, &mut, ¤t_pos}; + + // Initialize and start the background task + handle = new vex::task(background_task, list); + +} + +/** + * The background task constantly polling the motors and updating the position. + */ +int background_task(void* obj_ptrs) +{ + // Parse the hardware passed into the function + void** list = (void**) obj_ptrs; + + // Dereference the pointers and store as object references to make it cleaner later + vex::motor_group &left_side = *((vex::motor_group*) list[0]); + vex::motor_group &right_side = *((vex::motor_group*) list[1]); + vex::inertial *imu = (vex::inertial*) list[2]; // (keep as pointer to check for NULL) + odometry_config_t &config = *((odometry_config_t*) list[3]); + vex::mutex &mut = *((vex::mutex*) list[4]); + position_t ¤t_pos = *((position_t*) list[5]); + + double last_lside = 0, last_rside = 0; + + while(true) + { + double angle = 0; + + // If the IMU was passed in, use it for rotational data + if(imu != NULL) + angle = imu->heading(); + else + { + // Get the difference in distance driven between the two sides + double distance_diff = (left_side.position(rotationUnits::rev) - right_side.position(rotationUnits::rev)) * PI * config.wheel_diam; + + //Use the arclength formula to calculate the angle. + angle = (180.0 / PI) * (distance_diff / config.dist_between_wheels); + + //Limit the angle betwen 0 and 360. + //fmod (floating-point modulo) gets it between -359 and +359, so tack on another 360 if it's negative. + angle = fmod(angle, 360.0); + if(angle < 0) + angle += 360; + } + + angle *= PI / 180.0; // Degrees to radians + + // Get the encoder values in revolutions (Make sure the gearsetting is set) + double curr_lside = left_side.position(rotationUnits::rev); + double curr_rside = right_side.position(rotationUnits::rev); + + // Convert the revolutions into "change in distance", and average the values for a "distance driven" + double lside_diff = (curr_lside - last_lside) * config.wheel_diam; + double rside_diff = (curr_rside - last_rside) * config.wheel_diam; + double dist_driven = (lside_diff + rside_diff) / 2.0; + + // Create a vector from the change in distance in the current direction of the robot + Vector chg_vec(angle, dist_driven); + + // Create a vector from the current position in reference to X,Y=0,0 + Vector::point_t curr_point = {.x = current_pos.x, .y = current_pos.y}; + Vector curr_vec(curr_point); + + // Tack on the "difference" vector to the current vector + Vector new_vec = curr_vec + chg_vec; + + // Store the left and right encoder values to find the difference in the next iteration + last_lside = curr_lside; + last_rside = curr_rside; + + // Avoid race conditions by locking the mutex + mut.lock(); + + // Get the X and Y coordinates from the vector and save them to the "current position" + current_pos.x = new_vec.get_x(); + current_pos.y = new_vec.get_y(); + current_pos.rot = angle; + + mut.unlock(); + + vexDelay(DOWNTIME); + } +} + +/** + * Gets the current position and rotation + */ +position_t Odometry::get_position() +{ + mut.lock(); + + position_t out = + { + .x = current_pos.x, + .y = current_pos.y, + .rot = current_pos.rot + }; + + mut.unlock(); + + return out; +} + +/** + * Sets the current position of the robot + */ +void Odometry::set_position(position_t &newpos) +{ + mut.lock(); + + current_pos.x = newpos.x; + current_pos.y = newpos.y; + current_pos.rot = newpos.rot; + + mut.unlock(); +} + +/** + * Get the distance between two points + */ +double Odometry::pos_diff(position_t &pos1, position_t &pos2) +{ + // Use the pythagorean theorem + return sqrt(pow(pos2.x - pos1.x, 2) + pow(pos2.y - pos1.y, 2)); + +} + +/** + * Get the change in rotation between two points + */ +double Odometry::rot_diff(position_t &pos1, position_t &pos2) +{ + return pos2.rot - pos1.rot; +} + From 3c0bbe6327c654452bc601ecb30e35261d8a9477 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Fri, 2 Jul 2021 11:26:05 -0400 Subject: [PATCH 024/243] Restructured calculations, fixed async and added update() --- include/subsystems/odometry.h | 35 ++++++- src/subsystems/odometry.cpp | 192 ++++++++++++++++++++-------------- 2 files changed, 143 insertions(+), 84 deletions(-) diff --git a/include/subsystems/odometry.h b/include/subsystems/odometry.h index 5481146..3c2522d 100644 --- a/include/subsystems/odometry.h +++ b/include/subsystems/odometry.h @@ -29,6 +29,13 @@ typedef struct double wheel_diam; } odometry_config_t; +// Contains information stored between update()s required for calculating posiion +typedef struct +{ + position_t pos; + double lside, rside; +} stored_info_t; + class Odometry { public: @@ -38,16 +45,20 @@ class Odometry * @param left_side The left motors * @param right_side The right motors * @param imu The robot's inertial sensor + * @param is_async If true, the robot will automatically poll it's position and update it in the background. + * If false, the update() function must be called periodically. */ - Odometry(vex::motor_group &left_side, vex::motor_group &right_side, vex::inertial &imu, odometry_config_t &config); + Odometry(vex::motor_group &left_side, vex::motor_group &right_side, vex::inertial &imu, odometry_config_t &config, bool is_async); /** * Initialize the Odometry module, calculating the rotation from encoders * @param left_side The left motors * @param right_side The right motors * @param imu The robot's inertial sensor + * @param is_async If true, the robot will automatically poll it's position and update it in the background. + * If false, the update() function must be called periodically. */ - Odometry(vex::motor_group &left_side, vex::motor_group &right_side, odometry_config_t &config); + Odometry(vex::motor_group &left_side, vex::motor_group &right_side, odometry_config_t &config, bool is_async); /** * Gets the current position and rotation @@ -59,6 +70,15 @@ class Odometry */ void set_position(position_t &newpos); + /** + * Update the current position on the field based on the sensors + */ + position_t update(); + + void end_async(); + + bool end_task = false; + /** * Get the distance between two points */ @@ -71,16 +91,21 @@ class Odometry private: + /** + * Get information from the input hardware and an existing position, and calculate a new current position + */ + static position_t calculate_new_pos(odometry_config_t &config, stored_info_t &stored_info, double lside_revs, double rside_revs, double *gyro_angle_deg=NULL); + vex::mutex mut; position_t current_pos; - vex::motor_group *left_side, *right_side; + vex::motor_group &left_side, &right_side; vex::inertial *imu; - odometry_config_t *config; + odometry_config_t &config; vex::task *handle; - + stored_info_t stored_info; }; diff --git a/src/subsystems/odometry.cpp b/src/subsystems/odometry.cpp index 2a3197b..1b58dcf 100644 --- a/src/subsystems/odometry.cpp +++ b/src/subsystems/odometry.cpp @@ -6,15 +6,15 @@ * @param right_side The right motors * @param imu The robot's inertial sensor */ -Odometry::Odometry(vex::motor_group &left_side, vex::motor_group &right_side, vex::inertial &imu, odometry_config_t &config) -: left_side(&left_side), right_side(&right_side), imu(&imu), config(&config) +Odometry::Odometry(vex::motor_group &left_side, vex::motor_group &right_side, vex::inertial &imu, odometry_config_t &config, bool is_async) +: left_side(left_side), right_side(right_side), imu(&imu), config(config) { - // Create a raw pointer containing a list of all the hardware pointers needed to run the thread. - // This is done because callbacks do not allow class member functions - void* list[] = {this->left_side, this->right_side, this->imu, this->config, &mut, ¤t_pos}; + // Make sure the last known info starts zeroed + memset(&stored_info, 0, sizeof(stored_info_t)); - // Initialize and start the background task - handle = new vex::task(background_task, list); + // Start the asynchronous background thread + if (is_async) + handle = new vex::task(background_task, this); } /** @@ -23,95 +23,70 @@ Odometry::Odometry(vex::motor_group &left_side, vex::motor_group &right_side, ve * @param right_side The right motors * @param imu The robot's inertial sensor */ -Odometry::Odometry(vex::motor_group &left_side, vex::motor_group &right_side, odometry_config_t &config) -: left_side(&left_side), right_side(&right_side), imu(NULL), config(&config) +Odometry::Odometry(vex::motor_group &left_side, vex::motor_group &right_side, odometry_config_t &config, bool is_async) +: left_side(left_side), right_side(right_side), imu(NULL), config(config) { - // Create a raw pointer containing a list of all the hardware pointers needed to run the thread. - // This is done because callbacks do not allow class member functions - void* list[] = {this->left_side, this->right_side, this->imu, this->config, &mut, ¤t_pos}; + // Make sure the last known info starts zeroed + memset(&stored_info, 0, sizeof(stored_info_t)); - // Initialize and start the background task - handle = new vex::task(background_task, list); + // Start the asynchronous background thread + if (is_async) + handle = new vex::task(background_task, this); } /** * The background task constantly polling the motors and updating the position. */ -int background_task(void* obj_ptrs) +int background_task(void* odom_obj) { - // Parse the hardware passed into the function - void** list = (void**) obj_ptrs; - - // Dereference the pointers and store as object references to make it cleaner later - vex::motor_group &left_side = *((vex::motor_group*) list[0]); - vex::motor_group &right_side = *((vex::motor_group*) list[1]); - vex::inertial *imu = (vex::inertial*) list[2]; // (keep as pointer to check for NULL) - odometry_config_t &config = *((odometry_config_t*) list[3]); - vex::mutex &mut = *((vex::mutex*) list[4]); - position_t ¤t_pos = *((position_t*) list[5]); - - double last_lside = 0, last_rside = 0; - - while(true) + Odometry &odom = *((Odometry*) odom_obj); + while(!odom.end_task) { - double angle = 0; - - // If the IMU was passed in, use it for rotational data - if(imu != NULL) - angle = imu->heading(); - else - { - // Get the difference in distance driven between the two sides - double distance_diff = (left_side.position(rotationUnits::rev) - right_side.position(rotationUnits::rev)) * PI * config.wheel_diam; - - //Use the arclength formula to calculate the angle. - angle = (180.0 / PI) * (distance_diff / config.dist_between_wheels); - - //Limit the angle betwen 0 and 360. - //fmod (floating-point modulo) gets it between -359 and +359, so tack on another 360 if it's negative. - angle = fmod(angle, 360.0); - if(angle < 0) - angle += 360; - } - - angle *= PI / 180.0; // Degrees to radians - - // Get the encoder values in revolutions (Make sure the gearsetting is set) - double curr_lside = left_side.position(rotationUnits::rev); - double curr_rside = right_side.position(rotationUnits::rev); - - // Convert the revolutions into "change in distance", and average the values for a "distance driven" - double lside_diff = (curr_lside - last_lside) * config.wheel_diam; - double rside_diff = (curr_rside - last_rside) * config.wheel_diam; - double dist_driven = (lside_diff + rside_diff) / 2.0; + odom.update(); - // Create a vector from the change in distance in the current direction of the robot - Vector chg_vec(angle, dist_driven); - - // Create a vector from the current position in reference to X,Y=0,0 - Vector::point_t curr_point = {.x = current_pos.x, .y = current_pos.y}; - Vector curr_vec(curr_point); - - // Tack on the "difference" vector to the current vector - Vector new_vec = curr_vec + chg_vec; + vexDelay(DOWNTIME); + } - // Store the left and right encoder values to find the difference in the next iteration - last_lside = curr_lside; - last_rside = curr_rside; + return 0; +} - // Avoid race conditions by locking the mutex - mut.lock(); +/** + * End the background task. Cannot be restarted. + * If the user wants to end the thread but keep the data up to date, + * they must run the update() function manually from then on. + */ +void Odometry::end_async() +{ + this->end_task = true; +} - // Get the X and Y coordinates from the vector and save them to the "current position" - current_pos.x = new_vec.get_x(); - current_pos.y = new_vec.get_y(); - current_pos.rot = angle; +/** + * Update, store and return the current position of the robot. Only use if not initializing + * with a separate thread. + */ +position_t Odometry::update() +{ + position_t updated_pos; - mut.unlock(); + double lside_revs = left_side.position(rotationUnits::rev); + double rside_revs = right_side.position(rotationUnits::rev); - vexDelay(DOWNTIME); + if(imu == NULL) + { + updated_pos = calculate_new_pos(config, stored_info, lside_revs, rside_revs); + } else + { + double angle = imu->rotation(rotationUnits::deg); + updated_pos = calculate_new_pos(config, stored_info, lside_revs, rside_revs, &angle); } + + // Update the class' stored position + mut.lock(); + this->current_pos = updated_pos; + mut.unlock(); + + return updated_pos; } /** @@ -121,6 +96,7 @@ position_t Odometry::get_position() { mut.lock(); + // Create a new struct to pass-by-value position_t out = { .x = current_pos.x, @@ -165,3 +141,61 @@ double Odometry::rot_diff(position_t &pos1, position_t &pos2) return pos2.rot - pos1.rot; } +/** + * Using information about the robot's mechanical structure and sensors, calculate a new position + * of the robot, relative to when this method was previously ran. + */ +position_t Odometry::calculate_new_pos(odometry_config_t &config, stored_info_t &stored_info, double lside_revs, double rside_revs, double *gyro_angle_deg) +{ + position_t new_pos; + + double angle = 0; + + // If the IMU data was passed in, use it for rotational data + if(gyro_angle_deg != NULL) + angle = *gyro_angle_deg; + else + { + // Get the difference in distance driven between the two sides + // Uses the absolute position of the encoders, so resetting them will result in + // a bad angle. + double distance_diff = (lside_revs - rside_revs) * PI * config.wheel_diam; + + //Use the arclength formula to calculate the angle. + angle = (180.0 / PI) * (distance_diff / config.dist_between_wheels); + + //Limit the angle betwen 0 and 360. + //fmod (floating-point modulo) gets it between -359 and +359, so tack on another 360 if it's negative. + angle = fmod(angle, 360.0); + if(angle < 0) + angle += 360; + } + + angle *= PI / 180.0; // Degrees to radians + + // Convert the revolutions into "change in distance", and average the values for a "distance driven" + double lside_diff = (lside_revs - stored_info.lside) * PI * config.wheel_diam; + double rside_diff = (rside_revs - stored_info.rside) * PI * config.wheel_diam; + double dist_driven = (lside_diff + rside_diff) / 2.0; + + // Create a vector from the change in distance in the current direction of the robot + Vector chg_vec(angle, dist_driven); + + // Create a vector from the current position in reference to X,Y=0,0 + Vector::point_t curr_point = {.x = stored_info.pos.x, .y = stored_info.pos.y}; + Vector curr_vec(curr_point); + + // Tack on the "difference" vector to the current vector + Vector new_vec = curr_vec + chg_vec; + + new_pos.x = new_vec.get_x(); + new_pos.y = new_vec.get_y(); + new_pos.rot = angle * (180.0 / PI); + + // Store the left and right encoder values to find the difference in the next iteration + stored_info.lside = lside_revs; + stored_info.rside = rside_revs; + stored_info.pos = new_pos; + + return new_pos; +} \ No newline at end of file From 5c83d13dbbd7539b266ea6a597544e3d16c70719 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Wed, 11 Aug 2021 22:42:35 -0400 Subject: [PATCH 025/243] Restructured odometry to an object model --- include/subsystems/odometry/odometry_base.h | 66 +++++++++++++++++++ .../{odometry.h => odometry/odometry_tank.h} | 53 +++------------ include/subsystems/tank_drive.h | 2 + src/subsystems/odometry/odometry_base.cpp | 62 +++++++++++++++++ .../odometry_tank.cpp} | 64 +----------------- 5 files changed, 141 insertions(+), 106 deletions(-) create mode 100644 include/subsystems/odometry/odometry_base.h rename include/subsystems/{odometry.h => odometry/odometry_tank.h} (73%) create mode 100644 src/subsystems/odometry/odometry_base.cpp rename src/subsystems/{odometry.cpp => odometry/odometry_tank.cpp} (79%) diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h new file mode 100644 index 0000000..9081107 --- /dev/null +++ b/include/subsystems/odometry/odometry_base.h @@ -0,0 +1,66 @@ +#ifndef _ODOMETRY_ +#define _ODOMETRY_ + +#include "vex.h" + +#ifndef PI +#define PI 3.141592654 +#endif + +#define DOWNTIME 50 //milliseconds + +// Describes a single position and rotation +typedef struct +{ + double x; + double y; + double rot; +} position_t; + +/** + * Base odometry class to simplify implementations of multiple drivetrains. + */ +class OdometryBase +{ +public: + /** + * Gets the current position and rotation + */ + position_t get_position(void); + + /** + * Sets the current position of the robot + */ + void set_position(position_t &newpos); + + /** + * Update the current position on the field based on the sensors + */ + virtual position_t update() = 0; + + /** + * End the background task. Cannot be restarted. + * If the user wants to end the thread but keep the data up to date, + * they must run the update() function manually from then on. + */ + void end_async(); + + /** + * Get the distance between two points + */ + static double pos_diff(position_t &pos1, position_t &pos2); + + /** + * Get the change in rotation between two points + */ + static double rot_diff(position_t &pos1, position_t &pos2); + + bool end_task = false; + +protected: + vex::task *handle; + vex::mutex mut; + position_t current_pos; +}; + +#endif \ No newline at end of file diff --git a/include/subsystems/odometry.h b/include/subsystems/odometry/odometry_tank.h similarity index 73% rename from include/subsystems/odometry.h rename to include/subsystems/odometry/odometry_tank.h index 3c2522d..49496e5 100644 --- a/include/subsystems/odometry.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -1,27 +1,13 @@ -#ifndef _ODOMETRY_ -#define _ODOMETRY_ +#ifndef _ODOMETRY_TANK_ +#define _ODOMETRY_TANK_ -#include "vex.h" +#include "../core/include/subsystems/odometry/odometry_base.h" #include "../core/include/utils/vector.h" -#define DOWNTIME 50 //milliseconds - -#ifndef PI -#define PI 3.141592654 -#endif - /** * The background task constantly polling the motors and updating the position. */ -static int background_task(void* pos_ptr); - -// Describes a single position and rotation -typedef struct -{ - double x; - double y; - double rot; -} position_t; +static int background_task(void *pos_ptr); typedef struct { @@ -36,14 +22,14 @@ typedef struct double lside, rside; } stored_info_t; -class Odometry +class Odometry : public OdometryBase { - public: - +public: /** * Initialize the Odometry module, using the IMU to get rotation * @param left_side The left motors - * @param right_side The right motors + * @param right_ + * side The right motors * @param imu The robot's inertial sensor * @param is_async If true, the robot will automatically poll it's position and update it in the background. * If false, the update() function must be called periodically. @@ -77,36 +63,17 @@ class Odometry void end_async(); - bool end_task = false; - - /** - * Get the distance between two points - */ - static double pos_diff(position_t &pos1, position_t &pos2); - - /** - * Get the change in rotation between two points - */ - static double rot_diff(position_t &pos1, position_t &pos2); - - private: - +private: /** * Get information from the input hardware and an existing position, and calculate a new current position */ - static position_t calculate_new_pos(odometry_config_t &config, stored_info_t &stored_info, double lside_revs, double rside_revs, double *gyro_angle_deg=NULL); - - vex::mutex mut; - position_t current_pos; + static position_t calculate_new_pos(odometry_config_t &config, stored_info_t &stored_info, double lside_revs, double rside_revs, double *gyro_angle_deg = NULL); vex::motor_group &left_side, &right_side; vex::inertial *imu; odometry_config_t &config; - vex::task *handle; - stored_info_t stored_info; - }; #endif \ No newline at end of file diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 28de064..f442428 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -1,7 +1,9 @@ #ifndef _TANKDRIVE_ #define _TANKDRIVE_ +#ifndef PI #define PI 3.141592654 +#endif #include "vex.h" #include "../core/include/utils/pid.h" diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp new file mode 100644 index 0000000..b4846ad --- /dev/null +++ b/src/subsystems/odometry/odometry_base.cpp @@ -0,0 +1,62 @@ +#include "../core/include/subsystems/odometry/odometry_base.h" + +/** +* Gets the current position and rotation +*/ +position_t OdometryBase::get_position(void) +{ + mut.lock(); + + // Create a new struct to pass-by-value + position_t out = + { + .x = current_pos.x, + .y = current_pos.y, + .rot = current_pos.rot + }; + + mut.unlock(); + + return out; +} + +/** + * Sets the current position of the robot + */ +void OdometryBase::set_position(position_t &newpos) +{ + mut.lock(); + + current_pos.x = newpos.x; + current_pos.y = newpos.y; + current_pos.rot = newpos.rot; + + mut.unlock(); +} + +/** + * End the background task. Cannot be restarted. + * If the user wants to end the thread but keep the data up to date, + * they must run the update() function manually from then on. + */ +void OdometryBase::end_async() +{ + this->end_task = true; +} + +/** + * Get the distance between two points + */ +double OdometryBase::pos_diff(position_t &pos1, position_t &pos2) +{ + // Use the pythagorean theorem + return sqrt(pow(pos2.x - pos1.x, 2) + pow(pos2.y - pos1.y, 2)); +} + +/** + * Get the change in rotation between two points + */ +double OdometryBase::rot_diff(position_t &pos1, position_t &pos2) +{ + return pos2.rot - pos1.rot; +} \ No newline at end of file diff --git a/src/subsystems/odometry.cpp b/src/subsystems/odometry/odometry_tank.cpp similarity index 79% rename from src/subsystems/odometry.cpp rename to src/subsystems/odometry/odometry_tank.cpp index 1b58dcf..3de6224 100644 --- a/src/subsystems/odometry.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -1,4 +1,4 @@ -#include "../core/include/subsystems/odometry.h" +#include "../core/include/subsystems/odometry/odometry_tank.h" /** * Initialize the Odometry module, using the IMU to get rotation @@ -51,16 +51,6 @@ int background_task(void* odom_obj) return 0; } -/** - * End the background task. Cannot be restarted. - * If the user wants to end the thread but keep the data up to date, - * they must run the update() function manually from then on. - */ -void Odometry::end_async() -{ - this->end_task = true; -} - /** * Update, store and return the current position of the robot. Only use if not initializing * with a separate thread. @@ -89,58 +79,6 @@ position_t Odometry::update() return updated_pos; } -/** - * Gets the current position and rotation - */ -position_t Odometry::get_position() -{ - mut.lock(); - - // Create a new struct to pass-by-value - position_t out = - { - .x = current_pos.x, - .y = current_pos.y, - .rot = current_pos.rot - }; - - mut.unlock(); - - return out; -} - -/** - * Sets the current position of the robot - */ -void Odometry::set_position(position_t &newpos) -{ - mut.lock(); - - current_pos.x = newpos.x; - current_pos.y = newpos.y; - current_pos.rot = newpos.rot; - - mut.unlock(); -} - -/** - * Get the distance between two points - */ -double Odometry::pos_diff(position_t &pos1, position_t &pos2) -{ - // Use the pythagorean theorem - return sqrt(pow(pos2.x - pos1.x, 2) + pow(pos2.y - pos1.y, 2)); - -} - -/** - * Get the change in rotation between two points - */ -double Odometry::rot_diff(position_t &pos1, position_t &pos2) -{ - return pos2.rot - pos1.rot; -} - /** * Using information about the robot's mechanical structure and sensors, calculate a new position * of the robot, relative to when this method was previously ran. From 55cf4fb312f19dcfa2c7f253022d958935b9080a Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 15 Aug 2021 20:42:31 -0400 Subject: [PATCH 026/243] Added Swerve Drive odometry --- include/subsystems/odometry/odometry_swerve.h | 52 +++++++++++ include/subsystems/odometry/odometry_tank.h | 18 +--- include/subsystems/swerve_drive.h | 10 +++ include/subsystems/swerve_module.h | 16 ++-- src/subsystems/odometry/odometry_swerve.cpp | 89 +++++++++++++++++++ src/subsystems/odometry/odometry_tank.cpp | 10 +-- src/subsystems/swerve_drive.cpp | 20 +++++ src/subsystems/swerve_module.cpp | 13 ++- 8 files changed, 201 insertions(+), 27 deletions(-) create mode 100644 include/subsystems/odometry/odometry_swerve.h create mode 100644 src/subsystems/odometry/odometry_swerve.cpp diff --git a/include/subsystems/odometry/odometry_swerve.h b/include/subsystems/odometry/odometry_swerve.h new file mode 100644 index 0000000..1cc3f62 --- /dev/null +++ b/include/subsystems/odometry/odometry_swerve.h @@ -0,0 +1,52 @@ +#ifndef _ODOMETRY_SWERVE_ +#define _ODOMETRY_SWERVE_ + +#include "vex.h" +#include "../core/include/subsystems/odometry/odometry_base.h" +#include "../core/include/subsystems/swerve_drive.h" + +/** + * Function containing the code running in the background, if this odometry is running + * asynchronously. + */ +static int background_task(void *obj); + +typedef struct +{ + double lf_dist, rf_dist, lr_dist, rr_dist; +} stored_info_t; + +/** + * Odometry controller for a 4x module swerve drivetrain. Can either run in the background or + * called manually via the update() function. + */ +class OdometrySwerve : public OdometryBase +{ +public: + + /** + * Create the odometry object, decide whether to keep it in the background or foreground. + */ + OdometrySwerve(SwerveDrive &drive_system, vex::inertial &imu, bool is_async=true); + + /** + * Manually update the position of the robot. Must be called many times each second for an accurate position. + * Returns the new posiiton. + */ + position_t update(); + +private: + + /** + * Run the calculations required to find a new position based on a stored old position, stored information + * on each swerve module, and information from the sensors stored in the drive_system / imu + */ + static position_t calculate_new_pos(stored_info_t &stored_info, position_t &cur_pos, SwerveDrive &drive_system, vex::inertial &imu); + + SwerveDrive &drive_system; + vex::inertial &imu; + + stored_info_t stored_info; +}; + +#endif \ No newline at end of file diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index 49496e5..4318151 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -22,7 +22,7 @@ typedef struct double lside, rside; } stored_info_t; -class Odometry : public OdometryBase +class OdometryTank : public OdometryBase { public: /** @@ -34,7 +34,7 @@ class Odometry : public OdometryBase * @param is_async If true, the robot will automatically poll it's position and update it in the background. * If false, the update() function must be called periodically. */ - Odometry(vex::motor_group &left_side, vex::motor_group &right_side, vex::inertial &imu, odometry_config_t &config, bool is_async); + OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, vex::inertial &imu, odometry_config_t &config, bool is_async); /** * Initialize the Odometry module, calculating the rotation from encoders @@ -44,25 +44,13 @@ class Odometry : public OdometryBase * @param is_async If true, the robot will automatically poll it's position and update it in the background. * If false, the update() function must be called periodically. */ - Odometry(vex::motor_group &left_side, vex::motor_group &right_side, odometry_config_t &config, bool is_async); - - /** - * Gets the current position and rotation - */ - position_t get_position(); - - /** - * Sets the current position of the robot - */ - void set_position(position_t &newpos); + OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, odometry_config_t &config, bool is_async); /** * Update the current position on the field based on the sensors */ position_t update(); - void end_async(); - private: /** * Get information from the input hardware and an existing position, and calculate a new current position diff --git a/include/subsystems/swerve_drive.h b/include/subsystems/swerve_drive.h index 286c385..e301855 100644 --- a/include/subsystems/swerve_drive.h +++ b/include/subsystems/swerve_drive.h @@ -8,6 +8,11 @@ #define ROT_DEADBAND 0.2 #define LAT_DEADBAND 0.2 +enum ModulePosition +{ + LEFT_FRONT, RIGHT_FRONT, LEFT_REAR, RIGHT_REAR +}; + class SwerveDrive { @@ -45,6 +50,11 @@ bool auto_turn(double degrees, double speed); void set_drive_pid(PID::pid_config_t &config); void set_turn_pid(PID::pid_config_t &config); +/** + * Return the corresponding module to this swerve drive system + */ +SwerveModule& get_module(ModulePosition pos); + private: SwerveModule &left_front, &left_rear, &right_front, &right_rear; diff --git a/include/subsystems/swerve_module.h b/include/subsystems/swerve_module.h index e93d077..3ffd88a 100644 --- a/include/subsystems/swerve_module.h +++ b/include/subsystems/swerve_module.h @@ -26,7 +26,7 @@ class SwerveModule * * the Drive motor is the central one, with the Direction motor being offset. */ - SwerveModule(vex::motor &drive, vex::gearSetting drive_gearing, vex::motor &direction, vex::gearSetting dir_gearing); + SwerveModule(vex::motor &drive, vex::motor &direction); /** * Sets both the speed and direction of the module, taking into account how the motors are geared @@ -57,14 +57,23 @@ class SwerveModule /** * Reset the drive encoder to zero + * + * @deprecated Resetting encoders will screw up OdometrySwerve; do not use with odometry. */ void reset_distance_driven(); /** * Get 'distance' from the drive motor + * + * TODO take into account the effect of the direction motor on the driven distance */ double get_distance_driven(); + /** + * Return the direction that the module is pointing + */ + double get_module_angle(); + bool auto_reverse = false; private: @@ -84,11 +93,8 @@ class SwerveModule */ static int mod(int var1, int var2); - vex::motor &drive; - vex::gearSetting drive_gearing; + vex::motor &drive, &direction; - vex::motor &direction; - vex::gearSetting dir_gearing; bool inverseDrive; double lastStoredHeading; double driveMulitplier; diff --git a/src/subsystems/odometry/odometry_swerve.cpp b/src/subsystems/odometry/odometry_swerve.cpp new file mode 100644 index 0000000..4895c29 --- /dev/null +++ b/src/subsystems/odometry/odometry_swerve.cpp @@ -0,0 +1,89 @@ +#include "../core/include/subsystems/odometry/odometry_swerve.h" +#include "../core/include/utils/vector.h" + +OdometrySwerve::OdometrySwerve(SwerveDrive &drive_system, vex::inertial &imu, bool is_async=true) +: drive_system(drive_system), imu(imu) +{ + memset(&stored_info, 0, sizeof(stored_info_t)); + + if(is_async) + handle = new vex::task(background_task, this); +} + +/** + * Manually update the position of the robot. Must be called many times each second for an accurate position. + * Returns the new posiiton. + */ +position_t OdometrySwerve::update() +{ + position_t new_pos = calculate_new_pos(stored_info,current_pos, drive_system, imu); + + mut.lock(); + this->current_pos = new_pos; + mut.unlock(); + + return current_pos; +} + +/** + * Function containing the code running in the background, if this odometry is running + * asynchronously. + */ +int background_task(void *obj) +{ + OdometrySwerve &odom = *((OdometrySwerve*)obj); + + while(!odom.end_task) + { + odom.update(); + vexDelay(DOWNTIME); + } + + return 0; +} + +/** + * Run the calculations required to find a new position based on a stored old position, stored information + * on each swerve module, and information from the sensors stored in the drive_system / imu + */ +position_t OdometrySwerve::calculate_new_pos(stored_info_t &stored_info, position_t &cur_pos, SwerveDrive &drive_system, vex::inertial &imu) +{ + // Get the change in distance for each drive motor + double lf_delta = drive_system.get_module(LEFT_FRONT).get_distance_driven() - stored_info.lf_dist; + double rf_delta = drive_system.get_module(RIGHT_FRONT).get_distance_driven() - stored_info.rf_dist; + double lr_delta = drive_system.get_module(LEFT_REAR).get_distance_driven() - stored_info.lr_dist; + double rr_delta = drive_system.get_module(RIGHT_REAR).get_distance_driven() - stored_info.rr_dist; + + // Store the vector displacement + Vector lf_disp(drive_system.get_module(LEFT_FRONT).get_module_angle(), lf_delta); + Vector rf_disp(drive_system.get_module(RIGHT_FRONT).get_module_angle(), rf_delta); + Vector lr_disp(drive_system.get_module(LEFT_REAR).get_module_angle(), lr_delta); + Vector rr_disp(drive_system.get_module(RIGHT_REAR).get_module_angle(), rr_delta); + + // Get an overall displacement of the robot + // Adding the vectors cancels out rotation, and leaves the robots actual displacement + Vector delta_displacement = lf_disp + rf_disp + lr_disp + rr_disp; + + // Create a vector from the robot's current position, + // representing the displacement from the origin + Vector::point_t pt = {.x = cur_pos.x, .y = cur_pos.y}; + Vector old_displacement(pt); + + // Add the "change in displacement" to the existing displacement (from 0,0) + Vector new_displacement = old_displacement + delta_displacement; + + position_t out = + { + .x = new_displacement.get_x(), + .y = new_displacement.get_y(), + .rot = imu.heading() + }; + + // Store each module's previous distance driven for the next update + stored_info.lf_dist = drive_system.get_module(LEFT_FRONT).get_distance_driven(); + stored_info.rf_dist = drive_system.get_module(RIGHT_FRONT).get_distance_driven(); + stored_info.lr_dist = drive_system.get_module(LEFT_REAR).get_distance_driven(); + stored_info.rr_dist = drive_system.get_module(RIGHT_REAR).get_distance_driven(); + + return out; +} \ No newline at end of file diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 3de6224..65de254 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -6,7 +6,7 @@ * @param right_side The right motors * @param imu The robot's inertial sensor */ -Odometry::Odometry(vex::motor_group &left_side, vex::motor_group &right_side, vex::inertial &imu, odometry_config_t &config, bool is_async) +OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, vex::inertial &imu, odometry_config_t &config, bool is_async) : left_side(left_side), right_side(right_side), imu(&imu), config(config) { // Make sure the last known info starts zeroed @@ -23,7 +23,7 @@ Odometry::Odometry(vex::motor_group &left_side, vex::motor_group &right_side, ve * @param right_side The right motors * @param imu The robot's inertial sensor */ -Odometry::Odometry(vex::motor_group &left_side, vex::motor_group &right_side, odometry_config_t &config, bool is_async) +OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, odometry_config_t &config, bool is_async) : left_side(left_side), right_side(right_side), imu(NULL), config(config) { // Make sure the last known info starts zeroed @@ -40,7 +40,7 @@ Odometry::Odometry(vex::motor_group &left_side, vex::motor_group &right_side, od */ int background_task(void* odom_obj) { - Odometry &odom = *((Odometry*) odom_obj); + OdometryTank &odom = *((OdometryTank*) odom_obj); while(!odom.end_task) { odom.update(); @@ -55,7 +55,7 @@ int background_task(void* odom_obj) * Update, store and return the current position of the robot. Only use if not initializing * with a separate thread. */ -position_t Odometry::update() +position_t OdometryTank::update() { position_t updated_pos; @@ -83,7 +83,7 @@ position_t Odometry::update() * Using information about the robot's mechanical structure and sensors, calculate a new position * of the robot, relative to when this method was previously ran. */ -position_t Odometry::calculate_new_pos(odometry_config_t &config, stored_info_t &stored_info, double lside_revs, double rside_revs, double *gyro_angle_deg) +position_t OdometryTank::calculate_new_pos(odometry_config_t &config, stored_info_t &stored_info, double lside_revs, double rside_revs, double *gyro_angle_deg) { position_t new_pos; diff --git a/src/subsystems/swerve_drive.cpp b/src/subsystems/swerve_drive.cpp index c916e8c..9722440 100644 --- a/src/subsystems/swerve_drive.cpp +++ b/src/subsystems/swerve_drive.cpp @@ -213,4 +213,24 @@ bool SwerveDrive::auto_turn(double degrees, double speed) } return false; +} + +/** + * Return the corresponding module to this swerve drive system + */ +SwerveModule& SwerveDrive::get_module(ModulePosition pos) +{ + switch(pos) + { + case LEFT_FRONT: + return left_front; + case RIGHT_FRONT: + return right_front; + case LEFT_REAR: + return left_rear; + + default: // ONLY if something goes horribly wrong, return the right rear + case RIGHT_REAR: + return right_rear; + } } \ No newline at end of file diff --git a/src/subsystems/swerve_module.cpp b/src/subsystems/swerve_module.cpp index 570c6d4..a1e2711 100644 --- a/src/subsystems/swerve_module.cpp +++ b/src/subsystems/swerve_module.cpp @@ -6,8 +6,8 @@ * * the Drive motor is the central one, with the Direction motor being offset. */ -SwerveModule::SwerveModule(vex::motor &drive, vex::gearSetting drive_gearing, vex::motor &direction, vex::gearSetting dir_gearing) - : drive(drive), drive_gearing(drive_gearing), direction(direction), dir_gearing(dir_gearing) +SwerveModule::SwerveModule(vex::motor &drive, vex::motor &direction) + : drive(drive), direction(direction) { lastStoredHeading = 0.0; inverseDrive = false; @@ -104,6 +104,15 @@ double SwerveModule::get_distance_driven() return fabs(WHEEL_DIAM * PI * drive.position(vex::rotationUnits::rev) * DRIVE_GEAR_RATIO); } +/** + * Return the direction that the module is pointing + */ +double SwerveModule::get_module_angle() +{ + // Limit to 0->360 + return fmod(direction.rotation(vex::rotationUnits::deg) * DIR_GEAR_RATIO, 360); +} + /** * Grab the maximum degrees per second of a motor with a certain gearset * 36 : 1 = reds From a0ffb43ad55bf0627d32fb3cd9ebf80252c7902f Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 15 Aug 2021 21:34:25 -0400 Subject: [PATCH 027/243] Fixed tank_drive to use the odometry class --- include/subsystems/odometry/odometry_base.h | 2 +- include/subsystems/odometry/odometry_swerve.h | 6 ----- include/subsystems/odometry/odometry_tank.h | 5 ---- include/subsystems/tank_drive.h | 8 ++++--- include/utils/vector.h | 2 ++ src/subsystems/odometry/odometry_base.cpp | 23 ++++++++++++++++-- src/subsystems/tank_drive.cpp | 24 +++++++++++++++---- 7 files changed, 48 insertions(+), 22 deletions(-) diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index 9081107..59d263c 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -48,7 +48,7 @@ class OdometryBase /** * Get the distance between two points */ - static double pos_diff(position_t &pos1, position_t &pos2); + static double pos_diff(position_t pos1, position_t pos2, bool use_negatives=false); /** * Get the change in rotation between two points diff --git a/include/subsystems/odometry/odometry_swerve.h b/include/subsystems/odometry/odometry_swerve.h index 1cc3f62..a38a947 100644 --- a/include/subsystems/odometry/odometry_swerve.h +++ b/include/subsystems/odometry/odometry_swerve.h @@ -5,12 +5,6 @@ #include "../core/include/subsystems/odometry/odometry_base.h" #include "../core/include/subsystems/swerve_drive.h" -/** - * Function containing the code running in the background, if this odometry is running - * asynchronously. - */ -static int background_task(void *obj); - typedef struct { double lf_dist, rf_dist, lr_dist, rr_dist; diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index 4318151..4b215ef 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -4,11 +4,6 @@ #include "../core/include/subsystems/odometry/odometry_base.h" #include "../core/include/utils/vector.h" -/** - * The background task constantly polling the motors and updating the position. - */ -static int background_task(void *pos_ptr); - typedef struct { double dist_between_wheels; diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index f442428..6922c96 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -7,6 +7,7 @@ #include "vex.h" #include "../core/include/utils/pid.h" +#include "../core/include/subsystems/odometry/odometry_tank.h" using namespace vex; @@ -19,6 +20,7 @@ class TankDrive PID::pid_config_t drive_pid; PID::pid_config_t turn_pid; + double dist_between_wheels; double wheel_diam; }; @@ -65,15 +67,15 @@ class TankDrive bool turn_degrees(double degrees, double percent_speed); private: - tankdrive_config_t &config; - motor_group &left_motors; motor_group &right_motors; PID drive_pid; PID turn_pid; - inertial &gyro_sensor; + OdometryTank *odometry; + + position_t saved_pos; bool initialize_func = true; }; diff --git a/include/utils/vector.h b/include/utils/vector.h index b45227e..45ec32c 100644 --- a/include/utils/vector.h +++ b/include/utils/vector.h @@ -3,7 +3,9 @@ #include +#ifndef PI #define PI 3.141592654 +#endif class Vector { diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index b4846ad..c5ab0a9 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -1,4 +1,5 @@ #include "../core/include/subsystems/odometry/odometry_base.h" +#include "../core/include/utils/vector.h" /** * Gets the current position and rotation @@ -47,10 +48,28 @@ void OdometryBase::end_async() /** * Get the distance between two points */ -double OdometryBase::pos_diff(position_t &pos1, position_t &pos2) +double OdometryBase::pos_diff(position_t pos1, position_t pos2, bool use_negatives) { + int negative_multiplier = 1; + + // If we are using negative distances, define a "negative distance" as when the angle + // of a vector made from those two points is between 3PI/4 and 7PI/4 + if(use_negatives) + { + Vector::point_t point_diff = { + .x = pos1.x - pos2.x, + .y = pos1.y - pos2.y + }; + + Vector v_diff(point_diff); + double angle = rad2deg(v_diff.get_dir()); + + if(angle > 135 && angle < 315) + negative_multiplier = -1; + } + // Use the pythagorean theorem - return sqrt(pow(pos2.x - pos1.x, 2) + pow(pos2.y - pos1.y, 2)); + return negative_multiplier * sqrt(pow(pos1.x - pos2.x, 2) + pow(pos1.y - pos2.y, 2)); } /** diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 12e5805..9604916 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -1,8 +1,16 @@ #include "../core/include/subsystems/tank_drive.h" TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, inertial &gyro_sensor, TankDrive::tankdrive_config_t &config) - : config(config), left_motors(left_motors), right_motors(right_motors), drive_pid(config.drive_pid), turn_pid(config.turn_pid), gyro_sensor(gyro_sensor) + : left_motors(left_motors), right_motors(right_motors), + drive_pid(config.drive_pid), turn_pid(config.turn_pid) { + + odometry_config_t cfg = { + .dist_between_wheels = config.dist_between_wheels, + .wheel_diam = config.wheel_diam, + }; + + this->odometry = new OdometryTank(left_motors, right_motors, cfg, true); } /** @@ -46,13 +54,15 @@ void TankDrive::drive_arcade(double forward_back, double left_right) * of percent_speed (-1.0 -> 1.0). * * Uses a PID loop for it's control. + * + * NOTE: uses relative positioning, so after a few drive_forward's, position may be lost! */ bool TankDrive::drive_forward(double inches, double percent_speed) { // On the first run of the funciton, reset the motor position and PID if (initialize_func) { - left_motors.resetPosition(); + saved_pos = odometry->get_position(); drive_pid.reset(); drive_pid.set_limits(-fabs(percent_speed), fabs(percent_speed)); @@ -61,8 +71,12 @@ bool TankDrive::drive_forward(double inches, double percent_speed) initialize_func = false; } + double position_diff = OdometryBase::pos_diff(odometry->get_position(), saved_pos, true); + // Update PID loop and drive the robot based on it's output - drive_pid.update(left_motors.position(rotationUnits::rev) * PI * config.wheel_diam); + drive_pid.update(position_diff); + + // Drive backwards if we input negative inches, forward for positive drive_tank(drive_pid.get(), drive_pid.get()); // If the robot is at it's target, return true @@ -87,7 +101,7 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) // On the first run of the funciton, reset the gyro position and PID if (initialize_func) { - gyro_sensor.resetRotation(); + saved_pos = odometry->get_position(); turn_pid.reset(); turn_pid.set_limits(-fabs(percent_speed), fabs(percent_speed)); @@ -97,7 +111,7 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) } // Update PID loop and drive the robot based on it's output - turn_pid.update(gyro_sensor.rotation(rotationUnits::deg)); + turn_pid.update(odometry->get_position().rot - saved_pos.rot); drive_tank(turn_pid.get(), -turn_pid.get()); // If the robot is at it's target, return true From 9712bc0a268cf9cb5b3f70954ba954586b21fa4b Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Mon, 23 Aug 2021 23:20:12 -0400 Subject: [PATCH 028/243] Changed SwerveDrive to use odometry --- include/subsystems/swerve_drive.h | 4 ++++ src/subsystems/swerve_drive.cpp | 29 ++++++++++++----------------- 2 files changed, 16 insertions(+), 17 deletions(-) diff --git a/include/subsystems/swerve_drive.h b/include/subsystems/swerve_drive.h index e301855..5578465 100644 --- a/include/subsystems/swerve_drive.h +++ b/include/subsystems/swerve_drive.h @@ -2,6 +2,7 @@ #define _SWERVEDRIVE_ #include "../core/include/subsystems/swerve_module.h" +#include "../core/include/subsystems/odometry/odometry_swerve.h" #include "../core/include/utils/vector.h" #include "../core/include/utils/pid.h" @@ -64,6 +65,9 @@ bool auto_turn_init = true; PID *drive_pid, *turn_pid; vex::inertial &imu; +OdometrySwerve *odometry; +position_t saved_pos; + }; #endif \ No newline at end of file diff --git a/src/subsystems/swerve_drive.cpp b/src/subsystems/swerve_drive.cpp index 9722440..4c8ca42 100644 --- a/src/subsystems/swerve_drive.cpp +++ b/src/subsystems/swerve_drive.cpp @@ -9,7 +9,7 @@ using namespace std; SwerveDrive::SwerveDrive(SwerveModule &left_front, SwerveModule &left_rear, SwerveModule &right_front, SwerveModule &right_rear, vex::inertial &imu) :left_front(left_front), left_rear(left_rear), right_front(right_front), right_rear(right_rear), imu(imu) { - + // odometry = new OdometrySwerve(*this, imu, true); } /** @@ -90,6 +90,8 @@ void SwerveDrive::set_turn_pid(PID::pid_config_t &config) /** * Autonomously drive the robot in (degrees) direction, at (-1.0 -> 1.0) speed, for (inches) distance. * Indicate a negative speed or distance, or (preferably) a direction of +-180 degrees for backwards. + * + * NOTE: This function uses relative positioning, and a few calls to it may cause it to drift! */ bool SwerveDrive::auto_drive(double direction, double speed, double distance) { @@ -122,10 +124,7 @@ bool SwerveDrive::auto_drive(double direction, double speed, double distance) if(!all_wheels_done) return false; - left_front.reset_distance_driven(); - right_front.reset_distance_driven(); - left_rear.reset_distance_driven(); - right_rear.reset_distance_driven(); + saved_pos = odometry->get_position(); // set up the PID drive_pid->reset(); @@ -135,13 +134,10 @@ bool SwerveDrive::auto_drive(double direction, double speed, double distance) auto_drive_init = false; } - double average = (left_front.get_distance_driven() + right_front.get_distance_driven() - + left_rear.get_distance_driven() + right_rear.get_distance_driven()) / 4.0; + double pos_diff = OdometryBase::pos_diff(odometry->get_position(), saved_pos, true); // LOOP - drive_pid->update(average); - - fprintf(stderr, "Distance Driven: %f\n", average); + drive_pid->update(pos_diff); left_front.set_speed(drive_pid->get()); right_front.set_speed(drive_pid->get()); @@ -162,6 +158,8 @@ bool SwerveDrive::auto_drive(double direction, double speed, double distance) /** * Autonomously turn the robot over it's center axis in degrees. Positive degrees is clockwise, Negative is counter-clockwise * Function is non-blocking, and returns true when it has finished turning. + * + * NOTE: this uses relative positioning, and a few calls may cause it to lose it's desired angle! */ bool SwerveDrive::auto_turn(double degrees, double speed) { @@ -183,9 +181,8 @@ bool SwerveDrive::auto_turn(double degrees, double speed) if(!all_wheels_done) return false; - // Reset the IMU rotation and configure the PID loop - imu.resetRotation(); - + saved_pos = odometry->get_position(); + turn_pid->reset(); turn_pid->set_limits(-fabs(speed), fabs(speed)); turn_pid->set_target(degrees); @@ -195,15 +192,13 @@ bool SwerveDrive::auto_turn(double degrees, double speed) // LOOP - turn_pid->update(imu.rotation()); + turn_pid->update(odometry->get_position().rot); + left_front.set_speed(turn_pid->get()); right_front.set_speed(turn_pid->get()); left_rear.set_speed(turn_pid->get()); right_rear.set_speed(turn_pid->get()); - fprintf(stderr, "Angle: %f ", imu.rotation()); - fprintf(stderr, "Out: %f \n", turn_pid->get()); - // when the robot is on target, we are done. return true. if(turn_pid->is_on_target()) { From b7251f5e834bcfff9e33d18238bb5010fe2226b6 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Mon, 13 Sep 2021 23:05:57 -0400 Subject: [PATCH 029/243] Finished testing OdometryTank without imu --- include/subsystems/odometry/odometry_swerve.h | 9 +++++---- include/subsystems/odometry/odometry_tank.h | 7 +++++-- include/subsystems/swerve_drive.h | 7 +++---- include/subsystems/swerve_module.h | 1 + include/subsystems/tank_drive.h | 7 ++----- src/subsystems/odometry/odometry_swerve.cpp | 2 +- src/subsystems/odometry/odometry_tank.cpp | 6 +++--- src/subsystems/tank_drive.cpp | 19 ++++++++----------- 8 files changed, 28 insertions(+), 30 deletions(-) diff --git a/include/subsystems/odometry/odometry_swerve.h b/include/subsystems/odometry/odometry_swerve.h index a38a947..fe73180 100644 --- a/include/subsystems/odometry/odometry_swerve.h +++ b/include/subsystems/odometry/odometry_swerve.h @@ -1,15 +1,18 @@ -#ifndef _ODOMETRY_SWERVE_ -#define _ODOMETRY_SWERVE_ +#pragma once #include "vex.h" #include "../core/include/subsystems/odometry/odometry_base.h" #include "../core/include/subsystems/swerve_drive.h" +class SwerveDrive; + typedef struct { double lf_dist, rf_dist, lr_dist, rr_dist; } stored_info_t; +static int background_task(void *obj); + /** * Odometry controller for a 4x module swerve drivetrain. Can either run in the background or * called manually via the update() function. @@ -42,5 +45,3 @@ class OdometrySwerve : public OdometryBase stored_info_t stored_info; }; - -#endif \ No newline at end of file diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index 4b215ef..62a25c8 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -8,8 +8,11 @@ typedef struct { double dist_between_wheels; double wheel_diam; + double gear_ratio; } odometry_config_t; +static int background_task(void* odom_obj); + // Contains information stored between update()s required for calculating posiion typedef struct { @@ -29,7 +32,7 @@ class OdometryTank : public OdometryBase * @param is_async If true, the robot will automatically poll it's position and update it in the background. * If false, the update() function must be called periodically. */ - OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, vex::inertial &imu, odometry_config_t &config, bool is_async); + OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, vex::inertial &imu, odometry_config_t &config, bool is_async=true); /** * Initialize the Odometry module, calculating the rotation from encoders @@ -39,7 +42,7 @@ class OdometryTank : public OdometryBase * @param is_async If true, the robot will automatically poll it's position and update it in the background. * If false, the update() function must be called periodically. */ - OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, odometry_config_t &config, bool is_async); + OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, odometry_config_t &config, bool is_async=true); /** * Update the current position on the field based on the sensors diff --git a/include/subsystems/swerve_drive.h b/include/subsystems/swerve_drive.h index 5578465..c967cea 100644 --- a/include/subsystems/swerve_drive.h +++ b/include/subsystems/swerve_drive.h @@ -1,5 +1,4 @@ -#ifndef _SWERVEDRIVE_ -#define _SWERVEDRIVE_ +#pragma once #include "../core/include/subsystems/swerve_module.h" #include "../core/include/subsystems/odometry/odometry_swerve.h" @@ -9,6 +8,8 @@ #define ROT_DEADBAND 0.2 #define LAT_DEADBAND 0.2 +class OdometrySwerve; + enum ModulePosition { LEFT_FRONT, RIGHT_FRONT, LEFT_REAR, RIGHT_REAR @@ -69,5 +70,3 @@ OdometrySwerve *odometry; position_t saved_pos; }; - -#endif \ No newline at end of file diff --git a/include/subsystems/swerve_module.h b/include/subsystems/swerve_module.h index 3ffd88a..6f145c8 100644 --- a/include/subsystems/swerve_module.h +++ b/include/subsystems/swerve_module.h @@ -2,6 +2,7 @@ #define _SWERVEMODULE_ #include "vex.h" +using namespace vex; #ifndef PI #define PI 3.141592654 diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 6922c96..aa64063 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -1,5 +1,4 @@ -#ifndef _TANKDRIVE_ -#define _TANKDRIVE_ +#pragma once #ifndef PI #define PI 3.141592654 @@ -27,7 +26,7 @@ class TankDrive /** * Create the TankDrive object */ - TankDrive(motor_group &left_motors, motor_group &right_motors, inertial &gyro_sensor, tankdrive_config_t &config); + TankDrive(motor_group &left_motors, motor_group &right_motors, inertial &gyro_sensor, tankdrive_config_t &config, OdometryTank *odom=NULL); /** * Stops rotation of all the motors using their "brake mode" @@ -79,5 +78,3 @@ class TankDrive bool initialize_func = true; }; - -#endif \ No newline at end of file diff --git a/src/subsystems/odometry/odometry_swerve.cpp b/src/subsystems/odometry/odometry_swerve.cpp index 4895c29..cf13a95 100644 --- a/src/subsystems/odometry/odometry_swerve.cpp +++ b/src/subsystems/odometry/odometry_swerve.cpp @@ -1,7 +1,7 @@ #include "../core/include/subsystems/odometry/odometry_swerve.h" #include "../core/include/utils/vector.h" -OdometrySwerve::OdometrySwerve(SwerveDrive &drive_system, vex::inertial &imu, bool is_async=true) +OdometrySwerve::OdometrySwerve(SwerveDrive &drive_system, vex::inertial &imu, bool is_async) : drive_system(drive_system), imu(imu) { memset(&stored_info, 0, sizeof(stored_info_t)); diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 65de254..d7e4c13 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -59,15 +59,15 @@ position_t OdometryTank::update() { position_t updated_pos; - double lside_revs = left_side.position(rotationUnits::rev); - double rside_revs = right_side.position(rotationUnits::rev); + double lside_revs = left_side.position(vex::rotationUnits::rev) / config.gear_ratio; + double rside_revs = right_side.position(vex::rotationUnits::rev) / config.gear_ratio; if(imu == NULL) { updated_pos = calculate_new_pos(config, stored_info, lside_revs, rside_revs); } else { - double angle = imu->rotation(rotationUnits::deg); + double angle = imu->rotation(vex::rotationUnits::deg); updated_pos = calculate_new_pos(config, stored_info, lside_revs, rside_revs, &angle); } diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 9604916..89ca7f2 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -1,16 +1,10 @@ #include "../core/include/subsystems/tank_drive.h" -TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, inertial &gyro_sensor, TankDrive::tankdrive_config_t &config) +TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, inertial &gyro_sensor, TankDrive::tankdrive_config_t &config, OdometryTank *odom) : left_motors(left_motors), right_motors(right_motors), - drive_pid(config.drive_pid), turn_pid(config.turn_pid) + drive_pid(config.drive_pid), turn_pid(config.turn_pid), odometry(odom) { - odometry_config_t cfg = { - .dist_between_wheels = config.dist_between_wheels, - .wheel_diam = config.wheel_diam, - }; - - this->odometry = new OdometryTank(left_motors, right_motors, cfg, true); } /** @@ -30,8 +24,8 @@ void TankDrive::stop() */ void TankDrive::drive_tank(double left, double right) { - left_motors.setVelocity(left * 100, velocityUnits::pct); - right_motors.setVelocity(right * 100, velocityUnits::pct); + left_motors.spin(directionType::fwd, left * 100, velocityUnits::pct); + right_motors.spin(directionType::fwd, right * 100, velocityUnits::pct); } /** @@ -71,7 +65,10 @@ bool TankDrive::drive_forward(double inches, double percent_speed) initialize_func = false; } - double position_diff = OdometryBase::pos_diff(odometry->get_position(), saved_pos, true); + double position_diff = odometry->get_position().y - saved_pos.y; + + // printf("Pos diff: %f Saved pos: %f ", position_diff, saved_pos.y); + printf("Tank X: %f Tank Y: %f ", odometry->get_position().y, odometry->get_position().x); // Update PID loop and drive the robot based on it's output drive_pid.update(position_diff); From f171440675b53828e66928a070061c3eaddeefe0 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 19 Sep 2021 11:07:27 -0400 Subject: [PATCH 030/243] Odometry is slightly broken; worked on resetting position --- include/subsystems/odometry/odometry_base.h | 4 +- include/subsystems/odometry/odometry_tank.h | 17 ++- include/subsystems/tank_drive.h | 17 ++- src/subsystems/odometry/odometry_base.cpp | 2 +- src/subsystems/odometry/odometry_tank.cpp | 117 +++++++++++--------- src/subsystems/tank_drive.cpp | 82 ++++++++++++-- 6 files changed, 160 insertions(+), 79 deletions(-) diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index 59d263c..9866317 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -31,7 +31,7 @@ class OdometryBase /** * Sets the current position of the robot */ - void set_position(position_t &newpos); + virtual void set_position(const position_t &newpos=zero_pos); /** * Update the current position on the field based on the sensors @@ -57,6 +57,8 @@ class OdometryBase bool end_task = false; + static constexpr position_t zero_pos = {0, 0, 0}; + protected: vex::task *handle; vex::mutex mut; diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index 62a25c8..2caa894 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -13,13 +13,6 @@ typedef struct static int background_task(void* odom_obj); -// Contains information stored between update()s required for calculating posiion -typedef struct -{ - position_t pos; - double lside, rside; -} stored_info_t; - class OdometryTank : public OdometryBase { public: @@ -47,19 +40,23 @@ class OdometryTank : public OdometryBase /** * Update the current position on the field based on the sensors */ - position_t update(); + position_t update() override; + + + void set_position(const position_t &newpos=zero_pos) override; private: /** * Get information from the input hardware and an existing position, and calculate a new current position */ - static position_t calculate_new_pos(odometry_config_t &config, stored_info_t &stored_info, double lside_revs, double rside_revs, double *gyro_angle_deg = NULL); + static position_t calculate_new_pos(odometry_config_t &config, position_t &stored_info, double lside_diff, double rside_diff, double angle_deg); vex::motor_group &left_side, &right_side; vex::inertial *imu; odometry_config_t &config; - stored_info_t stored_info; + double rotation_offset = 0; + }; #endif \ No newline at end of file diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index aa64063..143e211 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -18,9 +18,6 @@ class TankDrive { PID::pid_config_t drive_pid; PID::pid_config_t turn_pid; - - double dist_between_wheels; - double wheel_diam; }; /** @@ -39,7 +36,7 @@ class TankDrive * * left_motors and right_motors are in "percent": -1.0 -> 1.0 */ - void drive_tank(double left, double right); + void drive_tank(double left, double right, int power=1); /** * Drive the robot using arcade style controls. forward_back controls the linear motion, @@ -47,7 +44,7 @@ class TankDrive * * left_motors and right_motors are in "percent": -1.0 -> 1.0 */ - void drive_arcade(double forward_back, double left_right); + void drive_arcade(double forward_back, double left_right, int power=1); /** * Autonomously drive the robot X inches forward (Negative for backwards), with a maximum speed @@ -65,6 +62,16 @@ class TankDrive */ bool turn_degrees(double degrees, double percent_speed); + /** + * Use odometry to automatically drive the robot to a point on the field. + * X, Y and Rotation are the final point and orientation we want the robot. + * + * Combing multiple drive_to_point's gives a pure pursuit system. + */ + bool drive_to_point(double x, double y, double rot_deg, double speed); + + static double modify_inputs(double input, int power=2); + private: motor_group &left_motors; motor_group &right_motors; diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index c5ab0a9..fc60016 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -24,7 +24,7 @@ position_t OdometryBase::get_position(void) /** * Sets the current position of the robot */ -void OdometryBase::set_position(position_t &newpos) +void OdometryBase::set_position(const position_t &newpos) { mut.lock(); diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index d7e4c13..508d53d 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -10,13 +10,24 @@ OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_ : left_side(left_side), right_side(right_side), imu(&imu), config(config) { // Make sure the last known info starts zeroed - memset(&stored_info, 0, sizeof(stored_info_t)); + memset(¤t_pos, 0, sizeof(position_t)); // Start the asynchronous background thread if (is_async) handle = new vex::task(background_task, this); } +/** + * Resets the position and rotational data to the input. + * + */ +void OdometryTank::set_position(const position_t &newpos) +{ + rotation_offset = newpos.rot - (current_pos.rot - rotation_offset); + + OdometryBase::set_position(newpos); +} + /** * Initialize the Odometry module, calculating the rotation from encoders * @param left_side The left motors @@ -27,7 +38,7 @@ OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_ : left_side(left_side), right_side(right_side), imu(NULL), config(config) { // Make sure the last known info starts zeroed - memset(&stored_info, 0, sizeof(stored_info_t)); + memset(¤t_pos, 0, sizeof(position_t)); // Start the asynchronous background thread if (is_async) @@ -62,15 +73,35 @@ position_t OdometryTank::update() double lside_revs = left_side.position(vex::rotationUnits::rev) / config.gear_ratio; double rside_revs = right_side.position(vex::rotationUnits::rev) / config.gear_ratio; + double angle = 0; + + // If the IMU data was passed in, use it for rotational data if(imu == NULL) { - updated_pos = calculate_new_pos(config, stored_info, lside_revs, rside_revs); + // Get the difference in distance driven between the two sides + // Uses the absolute position of the encoders, so resetting them will result in + // a bad angle. + double distance_diff = (lside_revs - rside_revs) * PI * config.wheel_diam; + + //Use the arclength formula to calculate the angle. + angle = (180.0 / PI) * (distance_diff / config.dist_between_wheels); + } else { - double angle = imu->rotation(vex::rotationUnits::deg); - updated_pos = calculate_new_pos(config, stored_info, lside_revs, rside_revs, &angle); + angle = imu->rotation(vex::rotationUnits::deg); } - + + // Offset the angle, if we've done a set_position + angle += rotation_offset; + + //Limit the angle betwen 0 and 360. + //fmod (floating-point modulo) gets it between -359 and +359, so tack on another 360 if it's negative. + angle = fmod(angle, 360.0); + if(angle < 0) + angle += 360; + + updated_pos = calculate_new_pos(config, current_pos, lside_revs, rside_revs, angle); + // Update the class' stored position mut.lock(); this->current_pos = updated_pos; @@ -83,57 +114,37 @@ position_t OdometryTank::update() * Using information about the robot's mechanical structure and sensors, calculate a new position * of the robot, relative to when this method was previously ran. */ -position_t OdometryTank::calculate_new_pos(odometry_config_t &config, stored_info_t &stored_info, double lside_revs, double rside_revs, double *gyro_angle_deg) +position_t OdometryTank::calculate_new_pos(odometry_config_t &config, position_t &curr_pos, double lside_revs, double rside_revs, double angle_deg) { position_t new_pos; - double angle = 0; + static double stored_lside_revs = lside_revs; + static double stored_rside_revs = rside_revs; + + // Convert the revolutions into "change in distance", and average the values for a "distance driven" + double lside_diff = (lside_revs - stored_lside_revs) * PI * config.wheel_diam; + double rside_diff = (rside_revs - stored_rside_revs) * PI * config.wheel_diam; + double dist_driven = (lside_diff + rside_diff) / 2.0; + + double angle = angle_deg * PI / 180.0; // Degrees to radians + + // Create a vector from the change in distance in the current direction of the robot + Vector chg_vec(angle_deg, dist_driven); + + // Create a vector from the current position in reference to X,Y=0,0 + Vector::point_t curr_point = {.x = curr_pos.x, .y = curr_pos.y}; + Vector curr_vec(curr_point); + + // Tack on the "difference" vector to the current vector + Vector new_vec = curr_vec + chg_vec; + + new_pos.x = new_vec.get_x(); + new_pos.y = new_vec.get_y(); + new_pos.rot = angle * (180.0 / PI); - // If the IMU data was passed in, use it for rotational data - if(gyro_angle_deg != NULL) - angle = *gyro_angle_deg; - else - { - // Get the difference in distance driven between the two sides - // Uses the absolute position of the encoders, so resetting them will result in - // a bad angle. - double distance_diff = (lside_revs - rside_revs) * PI * config.wheel_diam; - - //Use the arclength formula to calculate the angle. - angle = (180.0 / PI) * (distance_diff / config.dist_between_wheels); - - //Limit the angle betwen 0 and 360. - //fmod (floating-point modulo) gets it between -359 and +359, so tack on another 360 if it's negative. - angle = fmod(angle, 360.0); - if(angle < 0) - angle += 360; - } - - angle *= PI / 180.0; // Degrees to radians - - // Convert the revolutions into "change in distance", and average the values for a "distance driven" - double lside_diff = (lside_revs - stored_info.lside) * PI * config.wheel_diam; - double rside_diff = (rside_revs - stored_info.rside) * PI * config.wheel_diam; - double dist_driven = (lside_diff + rside_diff) / 2.0; - - // Create a vector from the change in distance in the current direction of the robot - Vector chg_vec(angle, dist_driven); - - // Create a vector from the current position in reference to X,Y=0,0 - Vector::point_t curr_point = {.x = stored_info.pos.x, .y = stored_info.pos.y}; - Vector curr_vec(curr_point); - - // Tack on the "difference" vector to the current vector - Vector new_vec = curr_vec + chg_vec; - - new_pos.x = new_vec.get_x(); - new_pos.y = new_vec.get_y(); - new_pos.rot = angle * (180.0 / PI); - - // Store the left and right encoder values to find the difference in the next iteration - stored_info.lside = lside_revs; - stored_info.rside = rside_revs; - stored_info.pos = new_pos; + // Store the left and right encoder values to find the difference in the next iteration + stored_lside_revs = lside_revs; + stored_rside_revs = rside_revs; return new_pos; } \ No newline at end of file diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 89ca7f2..5336fc7 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -22,10 +22,13 @@ void TankDrive::stop() * * left_motors and right_motors are in "percent": -1.0 -> 1.0 */ -void TankDrive::drive_tank(double left, double right) +void TankDrive::drive_tank(double left, double right, int power) { - left_motors.spin(directionType::fwd, left * 100, velocityUnits::pct); - right_motors.spin(directionType::fwd, right * 100, velocityUnits::pct); + left = modify_inputs(left, power); + right = modify_inputs(right, power); + + left_motors.spin(directionType::fwd, left * 12, voltageUnits::volt); + right_motors.spin(directionType::fwd, right * 12, voltageUnits::volt); } /** @@ -34,13 +37,16 @@ void TankDrive::drive_tank(double left, double right) * * left_motors and right_motors are in "percent": -1.0 -> 1.0 */ -void TankDrive::drive_arcade(double forward_back, double left_right) +void TankDrive::drive_arcade(double forward_back, double left_right, int power) { + forward_back = modify_inputs(forward_back, power); + left_right = modify_inputs(left_right, power); + double left = forward_back + left_right; double right = forward_back - left_right; - left_motors.setVelocity(left * 100, velocityUnits::pct); - right_motors.setVelocity(right * 100, velocityUnits::pct); + left_motors.spin(directionType::fwd, left * 12, voltageUnits::volt); + right_motors.spin(directionType::fwd, right * 12, voltageUnits::volt); } /** @@ -67,9 +73,6 @@ bool TankDrive::drive_forward(double inches, double percent_speed) double position_diff = odometry->get_position().y - saved_pos.y; - // printf("Pos diff: %f Saved pos: %f ", position_diff, saved_pos.y); - printf("Tank X: %f Tank Y: %f ", odometry->get_position().y, odometry->get_position().x); - // Update PID loop and drive the robot based on it's output drive_pid.update(position_diff); @@ -120,4 +123,65 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) } return false; +} + +bool TankDrive::drive_to_point(double x, double y, double rot_deg, double speed) +{ + static bool initialized = false; + + if(!initialized) + { + // Reset the control loops + drive_pid.reset(); + turn_pid.reset(); + + drive_pid.set_limits(-fabs(speed), fabs(speed)); + turn_pid.set_limits(-fabs(speed), fabs(speed)); + + // Set the distance target to 0, because we update with the change in distance between the current point + // and the new point. + drive_pid.set_target(0); + + initialized = true; + } + + position_t end_pos = + { + .x = x, + .y = y, + .rot = rot_deg + }; + + // Store the initial position of the robot + position_t current_pos = odometry->get_position(); + + // Set the rotational target of the PID loop. + // Every loop this gets updated, to make sure we are pointing in the right direction + turn_pid.set_target(OdometryBase::rot_diff(end_pos, current_pos)); + + // Update the PID controllers with new information + turn_pid.update(current_pos.rot); + drive_pid.update(OdometryBase::pos_diff(current_pos, end_pos)); + + // Combine the two pid outputs + double lside = drive_pid.get() + turn_pid.get(); + double rside = drive_pid.get() - turn_pid.get(); + + // limit the outputs between -1 and +1 + lside = (lside > 1) ? 1 : (lside < -1) ? -1 : lside; + rside = (rside > 1) ? 1 : (rside < -1) ? -1 : rside; + + drive_tank(lside, rside); + + + return false; +} + +/** + * Modify the inputs from the controller by squaring / cubing, etc + * Allows for better control of the robot at slower speeds + */ +double TankDrive::modify_inputs(double input, int power) +{ + return (power % 2 == 0 ? (input < 0 ? -1 : 1) : 1) * pow(input, power); } \ No newline at end of file From 8fe7b1a4d6c1de902f2555340dca56c794bfdcfd Mon Sep 17 00:00:00 2001 From: Jacob To Date: Sun, 19 Sep 2021 20:36:30 -0400 Subject: [PATCH 031/243] Find intersections of line segment and circle Will be used to find the pure pursuit target --- include/subsystems/tank_drive.h | 7 +++++ src/subsystems/tank_drive.cpp | 51 ++++++++++++++++++++++++++++++++- 2 files changed, 57 insertions(+), 1 deletion(-) diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 143e211..9bee583 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -7,6 +7,7 @@ #include "vex.h" #include "../core/include/utils/pid.h" #include "../core/include/subsystems/odometry/odometry_tank.h" +#include using namespace vex; @@ -72,6 +73,12 @@ class TankDrive static double modify_inputs(double input, int power=2); + /** + * Returns points of the intersections of a line segment and a circle. The line + * segment is defined by two points, and the circle is defined by a center and radius. + */ + std::vector line_circle_intersections(Vector::point_t center, double r, Vector::point_t point1, Vector::point_t point2); + private: motor_group &left_motors; motor_group &right_motors; diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 5336fc7..d46afba 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -184,4 +184,53 @@ bool TankDrive::drive_to_point(double x, double y, double rot_deg, double speed) double TankDrive::modify_inputs(double input, int power) { return (power % 2 == 0 ? (input < 0 ? -1 : 1) : 1) * pow(input, power); -} \ No newline at end of file +} + +/** + * Returns points of the intersections of a line segment and a circle. The line + * segment is defined by two points, and the circle is defined by a center and radius. + */ +std::vector TankDrive::line_circle_intersections(Vector::point_t center, double r, Vector::point_t point1, Vector::point_t point2) +{ + std::vector intersections = {}; + + //Do future calculations relative to the circle's center + point1.y -= center.y; + point1.x -= center.x; + point2.y -= center.y; + point2.x -= center.x; + + double x1, x2, y1, y2; + //Handling an infinite slope using mx+b and x^2 + y^2 = r^2 + if(point1.x - point2.x == 0) + { + y1 = point1.y; + x1 = sqrt(pow(r, 2) - pow(y1, 2)); + y2 = point1.y; + x2 = -sqrt(pow(r, 2) - pow(y1, 2)); + } + //Non-infinite slope using mx+b and x^2 + y^2 = r^2 + else + { + double m = (point1.y - point2.y) / (point1.x - point2.x); + double b = point1.y - (m * point1.x); + + x1 = ((-m * b) + sqrt(pow(r, 2) + (pow(m, 2) * pow(r, 2)) - pow(b, 2))) / (1 + pow(m,2)); + y1 = m * x1 + b; + x2 = ((-m * b) - sqrt(pow(r, 2) + (pow(m, 2) * pow(r, 2)) - pow(b, 2))) / (1 + pow(m,2)); + y2 = m * x2 + b; + } + + //The equations used define an infinitely long line, so we check if the detected intersection falls on the line segment. + if(x1 >= fmin(point1.x, point2.x) && x1 <= fmax(point1.x, point2.x) && y1 >= fmin(point1.y, point2.y) && y1 <= fmax(point1.y, point2.y)) + { + intersections.push_back(Vector::point_t{.x = x1 + center.x, .y = y1 + center.y}); + } + + if(x2 >= fmin(point1.x, point2.x) && x2 <= fmax(point1.x, point2.x) && y2 >= fmin(point1.y, point2.y) && y2 <= fmax(point1.y, point2.y)) + { + intersections.push_back(Vector::point_t{.x = x2 + center.x, .y = y2 + center.y}); + } + + return intersections; +} From 5db01f586931495cbd0141f46975e9b136aa9929 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Mon, 20 Sep 2021 14:08:07 -0400 Subject: [PATCH 032/243] Fixed odometry angle error, worked on tank_drive --- include/subsystems/odometry/odometry_base.h | 7 ++ include/subsystems/tank_drive.h | 12 ++-- src/subsystems/odometry/odometry_base.cpp | 20 ++++++ src/subsystems/odometry/odometry_tank.cpp | 4 +- src/subsystems/tank_drive.cpp | 74 ++++++++++++++++++--- 5 files changed, 100 insertions(+), 17 deletions(-) diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index 9866317..12d62de 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -55,6 +55,13 @@ class OdometryBase */ static double rot_diff(position_t &pos1, position_t &pos2); + /** + * Get the smallest difference in angle between a start heading and end heading. + * Returns the difference between -180 degrees and +180 degrees, representing the robot + * turning left or right, respectively. + */ + static double smallest_angle(double start_deg, double end_deg); + bool end_task = false; static constexpr position_t zero_pos = {0, 0, 0}; diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 9bee583..9404bff 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -65,11 +65,15 @@ class TankDrive /** * Use odometry to automatically drive the robot to a point on the field. - * X, Y and Rotation are the final point and orientation we want the robot. - * - * Combing multiple drive_to_point's gives a pure pursuit system. + * X and Y is the final point we want the robot. */ - bool drive_to_point(double x, double y, double rot_deg, double speed); + bool drive_to_point(double x, double y, double speed); + + /** + * Turn the robot in place to an exact heading relative to the field. + * 0 is forward, and 0->360 is clockwise. + */ + bool turn_to_heading(double heading_deg, double speed); static double modify_inputs(double input, int power=2); diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index fc60016..852f8f6 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -78,4 +78,24 @@ double OdometryBase::pos_diff(position_t pos1, position_t pos2, bool use_negativ double OdometryBase::rot_diff(position_t &pos1, position_t &pos2) { return pos2.rot - pos1.rot; +} + +/** + * Get the smallest difference in angle between a start heading and end heading. + * Returns the difference between -180 degrees and +180 degrees, representing the robot + * turning left or right, respectively. + */ +double OdometryBase::smallest_angle(double start_deg, double end_deg) +{ + double retval; + // get the difference between 0 and 360 + retval = fmod(end_deg - start_deg, 360.0); + if(retval < 0) + retval += 360.0; + + // Get the closest angle, now between -180 (turn left) and +180 (turn right) + if(retval > 180) + retval -= 360; + + return retval; } \ No newline at end of file diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 508d53d..5ebae0a 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -129,7 +129,7 @@ position_t OdometryTank::calculate_new_pos(odometry_config_t &config, position_t double angle = angle_deg * PI / 180.0; // Degrees to radians // Create a vector from the change in distance in the current direction of the robot - Vector chg_vec(angle_deg, dist_driven); + Vector chg_vec(angle, dist_driven); // Create a vector from the current position in reference to X,Y=0,0 Vector::point_t curr_point = {.x = curr_pos.x, .y = curr_pos.y}; @@ -140,7 +140,7 @@ position_t OdometryTank::calculate_new_pos(odometry_config_t &config, position_t new_pos.x = new_vec.get_x(); new_pos.y = new_vec.get_y(); - new_pos.rot = angle * (180.0 / PI); + new_pos.rot = angle_deg; // Store the left and right encoder values to find the difference in the next iteration stored_lside_revs = lside_revs; diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index d46afba..ab5ae26 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -125,7 +125,13 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) return false; } -bool TankDrive::drive_to_point(double x, double y, double rot_deg, double speed) +/** + * Use odometry to automatically drive the robot to a point on the field. + * X and Y is the final point we want the robot. + * + * Returns whether or not the robot has reached it's destination. + */ +bool TankDrive::drive_to_point(double x, double y, double speed) { static bool initialized = false; @@ -138,9 +144,10 @@ bool TankDrive::drive_to_point(double x, double y, double rot_deg, double speed) drive_pid.set_limits(-fabs(speed), fabs(speed)); turn_pid.set_limits(-fabs(speed), fabs(speed)); - // Set the distance target to 0, because we update with the change in distance between the current point + // Set the targets to 0, because we update with the change in distance and angle between the current point // and the new point. drive_pid.set_target(0); + turn_pid.set_target(0); initialized = true; } @@ -148,24 +155,27 @@ bool TankDrive::drive_to_point(double x, double y, double rot_deg, double speed) position_t end_pos = { .x = x, - .y = y, - .rot = rot_deg + .y = y }; // Store the initial position of the robot position_t current_pos = odometry->get_position(); - // Set the rotational target of the PID loop. - // Every loop this gets updated, to make sure we are pointing in the right direction - turn_pid.set_target(OdometryBase::rot_diff(end_pos, current_pos)); + // Get the distance between 2 points + double dist_left = OdometryBase::pos_diff(current_pos, end_pos); + + // Get the heading difference between where we are and where we want to be + // Optimize that heading so we don't turn clockwise all the time + double heading = OdometryBase::rot_diff(current_pos, end_pos); + double delta_heading = OdometryBase::smallest_angle(current_pos.rot, heading); // Update the PID controllers with new information - turn_pid.update(current_pos.rot); - drive_pid.update(OdometryBase::pos_diff(current_pos, end_pos)); + turn_pid.update(delta_heading); + drive_pid.update(dist_left); // Combine the two pid outputs - double lside = drive_pid.get() + turn_pid.get(); - double rside = drive_pid.get() - turn_pid.get(); + double lside = drive_pid.get() - turn_pid.get(); + double rside = drive_pid.get() + turn_pid.get(); // limit the outputs between -1 and +1 lside = (lside > 1) ? 1 : (lside < -1) ? -1 : lside; @@ -173,6 +183,48 @@ bool TankDrive::drive_to_point(double x, double y, double rot_deg, double speed) drive_tank(lside, rside); + // Check if the robot has reached it's destination + if(drive_pid.is_on_target()) + { + stop(); + initialized = false; + return true; + } + + return false; +} + +/** + * Turn the robot in place to an exact heading relative to the field. + * 0 is forward, and 0->360 is clockwise. + */ +bool TankDrive::turn_to_heading(double heading_deg, double speed) +{ + bool initialized = false; + if(!initialized) + { + turn_pid.reset(); + turn_pid.set_limits(-fabs(speed), fabs(speed)); + + // Set the target to zero, and the input will be a delta. + turn_pid.set_target(0); + + initialized = true; + } + + // Get the difference between the new heading and the current, and decide whether to turn left or right. + double delta_heading = OdometryBase::smallest_angle(odometry->get_position().rot, heading_deg); + turn_pid.update(delta_heading); + + drive_tank(-turn_pid.get(), turn_pid.get()); + + // When the robot has reached it's angle, return true. + if(turn_pid.is_on_target()) + { + initialized = false; + stop(); + return true; + } return false; } From df86d4021b1ac28149add96a45d04c9fa3528a98 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 23 Sep 2021 20:07:04 -0400 Subject: [PATCH 033/243] upgrading drive_to_point --- include/subsystems/tank_drive.h | 9 ++- src/subsystems/odometry/odometry_base.cpp | 24 +++---- src/subsystems/tank_drive.cpp | 77 ++++++++++++++--------- src/utils/pid.cpp | 1 + 4 files changed, 68 insertions(+), 43 deletions(-) diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 9404bff..775fc96 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -19,6 +19,7 @@ class TankDrive { PID::pid_config_t drive_pid; PID::pid_config_t turn_pid; + PID::pid_config_t correction_pid; }; /** @@ -75,6 +76,11 @@ class TankDrive */ bool turn_to_heading(double heading_deg, double speed); + /** + * Reset the initialization for autonomous drive functions + */ + void reset_auto(); + static double modify_inputs(double input, int power=2); /** @@ -89,10 +95,11 @@ class TankDrive PID drive_pid; PID turn_pid; + PID correction_pid; OdometryTank *odometry; position_t saved_pos; - bool initialize_func = true; + bool func_initialized = false; }; diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index 852f8f6..8f1db89 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -48,28 +48,30 @@ void OdometryBase::end_async() /** * Get the distance between two points */ -double OdometryBase::pos_diff(position_t pos1, position_t pos2, bool use_negatives) +double OdometryBase::pos_diff(position_t start_pos, position_t end_pos, bool use_negatives) { int negative_multiplier = 1; // If we are using negative distances, define a "negative distance" as when the angle - // of a vector made from those two points is between 3PI/4 and 7PI/4 + // of a vector made from those two points is between PI/2 and 3PI/2 if(use_negatives) { - Vector::point_t point_diff = { - .x = pos1.x - pos2.x, - .y = pos1.y - pos2.y - }; + // use atan2(x,y) instead of the documented (y,x), so 0 degrees is forwards, and positive angle is clockwise. + double angle = rad2deg(atan2(end_pos.x - start_pos.x, end_pos.y - start_pos.y)); - Vector v_diff(point_diff); - double angle = rad2deg(v_diff.get_dir()); + printf("Start: %f, %f End: %f, %f, Old Angle: %f, Odom angle: %f, ",start_pos.x, start_pos.y, end_pos.x, end_pos.y, angle, start_pos.rot); - if(angle > 135 && angle < 315) + // Get the angle in relation to the robot + angle = fmod(angle - start_pos.rot, 180.0); + + printf("Angle: %f\n", angle); + + if(angle > 90 || angle < -90) negative_multiplier = -1; } // Use the pythagorean theorem - return negative_multiplier * sqrt(pow(pos1.x - pos2.x, 2) + pow(pos1.y - pos2.y, 2)); + return negative_multiplier * sqrt(pow(end_pos.x - start_pos.x, 2) + pow(end_pos.y - start_pos.y, 2)); } /** @@ -77,7 +79,7 @@ double OdometryBase::pos_diff(position_t pos1, position_t pos2, bool use_negativ */ double OdometryBase::rot_diff(position_t &pos1, position_t &pos2) { - return pos2.rot - pos1.rot; + return pos1.rot - pos2.rot; } /** diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index ab5ae26..970d93f 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -2,11 +2,19 @@ TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, inertial &gyro_sensor, TankDrive::tankdrive_config_t &config, OdometryTank *odom) : left_motors(left_motors), right_motors(right_motors), - drive_pid(config.drive_pid), turn_pid(config.turn_pid), odometry(odom) + drive_pid(config.drive_pid), turn_pid(config.turn_pid), correction_pid(config.correction_pid), odometry(odom) { } +/** + * Reset the initialization for autonomous drive functions + */ +void TankDrive::reset_auto() +{ + func_initialized = false; +} + /** * Stops rotation of all the motors using their "brake mode" */ @@ -60,7 +68,7 @@ void TankDrive::drive_arcade(double forward_back, double left_right, int power) bool TankDrive::drive_forward(double inches, double percent_speed) { // On the first run of the funciton, reset the motor position and PID - if (initialize_func) + if (!func_initialized) { saved_pos = odometry->get_position(); drive_pid.reset(); @@ -68,7 +76,7 @@ bool TankDrive::drive_forward(double inches, double percent_speed) drive_pid.set_limits(-fabs(percent_speed), fabs(percent_speed)); drive_pid.set_target(inches); - initialize_func = false; + func_initialized = true; } double position_diff = odometry->get_position().y - saved_pos.y; @@ -83,7 +91,7 @@ bool TankDrive::drive_forward(double inches, double percent_speed) if (drive_pid.is_on_target()) { drive_tank(0, 0); - initialize_func = true; + func_initialized = false; return true; } @@ -99,26 +107,29 @@ bool TankDrive::drive_forward(double inches, double percent_speed) bool TankDrive::turn_degrees(double degrees, double percent_speed) { // On the first run of the funciton, reset the gyro position and PID - if (initialize_func) + if (!func_initialized) { saved_pos = odometry->get_position(); turn_pid.reset(); turn_pid.set_limits(-fabs(percent_speed), fabs(percent_speed)); - turn_pid.set_target(degrees); + turn_pid.set_target(0); - initialize_func = false; + func_initialized = true; } + double heading = odometry->get_position().rot - saved_pos.rot; + double delta_heading = OdometryBase::smallest_angle(heading, degrees); + turn_pid.update(delta_heading); - // Update PID loop and drive the robot based on it's output - turn_pid.update(odometry->get_position().rot - saved_pos.rot); - drive_tank(turn_pid.get(), -turn_pid.get()); + printf("heading: %f, delta_heading: %f\n", heading, delta_heading); + + drive_tank(-turn_pid.get(), turn_pid.get()); // If the robot is at it's target, return true if (turn_pid.is_on_target()) { drive_tank(0, 0); - initialize_func = true; + func_initialized = false; return true; } @@ -133,49 +144,51 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) */ bool TankDrive::drive_to_point(double x, double y, double speed) { - static bool initialized = false; - - if(!initialized) + if(!func_initialized) { // Reset the control loops drive_pid.reset(); - turn_pid.reset(); + correction_pid.reset(); drive_pid.set_limits(-fabs(speed), fabs(speed)); - turn_pid.set_limits(-fabs(speed), fabs(speed)); + correction_pid.set_limits(-fabs(speed), fabs(speed)); // Set the targets to 0, because we update with the change in distance and angle between the current point // and the new point. drive_pid.set_target(0); - turn_pid.set_target(0); + correction_pid.set_target(0); - initialized = true; + func_initialized = true; } - position_t end_pos = + // Store the initial position of the robot + position_t current_pos = odometry->get_position(); + position_t end_pos = {.x=x, .y=y}; + + // Create a point (and vector) to get the direction + Vector::point_t pos_diff_pt = { - .x = x, - .y = y + .x = x - current_pos.x, + .y = y - current_pos.y }; - // Store the initial position of the robot - position_t current_pos = odometry->get_position(); + Vector point_vec(pos_diff_pt); // Get the distance between 2 points - double dist_left = OdometryBase::pos_diff(current_pos, end_pos); + double dist_left = -OdometryBase::pos_diff(current_pos, end_pos, true); // Get the heading difference between where we are and where we want to be // Optimize that heading so we don't turn clockwise all the time - double heading = OdometryBase::rot_diff(current_pos, end_pos); - double delta_heading = OdometryBase::smallest_angle(current_pos.rot, heading); + double heading = rad2deg(point_vec.get_dir()); + double delta_heading = -OdometryBase::smallest_angle(current_pos.rot, heading); // Update the PID controllers with new information - turn_pid.update(delta_heading); + correction_pid.update(delta_heading); drive_pid.update(dist_left); // Combine the two pid outputs - double lside = drive_pid.get() - turn_pid.get(); - double rside = drive_pid.get() + turn_pid.get(); + double lside = drive_pid.get() + correction_pid.get(); + double rside = drive_pid.get() - correction_pid.get(); // limit the outputs between -1 and +1 lside = (lside > 1) ? 1 : (lside < -1) ? -1 : lside; @@ -187,7 +200,7 @@ bool TankDrive::drive_to_point(double x, double y, double speed) if(drive_pid.is_on_target()) { stop(); - initialized = false; + func_initialized = false; return true; } @@ -200,7 +213,7 @@ bool TankDrive::drive_to_point(double x, double y, double speed) */ bool TankDrive::turn_to_heading(double heading_deg, double speed) { - bool initialized = false; + static bool initialized = false; if(!initialized) { turn_pid.reset(); @@ -216,6 +229,8 @@ bool TankDrive::turn_to_heading(double heading_deg, double speed) double delta_heading = OdometryBase::smallest_angle(odometry->get_position().rot, heading_deg); turn_pid.update(delta_heading); + printf("delta heading: %f, pid: %f, ", delta_heading, turn_pid.get()); + drive_tank(-turn_pid.get(), turn_pid.get()); // When the robot has reached it's angle, return true. diff --git a/src/utils/pid.cpp b/src/utils/pid.cpp index c0c8727..d4e38e3 100644 --- a/src/utils/pid.cpp +++ b/src/utils/pid.cpp @@ -15,6 +15,7 @@ PID::PID(pid_config_t &config) */ void PID::update(double sensor_val) { + this->sensor_val = sensor_val; double time_delta = pid_timer.value() - last_time; From 596b9682ee8565f9aa535e1374efcf0c7b0624b9 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 23 Sep 2021 20:33:57 -0400 Subject: [PATCH 034/243] Finished drive_to_point --- src/subsystems/odometry/odometry_base.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index 8f1db89..281952f 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -62,7 +62,9 @@ double OdometryBase::pos_diff(position_t start_pos, position_t end_pos, bool use printf("Start: %f, %f End: %f, %f, Old Angle: %f, Odom angle: %f, ",start_pos.x, start_pos.y, end_pos.x, end_pos.y, angle, start_pos.rot); // Get the angle in relation to the robot - angle = fmod(angle - start_pos.rot, 180.0); + angle = fmod(angle - start_pos.rot, 360); + if(angle < -180) angle += 360; + if(angle > 180) angle -= 360; printf("Angle: %f\n", angle); From 1817a7ae7ea6c8476a085995832bfb576abc67d1 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 23 Sep 2021 20:37:24 -0400 Subject: [PATCH 035/243] Merge remote-tracking branch 'refs/remotes/origin/odometry' into odometry --- include/subsystems/tank_drive.h | 11 +++++ include/utils/vector.h | 30 ++++++++++++++ src/subsystems/tank_drive.cpp | 73 ++++++++++++++++++++++++++++++++- src/utils/vector.cpp | 31 +++++++++++++- 4 files changed, 143 insertions(+), 2 deletions(-) diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 775fc96..f34e577 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -89,6 +89,17 @@ class TankDrive */ std::vector line_circle_intersections(Vector::point_t center, double r, Vector::point_t point1, Vector::point_t point2); + /** + * Selects a look ahead from all the intersections in the path. + */ + Vector::point_t get_lookahead(std::vector path, Vector::point_t robot_loc, double radius); + + /** + * Injects points in a path without changing the curvature with a certain spacing. + */ + std::vector inject_path(std::vector path, double spacing); + + private: motor_group &left_motors; motor_group &right_motors; diff --git a/include/utils/vector.h b/include/utils/vector.h index 45ec32c..e7b204c 100644 --- a/include/utils/vector.h +++ b/include/utils/vector.h @@ -14,6 +14,26 @@ class Vector struct point_t { double x, y; + + point_t operator+(const point_t &other) + { + point_t p + { + .x = this->x + other.x, + .y = this->y + other.y + }; + return p; + } + + point_t operator-(const point_t &other) + { + point_t p + { + .x = this->x - other.x, + .y = this->y - other.y + }; + return p; + } }; /** @@ -54,7 +74,17 @@ class Vector */ double get_y() const; + /** + * Changes the magnetude of the vector to 1 + */ + Vector normalize(); + + /** + * Returns a point from the vector + */ + Vector::point_t point(); + Vector operator*(const double &x); Vector operator+(const Vector &other); Vector operator-(const Vector &other); diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 970d93f..32f5791 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -257,7 +257,7 @@ double TankDrive::modify_inputs(double input, int power) * Returns points of the intersections of a line segment and a circle. The line * segment is defined by two points, and the circle is defined by a center and radius. */ -std::vector TankDrive::line_circle_intersections(Vector::point_t center, double r, Vector::point_t point1, Vector::point_t point2) +std::vector line_circle_intersections(Vector::point_t center, double r, Vector::point_t point1, Vector::point_t point2) { std::vector intersections = {}; @@ -301,3 +301,74 @@ std::vector TankDrive::line_circle_intersections(Vector::point_ return intersections; } + +/** + * Selects a look ahead from all the intersections in the path. + */ +Vector::point_t get_lookahead(std::vector path, Vector::point_t robot_loc, double radius) +{ + //Default: the end of the path + Vector::point_t target = path.back(); + + //Check each line segment of the path for potential targets + for(int i = 0; i < path.size() - 1; i++) + { + Vector::point_t start = path[i]; + Vector::point_t end = path[i+1]; + + std::vector intersections = line_circle_intersections(robot_loc, radius, start, end); + //Choose the intersection that is closest to the end of the line segment + //This prioritizes the closest intersection to the end of the path + for(Vector::point_t intersection: intersections) + { + double intersection_dist_to_end = sqrt(pow(intersection.x - end.x, 2) + pow(intersection.y - end.y, 2)); + double target_dist_to_end = sqrt(pow(target.x - end.x, 2) + pow(target.y - end.y, 2)); + if(intersection_dist_to_end < target_dist_to_end) + target = intersection; + } + } + + return target; +} + +/** + Injects points in a path without changing the curvature with a certain spacing. +*/ +std::vector inject_path(std::vector path, double spacing) +{ + std::vector new_path; + + //Injecting points for each line segment + for(int i = 0; i < path.size() - 1; i++) + { + Vector::point_t start = path[i]; + Vector::point_t end = path[i+1]; + + Vector::point_t diff = end - start; + Vector vector = Vector(diff); + + int num_points = ceil(vector.get_mag() / spacing); + + //This is the vector between each point + vector = vector.normalize() * spacing; + + for(int j = 0; j < num_points; j++) + { + //We take the start point and add additional vectors + Vector::point_t path_point = (Vector(start) + vector * j).point(); + new_path.push_back(path_point); + } + } + //Adds the last point + new_path.push_back(path.back()); + return new_path; +} + +/** + Drives through a path using pure pursuit. +*/ +void pure_pursuit(std::vector path, Vector::point_t robot_loc, double radius, double speed) +{ + Vector::point_t lookahead = get_lookahead(path, robot_loc, radius); + // Travel towards target :) +} diff --git a/src/utils/vector.cpp b/src/utils/vector.cpp index 2600606..dacd865 100644 --- a/src/utils/vector.cpp +++ b/src/utils/vector.cpp @@ -52,6 +52,27 @@ double Vector::get_y() const return mag * cos(dir); } +/** + * Changes the magnetude of the vector to 1 +*/ +Vector Vector::normalize() +{ + return Vector(this->dir, 1); +} + +/** + * Returns a point from the vector +*/ +Vector::point_t Vector::point() +{ + point_t p = + { + .x = this->mag * cos(this->dir), + .y = this->mag * sin(this->dir) + }; + return p; +} + /** * Correctly add vectors together with the + operator */ @@ -79,6 +100,14 @@ Vector Vector::operator-(const Vector &other) return Vector( p ); } +/** + * Multiplies a vector by a double with the * operator +*/ +Vector Vector::operator*(const double &x) +{ + return Vector(this->dir, this->mag * x); +} + /** * General function for converting degrees to radians */ @@ -93,4 +122,4 @@ double deg2rad(double deg) double rad2deg(double rad) { return rad * (180.0 / PI); -} \ No newline at end of file +} From 6a291de4a1b0abe17f59f0c0b31e3dfc76bee957 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 26 Sep 2021 13:02:28 -0400 Subject: [PATCH 036/243] Finished integral clamping --- src/utils/pid.cpp | 30 +++++++++++++++++++++++++++++- 1 file changed, 29 insertions(+), 1 deletion(-) diff --git a/src/utils/pid.cpp b/src/utils/pid.cpp index d4e38e3..2d313b9 100644 --- a/src/utils/pid.cpp +++ b/src/utils/pid.cpp @@ -22,13 +22,41 @@ void PID::update(double sensor_val) accum_error += time_delta * get_error(); - out = (config.f * target) + (config.p * get_error()) + (config.i * accum_error) + (config.d * (get_error() - last_error) / time_delta); + double i_term = config.i * accum_error; + + // Avoid a divide by zero error + double d_term = 0; + if(time_delta != 0) + d_term = config.d * (get_error() - last_error) / time_delta; + else + printf("(pid.cpp): Warning - running PID without a delay is just a P loop!\n"); + + out = (config.f * target) + (config.p * get_error()) + i_term + d_term; last_time = pid_timer.value(); last_error = get_error(); + // Enable clamping if the limit is not 0 if (lower_limit != 0 || upper_limit != 0) + { + // Integral back-calculation + // If the PID is oversaturated and the integrated term is not pushing it in the right direction, + // then "turn off" the integral until it's actually helping. + bool clamping_upper = (out > upper_limit) && ((out - i_term) > upper_limit); + bool clamping_lower = (out < lower_limit) && ((out - i_term) < lower_limit); + + if(clamping_upper || clamping_lower) + { + out -= i_term; + printf("out: %f, out-iterm: %f, Integral clamping!\n", out, out-i_term); + }else + { + printf("out: %f, out-iterm: %f, NOT Integral clamping!\n", out, out-i_term); + } + + // Actually clamp the value out = (out < lower_limit) ? lower_limit : (out > upper_limit) ? upper_limit : out; + } } /** From 9c1b5c0e8bcfa96184028ca7bc1467dd1df01211 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 26 Sep 2021 13:12:07 -0400 Subject: [PATCH 037/243] Removed comments --- src/utils/pid.cpp | 6 ------ 1 file changed, 6 deletions(-) diff --git a/src/utils/pid.cpp b/src/utils/pid.cpp index 2d313b9..3754a89 100644 --- a/src/utils/pid.cpp +++ b/src/utils/pid.cpp @@ -46,13 +46,7 @@ void PID::update(double sensor_val) bool clamping_lower = (out < lower_limit) && ((out - i_term) < lower_limit); if(clamping_upper || clamping_lower) - { out -= i_term; - printf("out: %f, out-iterm: %f, Integral clamping!\n", out, out-i_term); - }else - { - printf("out: %f, out-iterm: %f, NOT Integral clamping!\n", out, out-i_term); - } // Actually clamp the value out = (out < lower_limit) ? lower_limit : (out > upper_limit) ? upper_limit : out; From b1b2b1eef3fe1389252c07bd483849bf5b5f91cf Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 26 Sep 2021 13:18:06 -0400 Subject: [PATCH 038/243] added correction speed --- include/subsystems/tank_drive.h | 2 +- src/subsystems/tank_drive.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index f34e577..c836c53 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -68,7 +68,7 @@ class TankDrive * Use odometry to automatically drive the robot to a point on the field. * X and Y is the final point we want the robot. */ - bool drive_to_point(double x, double y, double speed); + bool drive_to_point(double x, double y, double speed, double correction_speed); /** * Turn the robot in place to an exact heading relative to the field. diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 32f5791..fc3c3d1 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -142,7 +142,7 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) * * Returns whether or not the robot has reached it's destination. */ -bool TankDrive::drive_to_point(double x, double y, double speed) +bool TankDrive::drive_to_point(double x, double y, double speed, double correction_speed) { if(!func_initialized) { @@ -151,7 +151,7 @@ bool TankDrive::drive_to_point(double x, double y, double speed) correction_pid.reset(); drive_pid.set_limits(-fabs(speed), fabs(speed)); - correction_pid.set_limits(-fabs(speed), fabs(speed)); + correction_pid.set_limits(-fabs(correction_speed), fabs(correction_speed)); // Set the targets to 0, because we update with the change in distance and angle between the current point // and the new point. From 4782af55b84d76b99e13b455a9c670a4805b71a3 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 26 Sep 2021 14:54:31 -0400 Subject: [PATCH 039/243] fixed vector class --- include/utils/vector.h | 5 +++++ src/utils/vector.cpp | 2 +- 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/include/utils/vector.h b/include/utils/vector.h index e7b204c..a8a8cc4 100644 --- a/include/utils/vector.h +++ b/include/utils/vector.h @@ -11,10 +11,14 @@ class Vector { public: + /** + * Data structure representing an X,Y coordinate + */ struct point_t { double x, y; + // Vector addition operation on points point_t operator+(const point_t &other) { point_t p @@ -25,6 +29,7 @@ class Vector return p; } + // Vector subtraction operation on points point_t operator-(const point_t &other) { point_t p diff --git a/src/utils/vector.cpp b/src/utils/vector.cpp index dacd865..2badd84 100644 --- a/src/utils/vector.cpp +++ b/src/utils/vector.cpp @@ -19,7 +19,7 @@ Vector::Vector(double dir, double mag) */ Vector::Vector(point_t &p) { - this->dir = atan2(p.x, p.y); + this->dir = atan2(p.y, p.x); this->mag = sqrt( (p.x*p.x) + (p.y*p.y) ); } From 7e2514eeed9015ded83fd1023cd579fa6d6c5f3e Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 26 Sep 2021 15:31:46 -0400 Subject: [PATCH 040/243] Fixed tank odometry --- include/subsystems/tank_drive.h | 2 +- src/subsystems/odometry/odometry_base.cpp | 7 +------ src/subsystems/odometry/odometry_tank.cpp | 14 ++++++++++---- src/subsystems/tank_drive.cpp | 2 +- 4 files changed, 13 insertions(+), 12 deletions(-) diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index c836c53..1bb8a91 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -25,7 +25,7 @@ class TankDrive /** * Create the TankDrive object */ - TankDrive(motor_group &left_motors, motor_group &right_motors, inertial &gyro_sensor, tankdrive_config_t &config, OdometryTank *odom=NULL); + TankDrive(motor_group &left_motors, motor_group &right_motors, tankdrive_config_t &config, OdometryTank *odom=NULL); /** * Stops rotation of all the motors using their "brake mode" diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index 281952f..d2e01c3 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -56,18 +56,13 @@ double OdometryBase::pos_diff(position_t start_pos, position_t end_pos, bool use // of a vector made from those two points is between PI/2 and 3PI/2 if(use_negatives) { - // use atan2(x,y) instead of the documented (y,x), so 0 degrees is forwards, and positive angle is clockwise. - double angle = rad2deg(atan2(end_pos.x - start_pos.x, end_pos.y - start_pos.y)); - - printf("Start: %f, %f End: %f, %f, Old Angle: %f, Odom angle: %f, ",start_pos.x, start_pos.y, end_pos.x, end_pos.y, angle, start_pos.rot); + double angle = rad2deg(atan2(end_pos.y - start_pos.y, end_pos.x - start_pos.x)); // Get the angle in relation to the robot angle = fmod(angle - start_pos.rot, 360); if(angle < -180) angle += 360; if(angle > 180) angle -= 360; - printf("Angle: %f\n", angle); - if(angle > 90 || angle < -90) negative_multiplier = -1; } diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 5ebae0a..39b7998 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -81,14 +81,20 @@ position_t OdometryTank::update() // Get the difference in distance driven between the two sides // Uses the absolute position of the encoders, so resetting them will result in // a bad angle. - double distance_diff = (lside_revs - rside_revs) * PI * config.wheel_diam; + // Get the arclength of the turning circle of the robot + double distance_diff = (rside_revs - lside_revs) * PI * config.wheel_diam; - //Use the arclength formula to calculate the angle. - angle = (180.0 / PI) * (distance_diff / config.dist_between_wheels); + printf("dist_diff: %f, ", distance_diff); + + //Use the arclength formula to calculate the angle. Add 90 to make "0 degrees" to starboard + angle = ((180.0 / PI) * (distance_diff / config.dist_between_wheels)) + 90; + + printf("angle: %f, ", (180.0 / PI) * (distance_diff / config.dist_between_wheels)); } else { - angle = imu->rotation(vex::rotationUnits::deg); + // Translate "0 forward and clockwise positive" to "90 forward and CCW negative" + angle = -imu->rotation(vex::rotationUnits::deg) + 90; } // Offset the angle, if we've done a set_position diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index fc3c3d1..2ce61be 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -1,6 +1,6 @@ #include "../core/include/subsystems/tank_drive.h" -TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, inertial &gyro_sensor, TankDrive::tankdrive_config_t &config, OdometryTank *odom) +TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, TankDrive::tankdrive_config_t &config, OdometryTank *odom) : left_motors(left_motors), right_motors(right_motors), drive_pid(config.drive_pid), turn_pid(config.turn_pid), correction_pid(config.correction_pid), odometry(odom) { From f2a4665887065b763b8382672c121df94fe6d841 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Tue, 28 Sep 2021 20:39:28 -0400 Subject: [PATCH 041/243] fixed warning message in PID --- include/subsystems/odometry/odometry_base.h | 2 +- src/subsystems/tank_drive.cpp | 8 ++++---- src/utils/pid.cpp | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index 12d62de..70853b9 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -64,7 +64,7 @@ class OdometryBase bool end_task = false; - static constexpr position_t zero_pos = {0, 0, 0}; + inline static constexpr position_t zero_pos = {.x=0, .y=0, .rot=90}; protected: vex::task *handle; diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 2ce61be..b573c9d 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -121,7 +121,7 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) double delta_heading = OdometryBase::smallest_angle(heading, degrees); turn_pid.update(delta_heading); - printf("heading: %f, delta_heading: %f\n", heading, delta_heading); + // printf("heading: %f, delta_heading: %f\n", heading, delta_heading); drive_tank(-turn_pid.get(), turn_pid.get()); @@ -180,7 +180,7 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti // Get the heading difference between where we are and where we want to be // Optimize that heading so we don't turn clockwise all the time double heading = rad2deg(point_vec.get_dir()); - double delta_heading = -OdometryBase::smallest_angle(current_pos.rot, heading); + double delta_heading = OdometryBase::smallest_angle(current_pos.rot, heading); // Update the PID controllers with new information correction_pid.update(delta_heading); @@ -229,9 +229,9 @@ bool TankDrive::turn_to_heading(double heading_deg, double speed) double delta_heading = OdometryBase::smallest_angle(odometry->get_position().rot, heading_deg); turn_pid.update(delta_heading); - printf("delta heading: %f, pid: %f, ", delta_heading, turn_pid.get()); + // printf("delta heading: %f, pid: %f, ", delta_heading, turn_pid.get()); - drive_tank(-turn_pid.get(), turn_pid.get()); + drive_tank(turn_pid.get(), -turn_pid.get()); // When the robot has reached it's angle, return true. if(turn_pid.is_on_target()) diff --git a/src/utils/pid.cpp b/src/utils/pid.cpp index 3754a89..4e8dd5d 100644 --- a/src/utils/pid.cpp +++ b/src/utils/pid.cpp @@ -28,7 +28,7 @@ void PID::update(double sensor_val) double d_term = 0; if(time_delta != 0) d_term = config.d * (get_error() - last_error) / time_delta; - else + else if(last_time != 0) printf("(pid.cpp): Warning - running PID without a delay is just a P loop!\n"); out = (config.f * target) + (config.p * get_error()) + i_term + d_term; From 820683c4c645282f7054df01f114d239fd73472a Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 3 Oct 2021 14:08:29 -0400 Subject: [PATCH 042/243] fixed tank_drive, added dist across axis --- include/subsystems/odometry/odometry_base.h | 2 +- src/subsystems/odometry/odometry_base.cpp | 14 ++++++++++++-- src/subsystems/tank_drive.cpp | 14 ++++++++++---- src/utils/generic_auto.cpp | 2 +- 4 files changed, 24 insertions(+), 8 deletions(-) diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index 70853b9..d1c20d6 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -48,7 +48,7 @@ class OdometryBase /** * Get the distance between two points */ - static double pos_diff(position_t pos1, position_t pos2, bool use_negatives=false); + static double pos_diff(position_t pos1, position_t pos2, bool use_negatives=false, bool along_axis=false); /** * Get the change in rotation between two points diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index d2e01c3..e35c307 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -48,7 +48,7 @@ void OdometryBase::end_async() /** * Get the distance between two points */ -double OdometryBase::pos_diff(position_t start_pos, position_t end_pos, bool use_negatives) +double OdometryBase::pos_diff(position_t start_pos, position_t end_pos, bool use_negatives, bool along_axis) { int negative_multiplier = 1; @@ -68,7 +68,17 @@ double OdometryBase::pos_diff(position_t start_pos, position_t end_pos, bool use } // Use the pythagorean theorem - return negative_multiplier * sqrt(pow(end_pos.x - start_pos.x, 2) + pow(end_pos.y - start_pos.y, 2)); + double retval = negative_multiplier * sqrt(pow(end_pos.x - start_pos.x, 2) + pow(end_pos.y - start_pos.y, 2)); + + // If requested, only find the distance along the robot's forward axis + if(along_axis) + { + double angle = start_pos.rot - rad2deg(atan2(end_pos.y - start_pos.y, end_pos.x - start_pos.x)); + // printf("theta: %f, ", angle); + retval *= fabs(cos(deg2rad(angle))); + } + + return retval; } /** diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index b573c9d..e27546b 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -175,7 +175,7 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti Vector point_vec(pos_diff_pt); // Get the distance between 2 points - double dist_left = -OdometryBase::pos_diff(current_pos, end_pos, true); + double dist_left = -OdometryBase::pos_diff(current_pos, end_pos, true, true); // Get the heading difference between where we are and where we want to be // Optimize that heading so we don't turn clockwise all the time @@ -186,9 +186,13 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti correction_pid.update(delta_heading); drive_pid.update(dist_left); + printf("~DRIVE~ "); + printf("Correction: %f, Drive: %f, Corr_PID: %f, Drive_PID: %f \n", delta_heading, dist_left, correction_pid.get(), drive_pid.get()); + fflush(stdout); + // Combine the two pid outputs - double lside = drive_pid.get() + correction_pid.get(); - double rside = drive_pid.get() - correction_pid.get(); + double lside = drive_pid.get() + ((fabs(dist_left) > 2) ? correction_pid.get() : 0); + double rside = drive_pid.get() - ((fabs(dist_left) > 2) ? correction_pid.get() : 0); // limit the outputs between -1 and +1 lside = (lside > 1) ? 1 : (lside < -1) ? -1 : lside; @@ -229,7 +233,9 @@ bool TankDrive::turn_to_heading(double heading_deg, double speed) double delta_heading = OdometryBase::smallest_angle(odometry->get_position().rot, heading_deg); turn_pid.update(delta_heading); - // printf("delta heading: %f, pid: %f, ", delta_heading, turn_pid.get()); + printf("~TURN~ delta: %f\n", delta_heading); + // printf("delta heading: %f, pid: %f\n", delta_heading, turn_pid.get()); + fflush(stdout); drive_tank(turn_pid.get(), -turn_pid.get()); diff --git a/src/utils/generic_auto.cpp b/src/utils/generic_auto.cpp index b74804c..5c5c7ab 100644 --- a/src/utils/generic_auto.cpp +++ b/src/utils/generic_auto.cpp @@ -24,7 +24,7 @@ bool GenericAuto::run(bool blocking) state_list.pop(); if(blocking) - vexDelay(50); + vexDelay(20); } while(blocking && !state_list.empty()); From d5b7717a637a8d837ee73e8d4f61d144f81ab6b1 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 3 Oct 2021 14:20:03 -0400 Subject: [PATCH 043/243] Fixed sin/cos in vector --- src/utils/vector.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/utils/vector.cpp b/src/utils/vector.cpp index 2badd84..b29cb14 100644 --- a/src/utils/vector.cpp +++ b/src/utils/vector.cpp @@ -41,7 +41,7 @@ double Vector::get_mag() const { return mag; } */ double Vector::get_x() const { -return mag * sin(dir); +return mag * cos(dir); } /** @@ -49,7 +49,7 @@ return mag * sin(dir); */ double Vector::get_y() const { -return mag * cos(dir); +return mag * sin(dir); } /** From 1364e2359e535ddb3815974f4749f053d0bfb25a Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 7 Oct 2021 19:13:40 -0400 Subject: [PATCH 044/243] Fixed pid stuff and backwards turning --- src/subsystems/tank_drive.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index e27546b..b0851b6 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -123,7 +123,7 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) // printf("heading: %f, delta_heading: %f\n", heading, delta_heading); - drive_tank(-turn_pid.get(), turn_pid.get()); + drive_tank(turn_pid.get(), -turn_pid.get()); // If the robot is at it's target, return true if (turn_pid.is_on_target()) From caf259519868b4f20247e3ac66af2ea59eb4dd00 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Wed, 15 Dec 2021 12:53:31 -0800 Subject: [PATCH 045/243] Merge branch 'odometry' --- include/robot_specs.h | 24 ++ include/subsystems/odometry/odometry_base.h | 5 +- include/subsystems/odometry/odometry_tank.h | 46 ++-- include/subsystems/tank_drive.h | 45 ++-- include/utils/pure_pursuit.h | 78 +++++++ include/utils/vector.h | 7 +- src/subsystems/odometry/odometry_base.cpp | 39 +--- src/subsystems/odometry/odometry_tank.cpp | 60 ++--- src/subsystems/swerve_drive.cpp | 3 +- src/subsystems/tank_drive.cpp | 232 +++++++------------ src/utils/pure_pursuit.cpp | 236 ++++++++++++++++++++ 11 files changed, 501 insertions(+), 274 deletions(-) create mode 100644 include/robot_specs.h create mode 100644 include/utils/pure_pursuit.h create mode 100644 src/utils/pure_pursuit.cpp diff --git a/include/robot_specs.h b/include/robot_specs.h new file mode 100644 index 0000000..95dae0a --- /dev/null +++ b/include/robot_specs.h @@ -0,0 +1,24 @@ +#pragma once +#include "../core/include/utils/pid.h" + +/** + * Main robot characterization struct. + * This will be passed to all the major subsystems + * that require info about the robot. + * All distance measurements are in inches. + */ +typedef struct +{ + double robot_radius; + + double odom_wheel_diam; + double odom_gear_ratio; + double dist_between_wheels; + + double drive_correction_cutoff; + + PID::pid_config_t drive_pid; + PID::pid_config_t turn_pid; + PID::pid_config_t correction_pid; + +} robot_specs_t; \ No newline at end of file diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index d1c20d6..daf1692 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -2,12 +2,13 @@ #define _ODOMETRY_ #include "vex.h" +#include "../core/include/robot_specs.h" #ifndef PI #define PI 3.141592654 #endif -#define DOWNTIME 50 //milliseconds +#define DOWNTIME 0 //milliseconds // Describes a single position and rotation typedef struct @@ -48,7 +49,7 @@ class OdometryBase /** * Get the distance between two points */ - static double pos_diff(position_t pos1, position_t pos2, bool use_negatives=false, bool along_axis=false); + static double pos_diff(position_t pos1, position_t pos2); /** * Get the change in rotation between two points diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index 2caa894..e40daff 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -3,13 +3,7 @@ #include "../core/include/subsystems/odometry/odometry_base.h" #include "../core/include/utils/vector.h" - -typedef struct -{ - double dist_between_wheels; - double wheel_diam; - double gear_ratio; -} odometry_config_t; +#include "../core/include/robot_specs.h" static int background_task(void* odom_obj); @@ -17,25 +11,22 @@ class OdometryTank : public OdometryBase { public: /** - * Initialize the Odometry module, using the IMU to get rotation - * @param left_side The left motors - * @param right_ - * side The right motors - * @param imu The robot's inertial sensor - * @param is_async If true, the robot will automatically poll it's position and update it in the background. - * If false, the update() function must be called periodically. - */ - OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, vex::inertial &imu, odometry_config_t &config, bool is_async=true); + * Initialize the Odometry module, calculating position from the drive motors. + * @param left_side The left motors + * @param right_side The right motors + * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). + */ + OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true); /** - * Initialize the Odometry module, calculating the rotation from encoders - * @param left_side The left motors - * @param right_side The right motors - * @param imu The robot's inertial sensor - * @param is_async If true, the robot will automatically poll it's position and update it in the background. - * If false, the update() function must be called periodically. - */ - OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, odometry_config_t &config, bool is_async=true); + * Initialize the Odometry module, calculating posiiton from encoders on "dead wheels" + * @param left_side The left motors + * @param right_side The right motors + * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). + */ + OdometryTank(vex::encoder &left_enc, vex::encoder &right_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true); /** * Update the current position on the field based on the sensors @@ -49,11 +40,12 @@ class OdometryTank : public OdometryBase /** * Get information from the input hardware and an existing position, and calculate a new current position */ - static position_t calculate_new_pos(odometry_config_t &config, position_t &stored_info, double lside_diff, double rside_diff, double angle_deg); + static position_t calculate_new_pos(robot_specs_t &config, position_t &stored_info, double lside_diff, double rside_diff, double angle_deg); - vex::motor_group &left_side, &right_side; + vex::motor_group *left_side, *right_side; + vex::encoder *left_enc, *right_enc; vex::inertial *imu; - odometry_config_t &config; + robot_specs_t &config; double rotation_offset = 0; diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 1bb8a91..16bd27d 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -7,7 +7,9 @@ #include "vex.h" #include "../core/include/utils/pid.h" #include "../core/include/subsystems/odometry/odometry_tank.h" +#include "../core/include/robot_specs.h" #include +#include "../core/src/utils/pure_pursuit.cpp" using namespace vex; @@ -15,17 +17,10 @@ class TankDrive { public: - struct tankdrive_config_t - { - PID::pid_config_t drive_pid; - PID::pid_config_t turn_pid; - PID::pid_config_t correction_pid; - }; - /** * Create the TankDrive object */ - TankDrive(motor_group &left_motors, motor_group &right_motors, tankdrive_config_t &config, OdometryTank *odom=NULL); + TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryTank *odom=NULL); /** * Stops rotation of all the motors using their "brake mode" @@ -49,12 +44,15 @@ class TankDrive void drive_arcade(double forward_back, double left_right, int power=1); /** - * Autonomously drive the robot X inches forward (Negative for backwards), with a maximum speed - * of percent_speed (-1.0 -> 1.0). - * - * Uses a PID loop for it's control. + * Autonomously drive forward or backwards, X inches infront or behind the robot's current position. + * This driving method is relative, so excessive use may cause the robot to get off course! + * + * @param inches Distance to drive in a straight line + * @param speed How fast the robot should travel, 0 -> 1.0 + * @param correction How much the robot should correct for being off angle + * @param dir Whether the robot is travelling forwards or backwards */ - bool drive_forward(double inches, double percent_speed); + bool drive_forward(double inches, double speed, double correction, directionType dir); /** * Autonomously turn the robot X degrees to the right (negative for left), with a maximum motor speed @@ -68,7 +66,7 @@ class TankDrive * Use odometry to automatically drive the robot to a point on the field. * X and Y is the final point we want the robot. */ - bool drive_to_point(double x, double y, double speed, double correction_speed); + bool drive_to_point(double x, double y, double speed, double correction_speed, vex::directionType direction=vex::directionType::fwd); /** * Turn the robot in place to an exact heading relative to the field. @@ -83,22 +81,7 @@ class TankDrive static double modify_inputs(double input, int power=2); - /** - * Returns points of the intersections of a line segment and a circle. The line - * segment is defined by two points, and the circle is defined by a center and radius. - */ - std::vector line_circle_intersections(Vector::point_t center, double r, Vector::point_t point1, Vector::point_t point2); - - /** - * Selects a look ahead from all the intersections in the path. - */ - Vector::point_t get_lookahead(std::vector path, Vector::point_t robot_loc, double radius); - - /** - * Injects points in a path without changing the curvature with a certain spacing. - */ - std::vector inject_path(std::vector path, double spacing); - + bool pure_pursuit(std::vector path, double radius, double speed, double res); private: motor_group &left_motors; @@ -112,5 +95,7 @@ class TankDrive position_t saved_pos; + robot_specs_t &config; + bool func_initialized = false; }; diff --git a/include/utils/pure_pursuit.h b/include/utils/pure_pursuit.h new file mode 100644 index 0000000..818fa2f --- /dev/null +++ b/include/utils/pure_pursuit.h @@ -0,0 +1,78 @@ +#pragma once + +#include +#include "../core/include/utils/vector.h" +#include "vex.h" + +using namespace vex; + +namespace PurePursuit { + /** + * Represents a piece of a cubic spline with s(x) = a(x-xi)^3 + b(x-xi)^2 + c(x-xi) + d + * The x_start and x_end shows where the equation is valid. + */ + struct spline + { + double a, b, c, d, x_start, x_end; + + double getY(double x) { + return a * pow((x - x_start), 3) + b * pow((x - x_start), 2) + c * (x - x_start) + d; + } + }; + + struct hermite_point + { + double x; + double y; + double dir; + double mag; + + Vector::point_t getPoint() { + return {x, y}; + } + + Vector getTangent() { + return Vector(dir, mag); + } + }; + + /** + * Returns points of the intersections of a line segment and a circle. The line + * segment is defined by two points, and the circle is defined by a center and radius. + */ + static std::vector line_circle_intersections(Vector::point_t center, double r, Vector::point_t point1, Vector::point_t point2); + /** + * Selects a look ahead from all the intersections in the path. + */ + static Vector::point_t get_lookahead(std::vector path, Vector::point_t robot_loc, double radius); + + /** + * Injects points in a path without changing the curvature with a certain spacing. + */ + static std::vector inject_path(std::vector path, double spacing); + + /** + * Returns a smoothed path maintaining the start and end of the path. + * + * Weight data is how much weight to update the data (alpha) + * Weight smooth is how much weight to smooth the coordinates (beta) + * Tolerance is how much change per iteration is necessary to continue iterating. + * + * Honestly have no idea if/how this works. + * https://medium.com/@jaems33/understanding-robot-motion-path-smoothing-5970c8363bc4 + */ + + static std::vector smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance); + + static std::vector smooth_path_cubic(std::vector path, double res); + + /** + * Interpolates a smooth path given a list of waypoints using hermite splines. + * For more information: https://www.youtube.com/watch?v=hG0p4XgePSA. + * + * @param path The path of hermite points to interpolate. + * @param steps The number of points interpolated between points. + * @return The smoothed path. + */ + static std::vector smooth_path_hermite(std::vector path, double step); +} \ No newline at end of file diff --git a/include/utils/vector.h b/include/utils/vector.h index a8a8cc4..48d0d05 100644 --- a/include/utils/vector.h +++ b/include/utils/vector.h @@ -18,6 +18,11 @@ class Vector { double x, y; + double dist(const point_t other) + { + return sqrt(pow(this->x - other.x, 2) + pow(this->y - other.y, 2)); + } + // Vector addition operation on points point_t operator+(const point_t &other) { @@ -109,4 +114,4 @@ double deg2rad(double deg); */ double rad2deg(double r); -#endif \ No newline at end of file +#endif diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index e35c307..ffa872c 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -42,43 +42,18 @@ void OdometryBase::set_position(const position_t &newpos) */ void OdometryBase::end_async() { - this->end_task = true; + this->end_task = true; } /** * Get the distance between two points */ -double OdometryBase::pos_diff(position_t start_pos, position_t end_pos, bool use_negatives, bool along_axis) +double OdometryBase::pos_diff(position_t start_pos, position_t end_pos) { - int negative_multiplier = 1; - - // If we are using negative distances, define a "negative distance" as when the angle - // of a vector made from those two points is between PI/2 and 3PI/2 - if(use_negatives) - { - double angle = rad2deg(atan2(end_pos.y - start_pos.y, end_pos.x - start_pos.x)); - - // Get the angle in relation to the robot - angle = fmod(angle - start_pos.rot, 360); - if(angle < -180) angle += 360; - if(angle > 180) angle -= 360; - - if(angle > 90 || angle < -90) - negative_multiplier = -1; - } - - // Use the pythagorean theorem - double retval = negative_multiplier * sqrt(pow(end_pos.x - start_pos.x, 2) + pow(end_pos.y - start_pos.y, 2)); - - // If requested, only find the distance along the robot's forward axis - if(along_axis) - { - double angle = start_pos.rot - rad2deg(atan2(end_pos.y - start_pos.y, end_pos.x - start_pos.x)); - // printf("theta: %f, ", angle); - retval *= fabs(cos(deg2rad(angle))); - } - - return retval; + // Use the pythagorean theorem + double retval = sqrt(pow(end_pos.x - start_pos.x, 2) + pow(end_pos.y - start_pos.y, 2)); + + return retval; } /** @@ -86,7 +61,7 @@ double OdometryBase::pos_diff(position_t start_pos, position_t end_pos, bool use */ double OdometryBase::rot_diff(position_t &pos1, position_t &pos2) { - return pos1.rot - pos2.rot; + return pos1.rot - pos2.rot; } /** diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 39b7998..2db44bd 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -1,13 +1,13 @@ #include "../core/include/subsystems/odometry/odometry_tank.h" /** - * Initialize the Odometry module, using the IMU to get rotation + * Initialize the Odometry module, calculating position from the drive motors. * @param left_side The left motors * @param right_side The right motors - * @param imu The robot's inertial sensor + * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. */ -OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, vex::inertial &imu, odometry_config_t &config, bool is_async) -: left_side(left_side), right_side(right_side), imu(&imu), config(config) +OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu, bool is_async) +: left_side(&left_side), right_side(&right_side), left_enc(NULL), right_enc(NULL), imu(imu), config(config) { // Make sure the last known info starts zeroed memset(¤t_pos, 0, sizeof(position_t)); @@ -18,24 +18,13 @@ OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_ } /** - * Resets the position and rotational data to the input. - * - */ -void OdometryTank::set_position(const position_t &newpos) -{ - rotation_offset = newpos.rot - (current_pos.rot - rotation_offset); - - OdometryBase::set_position(newpos); -} - -/** - * Initialize the Odometry module, calculating the rotation from encoders + * Initialize the Odometry module, calculating posiiton from encoders on "dead wheels" * @param left_side The left motors * @param right_side The right motors - * @param imu The robot's inertial sensor + * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. */ -OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, odometry_config_t &config, bool is_async) -: left_side(left_side), right_side(right_side), imu(NULL), config(config) +OdometryTank::OdometryTank(vex::encoder &left_enc, vex::encoder &right_enc, robot_specs_t &config, vex::inertial *imu, bool is_async) +: left_side(NULL), right_side(NULL), left_enc(&left_enc), right_enc(&right_enc), imu(imu), config(config) { // Make sure the last known info starts zeroed memset(¤t_pos, 0, sizeof(position_t)); @@ -43,7 +32,17 @@ OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_ // Start the asynchronous background thread if (is_async) handle = new vex::task(background_task, this); - +} + +/** + * Resets the position and rotational data to the input. + * + */ +void OdometryTank::set_position(const position_t &newpos) +{ + rotation_offset = newpos.rot - (current_pos.rot - rotation_offset); + + OdometryBase::set_position(newpos); } /** @@ -70,8 +69,17 @@ position_t OdometryTank::update() { position_t updated_pos; - double lside_revs = left_side.position(vex::rotationUnits::rev) / config.gear_ratio; - double rside_revs = right_side.position(vex::rotationUnits::rev) / config.gear_ratio; + double lside_revs = 0, rside_revs = 0; + + if(left_side != NULL && right_side != NULL) + { + lside_revs = left_side->position(vex::rotationUnits::rev) / config.odom_gear_ratio; + rside_revs = right_side->position(vex::rotationUnits::rev) / config.odom_gear_ratio; + }else if(left_enc != NULL && right_enc != NULL) + { + lside_revs = left_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; + rside_revs = right_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; + } double angle = 0; @@ -82,7 +90,7 @@ position_t OdometryTank::update() // Uses the absolute position of the encoders, so resetting them will result in // a bad angle. // Get the arclength of the turning circle of the robot - double distance_diff = (rside_revs - lside_revs) * PI * config.wheel_diam; + double distance_diff = (rside_revs - lside_revs) * PI * config.odom_wheel_diam; printf("dist_diff: %f, ", distance_diff); @@ -120,7 +128,7 @@ position_t OdometryTank::update() * Using information about the robot's mechanical structure and sensors, calculate a new position * of the robot, relative to when this method was previously ran. */ -position_t OdometryTank::calculate_new_pos(odometry_config_t &config, position_t &curr_pos, double lside_revs, double rside_revs, double angle_deg) +position_t OdometryTank::calculate_new_pos(robot_specs_t &config, position_t &curr_pos, double lside_revs, double rside_revs, double angle_deg) { position_t new_pos; @@ -128,8 +136,8 @@ position_t OdometryTank::calculate_new_pos(odometry_config_t &config, position_t static double stored_rside_revs = rside_revs; // Convert the revolutions into "change in distance", and average the values for a "distance driven" - double lside_diff = (lside_revs - stored_lside_revs) * PI * config.wheel_diam; - double rside_diff = (rside_revs - stored_rside_revs) * PI * config.wheel_diam; + double lside_diff = (lside_revs - stored_lside_revs) * PI * config.odom_wheel_diam; + double rside_diff = (rside_revs - stored_rside_revs) * PI * config.odom_wheel_diam; double dist_driven = (lside_diff + rside_diff) / 2.0; double angle = angle_deg * PI / 180.0; // Degrees to radians diff --git a/src/subsystems/swerve_drive.cpp b/src/subsystems/swerve_drive.cpp index 4c8ca42..ca59f6f 100644 --- a/src/subsystems/swerve_drive.cpp +++ b/src/subsystems/swerve_drive.cpp @@ -134,7 +134,8 @@ bool SwerveDrive::auto_drive(double direction, double speed, double distance) auto_drive_init = false; } - double pos_diff = OdometryBase::pos_diff(odometry->get_position(), saved_pos, true); + // TODO fix negatives + double pos_diff = OdometryBase::pos_diff(odometry->get_position(), saved_pos); // LOOP drive_pid->update(pos_diff); diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index b0851b6..b531ee1 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -1,8 +1,8 @@ #include "../core/include/subsystems/tank_drive.h" -TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, TankDrive::tankdrive_config_t &config, OdometryTank *odom) +TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryTank *odom) : left_motors(left_motors), right_motors(right_motors), - drive_pid(config.drive_pid), turn_pid(config.turn_pid), correction_pid(config.correction_pid), odometry(odom) + drive_pid(config.drive_pid), turn_pid(config.turn_pid), correction_pid(config.correction_pid), odometry(odom), config(config) { } @@ -58,44 +58,37 @@ void TankDrive::drive_arcade(double forward_back, double left_right, int power) } /** - * Autonomously drive the robot X inches forward (Negative for backwards), with a maximum speed - * of percent_speed (-1.0 -> 1.0). - * - * Uses a PID loop for it's control. - * - * NOTE: uses relative positioning, so after a few drive_forward's, position may be lost! + * Autonomously drive forward or backwards, X inches infront or behind the robot's current position. + * This driving method is relative, so excessive use may cause the robot to get off course! + * + * @param inches Distance to drive in a straight line + * @param speed How fast the robot should travel, 0 -> 1.0 + * @param correction How much the robot should correct for being off angle + * @param dir Whether the robot is travelling forwards or backwards */ -bool TankDrive::drive_forward(double inches, double percent_speed) +bool TankDrive::drive_forward(double inches, double speed, double correction, directionType dir) { - // On the first run of the funciton, reset the motor position and PID + static position_t pos_setpt; + + // Generate a point X inches forward of the current position, on first startup if (!func_initialized) { saved_pos = odometry->get_position(); drive_pid.reset(); - drive_pid.set_limits(-fabs(percent_speed), fabs(percent_speed)); - drive_pid.set_target(inches); - - func_initialized = true; - } - - double position_diff = odometry->get_position().y - saved_pos.y; + // Use vector math to get an X and Y + Vector current_pos({saved_pos.x , saved_pos.y}); + Vector delta_pos(deg2rad(saved_pos.rot), inches); + Vector setpt_vec = current_pos + delta_pos; - // Update PID loop and drive the robot based on it's output - drive_pid.update(position_diff); + // Save the new X and Y values + pos_setpt = {.x=setpt_vec.get_x(), .y=setpt_vec.get_y()}; - // Drive backwards if we input negative inches, forward for positive - drive_tank(drive_pid.get(), drive_pid.get()); - - // If the robot is at it's target, return true - if (drive_pid.is_on_target()) - { - drive_tank(0, 0); - func_initialized = false; - return true; + func_initialized = true; } - return false; + // Call the drive_to_point with updated point values + return drive_to_point(pos_setpt.x, pos_setpt.y, speed, correction, dir); } /** @@ -142,8 +135,9 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) * * Returns whether or not the robot has reached it's destination. */ -bool TankDrive::drive_to_point(double x, double y, double speed, double correction_speed) +bool TankDrive::drive_to_point(double x, double y, double speed, double correction_speed, vex::directionType dir) { + if(!func_initialized) { // Reset the control loops @@ -158,6 +152,8 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti drive_pid.set_target(0); correction_pid.set_target(0); + // point_orientation_deg = atan2(y - odometry->get_position().y, x - odometry->get_position().x) * 180.0 / PI; + func_initialized = true; } @@ -175,24 +171,61 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti Vector point_vec(pos_diff_pt); // Get the distance between 2 points - double dist_left = -OdometryBase::pos_diff(current_pos, end_pos, true, true); + double dist_left = OdometryBase::pos_diff(current_pos, end_pos); + + int sign = 1; + + if (fabs(dist_left) < config.drive_correction_cutoff) + { + // Make an imaginary perpendicualar line to that between the bot and the point. If the point is behind that line, + // and the point is within the robot's radius, use negatives for feedback control. + + double angle_to_point = atan2(y - current_pos.y, x - current_pos.x) * 180.0 / PI; + double angle = fmod(current_pos.rot - angle_to_point, 360.0); + // Normalize the angle between 0 and 360 + if (angle > 360) angle -= 360; + if (angle < 0) angle += 360; + // If the angle is behind the robot, report negative. + if (dir == directionType::fwd && angle > 90 && angle < 270) + sign = -1; + else if(dir == directionType::rev && (angle < 90 || angle > 270)) + sign = -1; + + // When inside the robot's cutoff radius, report the distance to the point along the robot's forward axis, + // so we always "reach" the point without having to do a lateral translation + dist_left *= fabs(cos(angle * PI / 180.0)); + } // Get the heading difference between where we are and where we want to be // Optimize that heading so we don't turn clockwise all the time double heading = rad2deg(point_vec.get_dir()); - double delta_heading = OdometryBase::smallest_angle(current_pos.rot, heading); + double delta_heading = 0; + + // Going backwards "flips" the robot's current heading + if (dir == directionType::fwd) + delta_heading = OdometryBase::smallest_angle(current_pos.rot, heading); + else + delta_heading = OdometryBase::smallest_angle(current_pos.rot - 180, heading); // Update the PID controllers with new information correction_pid.update(delta_heading); - drive_pid.update(dist_left); + drive_pid.update(sign * -1 * dist_left); - printf("~DRIVE~ "); - printf("Correction: %f, Drive: %f, Corr_PID: %f, Drive_PID: %f \n", delta_heading, dist_left, correction_pid.get(), drive_pid.get()); - fflush(stdout); + // Disable correction when we're close enough to the point + double correction = 0; + if(fabs(dist_left) > config.drive_correction_cutoff) + correction = correction_pid.get(); + + // Reverse the drive_pid output if we're going backwards + double drive_pid_rval; + if(dir == directionType::rev) + drive_pid_rval = drive_pid.get() * -1; + else + drive_pid_rval = drive_pid.get(); // Combine the two pid outputs - double lside = drive_pid.get() + ((fabs(dist_left) > 2) ? correction_pid.get() : 0); - double rside = drive_pid.get() - ((fabs(dist_left) > 2) ? correction_pid.get() : 0); + double lside = drive_pid_rval + correction; + double rside = drive_pid_rval - correction; // limit the outputs between -1 and +1 lside = (lside > 1) ? 1 : (lside < -1) ? -1 : lside; @@ -259,122 +292,11 @@ double TankDrive::modify_inputs(double input, int power) return (power % 2 == 0 ? (input < 0 ? -1 : 1) : 1) * pow(input, power); } -/** - * Returns points of the intersections of a line segment and a circle. The line - * segment is defined by two points, and the circle is defined by a center and radius. - */ -std::vector line_circle_intersections(Vector::point_t center, double r, Vector::point_t point1, Vector::point_t point2) -{ - std::vector intersections = {}; - - //Do future calculations relative to the circle's center - point1.y -= center.y; - point1.x -= center.x; - point2.y -= center.y; - point2.x -= center.x; - - double x1, x2, y1, y2; - //Handling an infinite slope using mx+b and x^2 + y^2 = r^2 - if(point1.x - point2.x == 0) - { - y1 = point1.y; - x1 = sqrt(pow(r, 2) - pow(y1, 2)); - y2 = point1.y; - x2 = -sqrt(pow(r, 2) - pow(y1, 2)); - } - //Non-infinite slope using mx+b and x^2 + y^2 = r^2 - else - { - double m = (point1.y - point2.y) / (point1.x - point2.x); - double b = point1.y - (m * point1.x); - - x1 = ((-m * b) + sqrt(pow(r, 2) + (pow(m, 2) * pow(r, 2)) - pow(b, 2))) / (1 + pow(m,2)); - y1 = m * x1 + b; - x2 = ((-m * b) - sqrt(pow(r, 2) + (pow(m, 2) * pow(r, 2)) - pow(b, 2))) / (1 + pow(m,2)); - y2 = m * x2 + b; - } - - //The equations used define an infinitely long line, so we check if the detected intersection falls on the line segment. - if(x1 >= fmin(point1.x, point2.x) && x1 <= fmax(point1.x, point2.x) && y1 >= fmin(point1.y, point2.y) && y1 <= fmax(point1.y, point2.y)) - { - intersections.push_back(Vector::point_t{.x = x1 + center.x, .y = y1 + center.y}); - } - - if(x2 >= fmin(point1.x, point2.x) && x2 <= fmax(point1.x, point2.x) && y2 >= fmin(point1.y, point2.y) && y2 <= fmax(point1.y, point2.y)) - { - intersections.push_back(Vector::point_t{.x = x2 + center.x, .y = y2 + center.y}); - } - - return intersections; -} - -/** - * Selects a look ahead from all the intersections in the path. - */ -Vector::point_t get_lookahead(std::vector path, Vector::point_t robot_loc, double radius) -{ - //Default: the end of the path - Vector::point_t target = path.back(); - - //Check each line segment of the path for potential targets - for(int i = 0; i < path.size() - 1; i++) - { - Vector::point_t start = path[i]; - Vector::point_t end = path[i+1]; - - std::vector intersections = line_circle_intersections(robot_loc, radius, start, end); - //Choose the intersection that is closest to the end of the line segment - //This prioritizes the closest intersection to the end of the path - for(Vector::point_t intersection: intersections) - { - double intersection_dist_to_end = sqrt(pow(intersection.x - end.x, 2) + pow(intersection.y - end.y, 2)); - double target_dist_to_end = sqrt(pow(target.x - end.x, 2) + pow(target.y - end.y, 2)); - if(intersection_dist_to_end < target_dist_to_end) - target = intersection; - } - } - - return target; -} - -/** - Injects points in a path without changing the curvature with a certain spacing. -*/ -std::vector inject_path(std::vector path, double spacing) -{ - std::vector new_path; - - //Injecting points for each line segment - for(int i = 0; i < path.size() - 1; i++) - { - Vector::point_t start = path[i]; - Vector::point_t end = path[i+1]; - - Vector::point_t diff = end - start; - Vector vector = Vector(diff); - - int num_points = ceil(vector.get_mag() / spacing); - - //This is the vector between each point - vector = vector.normalize() * spacing; - - for(int j = 0; j < num_points; j++) - { - //We take the start point and add additional vectors - Vector::point_t path_point = (Vector(start) + vector * j).point(); - new_path.push_back(path_point); - } - } - //Adds the last point - new_path.push_back(path.back()); - return new_path; -} +bool TankDrive::pure_pursuit(std::vector path, double radius, double speed, double res) { + std::vector smoothed_path = PurePursuit::smooth_path_hermite(path, res); -/** - Drives through a path using pure pursuit. -*/ -void pure_pursuit(std::vector path, Vector::point_t robot_loc, double radius, double speed) -{ - Vector::point_t lookahead = get_lookahead(path, robot_loc, radius); - // Travel towards target :) + Vector::point_t lookahead = PurePursuit::get_lookahead(smoothed_path, {odometry->get_position().x, odometry->get_position().y}, radius); + //printf("%f\t%f\n", odometry->get_position().x, odometry->get_position().y); + //printf("%f\t%f\n", lookahead.x, lookahead.y); + return drive_to_point(lookahead.x, lookahead.y, speed, speed/2); } diff --git a/src/utils/pure_pursuit.cpp b/src/utils/pure_pursuit.cpp new file mode 100644 index 0000000..11aaea9 --- /dev/null +++ b/src/utils/pure_pursuit.cpp @@ -0,0 +1,236 @@ +#include "../core/include/utils/pure_pursuit.h" + +/** + * Returns points of the intersections of a line segment and a circle. The line + * segment is defined by two points, and the circle is defined by a center and radius. + */ +std::vector PurePursuit::line_circle_intersections(Vector::point_t center, double r, Vector::point_t point1, Vector::point_t point2) +{ + std::vector intersections = {}; + + //Do future calculations relative to the circle's center + point1.y -= center.y; + point1.x -= center.x; + point2.y -= center.y; + point2.x -= center.x; + + double x1, x2, y1, y2; + //Handling an infinite slope using mx+b and x^2 + y^2 = r^2 + if(point1.x - point2.x == 0) + { + x1 = point1.x; + y1 = sqrt(pow(r, 2) - pow(x1, 2)); + x2 = point1.x; + y2 = -sqrt(pow(r, 2) - pow(x2, 2)); + } + //Non-infinite slope using mx+b and x^2 + y^2 = r^2 + else + { + double m = (point1.y - point2.y) / (point1.x - point2.x); + double b = point1.y - (m * point1.x); + + x1 = ((-m * b) + sqrt(pow(r, 2) + (pow(m, 2) * pow(r, 2)) - pow(b, 2))) / (1 + pow(m,2)); + y1 = m * x1 + b; + x2 = ((-m * b) - sqrt(pow(r, 2) + (pow(m, 2) * pow(r, 2)) - pow(b, 2))) / (1 + pow(m,2)); + y2 = m * x2 + b; + } + + //The equations used define an infinitely long line, so we check if the detected intersection falls on the line segment. + if(x1 >= fmin(point1.x, point2.x) && x1 <= fmax(point1.x, point2.x) && y1 >= fmin(point1.y, point2.y) && y1 <= fmax(point1.y, point2.y)) + { + intersections.push_back(Vector::point_t{.x = x1 + center.x, .y = y1 + center.y}); + } + + if(x2 >= fmin(point1.x, point2.x) && x2 <= fmax(point1.x, point2.x) && y2 >= fmin(point1.y, point2.y) && y2 <= fmax(point1.y, point2.y)) + { + intersections.push_back(Vector::point_t{.x = x2 + center.x, .y = y2 + center.y}); + } + + return intersections; +} + +/** + * Selects a look ahead from all the intersections in the path. + */ +Vector::point_t PurePursuit::get_lookahead(std::vector path, Vector::point_t robot_loc, double radius) +{ + //Default: the end of the path + Vector::point_t target = path.back(); + + + if(target.dist(robot_loc) <= radius) + { + return target; + } + + //Check each line segment of the path for potential targets + for(int i = 0; i < path.size() - 1; i++) + { + Vector::point_t start = path[i]; + Vector::point_t end = path[i+1]; + + std::vector intersections = line_circle_intersections(robot_loc, radius, start, end); + //Choose the intersection that is closest to the end of the line segment + //This prioritizes the closest intersection to the end of the path + for(Vector::point_t intersection: intersections) + { + if(intersection.dist(end) < target.dist(end)) + target = intersection; + } + } + + return target; +} + +/** + Injects points in a path without changing the curvature with a certain spacing. +*/ +std::vector PurePursuit::inject_path(std::vector path, double spacing) +{ + std::vector new_path; + + //Injecting points for each line segment + for(int i = 0; i < path.size() - 1; i++) + { + Vector::point_t start = path[i]; + Vector::point_t end = path[i+1]; + + Vector::point_t diff = end - start; + Vector vector = Vector(diff); + + int num_points = ceil(vector.get_mag() / spacing); + + //This is the vector between each point + vector = vector.normalize() * spacing; + + for(int j = 0; j < num_points; j++) + { + //We take the start point and add additional vectors + Vector::point_t path_point = (Vector(start) + vector * j).point(); + new_path.push_back(path_point); + } + } + //Adds the last point + new_path.push_back(path.back()); + return new_path; +} + +/** + * Returns a smoothed path maintaining the start and end of the path. + * + * Weight data is how much weight to update the data (alpha) + * Weight smooth is how much weight to smooth the coordinates (beta) + * Tolerance is how much change per iteration is necessary to continue iterating. + * + * Honestly have no idea if/how this works. + * https://medium.com/@jaems33/understanding-robot-motion-path-smoothing-5970c8363bc4 +*/ +std::vector PurePursuit::smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance) +{ + std::vector new_path = path; + double change = tolerance; + while(change >= tolerance) + { + change = 0; + for(int i = 1; i < path.size() - 1; i++) + { + Vector::point_t x_i = path[i]; + Vector::point_t y_i = new_path[i]; + Vector::point_t y_prev = new_path[i-1]; + Vector::point_t y_next = new_path[i+1]; + + Vector::point_t y_i_saved = y_i; + + y_i.x += weight_data * (x_i.x - y_i.x) + weight_smooth * (y_next.x + y_prev.x - (2 * y_i.x)); + y_i.y += weight_data * (x_i.y - y_i.y) + weight_smooth * (y_next.y + y_prev.y - (2 * y_i.y)); + new_path[i] = y_i; + + change += y_i.dist(y_i_saved); + } + } + return new_path; +} + +/** + * Interpolates a smooth path given a list of waypoints using hermite splines. + * For more information: https://www.youtube.com/watch?v=hG0p4XgePSA. + * + * @param path The path of hermite points to interpolate. + * @param steps The number of points interpolated between points. + * @return The smoothed path. + */ +std::vector PurePursuit::smooth_path_hermite(std::vector path, double steps) { + std::vector new_path; + for(int i = 0; i < path.size() - 1; i++) { + for(int t = 0; t < steps; t++) { + // Storing the start and end points and slopes at those points as Vectors. + Vector::point_t tmp = path[i].getPoint(); + Vector p1 = Vector(tmp); + tmp = path[i+1].getPoint(); + Vector p2 = Vector(tmp); + Vector t1 = path[i].getTangent(); + Vector t2 = path[i+1].getTangent(); + + + // Scale s from 0.0 to 1.0 + double s = (double)t / (double)steps; + + // Hermite Blending functions + double h1 = 2 * pow(s, 3) - 3 * pow(s, 2) + 1; + double h2 = -2 * pow(s, 3) + 3 * pow(s, 2); + double h3 = pow(s, 3) - 2 * pow(s, 2) + s; + double h4 = pow(s, 3) - pow(s, 2); + + // Calculate the point + Vector p = p1 * h1 + p2 * h2 + t1 * h3 + t2 * h4; + new_path.push_back(p.point()); + } + } + //Adding last point + new_path.push_back(path.back().getPoint()); + return new_path; +} + +std::vector PurePursuit::smooth_path_cubic(std::vector path, double res) { + std::vector new_path; + std::vector splines; + + double delta_x[path.size() - 1]; + double slope[path.size() - 1]; + double ftt[path.size()]; + + for(int i = 0; i < path.size() - 1; i++) { + delta_x[i] = path[i+1].x - path[i].x; + slope[i] = (path[i+1].y - path[i].y) / delta_x[i]; + } + + ftt[0] = 0; + for(int i = 0; i < path.size() - 2; i++) { + ftt[i+1] = 3 * (slope[i+1] - slope[i]) / (delta_x[i+1] + delta_x[i]); + } + ftt[path.size() - 1] = 0; + + for (int i = 0; i < path.size() - 1; i++) + { + splines.push_back({ + .a = (ftt[i + 1] - ftt[i]) / (6 * delta_x[i]), + .b = ftt[i] / 2, + .c = slope[i] - delta_x[i] * (ftt[i + 1] + 2 * ftt[i]) / 6, + .d = path[i].y, + .x_start = path[i].x, + .x_end = path[i+1].x + }); + } + + for(spline spline: splines) { + printf("spline a: %f b: %f c: %f d %f start %f, %f end %f, %f\n", spline.a, spline.b, spline.c, spline.d, spline.x_start, spline.getY(spline.x_start), spline.x_end, spline.getY(spline.x_end)); + double x = spline.x_start; + while(x >= fmin(spline.x_start, spline.x_end) && x <= fmax(spline.x_start, spline.x_end)) { + new_path.push_back({x, spline.getY(x)}); + spline.x_start < spline.x_end ? x += res: x -= res; + } + } + new_path.push_back({splines.back().x_end, splines.back().getY(splines.back().x_end)}); + + return new_path; +} From bef47581eb8e7a59519d0c47e15f24d08aec8090 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 23 Jan 2022 14:44:09 -0500 Subject: [PATCH 046/243] Create LICENSE --- LICENSE | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) create mode 100644 LICENSE diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..5be734b --- /dev/null +++ b/LICENSE @@ -0,0 +1,21 @@ +MIT License + +Copyright (c) 2022 RIT-VEX-U + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. From 8a2d36fec60d1b646483b551678040f683d09978 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 16 Jan 2022 19:19:18 -0500 Subject: [PATCH 047/243] Added initial autonomous program --- include/subsystems/odometry/odometry_tank.h | 2 ++ include/utils/pid.h | 2 +- src/subsystems/odometry/odometry_tank.cpp | 15 +++++++++++++++ src/subsystems/tank_drive.cpp | 3 +++ src/utils/pid.cpp | 9 ++++++++- 5 files changed, 29 insertions(+), 2 deletions(-) diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index e40daff..feb31c4 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -36,6 +36,8 @@ class OdometryTank : public OdometryBase void set_position(const position_t &newpos=zero_pos) override; + double get_speed(); + private: /** * Get information from the input hardware and an existing position, and calculate a new current position diff --git a/include/utils/pid.h b/include/utils/pid.h index a2ef91d..d102db2 100644 --- a/include/utils/pid.h +++ b/include/utils/pid.h @@ -11,7 +11,7 @@ class PID public: struct pid_config_t { - double p, i, d, f; + double p, i, d, f, k; double deadband, on_target_time; }; diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 2db44bd..93e3289 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -161,4 +161,19 @@ position_t OdometryTank::calculate_new_pos(robot_specs_t &config, position_t &cu stored_rside_revs = rside_revs; return new_pos; +} + +double OdometryTank::get_speed() +{ + static position_t last_pos = get_position(); + static timer speed_tmr; + + double out = 0; + if(speed_tmr.value() != 0) + { + out = pos_diff(last_pos, get_position()) / speed_tmr.time(timeUnits::sec); + speed_tmr.reset(); + } + last_pos = get_position(); + return out; } \ No newline at end of file diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index b531ee1..d9084a7 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -233,6 +233,9 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti drive_tank(lside, rside); + printf("dist: %f\n", dist_left); + fflush(stdout); + // Check if the robot has reached it's destination if(drive_pid.is_on_target()) { diff --git a/src/utils/pid.cpp b/src/utils/pid.cpp index 4e8dd5d..9f54370 100644 --- a/src/utils/pid.cpp +++ b/src/utils/pid.cpp @@ -31,7 +31,14 @@ void PID::update(double sensor_val) else if(last_time != 0) printf("(pid.cpp): Warning - running PID without a delay is just a P loop!\n"); - out = (config.f * target) + (config.p * get_error()) + i_term + d_term; + double k_term = 0; + if(get_error() < 0) + k_term = config.k; + else if(get_error() > 0) + k_term = -config.k; + + + out = (config.f * target) + (config.p * get_error()) + i_term + d_term + k_term; last_time = pid_timer.value(); last_error = get_error(); From 745171dfd4e603e273c086c673359cc252357f04 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Tue, 18 Jan 2022 22:28:35 -0500 Subject: [PATCH 048/243] Faster initial auto --- include/subsystems/tank_drive.h | 2 +- src/subsystems/tank_drive.cpp | 35 ++++++++++++++++++++++++++++++++- 2 files changed, 35 insertions(+), 2 deletions(-) diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 16bd27d..779e0ac 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -66,7 +66,7 @@ class TankDrive * Use odometry to automatically drive the robot to a point on the field. * X and Y is the final point we want the robot. */ - bool drive_to_point(double x, double y, double speed, double correction_speed, vex::directionType direction=vex::directionType::fwd); + bool drive_to_point(double x, double y, double speed, double correction_speed, vex::directionType direction=vex::directionType::fwd, double max_accel=0); /** * Turn the robot in place to an exact heading relative to the field. diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index d9084a7..f1ad959 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -135,9 +135,12 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) * * Returns whether or not the robot has reached it's destination. */ -bool TankDrive::drive_to_point(double x, double y, double speed, double correction_speed, vex::directionType dir) +bool TankDrive::drive_to_point(double x, double y, double speed, double correction_speed, vex::directionType dir, double max_accel) { + static timer accel_tmr; + static double lside_accel = 0, rside_accel = 0; + if(!func_initialized) { // Reset the control loops @@ -154,6 +157,10 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti // point_orientation_deg = atan2(y - odometry->get_position().y, x - odometry->get_position().x) * 180.0 / PI; + accel_tmr.reset(); + lside_accel = 0; + rside_accel = 0; + func_initialized = true; } @@ -231,6 +238,32 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti lside = (lside > 1) ? 1 : (lside < -1) ? -1 : lside; rside = (rside > 1) ? 1 : (rside < -1) ? -1 : rside; + // static double last_lside = lside, last_rside = rside; + // bool decelerating = (fabs(lside) < fabs(last_lside)) && (fabs(rside) < fabs(last_rside)); + // last_lside = lside; + // last_rside = rside; + + // if(max_accel != 0 && !decelerating) + // { + // double accel_addition = max_accel * accel_tmr.time(timeUnits::sec); + // accel_tmr.reset(); + + // lside_accel += (lside > 0 ? accel_addition : -accel_addition); + // rside_accel += (rside > 0 ? accel_addition : -accel_addition); + + // printf("lside: %f, rside: %f, laccel: %f, raccel: %f\n", lside, rside, lside_accel, rside_accel); + + // if ((lside < 0 && lside_accel > lside) || (lside > 0 && lside_accel < lside)) + // lside = lside_accel; + // else + // lside_accel = lside; + + // if ((rside < 0 && rside_accel > rside) || (rside > 0 && rside_accel < rside)) + // rside = rside_accel; + // else + // rside_accel = rside; + // } + drive_tank(lside, rside); printf("dist: %f\n", dist_left); From 4d6c9a0ddbe8c0ee4af5a76d76e34cfb8406d860 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Mon, 24 Jan 2022 18:19:08 -0500 Subject: [PATCH 049/243] Created auto skills program --- include/subsystems/tank_drive.h | 13 +++++++++++++ include/utils/generic_auto.h | 3 +++ include/utils/pid.h | 2 ++ src/subsystems/tank_drive.cpp | 15 +++++++++++++-- src/utils/pid.cpp | 5 +++++ 5 files changed, 36 insertions(+), 2 deletions(-) diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 779e0ac..c584bfc 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -79,8 +79,20 @@ class TankDrive */ void reset_auto(); + /** + * Create a curve for the inputs, so that drivers have more control at lower speeds. + * Curves are exponential, with the deault being squaring the inputs. + */ static double modify_inputs(double input, int power=2); + /** + * Follow a hermite curve using the pure pursuit algorithm. + * + * @param path The hermite curve for the robot to take. Must have 2 or more points. + * @param radius How the pure pursuit radius, in inches, for finding the lookahead point + * @param speed Robot's maximum speed throughout the path, between 0 and 1.0 + * @param res The number of points to use along the path; the hermite curve is split up into "res" individual points. + */ bool pure_pursuit(std::vector path, double radius, double speed, double res); private: @@ -98,4 +110,5 @@ class TankDrive robot_specs_t &config; bool func_initialized = false; + bool is_pure_pursuit = false; }; diff --git a/include/utils/generic_auto.h b/include/utils/generic_auto.h index 80e4123..3931ab3 100644 --- a/include/utils/generic_auto.h +++ b/include/utils/generic_auto.h @@ -26,6 +26,9 @@ class GenericAuto */ bool run(bool blocking); + /** + * Add a new state to the autonomous via function point of type "bool (ptr*)()" + */ void add(state_ptr); private: diff --git a/include/utils/pid.h b/include/utils/pid.h index d102db2..d804904 100644 --- a/include/utils/pid.h +++ b/include/utils/pid.h @@ -41,6 +41,8 @@ class PID */ double get_error(); + double get_target(); + /** * Set the target for the PID loop, where the robot is trying to end up */ diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index f1ad959..f394e30 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -220,7 +220,7 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti // Disable correction when we're close enough to the point double correction = 0; - if(fabs(dist_left) > config.drive_correction_cutoff) + if(is_pure_pursuit || fabs(dist_left) > config.drive_correction_cutoff) correction = correction_pid.get(); // Reverse the drive_pid output if we're going backwards @@ -329,10 +329,21 @@ double TankDrive::modify_inputs(double input, int power) } bool TankDrive::pure_pursuit(std::vector path, double radius, double speed, double res) { + is_pure_pursuit = true; std::vector smoothed_path = PurePursuit::smooth_path_hermite(path, res); Vector::point_t lookahead = PurePursuit::get_lookahead(smoothed_path, {odometry->get_position().x, odometry->get_position().y}, radius); //printf("%f\t%f\n", odometry->get_position().x, odometry->get_position().y); //printf("%f\t%f\n", lookahead.x, lookahead.y); - return drive_to_point(lookahead.x, lookahead.y, speed, speed/2); + bool is_last_point = (path.back().x == lookahead.x) && (path.back().y == lookahead.y); + + if(is_last_point) + is_pure_pursuit = false; + + bool retval = drive_to_point(lookahead.x, lookahead.y, speed, 1); + + if(is_last_point) + return retval; + + return false; } diff --git a/src/utils/pid.cpp b/src/utils/pid.cpp index 9f54370..9fcfd34 100644 --- a/src/utils/pid.cpp +++ b/src/utils/pid.cpp @@ -91,6 +91,11 @@ double PID::get_error() return target - sensor_val; } +double PID::get_target() +{ + return target; +} + /** * Set the target for the PID loop, where the robot is trying to end up */ From 482db9cbf1f86d30cc7a6b41a34be33a171bf2c8 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 6 Feb 2022 12:32:12 -0500 Subject: [PATCH 050/243] Post WPI squash commit --- include/subsystems/tank_drive.h | 2 +- src/subsystems/tank_drive.cpp | 61 +++++++++++++++++---------------- 2 files changed, 33 insertions(+), 30 deletions(-) diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index c584bfc..90d6386 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -66,7 +66,7 @@ class TankDrive * Use odometry to automatically drive the robot to a point on the field. * X and Y is the final point we want the robot. */ - bool drive_to_point(double x, double y, double speed, double correction_speed, vex::directionType direction=vex::directionType::fwd, double max_accel=0); + bool drive_to_point(double x, double y, double speed, double correction_speed, vex::directionType direction=vex::directionType::fwd); /** * Turn the robot in place to an exact heading relative to the field. diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index f394e30..a7a2d3a 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -70,6 +70,14 @@ bool TankDrive::drive_forward(double inches, double speed, double correction, di { static position_t pos_setpt; + // We can't run the auto drive function without odometry + if(odometry == NULL) + { + fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); + fflush(stderr); + return true; + } + // Generate a point X inches forward of the current position, on first startup if (!func_initialized) { @@ -99,6 +107,14 @@ bool TankDrive::drive_forward(double inches, double speed, double correction, di */ bool TankDrive::turn_degrees(double degrees, double percent_speed) { + // We can't run the auto drive function without odometry + if(odometry == NULL) + { + fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); + fflush(stderr); + return true; + } + // On the first run of the funciton, reset the gyro position and PID if (!func_initialized) { @@ -135,10 +151,16 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) * * Returns whether or not the robot has reached it's destination. */ -bool TankDrive::drive_to_point(double x, double y, double speed, double correction_speed, vex::directionType dir, double max_accel) +bool TankDrive::drive_to_point(double x, double y, double speed, double correction_speed, vex::directionType dir) { + // We can't run the auto drive function without odometry + if(odometry == NULL) + { + fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); + fflush(stderr); + return true; + } - static timer accel_tmr; static double lside_accel = 0, rside_accel = 0; if(!func_initialized) @@ -157,7 +179,6 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti // point_orientation_deg = atan2(y - odometry->get_position().y, x - odometry->get_position().x) * 180.0 / PI; - accel_tmr.reset(); lside_accel = 0; rside_accel = 0; @@ -238,32 +259,6 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti lside = (lside > 1) ? 1 : (lside < -1) ? -1 : lside; rside = (rside > 1) ? 1 : (rside < -1) ? -1 : rside; - // static double last_lside = lside, last_rside = rside; - // bool decelerating = (fabs(lside) < fabs(last_lside)) && (fabs(rside) < fabs(last_rside)); - // last_lside = lside; - // last_rside = rside; - - // if(max_accel != 0 && !decelerating) - // { - // double accel_addition = max_accel * accel_tmr.time(timeUnits::sec); - // accel_tmr.reset(); - - // lside_accel += (lside > 0 ? accel_addition : -accel_addition); - // rside_accel += (rside > 0 ? accel_addition : -accel_addition); - - // printf("lside: %f, rside: %f, laccel: %f, raccel: %f\n", lside, rside, lside_accel, rside_accel); - - // if ((lside < 0 && lside_accel > lside) || (lside > 0 && lside_accel < lside)) - // lside = lside_accel; - // else - // lside_accel = lside; - - // if ((rside < 0 && rside_accel > rside) || (rside > 0 && rside_accel < rside)) - // rside = rside_accel; - // else - // rside_accel = rside; - // } - drive_tank(lside, rside); printf("dist: %f\n", dist_left); @@ -286,6 +281,14 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti */ bool TankDrive::turn_to_heading(double heading_deg, double speed) { + // We can't run the auto drive function without odometry + if(odometry == NULL) + { + fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); + fflush(stderr); + return true; + } + static bool initialized = false; if(!initialized) { From e24602b236e048752d272881963cafdde867bd3b Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 6 Feb 2022 16:07:43 -0500 Subject: [PATCH 051/243] Created new generic lift class in Core --- include/subsystems/lift.h | 257 ++++++++++++++++++++++++++++++++++ src/subsystems/tank_drive.cpp | 7 +- 2 files changed, 258 insertions(+), 6 deletions(-) create mode 100644 include/subsystems/lift.h diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h new file mode 100644 index 0000000..27d12ab --- /dev/null +++ b/include/subsystems/lift.h @@ -0,0 +1,257 @@ +#pragma once + +#include "vex.h" +#include "../core/include/utils/pid.h" +#include +#include +#include + +using namespace vex; +using namespace std; + +/** + * LIFT + * A general class for lifts (e.g. 4bar, dr4bar, linear, etc) + * Uses a PID to hold the lift at a certain height under load, and to move the lift to different heights + * + * @author Ryan McGee + */ +template +class Lift +{ + public: + + struct lift_cfg_t + { + double up_speed, down_speed; + double softstop_up, softstop_down; + + PID::pid_config_t lift_pid_cfg; + }; + + /** + * Construct the Lift object and begin the background task that controls the lift. + * + * Usage example: + * /code{.cpp} + * enum Positions {UP, MID, DOWN}; + * map setpt_map { + * {DOWN, 0.0}, + * {MID, 0.5}, + * {UP, 1.0} + * }; + * Lift my_lift(motors, lift_cfg, setpt_map); + * /endcode + * + * @param lift_motors + * A set of motors, all set that positive rotation correlates with the lift going up + * @param lift_cfg + * Lift characterization information; PID tunings and movement speeds + * @param setpoint_map + * A map of enum type T, in which each enum entry corresponds to a different lift height + */ + Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map setpoint_map) + : lift_motors(lift_motors), cfg(lift_cfg), lift_pid(cfg.lift_pid_cfg), setpoint_map(setpoint_map) + { + + is_async = true; + setpoint = 0; + + // Create a background task that is constantly updating the lift PID, if requested. + // Set once, and forget. + task t([](void* ptr){ + Lift &lift = *((Lift*) ptr); + + while(true) + { + if(lift.get_async()) + lift.hold(); + + vexDelay(50); + } + + return 0; + }, this); + + } + + /** + * Control the lift with an "up" button and a "down" button. + * Use PID to hold the lift when letting go. + * @param up_ctrl + * Button controlling the "UP" motion + * @param down_ctrl + * Button controlling the "DOWN" motion + */ + void control_continuous(bool up_ctrl, bool down_ctrl) + { + static timer tmr; + + double cur_pos = 0; + + // Check if there's a hook for a custom sensor. If not, use the motors. + if(get_sensor == NULL) + cur_pos = lift_motors.rotation(rev); + else + cur_pos = get_sensor(); + + if(up_ctrl && cur_pos < cfg.softstop_up) + { + lift_motors.spin(directionType::fwd, cfg.up_speed, volt); + setpoint = cur_pos; + + // Disable the PID while going UP. + is_async = false; + } else if(down_ctrl && cur_pos > cfg.softstop_down) + { + // Lower the lift slowly, at a rate defined by down_speed + setpoint -= tmr.time(sec) * cfg.down_speed; + is_async = true; + } else + { + // Hold the lift at the last setpoint + is_async = true; + } + + tmr.reset(); + } + + /** + * Control the lift in "steps". When the "up" button is pressed, the lift will go to the next + * position as defined by pos_list. Order matters! + * + * @param up_step + * A button that increments the position of the lift. + * @param down_step + * A button that decrements the position of the lift. + * @param pos_list + * A list of positions for the lift to go through. The higher the index, the higher the lift should be (generally). + */ + void control_setpoints(bool up_step, bool down_step, vector pos_list) + { + // Make sure inputs are only processed on the rising edge of the button + static bool up_last = up_step, down_last = down_step; + + bool up_rising = up_step && !up_last; + bool down_rising = down_step && !down_last; + + up_last = up_step; + down_last = down_step; + + static int cur_index = 0; + + // Avoid an index overflow. Shouldn't happen unless the user changes pos_list between calls. + if(cur_index >= pos_list.size()) + cur_index = pos_list.size() - 1; + + // Increment or decrement the index of the list, bringing it up or down. + if(up_rising && cur_index < (pos_list.size() - 1)) + cur_index++; + else if(down_rising && cur_index > 0) + cur_index--; + + // Set the lift to hold the position in the background with the PID loop + set_position(pos_list[cur_index]); + is_async = true; + + } + + /** + * Enable the background task, and send the lift to a position, specified by the + * setpoint map from the constructor. + * + * @param pos + * A lift position enum type + * @return True if the pid has reached the setpoint + */ + bool set_position(T pos) + { + this->setpoint = setpoint_map[pos]; + is_async = true; + + return (lift_pid.get_target() == this->setpoint) && lift_pid.is_on_target(); + } + + /** + * Manually set a setpoint value for the lift PID to go to. + * @param val + * Lift setpoint, in motor revolutions or sensor units defined by get_sensor. Cannot be outside the softstops. + * @return True if the pid has reached the setpoint + */ + bool set_setpoint(double val) + { + this->setpoint = val; + return (lift_pid.get_target() == this->setpoint) && lift_pid.is_on_target(); + } + + /** + * @return The current setpoint for the lift + */ + double get_setpoint() + { + return this->setpoint; + } + + /** + * Target the class's setpoint. + * Calculate the PID output and set the lift motors accordingly. + */ + void hold() + { + lift_pid.set_target(setpoint); + + if(get_sensor != NULL) + lift_pid.update(get_sensor()); + else + lift_pid.update(lift_motors.rotation(rev)); + + lift_motors.spin(fwd, lift_pid.get(), volt); + } + + /** + * @return whether or not the background thread is running the lift + */ + bool get_async() + { + return is_async; + } + + /** + * Enables or disables the background task. Note that running the control functions, or set_position functions + * will immediately re-enable the task for autonomous use. + * @param Whether or not the background thread should run the lift + */ + void set_async(bool val) + { + this->is_async = val; + } + + /** + * Creates a custom hook for any other type of sensor to be used on the lift. Example: + * /code{.cpp} + * my_lift.set_sensor_function( [](){return my_sensor.position();} ); + * /endcode + * + * @param fn_ptr + * Pointer to custom sensor function + */ + void set_sensor_function(double (*fn_ptr) (void)) + { + this->get_sensor = fn_ptr; + } + + private: + + motor_group &lift_motors; + lift_cfg_t &cfg; + PID lift_pid; + map &setpoint_map; + + atomic setpoint; + atomic is_async; + + double (*get_sensor)(void) = NULL; + + + +}; \ No newline at end of file diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index a7a2d3a..8a9a195 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -160,9 +160,7 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti fflush(stderr); return true; } - - static double lside_accel = 0, rside_accel = 0; - + if(!func_initialized) { // Reset the control loops @@ -179,9 +177,6 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti // point_orientation_deg = atan2(y - odometry->get_position().y, x - odometry->get_position().x) * 180.0 / PI; - lside_accel = 0; - rside_accel = 0; - func_initialized = true; } From e5596e4a7dc4e0dfdedcce1db84705e66d4d7a96 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Wed, 9 Feb 2022 10:53:25 -0500 Subject: [PATCH 052/243] Added homing function to Lift --- include/subsystems/lift.h | 45 ++++++++++++++++++++++++++++++++++++--- 1 file changed, 42 insertions(+), 3 deletions(-) diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index 27d12ab..a44d206 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -50,8 +50,8 @@ class Lift * @param setpoint_map * A map of enum type T, in which each enum entry corresponds to a different lift height */ - Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map setpoint_map) - : lift_motors(lift_motors), cfg(lift_cfg), lift_pid(cfg.lift_pid_cfg), setpoint_map(setpoint_map) + Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map setpoint_map, limit *homing_switch=NULL) + : lift_motors(lift_motors), cfg(lift_cfg), lift_pid(cfg.lift_pid_cfg), setpoint_map(setpoint_map), homing_switch(homing_switch) { is_async = true; @@ -208,6 +208,33 @@ class Lift lift_motors.spin(fwd, lift_pid.get(), volt); } + /** + * A blocking function that automatically homes the lift based on a sensor or hard stop, + * and sets the position to 0. A watchdog times out after 3 seconds, to avoid damage. + */ + void home() + { + static timer tmr; + tmr.reset(); + + while(tmr.time(sec) < 3) + { + lift_motors.spin(directionType::rev, 6, volt); + + if (homing_switch == NULL && lift_motors.current(currentUnits::amp) > 1.5) + break; + else if (homing_switch != NULL && homing_switch->pressing()) + break; + } + + if(reset_sensor != NULL) + reset_sensor(); + + lift_motors.resetPosition(); + lift_motors.stop(); + + } + /** * @return whether or not the background thread is running the lift */ @@ -240,18 +267,30 @@ class Lift this->get_sensor = fn_ptr; } + /** + * Creates a custom hook to reset the sensor used in set_sensor_function(). Example: + * /code{.cpp} + * my_lift.set_sensor_reset( my_sensor.resetPosition ); + * /endcode + */ + void set_sensor_reset(void (*fn_ptr) (void)) + { + this->reset_sensor = fn_ptr; + } + private: motor_group &lift_motors; lift_cfg_t &cfg; PID lift_pid; map &setpoint_map; + limit *homing_switch; atomic setpoint; atomic is_async; double (*get_sensor)(void) = NULL; - + void (*reset_sensor)(void) = NULL; }; \ No newline at end of file From c69dc43e4541a22fe92e0ff88995324c54c843a1 Mon Sep 17 00:00:00 2001 From: Dana Date: Wed, 23 Feb 2022 20:10:40 -0500 Subject: [PATCH 053/243] debugging in progress --- include/subsystems/lift.h | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index a44d206..cc0194b 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -2,6 +2,7 @@ #include "vex.h" #include "../core/include/utils/pid.h" +#include #include #include #include @@ -100,12 +101,15 @@ class Lift lift_motors.spin(directionType::fwd, cfg.up_speed, volt); setpoint = cur_pos; + std::cout << "DEBUG OUT: UP " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n"; + // Disable the PID while going UP. is_async = false; } else if(down_ctrl && cur_pos > cfg.softstop_down) { // Lower the lift slowly, at a rate defined by down_speed - setpoint -= tmr.time(sec) * cfg.down_speed; + setpoint = setpoint - (tmr.time(sec) * /*cfg.down_speed*/ 2.4); + std::cout << "DEBUG OUT: DOWN " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n"; is_async = true; } else { @@ -199,12 +203,15 @@ class Lift void hold() { lift_pid.set_target(setpoint); + std::cout << "DEBUG OUT: SETPOINT " << setpoint << "\n"; if(get_sensor != NULL) lift_pid.update(get_sensor()); else lift_pid.update(lift_motors.rotation(rev)); + std::cout << "DEBUG OUT: ROTATION " << lift_motors.rotation(rev) << "\n\n"; + lift_motors.spin(fwd, lift_pid.get(), volt); } From c37391f885cdf32cd1eaf1a4182dcd8fe1682803 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 24 Feb 2022 22:06:17 -0500 Subject: [PATCH 054/243] Fixed everything (ready for comp kinda) --- include/subsystems/lift.h | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index cc0194b..351c41f 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -99,17 +99,18 @@ class Lift if(up_ctrl && cur_pos < cfg.softstop_up) { lift_motors.spin(directionType::fwd, cfg.up_speed, volt); - setpoint = cur_pos; + setpoint = cur_pos + .3; - std::cout << "DEBUG OUT: UP " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n"; + // std::cout << "DEBUG OUT: UP " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n"; // Disable the PID while going UP. is_async = false; } else if(down_ctrl && cur_pos > cfg.softstop_down) { // Lower the lift slowly, at a rate defined by down_speed - setpoint = setpoint - (tmr.time(sec) * /*cfg.down_speed*/ 2.4); - std::cout << "DEBUG OUT: DOWN " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n"; + if(setpoint > cfg.softstop_down) + setpoint = setpoint - (tmr.time(sec) * cfg.down_speed); + // std::cout << "DEBUG OUT: DOWN " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n"; is_async = true; } else { @@ -203,14 +204,14 @@ class Lift void hold() { lift_pid.set_target(setpoint); - std::cout << "DEBUG OUT: SETPOINT " << setpoint << "\n"; + // std::cout << "DEBUG OUT: SETPOINT " << setpoint << "\n"; if(get_sensor != NULL) lift_pid.update(get_sensor()); else lift_pid.update(lift_motors.rotation(rev)); - std::cout << "DEBUG OUT: ROTATION " << lift_motors.rotation(rev) << "\n\n"; + // std::cout << "DEBUG OUT: ROTATION " << lift_motors.rotation(rev) << "\n\n"; lift_motors.spin(fwd, lift_pid.get(), volt); } From 03e55db9fe821d47451d5421a0da63b768e9ec7b Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Tue, 1 Mar 2022 13:05:37 -0500 Subject: [PATCH 055/243] Post competition commit --- include/subsystems/lift.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index 351c41f..29b9767 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -51,7 +51,7 @@ class Lift * @param setpoint_map * A map of enum type T, in which each enum entry corresponds to a different lift height */ - Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map setpoint_map, limit *homing_switch=NULL) + Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map &setpoint_map, limit *homing_switch=NULL) : lift_motors(lift_motors), cfg(lift_cfg), lift_pid(cfg.lift_pid_cfg), setpoint_map(setpoint_map), homing_switch(homing_switch) { From 3484b6c801e751a27c6ed64724413cc9cce98371 Mon Sep 17 00:00:00 2001 From: Dana Date: Thu, 3 Mar 2022 20:34:35 -0500 Subject: [PATCH 056/243] removed pathfinder --- lib/libpathfinder.a | Bin 31010 -> 0 bytes 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 lib/libpathfinder.a diff --git a/lib/libpathfinder.a b/lib/libpathfinder.a deleted file mode 100644 index f96adc441fd3bad6c48253e7f03d119a70606a7b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 31010 zcmd^oe{j@CmS2x%1Of>&ti>X)WP1Ps@>;MXA+T6eyTgJFtneK+(<(xE&Z*XUt9i_NT#W&tFMXH z?x?G&iA170$o-8(>K`+3B+|TGDYZeV;G5aM`~Os_yZIhHrWC*0chcX^KUPY<-3W8P zXU;0c@7ay!JNElZ@r(aPyrXF#-qY3F-qhOH*WWgv(jIN?{axSj!%el0PfPD}J?#$M z)-{l5>1}nr;{AQk^|ucUGEMmMR(b>_}i&``dpe8LnUH=RPOMAApXZ7|xn_34@`>go> zppL$tp1$v1!?MabS0WP+xw4qB|!BP$GTccLf13iuSw{7eftDx2Fzo9CwkkO z`diw%T6zame{Gv;tL^1?Y*si2+tj&>w3Jet*hfy)4+Gz`@hrP)Yjh7a-t{U z#>qf%1H2-qbAGP9x4mDNIPGWSqu+HaWxDc~J{hSsb=$XY+g`K1W?SY6t%*jrZ{Hq? z)J3<~nK9kG{QFNFcrp+OV4xZkP*o}oDK)lC`xn+}t4iIcinXig+EWv1-{xP0u3VU? zhr3=CPlm!TPL!zUr&bSMnm*S3+Vr0ezC9EE+rODvg5gKMk-`6<;XpL`zKSOQVj%j< zzd~X+0pC#S&<#u%%ZYc$iHov4JG$X&st|Z80zBZ(etq{1_PUz`?=t>80I-;orS|CfHbR{2DjF4`E^tZkQonVWW)$|D}x6xNRobVB-u{!jE{{ zXO;;b;lb@Qg~)Gg{nb=~N~VJ0Wa?M9Z~ygtpdsb=n=5EY1-p^2EmtARvy5(}vlr9ByFx_qD`;(n2MjW%whrRU&dGn%Hh&YG6CE^8h=^qJ64q3oe6Km0T-WuJ|pf6$c1 zw57t(0qPvLuwh?Ubmm^3x&up;;ReW;K4lV5J{-n}es}S!OK1M);E!jPp&t$bz7}~u zHNUPQMfY{M=hhqdwYBiK?(1;RRa*ab@E3O_{5LeDWQ@;89Jk{?w~^zjAvGKMI5mp6 zw_uOKo?QzVc(-6n8nf#VhA}q^d_5+Yq|=<+)Q~F27%SI(apTOB>>p^;HI^o%lNp<5 z_4wwzQx+|rd=&Fenbf_Tb?4YTJF`a50e3Ff7|Q1_(;Uk50Lt-zEl1@Y%JCrbco4Yk z&+KRA8ux`6GpAsFL-;7_HHR_4G6te&CRpaONV#sWpn4|t=eKWvvKndV`48jcVYXek zd~yu&ZdLvyMO((9?g!`In^IoCo&CBQe=6qoSN02;M~+4>dHrG~%M-b(+j|T)+j?{@ zV9;R<_B`y-b%4>Pqm_VROWV2a&-#cz+fCdY>uhuO1=5y%VH9bwFO0$V_l40A@XRfLt^)P7iux*2uEN!sTwln+sYRoUD-<+LUJ^11@`$iS$ycK<;%IO;thwH;) zGeu6dk<|yhv zhjBZGF-MxR4(vOuQx*CS+mwChr|3H@C&#s{V|#5{E4X&+dAEF;YZ=!D&arz3w_%Mu zJ5z%4JlXx&jL>8S$|7qW$7e>L!@A|oJ-WlC`(5l(;Q1?op<#Lt(S0R2M7Q=28h`D+ z;<&9p@o0Vw=Ai`kxdNmybZO{dP^mJ&pTVvq0vMJk?Y+Bqe>GBt-w62l$dk|Pek4-2 zWyh8pwW}7PE$uDGx>TSF&ceqw?@~*aFWprXSXQvS;0vMB!0N!7U|HaSz?TZjgAXlP z7f@RUP90CQ9D|+cH+HAE`rCW9B-&3V)RwlEM2p&TY+yib+4am*Tj0kS3^!m`+ex*h zweR@xcI+Is^!6p%x9t6mf3z7Jkk)P!r6rN*?>csZn~Z$T!$1T{SZ!_U@q4n!0Fu;`TFjS* zlN0dbr!|E31fImDm*71Pw_A^sPCZBismC|rX1=;Fz^*`~FTobWFn))uE&kix#GSBK zxKY=*i-$SGGfazS6+WQ};Vz`-wx;0G7Mc*R1Pu{|2gaiMB0kn5jE}`})7yEUQlsz_ zBk2h&w(B2Ke{);>X$N)9(>}qB92g!_m|GkZ(B-<~CF(gePEZx<@N@)l{Ei8tcd}k- zvqY!Qv22Vw`o5FTGPgac?E;30u$mGZ8YQ_^c%u$v;n^hIuV|t4Y+x!frn@V zruj1HsLcartbQ3`>^1b~oJyGOM3}a!FzXayICXf0HsDGNS6R5)!d-o7xj+QQNbl-* z)Idn*%I!opux&?u-m-xMm`7kd*}zJaTJ~eyTNYujP!cYlECN5VerGZ@5c%a_mB6hc z?@!Vuk5L5v;u}@TR6oMRzd-yeGyQ|sUvOog$i0>1%Y9%O@+D7J1pb9~32e~sCi4tN zTPM!cBvWDd5hiaOjGi7>(Z84sV!srI-xszfQ!E$#nTC{=>F6{dtN3g1LabL%B~xxW zW{Wrfq6~ZMI+TO^{i;au3tyJ_+CN;kmJ~N^5>XWIR7Ox)m zPT;BNPc%+};M65kdn`^2_8tc(XmNtr_Z_e}`(Ph%a6%Sm-Fe6>hR>zeUrwe@QWj(L zDU|R|gm<1ztv{Jeea8u3BH?=weqcDY{%|staKe{H&rDQCP;Rty8TRtC#qUkAjl$SR z7J)WwqX^qbL7o#%-r&BSc3HT15<~B1S-5<1X}D$L`BlkO1^fs{6#7eeXk3MVHu-IZ zvI4(i1pcuD6Or+riB+I)xb93U`n5BuaCI^@iZlz<#qnVH56784(+Gs0pI{z3ef9K> zPc1(yyk`;08peJ{`cf&|5OK-#az8@;Sa97ozgv9S=W`D=uNqQe^pP>x+4kaL^h5f4 zdojBgr~HlMs|a+-7B8EhKaFOjaRg}`1x=b!hLUK*L^IM885Uvo?*M2Wg6!=G`nygy zYQ|O^ZKcNm#>-KZljG&^2;z(XY(@Kb)}`l>2>M?PeI&yEhk2x@(##`I{8__9$;g3; zB7FJGCr^A0_|e@H1r7I4i~Cya{gk*18ej7KL)~fjlEJk5+UYd@^N52-7@ISRs$vbom%oit$*B*#--1Iep$ zon7n0!&trL^V4$ebv`_d;afgGj_cX=K0L}l;itzX#?fUvjyQJqV=RR*jusp5>>H#v z$34&Eu&r3m^w>YyuiW{-?O%a%&=~nKF8dkd{`T$LU-Hip?;^oh@Fnma#8-{42;Zjx zrAF{Qq2+o1d5B$omv%otO!oqLo-5nS;(pSkvmh?hqP*{}0kGB){E$q+s!9EHB%VF4UiRzQpr>f(916_%(zTWEZwD7_$60pobIa9+j_PcGT6Dra+^?$)vcJ!WD*vHnkvwHqJ0uanj+4QjasBT_W=Wc-jhh%uRTLLZ^6f~bNCp(12&0EIT+z52wOw^qxd*q zz5$!zov=A?MlE~-Hs?=)PXp#W%K4J`7hyL8-ecicVRK%sLL7$w5nwUQ52{{zzU5lM z@SjN_Y=-}Le4K~dYgHNE14ttI^7Gf=X#UwFK z_(9-fvY>4CFm1p+79O_nWedM;;g2l*sfFh)T#8}J_|>$L-X04dwQ$11=PmrYh39BP z7R*6gf%T_~HsCtiSfCDC_^5?XT6oyPNejPa;SVi5YT;Q6&s(?*{haAn(nk6*3m>p> z6&5_!qZIv{GUjU9>p&maK};1#to<_mE3wYd-k{V7?Tt!ZxA2sOd4R(3Fl~faS-9T9 z2QA!e;gc3VXW^uUuUPm)3tzYJ2vo@`HYqhvy9yuXIhHeG?MiD`S-aZWQES&(yWZOD zLzIPUgY^RB@MPzn3?1t$no4~cG)0%v;T0B+SQtgo{!we!(FT6Kg*lfIj#+q*h4)$b zfQ1iQnCmq0k64&|KcW{jJ!~V!siMAP(ez2lAEw zVeiEBxL1-ialGQm6Lor#)8nRW7bYVk7bXg@msu!J6#1f&E3!<@(F>E*y}Pw>q25$b zU7iXqq9>(g8jcPE>E_CKGw2q1X)=L4NiUpdzsd5lKBU+E(1&;!`WAbktK-*6q^_aH zh5Ug!hI6Cen)R1MvuBs@1R=x@MmYFV6_8fqtg(7sKQH#W+$V z?z=hXiIMX8_bTUsM_x$s6THXaho!+YbEpUBO4b8TuO8oon{k;x&1IyQZ4Yt?VUh>& z{-YF>0E~pS!i~DdwI_avw^abxg6G$p_yzDZV_|UxkG7i?*L5bsEf7D}m-S~|g~o8I z^QdGq9o9&C0*meX-^(6Ek0D9StDW)S9t7$tj$z@`hI^9CaJEd^EZifo=cP>$i$3>Z zG#t<5xi?#Pk%jl`Q1e4Nr57^cd>uZ}cNM^85q&|mx%31|k#B`LYfi84s3hBo>nLl$ z^__GhY;PIJvWheBJL|*OZj0u9=3QdQow2SW+l;l9`tY(w6piD&)6v_N^@rgf$=>YdJVz|P3w)lp)M1T~IiKr?3v*qj zj-S>wg+3q45rzz1+bECLg@;}r;n3h2t84!lbY+cR-`?&YnK&BP;4J|j^U&)RWSZI5 zS&?za{(qq%>VFNo%ha3n=!Leb)B2a2px6H+=)4v&;a{J%u}3$!dNu) zI{P`+AHD7@oU+3B`JgBk*k;g+Gy~~8{=v@&g@pkD4h?Z>{CrR@Jn|uoBWphKDw%*a zlDwY}szU(VQSuW!KOb}v^{59P>%rBQc&xLZ4?2K=eE6Ua$p~rCNdB#GgRCAOM7(_X zpnnCteE6W9kR!yA8F?V`5G+PEKIkn}ZWv)=qf4vzVP4i!5*XIv0a%LDs$el%)CxX<;ffpN8b%ixsItdDXDZ>t94K- zP?=7YtpWu39&Ip?uUPmk3%`sy5$`S9z#E|ryfF*UT6hTbqwG)XTT+P`#+B)?PiEu! zNKfL4Z09&6ktY&eJ;DSo#sk)DughDuQfd0o0v=F!7s?B?-WYhSvdslI_EbJ`56EORjm0yUg+% z#(rV(J7_~4F_Yf1|Ks!|9k!K1x_X_o=d#)lKkOeoTm7-Me_hWt|Dk0BTqn4X5`(E! zn+0p5-PbI(HpZN^n2><}wJ{f7)W(r%k$B8g496Rde{DPfyfXMpeuC#;8|zUI=CRn? z$n%?g*2dqF3|S}`0bAk5IErge{17jnwed&5%V%xm8N(28xi)ft%=&W9;VOZAJu`}B zsL_Mc<#W8WQ_4-?Ue-ppjhGA9>t-gVjhnhzD>G#R3)jlb@FlvvIA)D8>AxW$@?-uS z%f^`STLOBmVm$6f=D<9;c1FCk44ugniXq)8gD37me8i8z7Q^s=jF07$aOEusvRGy= zf*rU~pKBH5djnY)$f$mXK=YCn_nX|kwF(On`-rR4UqlqFX)GV{($5c=Rcf&{YHNKB zZtv49F8?1h>`Try>J_XV7oqp{a=3W%l}NFtLx%HUPX>Px`e>BtpU+dKKL%aIdFUqT z`-HH0mvkO_PWnzNY~IP7hb|QFXwJdrolWkWsS7*@Tl5rPw)s+biRTH6=`Fc>Nz`S1 zg}Q{0$A9GLvT_f~^||21&C?~&Q|tsBNB!l^0?Jy<{cYY~FUETTl*RMgh2mhmvM1#|V(#VjzE-D)JMh@^|MW$32NNR|YyYKb%qce)OaJM+ zNT2sqS)XORXW4yrhWlxKPubpYUW0P|bnt)8T>R>qnJS$7u>QKfi{MrRcLi|G+XU%! z`DQ^CXkSg*qtEEO;kX~Y0(IwEh0w#zm-id0fZqd~@j7AG!)}93IRWnni+pMhZmsvq z{)N6Y2RqKZ&_{Z*_7S7Q8dv3$CD5ZRc=5f@7QTmI(SN^f`&ZLpjX#(!CT$xx%#;A{`|H0kkr6)l1JM1SqpxkBxesz4SI?CATHh99EL3E`z-xFf!~vS!-2H7XPR?J18X_PA;$v7ENEAV``x?~#JV8vCv-nl zyIbEOsz#fzuk+ml&S%V@iS;eR-=hI&r63PBcgM|{DC1JUl<9H)NC4*CJ%zd3D>rCi z;+)lcqcCxB<{Yu(BY}7qzii&3(0J%a=8cYxGezh-e*F6}C$iieFA+PQiu8EdK68Zo zsO}f=E&|#Hvd7hy&Xiqeq!T_po&lq7eA|L@^9+CBN&lh_a7Gy7EGS3!52o)&o?I`? zdjw}^mizP05^p);t@6by@yA11I8G_+_m_inDCg3}&es`_?ZvUkvU5zcy&gb&RVz;i zSkDczZ%xaMy?gxVCfa1|6~A$*;Q689q5pE_in%4M^?`%04HGllo|60~`B2JSDqvTG z;i`iDdEQ%I)J!IcU}TWA{d>zJ5RC1EKWT@#Q}d~ew!y+6r#2rtY0-nYH2%G1F1#pk z83*%;HpHVYjTkhSHvYZkJn$k2k^BVDzqd>}^|+JVwF10wK6}gmm-qIQs4VxE+#9gI zwEcU_w}9{_{KW`;1Qy%%zn8sbrrgv`&Fm#b?rHKXlx(%l^XJTP0~blBLaQ=;SMEyu z^m`Nj{LDs1GRY=~rOc0p^8xpQn>1v8NXM_?V^|qFBEt`xApOhmf8v9G8?c^JP!!@* zKES!94Ikk@@ZrDega3^Wb~k#m`^@roUDhq8z9paDDB|9{dD2dcU|ZX}dU&JV32%kE zW}c7R9dAEA(4N4?7|-~%8dXf_P@>M<%YJ0-5NJl-M!qXS`+L^z;hc-Ttk%7xjwWbB z9nEHpUFvYsczaFBfC0s zBj9^wKd=+)oU0?Z$F6&rTi;=r=uqtpgYR{8&(;vEa!@w0?JNl8<)V1RtiE?nmvt#cI*yt{p z^J9$*-m|a)IMB6QrT4>WUAyAOOL&6|d_VS6D;oH|6WsdEKcj2MeFED;>(qgN8ryW$ zYa9COyI|n&bUC3*NnJZr<}*4B{r@Im=_k@h?p4<=hVjYu`}4}{)S>Ep`$P=q7aBjW zQ-=)`*_g$6op+tIm=4IRji1-ag%`DPBpKpyE)yf=^Yc2Rz~dSu`3at%*WuZ074TS( zJMlW7BE5WgonJ{oZ2=|!R=}7Rs>X1&?dCnLbTm4FIl_Vg!%2o7HF`Jm5)Q zhac<9`ulku>cIa~_=}PB1Qy%%zZYJoSQ65`1{pC{=2Lr{EhgTI(9$8yFd9)@i$4)xyYQQASb(841rL4%eXnK}Pbd za~_eFiKv+94OD?&k~fq1CQK>fSCGenTn+R7m&i9M%9&w@U{ilizj+C{C1ufk3#KGo zuH`bN;1MZfb!9NF48?WpF@>LNn5aL`JViZdkbWO7xBMgoh9V!HBJM7bNLyAHKTnYh z&(Bj3FCU)b9PsktDN0a@e0YjikX}AK#lO!{-&WKeK^{**ynJ{H44S-nigQ?YBOosM z37%u;;wjz$59RLlr9BWO!?^zU!c#2wrN(l7=rKWV>W0T)c-k!FF*3u=yN4XB#`x1) zTwcPyLBll2b39@|{mZZzK8CfyX1KD8yvK5MG-bSB?>%szgRO9G17yTQ@~R4LTw#?D zJbnX((ENtw-RaMHiD&8dG5o%M%W^DwW?r`~Z+SqNgW4|-0I$I}%MO9pP~bH};5CZC zYm|W32w`3im~%axp^e}8L+~8hk8iw0@a{Iw0E0OH!FzV&!P?AoFNRlgKF8iw;_#fr zJsT685O8F_$a8X@zwlk>81m!$b7> zPEfsyy9no}=5fv^cND_WVegK@O7-$o(ND@Jcj8Sq;;_smtIT@CH(_+W!Y}E!^%l?| z`uun>oYe6SV(%V6T*CUSlhdm>hV4JmEb-{2z6ta3peJVjtQdTN%a>P8kzrOI0Jo4$oxH z<;&2YhN!o(vx#H$|tDHmr32>_rhrHn!Xi8pRzcatV z;P8z3kATB>&*fZ~@3r$Ri~Vemjic}`)EdZ;hh+zyNzWfh?yDbCgt?wG$TK|E57u=&U$0o)X`*KEp@TZ;+&pL5#eS@@zy!~dK zrq^zq8=5hSHBFzTXV4$=Idkre|FMDg(fS@}bN9?~7t=y}`RA1+=G++DF@kbsX_JgH zf+o_Bs3-9EL7QQ;lbhx}w-@OOJ*up9<=L%6SFIa?F|+UX?d7bWdyXEpbgsvqL&mY& zKRK2KHn{2e!hL(mb?em;KOflj`134#>oq5z;zl~$=*FYXiTJjEbHM$A+OP#bqI+Wh6jZ!=ThzD@gBIdS3t!2c)1-fbuLZZYiL z_F(Tueb}E<*K6h7beH&$eg#RT5x$ooPpY~gSqi1OD%I<(a>qlO@4m=p$-ubkxZvy2D zf^T2A|B(HNk$*pq^!a~qc!v8p^4D&AXLko+{!b&`+1=4#-P!K!qWo)+j@D&GxgSIM zo1A-?3pS5uF4_*&L)fgyz-WmLBD}HTZ|D&E#xh! zXA=R^V!Y+JlNQqyF2m1T=E95GI9OJ+As+J-W2WAP_rv&qL|AsoPw@P_7LDZJ3OAC7YftR-~yFN5~;p0z%Fr5TDWY@hp|QRV;7Xl1z^3?0(_2p@T>aoQ+M66EoCDSJS_ KfXBg}<9`ED4F!V$ From 9e1d85ff3f95def633975ab391eea930033e5a47 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 3 Mar 2022 21:09:29 -0500 Subject: [PATCH 057/243] Remade the subsystem code, started vision tracking --- include/subsystems/custom_encoder.h | 28 +++++++++++++++++++++++++ src/subsystems/custom_encoder.cpp | 32 +++++++++++++++++++++++++++++ 2 files changed, 60 insertions(+) create mode 100644 include/subsystems/custom_encoder.h create mode 100644 src/subsystems/custom_encoder.cpp diff --git a/include/subsystems/custom_encoder.h b/include/subsystems/custom_encoder.h new file mode 100644 index 0000000..19df840 --- /dev/null +++ b/include/subsystems/custom_encoder.h @@ -0,0 +1,28 @@ +#pragma once +#include "vex.h" + +/** + * A wrapper class for the vex encoder that allows the use of 3rd party + * encoders with different tick-per-revolution values. + */ +class CustomEncoder : public vex::encoder +{ + typedef vex::encoder super; + + public: + CustomEncoder(vex::triport::port &port, double ticks_per_rev); + + void setRotation(double val, vex::rotationUnits units); + + void setPosition(double val, vex::rotationUnits units); + + double rotation(vex::rotationUnits units); + + double position(vex::rotationUnits units); + + double velocity(vex::velocityUnits units); + + + private: + double tick_scalar; +}; \ No newline at end of file diff --git a/src/subsystems/custom_encoder.cpp b/src/subsystems/custom_encoder.cpp new file mode 100644 index 0000000..b920782 --- /dev/null +++ b/src/subsystems/custom_encoder.cpp @@ -0,0 +1,32 @@ +#include "../core/include/subsystems/custom_encoder.h" + +CustomEncoder::CustomEncoder(vex::triport::port &port, double ticks_per_rev) +: super(port) +{ + tick_scalar = ticks_per_rev / 90; +} + +void CustomEncoder::setRotation(double val, vex::rotationUnits units) +{ + super::setRotation(val * tick_scalar, units); +} + +void CustomEncoder::setPosition(double val, vex::rotationUnits units) +{ + super::setPosition(val * tick_scalar, units); +} + +double CustomEncoder::rotation(vex::rotationUnits units) +{ + return super::rotation(units) / tick_scalar; +} + +double CustomEncoder::position(vex::rotationUnits units) +{ + return super::position(units) / tick_scalar; +} + +double CustomEncoder::velocity(vex::velocityUnits units) +{ + return super::velocity(units) / tick_scalar; +} \ No newline at end of file From c57151285221e7fa0c6d75dad2dbbd5dcd2604e9 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 6 Feb 2022 12:32:12 -0500 Subject: [PATCH 058/243] Post WPI squash commit --- include/subsystems/tank_drive.h | 2 +- src/subsystems/tank_drive.cpp | 61 +++++++++++++++++---------------- 2 files changed, 33 insertions(+), 30 deletions(-) diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index c584bfc..90d6386 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -66,7 +66,7 @@ class TankDrive * Use odometry to automatically drive the robot to a point on the field. * X and Y is the final point we want the robot. */ - bool drive_to_point(double x, double y, double speed, double correction_speed, vex::directionType direction=vex::directionType::fwd, double max_accel=0); + bool drive_to_point(double x, double y, double speed, double correction_speed, vex::directionType direction=vex::directionType::fwd); /** * Turn the robot in place to an exact heading relative to the field. diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index f394e30..a7a2d3a 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -70,6 +70,14 @@ bool TankDrive::drive_forward(double inches, double speed, double correction, di { static position_t pos_setpt; + // We can't run the auto drive function without odometry + if(odometry == NULL) + { + fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); + fflush(stderr); + return true; + } + // Generate a point X inches forward of the current position, on first startup if (!func_initialized) { @@ -99,6 +107,14 @@ bool TankDrive::drive_forward(double inches, double speed, double correction, di */ bool TankDrive::turn_degrees(double degrees, double percent_speed) { + // We can't run the auto drive function without odometry + if(odometry == NULL) + { + fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); + fflush(stderr); + return true; + } + // On the first run of the funciton, reset the gyro position and PID if (!func_initialized) { @@ -135,10 +151,16 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) * * Returns whether or not the robot has reached it's destination. */ -bool TankDrive::drive_to_point(double x, double y, double speed, double correction_speed, vex::directionType dir, double max_accel) +bool TankDrive::drive_to_point(double x, double y, double speed, double correction_speed, vex::directionType dir) { + // We can't run the auto drive function without odometry + if(odometry == NULL) + { + fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); + fflush(stderr); + return true; + } - static timer accel_tmr; static double lside_accel = 0, rside_accel = 0; if(!func_initialized) @@ -157,7 +179,6 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti // point_orientation_deg = atan2(y - odometry->get_position().y, x - odometry->get_position().x) * 180.0 / PI; - accel_tmr.reset(); lside_accel = 0; rside_accel = 0; @@ -238,32 +259,6 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti lside = (lside > 1) ? 1 : (lside < -1) ? -1 : lside; rside = (rside > 1) ? 1 : (rside < -1) ? -1 : rside; - // static double last_lside = lside, last_rside = rside; - // bool decelerating = (fabs(lside) < fabs(last_lside)) && (fabs(rside) < fabs(last_rside)); - // last_lside = lside; - // last_rside = rside; - - // if(max_accel != 0 && !decelerating) - // { - // double accel_addition = max_accel * accel_tmr.time(timeUnits::sec); - // accel_tmr.reset(); - - // lside_accel += (lside > 0 ? accel_addition : -accel_addition); - // rside_accel += (rside > 0 ? accel_addition : -accel_addition); - - // printf("lside: %f, rside: %f, laccel: %f, raccel: %f\n", lside, rside, lside_accel, rside_accel); - - // if ((lside < 0 && lside_accel > lside) || (lside > 0 && lside_accel < lside)) - // lside = lside_accel; - // else - // lside_accel = lside; - - // if ((rside < 0 && rside_accel > rside) || (rside > 0 && rside_accel < rside)) - // rside = rside_accel; - // else - // rside_accel = rside; - // } - drive_tank(lside, rside); printf("dist: %f\n", dist_left); @@ -286,6 +281,14 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti */ bool TankDrive::turn_to_heading(double heading_deg, double speed) { + // We can't run the auto drive function without odometry + if(odometry == NULL) + { + fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); + fflush(stderr); + return true; + } + static bool initialized = false; if(!initialized) { From d25a6cae450abda65291e5c690d5981fa5131400 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 6 Feb 2022 16:07:43 -0500 Subject: [PATCH 059/243] Created new generic lift class in Core --- include/subsystems/lift.h | 257 ++++++++++++++++++++++++++++++++++ src/subsystems/tank_drive.cpp | 7 +- 2 files changed, 258 insertions(+), 6 deletions(-) create mode 100644 include/subsystems/lift.h diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h new file mode 100644 index 0000000..27d12ab --- /dev/null +++ b/include/subsystems/lift.h @@ -0,0 +1,257 @@ +#pragma once + +#include "vex.h" +#include "../core/include/utils/pid.h" +#include +#include +#include + +using namespace vex; +using namespace std; + +/** + * LIFT + * A general class for lifts (e.g. 4bar, dr4bar, linear, etc) + * Uses a PID to hold the lift at a certain height under load, and to move the lift to different heights + * + * @author Ryan McGee + */ +template +class Lift +{ + public: + + struct lift_cfg_t + { + double up_speed, down_speed; + double softstop_up, softstop_down; + + PID::pid_config_t lift_pid_cfg; + }; + + /** + * Construct the Lift object and begin the background task that controls the lift. + * + * Usage example: + * /code{.cpp} + * enum Positions {UP, MID, DOWN}; + * map setpt_map { + * {DOWN, 0.0}, + * {MID, 0.5}, + * {UP, 1.0} + * }; + * Lift my_lift(motors, lift_cfg, setpt_map); + * /endcode + * + * @param lift_motors + * A set of motors, all set that positive rotation correlates with the lift going up + * @param lift_cfg + * Lift characterization information; PID tunings and movement speeds + * @param setpoint_map + * A map of enum type T, in which each enum entry corresponds to a different lift height + */ + Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map setpoint_map) + : lift_motors(lift_motors), cfg(lift_cfg), lift_pid(cfg.lift_pid_cfg), setpoint_map(setpoint_map) + { + + is_async = true; + setpoint = 0; + + // Create a background task that is constantly updating the lift PID, if requested. + // Set once, and forget. + task t([](void* ptr){ + Lift &lift = *((Lift*) ptr); + + while(true) + { + if(lift.get_async()) + lift.hold(); + + vexDelay(50); + } + + return 0; + }, this); + + } + + /** + * Control the lift with an "up" button and a "down" button. + * Use PID to hold the lift when letting go. + * @param up_ctrl + * Button controlling the "UP" motion + * @param down_ctrl + * Button controlling the "DOWN" motion + */ + void control_continuous(bool up_ctrl, bool down_ctrl) + { + static timer tmr; + + double cur_pos = 0; + + // Check if there's a hook for a custom sensor. If not, use the motors. + if(get_sensor == NULL) + cur_pos = lift_motors.rotation(rev); + else + cur_pos = get_sensor(); + + if(up_ctrl && cur_pos < cfg.softstop_up) + { + lift_motors.spin(directionType::fwd, cfg.up_speed, volt); + setpoint = cur_pos; + + // Disable the PID while going UP. + is_async = false; + } else if(down_ctrl && cur_pos > cfg.softstop_down) + { + // Lower the lift slowly, at a rate defined by down_speed + setpoint -= tmr.time(sec) * cfg.down_speed; + is_async = true; + } else + { + // Hold the lift at the last setpoint + is_async = true; + } + + tmr.reset(); + } + + /** + * Control the lift in "steps". When the "up" button is pressed, the lift will go to the next + * position as defined by pos_list. Order matters! + * + * @param up_step + * A button that increments the position of the lift. + * @param down_step + * A button that decrements the position of the lift. + * @param pos_list + * A list of positions for the lift to go through. The higher the index, the higher the lift should be (generally). + */ + void control_setpoints(bool up_step, bool down_step, vector pos_list) + { + // Make sure inputs are only processed on the rising edge of the button + static bool up_last = up_step, down_last = down_step; + + bool up_rising = up_step && !up_last; + bool down_rising = down_step && !down_last; + + up_last = up_step; + down_last = down_step; + + static int cur_index = 0; + + // Avoid an index overflow. Shouldn't happen unless the user changes pos_list between calls. + if(cur_index >= pos_list.size()) + cur_index = pos_list.size() - 1; + + // Increment or decrement the index of the list, bringing it up or down. + if(up_rising && cur_index < (pos_list.size() - 1)) + cur_index++; + else if(down_rising && cur_index > 0) + cur_index--; + + // Set the lift to hold the position in the background with the PID loop + set_position(pos_list[cur_index]); + is_async = true; + + } + + /** + * Enable the background task, and send the lift to a position, specified by the + * setpoint map from the constructor. + * + * @param pos + * A lift position enum type + * @return True if the pid has reached the setpoint + */ + bool set_position(T pos) + { + this->setpoint = setpoint_map[pos]; + is_async = true; + + return (lift_pid.get_target() == this->setpoint) && lift_pid.is_on_target(); + } + + /** + * Manually set a setpoint value for the lift PID to go to. + * @param val + * Lift setpoint, in motor revolutions or sensor units defined by get_sensor. Cannot be outside the softstops. + * @return True if the pid has reached the setpoint + */ + bool set_setpoint(double val) + { + this->setpoint = val; + return (lift_pid.get_target() == this->setpoint) && lift_pid.is_on_target(); + } + + /** + * @return The current setpoint for the lift + */ + double get_setpoint() + { + return this->setpoint; + } + + /** + * Target the class's setpoint. + * Calculate the PID output and set the lift motors accordingly. + */ + void hold() + { + lift_pid.set_target(setpoint); + + if(get_sensor != NULL) + lift_pid.update(get_sensor()); + else + lift_pid.update(lift_motors.rotation(rev)); + + lift_motors.spin(fwd, lift_pid.get(), volt); + } + + /** + * @return whether or not the background thread is running the lift + */ + bool get_async() + { + return is_async; + } + + /** + * Enables or disables the background task. Note that running the control functions, or set_position functions + * will immediately re-enable the task for autonomous use. + * @param Whether or not the background thread should run the lift + */ + void set_async(bool val) + { + this->is_async = val; + } + + /** + * Creates a custom hook for any other type of sensor to be used on the lift. Example: + * /code{.cpp} + * my_lift.set_sensor_function( [](){return my_sensor.position();} ); + * /endcode + * + * @param fn_ptr + * Pointer to custom sensor function + */ + void set_sensor_function(double (*fn_ptr) (void)) + { + this->get_sensor = fn_ptr; + } + + private: + + motor_group &lift_motors; + lift_cfg_t &cfg; + PID lift_pid; + map &setpoint_map; + + atomic setpoint; + atomic is_async; + + double (*get_sensor)(void) = NULL; + + + +}; \ No newline at end of file diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index a7a2d3a..8a9a195 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -160,9 +160,7 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti fflush(stderr); return true; } - - static double lside_accel = 0, rside_accel = 0; - + if(!func_initialized) { // Reset the control loops @@ -179,9 +177,6 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti // point_orientation_deg = atan2(y - odometry->get_position().y, x - odometry->get_position().x) * 180.0 / PI; - lside_accel = 0; - rside_accel = 0; - func_initialized = true; } From 9b251405398a956859df93f8fec2cc32a5bf5c5a Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Wed, 9 Feb 2022 10:53:25 -0500 Subject: [PATCH 060/243] Added homing function to Lift --- include/subsystems/lift.h | 45 ++++++++++++++++++++++++++++++++++++--- 1 file changed, 42 insertions(+), 3 deletions(-) diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index 27d12ab..a44d206 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -50,8 +50,8 @@ class Lift * @param setpoint_map * A map of enum type T, in which each enum entry corresponds to a different lift height */ - Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map setpoint_map) - : lift_motors(lift_motors), cfg(lift_cfg), lift_pid(cfg.lift_pid_cfg), setpoint_map(setpoint_map) + Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map setpoint_map, limit *homing_switch=NULL) + : lift_motors(lift_motors), cfg(lift_cfg), lift_pid(cfg.lift_pid_cfg), setpoint_map(setpoint_map), homing_switch(homing_switch) { is_async = true; @@ -208,6 +208,33 @@ class Lift lift_motors.spin(fwd, lift_pid.get(), volt); } + /** + * A blocking function that automatically homes the lift based on a sensor or hard stop, + * and sets the position to 0. A watchdog times out after 3 seconds, to avoid damage. + */ + void home() + { + static timer tmr; + tmr.reset(); + + while(tmr.time(sec) < 3) + { + lift_motors.spin(directionType::rev, 6, volt); + + if (homing_switch == NULL && lift_motors.current(currentUnits::amp) > 1.5) + break; + else if (homing_switch != NULL && homing_switch->pressing()) + break; + } + + if(reset_sensor != NULL) + reset_sensor(); + + lift_motors.resetPosition(); + lift_motors.stop(); + + } + /** * @return whether or not the background thread is running the lift */ @@ -240,18 +267,30 @@ class Lift this->get_sensor = fn_ptr; } + /** + * Creates a custom hook to reset the sensor used in set_sensor_function(). Example: + * /code{.cpp} + * my_lift.set_sensor_reset( my_sensor.resetPosition ); + * /endcode + */ + void set_sensor_reset(void (*fn_ptr) (void)) + { + this->reset_sensor = fn_ptr; + } + private: motor_group &lift_motors; lift_cfg_t &cfg; PID lift_pid; map &setpoint_map; + limit *homing_switch; atomic setpoint; atomic is_async; double (*get_sensor)(void) = NULL; - + void (*reset_sensor)(void) = NULL; }; \ No newline at end of file From 0868b6713ee16d4ecd3d7d0291f47d7bd618cd42 Mon Sep 17 00:00:00 2001 From: Dana Date: Wed, 23 Feb 2022 20:10:40 -0500 Subject: [PATCH 061/243] debugging in progress --- include/subsystems/lift.h | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index a44d206..cc0194b 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -2,6 +2,7 @@ #include "vex.h" #include "../core/include/utils/pid.h" +#include #include #include #include @@ -100,12 +101,15 @@ class Lift lift_motors.spin(directionType::fwd, cfg.up_speed, volt); setpoint = cur_pos; + std::cout << "DEBUG OUT: UP " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n"; + // Disable the PID while going UP. is_async = false; } else if(down_ctrl && cur_pos > cfg.softstop_down) { // Lower the lift slowly, at a rate defined by down_speed - setpoint -= tmr.time(sec) * cfg.down_speed; + setpoint = setpoint - (tmr.time(sec) * /*cfg.down_speed*/ 2.4); + std::cout << "DEBUG OUT: DOWN " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n"; is_async = true; } else { @@ -199,12 +203,15 @@ class Lift void hold() { lift_pid.set_target(setpoint); + std::cout << "DEBUG OUT: SETPOINT " << setpoint << "\n"; if(get_sensor != NULL) lift_pid.update(get_sensor()); else lift_pid.update(lift_motors.rotation(rev)); + std::cout << "DEBUG OUT: ROTATION " << lift_motors.rotation(rev) << "\n\n"; + lift_motors.spin(fwd, lift_pid.get(), volt); } From a5d34b315c152aebbebeb5b43966c4787d112e64 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 24 Feb 2022 22:06:17 -0500 Subject: [PATCH 062/243] Fixed everything (ready for comp kinda) --- include/subsystems/lift.h | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index cc0194b..351c41f 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -99,17 +99,18 @@ class Lift if(up_ctrl && cur_pos < cfg.softstop_up) { lift_motors.spin(directionType::fwd, cfg.up_speed, volt); - setpoint = cur_pos; + setpoint = cur_pos + .3; - std::cout << "DEBUG OUT: UP " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n"; + // std::cout << "DEBUG OUT: UP " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n"; // Disable the PID while going UP. is_async = false; } else if(down_ctrl && cur_pos > cfg.softstop_down) { // Lower the lift slowly, at a rate defined by down_speed - setpoint = setpoint - (tmr.time(sec) * /*cfg.down_speed*/ 2.4); - std::cout << "DEBUG OUT: DOWN " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n"; + if(setpoint > cfg.softstop_down) + setpoint = setpoint - (tmr.time(sec) * cfg.down_speed); + // std::cout << "DEBUG OUT: DOWN " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n"; is_async = true; } else { @@ -203,14 +204,14 @@ class Lift void hold() { lift_pid.set_target(setpoint); - std::cout << "DEBUG OUT: SETPOINT " << setpoint << "\n"; + // std::cout << "DEBUG OUT: SETPOINT " << setpoint << "\n"; if(get_sensor != NULL) lift_pid.update(get_sensor()); else lift_pid.update(lift_motors.rotation(rev)); - std::cout << "DEBUG OUT: ROTATION " << lift_motors.rotation(rev) << "\n\n"; + // std::cout << "DEBUG OUT: ROTATION " << lift_motors.rotation(rev) << "\n\n"; lift_motors.spin(fwd, lift_pid.get(), volt); } From f5eb835d158ad88662ebc7905200e9bcc5311ca2 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Tue, 1 Mar 2022 13:05:37 -0500 Subject: [PATCH 063/243] Post competition commit --- include/subsystems/lift.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index 351c41f..29b9767 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -51,7 +51,7 @@ class Lift * @param setpoint_map * A map of enum type T, in which each enum entry corresponds to a different lift height */ - Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map setpoint_map, limit *homing_switch=NULL) + Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map &setpoint_map, limit *homing_switch=NULL) : lift_motors(lift_motors), cfg(lift_cfg), lift_pid(cfg.lift_pid_cfg), setpoint_map(setpoint_map), homing_switch(homing_switch) { From ff6400a295d55f5540d81d804923c9de790195b1 Mon Sep 17 00:00:00 2001 From: Dana Date: Thu, 3 Mar 2022 20:34:35 -0500 Subject: [PATCH 064/243] removed pathfinder --- lib/libpathfinder.a | Bin 31010 -> 0 bytes 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 lib/libpathfinder.a diff --git a/lib/libpathfinder.a b/lib/libpathfinder.a deleted file mode 100644 index f96adc441fd3bad6c48253e7f03d119a70606a7b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 31010 zcmd^oe{j@CmS2x%1Of>&ti>X)WP1Ps@>;MXA+T6eyTgJFtneK+(<(xE&Z*XUt9i_NT#W&tFMXH z?x?G&iA170$o-8(>K`+3B+|TGDYZeV;G5aM`~Os_yZIhHrWC*0chcX^KUPY<-3W8P zXU;0c@7ay!JNElZ@r(aPyrXF#-qY3F-qhOH*WWgv(jIN?{axSj!%el0PfPD}J?#$M z)-{l5>1}nr;{AQk^|ucUGEMmMR(b>_}i&``dpe8LnUH=RPOMAApXZ7|xn_34@`>go> zppL$tp1$v1!?MabS0WP+xw4qB|!BP$GTccLf13iuSw{7eftDx2Fzo9CwkkO z`diw%T6zame{Gv;tL^1?Y*si2+tj&>w3Jet*hfy)4+Gz`@hrP)Yjh7a-t{U z#>qf%1H2-qbAGP9x4mDNIPGWSqu+HaWxDc~J{hSsb=$XY+g`K1W?SY6t%*jrZ{Hq? z)J3<~nK9kG{QFNFcrp+OV4xZkP*o}oDK)lC`xn+}t4iIcinXig+EWv1-{xP0u3VU? zhr3=CPlm!TPL!zUr&bSMnm*S3+Vr0ezC9EE+rODvg5gKMk-`6<;XpL`zKSOQVj%j< zzd~X+0pC#S&<#u%%ZYc$iHov4JG$X&st|Z80zBZ(etq{1_PUz`?=t>80I-;orS|CfHbR{2DjF4`E^tZkQonVWW)$|D}x6xNRobVB-u{!jE{{ zXO;;b;lb@Qg~)Gg{nb=~N~VJ0Wa?M9Z~ygtpdsb=n=5EY1-p^2EmtARvy5(}vlr9ByFx_qD`;(n2MjW%whrRU&dGn%Hh&YG6CE^8h=^qJ64q3oe6Km0T-WuJ|pf6$c1 zw57t(0qPvLuwh?Ubmm^3x&up;;ReW;K4lV5J{-n}es}S!OK1M);E!jPp&t$bz7}~u zHNUPQMfY{M=hhqdwYBiK?(1;RRa*ab@E3O_{5LeDWQ@;89Jk{?w~^zjAvGKMI5mp6 zw_uOKo?QzVc(-6n8nf#VhA}q^d_5+Yq|=<+)Q~F27%SI(apTOB>>p^;HI^o%lNp<5 z_4wwzQx+|rd=&Fenbf_Tb?4YTJF`a50e3Ff7|Q1_(;Uk50Lt-zEl1@Y%JCrbco4Yk z&+KRA8ux`6GpAsFL-;7_HHR_4G6te&CRpaONV#sWpn4|t=eKWvvKndV`48jcVYXek zd~yu&ZdLvyMO((9?g!`In^IoCo&CBQe=6qoSN02;M~+4>dHrG~%M-b(+j|T)+j?{@ zV9;R<_B`y-b%4>Pqm_VROWV2a&-#cz+fCdY>uhuO1=5y%VH9bwFO0$V_l40A@XRfLt^)P7iux*2uEN!sTwln+sYRoUD-<+LUJ^11@`$iS$ycK<;%IO;thwH;) zGeu6dk<|yhv zhjBZGF-MxR4(vOuQx*CS+mwChr|3H@C&#s{V|#5{E4X&+dAEF;YZ=!D&arz3w_%Mu zJ5z%4JlXx&jL>8S$|7qW$7e>L!@A|oJ-WlC`(5l(;Q1?op<#Lt(S0R2M7Q=28h`D+ z;<&9p@o0Vw=Ai`kxdNmybZO{dP^mJ&pTVvq0vMJk?Y+Bqe>GBt-w62l$dk|Pek4-2 zWyh8pwW}7PE$uDGx>TSF&ceqw?@~*aFWprXSXQvS;0vMB!0N!7U|HaSz?TZjgAXlP z7f@RUP90CQ9D|+cH+HAE`rCW9B-&3V)RwlEM2p&TY+yib+4am*Tj0kS3^!m`+ex*h zweR@xcI+Is^!6p%x9t6mf3z7Jkk)P!r6rN*?>csZn~Z$T!$1T{SZ!_U@q4n!0Fu;`TFjS* zlN0dbr!|E31fImDm*71Pw_A^sPCZBismC|rX1=;Fz^*`~FTobWFn))uE&kix#GSBK zxKY=*i-$SGGfazS6+WQ};Vz`-wx;0G7Mc*R1Pu{|2gaiMB0kn5jE}`})7yEUQlsz_ zBk2h&w(B2Ke{);>X$N)9(>}qB92g!_m|GkZ(B-<~CF(gePEZx<@N@)l{Ei8tcd}k- zvqY!Qv22Vw`o5FTGPgac?E;30u$mGZ8YQ_^c%u$v;n^hIuV|t4Y+x!frn@V zruj1HsLcartbQ3`>^1b~oJyGOM3}a!FzXayICXf0HsDGNS6R5)!d-o7xj+QQNbl-* z)Idn*%I!opux&?u-m-xMm`7kd*}zJaTJ~eyTNYujP!cYlECN5VerGZ@5c%a_mB6hc z?@!Vuk5L5v;u}@TR6oMRzd-yeGyQ|sUvOog$i0>1%Y9%O@+D7J1pb9~32e~sCi4tN zTPM!cBvWDd5hiaOjGi7>(Z84sV!srI-xszfQ!E$#nTC{=>F6{dtN3g1LabL%B~xxW zW{Wrfq6~ZMI+TO^{i;au3tyJ_+CN;kmJ~N^5>XWIR7Ox)m zPT;BNPc%+};M65kdn`^2_8tc(XmNtr_Z_e}`(Ph%a6%Sm-Fe6>hR>zeUrwe@QWj(L zDU|R|gm<1ztv{Jeea8u3BH?=weqcDY{%|staKe{H&rDQCP;Rty8TRtC#qUkAjl$SR z7J)WwqX^qbL7o#%-r&BSc3HT15<~B1S-5<1X}D$L`BlkO1^fs{6#7eeXk3MVHu-IZ zvI4(i1pcuD6Or+riB+I)xb93U`n5BuaCI^@iZlz<#qnVH56784(+Gs0pI{z3ef9K> zPc1(yyk`;08peJ{`cf&|5OK-#az8@;Sa97ozgv9S=W`D=uNqQe^pP>x+4kaL^h5f4 zdojBgr~HlMs|a+-7B8EhKaFOjaRg}`1x=b!hLUK*L^IM885Uvo?*M2Wg6!=G`nygy zYQ|O^ZKcNm#>-KZljG&^2;z(XY(@Kb)}`l>2>M?PeI&yEhk2x@(##`I{8__9$;g3; zB7FJGCr^A0_|e@H1r7I4i~Cya{gk*18ej7KL)~fjlEJk5+UYd@^N52-7@ISRs$vbom%oit$*B*#--1Iep$ zon7n0!&trL^V4$ebv`_d;afgGj_cX=K0L}l;itzX#?fUvjyQJqV=RR*jusp5>>H#v z$34&Eu&r3m^w>YyuiW{-?O%a%&=~nKF8dkd{`T$LU-Hip?;^oh@Fnma#8-{42;Zjx zrAF{Qq2+o1d5B$omv%otO!oqLo-5nS;(pSkvmh?hqP*{}0kGB){E$q+s!9EHB%VF4UiRzQpr>f(916_%(zTWEZwD7_$60pobIa9+j_PcGT6Dra+^?$)vcJ!WD*vHnkvwHqJ0uanj+4QjasBT_W=Wc-jhh%uRTLLZ^6f~bNCp(12&0EIT+z52wOw^qxd*q zz5$!zov=A?MlE~-Hs?=)PXp#W%K4J`7hyL8-ecicVRK%sLL7$w5nwUQ52{{zzU5lM z@SjN_Y=-}Le4K~dYgHNE14ttI^7Gf=X#UwFK z_(9-fvY>4CFm1p+79O_nWedM;;g2l*sfFh)T#8}J_|>$L-X04dwQ$11=PmrYh39BP z7R*6gf%T_~HsCtiSfCDC_^5?XT6oyPNejPa;SVi5YT;Q6&s(?*{haAn(nk6*3m>p> z6&5_!qZIv{GUjU9>p&maK};1#to<_mE3wYd-k{V7?Tt!ZxA2sOd4R(3Fl~faS-9T9 z2QA!e;gc3VXW^uUuUPm)3tzYJ2vo@`HYqhvy9yuXIhHeG?MiD`S-aZWQES&(yWZOD zLzIPUgY^RB@MPzn3?1t$no4~cG)0%v;T0B+SQtgo{!we!(FT6Kg*lfIj#+q*h4)$b zfQ1iQnCmq0k64&|KcW{jJ!~V!siMAP(ez2lAEw zVeiEBxL1-ialGQm6Lor#)8nRW7bYVk7bXg@msu!J6#1f&E3!<@(F>E*y}Pw>q25$b zU7iXqq9>(g8jcPE>E_CKGw2q1X)=L4NiUpdzsd5lKBU+E(1&;!`WAbktK-*6q^_aH zh5Ug!hI6Cen)R1MvuBs@1R=x@MmYFV6_8fqtg(7sKQH#W+$V z?z=hXiIMX8_bTUsM_x$s6THXaho!+YbEpUBO4b8TuO8oon{k;x&1IyQZ4Yt?VUh>& z{-YF>0E~pS!i~DdwI_avw^abxg6G$p_yzDZV_|UxkG7i?*L5bsEf7D}m-S~|g~o8I z^QdGq9o9&C0*meX-^(6Ek0D9StDW)S9t7$tj$z@`hI^9CaJEd^EZifo=cP>$i$3>Z zG#t<5xi?#Pk%jl`Q1e4Nr57^cd>uZ}cNM^85q&|mx%31|k#B`LYfi84s3hBo>nLl$ z^__GhY;PIJvWheBJL|*OZj0u9=3QdQow2SW+l;l9`tY(w6piD&)6v_N^@rgf$=>YdJVz|P3w)lp)M1T~IiKr?3v*qj zj-S>wg+3q45rzz1+bECLg@;}r;n3h2t84!lbY+cR-`?&YnK&BP;4J|j^U&)RWSZI5 zS&?za{(qq%>VFNo%ha3n=!Leb)B2a2px6H+=)4v&;a{J%u}3$!dNu) zI{P`+AHD7@oU+3B`JgBk*k;g+Gy~~8{=v@&g@pkD4h?Z>{CrR@Jn|uoBWphKDw%*a zlDwY}szU(VQSuW!KOb}v^{59P>%rBQc&xLZ4?2K=eE6Ua$p~rCNdB#GgRCAOM7(_X zpnnCteE6W9kR!yA8F?V`5G+PEKIkn}ZWv)=qf4vzVP4i!5*XIv0a%LDs$el%)CxX<;ffpN8b%ixsItdDXDZ>t94K- zP?=7YtpWu39&Ip?uUPmk3%`sy5$`S9z#E|ryfF*UT6hTbqwG)XTT+P`#+B)?PiEu! zNKfL4Z09&6ktY&eJ;DSo#sk)DughDuQfd0o0v=F!7s?B?-WYhSvdslI_EbJ`56EORjm0yUg+% z#(rV(J7_~4F_Yf1|Ks!|9k!K1x_X_o=d#)lKkOeoTm7-Me_hWt|Dk0BTqn4X5`(E! zn+0p5-PbI(HpZN^n2><}wJ{f7)W(r%k$B8g496Rde{DPfyfXMpeuC#;8|zUI=CRn? z$n%?g*2dqF3|S}`0bAk5IErge{17jnwed&5%V%xm8N(28xi)ft%=&W9;VOZAJu`}B zsL_Mc<#W8WQ_4-?Ue-ppjhGA9>t-gVjhnhzD>G#R3)jlb@FlvvIA)D8>AxW$@?-uS z%f^`STLOBmVm$6f=D<9;c1FCk44ugniXq)8gD37me8i8z7Q^s=jF07$aOEusvRGy= zf*rU~pKBH5djnY)$f$mXK=YCn_nX|kwF(On`-rR4UqlqFX)GV{($5c=Rcf&{YHNKB zZtv49F8?1h>`Try>J_XV7oqp{a=3W%l}NFtLx%HUPX>Px`e>BtpU+dKKL%aIdFUqT z`-HH0mvkO_PWnzNY~IP7hb|QFXwJdrolWkWsS7*@Tl5rPw)s+biRTH6=`Fc>Nz`S1 zg}Q{0$A9GLvT_f~^||21&C?~&Q|tsBNB!l^0?Jy<{cYY~FUETTl*RMgh2mhmvM1#|V(#VjzE-D)JMh@^|MW$32NNR|YyYKb%qce)OaJM+ zNT2sqS)XORXW4yrhWlxKPubpYUW0P|bnt)8T>R>qnJS$7u>QKfi{MrRcLi|G+XU%! z`DQ^CXkSg*qtEEO;kX~Y0(IwEh0w#zm-id0fZqd~@j7AG!)}93IRWnni+pMhZmsvq z{)N6Y2RqKZ&_{Z*_7S7Q8dv3$CD5ZRc=5f@7QTmI(SN^f`&ZLpjX#(!CT$xx%#;A{`|H0kkr6)l1JM1SqpxkBxesz4SI?CATHh99EL3E`z-xFf!~vS!-2H7XPR?J18X_PA;$v7ENEAV``x?~#JV8vCv-nl zyIbEOsz#fzuk+ml&S%V@iS;eR-=hI&r63PBcgM|{DC1JUl<9H)NC4*CJ%zd3D>rCi z;+)lcqcCxB<{Yu(BY}7qzii&3(0J%a=8cYxGezh-e*F6}C$iieFA+PQiu8EdK68Zo zsO}f=E&|#Hvd7hy&Xiqeq!T_po&lq7eA|L@^9+CBN&lh_a7Gy7EGS3!52o)&o?I`? zdjw}^mizP05^p);t@6by@yA11I8G_+_m_inDCg3}&es`_?ZvUkvU5zcy&gb&RVz;i zSkDczZ%xaMy?gxVCfa1|6~A$*;Q689q5pE_in%4M^?`%04HGllo|60~`B2JSDqvTG z;i`iDdEQ%I)J!IcU}TWA{d>zJ5RC1EKWT@#Q}d~ew!y+6r#2rtY0-nYH2%G1F1#pk z83*%;HpHVYjTkhSHvYZkJn$k2k^BVDzqd>}^|+JVwF10wK6}gmm-qIQs4VxE+#9gI zwEcU_w}9{_{KW`;1Qy%%zn8sbrrgv`&Fm#b?rHKXlx(%l^XJTP0~blBLaQ=;SMEyu z^m`Nj{LDs1GRY=~rOc0p^8xpQn>1v8NXM_?V^|qFBEt`xApOhmf8v9G8?c^JP!!@* zKES!94Ikk@@ZrDega3^Wb~k#m`^@roUDhq8z9paDDB|9{dD2dcU|ZX}dU&JV32%kE zW}c7R9dAEA(4N4?7|-~%8dXf_P@>M<%YJ0-5NJl-M!qXS`+L^z;hc-Ttk%7xjwWbB z9nEHpUFvYsczaFBfC0s zBj9^wKd=+)oU0?Z$F6&rTi;=r=uqtpgYR{8&(;vEa!@w0?JNl8<)V1RtiE?nmvt#cI*yt{p z^J9$*-m|a)IMB6QrT4>WUAyAOOL&6|d_VS6D;oH|6WsdEKcj2MeFED;>(qgN8ryW$ zYa9COyI|n&bUC3*NnJZr<}*4B{r@Im=_k@h?p4<=hVjYu`}4}{)S>Ep`$P=q7aBjW zQ-=)`*_g$6op+tIm=4IRji1-ag%`DPBpKpyE)yf=^Yc2Rz~dSu`3at%*WuZ074TS( zJMlW7BE5WgonJ{oZ2=|!R=}7Rs>X1&?dCnLbTm4FIl_Vg!%2o7HF`Jm5)Q zhac<9`ulku>cIa~_=}PB1Qy%%zZYJoSQ65`1{pC{=2Lr{EhgTI(9$8yFd9)@i$4)xyYQQASb(841rL4%eXnK}Pbd za~_eFiKv+94OD?&k~fq1CQK>fSCGenTn+R7m&i9M%9&w@U{ilizj+C{C1ufk3#KGo zuH`bN;1MZfb!9NF48?WpF@>LNn5aL`JViZdkbWO7xBMgoh9V!HBJM7bNLyAHKTnYh z&(Bj3FCU)b9PsktDN0a@e0YjikX}AK#lO!{-&WKeK^{**ynJ{H44S-nigQ?YBOosM z37%u;;wjz$59RLlr9BWO!?^zU!c#2wrN(l7=rKWV>W0T)c-k!FF*3u=yN4XB#`x1) zTwcPyLBll2b39@|{mZZzK8CfyX1KD8yvK5MG-bSB?>%szgRO9G17yTQ@~R4LTw#?D zJbnX((ENtw-RaMHiD&8dG5o%M%W^DwW?r`~Z+SqNgW4|-0I$I}%MO9pP~bH};5CZC zYm|W32w`3im~%axp^e}8L+~8hk8iw0@a{Iw0E0OH!FzV&!P?AoFNRlgKF8iw;_#fr zJsT685O8F_$a8X@zwlk>81m!$b7> zPEfsyy9no}=5fv^cND_WVegK@O7-$o(ND@Jcj8Sq;;_smtIT@CH(_+W!Y}E!^%l?| z`uun>oYe6SV(%V6T*CUSlhdm>hV4JmEb-{2z6ta3peJVjtQdTN%a>P8kzrOI0Jo4$oxH z<;&2YhN!o(vx#H$|tDHmr32>_rhrHn!Xi8pRzcatV z;P8z3kATB>&*fZ~@3r$Ri~Vemjic}`)EdZ;hh+zyNzWfh?yDbCgt?wG$TK|E57u=&U$0o)X`*KEp@TZ;+&pL5#eS@@zy!~dK zrq^zq8=5hSHBFzTXV4$=Idkre|FMDg(fS@}bN9?~7t=y}`RA1+=G++DF@kbsX_JgH zf+o_Bs3-9EL7QQ;lbhx}w-@OOJ*up9<=L%6SFIa?F|+UX?d7bWdyXEpbgsvqL&mY& zKRK2KHn{2e!hL(mb?em;KOflj`134#>oq5z;zl~$=*FYXiTJjEbHM$A+OP#bqI+Wh6jZ!=ThzD@gBIdS3t!2c)1-fbuLZZYiL z_F(Tueb}E<*K6h7beH&$eg#RT5x$ooPpY~gSqi1OD%I<(a>qlO@4m=p$-ubkxZvy2D zf^T2A|B(HNk$*pq^!a~qc!v8p^4D&AXLko+{!b&`+1=4#-P!K!qWo)+j@D&GxgSIM zo1A-?3pS5uF4_*&L)fgyz-WmLBD}HTZ|D&E#xh! zXA=R^V!Y+JlNQqyF2m1T=E95GI9OJ+As+J-W2WAP_rv&qL|AsoPw@P_7LDZJ3OAC7YftR-~yFN5~;p0z%Fr5TDWY@hp|QRV;7Xl1z^3?0(_2p@T>aoQ+M66EoCDSJS_ KfXBg}<9`ED4F!V$ From a9bcdffe4d40202adc7fbda7924a95557d6c6187 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 3 Mar 2022 21:09:29 -0500 Subject: [PATCH 065/243] Remade the subsystem code, started vision tracking --- include/subsystems/custom_encoder.h | 28 +++++++++++++++++++++++++ src/subsystems/custom_encoder.cpp | 32 +++++++++++++++++++++++++++++ 2 files changed, 60 insertions(+) create mode 100644 include/subsystems/custom_encoder.h create mode 100644 src/subsystems/custom_encoder.cpp diff --git a/include/subsystems/custom_encoder.h b/include/subsystems/custom_encoder.h new file mode 100644 index 0000000..19df840 --- /dev/null +++ b/include/subsystems/custom_encoder.h @@ -0,0 +1,28 @@ +#pragma once +#include "vex.h" + +/** + * A wrapper class for the vex encoder that allows the use of 3rd party + * encoders with different tick-per-revolution values. + */ +class CustomEncoder : public vex::encoder +{ + typedef vex::encoder super; + + public: + CustomEncoder(vex::triport::port &port, double ticks_per_rev); + + void setRotation(double val, vex::rotationUnits units); + + void setPosition(double val, vex::rotationUnits units); + + double rotation(vex::rotationUnits units); + + double position(vex::rotationUnits units); + + double velocity(vex::velocityUnits units); + + + private: + double tick_scalar; +}; \ No newline at end of file diff --git a/src/subsystems/custom_encoder.cpp b/src/subsystems/custom_encoder.cpp new file mode 100644 index 0000000..b920782 --- /dev/null +++ b/src/subsystems/custom_encoder.cpp @@ -0,0 +1,32 @@ +#include "../core/include/subsystems/custom_encoder.h" + +CustomEncoder::CustomEncoder(vex::triport::port &port, double ticks_per_rev) +: super(port) +{ + tick_scalar = ticks_per_rev / 90; +} + +void CustomEncoder::setRotation(double val, vex::rotationUnits units) +{ + super::setRotation(val * tick_scalar, units); +} + +void CustomEncoder::setPosition(double val, vex::rotationUnits units) +{ + super::setPosition(val * tick_scalar, units); +} + +double CustomEncoder::rotation(vex::rotationUnits units) +{ + return super::rotation(units) / tick_scalar; +} + +double CustomEncoder::position(vex::rotationUnits units) +{ + return super::position(units) / tick_scalar; +} + +double CustomEncoder::velocity(vex::velocityUnits units) +{ + return super::velocity(units) / tick_scalar; +} \ No newline at end of file From d0880d83a1561829a08115461ce141c9f33d4986 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 17 Mar 2022 21:17:45 -0400 Subject: [PATCH 066/243] Added custom encoders to hardware --- src/subsystems/custom_encoder.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/subsystems/custom_encoder.cpp b/src/subsystems/custom_encoder.cpp index b920782..fb313aa 100644 --- a/src/subsystems/custom_encoder.cpp +++ b/src/subsystems/custom_encoder.cpp @@ -3,7 +3,7 @@ CustomEncoder::CustomEncoder(vex::triport::port &port, double ticks_per_rev) : super(port) { - tick_scalar = ticks_per_rev / 90; + tick_scalar = 90 / ticks_per_rev; } void CustomEncoder::setRotation(double val, vex::rotationUnits units) From 7c277006b14a1ca60590785a99c4c560d436e988 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 20 Mar 2022 14:51:57 -0400 Subject: [PATCH 067/243] Added autonomous chooser class --- include/subsystems/lift.h | 20 +++++++++ include/utils/auto_chooser.h | 28 ++++++++++++ src/utils/auto_chooser.cpp | 86 ++++++++++++++++++++++++++++++++++++ 3 files changed, 134 insertions(+) create mode 100644 include/utils/auto_chooser.h create mode 100644 src/utils/auto_chooser.cpp diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index 29b9767..1842caf 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -121,6 +121,26 @@ class Lift tmr.reset(); } + /** + * Control the lift with manual controls (no holding voltage) + * + * @param up_btn Raise the lift when true + * @param down_btn Lower the lift when true + * @param volt_up Motor voltage when raising the lift + * @param volt_down Motor voltage when lowering the lift + */ + void control_manual(bool up_btn, bool down_btn, int volt_up, int volt_down) + { + is_async = false; + + if(up_btn) + lift_motors.spin(directionType::fwd, volt_up, voltageUnits::volt); + else if(down_btn) + lift_motors.spin(directionType::rev, volt_down, voltageUnits::volt); + else + lift_motors.spin(directionType::fwd, 0, voltageUnits::volt); + } + /** * Control the lift in "steps". When the "up" button is pressed, the lift will go to the next * position as defined by pos_list. Order matters! diff --git a/include/utils/auto_chooser.h b/include/utils/auto_chooser.h new file mode 100644 index 0000000..b2f3544 --- /dev/null +++ b/include/utils/auto_chooser.h @@ -0,0 +1,28 @@ +#pragma once +#include "vex.h" +#include +#include + +class AutoChooser +{ + public: + AutoChooser(vex::brain &brain); + + void add(std::string name); + std::string get_choice(); + + protected: + + struct entry_t + { + int x, y, width, height; + std::string name; + }; + + void render(entry_t *selected); + std::string choice; + std::vector list; + vex::brain &brain; + + +}; \ No newline at end of file diff --git a/src/utils/auto_chooser.cpp b/src/utils/auto_chooser.cpp new file mode 100644 index 0000000..a768179 --- /dev/null +++ b/src/utils/auto_chooser.cpp @@ -0,0 +1,86 @@ +#include "../core/include/utils/auto_chooser.h" + +/** + * Initialize the auto-chooser. This class places a choice menu on the brain screen, + * so the driver can choose which autonomous to run. + */ +AutoChooser::AutoChooser(vex::brain &brain) : brain(brain) +{ + brain.Screen.pressed([](void *ptr){ + AutoChooser &a = *(AutoChooser*)ptr; + int x = a.brain.Screen.xPosition(); + int y = a.brain.Screen.yPosition(); + + entry_t *selected = NULL; + + // Check if the touchscreen press is inside each rectangle + for(int i = 0; i < a.list.size(); i++) + { + int rect_x = a.list[i].x, rect_y = a.list[i].y; + int rect_w = a.list[i].width, rect_h = a.list[i].height; + if (x > rect_x && x < rect_x + rect_w) + if (y > rect_y && y < rect_y + rect_h) + selected = &a.list[i]; + } + + // Re-render all the choices on each press. + a.render(selected); + + if(selected == NULL) + a.choice = ""; + else + a.choice = selected->name; + + }, this); +} + +#define PADDING 10 +#define WIDTH 150 +#define HEIGHT 40 + +/** + * Place all the autonomous choices on the screen. + * If one is selected, change it's color + */ +void AutoChooser::render(entry_t *selected) +{ + for(int i = 0; i < list.size(); i++) + { + brain.Screen.setPenColor(vex::color::black); + + if(selected != NULL && selected == &list[i]) + brain.Screen.setFillColor(vex::color::white); + else + brain.Screen.setFillColor(vex::color::orange); + + brain.Screen.drawRectangle(list[i].x, list[i].y, list[i].width, list[i].height); + brain.Screen.printAt(list[i].x + PADDING, list[i].y + list[i].height - PADDING, list[i].name.c_str()); + } +} + +/** + * Add a new autonomous option. There are 3 options per row. + */ +void AutoChooser::add(std::string name) +{ + int x = (PADDING * ((list.size() % 3) + 1)) + ((list.size() % 3) * WIDTH); + int y = (PADDING * ((list.size() / 3) + 1)) + ((list.size() / 3) * HEIGHT); + entry_t entry = { + .x=x, + .y=y, + .width=WIDTH, + .height=HEIGHT, + .name=name + }; + + list.push_back(entry); + render(NULL); +} + +/** + * Return the selected autonomous + */ +std::string AutoChooser::get_choice() +{ + return choice; +} \ No newline at end of file From 69bf4ffc89d35267f8714e668f9c1c7b471cc4af Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Tue, 29 Mar 2022 19:47:24 -0400 Subject: [PATCH 068/243] Added more autonomous stuff --- include/subsystems/tank_drive.h | 2 +- include/utils/generic_auto.h | 7 ++++++- src/subsystems/tank_drive.cpp | 4 ++-- src/utils/generic_auto.cpp | 26 ++++++++++++++++++++++++-- 4 files changed, 33 insertions(+), 6 deletions(-) diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 90d6386..97c2085 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -93,7 +93,7 @@ class TankDrive * @param speed Robot's maximum speed throughout the path, between 0 and 1.0 * @param res The number of points to use along the path; the hermite curve is split up into "res" individual points. */ - bool pure_pursuit(std::vector path, double radius, double speed, double res); + bool pure_pursuit(std::vector path, double radius, double speed, double res, directionType dir=fwd); private: motor_group &left_motors; diff --git a/include/utils/generic_auto.h b/include/utils/generic_auto.h index 3931ab3..2a6f6d9 100644 --- a/include/utils/generic_auto.h +++ b/include/utils/generic_auto.h @@ -4,8 +4,9 @@ #include #include #include "vex.h" +#include -typedef bool (*state_ptr)(); +typedef std::function state_ptr; class GenericAuto { @@ -31,6 +32,10 @@ class GenericAuto */ void add(state_ptr); + void add_async(state_ptr); + + void add_delay(int ms); + private: std::queue state_list; diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 8a9a195..fc483cb 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -326,7 +326,7 @@ double TankDrive::modify_inputs(double input, int power) return (power % 2 == 0 ? (input < 0 ? -1 : 1) : 1) * pow(input, power); } -bool TankDrive::pure_pursuit(std::vector path, double radius, double speed, double res) { +bool TankDrive::pure_pursuit(std::vector path, double radius, double speed, double res, directionType dir) { is_pure_pursuit = true; std::vector smoothed_path = PurePursuit::smooth_path_hermite(path, res); @@ -338,7 +338,7 @@ bool TankDrive::pure_pursuit(std::vector path, doubl if(is_last_point) is_pure_pursuit = false; - bool retval = drive_to_point(lookahead.x, lookahead.y, speed, 1); + bool retval = drive_to_point(lookahead.x, lookahead.y, speed, 1, dir); if(is_last_point) return retval; diff --git a/src/utils/generic_auto.cpp b/src/utils/generic_auto.cpp index 5c5c7ab..5147af5 100644 --- a/src/utils/generic_auto.cpp +++ b/src/utils/generic_auto.cpp @@ -33,8 +33,30 @@ bool GenericAuto::run(bool blocking) return blocking; } -void GenericAuto::add(state_ptr newState) +void GenericAuto::add(state_ptr new_state) { - state_list.push(newState); + state_list.push(new_state); } +void GenericAuto::add_async(state_ptr async_state) +{ + state_ptr fn = [&async_state](){ + vex::task t([](void* fn_ptr){ + while(! (*(state_ptr*)fn_ptr)() ) + vexDelay(20); + + return 0; + }, &async_state); + return true; + }; + + state_list.push(fn); +} + +void GenericAuto::add_delay(int ms) +{ + add([ms](){ + vexDelay(ms); + return true; + }); +} \ No newline at end of file From 8b6bf49b1cbe52b68142b906ea78872107a110aa Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 3 Apr 2022 16:41:51 -0400 Subject: [PATCH 069/243] Updated PID code for core --- src/subsystems/tank_drive.cpp | 7 +++---- src/utils/pid.cpp | 36 ++++++++++++++++------------------- 2 files changed, 19 insertions(+), 24 deletions(-) diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index fc483cb..3e3de4c 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -284,8 +284,7 @@ bool TankDrive::turn_to_heading(double heading_deg, double speed) return true; } - static bool initialized = false; - if(!initialized) + if(!func_initialized) { turn_pid.reset(); turn_pid.set_limits(-fabs(speed), fabs(speed)); @@ -293,7 +292,7 @@ bool TankDrive::turn_to_heading(double heading_deg, double speed) // Set the target to zero, and the input will be a delta. turn_pid.set_target(0); - initialized = true; + func_initialized = true; } // Get the difference between the new heading and the current, and decide whether to turn left or right. @@ -309,7 +308,7 @@ bool TankDrive::turn_to_heading(double heading_deg, double speed) // When the robot has reached it's angle, return true. if(turn_pid.is_on_target()) { - initialized = false; + func_initialized = false; stop(); return true; } diff --git a/src/utils/pid.cpp b/src/utils/pid.cpp index 9fcfd34..e070c77 100644 --- a/src/utils/pid.cpp +++ b/src/utils/pid.cpp @@ -20,10 +20,6 @@ void PID::update(double sensor_val) double time_delta = pid_timer.value() - last_time; - accum_error += time_delta * get_error(); - - double i_term = config.i * accum_error; - // Avoid a divide by zero error double d_term = 0; if(time_delta != 0) @@ -32,32 +28,32 @@ void PID::update(double sensor_val) printf("(pid.cpp): Warning - running PID without a delay is just a P loop!\n"); double k_term = 0; - if(get_error() < 0) + if(get_error() > 0) k_term = config.k; - else if(get_error() > 0) + else if(get_error() < 0) k_term = -config.k; - out = (config.f * target) + (config.p * get_error()) + i_term + d_term + k_term; + // F, P, D and K terms + out = (config.f * target) + (config.p * get_error()) + d_term + k_term; + + bool limits_exist = lower_limit != 0 || upper_limit != 0; + + // Only add to the accumulated error if the output is not saturated + // aka "Integral Clamping" anti-windup technique + if ( !limits_exist || (limits_exist && (out < upper_limit && out > lower_limit)) ) + accum_error += time_delta * get_error(); + + // I term + out += config.i * accum_error; last_time = pid_timer.value(); last_error = get_error(); // Enable clamping if the limit is not 0 - if (lower_limit != 0 || upper_limit != 0) - { - // Integral back-calculation - // If the PID is oversaturated and the integrated term is not pushing it in the right direction, - // then "turn off" the integral until it's actually helping. - bool clamping_upper = (out > upper_limit) && ((out - i_term) > upper_limit); - bool clamping_lower = (out < lower_limit) && ((out - i_term) < lower_limit); - - if(clamping_upper || clamping_lower) - out -= i_term; - - // Actually clamp the value + if (limits_exist) out = (out < lower_limit) ? lower_limit : (out > upper_limit) ? upper_limit : out; - } + } /** From 2f1c04c1ed351e71d03b8273f2760d569a863874 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Fri, 28 Jan 2022 00:52:31 -0500 Subject: [PATCH 070/243] Created qual auto --- include/subsystems/tank_drive.h | 2 +- src/subsystems/tank_drive.cpp | 13 ++++++++++--- 2 files changed, 11 insertions(+), 4 deletions(-) diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index c584bfc..87ba50a 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -33,7 +33,7 @@ class TankDrive * * left_motors and right_motors are in "percent": -1.0 -> 1.0 */ - void drive_tank(double left, double right, int power=1); + void drive_tank(double left, double right, int power=1, bool isdriver=false); /** * Drive the robot using arcade style controls. forward_back controls the linear motion, diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index f394e30..772c2e7 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -30,13 +30,20 @@ void TankDrive::stop() * * left_motors and right_motors are in "percent": -1.0 -> 1.0 */ -void TankDrive::drive_tank(double left, double right, int power) +void TankDrive::drive_tank(double left, double right, int power, bool isdriver) { left = modify_inputs(left, power); right = modify_inputs(right, power); - left_motors.spin(directionType::fwd, left * 12, voltageUnits::volt); - right_motors.spin(directionType::fwd, right * 12, voltageUnits::volt); + if(isdriver == false) + { + left_motors.spin(directionType::fwd, left * 12, voltageUnits::volt); + right_motors.spin(directionType::fwd, right * 12, voltageUnits::volt); + }else + { + left_motors.spin(directionType::fwd, left * 100.0, percentUnits::pct); + right_motors.spin(directionType::fwd, right * 100.0, percentUnits::pct); + } } /** From 9d59bbe15bcf0fa56966fa6b53d276b3e859cfac Mon Sep 17 00:00:00 2001 From: Dana Date: Tue, 29 Mar 2022 22:19:04 -0400 Subject: [PATCH 071/243] config updated --- src/subsystems/custom_encoder.cpp | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/src/subsystems/custom_encoder.cpp b/src/subsystems/custom_encoder.cpp index 0cd5e4c..4ecbae9 100644 --- a/src/subsystems/custom_encoder.cpp +++ b/src/subsystems/custom_encoder.cpp @@ -3,30 +3,31 @@ CustomEncoder::CustomEncoder(vex::triport::port &port, double ticks_per_rev) : super(port) { - tick_scalar = 90 / ticks_per_rev; + // bc it's a quadrature encoder, ticks per rev has to be multiplied by 4 + tick_scalar = 360 / (ticks_per_rev * 4); } void CustomEncoder::setRotation(double val, vex::rotationUnits units) { - super::setRotation(val * tick_scalar, units); + super::setRotation(val / tick_scalar, units); } void CustomEncoder::setPosition(double val, vex::rotationUnits units) { - super::setPosition(val * tick_scalar, units); + super::setPosition(val / tick_scalar, units); } double CustomEncoder::rotation(vex::rotationUnits units) { - return super::rotation(units) / tick_scalar; + return super::rotation(units) * tick_scalar; } double CustomEncoder::position(vex::rotationUnits units) { - return super::position(units) / tick_scalar; + return super::position(units) * tick_scalar; } double CustomEncoder::velocity(vex::velocityUnits units) { - return super::velocity(units) / tick_scalar; -} + return super::velocity(units) * tick_scalar; +} From abf8c36c644abe46ddb1a969c1cd9a47be50b4a3 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 3 Apr 2022 19:36:55 -0400 Subject: [PATCH 072/243] Tuned drive functions, fixed tank_drive issues --- include/subsystems/odometry/odometry_tank.h | 5 ++-- src/subsystems/custom_encoder.cpp | 12 ++++++--- src/subsystems/odometry/odometry_tank.cpp | 2 +- src/subsystems/tank_drive.cpp | 30 ++++++++++----------- 4 files changed, 28 insertions(+), 21 deletions(-) diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index feb31c4..ac376f6 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -2,6 +2,7 @@ #define _ODOMETRY_TANK_ #include "../core/include/subsystems/odometry/odometry_base.h" +#include "../core/include/subsystems/custom_encoder.h" #include "../core/include/utils/vector.h" #include "../core/include/robot_specs.h" @@ -26,7 +27,7 @@ class OdometryTank : public OdometryBase * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). */ - OdometryTank(vex::encoder &left_enc, vex::encoder &right_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true); + OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true); /** * Update the current position on the field based on the sensors @@ -45,7 +46,7 @@ class OdometryTank : public OdometryBase static position_t calculate_new_pos(robot_specs_t &config, position_t &stored_info, double lside_diff, double rside_diff, double angle_deg); vex::motor_group *left_side, *right_side; - vex::encoder *left_enc, *right_enc; + CustomEncoder *left_enc, *right_enc; vex::inertial *imu; robot_specs_t &config; diff --git a/src/subsystems/custom_encoder.cpp b/src/subsystems/custom_encoder.cpp index 4ecbae9..81472ac 100644 --- a/src/subsystems/custom_encoder.cpp +++ b/src/subsystems/custom_encoder.cpp @@ -19,15 +19,21 @@ void CustomEncoder::setPosition(double val, vex::rotationUnits units) double CustomEncoder::rotation(vex::rotationUnits units) { - return super::rotation(units) * tick_scalar; + if(units != vex::rotationUnits::raw) + return super::rotation(units) * tick_scalar; + + return super::rotation(units); } double CustomEncoder::position(vex::rotationUnits units) { - return super::position(units) * tick_scalar; + if (units != vex::rotationUnits::raw) + return super::position(units) * tick_scalar; + + return super::position(units); } double CustomEncoder::velocity(vex::velocityUnits units) { - return super::velocity(units) * tick_scalar; + return super::velocity(units) * tick_scalar; } diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 93e3289..111cca3 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -23,7 +23,7 @@ OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_ * @param right_side The right motors * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. */ -OdometryTank::OdometryTank(vex::encoder &left_enc, vex::encoder &right_enc, robot_specs_t &config, vex::inertial *imu, bool is_async) +OdometryTank::OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu, bool is_async) : left_side(NULL), right_side(NULL), left_enc(&left_enc), right_enc(&right_enc), imu(imu), config(config) { // Make sure the last known info starts zeroed diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 906a3d0..e9c4839 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -205,22 +205,22 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti int sign = 1; + // Make an imaginary perpendicualar line to that between the bot and the point. If the point is behind that line, + // and the point is within the robot's radius, use negatives for feedback control. + + double angle_to_point = atan2(y - current_pos.y, x - current_pos.x) * 180.0 / PI; + double angle = fmod(current_pos.rot - angle_to_point, 360.0); + // Normalize the angle between 0 and 360 + if (angle > 360) angle -= 360; + if (angle < 0) angle += 360; + // If the angle is behind the robot, report negative. + if (dir == directionType::fwd && angle > 90 && angle < 270) + sign = -1; + else if(dir == directionType::rev && (angle < 90 || angle > 270)) + sign = -1; + if (fabs(dist_left) < config.drive_correction_cutoff) { - // Make an imaginary perpendicualar line to that between the bot and the point. If the point is behind that line, - // and the point is within the robot's radius, use negatives for feedback control. - - double angle_to_point = atan2(y - current_pos.y, x - current_pos.x) * 180.0 / PI; - double angle = fmod(current_pos.rot - angle_to_point, 360.0); - // Normalize the angle between 0 and 360 - if (angle > 360) angle -= 360; - if (angle < 0) angle += 360; - // If the angle is behind the robot, report negative. - if (dir == directionType::fwd && angle > 90 && angle < 270) - sign = -1; - else if(dir == directionType::rev && (angle < 90 || angle > 270)) - sign = -1; - // When inside the robot's cutoff radius, report the distance to the point along the robot's forward axis, // so we always "reach" the point without having to do a lateral translation dist_left *= fabs(cos(angle * PI / 180.0)); @@ -263,7 +263,7 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti drive_tank(lside, rside); - printf("dist: %f\n", dist_left); + printf("dist: %f\n", sign * -1 * dist_left); fflush(stdout); // Check if the robot has reached it's destination From 842c5e1fa2a4e6a2e4b984f9c1ddb2c7482fff85 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 14 Apr 2022 22:11:29 -0400 Subject: [PATCH 073/243] Changed hardware ports and refactored --- include/subsystems/lift.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index 1842caf..9676114 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -133,9 +133,9 @@ class Lift { is_async = false; - if(up_btn) + if(up_btn && lift_motors.rotation(rev) < cfg.softstop_up) lift_motors.spin(directionType::fwd, volt_up, voltageUnits::volt); - else if(down_btn) + else if(down_btn && lift_motors.rotation(rev) > cfg.softstop_down) lift_motors.spin(directionType::rev, volt_down, voltageUnits::volt); else lift_motors.spin(directionType::fwd, 0, voltageUnits::volt); From b5c41582ae92473eb10b0221f4d33e0fac915629 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Tue, 19 Apr 2022 23:15:42 -0400 Subject: [PATCH 074/243] Decent progress on rush auto --- include/subsystems/lift.h | 22 +++++++++++++++++++--- 1 file changed, 19 insertions(+), 3 deletions(-) diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index 9676114..7df177e 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -131,14 +131,30 @@ class Lift */ void control_manual(bool up_btn, bool down_btn, int volt_up, int volt_down) { - is_async = false; + static bool down_hold = false; + static bool init = true; - if(up_btn && lift_motors.rotation(rev) < cfg.softstop_up) + // Allow for setting position while still calling this function + if(init || up_btn || down_btn) + { + init = false; + is_async = false; + } + + double rev = lift_motors.rotation(rotationUnits::rev); + + if(rev < cfg.softstop_down && down_btn) + down_hold = true; + else if( !down_btn ) + down_hold = false; + + if(up_btn && rev < cfg.softstop_up) lift_motors.spin(directionType::fwd, volt_up, voltageUnits::volt); - else if(down_btn && lift_motors.rotation(rev) > cfg.softstop_down) + else if(down_btn && rev > cfg.softstop_down && !down_hold) lift_motors.spin(directionType::rev, volt_down, voltageUnits::volt); else lift_motors.spin(directionType::fwd, 0, voltageUnits::volt); + } /** From 72408fe574b16cde4a7fdd6b3cc185904a1c633b Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sat, 11 Jun 2022 22:08:55 -0400 Subject: [PATCH 075/243] Removed useless items from core --- include/pathfinder.h | 27 --------------- include/pathfinder/fit.h | 14 -------- include/pathfinder/followers/distance.h | 20 ----------- include/pathfinder/followers/encoder.h | 21 ----------- include/pathfinder/io.h | 27 --------------- include/pathfinder/lib.h | 10 ------ include/pathfinder/mathutil.h | 20 ----------- include/pathfinder/modifiers/swerve.h | 14 -------- include/pathfinder/modifiers/tank.h | 9 ----- include/pathfinder/spline.h | 20 ----------- include/pathfinder/structs.h | 43 ----------------------- include/pathfinder/trajectory.h | 18 ---------- include/subsystems/rgb_controller.h | 28 --------------- src/subsystems/rgb_controller.cpp | 46 ------------------------- 14 files changed, 317 deletions(-) delete mode 100644 include/pathfinder.h delete mode 100644 include/pathfinder/fit.h delete mode 100644 include/pathfinder/followers/distance.h delete mode 100644 include/pathfinder/followers/encoder.h delete mode 100644 include/pathfinder/io.h delete mode 100644 include/pathfinder/lib.h delete mode 100644 include/pathfinder/mathutil.h delete mode 100644 include/pathfinder/modifiers/swerve.h delete mode 100644 include/pathfinder/modifiers/tank.h delete mode 100644 include/pathfinder/spline.h delete mode 100644 include/pathfinder/structs.h delete mode 100644 include/pathfinder/trajectory.h delete mode 100644 include/subsystems/rgb_controller.h delete mode 100644 src/subsystems/rgb_controller.cpp diff --git a/include/pathfinder.h b/include/pathfinder.h deleted file mode 100644 index e366d05..0000000 --- a/include/pathfinder.h +++ /dev/null @@ -1,27 +0,0 @@ -#ifndef PATHFINDER_H_DEF -#define PATHFINDER_H_DEF - -#ifdef __cplusplus -extern "C" { -#endif - -#include "../core/include/pathfinder/mathutil.h" -#include "../core/include/pathfinder/structs.h" - -#include "../core/include/pathfinder/fit.h" -#include "../core/include/pathfinder/spline.h" -#include "../core/include/pathfinder/trajectory.h" - -#include "../core/include/pathfinder/modifiers/tank.h" -#include "../core/include/pathfinder/modifiers/swerve.h" - -#include "../core/include/pathfinder/followers/encoder.h" -#include "../core/include/pathfinder/followers/distance.h" - -#include "../core/include/pathfinder/io.h" - -#ifdef __cplusplus -} -#endif - -#endif \ No newline at end of file diff --git a/include/pathfinder/fit.h b/include/pathfinder/fit.h deleted file mode 100644 index 66a10f8..0000000 --- a/include/pathfinder/fit.h +++ /dev/null @@ -1,14 +0,0 @@ -#ifndef PATHFINDER_FIT_H_DEF -#define PATHFINDER_FIT_H_DEF - -#include "../core/include/pathfinder/lib.h" -#include "../core/include/pathfinder/structs.h" - -CAPI void pf_fit_hermite_pre(Waypoint a, Waypoint b, Spline *s); -CAPI void pf_fit_hermite_cubic(Waypoint a, Waypoint b, Spline *s); -CAPI void pf_fit_hermite_quintic(Waypoint a, Waypoint b, Spline *s); - -#define FIT_HERMITE_CUBIC &pf_fit_hermite_cubic -#define FIT_HERMITE_QUINTIC &pf_fit_hermite_quintic - -#endif \ No newline at end of file diff --git a/include/pathfinder/followers/distance.h b/include/pathfinder/followers/distance.h deleted file mode 100644 index 3779549..0000000 --- a/include/pathfinder/followers/distance.h +++ /dev/null @@ -1,20 +0,0 @@ -#ifndef PATHFINDER_FOL_DISTANCE_H_DEF -#define PATHFINDER_FOL_DISTANCE_H_DEF - -#include "../core/include/pathfinder/lib.h" -#include "../core/include/pathfinder/structs.h" - -CAPI typedef struct { - double kp, ki, kd, kv, ka; -} FollowerConfig; - -CAPI typedef struct { - double last_error, heading, output; - int segment, finished; -} DistanceFollower; - -CAPI double pathfinder_follow_distance(FollowerConfig c, DistanceFollower *follower, Segment *trajectory, int trajectory_length, double distance); - -CAPI double pathfinder_follow_distance2(FollowerConfig c, DistanceFollower *follower, Segment segment, int trajectory_length, double distance); - -#endif \ No newline at end of file diff --git a/include/pathfinder/followers/encoder.h b/include/pathfinder/followers/encoder.h deleted file mode 100644 index 7b42d8b..0000000 --- a/include/pathfinder/followers/encoder.h +++ /dev/null @@ -1,21 +0,0 @@ -#ifndef PATHFINDER_FOL_ENCODER_H_DEF -#define PATHFINDER_FOL_ENCODER_H_DEF - -#include "../core/include/pathfinder/structs.h" - -typedef struct { - int initial_position, ticks_per_revolution; - double wheel_circumference; - double kp, ki, kd, kv, ka; -} EncoderConfig; - -typedef struct { - double last_error, heading, output; - int segment, finished; -} EncoderFollower; - -double pathfinder_follow_encoder(EncoderConfig c, EncoderFollower *follower, Segment *trajectory, int trajectory_length, int encoder_tick); - -double pathfinder_follow_encoder2(EncoderConfig c, EncoderFollower *follower, Segment segment, int trajectory_length, int encoder_tick); - -#endif \ No newline at end of file diff --git a/include/pathfinder/io.h b/include/pathfinder/io.h deleted file mode 100644 index ef8d40f..0000000 --- a/include/pathfinder/io.h +++ /dev/null @@ -1,27 +0,0 @@ -#ifndef PATHFINDER_IO_H_DEF -#define PATHFINDER_IO_H_DEF - -#include -#include -#include -#include "../core/include/pathfinder/lib.h" -#include "../core/include/pathfinder/structs.h" - -#define CSV_LEADING_STRING "dt,x,y,position,velocity,acceleration,jerk,heading\n" - -CAPI void intToBytes(int n, char *bytes); -CAPI int bytesToInt(char *bytes); -CAPI void longToBytes(unsigned long long n, char *bytes); -CAPI unsigned long long bytesToLong(char *bytes); -CAPI double longToDouble(unsigned long long l); -CAPI unsigned long long doubleToLong(double d); -CAPI void doubleToBytes(double n, char *bytes); -CAPI double bytesToDouble(char *bytes); - -CAPI void pathfinder_serialize(FILE *fp, Segment *trajectory, int trajectory_length); -CAPI int pathfinder_deserialize(FILE *fp, Segment *target); - -CAPI void pathfinder_serialize_csv(FILE *fp, Segment *trajectory, int trajectory_length); -CAPI int pathfinder_deserialize_csv(FILE *fp, Segment *target); - -#endif \ No newline at end of file diff --git a/include/pathfinder/lib.h b/include/pathfinder/lib.h deleted file mode 100644 index 4c15a58..0000000 --- a/include/pathfinder/lib.h +++ /dev/null @@ -1,10 +0,0 @@ -#ifndef PATHFINDER_LIB_H_DEF -#define PATHFINDER_LIB_H_DEF - -#if defined(WIN32) || defined(_WIN32) || defined(__WIN32) && !defined(__CYGWIN__) - #define CAPI __declspec(dllexport) -#else - #define CAPI -#endif - -#endif \ No newline at end of file diff --git a/include/pathfinder/mathutil.h b/include/pathfinder/mathutil.h deleted file mode 100644 index 170c625..0000000 --- a/include/pathfinder/mathutil.h +++ /dev/null @@ -1,20 +0,0 @@ -#include - -#ifndef PATHFINDER_MATH_UTIL_H_DEF -#define PATHFINDER_MATH_UTIL_H_DEF - -#include "../core/include/pathfinder/lib.h" - -#define PI 3.14159265358979323846 -#define TAU PI*2 - -#define MIN(a,b) (((a)<(b))?(a):(b)) -#define MAX(a,b) (((a)>(b))?(a):(b)) - -CAPI double bound_radians(double angle); - -CAPI double r2d(double angleInRads); - -CAPI double d2r(double angleInDegrees); - -#endif \ No newline at end of file diff --git a/include/pathfinder/modifiers/swerve.h b/include/pathfinder/modifiers/swerve.h deleted file mode 100644 index 58eaf28..0000000 --- a/include/pathfinder/modifiers/swerve.h +++ /dev/null @@ -1,14 +0,0 @@ -#ifndef PATHFINDER_MOD_SWERVE_H_DEF -#define PATHFINDER_MOD_SWERVE_H_DEF - -#include "../core/include/pathfinder/lib.h" -#include "../core/include/pathfinder/structs.h" - -CAPI typedef enum { - SWERVE_DEFAULT -} SWERVE_MODE; - -CAPI void pathfinder_modify_swerve(Segment *original, int length, Segment *front_left, Segment *front_right, - Segment *back_left, Segment *back_right, double wheelbase_width, double wheelbase_depth, SWERVE_MODE mode); - -#endif \ No newline at end of file diff --git a/include/pathfinder/modifiers/tank.h b/include/pathfinder/modifiers/tank.h deleted file mode 100644 index 1b8b8b5..0000000 --- a/include/pathfinder/modifiers/tank.h +++ /dev/null @@ -1,9 +0,0 @@ -#ifndef PATHFINDER_MOD_TANK_H_DEF -#define PATHFINDER_MOD_TANK_H_DEF - -#include "../core/include/pathfinder/lib.h" -#include "../core/include/pathfinder/structs.h" - -CAPI void pathfinder_modify_tank(Segment *original, int length, Segment *left, Segment *right, double wheelbase_width); - -#endif \ No newline at end of file diff --git a/include/pathfinder/spline.h b/include/pathfinder/spline.h deleted file mode 100644 index 401cde7..0000000 --- a/include/pathfinder/spline.h +++ /dev/null @@ -1,20 +0,0 @@ -#ifndef PATHFINDER_SPLINE_H_DEF -#define PATHFINDER_SPLINE_H_DEF - -#include "../core/include/pathfinder/lib.h" -#include "../core/include/pathfinder/structs.h" - - -#define PATHFINDER_SAMPLES_FAST (int)1000 -#define PATHFINDER_SAMPLES_LOW (int)PATHFINDER_SAMPLES_FAST*10 -#define PATHFINDER_SAMPLES_HIGH (int)PATHFINDER_SAMPLES_LOW*10 - -CAPI Coord pf_spline_coords(Spline s, double percentage); -CAPI double pf_spline_deriv(Spline s, double percentage); -CAPI double pf_spline_deriv_2(double a, double b, double c, double d, double e, double k, double p); -CAPI double pf_spline_angle(Spline s, double percentage); - -CAPI double pf_spline_distance(Spline *s, int sample_count); -CAPI double pf_spline_progress_for_distance(Spline s, double distance, int sample_count); - -#endif \ No newline at end of file diff --git a/include/pathfinder/structs.h b/include/pathfinder/structs.h deleted file mode 100644 index 63451c0..0000000 --- a/include/pathfinder/structs.h +++ /dev/null @@ -1,43 +0,0 @@ -#ifndef PATHFINDER_STRUCT_H_DEF -#define PATHFINDER_STRUCT_H_DEF - -#include "../core/include/pathfinder/lib.h" - -CAPI typedef struct { - double x, y, angle; -} Waypoint; - -CAPI typedef struct { - double a, b, c, d, e; - double x_offset, y_offset, angle_offset, knot_distance, arc_length; -} Spline; - -CAPI typedef struct { - double x, y; -} Coord; - -CAPI typedef struct { - double dt, x, y, position, velocity, acceleration, jerk, heading; -} Segment; - -CAPI typedef struct { - double dt, max_v, max_a, max_j, src_v, src_theta, dest_pos, dest_v, dest_theta; - int sample_count; -} TrajectoryConfig; - -CAPI typedef struct { - int filter1, filter2, length; - double dt, u, v, impulse; -} TrajectoryInfo; - -CAPI typedef struct { - Spline *saptr; - double *laptr; - double totalLength; - int length; - int path_length; - TrajectoryInfo info; - TrajectoryConfig config; -} TrajectoryCandidate; - -#endif \ No newline at end of file diff --git a/include/pathfinder/trajectory.h b/include/pathfinder/trajectory.h deleted file mode 100644 index b585167..0000000 --- a/include/pathfinder/trajectory.h +++ /dev/null @@ -1,18 +0,0 @@ -#ifndef PATHFINDER_TRAJECTORY_H_DEF -#define PATHFINDER_TRAJECTORY_H_DEF - -#include "../core/include/pathfinder/lib.h" -#include "../core/include/pathfinder/structs.h" - -CAPI int pathfinder_prepare(Waypoint *path, int path_length, void (*fit)(Waypoint,Waypoint,Spline*), int sample_count, double dt, - double max_velocity, double max_acceleration, double max_jerk, TrajectoryCandidate *cand); -CAPI int pathfinder_generate(TrajectoryCandidate *c, Segment *segments); - -CAPI void pf_trajectory_copy(Segment *src, Segment *dest, int length); - -CAPI TrajectoryInfo pf_trajectory_prepare(TrajectoryConfig c); -CAPI int pf_trajectory_create(TrajectoryInfo info, TrajectoryConfig c, Segment *seg); -CAPI int pf_trajectory_fromSecondOrderFilter(int filter_1_l, int filter_2_l, - double dt, double u, double v, double impulse, int len, Segment *t); - -#endif \ No newline at end of file diff --git a/include/subsystems/rgb_controller.h b/include/subsystems/rgb_controller.h deleted file mode 100644 index 33dfb80..0000000 --- a/include/subsystems/rgb_controller.h +++ /dev/null @@ -1,28 +0,0 @@ -#ifndef _RGB_CON_ -#define _RGB_CON_ - -#include "vex.h" - -/** - * A simple rgb controller for controlling the arduino, which in turn controls the led strip. - * Sends binary over 3 seperate 3 wire ports for up to 7 color modes, and off. - */ -class RGBController -{ - private: - vex::digital_out port1, port2, port3; - - public: - - enum rgb_t - { - Off, Blue, Red, Green, OrangeWhite, Rainbow - }; - - RGBController(rgb_t starting_color, vex::triport::port port1, vex::triport::port port2, vex::triport::port port3); - - void set(rgb_t color); - - -}; -#endif \ No newline at end of file diff --git a/src/subsystems/rgb_controller.cpp b/src/subsystems/rgb_controller.cpp deleted file mode 100644 index 63b8f73..0000000 --- a/src/subsystems/rgb_controller.cpp +++ /dev/null @@ -1,46 +0,0 @@ -#include "../core/include/subsystems/rgb_controller.h" - -RGBController::RGBController(rgb_t starting_color, vex::triport::port port1, vex::triport::port port2, vex::triport::port port3) - : port1(port1), port2(port2), port3(port3) - { - set(starting_color); - } - - void RGBController::set(rgb_t color) - { - switch(color) - { - case Blue: - port1.set(1); - port2.set(0); - port3.set(0); - break; - case Red: - port1.set(0); - port2.set(1); - port3.set(0); - break; - case Green: - port1.set(1); - port2.set(1); - port3.set(0); - break; - case OrangeWhite: - port1.set(0); - port2.set(0); - port3.set(1); - break; - case Rainbow: - port1.set(1); - port2.set(0); - port3.set(1); - break; - - default: - case Off: - port1.set(0); - port2.set(0); - port3.set(0); - break; - } - } \ No newline at end of file From 020d9af6e8ea1c5e994280cf3a1df22c7af7d396 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sat, 11 Jun 2022 23:06:19 -0400 Subject: [PATCH 076/243] Removed spline_path to fix compilation issues --- include/utils/spline_path.h | 57 ------------------------ src/utils/spline_path.cpp | 86 ------------------------------------- 2 files changed, 143 deletions(-) delete mode 100644 include/utils/spline_path.h delete mode 100644 src/utils/spline_path.cpp diff --git a/include/utils/spline_path.h b/include/utils/spline_path.h deleted file mode 100644 index 05f0988..0000000 --- a/include/utils/spline_path.h +++ /dev/null @@ -1,57 +0,0 @@ -#ifndef _SPLINE_ -#define _SPLINE_ - -#include "../core/include/pathfinder.h" - -#include "../core/include/subsystems/tank_drive.h" - - -class SplinePath -{ -public: - struct motion_profile_t - { - // drive_pid controls the speed at which the robot drives forward, - // turn_p is for turning the robot based on the desired heading - float drive_p = .1, drive_i = 0, drive_d = 0; - float turn_p = .05; - - // Maximum velocity, acceleration, and jerk the robot is allowed to achieve (Jerk doesn't matter THAT much...) - double max_v = 10, max_a = 20, max_j = 100; - - // kv and ka are constants fed into the spline system, and are multiplied by the - // velocity setpoint and acceleration setpoint inside the main pathfinder stuff. - // Generally 1/max_v is sufficient for kv (does NOT work for ka) - float kv = 1.0 / max_v, ka = 0; - - // Time delta between loops inside the pathfinder calls - double dt = .01; - - // Misc robot info - double wheel_diam = 4; - int ticks_per_rev = 900; // 300 with blues, 900 with greens, 1800 with reds - double wheelbase_width = 11.5; - }; - - SplinePath(TankDrive &drive_system, vex::inertial &imu, vex::motor &l_enc, vex::motor &r_enc, motion_profile_t &motion_profile); - - bool run_path(Waypoint *point_list, int list_length); - -private: - bool run_path_init = true; - double reset_heading = 0; - - TrajectoryCandidate candidate; - Segment *center_traj, *left_traj, *right_traj; - - EncoderFollower *left_follower, *right_follower; - EncoderConfig enc_conf; - - TankDrive &drive_system; - vex::motor &l_enc, &r_enc; - vex::inertial &imu; - - motion_profile_t &motion_profile; -}; - -#endif \ No newline at end of file diff --git a/src/utils/spline_path.cpp b/src/utils/spline_path.cpp deleted file mode 100644 index aedbb57..0000000 --- a/src/utils/spline_path.cpp +++ /dev/null @@ -1,86 +0,0 @@ -#include "../core/include/utils/spline_path.h" - -SplinePath::SplinePath(TankDrive &drive_system, vex::inertial &imu, vex::motor &l_enc, vex::motor &r_enc, motion_profile_t &motion_profile) -: drive_system(drive_system), l_enc(l_enc), r_enc(r_enc), imu(imu), motion_profile(motion_profile) -{ -} - -/** - * Makes the robot follow a predetermined path defined by point_list array, - * with list_length number of waypoints. The first waypoint should be the - * starting position. - * - * Returns true when the path has finished - */ -bool SplinePath::run_path(Waypoint *point_list, int list_length) -{ - if (run_path_init) - { - // Set up Pathfinder's "EncoderConfig" struct that will be fed into the path generation - enc_conf.initial_position = 0; - enc_conf.ticks_per_revolution = motion_profile.ticks_per_rev; - enc_conf.wheel_circumference = motion_profile.wheel_diam * PI; - enc_conf.kp = motion_profile.drive_p; - enc_conf.ki = motion_profile.drive_i; - enc_conf.kd = motion_profile.drive_d; - enc_conf.kv = motion_profile.kv; - enc_conf.ka = motion_profile.ka; - - // Prepare the "trajectory candidate" with information about the curve (max velocities / accels, type of curve, etc) - pathfinder_prepare(point_list, list_length, FIT_HERMITE_CUBIC, PATHFINDER_SAMPLES_LOW, motion_profile.dt, - motion_profile.max_v, motion_profile.max_a, motion_profile.max_j, &candidate); - - // Allocate the memory for the center, left and right "trajectories", or paths. - center_traj = (Segment *)malloc(sizeof(Segment) * candidate.length); - left_traj = (Segment*) malloc(sizeof(Segment) * candidate.length); - right_traj = (Segment*) malloc(sizeof(Segment) * candidate.length); - - // Generate the main center trajectory - pathfinder_generate(&candidate, center_traj); - - // Generate the left wheel and right wheel paths from the center trajectory - pathfinder_modify_tank(center_traj, candidate.length, left_traj, right_traj, motion_profile.wheelbase_width); - - // Create the "follower" structs, which contains info about the current state of each path when it is running - // (e.g. current error for PID, whether it is finished) - left_follower = (EncoderFollower *)malloc(sizeof(EncoderFollower)); - right_follower = (EncoderFollower *)malloc(sizeof(EncoderFollower)); - - reset_heading = imu.rotation(); - - // Make sure this only runs once per run - run_path_init = false; - } - - double lout = pathfinder_follow_encoder(enc_conf, left_follower, left_traj, candidate.length, l_enc.position(rotationUnits::raw)); - double rout = pathfinder_follow_encoder(enc_conf, right_follower, right_traj, candidate.length, r_enc.position(rotationUnits::raw)); - - double in_heading = r2d(left_follower->heading); - if(in_heading > 180) - in_heading -= 360; - double heading_error = in_heading + (imu.rotation() - reset_heading); - - lout -= motion_profile.turn_p * heading_error; - rout += motion_profile.turn_p * heading_error; - - drive_system.drive_tank(lout, rout); - - if(left_follower->finished && right_follower->finished) - { - // Actively set all velocities of the wheels to 0 - drive_system.stop(); - - // Free the memory allocated in the last run - free(center_traj); - free(left_traj); - free(right_traj); - free(left_follower); - free(right_follower); - - // Re-run initialization for the next path - run_path_init = true; - return true; - } - - return false; -} \ No newline at end of file From d300d5f458cec26827af2434d09374cbb9a92c3d Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 4 Sep 2022 21:36:48 -0400 Subject: [PATCH 077/243] Updated to new SDK --- include/subsystems/lift.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index 7df177e..f99bec6 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -92,7 +92,7 @@ class Lift // Check if there's a hook for a custom sensor. If not, use the motors. if(get_sensor == NULL) - cur_pos = lift_motors.rotation(rev); + cur_pos = lift_motors.position(rev); else cur_pos = get_sensor(); @@ -141,7 +141,7 @@ class Lift is_async = false; } - double rev = lift_motors.rotation(rotationUnits::rev); + double rev = lift_motors.position(rotationUnits::rev); if(rev < cfg.softstop_down && down_btn) down_hold = true; @@ -245,7 +245,7 @@ class Lift if(get_sensor != NULL) lift_pid.update(get_sensor()); else - lift_pid.update(lift_motors.rotation(rev)); + lift_pid.update(lift_motors.position(rev)); // std::cout << "DEBUG OUT: ROTATION " << lift_motors.rotation(rev) << "\n\n"; From 9a9c7c9806ded60ed169a6e8e3d4fc26bc2eeae8 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Fri, 9 Sep 2022 21:57:41 -0400 Subject: [PATCH 078/243] Fixed cyclical includes and missing makefile stuff --- include/subsystems/mecanum_drive.h | 7 +- include/subsystems/odometry/odometry_base.h | 7 +- include/subsystems/odometry/odometry_swerve.h | 47 ---- include/subsystems/odometry/odometry_tank.h | 7 +- include/subsystems/swerve_drive.h | 72 ------ include/subsystems/swerve_module.h | 109 -------- include/utils/generic_auto.h | 5 +- include/utils/pid.h | 7 +- include/utils/vector.h | 5 +- src/subsystems/odometry/odometry_swerve.cpp | 89 ------- src/subsystems/swerve_drive.cpp | 232 ------------------ src/subsystems/swerve_module.cpp | 143 ----------- 12 files changed, 10 insertions(+), 720 deletions(-) delete mode 100644 include/subsystems/odometry/odometry_swerve.h delete mode 100644 include/subsystems/swerve_drive.h delete mode 100644 include/subsystems/swerve_module.h delete mode 100644 src/subsystems/odometry/odometry_swerve.cpp delete mode 100644 src/subsystems/swerve_drive.cpp delete mode 100644 src/subsystems/swerve_module.cpp diff --git a/include/subsystems/mecanum_drive.h b/include/subsystems/mecanum_drive.h index 398b821..cf01c3d 100644 --- a/include/subsystems/mecanum_drive.h +++ b/include/subsystems/mecanum_drive.h @@ -1,5 +1,4 @@ -#ifndef _MECANUMDRIVE_ -#define _MECANUMDRIVE_ +#pragma once #include "vex.h" #include "../core/include/utils/pid.h" @@ -106,6 +105,4 @@ class MecanumDrive bool init = true; -}; - -#endif \ No newline at end of file +}; \ No newline at end of file diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index daf1692..9c9b840 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -1,5 +1,4 @@ -#ifndef _ODOMETRY_ -#define _ODOMETRY_ +#pragma once #include "vex.h" #include "../core/include/robot_specs.h" @@ -71,6 +70,4 @@ class OdometryBase vex::task *handle; vex::mutex mut; position_t current_pos; -}; - -#endif \ No newline at end of file +}; \ No newline at end of file diff --git a/include/subsystems/odometry/odometry_swerve.h b/include/subsystems/odometry/odometry_swerve.h deleted file mode 100644 index fe73180..0000000 --- a/include/subsystems/odometry/odometry_swerve.h +++ /dev/null @@ -1,47 +0,0 @@ -#pragma once - -#include "vex.h" -#include "../core/include/subsystems/odometry/odometry_base.h" -#include "../core/include/subsystems/swerve_drive.h" - -class SwerveDrive; - -typedef struct -{ - double lf_dist, rf_dist, lr_dist, rr_dist; -} stored_info_t; - -static int background_task(void *obj); - -/** - * Odometry controller for a 4x module swerve drivetrain. Can either run in the background or - * called manually via the update() function. - */ -class OdometrySwerve : public OdometryBase -{ -public: - - /** - * Create the odometry object, decide whether to keep it in the background or foreground. - */ - OdometrySwerve(SwerveDrive &drive_system, vex::inertial &imu, bool is_async=true); - - /** - * Manually update the position of the robot. Must be called many times each second for an accurate position. - * Returns the new posiiton. - */ - position_t update(); - -private: - - /** - * Run the calculations required to find a new position based on a stored old position, stored information - * on each swerve module, and information from the sensors stored in the drive_system / imu - */ - static position_t calculate_new_pos(stored_info_t &stored_info, position_t &cur_pos, SwerveDrive &drive_system, vex::inertial &imu); - - SwerveDrive &drive_system; - vex::inertial &imu; - - stored_info_t stored_info; -}; diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index ac376f6..d0eceed 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -1,5 +1,4 @@ -#ifndef _ODOMETRY_TANK_ -#define _ODOMETRY_TANK_ +#pragma once #include "../core/include/subsystems/odometry/odometry_base.h" #include "../core/include/subsystems/custom_encoder.h" @@ -52,6 +51,4 @@ class OdometryTank : public OdometryBase double rotation_offset = 0; -}; - -#endif \ No newline at end of file +}; \ No newline at end of file diff --git a/include/subsystems/swerve_drive.h b/include/subsystems/swerve_drive.h deleted file mode 100644 index c967cea..0000000 --- a/include/subsystems/swerve_drive.h +++ /dev/null @@ -1,72 +0,0 @@ -#pragma once - -#include "../core/include/subsystems/swerve_module.h" -#include "../core/include/subsystems/odometry/odometry_swerve.h" -#include "../core/include/utils/vector.h" -#include "../core/include/utils/pid.h" - -#define ROT_DEADBAND 0.2 -#define LAT_DEADBAND 0.2 - -class OdometrySwerve; - -enum ModulePosition -{ - LEFT_FRONT, RIGHT_FRONT, LEFT_REAR, RIGHT_REAR -}; - -class SwerveDrive -{ - -public: - -/** - * Construct the SwerveDrive object. - */ -SwerveDrive(SwerveModule &left_front, SwerveModule &left_rear, SwerveModule &right_front, SwerveModule &right_rear, vex::inertial &imu); - -/** - * Drive the robot using controller inputs. Deadbands are automatically taken into - * account before passing to the main control method. - */ -void drive(int32_t leftY, int32_t leftX, int32_t rightX); - -/** - * The main control method. Takes a vector and a rotation, and performs vector math to - * calculate the position/speed for each wheel. - */ -void drive(Vector lateral, double rotation); - -/** - * Autonomously drive the robot in (degrees) direction, at (-1.0 -> 1.0) speed, for (inches) distance. - * Indicate a negative speed or distance, or (preferably) a direction of +-180 degrees for backwards. - */ -bool auto_drive(double direction, double speed, double distance); - -/** - * Autonomously turn the robot over it's center axis in degrees. Positive degrees is clockwise, Negative is counter-clockwise - * Speed is in percent (-1.0 -> 1.0) - */ -bool auto_turn(double degrees, double speed); - -void set_drive_pid(PID::pid_config_t &config); -void set_turn_pid(PID::pid_config_t &config); - -/** - * Return the corresponding module to this swerve drive system - */ -SwerveModule& get_module(ModulePosition pos); - -private: - -SwerveModule &left_front, &left_rear, &right_front, &right_rear; -bool auto_drive_init = true; -bool auto_turn_init = true; - -PID *drive_pid, *turn_pid; -vex::inertial &imu; - -OdometrySwerve *odometry; -position_t saved_pos; - -}; diff --git a/include/subsystems/swerve_module.h b/include/subsystems/swerve_module.h deleted file mode 100644 index 1ab559b..0000000 --- a/include/subsystems/swerve_module.h +++ /dev/null @@ -1,109 +0,0 @@ -#ifndef _SWERVEMODULE_ -#define _SWERVEMODULE_ - -#include "vex.h" -using namespace vex; - -#ifndef PI -#define PI 3.141592654 -#endif - -#ifndef PI -#define PI 3.141592654 -#endif - -// Gear teeth (input to output): 16, 35 -#define DIR_GEAR_RATIO (16.0/35.0) // ~0.457 - -// Gear teeth (input to output): 21, 10, 12, 30 -#define DRIVE_GEAR_RATIO ((21.0/10.0)*(12.0/30.0)) // 0.84 - -#define MOTOR_MAX_RPM 3600 - -#define WHEEL_DIAM 2.75 //inches - -class SwerveModule -{ - public: - - /** - * Create a single swerve module, made up of a Drive motor and a Direction motor. - * - * the Drive motor is the central one, with the Direction motor being offset. - */ - SwerveModule(vex::motor &drive, vex::motor &direction); - - /** - * Sets both the speed and direction of the module, taking into account how the motors are geared - * together, and each gear ratio. - * - * @param direction_deg Degrees of rotation for the module's direction (clockwise positive, from top) - * @param speed_pct Speed of the wheel for the module, in percent (-1.0 -> 1.0, positive fwd) - */ - void set(double direction_deg, double speed_pct, int power=2); - - /** - * Sets the direction of the module to X degrees (clockwise positive, from top perspective). - * - * If set_speed is not called (even when the robot is not moving), then the wheel WILL rotate - * despite not being set, due to how the motors are geared together. - * - * Calling set_speed(0) will compensate for this. - * - * @param deg position to set the motor, counter clockwise from the top. - */ - bool set_direction(double deg); - - /** - * Sets the speed of the drive motor, taking into account the speed of the direction motor, - * in percent units (-1.0 -> 1.0) - */ - void set_speed(double percent); - - /** - * Reset the drive encoder to zero - * - * @deprecated Resetting encoders will screw up OdometrySwerve; do not use with odometry. - */ - void reset_distance_driven(); - - /** - * Get 'distance' from the drive motor - * - * TODO take into account the effect of the direction motor on the driven distance - */ - double get_distance_driven(); - - /** - * Return the direction that the module is pointing - */ - double get_module_angle(); - - bool auto_reverse = false; - - private: - - /** - * Grab the maximum RPM of a motor with a certain gearset - * - * values are: - * RED: 100 - * GREEN: 200 - * BLUE: 600 - */ - static double gearset_dps(vex::gearSetting gearing); - - /** - * Improved modulus which correctly calculates negatives - */ - static int mod(int var1, int var2); - - vex::motor &drive, &direction; - - bool inverseDrive; - double lastStoredHeading; - double driveMulitplier; - -}; - -#endif \ No newline at end of file diff --git a/include/utils/generic_auto.h b/include/utils/generic_auto.h index 2a6f6d9..092c1e5 100644 --- a/include/utils/generic_auto.h +++ b/include/utils/generic_auto.h @@ -1,5 +1,4 @@ -#ifndef _GENAUTO_ -#define _GENAUTO_ +#pragma once #include #include @@ -41,5 +40,3 @@ class GenericAuto std::queue state_list; }; - -#endif \ No newline at end of file diff --git a/include/utils/pid.h b/include/utils/pid.h index d804904..0636785 100644 --- a/include/utils/pid.h +++ b/include/utils/pid.h @@ -1,5 +1,4 @@ -#ifndef _PID_ -#define _PID_ +#pragma once #include #include "vex.h" @@ -71,6 +70,4 @@ class PID bool is_checking_on_target = false; timer pid_timer; -}; - -#endif \ No newline at end of file +}; \ No newline at end of file diff --git a/include/utils/vector.h b/include/utils/vector.h index 48d0d05..858ce88 100644 --- a/include/utils/vector.h +++ b/include/utils/vector.h @@ -1,5 +1,4 @@ -#ifndef _VECTOR_ -#define _VECTOR_ +#pragma once #include @@ -113,5 +112,3 @@ double deg2rad(double deg); * General function for converting radians to degrees */ double rad2deg(double r); - -#endif diff --git a/src/subsystems/odometry/odometry_swerve.cpp b/src/subsystems/odometry/odometry_swerve.cpp deleted file mode 100644 index cf13a95..0000000 --- a/src/subsystems/odometry/odometry_swerve.cpp +++ /dev/null @@ -1,89 +0,0 @@ -#include "../core/include/subsystems/odometry/odometry_swerve.h" -#include "../core/include/utils/vector.h" - -OdometrySwerve::OdometrySwerve(SwerveDrive &drive_system, vex::inertial &imu, bool is_async) -: drive_system(drive_system), imu(imu) -{ - memset(&stored_info, 0, sizeof(stored_info_t)); - - if(is_async) - handle = new vex::task(background_task, this); -} - -/** - * Manually update the position of the robot. Must be called many times each second for an accurate position. - * Returns the new posiiton. - */ -position_t OdometrySwerve::update() -{ - position_t new_pos = calculate_new_pos(stored_info,current_pos, drive_system, imu); - - mut.lock(); - this->current_pos = new_pos; - mut.unlock(); - - return current_pos; -} - -/** - * Function containing the code running in the background, if this odometry is running - * asynchronously. - */ -int background_task(void *obj) -{ - OdometrySwerve &odom = *((OdometrySwerve*)obj); - - while(!odom.end_task) - { - odom.update(); - vexDelay(DOWNTIME); - } - - return 0; -} - -/** - * Run the calculations required to find a new position based on a stored old position, stored information - * on each swerve module, and information from the sensors stored in the drive_system / imu - */ -position_t OdometrySwerve::calculate_new_pos(stored_info_t &stored_info, position_t &cur_pos, SwerveDrive &drive_system, vex::inertial &imu) -{ - // Get the change in distance for each drive motor - double lf_delta = drive_system.get_module(LEFT_FRONT).get_distance_driven() - stored_info.lf_dist; - double rf_delta = drive_system.get_module(RIGHT_FRONT).get_distance_driven() - stored_info.rf_dist; - double lr_delta = drive_system.get_module(LEFT_REAR).get_distance_driven() - stored_info.lr_dist; - double rr_delta = drive_system.get_module(RIGHT_REAR).get_distance_driven() - stored_info.rr_dist; - - // Store the vector displacement - Vector lf_disp(drive_system.get_module(LEFT_FRONT).get_module_angle(), lf_delta); - Vector rf_disp(drive_system.get_module(RIGHT_FRONT).get_module_angle(), rf_delta); - Vector lr_disp(drive_system.get_module(LEFT_REAR).get_module_angle(), lr_delta); - Vector rr_disp(drive_system.get_module(RIGHT_REAR).get_module_angle(), rr_delta); - - // Get an overall displacement of the robot - // Adding the vectors cancels out rotation, and leaves the robots actual displacement - Vector delta_displacement = lf_disp + rf_disp + lr_disp + rr_disp; - - // Create a vector from the robot's current position, - // representing the displacement from the origin - Vector::point_t pt = {.x = cur_pos.x, .y = cur_pos.y}; - Vector old_displacement(pt); - - // Add the "change in displacement" to the existing displacement (from 0,0) - Vector new_displacement = old_displacement + delta_displacement; - - position_t out = - { - .x = new_displacement.get_x(), - .y = new_displacement.get_y(), - .rot = imu.heading() - }; - - // Store each module's previous distance driven for the next update - stored_info.lf_dist = drive_system.get_module(LEFT_FRONT).get_distance_driven(); - stored_info.rf_dist = drive_system.get_module(RIGHT_FRONT).get_distance_driven(); - stored_info.lr_dist = drive_system.get_module(LEFT_REAR).get_distance_driven(); - stored_info.rr_dist = drive_system.get_module(RIGHT_REAR).get_distance_driven(); - - return out; -} \ No newline at end of file diff --git a/src/subsystems/swerve_drive.cpp b/src/subsystems/swerve_drive.cpp deleted file mode 100644 index ca59f6f..0000000 --- a/src/subsystems/swerve_drive.cpp +++ /dev/null @@ -1,232 +0,0 @@ -#include "../core/include/subsystems/swerve_drive.h" -#include - -using namespace std; - -/** - * Construct the SwerveDrive object. - */ -SwerveDrive::SwerveDrive(SwerveModule &left_front, SwerveModule &left_rear, SwerveModule &right_front, SwerveModule &right_rear, vex::inertial &imu) -:left_front(left_front), left_rear(left_rear), right_front(right_front), right_rear(right_rear), imu(imu) -{ - // odometry = new OdometrySwerve(*this, imu, true); -} - -/** - * Drive the robot using controller inputs. Deadbands are automatically taken into - * account before passing to the main control method. - * - * @param leftY Left joystick, Y axis (-100 -> 100) - * @param leftX Left joystick, X axis (-100 -> 100) - * @param rightX Right joystick, X axis(-100 -> 100) - */ -void SwerveDrive::drive(int32_t leftY, int32_t leftX, int32_t rightX) -{ - Vector::point_t p = {.x=(leftX / 100.0), .y=(leftY / 100.0)}; - - Vector input_lat(p); - - // Lateral Deadband - if(fabs(input_lat.get_mag()) < LAT_DEADBAND) - Vector input_lat(0,0); - - // Rotational Deadband - if(fabs(rightX / 100.0) < LAT_DEADBAND) - rightX = 0; - - // printf("distance: %f\n", left_front.get_distance_driven()); - - // Convert input to a vector, and pass into main control method - this->drive(input_lat, rightX / 100.0); -} - -/** - * The main control method. Takes a vector and a rotation, and performs vector math to - * calculate the position/speed for each wheel. - */ -void SwerveDrive::drive(Vector lateral, double rotation) -{ - // Each wheel has a different rotation vector - Vector rot_lf(deg2rad(45), rotation); - Vector rot_rf(deg2rad(45+90), rotation); - Vector rot_rr(deg2rad(45+180), rotation); - Vector rot_lr(deg2rad(45+270), rotation); - - // Perform vector addition between the rotation vector and lateral vectors - Vector lf_out = rot_lf + lateral; - Vector rf_out = rot_rf + lateral; - Vector rr_out = rot_rr + lateral; - Vector lr_out = rot_lr + lateral; - - // Set each swerve module to the respective direction / speed - left_front.set(rad2deg(lf_out.get_dir()), lf_out.get_mag()); - right_front.set(rad2deg(rf_out.get_dir()), rf_out.get_mag()); - right_rear.set(rad2deg(rr_out.get_dir()), rr_out.get_mag()); - left_rear.set(rad2deg(lr_out.get_dir()), lr_out.get_mag()); -} - -/** - * Set the PID configuration for the "auto_drive" function - */ -void SwerveDrive::set_drive_pid(PID::pid_config_t &config) -{ - if(drive_pid != NULL) - delete drive_pid; - - this->drive_pid = new PID(config); -} - -/** - * Set the PID configuration for the "auto_turn" function - */ -void SwerveDrive::set_turn_pid(PID::pid_config_t &config) -{ - if(turn_pid != NULL) - delete turn_pid; - - this->turn_pid = new PID(config); -} - -/** - * Autonomously drive the robot in (degrees) direction, at (-1.0 -> 1.0) speed, for (inches) distance. - * Indicate a negative speed or distance, or (preferably) a direction of +-180 degrees for backwards. - * - * NOTE: This function uses relative positioning, and a few calls to it may cause it to drift! - */ -bool SwerveDrive::auto_drive(double direction, double speed, double distance) -{ - // Null check the PID config - if(drive_pid == NULL) - { - fprintf(stderr, "Failed to run auto_drive: Missing PID config\n"); - return true; // true to indicate 'finished' - } - - // INITIALIZATION - if(auto_drive_init) - { - // std::cout << "Init-ing" << std::endl; - // Turn all the wheels in the correct direction before running - bool all_wheels_done = true; - all_wheels_done = all_wheels_done & left_front.set_direction(direction); - all_wheels_done = all_wheels_done & right_front.set_direction(direction); - all_wheels_done = all_wheels_done & left_rear.set_direction(direction); - all_wheels_done = all_wheels_done & right_rear.set_direction(direction); - - // Setting the speed of all wheels to zero will still slowly run the motor, to make sure the wheel is stopped. - // (running the direction motor affects the speed of the wheel due to how it's geared together) - left_front.set_speed(0); - right_front.set_speed(0); - left_rear.set_speed(0); - right_rear.set_speed(0); - - // Make sure all the wheels are done turning before continuing with the 'init' phase - if(!all_wheels_done) - return false; - - saved_pos = odometry->get_position(); - - // set up the PID - drive_pid->reset(); - drive_pid->set_target(distance); - drive_pid->set_limits(-fabs(speed), fabs(speed)); - - auto_drive_init = false; - } - - // TODO fix negatives - double pos_diff = OdometryBase::pos_diff(odometry->get_position(), saved_pos); - - // LOOP - drive_pid->update(pos_diff); - - left_front.set_speed(drive_pid->get()); - right_front.set_speed(drive_pid->get()); - left_rear.set_speed(drive_pid->get()); - right_rear.set_speed(drive_pid->get()); - - // Check if the driving is complete - if(drive_pid->is_on_target()) - { - this->drive(Vector(0,0), 0); // stop the robot - auto_drive_init = true; - return true; - } - - return false; -} - -/** - * Autonomously turn the robot over it's center axis in degrees. Positive degrees is clockwise, Negative is counter-clockwise - * Function is non-blocking, and returns true when it has finished turning. - * - * NOTE: this uses relative positioning, and a few calls may cause it to lose it's desired angle! - */ -bool SwerveDrive::auto_turn(double degrees, double speed) -{ - if(turn_pid == NULL) - { - fprintf(stderr, "Failed to run auto_turn: missing PID config!"); - return true; - } - - // INIT - if(auto_turn_init) - { - // Wait until all the modules are at their 45's before continuing - bool all_wheels_done = true; - all_wheels_done = all_wheels_done & left_front.set_direction(45); - all_wheels_done = all_wheels_done & right_front.set_direction(45 + 90); - all_wheels_done = all_wheels_done & right_rear.set_direction(-45 - 90); - all_wheels_done = all_wheels_done & left_rear.set_direction(-45); - if(!all_wheels_done) - return false; - - saved_pos = odometry->get_position(); - - turn_pid->reset(); - turn_pid->set_limits(-fabs(speed), fabs(speed)); - turn_pid->set_target(degrees); - - auto_turn_init = false; - } - - // LOOP - - turn_pid->update(odometry->get_position().rot); - - left_front.set_speed(turn_pid->get()); - right_front.set_speed(turn_pid->get()); - left_rear.set_speed(turn_pid->get()); - right_rear.set_speed(turn_pid->get()); - - // when the robot is on target, we are done. return true. - if(turn_pid->is_on_target()) - { - drive(Vector(0,0), 0); - auto_turn_init = true; - return true; - } - - return false; -} - -/** - * Return the corresponding module to this swerve drive system - */ -SwerveModule& SwerveDrive::get_module(ModulePosition pos) -{ - switch(pos) - { - case LEFT_FRONT: - return left_front; - case RIGHT_FRONT: - return right_front; - case LEFT_REAR: - return left_rear; - - default: // ONLY if something goes horribly wrong, return the right rear - case RIGHT_REAR: - return right_rear; - } -} \ No newline at end of file diff --git a/src/subsystems/swerve_module.cpp b/src/subsystems/swerve_module.cpp deleted file mode 100644 index a1e2711..0000000 --- a/src/subsystems/swerve_module.cpp +++ /dev/null @@ -1,143 +0,0 @@ -#include "../core/include/subsystems/swerve_module.h" - - -/** - * Create a single swerve module, made up of a Drive motor and a Direction motor. - * - * the Drive motor is the central one, with the Direction motor being offset. - */ -SwerveModule::SwerveModule(vex::motor &drive, vex::motor &direction) - : drive(drive), direction(direction) -{ - lastStoredHeading = 0.0; - inverseDrive = false; - driveMulitplier = 0.0; -} - -/** - * Sets both the speed and direction of the module, taking into account how the motors are geared - * together, and each gear ratio. - * - * @param direction_deg Degrees of rotation for the module's direction (clockwise positive, from top) - * @param speed_pct Speed of the wheel for the module, in percent (-1.0 -> 1.0, positive fwd) - * @param power=2 Square / Cube the input for a exponential curve for more lower speed control - */ -void SwerveModule::set(double direction_deg, double speed_pct, int power) -{ - // Don't move the direction wheel unless we need to - if(speed_pct == 0.0) - direction_deg = lastStoredHeading; - else - lastStoredHeading = direction_deg; - - set_direction(direction_deg); - if(power % 2 == 0) - set_speed((speed_pct > 0 ? 1.0 : -1.0) * pow(speed_pct, power)); - else - set_speed(pow(speed_pct, power)); -} - -/** - * Sets the direction of the module to X degrees (clockwise positive, from top perspective). - * - * If set_speed is not called (even when the robot is not moving), then the wheel WILL rotate - * despite not being set, due to how the motors are geared together. - * - * Calling set_speed(0) will compensate for this. - * - * @param deg position to set the motor, counter clockwise from the top. - */ -bool SwerveModule::set_direction(double deg) -{ - double pos = direction.position(vex::rotationUnits::deg) * DIR_GEAR_RATIO; - - // Find the degrees of the direction module between -180 and +180, with 0 being forward. - int modpos = mod(pos, 360); - modpos -= (modpos > 180) ? 360 : 0; - - // Delta between where we are (modpos) and where we need to be (deg) - // Normalize the delta to make sure the maximum movement of the direction motor is 90 degrees. - // If the delta is above 90, then the wheel will go to the nearest 180 from the target, and move the drive wheel backwards. - int delta = deg - modpos; - int normalizedDelta = delta + (abs(delta) > 90 ? (delta > 0 ? -180 : 180) : 0); - - inverseDrive = abs(delta) > 90 ? true : false; - - // Slow down the drive if we aren't close to the set direction yet (use the cube of the error) - driveMulitplier = pow(1 - (abs(normalizedDelta) / 90.0), 3); - double setpnt = (normalizedDelta + pos) / DIR_GEAR_RATIO; - - direction.spinTo(setpnt, vex::rotationUnits::deg, 100, vex::velocityUnits::pct, false); - - return fabs(setpnt - direction.rotation(rotationUnits::deg)) < 2; -} - -/** - * Sets the speed of the drive motor, taking into account the speed of the direction motor, - * in percent units (-1.0 -> 1.0) - */ -void SwerveModule::set_speed(double percent) -{ - // take into account how the RPM of the direction motor affects the RPM of the drive wheel - //double speed_diff_dps = 0;//direction.velocity(vex::velocityUnits::dps) * DIR_GEAR_RATIO * -.2; - // Difference is negligable. Not worth the effort of getting it right. - drive.setReversed(inverseDrive); - - drive.spin(vex::directionType::fwd, percent * 100.0, vex::velocityUnits::pct); -} - -/** - * Reset the drive encoder to zero - */ -void SwerveModule::reset_distance_driven() -{ - drive.resetPosition(); -} - -/** - * Get 'distance' from the drive motor. - * Will ALWAYS be positive. - */ -double SwerveModule::get_distance_driven() -{ - // return drive.position(vex::rotationUnits::rev); - return fabs(WHEEL_DIAM * PI * drive.position(vex::rotationUnits::rev) * DRIVE_GEAR_RATIO); -} - -/** - * Return the direction that the module is pointing - */ -double SwerveModule::get_module_angle() -{ - // Limit to 0->360 - return fmod(direction.rotation(vex::rotationUnits::deg) * DIR_GEAR_RATIO, 360); -} - -/** - * Grab the maximum degrees per second of a motor with a certain gearset - * 36 : 1 = reds - * 18 : 1 = greens - * 6 : 1 = blues - */ -double SwerveModule::gearset_dps(vex::gearSetting gearing) -{ - switch (gearing) - { - case vex::gearSetting::ratio36_1: - return (1.0 / 36.0) * MOTOR_MAX_RPM * 360.0; - case vex::gearSetting::ratio18_1: - return (1.0 / 18.0) * MOTOR_MAX_RPM * 360.0; - case vex::gearSetting::ratio6_1: - return (1.0 / 6.0) * MOTOR_MAX_RPM * 360.0; - default: - return 0.0; - } -} - -/** - * Improved modulus which correctly calculates negatives - */ -int SwerveModule::mod(int a, int b) -{ - return (b + (a % b)) % b; -} \ No newline at end of file From f43ec74dd054912f80246f9ac1dc169b79a51206 Mon Sep 17 00:00:00 2001 From: Christopher Nokes Date: Fri, 16 Sep 2022 21:27:09 -0400 Subject: [PATCH 079/243] Initial commit. --- include/subsystems/flywheel.h | 25 ++++++++++++++++ src/subsystems/flywheel.cpp | 56 +++++++++++++++++++++++++++++++++++ 2 files changed, 81 insertions(+) create mode 100644 include/subsystems/flywheel.h create mode 100644 src/subsystems/flywheel.cpp diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h new file mode 100644 index 0000000..f36f9cd --- /dev/null +++ b/include/subsystems/flywheel.h @@ -0,0 +1,25 @@ +#include "vex.h" +#include "../core/include/robot_specs.h" +#include "../core/include/utils/pid.h" + +using namespace vex; + +class Flywheel{ + public: + + Flywheel(motor_group &motors, robot_specs_t &config, PID &pid); + + void spin(double speed, directionType dir=fwd); + bool spinRPM(int rpm); + void stop(); + void spinToDistance(double distance); + + private: + + motor_group &motors; + robot_specs_t &config; + PID pid; + const int VOLTAGECONSTANT = 12; + bool inRPMLoop = false; + +}; \ No newline at end of file diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp new file mode 100644 index 0000000..5ef527d --- /dev/null +++ b/src/subsystems/flywheel.cpp @@ -0,0 +1,56 @@ +/********************************************************* +* +* File: Flywheel.cpp +* Purpose: Generalized flywheel class for Core. +* Author: Chris Nokes +* +********************************************************** +* EDIT HISTORY +********************************************************** +* 09/16/2022 Created file, added constructor, spins, RPM setting, stop. +*********************************************************/ + +#include "../core/include/subsystems/flywheel.h" +#include "../core/include/utils/pid.h" +#include "vex.h" + +using namespace vex; + +/* +* Create the Flywheel object. +*/ +Flywheel::Flywheel(motor_group &motors, robot_specs_t &config, PID &pid) + :motors(motors), config(config), pid(pid){ } + +// Spin motors using voltage; defaults forward at 12 volts +// Speed is between -1 and 1. +void Flywheel::spin(double speed, directionType dir){ + motors.spin(dir, speed * VOLTAGECONSTANT, voltageUnits::volt); +} + + +// Gets to RPM; continue calling at some delay +bool Flywheel::spinRPM(int RPM) { + // run if this is the first time calling + if(!inRPMLoop){ + pid.set_target(RPM); + inRPMLoop = true; + } + + pid.update(motors.velocity(velocityUnits::rpm)); + + if(pid.is_on_target()) { + inRPMLoop = false; + return true; + } return false; +} + +// stop +void Flywheel::stop() { + motors.stop(); +} + +// Sets RPM based on distance to lubber's hole +void Flywheel::spinToDistance(double distance){ + +} \ No newline at end of file From b5b968fe4b01753e31c5c8be03b06121e6c4b932 Mon Sep 17 00:00:00 2001 From: Christopher Nokes Date: Sun, 18 Sep 2022 15:57:40 -0400 Subject: [PATCH 080/243] Added async functionality to Flywheel. --- include/subsystems/flywheel.h | 12 ++++++--- src/subsystems/flywheel.cpp | 51 ++++++++++++++++++++++------------- 2 files changed, 41 insertions(+), 22 deletions(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index f36f9cd..b3b6da9 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -10,16 +10,20 @@ class Flywheel{ Flywheel(motor_group &motors, robot_specs_t &config, PID &pid); void spin(double speed, directionType dir=fwd); - bool spinRPM(int rpm); + void spinRPM(int rpm); void stop(); - void spinToDistance(double distance); + void stopThread(); + + double getRPM(); + PID* getPID(); + motor_group* getMotors(); private: motor_group &motors; robot_specs_t &config; PID pid; - const int VOLTAGECONSTANT = 12; bool inRPMLoop = false; - + double RPM = -1.0; + thread rpmThread; }; \ No newline at end of file diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 5ef527d..04c4cd0 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -8,11 +8,13 @@ * EDIT HISTORY ********************************************************** * 09/16/2022 Created file, added constructor, spins, RPM setting, stop. +* 09/18/2022 Added async functionality. *********************************************************/ #include "../core/include/subsystems/flywheel.h" #include "../core/include/utils/pid.h" #include "vex.h" +#include using namespace vex; @@ -25,32 +27,45 @@ Flywheel::Flywheel(motor_group &motors, robot_specs_t &config, PID &pid) // Spin motors using voltage; defaults forward at 12 volts // Speed is between -1 and 1. void Flywheel::spin(double speed, directionType dir){ - motors.spin(dir, speed * VOLTAGECONSTANT, voltageUnits::volt); + motors.spin(dir, speed * 12, voltageUnits::volt); } - -// Gets to RPM; continue calling at some delay -bool Flywheel::spinRPM(int RPM) { - // run if this is the first time calling - if(!inRPMLoop){ - pid.set_target(RPM); - inRPMLoop = true; +// spin this flywheel at a given RPM, async; runs until stop(), stopThread(), or a new spinRPM() is called. +int spinRPMThread(void* wheelPointer) { + Flywheel* wheel = (Flywheel*) wheelPointer; + wheel->getPID()->set_target((double) wheel->getRPM()); // get the pid from the wheel and set its target to the RPM stored in the wheel. + while(true) { + wheel->getPID()->update(wheel->getMotors()->velocity(velocityUnits::rpm)); // check the current velocity and update the PID with it. + wheel->getMotors()->spin(fwd, wheel->getPID()->get() * 12, voltageUnits::volt); // set the motors to whatever PID tells them to do + vexDelay(20); } + return 0; // only here to make the compiler SHUT UP +} - pid.update(motors.velocity(velocityUnits::rpm)); - - if(pid.is_on_target()) { - inRPMLoop = false; - return true; - } return false; +// starts / restarts RPM thread at new value +void Flywheel::spinRPM(int inputRPM) { + RPM = inputRPM; + rpmThread.interrupt(); + rpmThread = thread(spinRPMThread, this); } -// stop +// return the current value that the RPM should be set to; +double Flywheel::getRPM() { return RPM; } + +// Returns a POINTER TO the PID; only for use in the spinRPMThread function. +PID* Flywheel::getPID() { return &pid; } + +// Returns a POINTER TO the motors; only for use in the spinRPMThread function. +motor_group* Flywheel::getMotors() { return &motors; } + +// stop the RPM thread and the wheel void Flywheel::stop() { + rpmThread.interrupt(); motors.stop(); } -// Sets RPM based on distance to lubber's hole -void Flywheel::spinToDistance(double distance){ - + +// end the thread but keep spinning the wheel; not sure why anyone would use this but here it is anyway. +void Flywheel::stopThread() { + rpmThread.interrupt(); } \ No newline at end of file From b5c3a32f0f22a6099495f890b2bc81bcf2a62617 Mon Sep 17 00:00:00 2001 From: Christopher Nokes Date: Sun, 18 Sep 2022 18:06:11 -0400 Subject: [PATCH 081/243] Handling McGee's requests, pt. 1. --- include/subsystems/flywheel.h | 8 +++----- src/subsystems/flywheel.cpp | 19 ++++++++++--------- 2 files changed, 13 insertions(+), 14 deletions(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index b3b6da9..f7c9fe1 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -7,9 +7,9 @@ using namespace vex; class Flywheel{ public: - Flywheel(motor_group &motors, robot_specs_t &config, PID &pid); + Flywheel(motor_group &motors, PID &pid); - void spin(double speed, directionType dir=fwd); + void spin_raw(double speed, directionType dir=fwd); void spinRPM(int rpm); void stop(); void stopThread(); @@ -21,9 +21,7 @@ class Flywheel{ private: motor_group &motors; - robot_specs_t &config; PID pid; - bool inRPMLoop = false; double RPM = -1.0; - thread rpmThread; + task rpmTask; }; \ No newline at end of file diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 04c4cd0..84c3a5a 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -14,19 +14,18 @@ #include "../core/include/subsystems/flywheel.h" #include "../core/include/utils/pid.h" #include "vex.h" -#include using namespace vex; /* * Create the Flywheel object. */ -Flywheel::Flywheel(motor_group &motors, robot_specs_t &config, PID &pid) - :motors(motors), config(config), pid(pid){ } +Flywheel::Flywheel(motor_group &motors, PID &pid) + :motors(motors), pid(pid){ } // Spin motors using voltage; defaults forward at 12 volts // Speed is between -1 and 1. -void Flywheel::spin(double speed, directionType dir){ +void Flywheel::spin_raw(double speed, directionType dir){ motors.spin(dir, speed * 12, voltageUnits::volt); } @@ -44,9 +43,11 @@ int spinRPMThread(void* wheelPointer) { // starts / restarts RPM thread at new value void Flywheel::spinRPM(int inputRPM) { - RPM = inputRPM; - rpmThread.interrupt(); - rpmThread = thread(spinRPMThread, this); + if(inputRPM != RPM) { + RPM = inputRPM; + rpmTask.stop(); + rpmTask = task(spinRPMThread, this); + } } // return the current value that the RPM should be set to; @@ -60,12 +61,12 @@ motor_group* Flywheel::getMotors() { return &motors; } // stop the RPM thread and the wheel void Flywheel::stop() { - rpmThread.interrupt(); + rpmTask.stop(); motors.stop(); } // end the thread but keep spinning the wheel; not sure why anyone would use this but here it is anyway. void Flywheel::stopThread() { - rpmThread.interrupt(); + rpmTask.stop(); } \ No newline at end of file From 3943caec8f6a2b143ebfba612f59ca44c9e08801 Mon Sep 17 00:00:00 2001 From: Christopher Nokes Date: Sun, 18 Sep 2022 18:57:16 -0400 Subject: [PATCH 082/243] Merge --- include/subsystems/odometry/odometry_tank.h | 2 +- include/utils/feedforward.h | 61 +++++ include/utils/math_util.h | 18 ++ include/utils/pure_pursuit.h | 20 +- include/utils/{vector.h => vector2d.h} | 228 +++++++++--------- src/subsystems/custom_encoder.cpp | 2 +- src/subsystems/mecanum_drive.cpp | 25 +- src/subsystems/odometry/odometry_base.cpp | 2 +- src/subsystems/odometry/odometry_tank.cpp | 8 +- src/subsystems/tank_drive.cpp | 14 +- src/utils/math_util.cpp | 29 +++ src/utils/pure_pursuit.cpp | 70 +++--- src/utils/{vector.cpp => vector2d.cpp} | 250 ++++++++++---------- 13 files changed, 420 insertions(+), 309 deletions(-) create mode 100644 include/utils/feedforward.h create mode 100644 include/utils/math_util.h rename include/utils/{vector.h => vector2d.h} (80%) create mode 100644 src/utils/math_util.cpp rename src/utils/{vector.cpp => vector2d.cpp} (70%) diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index d0eceed..e417efb 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -2,7 +2,7 @@ #include "../core/include/subsystems/odometry/odometry_base.h" #include "../core/include/subsystems/custom_encoder.h" -#include "../core/include/utils/vector.h" +#include "../core/include/utils/vector2d.h" #include "../core/include/robot_specs.h" static int background_task(void* odom_obj); diff --git a/include/utils/feedforward.h b/include/utils/feedforward.h new file mode 100644 index 0000000..f2fae43 --- /dev/null +++ b/include/utils/feedforward.h @@ -0,0 +1,61 @@ +#pragma once + +/** + * FeedForward + * + * Stores the feedfoward constants, and allows for quick computation. + * Feedfoward should be used in systems that require smooth precise movements + * and have high inertia, such as drivetrains and lifts. + * + * This is best used alongside a PID loop, with the form: + * output = pid.get() + feedforward.calculate(v, a); + * + * In this case, the feedforward does the majority of the heavy lifting, and the + * pid loop only corrects for inconsistencies + * + * For information about tuning feedforward, I reccommend looking at this post: + * https://www.chiefdelphi.com/t/paper-frc-drivetrain-characterization/160915 + * (yes I know it's for FRC but trust me, it's useful) + * + * @author Ryan McGee + * @date 6/13/2022 + */ +class FeedForward +{ + public: + + /** + * kS - Coefficient to overcome static friction: the point at which the motor *starts* to move. + * kV - Veclocity coefficient: the power required to keep the mechanism in motion. Multiplied by the requested velocity. + * kA - Acceleration coefficient: the power required to change the mechanism's speed. Multiplied by the requested acceleration. + * kG - Gravity coefficient: only needed for lifts. The power required to overcome gravity and stay at steady state. + * Should relate to acceleration due to gravity and mass of the lift. + */ + typedef struct + { + double kS, kV, kA, kG; + } ff_config_t; + + + FeedForward(ff_config_t &cfg) : cfg(cfg) {} + + /** + * @brief Perform the feedforward calculation + * + * This calculation is the equation: + * F = kG + kS*sgn(v) + kV*v + kA*a + * + * @param v Requested velocity of system + * @param a Requested acceleration of system + * @return A feedforward that should closely represent the system if tuned correctly + */ + double calculate(double v, double a) + { + return (cfg.kS * (v > 0 ? 1 : v < 0 ? -1 : 0)) + (cfg.kV * v) + (cfg.kA * a) + cfg.kG; + } + + private: + + ff_config_t &cfg; + +}; \ No newline at end of file diff --git a/include/utils/math_util.h b/include/utils/math_util.h new file mode 100644 index 0000000..a27c5b2 --- /dev/null +++ b/include/utils/math_util.h @@ -0,0 +1,18 @@ +#pragma once + +/** +* Constrain the input between a minimum and a maximum value +* +* @param val the value to be restrained +* @param low the minimum value that will be returned +* @param high the maximum value that will be returned +**/ +double clamp(double value, double low, double high); + +/** +* Returns the sign of a number +* @param x +* +* returns the sign +/-1 of x. 0 if x is 0 +**/ +double sign(double x); \ No newline at end of file diff --git a/include/utils/pure_pursuit.h b/include/utils/pure_pursuit.h index 818fa2f..64c56dc 100644 --- a/include/utils/pure_pursuit.h +++ b/include/utils/pure_pursuit.h @@ -1,7 +1,7 @@ #pragma once #include -#include "../core/include/utils/vector.h" +#include "../core/include/utils/vector2d.h" #include "vex.h" using namespace vex; @@ -27,12 +27,12 @@ namespace PurePursuit { double dir; double mag; - Vector::point_t getPoint() { + Vector2D::point_t getPoint() { return {x, y}; } - Vector getTangent() { - return Vector(dir, mag); + Vector2D getTangent() { + return Vector2D(dir, mag); } }; @@ -40,16 +40,16 @@ namespace PurePursuit { * Returns points of the intersections of a line segment and a circle. The line * segment is defined by two points, and the circle is defined by a center and radius. */ - static std::vector line_circle_intersections(Vector::point_t center, double r, Vector::point_t point1, Vector::point_t point2); + static std::vector line_circle_intersections(Vector2D::point_t center, double r, Vector2D::point_t point1, Vector2D::point_t point2); /** * Selects a look ahead from all the intersections in the path. */ - static Vector::point_t get_lookahead(std::vector path, Vector::point_t robot_loc, double radius); + static Vector2D::point_t get_lookahead(std::vector path, Vector2D::point_t robot_loc, double radius); /** * Injects points in a path without changing the curvature with a certain spacing. */ - static std::vector inject_path(std::vector path, double spacing); + static std::vector inject_path(std::vector path, double spacing); /** * Returns a smoothed path maintaining the start and end of the path. @@ -62,9 +62,9 @@ namespace PurePursuit { * https://medium.com/@jaems33/understanding-robot-motion-path-smoothing-5970c8363bc4 */ - static std::vector smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance); + static std::vector smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance); - static std::vector smooth_path_cubic(std::vector path, double res); + static std::vector smooth_path_cubic(std::vector path, double res); /** * Interpolates a smooth path given a list of waypoints using hermite splines. @@ -74,5 +74,5 @@ namespace PurePursuit { * @param steps The number of points interpolated between points. * @return The smoothed path. */ - static std::vector smooth_path_hermite(std::vector path, double step); + static std::vector smooth_path_hermite(std::vector path, double step); } \ No newline at end of file diff --git a/include/utils/vector.h b/include/utils/vector2d.h similarity index 80% rename from include/utils/vector.h rename to include/utils/vector2d.h index 858ce88..1e3bbb8 100644 --- a/include/utils/vector.h +++ b/include/utils/vector2d.h @@ -1,114 +1,114 @@ -#pragma once - -#include - -#ifndef PI -#define PI 3.141592654 -#endif - -class Vector -{ -public: - - /** - * Data structure representing an X,Y coordinate - */ - struct point_t - { - double x, y; - - double dist(const point_t other) - { - return sqrt(pow(this->x - other.x, 2) + pow(this->y - other.y, 2)); - } - - // Vector addition operation on points - point_t operator+(const point_t &other) - { - point_t p - { - .x = this->x + other.x, - .y = this->y + other.y - }; - return p; - } - - // Vector subtraction operation on points - point_t operator-(const point_t &other) - { - point_t p - { - .x = this->x - other.x, - .y = this->y - other.y - }; - return p; - } - }; - - /** - * Construct a vector object. - * - * @param dir Direction, in radians. 'foward' is 0, clockwise positive when viewed from the top. - * @param mag Magnitude. - */ - Vector(double dir, double mag); - - /** - * Construct a vector object from a cartesian point. - * - * @param p point_t.x , point_t.y - */ - Vector(point_t &p); - - /** - * Get the direction of the vector, in radians. - * '0' is forward, clockwise positive when viewed from the top. - * - * Use r2d() to convert. - */ - double get_dir() const; - - /** - * Get the magnitude of the vector - */ - double get_mag() const; - - /** - * Get the X component of the vector; positive to the right. - */ - double get_x() const; - - /** - * Get the Y component of the vector, positive forward. - */ - double get_y() const; - - /** - * Changes the magnetude of the vector to 1 - */ - Vector normalize(); - - /** - * Returns a point from the vector - */ - Vector::point_t point(); - - Vector operator*(const double &x); - Vector operator+(const Vector &other); - Vector operator-(const Vector &other); - -private: - - double dir, mag; - -}; - -/** - * General function for converting degrees to radians - */ -double deg2rad(double deg); - -/** - * General function for converting radians to degrees - */ -double rad2deg(double r); +#pragma once + +#include + +#ifndef PI +#define PI 3.141592654 +#endif + +class Vector2D +{ +public: + + /** + * Data structure representing an X,Y coordinate + */ + struct point_t + { + double x, y; + + double dist(const point_t other) + { + return sqrt(pow(this->x - other.x, 2) + pow(this->y - other.y, 2)); + } + + // Vector2D addition operation on points + point_t operator+(const point_t &other) + { + point_t p + { + .x = this->x + other.x, + .y = this->y + other.y + }; + return p; + } + + // Vector2D subtraction operation on points + point_t operator-(const point_t &other) + { + point_t p + { + .x = this->x - other.x, + .y = this->y - other.y + }; + return p; + } + }; + + /** + * Construct a vector object. + * + * @param dir Direction, in radians. 'foward' is 0, clockwise positive when viewed from the top. + * @param mag Magnitude. + */ + Vector2D(double dir, double mag); + + /** + * Construct a vector object from a cartesian point. + * + * @param p point_t.x , point_t.y + */ + Vector2D(point_t &p); + + /** + * Get the direction of the vector, in radians. + * '0' is forward, clockwise positive when viewed from the top. + * + * Use r2d() to convert. + */ + double get_dir() const; + + /** + * Get the magnitude of the vector + */ + double get_mag() const; + + /** + * Get the X component of the vector; positive to the right. + */ + double get_x() const; + + /** + * Get the Y component of the vector, positive forward. + */ + double get_y() const; + + /** + * Changes the magnetude of the vector to 1 + */ + Vector2D normalize(); + + /** + * Returns a point from the vector + */ + Vector2D::point_t point(); + + Vector2D operator*(const double &x); + Vector2D operator+(const Vector2D &other); + Vector2D operator-(const Vector2D &other); + +private: + + double dir, mag; + +}; + +/** + * General function for converting degrees to radians + */ +double deg2rad(double deg); + +/** + * General function for converting radians to degrees + */ +double rad2deg(double r); diff --git a/src/subsystems/custom_encoder.cpp b/src/subsystems/custom_encoder.cpp index 81472ac..64f3662 100644 --- a/src/subsystems/custom_encoder.cpp +++ b/src/subsystems/custom_encoder.cpp @@ -1,4 +1,4 @@ -#include "../core/include/subsystems/custom_encoder.h" +#include "../core/include/subsystems/custom_encoder.h" CustomEncoder::CustomEncoder(vex::triport::port &port, double ticks_per_rev) : super(port) diff --git a/src/subsystems/mecanum_drive.cpp b/src/subsystems/mecanum_drive.cpp index 962a3bc..0fcf6af 100644 --- a/src/subsystems/mecanum_drive.cpp +++ b/src/subsystems/mecanum_drive.cpp @@ -1,4 +1,6 @@ #include "../core/include/subsystems/mecanum_drive.h" +#include "../core/include/utils/vector2d.h" +#include "../core/include/utils/math_util.h" /** * Create the Mecanum drivetrain object @@ -31,20 +33,20 @@ MecanumDrive::MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex: */ void MecanumDrive::drive_raw(double direction_deg, double magnitude, double rotation) { - double direction = (PI / 180.0) * direction_deg; - + double direction = deg2rad(direction_deg); + // ALGORITHM - "rotate" the vector by 45 degrees and apply each corner to a wheel // .. Oh, and mix rotation too double lf = (magnitude * cos(direction - (PI / 4.0))) + rotation; double rf = (magnitude * cos(direction + (PI / 4.0))) - rotation; double lr = (magnitude * cos(direction + (PI / 4.0))) + rotation; double rr = (magnitude * cos(direction - (PI / 4.0))) - rotation; - + // Limit the output between -1.0 and +1.0 - lf = lf > 1.0 ? 1.0 : (lf < -1.0 ? -1.0 : lf); - rf = rf > 1.0 ? 1.0 : (rf < -1.0 ? -1.0 : rf); - lr = lr > 1.0 ? 1.0 : (lr < -1.0 ? -1.0 : lr); - rr = rr > 1.0 ? 1.0 : (rr < -1.0 ? -1.0 : rr); + lf = clamp(lf, -1.0, 1.0); + rf = clamp(rf, -1.0, 1.0); + lr = clamp(lr, -1.0, 1.0); + rr = clamp(rr, -1.0, 1.0); // Finally, spin the motors left_front.spin(vex::directionType::fwd, lf * 100.0, vex::velocityUnits::pct); @@ -68,15 +70,16 @@ void MecanumDrive::drive(double left_y, double left_x, double right_x, int power // LATERAL CONTROLS - convert cartesion to a vector double magnitude = sqrt(pow(left_y / 100.0, 2) + pow(left_x / 100.0, 2)); magnitude = pow(magnitude, power); - + double direction = atan2(left_x / 100.0, left_y / 100.0); // ROTATIONAL CONTROLS - just the right x joystick - // Ternary makes sure that if the "power" is even, the rotation keeps it's sign double rotation = right_x / 100.0; - rotation = (power%2 == 0 ? rotation < 0 ? -1.0 : 1.0 : 1.0) * pow(rotation, power); - return this->drive_raw(direction * (180.0 / PI), magnitude, rotation); + // + rotation = sign(rotation) * fabs(pow(rotation, power)); + + return this->drive_raw(rad2deg(direction), magnitude, rotation); } /** diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index ffa872c..3c55330 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -1,5 +1,5 @@ #include "../core/include/subsystems/odometry/odometry_base.h" -#include "../core/include/utils/vector.h" +#include "../core/include/utils/vector2d.h" /** * Gets the current position and rotation diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 111cca3..c801c2f 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -143,14 +143,14 @@ position_t OdometryTank::calculate_new_pos(robot_specs_t &config, position_t &cu double angle = angle_deg * PI / 180.0; // Degrees to radians // Create a vector from the change in distance in the current direction of the robot - Vector chg_vec(angle, dist_driven); + Vector2D chg_vec(angle, dist_driven); // Create a vector from the current position in reference to X,Y=0,0 - Vector::point_t curr_point = {.x = curr_pos.x, .y = curr_pos.y}; - Vector curr_vec(curr_point); + Vector2D::point_t curr_point = {.x = curr_pos.x, .y = curr_pos.y}; + Vector2D curr_vec(curr_point); // Tack on the "difference" vector to the current vector - Vector new_vec = curr_vec + chg_vec; + Vector2D new_vec = curr_vec + chg_vec; new_pos.x = new_vec.get_x(); new_pos.y = new_vec.get_y(); diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index e9c4839..bd99b81 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -92,9 +92,9 @@ bool TankDrive::drive_forward(double inches, double speed, double correction, di drive_pid.reset(); // Use vector math to get an X and Y - Vector current_pos({saved_pos.x , saved_pos.y}); - Vector delta_pos(deg2rad(saved_pos.rot), inches); - Vector setpt_vec = current_pos + delta_pos; + Vector2D current_pos({saved_pos.x , saved_pos.y}); + Vector2D delta_pos(deg2rad(saved_pos.rot), inches); + Vector2D setpt_vec = current_pos + delta_pos; // Save the new X and Y values pos_setpt = {.x=setpt_vec.get_x(), .y=setpt_vec.get_y()}; @@ -192,13 +192,13 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti position_t end_pos = {.x=x, .y=y}; // Create a point (and vector) to get the direction - Vector::point_t pos_diff_pt = + Vector2D::point_t pos_diff_pt = { .x = x - current_pos.x, .y = y - current_pos.y }; - Vector point_vec(pos_diff_pt); + Vector2D point_vec(pos_diff_pt); // Get the distance between 2 points double dist_left = OdometryBase::pos_diff(current_pos, end_pos); @@ -334,9 +334,9 @@ double TankDrive::modify_inputs(double input, int power) bool TankDrive::pure_pursuit(std::vector path, double radius, double speed, double res, directionType dir) { is_pure_pursuit = true; - std::vector smoothed_path = PurePursuit::smooth_path_hermite(path, res); + std::vector smoothed_path = PurePursuit::smooth_path_hermite(path, res); - Vector::point_t lookahead = PurePursuit::get_lookahead(smoothed_path, {odometry->get_position().x, odometry->get_position().y}, radius); + Vector2D::point_t lookahead = PurePursuit::get_lookahead(smoothed_path, {odometry->get_position().x, odometry->get_position().y}, radius); //printf("%f\t%f\n", odometry->get_position().x, odometry->get_position().y); //printf("%f\t%f\n", lookahead.x, lookahead.y); bool is_last_point = (path.back().x == lookahead.x) && (path.back().y == lookahead.y); diff --git a/src/utils/math_util.cpp b/src/utils/math_util.cpp new file mode 100644 index 0000000..51b5555 --- /dev/null +++ b/src/utils/math_util.cpp @@ -0,0 +1,29 @@ +#include "../core/include/utils/math_util.h" + +/** +* Constrain the input between a minimum and a maximum value +* +* @param val the value to be restrained +* @param low the minimum value that will be returned +* @param high the maximum value that will be returned +**/ +double clamp(double val, double low, double high){ + if (val < low){ + return low; + } else if (val > high){ + return high; + } + return val; +} +/** +* Returns the sign of a number +* @param x +* +* returns the sign +/-1 of x. special case at 0 it returns +1 +**/ +double sign(double x){ + if (x<0){ + return -1; + } + return 1; +} \ No newline at end of file diff --git a/src/utils/pure_pursuit.cpp b/src/utils/pure_pursuit.cpp index 11aaea9..4b28a3c 100644 --- a/src/utils/pure_pursuit.cpp +++ b/src/utils/pure_pursuit.cpp @@ -4,9 +4,9 @@ * Returns points of the intersections of a line segment and a circle. The line * segment is defined by two points, and the circle is defined by a center and radius. */ -std::vector PurePursuit::line_circle_intersections(Vector::point_t center, double r, Vector::point_t point1, Vector::point_t point2) +std::vector PurePursuit::line_circle_intersections(Vector2D::point_t center, double r, Vector2D::point_t point1, Vector2D::point_t point2) { - std::vector intersections = {}; + std::vector intersections = {}; //Do future calculations relative to the circle's center point1.y -= center.y; @@ -38,12 +38,12 @@ std::vector PurePursuit::line_circle_intersections(Vector::poin //The equations used define an infinitely long line, so we check if the detected intersection falls on the line segment. if(x1 >= fmin(point1.x, point2.x) && x1 <= fmax(point1.x, point2.x) && y1 >= fmin(point1.y, point2.y) && y1 <= fmax(point1.y, point2.y)) { - intersections.push_back(Vector::point_t{.x = x1 + center.x, .y = y1 + center.y}); + intersections.push_back(Vector2D::point_t{.x = x1 + center.x, .y = y1 + center.y}); } if(x2 >= fmin(point1.x, point2.x) && x2 <= fmax(point1.x, point2.x) && y2 >= fmin(point1.y, point2.y) && y2 <= fmax(point1.y, point2.y)) { - intersections.push_back(Vector::point_t{.x = x2 + center.x, .y = y2 + center.y}); + intersections.push_back(Vector2D::point_t{.x = x2 + center.x, .y = y2 + center.y}); } return intersections; @@ -52,10 +52,10 @@ std::vector PurePursuit::line_circle_intersections(Vector::poin /** * Selects a look ahead from all the intersections in the path. */ -Vector::point_t PurePursuit::get_lookahead(std::vector path, Vector::point_t robot_loc, double radius) +Vector2D::point_t PurePursuit::get_lookahead(std::vector path, Vector2D::point_t robot_loc, double radius) { //Default: the end of the path - Vector::point_t target = path.back(); + Vector2D::point_t target = path.back(); if(target.dist(robot_loc) <= radius) @@ -66,13 +66,13 @@ Vector::point_t PurePursuit::get_lookahead(std::vector path, Ve //Check each line segment of the path for potential targets for(int i = 0; i < path.size() - 1; i++) { - Vector::point_t start = path[i]; - Vector::point_t end = path[i+1]; + Vector2D::point_t start = path[i]; + Vector2D::point_t end = path[i+1]; - std::vector intersections = line_circle_intersections(robot_loc, radius, start, end); + std::vector intersections = line_circle_intersections(robot_loc, radius, start, end); //Choose the intersection that is closest to the end of the line segment //This prioritizes the closest intersection to the end of the path - for(Vector::point_t intersection: intersections) + for(Vector2D::point_t intersection: intersections) { if(intersection.dist(end) < target.dist(end)) target = intersection; @@ -85,18 +85,18 @@ Vector::point_t PurePursuit::get_lookahead(std::vector path, Ve /** Injects points in a path without changing the curvature with a certain spacing. */ -std::vector PurePursuit::inject_path(std::vector path, double spacing) +std::vector PurePursuit::inject_path(std::vector path, double spacing) { - std::vector new_path; + std::vector new_path; //Injecting points for each line segment for(int i = 0; i < path.size() - 1; i++) { - Vector::point_t start = path[i]; - Vector::point_t end = path[i+1]; + Vector2D::point_t start = path[i]; + Vector2D::point_t end = path[i+1]; - Vector::point_t diff = end - start; - Vector vector = Vector(diff); + Vector2D::point_t diff = end - start; + Vector2D vector = Vector2D(diff); int num_points = ceil(vector.get_mag() / spacing); @@ -106,7 +106,7 @@ std::vector PurePursuit::inject_path(std::vector PurePursuit::inject_path(std::vector PurePursuit::smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance) +std::vector PurePursuit::smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance) { - std::vector new_path = path; + std::vector new_path = path; double change = tolerance; while(change >= tolerance) { change = 0; for(int i = 1; i < path.size() - 1; i++) { - Vector::point_t x_i = path[i]; - Vector::point_t y_i = new_path[i]; - Vector::point_t y_prev = new_path[i-1]; - Vector::point_t y_next = new_path[i+1]; + Vector2D::point_t x_i = path[i]; + Vector2D::point_t y_i = new_path[i]; + Vector2D::point_t y_prev = new_path[i-1]; + Vector2D::point_t y_next = new_path[i+1]; - Vector::point_t y_i_saved = y_i; + Vector2D::point_t y_i_saved = y_i; y_i.x += weight_data * (x_i.x - y_i.x) + weight_smooth * (y_next.x + y_prev.x - (2 * y_i.x)); y_i.y += weight_data * (x_i.y - y_i.y) + weight_smooth * (y_next.y + y_prev.y - (2 * y_i.y)); @@ -159,17 +159,17 @@ std::vector PurePursuit::smooth_path(std::vector PurePursuit::smooth_path_hermite(std::vector path, double steps) { - std::vector new_path; +std::vector PurePursuit::smooth_path_hermite(std::vector path, double steps) { + std::vector new_path; for(int i = 0; i < path.size() - 1; i++) { for(int t = 0; t < steps; t++) { - // Storing the start and end points and slopes at those points as Vectors. - Vector::point_t tmp = path[i].getPoint(); - Vector p1 = Vector(tmp); + // Storing the start and end points and slopes at those points as Vector2Ds. + Vector2D::point_t tmp = path[i].getPoint(); + Vector2D p1 = Vector2D(tmp); tmp = path[i+1].getPoint(); - Vector p2 = Vector(tmp); - Vector t1 = path[i].getTangent(); - Vector t2 = path[i+1].getTangent(); + Vector2D p2 = Vector2D(tmp); + Vector2D t1 = path[i].getTangent(); + Vector2D t2 = path[i+1].getTangent(); // Scale s from 0.0 to 1.0 @@ -182,7 +182,7 @@ std::vector PurePursuit::smooth_path_hermite(std::vector PurePursuit::smooth_path_hermite(std::vector PurePursuit::smooth_path_cubic(std::vector path, double res) { - std::vector new_path; +std::vector PurePursuit::smooth_path_cubic(std::vector path, double res) { + std::vector new_path; std::vector splines; double delta_x[path.size() - 1]; diff --git a/src/utils/vector.cpp b/src/utils/vector2d.cpp similarity index 70% rename from src/utils/vector.cpp rename to src/utils/vector2d.cpp index b29cb14..8532847 100644 --- a/src/utils/vector.cpp +++ b/src/utils/vector2d.cpp @@ -1,125 +1,125 @@ -#include "../core/include/utils/vector.h" - -/** - * Construct a vector object. - * - * @param dir Direction, in radians. 'foward' is 0, clockwise positive when viewed from the top. - * @param mag Magnitude. - */ -Vector::Vector(double dir, double mag) -: dir(dir), mag(mag) -{ - -} - -/** - * Construct a vector object from a cartesian point. - * - * @param p point_t.x , point_t.y - */ -Vector::Vector(point_t &p) -{ - this->dir = atan2(p.y, p.x); - this->mag = sqrt( (p.x*p.x) + (p.y*p.y) ); -} - -/** - * Get the direction of the vector, in radians. - * '0' is forward, clockwise positive when viewed from the top. - * - * Use r2d() to convert. - */ -double Vector::get_dir() const { return dir;} - -/** - * Get the magnitude of the vector - */ -double Vector::get_mag() const { return mag; } - -/** - * Get the X component of the vector; positive to the right. - */ -double Vector::get_x() const -{ -return mag * cos(dir); -} - -/** - * Get the Y component of the vector, positive forward. - */ -double Vector::get_y() const -{ -return mag * sin(dir); -} - -/** - * Changes the magnetude of the vector to 1 -*/ -Vector Vector::normalize() -{ - return Vector(this->dir, 1); -} - -/** - * Returns a point from the vector -*/ -Vector::point_t Vector::point() -{ - point_t p = - { - .x = this->mag * cos(this->dir), - .y = this->mag * sin(this->dir) - }; - return p; -} - -/** - * Correctly add vectors together with the + operator - */ -Vector Vector::operator+(const Vector &other) -{ - point_t p = - { - .x = this->get_x() + other.get_x(), - .y = this->get_y() + other.get_y() - }; - - return Vector( p ); -} - -/** - * Correctly subtract vectors with the - operator - */ -Vector Vector::operator-(const Vector &other) -{ - point_t p = - { - .x = this->get_x() - other.get_x(), - .y = this->get_y() - other.get_y() - }; - return Vector( p ); -} - -/** - * Multiplies a vector by a double with the * operator -*/ -Vector Vector::operator*(const double &x) -{ - return Vector(this->dir, this->mag * x); -} - -/** - * General function for converting degrees to radians - */ -double deg2rad(double deg) -{ - return deg * (PI / 180.0); -} - -/** - * General function for converting radians to degrees - */ -double rad2deg(double rad) -{ - return rad * (180.0 / PI); -} +#include "../core/include/utils/vector2d.h" + +/** + * Construct a vector object. + * + * @param dir Direction, in radians. 'foward' is 0, clockwise positive when viewed from the top. + * @param mag Magnitude. + */ +Vector2D::Vector2D(double dir, double mag) +: dir(dir), mag(mag) +{ + +} + +/** + * Construct a vector object from a cartesian point. + * + * @param p point_t.x , point_t.y + */ +Vector2D::Vector2D(point_t &p) +{ + this->dir = atan2(p.y, p.x); + this->mag = sqrt( (p.x*p.x) + (p.y*p.y) ); +} + +/** + * Get the direction of the vector, in radians. + * '0' is forward, clockwise positive when viewed from the top. + * + * Use r2d() to convert. + */ +double Vector2D::get_dir() const { return dir;} + +/** + * Get the magnitude of the vector + */ +double Vector2D::get_mag() const { return mag; } + +/** + * Get the X component of the vector; positive to the right. + */ +double Vector2D::get_x() const +{ +return mag * cos(dir); +} + +/** + * Get the Y component of the vector, positive forward. + */ +double Vector2D::get_y() const +{ +return mag * sin(dir); +} + +/** + * Changes the magnetude of the vector to 1 +*/ +Vector2D Vector2D::normalize() +{ + return Vector2D(this->dir, 1); +} + +/** + * Returns a point from the vector +*/ +Vector2D::point_t Vector2D::point() +{ + point_t p = + { + .x = this->mag * cos(this->dir), + .y = this->mag * sin(this->dir) + }; + return p; +} + +/** + * Correctly add vectors together with the + operator + */ +Vector2D Vector2D::operator+(const Vector2D &other) +{ + point_t p = + { + .x = this->get_x() + other.get_x(), + .y = this->get_y() + other.get_y() + }; + + return Vector2D( p ); +} + +/** + * Correctly subtract vectors with the - operator + */ +Vector2D Vector2D::operator-(const Vector2D &other) +{ + point_t p = + { + .x = this->get_x() - other.get_x(), + .y = this->get_y() - other.get_y() + }; + return Vector2D( p ); +} + +/** + * Multiplies a vector by a double with the * operator +*/ +Vector2D Vector2D::operator*(const double &x) +{ + return Vector2D(this->dir, this->mag * x); +} + +/** + * General function for converting degrees to radians + */ +double deg2rad(double deg) +{ + return deg * (PI / 180.0); +} + +/** + * General function for converting radians to degrees + */ +double rad2deg(double rad) +{ + return rad * (180.0 / PI); +} From b2af760b3df6fb67935d3f67f93edf33ac8502a7 Mon Sep 17 00:00:00 2001 From: Christopher Nokes Date: Thu, 22 Sep 2022 20:11:38 -0400 Subject: [PATCH 083/243] Added documentation, fixed async stuff. --- include/subsystems/flywheel.h | 1 + src/subsystems/flywheel.cpp | 22 +++++++++++++++++----- 2 files changed, 18 insertions(+), 5 deletions(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index f7c9fe1..8610616 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -21,6 +21,7 @@ class Flywheel{ private: motor_group &motors; + bool taskRunning = false; PID pid; double RPM = -1.0; task rpmTask; diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 84c3a5a..d479160 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -9,6 +9,7 @@ ********************************************************** * 09/16/2022 Created file, added constructor, spins, RPM setting, stop. * 09/18/2022 Added async functionality. +* 09/22/2022 Documentation improvements, fixed error if RPM is set but motor is stopped. *********************************************************/ #include "../core/include/subsystems/flywheel.h" @@ -19,17 +20,23 @@ using namespace vex; /* * Create the Flywheel object. +* @param motors - pointer to the motors on the fly wheel +* @param pid - pointer to the PID */ Flywheel::Flywheel(motor_group &motors, PID &pid) :motors(motors), pid(pid){ } -// Spin motors using voltage; defaults forward at 12 volts -// Speed is between -1 and 1. +/* Spin motors using voltage; defaults forward at 12 volts +* @param speed - speed (between -1 and 1) to set the motor +* @param dir - direction that the motor moves in; defaults to forward +*/ void Flywheel::spin_raw(double speed, directionType dir){ motors.spin(dir, speed * 12, voltageUnits::volt); } -// spin this flywheel at a given RPM, async; runs until stop(), stopThread(), or a new spinRPM() is called. +/* spin this flywheel at a given RPM, async; runs until stop(), stopThread(), or a new spinRPM() is called. +* @param wheelPointer - points to the current wheel object +*/ int spinRPMThread(void* wheelPointer) { Flywheel* wheel = (Flywheel*) wheelPointer; wheel->getPID()->set_target((double) wheel->getRPM()); // get the pid from the wheel and set its target to the RPM stored in the wheel. @@ -41,12 +48,15 @@ int spinRPMThread(void* wheelPointer) { return 0; // only here to make the compiler SHUT UP } -// starts / restarts RPM thread at new value +/* starts / restarts RPM thread at new value +* @param inputRPM - set the current RPM +*/ void Flywheel::spinRPM(int inputRPM) { - if(inputRPM != RPM) { + if(inputRPM != RPM || !taskRunning) { RPM = inputRPM; rpmTask.stop(); rpmTask = task(spinRPMThread, this); + taskRunning = true; } } @@ -62,11 +72,13 @@ motor_group* Flywheel::getMotors() { return &motors; } // stop the RPM thread and the wheel void Flywheel::stop() { rpmTask.stop(); + taskRunning = false; motors.stop(); } // end the thread but keep spinning the wheel; not sure why anyone would use this but here it is anyway. void Flywheel::stopThread() { + taskRunning = false; rpmTask.stop(); } \ No newline at end of file From 92819ea3a073ed1b7ece84a17ada0dd363979081 Mon Sep 17 00:00:00 2001 From: Christopher Nokes Date: Thu, 22 Sep 2022 21:27:41 -0400 Subject: [PATCH 084/243] Added 'bang bang'. --- src/subsystems/flywheel.cpp | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index d479160..faa04f8 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -48,6 +48,22 @@ int spinRPMThread(void* wheelPointer) { return 0; // only here to make the compiler SHUT UP } +/* spin this flywheel at a given RPM, async; runs until stop(), stopThread(), or a new spinRPM() is called. +* Runs a BANG BANG variant. I have NO IDEA if it will work properly but I have NOTHING to test this on. +* @param wheelPointer - points to the current wheel object +*/ +int spinRPMThread_BangBang(void* wheelPointer) { + Flywheel* wheel = (Flywheel*) wheelPointer; + while(true) { + wheel->getPID()->update(wheel->getMotors()->velocity(velocityUnits::rpm)); // check the current velocity and update the PID with it. + // if it below the RPM, go, otherwise don't + if(wheel->getMotors()->velocity(velocityUnits::rpm) < wheel->getRPM()) { wheel->getMotors()->spin(fwd, 12, voltageUnits::volt); } + else { wheel->getMotors()->stop(); } + vexDelay(20); + } + return 0; // only here to make the compiler SHUT UP +} + /* starts / restarts RPM thread at new value * @param inputRPM - set the current RPM */ From 5ca4288acb54842fda47a73c13eb23335ac4a194 Mon Sep 17 00:00:00 2001 From: Christopher Nokes Date: Fri, 23 Sep 2022 18:45:07 -0400 Subject: [PATCH 085/243] Changed the Flywheel constructor to take a pid *config* pointer instead of a PID pointer. --- include/subsystems/flywheel.h | 2 +- src/subsystems/flywheel.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index 8610616..7f3f30d 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -7,7 +7,7 @@ using namespace vex; class Flywheel{ public: - Flywheel(motor_group &motors, PID &pid); + Flywheel(motor_group &motors, PID::pid_config_t &pid_config); void spin_raw(double speed, directionType dir=fwd); void spinRPM(int rpm); diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index faa04f8..3ef4c72 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -23,8 +23,8 @@ using namespace vex; * @param motors - pointer to the motors on the fly wheel * @param pid - pointer to the PID */ -Flywheel::Flywheel(motor_group &motors, PID &pid) - :motors(motors), pid(pid){ } +Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config) + :motors(motors), pid(pid_config) { } /* Spin motors using voltage; defaults forward at 12 volts * @param speed - speed (between -1 and 1) to set the motor From 9975cf8977572733993851c2507e3b3288b49a05 Mon Sep 17 00:00:00 2001 From: Christopher Nokes Date: Fri, 23 Sep 2022 19:43:17 -0400 Subject: [PATCH 086/243] Documentation and organization improvements, added stubs for RPM control test functions. --- include/subsystems/flywheel.h | 46 +++++++++----- src/subsystems/flywheel.cpp | 111 ++++++++++++++++++++++++---------- 2 files changed, 111 insertions(+), 46 deletions(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index 7f3f30d..5436f60 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -1,3 +1,15 @@ +/********************************************************* +* +* File: Flywheel.h +* Purpose: Generalized flywheel class for Core. +* Author: Chris Nokes +* +********************************************************** +* EDIT HISTORY +********************************************************** +* 09/23/2022 Reorganized, added documentation. +*********************************************************/ + #include "vex.h" #include "../core/include/robot_specs.h" #include "../core/include/utils/pid.h" @@ -7,22 +19,28 @@ using namespace vex; class Flywheel{ public: - Flywheel(motor_group &motors, PID::pid_config_t &pid_config); - - void spin_raw(double speed, directionType dir=fwd); - void spinRPM(int rpm); - void stop(); - void stopThread(); + // CONSTRUCTORS, GETTERS, AND SETTERS + Flywheel(motor_group &motors, PID::pid_config_t &pid_config); // constructor + double getRPM(); // returns the desired RPM + motor_group* getMotors(); // returns a pointer to the motors + double getVelocity_RPM(); // get the current velocity of the motors in RPM + PID* getPID(); // returns a pointer to the PID + double getPIDValue(); // get the current OUT value of the PID + void setPIDTarget(double value); // set the PID target + void updatePID(double value); // update the PID with the current value it's tracking - double getRPM(); - PID* getPID(); - motor_group* getMotors(); + // SPINNERS AND STOPPERS + void spin_raw(double speed, directionType dir=fwd); // Spins at a given speed between -1 and 1 + void spinRPM(int rpm); // spins the turret at a target RPM + void stop(); // stops the motors and the thread + void stopMotors(); // stops ONLY the motors + void stopThread(); // stops ONLY the thread private: - motor_group &motors; - bool taskRunning = false; - PID pid; - double RPM = -1.0; - task rpmTask; + motor_group &motors; // motors that make up the flywheel + bool taskRunning = false; // is the task (thread but not) currently running? + PID pid; // PID on the flywheel + double RPM = -1.0; // Desired RPM of the flywheel. + task rpmTask; // task (thread but not) that handles spinning the wheel at a given RPM }; \ No newline at end of file diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 3ef4c72..cc5e650 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -10,6 +10,7 @@ * 09/16/2022 Created file, added constructor, spins, RPM setting, stop. * 09/18/2022 Added async functionality. * 09/22/2022 Documentation improvements, fixed error if RPM is set but motor is stopped. +* 09/23/2022 Neatened up program, added getters and setters, fixed documentation and bang bang. *********************************************************/ #include "../core/include/subsystems/flywheel.h" @@ -18,6 +19,10 @@ using namespace vex; +/********************************************************* +* CONSTRUCTOR, GETTERS, SETTERS +*********************************************************/ + /* * Create the Flywheel object. * @param motors - pointer to the motors on the fly wheel @@ -26,65 +31,104 @@ using namespace vex; Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config) :motors(motors), pid(pid_config) { } -/* Spin motors using voltage; defaults forward at 12 volts -* @param speed - speed (between -1 and 1) to set the motor -* @param dir - direction that the motor moves in; defaults to forward +// return the current value that the RPM should be set to; +double Flywheel::getRPM() { return RPM; } + +// Returns a POINTER TO the motors; not currently used. +motor_group* Flywheel::getMotors() { return &motors; } // TODO -- Remove? + +// return the current velocity of the flywheel motors, in RPM +double Flywheel::getVelocity_RPM() { return motors.velocity(velocityUnits::rpm); } + +// Returns a POINTER TO the PID; not currently used. +PID* Flywheel::getPID() { return &pid; } // TODO -- Remove? + +// returns the current OUT value of the PID +double Flywheel::getPIDValue() { return pid.get(); } + +/* +* Sets the value of the PID target +* @param value - desired value of the PID */ -void Flywheel::spin_raw(double speed, directionType dir){ - motors.spin(dir, speed * 12, voltageUnits::volt); -} +void Flywheel::setPIDTarget(double value) { pid.set_target(value); } -/* spin this flywheel at a given RPM, async; runs until stop(), stopThread(), or a new spinRPM() is called. -* @param wheelPointer - points to the current wheel object +/* +* updates the value of the PID +* @param value - value to update the PID with */ -int spinRPMThread(void* wheelPointer) { +void Flywheel::updatePID(double value) { pid.update(value); } + +/********************************************************* +* RPM SETTING THREADS +* ALL OF THE FOLLOWING PROGRAMS HAVE THE SAME PARAMETERS AND RESULTS: +* spin this flywheel at a given RPM, async; runs until stop(), stopThread(), or a new spinRPM() is called. +* @param wheelPointer - points to the current wheel object +*********************************************************/ + +// Runs a PID loop to get to the set RPM. +int spinRPMTask_PID(void* wheelPointer) { Flywheel* wheel = (Flywheel*) wheelPointer; - wheel->getPID()->set_target((double) wheel->getRPM()); // get the pid from the wheel and set its target to the RPM stored in the wheel. + wheel->setPIDTarget(wheel->getRPM()); // get the pid from the wheel and set its target to the RPM stored in the wheel. while(true) { - wheel->getPID()->update(wheel->getMotors()->velocity(velocityUnits::rpm)); // check the current velocity and update the PID with it. - wheel->getMotors()->spin(fwd, wheel->getPID()->get() * 12, voltageUnits::volt); // set the motors to whatever PID tells them to do + wheel->updatePID(wheel->getVelocity_RPM()); // check the current velocity and update the PID with it. + wheel->spin_raw(wheel->getPIDValue(), fwd); // set the motors to whatever PID tells them to do vexDelay(20); } return 0; // only here to make the compiler SHUT UP } -/* spin this flywheel at a given RPM, async; runs until stop(), stopThread(), or a new spinRPM() is called. -* Runs a BANG BANG variant. I have NO IDEA if it will work properly but I have NOTHING to test this on. -* @param wheelPointer - points to the current wheel object -*/ -int spinRPMThread_BangBang(void* wheelPointer) { +// Runs a BANG BANG variant. I have NO IDEA if it will work properly but I have NOTHING to test this on. +int spinRPMTask_BangBang(void* wheelPointer) { Flywheel* wheel = (Flywheel*) wheelPointer; while(true) { - wheel->getPID()->update(wheel->getMotors()->velocity(velocityUnits::rpm)); // check the current velocity and update the PID with it. // if it below the RPM, go, otherwise don't - if(wheel->getMotors()->velocity(velocityUnits::rpm) < wheel->getRPM()) { wheel->getMotors()->spin(fwd, 12, voltageUnits::volt); } - else { wheel->getMotors()->stop(); } + if(wheel->getVelocity_RPM() < wheel->getRPM()) { + wheel->spin_raw(1, fwd); + } + else { wheel->stopMotors(); } vexDelay(20); } return 0; // only here to make the compiler SHUT UP } +// Runs a Feedforward variant; FUNCTION STUB +int spinRPMTask_Feedforward(void* wheelPointer) { return 0; } + +// Runs a PID + Feedforward variant; FUNCTION STUB +int spinRPMTask_PID_Feedforward(void* wheelPointer) { return 0; } + +// Runs a Take Back Half variant; FUNCTION STUB +int spinRPMTask_TBH(void* wheelPointer) { return 0; } + +// Runs a 'Moving average filter with above closed loop systems' variant, whatever that means; FUNCTION STUB +int spinRPMTask_ClosedLoop(void* wheelPointer) { return 0; } + + +/********************************************************* +* SPINNERS AND STOPPERS +*********************************************************/ + +/* Spin motors using voltage; defaults forward at 12 volts +* @param speed - speed (between -1 and 1) to set the motor +* @param dir - direction that the motor moves in; defaults to forward +*/ +void Flywheel::spin_raw(double speed, directionType dir){ + motors.spin(dir, speed * 12, voltageUnits::volt); +} + /* starts / restarts RPM thread at new value * @param inputRPM - set the current RPM */ void Flywheel::spinRPM(int inputRPM) { + // only run if the RPM is different or it isn't already running if(inputRPM != RPM || !taskRunning) { RPM = inputRPM; rpmTask.stop(); - rpmTask = task(spinRPMThread, this); + rpmTask = task(spinRPMTask_PID, this); taskRunning = true; } } -// return the current value that the RPM should be set to; -double Flywheel::getRPM() { return RPM; } - -// Returns a POINTER TO the PID; only for use in the spinRPMThread function. -PID* Flywheel::getPID() { return &pid; } - -// Returns a POINTER TO the motors; only for use in the spinRPMThread function. -motor_group* Flywheel::getMotors() { return &motors; } - // stop the RPM thread and the wheel void Flywheel::stop() { rpmTask.stop(); @@ -92,9 +136,12 @@ void Flywheel::stop() { motors.stop(); } +// stop only the motors; exclusively for BANG BANG use +void Flywheel::stopMotors() { motors.stop(); } + -// end the thread but keep spinning the wheel; not sure why anyone would use this but here it is anyway. -void Flywheel::stopThread() { +// stop only the thread; not currently used but might come in handy \__('-')__/ +void Flywheel::stopThread() { // TODO -- Remove? taskRunning = false; rpmTask.stop(); } \ No newline at end of file From f4d060e85afc047f4213cbab24b724de48c3a054 Mon Sep 17 00:00:00 2001 From: Christopher Nokes Date: Fri, 23 Sep 2022 20:48:14 -0400 Subject: [PATCH 087/243] Updated async to not 'have a stroke'. --- include/subsystems/flywheel.h | 1 - src/subsystems/flywheel.cpp | 20 ++++++-------------- 2 files changed, 6 insertions(+), 15 deletions(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index 5436f60..41d7b57 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -34,7 +34,6 @@ class Flywheel{ void spinRPM(int rpm); // spins the turret at a target RPM void stop(); // stops the motors and the thread void stopMotors(); // stops ONLY the motors - void stopThread(); // stops ONLY the thread private: diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index cc5e650..9a9afb6 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -68,9 +68,9 @@ void Flywheel::updatePID(double value) { pid.update(value); } // Runs a PID loop to get to the set RPM. int spinRPMTask_PID(void* wheelPointer) { Flywheel* wheel = (Flywheel*) wheelPointer; - wheel->setPIDTarget(wheel->getRPM()); // get the pid from the wheel and set its target to the RPM stored in the wheel. + // get the pid from the wheel and set its target to the RPM stored in the wheel. while(true) { - wheel->updatePID(wheel->getVelocity_RPM()); // check the current velocity and update the PID with it. + wheel->updatePID(wheel->getVelocity_RPM()); // check the current velocity and update the PID with it. wheel->spin_raw(wheel->getPIDValue(), fwd); // set the motors to whatever PID tells them to do vexDelay(20); } @@ -103,7 +103,6 @@ int spinRPMTask_TBH(void* wheelPointer) { return 0; } // Runs a 'Moving average filter with above closed loop systems' variant, whatever that means; FUNCTION STUB int spinRPMTask_ClosedLoop(void* wheelPointer) { return 0; } - /********************************************************* * SPINNERS AND STOPPERS *********************************************************/ @@ -121,12 +120,12 @@ void Flywheel::spin_raw(double speed, directionType dir){ */ void Flywheel::spinRPM(int inputRPM) { // only run if the RPM is different or it isn't already running - if(inputRPM != RPM || !taskRunning) { - RPM = inputRPM; - rpmTask.stop(); + if(!taskRunning) { rpmTask = task(spinRPMTask_PID, this); taskRunning = true; } + RPM = inputRPM; + setPIDTarget(RPM); } // stop the RPM thread and the wheel @@ -137,11 +136,4 @@ void Flywheel::stop() { } // stop only the motors; exclusively for BANG BANG use -void Flywheel::stopMotors() { motors.stop(); } - - -// stop only the thread; not currently used but might come in handy \__('-')__/ -void Flywheel::stopThread() { // TODO -- Remove? - taskRunning = false; - rpmTask.stop(); -} \ No newline at end of file +void Flywheel::stopMotors() { motors.stop(); } \ No newline at end of file From 67e227ad14bb1d8bb5df794e53c66c447f34fa18 Mon Sep 17 00:00:00 2001 From: Christopher Nokes Date: Sun, 2 Oct 2022 12:05:43 -0400 Subject: [PATCH 088/243] Changes made during testing, futile attempts at debugging. --- include/subsystems/flywheel.h | 7 +++++- src/subsystems/flywheel.cpp | 27 ++++++++++++++++++----- src/subsystems/odometry/odometry_tank.cpp | 2 +- 3 files changed, 28 insertions(+), 8 deletions(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index 41d7b57..07c3f6e 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -8,6 +8,7 @@ * EDIT HISTORY ********************************************************** * 09/23/2022 Reorganized, added documentation. +* 09/23/2022 Added functions elaborated on in .cpp. *********************************************************/ #include "vex.h" @@ -20,8 +21,9 @@ class Flywheel{ public: // CONSTRUCTORS, GETTERS, AND SETTERS - Flywheel(motor_group &motors, PID::pid_config_t &pid_config); // constructor + Flywheel(motor_group &motors, PID::pid_config_t &pid_config, const double ratio); // constructor double getRPM(); // returns the desired RPM + bool isTaskRunning(); // returns if a task is running motor_group* getMotors(); // returns a pointer to the motors double getVelocity_RPM(); // get the current velocity of the motors in RPM PID* getPID(); // returns a pointer to the PID @@ -31,15 +33,18 @@ class Flywheel{ // SPINNERS AND STOPPERS void spin_raw(double speed, directionType dir=fwd); // Spins at a given speed between -1 and 1 + void spin_manual(double speed, directionType dir=fwd); // Same as spin_raw, but check to make sure a task isn't running before doing it. void spinRPM(int rpm); // spins the turret at a target RPM void stop(); // stops the motors and the thread void stopMotors(); // stops ONLY the motors + void stopNonTasks(); // stops motors IFF a task isn't running and a manual setter isn't being pressed private: motor_group &motors; // motors that make up the flywheel bool taskRunning = false; // is the task (thread but not) currently running? PID pid; // PID on the flywheel + double ratio; // multiplies the velocity by this value double RPM = -1.0; // Desired RPM of the flywheel. task rpmTask; // task (thread but not) that handles spinning the wheel at a given RPM }; \ No newline at end of file diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 9a9afb6..7718670 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -11,6 +11,7 @@ * 09/18/2022 Added async functionality. * 09/22/2022 Documentation improvements, fixed error if RPM is set but motor is stopped. * 09/23/2022 Neatened up program, added getters and setters, fixed documentation and bang bang. +* 09/29/2022 Bug fixes, RPM handling. Multiplied the motor by 18. *********************************************************/ #include "../core/include/subsystems/flywheel.h" @@ -27,18 +28,22 @@ using namespace vex; * Create the Flywheel object. * @param motors - pointer to the motors on the fly wheel * @param pid - pointer to the PID +* @param ratio - ratio of the whatever just multiplies the velocity */ -Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config) - :motors(motors), pid(pid_config) { } +Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, const double ratio) + :motors(motors), pid(pid_config), ratio(ratio) { } // return the current value that the RPM should be set to; double Flywheel::getRPM() { return RPM; } + +// returns whether or not the wheel is running a task currently +bool Flywheel::isTaskRunning() { return taskRunning; } // Returns a POINTER TO the motors; not currently used. motor_group* Flywheel::getMotors() { return &motors; } // TODO -- Remove? // return the current velocity of the flywheel motors, in RPM -double Flywheel::getVelocity_RPM() { return motors.velocity(velocityUnits::rpm); } +double Flywheel::getVelocity_RPM() { return ratio * motors.velocity(velocityUnits::rpm); } // Returns a POINTER TO the PID; not currently used. PID* Flywheel::getPID() { return &pid; } // TODO -- Remove? @@ -72,7 +77,7 @@ int spinRPMTask_PID(void* wheelPointer) { while(true) { wheel->updatePID(wheel->getVelocity_RPM()); // check the current velocity and update the PID with it. wheel->spin_raw(wheel->getPIDValue(), fwd); // set the motors to whatever PID tells them to do - vexDelay(20); + vexDelay(1); } return 0; // only here to make the compiler SHUT UP } @@ -86,7 +91,7 @@ int spinRPMTask_BangBang(void* wheelPointer) { wheel->spin_raw(1, fwd); } else { wheel->stopMotors(); } - vexDelay(20); + vexDelay(1); } return 0; // only here to make the compiler SHUT UP } @@ -108,6 +113,7 @@ int spinRPMTask_ClosedLoop(void* wheelPointer) { return 0; } *********************************************************/ /* Spin motors using voltage; defaults forward at 12 volts +* FOR USE BY TASKS ONLY * @param speed - speed (between -1 and 1) to set the motor * @param dir - direction that the motor moves in; defaults to forward */ @@ -115,6 +121,12 @@ void Flywheel::spin_raw(double speed, directionType dir){ motors.spin(dir, speed * 12, voltageUnits::volt); } +// Spin motors using voltage; defaults forward at 12 volts +// FOR USE BY OPCONTROL AND AUTONOMOUS, same as spin_raw otherwise +void Flywheel::spin_manual(double speed, directionType dir){ + if(!taskRunning) motors.spin(dir, speed * 12, voltageUnits::volt); +} + /* starts / restarts RPM thread at new value * @param inputRPM - set the current RPM */ @@ -136,4 +148,7 @@ void Flywheel::stop() { } // stop only the motors; exclusively for BANG BANG use -void Flywheel::stopMotors() { motors.stop(); } \ No newline at end of file +void Flywheel::stopMotors() { motors.stop(); } + +// stop the motors iff the task isn't running +void Flywheel::stopNonTasks() { if(!taskRunning) { motors.stop(); }} \ No newline at end of file diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index c801c2f..b1a87e1 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -97,7 +97,7 @@ position_t OdometryTank::update() //Use the arclength formula to calculate the angle. Add 90 to make "0 degrees" to starboard angle = ((180.0 / PI) * (distance_diff / config.dist_between_wheels)) + 90; - printf("angle: %f, ", (180.0 / PI) * (distance_diff / config.dist_between_wheels)); + // printf("angle: %f, ", (180.0 / PI) * (distance_diff / config.dist_between_wheels)); } else { From e242000c4cd98c970431e855b96ead774601a5a7 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 2 Oct 2022 13:07:53 -0400 Subject: [PATCH 089/243] Commented out old printf s Terminal is cleaner now --- src/subsystems/odometry/odometry_tank.cpp | 3 +-- src/subsystems/tank_drive.cpp | 4 ++-- src/utils/pure_pursuit.cpp | 2 +- 3 files changed, 4 insertions(+), 5 deletions(-) diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index b1a87e1..7ca1047 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -92,8 +92,7 @@ position_t OdometryTank::update() // Get the arclength of the turning circle of the robot double distance_diff = (rside_revs - lside_revs) * PI * config.odom_wheel_diam; - printf("dist_diff: %f, ", distance_diff); - + //Use the arclength formula to calculate the angle. Add 90 to make "0 degrees" to starboard angle = ((180.0 / PI) * (distance_diff / config.dist_between_wheels)) + 90; diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index bd99b81..f72c0ee 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -263,7 +263,7 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti drive_tank(lside, rside); - printf("dist: %f\n", sign * -1 * dist_left); + //printf("dist: %f\n", sign * -1 * dist_left); fflush(stdout); // Check if the robot has reached it's destination @@ -306,7 +306,7 @@ bool TankDrive::turn_to_heading(double heading_deg, double speed) double delta_heading = OdometryBase::smallest_angle(odometry->get_position().rot, heading_deg); turn_pid.update(delta_heading); - printf("~TURN~ delta: %f\n", delta_heading); + //printf("~TURN~ delta: %f\n", delta_heading); // printf("delta heading: %f, pid: %f\n", delta_heading, turn_pid.get()); fflush(stdout); diff --git a/src/utils/pure_pursuit.cpp b/src/utils/pure_pursuit.cpp index 4b28a3c..b5e09b3 100644 --- a/src/utils/pure_pursuit.cpp +++ b/src/utils/pure_pursuit.cpp @@ -223,7 +223,7 @@ std::vector PurePursuit::smooth_path_cubic(std::vector= fmin(spline.x_start, spline.x_end) && x <= fmax(spline.x_start, spline.x_end)) { new_path.push_back({x, spline.getY(x)}); From c2c1989daecf92e1366c9c6385a942bb28a071f5 Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 7 Oct 2022 21:06:50 -0400 Subject: [PATCH 090/243] Flywheel PID + Feedforward, Feedforward. Functions and configs --- include/subsystems/flywheel.h | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index 07c3f6e..825084c 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -11,6 +11,7 @@ * 09/23/2022 Added functions elaborated on in .cpp. *********************************************************/ +#include "../core/include/utils/feedforward.h" #include "vex.h" #include "../core/include/robot_specs.h" #include "../core/include/utils/pid.h" @@ -21,13 +22,15 @@ class Flywheel{ public: // CONSTRUCTORS, GETTERS, AND SETTERS - Flywheel(motor_group &motors, PID::pid_config_t &pid_config, const double ratio); // constructor + Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio); // constructor double getRPM(); // returns the desired RPM bool isTaskRunning(); // returns if a task is running motor_group* getMotors(); // returns a pointer to the motors double getVelocity_RPM(); // get the current velocity of the motors in RPM PID* getPID(); // returns a pointer to the PID double getPIDValue(); // get the current OUT value of the PID + double getFeedforwardValue(); // get the current OUT value of the feedforward + void setPIDTarget(double value); // set the PID target void updatePID(double value); // update the PID with the current value it's tracking @@ -44,6 +47,7 @@ class Flywheel{ motor_group &motors; // motors that make up the flywheel bool taskRunning = false; // is the task (thread but not) currently running? PID pid; // PID on the flywheel + FeedForward ff; double ratio; // multiplies the velocity by this value double RPM = -1.0; // Desired RPM of the flywheel. task rpmTask; // task (thread but not) that handles spinning the wheel at a given RPM From 42252ce3eba720017a71e26e4ddd28f724a9d2ad Mon Sep 17 00:00:00 2001 From: cowsed Date: Thu, 13 Oct 2022 21:31:48 -0400 Subject: [PATCH 091/243] Take Back Half control and tuning. Right now, the tbh gain parameter is hardcoded into the flywheel definition, this should be extracted so we can use the same code with different configs for different flywheels. --- include/subsystems/flywheel.h | 4 +- src/subsystems/flywheel.cpp | 97 ++++++++++++++++++++++++++--------- 2 files changed, 74 insertions(+), 27 deletions(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index 825084c..4c4ac54 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -23,10 +23,10 @@ class Flywheel{ // CONSTRUCTORS, GETTERS, AND SETTERS Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio); // constructor - double getRPM(); // returns the desired RPM + double getDesiredRPM(); // returns the desired RPM bool isTaskRunning(); // returns if a task is running motor_group* getMotors(); // returns a pointer to the motors - double getVelocity_RPM(); // get the current velocity of the motors in RPM + double getRPM(); // get the current velocity of the motors in RPM PID* getPID(); // returns a pointer to the PID double getPIDValue(); // get the current OUT value of the PID double getFeedforwardValue(); // get the current OUT value of the feedforward diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 7718670..4011013 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -16,6 +16,7 @@ #include "../core/include/subsystems/flywheel.h" #include "../core/include/utils/pid.h" +#include "../core/include/utils/math_util.h" #include "vex.h" using namespace vex; @@ -27,14 +28,15 @@ using namespace vex; /* * Create the Flywheel object. * @param motors - pointer to the motors on the fly wheel -* @param pid - pointer to the PID +* @param pid - pointer to the PID config +* @param ff - pointer to the feedforward config * @param ratio - ratio of the whatever just multiplies the velocity */ -Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, const double ratio) - :motors(motors), pid(pid_config), ratio(ratio) { } +Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio) + :motors(motors), pid(pid_config), ff(ff_config), ratio(ratio) { } // return the current value that the RPM should be set to; -double Flywheel::getRPM() { return RPM; } +double Flywheel::getDesiredRPM() { return RPM; } // returns whether or not the wheel is running a task currently bool Flywheel::isTaskRunning() { return taskRunning; } @@ -43,13 +45,20 @@ bool Flywheel::isTaskRunning() { return taskRunning; } motor_group* Flywheel::getMotors() { return &motors; } // TODO -- Remove? // return the current velocity of the flywheel motors, in RPM -double Flywheel::getVelocity_RPM() { return ratio * motors.velocity(velocityUnits::rpm); } +double Flywheel::getRPM() { return ratio * motors.velocity(velocityUnits::rpm); } // Returns a POINTER TO the PID; not currently used. PID* Flywheel::getPID() { return &pid; } // TODO -- Remove? // returns the current OUT value of the PID double Flywheel::getPIDValue() { return pid.get(); } +// returns the current OUT value of the Feedforward +// uses the current set rpm and the acceleration by ????????? +double Flywheel::getFeedforwardValue() { + double v = getDesiredRPM(); + + return ff.calculate(v, 0); +} /* * Sets the value of the PID target @@ -70,24 +79,12 @@ void Flywheel::updatePID(double value) { pid.update(value); } * @param wheelPointer - points to the current wheel object *********************************************************/ -// Runs a PID loop to get to the set RPM. -int spinRPMTask_PID(void* wheelPointer) { - Flywheel* wheel = (Flywheel*) wheelPointer; - // get the pid from the wheel and set its target to the RPM stored in the wheel. - while(true) { - wheel->updatePID(wheel->getVelocity_RPM()); // check the current velocity and update the PID with it. - wheel->spin_raw(wheel->getPIDValue(), fwd); // set the motors to whatever PID tells them to do - vexDelay(1); - } - return 0; // only here to make the compiler SHUT UP -} - // Runs a BANG BANG variant. I have NO IDEA if it will work properly but I have NOTHING to test this on. int spinRPMTask_BangBang(void* wheelPointer) { Flywheel* wheel = (Flywheel*) wheelPointer; while(true) { // if it below the RPM, go, otherwise don't - if(wheel->getVelocity_RPM() < wheel->getRPM()) { + if(wheel->getRPM() < wheel->getDesiredRPM()) { wheel->spin_raw(1, fwd); } else { wheel->stopMotors(); } @@ -96,14 +93,64 @@ int spinRPMTask_BangBang(void* wheelPointer) { return 0; // only here to make the compiler SHUT UP } -// Runs a Feedforward variant; FUNCTION STUB -int spinRPMTask_Feedforward(void* wheelPointer) { return 0; } +// Runs a Feedforward variant; +int spinRPMTask_Feedforward(void* wheelPointer) { + Flywheel* wheel = (Flywheel*) wheelPointer; + // get the pid from the wheel and set its target to the RPM stored in the wheel. + while(true) { + wheel->updatePID(wheel->getRPM()); // check the current velocity and update the PID with it. + double output = wheel->getFeedforwardValue(); + wheel->spin_raw(output, fwd); // set the motors to whatever feedforward tells them to do + vexDelay(1); + } + return 0; +} + +// Runs a PID + Feedforward variant; +int spinRPMTask_PID_Feedforward(void* wheelPointer) { + Flywheel* wheel = (Flywheel*) wheelPointer; + // get the pid from the wheel and set its target to the RPM stored in the wheel. + while(true) { + wheel->updatePID(wheel->getRPM()); // check the current velocity and update the PID with it. + double output = wheel->getPIDValue() + wheel->getFeedforwardValue(); + wheel->spin_raw(output, fwd); // set the motors to whatever PID tells them to do + vexDelay(1); + } + return 0; +} -// Runs a PID + Feedforward variant; FUNCTION STUB -int spinRPMTask_PID_Feedforward(void* wheelPointer) { return 0; } +// Runs a Take Back Half variant; +//https://www.vexwiki.org/programming/controls_algorithms/tbh +int spinRPMTask_TBH(void* wheelPointer) { + Flywheel* wheel = (Flywheel*) wheelPointer; + double gain = .00001; + + double tbh = 0.0; + double output = 0.0; + double previous_error = 0.0; + + while (true){ + //reset if set to 0, this keeps the tbh val from screwing us up when we start up again + if (wheel->getDesiredRPM()==0){ + output = 0; + tbh = 0; + } + + double error = wheel->getDesiredRPM() - wheel->getRPM(); + output += gain * error; + wheel->spin_raw(clamp(output, 0, 1), fwd); + + if (sign(error)!=sign(previous_error)){ + output = .5 * (output + tbh); + tbh = output; + previous_error = error; + } -// Runs a Take Back Half variant; FUNCTION STUB -int spinRPMTask_TBH(void* wheelPointer) { return 0; } + vexDelay(1); + } + + return 0; +} // Runs a 'Moving average filter with above closed loop systems' variant, whatever that means; FUNCTION STUB int spinRPMTask_ClosedLoop(void* wheelPointer) { return 0; } @@ -133,7 +180,7 @@ void Flywheel::spin_manual(double speed, directionType dir){ void Flywheel::spinRPM(int inputRPM) { // only run if the RPM is different or it isn't already running if(!taskRunning) { - rpmTask = task(spinRPMTask_PID, this); + rpmTask = task(spinRPMTask_TBH, this); taskRunning = true; } RPM = inputRPM; From d4ec1009d77299299ff11788c5c5e6ba3c098cb0 Mon Sep 17 00:00:00 2001 From: cowsed Date: Thu, 13 Oct 2022 23:14:06 -0400 Subject: [PATCH 092/243] Created multiple ways to construct a Flywheel each corresponding to a different control method Flywheel now chooses which spinRPMtask to use based on this --- include/subsystems/flywheel.h | 33 ++++++++++++----- src/subsystems/flywheel.cpp | 70 +++++++++++++++++++++++++++++++---- 2 files changed, 86 insertions(+), 17 deletions(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index 4c4ac54..7f644a9 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -19,10 +19,21 @@ using namespace vex; class Flywheel{ + enum FlywheelControlStyle{ + PID_Feedforward, + Feedforward, + Take_Back_Half, + Bang_Bang, + }; public: // CONSTRUCTORS, GETTERS, AND SETTERS - Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio); // constructor + Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio); // constructor for feedforward + pid + Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio); // constructor for only feed forward + Flywheel(motor_group &motors, double tbh_gain, const double ratio); // constructor for take back half + Flywheel(motor_group &motors, const double ratio); // constructor for bang-bang control + + double getDesiredRPM(); // returns the desired RPM bool isTaskRunning(); // returns if a task is running motor_group* getMotors(); // returns a pointer to the motors @@ -30,7 +41,8 @@ class Flywheel{ PID* getPID(); // returns a pointer to the PID double getPIDValue(); // get the current OUT value of the PID double getFeedforwardValue(); // get the current OUT value of the feedforward - + double getTBHGain(); // get the gain used for TBH control + void setPIDTarget(double value); // set the PID target void updatePID(double value); // update the PID with the current value it's tracking @@ -44,11 +56,14 @@ class Flywheel{ private: - motor_group &motors; // motors that make up the flywheel - bool taskRunning = false; // is the task (thread but not) currently running? - PID pid; // PID on the flywheel - FeedForward ff; - double ratio; // multiplies the velocity by this value - double RPM = -1.0; // Desired RPM of the flywheel. - task rpmTask; // task (thread but not) that handles spinning the wheel at a given RPM + motor_group &motors; // motors that make up the flywheel + bool taskRunning = false; // is the task (thread but not) currently running? + PID pid; // PID on the flywheel + FeedForward ff; // FF constants for the flywheel + double TBH_gain; // TBH gain parameter for the flywheel + double ratio; // multiplies the velocity by this value + double RPM = -1.0; // Desired RPM of the flywheel. + task rpmTask; // task (thread but not) that handles spinning the wheel at a given RPM + FlywheelControlStyle control_style; // how the flywheel should be controlled + }; \ No newline at end of file diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 4011013..1827cd6 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -15,8 +15,10 @@ *********************************************************/ #include "../core/include/subsystems/flywheel.h" +#include "../core/include/utils/feedforward.h" #include "../core/include/utils/pid.h" #include "../core/include/utils/math_util.h" +#include "C:/Users/richi/VEX/2022-2023-Flynn/include/robot-config.h" #include "vex.h" using namespace vex; @@ -24,16 +26,46 @@ using namespace vex; /********************************************************* * CONSTRUCTOR, GETTERS, SETTERS *********************************************************/ +//used when using bang bang or TBH control +PID::pid_config_t empty_pid = PID::pid_config_t{}; +FeedForward::ff_config_t empty_ff = FeedForward::ff_config_t{}; /* -* Create the Flywheel object. +* Create the Flywheel object using PID + feedforward for control. * @param motors - pointer to the motors on the fly wheel -* @param pid - pointer to the PID config * @param ff - pointer to the feedforward config * @param ratio - ratio of the whatever just multiplies the velocity */ Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio) - :motors(motors), pid(pid_config), ff(ff_config), ratio(ratio) { } + :motors(motors), pid(pid_config), ff(ff_config), ratio(ratio), control_style(PID_Feedforward) { } + +/* +* Create the Flywheel object using only feedforward for control +* @param motors - pointer to the motors on the fly wheel +* @param ff - pointer to the feedforward config +* @param ratio - ratio of the whatever just multiplies the velocity +*/ +Flywheel::Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio) + :motors(motors), pid(empty_pid), ff(ff_config), ratio(ratio), control_style(Feedforward) {} + +/* +* Create the Flywheel object using Take Back Half for control +* @param motors - pointer to the motors on the fly wheel +* @param TBH_gain - the TBH control paramater +* @param ratio - ratio of the whatever just multiplies the velocity +*/ +Flywheel::Flywheel(motor_group &motors, const double TBH_gain, const double ratio) + :motors(motors), pid(empty_pid), ff(empty_ff), TBH_gain(TBH_gain), ratio(ratio), control_style(Take_Back_Half) {} + +/* +* Create the Flywheel object using Bang Bang for control +* @param motors - pointer to the motors on the fly wheel +* @param ratio - ratio of the whatever just multiplies the velocity +*/ +Flywheel::Flywheel(motor_group &motors, const double ratio) + :motors(motors), pid(empty_pid), ff(empty_ff), ratio(ratio), control_style(Bang_Bang) {} + + // return the current value that the RPM should be set to; double Flywheel::getDesiredRPM() { return RPM; } @@ -52,14 +84,18 @@ PID* Flywheel::getPID() { return &pid; } // TODO -- Remove? // returns the current OUT value of the PID double Flywheel::getPIDValue() { return pid.get(); } + // returns the current OUT value of the Feedforward -// uses the current set rpm and the acceleration by ????????? double Flywheel::getFeedforwardValue() { double v = getDesiredRPM(); - return ff.calculate(v, 0); } +// get the gain used for TBH control +double Flywheel::getTBHGain(){ + return TBH_gain; +} + /* * Sets the value of the PID target * @param value - desired value of the PID @@ -123,7 +159,6 @@ int spinRPMTask_PID_Feedforward(void* wheelPointer) { //https://www.vexwiki.org/programming/controls_algorithms/tbh int spinRPMTask_TBH(void* wheelPointer) { Flywheel* wheel = (Flywheel*) wheelPointer; - double gain = .00001; double tbh = 0.0; double output = 0.0; @@ -137,7 +172,7 @@ int spinRPMTask_TBH(void* wheelPointer) { } double error = wheel->getDesiredRPM() - wheel->getRPM(); - output += gain * error; + output += wheel->getTBHGain() * error; wheel->spin_raw(clamp(output, 0, 1), fwd); if (sign(error)!=sign(previous_error)){ @@ -180,7 +215,26 @@ void Flywheel::spin_manual(double speed, directionType dir){ void Flywheel::spinRPM(int inputRPM) { // only run if the RPM is different or it isn't already running if(!taskRunning) { - rpmTask = task(spinRPMTask_TBH, this); + + int (*rpm_control_task)(void *); // this just means a function that returns int and takes a void pointer as an argument aka a spinRPMTask function + // choose which version to use based on how the flywheel was constructed + switch(control_style){ + case Bang_Bang: + rpm_control_task = spinRPMTask_BangBang; + break; + case Take_Back_Half: + rpm_control_task = spinRPMTask_TBH; + break; + case Feedforward: + rpm_control_task = spinRPMTask_Feedforward; + break; + case PID_Feedforward: + rpm_control_task = spinRPMTask_PID_Feedforward; + break; + } + + + rpmTask = task(rpm_control_task, this); taskRunning = true; } RPM = inputRPM; From 0e4fbdb85484c71425abc6b382f00751f9520945 Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 14 Oct 2022 18:48:15 -0400 Subject: [PATCH 093/243] Formalized TBH Control in robot config Cleaned up opcontrol to remove all testing stuff --- src/subsystems/flywheel.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 1827cd6..2bcd918 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -18,7 +18,6 @@ #include "../core/include/utils/feedforward.h" #include "../core/include/utils/pid.h" #include "../core/include/utils/math_util.h" -#include "C:/Users/richi/VEX/2022-2023-Flynn/include/robot-config.h" #include "vex.h" using namespace vex; From 3c324ef8c6f27493bba77f33bea163b38a468cdd Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 14 Oct 2022 19:05:14 -0400 Subject: [PATCH 094/243] Revert "Formalized TBH Control in robot config" This reverts commit 032ecfddbaaa20af02931ae0630a58e037e32a70. --- src/subsystems/flywheel.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 2bcd918..1827cd6 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -18,6 +18,7 @@ #include "../core/include/utils/feedforward.h" #include "../core/include/utils/pid.h" #include "../core/include/utils/math_util.h" +#include "C:/Users/richi/VEX/2022-2023-Flynn/include/robot-config.h" #include "vex.h" using namespace vex; From 0e1866e9b741f684ebcc8be2146c00067766c4b2 Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 14 Oct 2022 20:14:14 -0400 Subject: [PATCH 095/243] Reset non-flywheel related files to their initial state --- include/subsystems/flywheel.h | 3 +- src/subsystems/flywheel.cpp | 97 +++++++++++++++-------- src/subsystems/odometry/odometry_tank.cpp | 5 +- src/subsystems/tank_drive.cpp | 4 +- src/utils/pure_pursuit.cpp | 2 +- 5 files changed, 73 insertions(+), 38 deletions(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index 7f644a9..d9f31ad 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -15,6 +15,7 @@ #include "vex.h" #include "../core/include/robot_specs.h" #include "../core/include/utils/pid.h" +#include using namespace vex; @@ -62,7 +63,7 @@ class Flywheel{ FeedForward ff; // FF constants for the flywheel double TBH_gain; // TBH gain parameter for the flywheel double ratio; // multiplies the velocity by this value - double RPM = -1.0; // Desired RPM of the flywheel. + std::atomic RPM; // Desired RPM of the flywheel. task rpmTask; // task (thread but not) that handles spinning the wheel at a given RPM FlywheelControlStyle control_style; // how the flywheel should be controlled diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 1827cd6..29c6a13 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -18,7 +18,6 @@ #include "../core/include/utils/feedforward.h" #include "../core/include/utils/pid.h" #include "../core/include/utils/math_util.h" -#include "C:/Users/richi/VEX/2022-2023-Flynn/include/robot-config.h" #include "vex.h" using namespace vex; @@ -30,7 +29,7 @@ using namespace vex; PID::pid_config_t empty_pid = PID::pid_config_t{}; FeedForward::ff_config_t empty_ff = FeedForward::ff_config_t{}; -/* +/** * Create the Flywheel object using PID + feedforward for control. * @param motors - pointer to the motors on the fly wheel * @param ff - pointer to the feedforward config @@ -39,7 +38,7 @@ FeedForward::ff_config_t empty_ff = FeedForward::ff_config_t{}; Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio) :motors(motors), pid(pid_config), ff(ff_config), ratio(ratio), control_style(PID_Feedforward) { } -/* +/** * Create the Flywheel object using only feedforward for control * @param motors - pointer to the motors on the fly wheel * @param ff - pointer to the feedforward config @@ -48,7 +47,7 @@ Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForwa Flywheel::Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio) :motors(motors), pid(empty_pid), ff(ff_config), ratio(ratio), control_style(Feedforward) {} -/* +/** * Create the Flywheel object using Take Back Half for control * @param motors - pointer to the motors on the fly wheel * @param TBH_gain - the TBH control paramater @@ -57,7 +56,7 @@ Flywheel::Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, con Flywheel::Flywheel(motor_group &motors, const double TBH_gain, const double ratio) :motors(motors), pid(empty_pid), ff(empty_ff), TBH_gain(TBH_gain), ratio(ratio), control_style(Take_Back_Half) {} -/* +/** * Create the Flywheel object using Bang Bang for control * @param motors - pointer to the motors on the fly wheel * @param ratio - ratio of the whatever just multiplies the velocity @@ -65,44 +64,60 @@ Flywheel::Flywheel(motor_group &motors, const double TBH_gain, const double rati Flywheel::Flywheel(motor_group &motors, const double ratio) :motors(motors), pid(empty_pid), ff(empty_ff), ratio(ratio), control_style(Bang_Bang) {} - - -// return the current value that the RPM should be set to; +/** +* Return the current value that the RPM should be set to +* @return RPM = the target rpm +*/ double Flywheel::getDesiredRPM() { return RPM; } -// returns whether or not the wheel is running a task currently +/** +* Checks if the background RPM controlling task is running +* @return taskRunning - If the task is running +*/ bool Flywheel::isTaskRunning() { return taskRunning; } - -// Returns a POINTER TO the motors; not currently used. + +/** +* Returns a POINTER TO the motors; not currently used. +*/ motor_group* Flywheel::getMotors() { return &motors; } // TODO -- Remove? -// return the current velocity of the flywheel motors, in RPM +/** +* return the current velocity of the flywheel motors, in RPM +*/ double Flywheel::getRPM() { return ratio * motors.velocity(velocityUnits::rpm); } -// Returns a POINTER TO the PID; not currently used. +/** +* Returns a POINTER TO the PID; not currently used. +*/ PID* Flywheel::getPID() { return &pid; } // TODO -- Remove? -// returns the current OUT value of the PID +/** +* returns the current OUT value of the PID - the value that the PID would set the motors to +*/ double Flywheel::getPIDValue() { return pid.get(); } -// returns the current OUT value of the Feedforward +/** +* returns the current OUT value of the Feedforward - the value that the Feedforward would set the motors to +*/ double Flywheel::getFeedforwardValue() { double v = getDesiredRPM(); return ff.calculate(v, 0); } -// get the gain used for TBH control +/** +* get the gain used for TBH control +*/ double Flywheel::getTBHGain(){ return TBH_gain; } -/* +/** * Sets the value of the PID target * @param value - desired value of the PID */ void Flywheel::setPIDTarget(double value) { pid.set_target(value); } -/* +/** * updates the value of the PID * @param value - value to update the PID with */ @@ -115,7 +130,9 @@ void Flywheel::updatePID(double value) { pid.update(value); } * @param wheelPointer - points to the current wheel object *********************************************************/ -// Runs a BANG BANG variant. I have NO IDEA if it will work properly but I have NOTHING to test this on. +/** +* Runs a Feedforward variant to control rpm +*/ int spinRPMTask_BangBang(void* wheelPointer) { Flywheel* wheel = (Flywheel*) wheelPointer; while(true) { @@ -126,10 +143,12 @@ int spinRPMTask_BangBang(void* wheelPointer) { else { wheel->stopMotors(); } vexDelay(1); } - return 0; // only here to make the compiler SHUT UP + return 0; } -// Runs a Feedforward variant; +/** +* Runs a Feedforward variant to control rpm +*/ int spinRPMTask_Feedforward(void* wheelPointer) { Flywheel* wheel = (Flywheel*) wheelPointer; // get the pid from the wheel and set its target to the RPM stored in the wheel. @@ -141,8 +160,9 @@ int spinRPMTask_Feedforward(void* wheelPointer) { } return 0; } - -// Runs a PID + Feedforward variant; +/** +* Runs a PID + Feedforward variant to control rpm +*/ int spinRPMTask_PID_Feedforward(void* wheelPointer) { Flywheel* wheel = (Flywheel*) wheelPointer; // get the pid from the wheel and set its target to the RPM stored in the wheel. @@ -155,8 +175,10 @@ int spinRPMTask_PID_Feedforward(void* wheelPointer) { return 0; } -// Runs a Take Back Half variant; -//https://www.vexwiki.org/programming/controls_algorithms/tbh +/** +* Runs a Take Back Half variant to control RPM +* https://www.vexwiki.org/programming/controls_algorithms/tbh +*/ int spinRPMTask_TBH(void* wheelPointer) { Flywheel* wheel = (Flywheel*) wheelPointer; @@ -194,7 +216,8 @@ int spinRPMTask_ClosedLoop(void* wheelPointer) { return 0; } * SPINNERS AND STOPPERS *********************************************************/ -/* Spin motors using voltage; defaults forward at 12 volts +/** +* Spin motors using voltage; defaults forward at 12 volts * FOR USE BY TASKS ONLY * @param speed - speed (between -1 and 1) to set the motor * @param dir - direction that the motor moves in; defaults to forward @@ -203,13 +226,17 @@ void Flywheel::spin_raw(double speed, directionType dir){ motors.spin(dir, speed * 12, voltageUnits::volt); } -// Spin motors using voltage; defaults forward at 12 volts -// FOR USE BY OPCONTROL AND AUTONOMOUS, same as spin_raw otherwise +/** +* Spin motors using voltage; defaults forward at 12 volts +* FOR USE BY OPCONTROL AND AUTONOMOUS - this only applies if the RPM thread is not running +*/ void Flywheel::spin_manual(double speed, directionType dir){ if(!taskRunning) motors.spin(dir, speed * 12, voltageUnits::volt); } -/* starts / restarts RPM thread at new value +/** +* starts or sets the RPM thread at new value +* what control scheme is dependent on control_style * @param inputRPM - set the current RPM */ void Flywheel::spinRPM(int inputRPM) { @@ -241,15 +268,21 @@ void Flywheel::spinRPM(int inputRPM) { setPIDTarget(RPM); } -// stop the RPM thread and the wheel +/** +* stop the RPM thread and the wheel +*/ void Flywheel::stop() { rpmTask.stop(); taskRunning = false; motors.stop(); } -// stop only the motors; exclusively for BANG BANG use +/** +* stop only the motors; exclusively for BANG BANG use +*/ void Flywheel::stopMotors() { motors.stop(); } -// stop the motors iff the task isn't running +/** +* Stop the motors if the task isn't running - stop manual control +*/ void Flywheel::stopNonTasks() { if(!taskRunning) { motors.stop(); }} \ No newline at end of file diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 7ca1047..c801c2f 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -92,11 +92,12 @@ position_t OdometryTank::update() // Get the arclength of the turning circle of the robot double distance_diff = (rside_revs - lside_revs) * PI * config.odom_wheel_diam; - + printf("dist_diff: %f, ", distance_diff); + //Use the arclength formula to calculate the angle. Add 90 to make "0 degrees" to starboard angle = ((180.0 / PI) * (distance_diff / config.dist_between_wheels)) + 90; - // printf("angle: %f, ", (180.0 / PI) * (distance_diff / config.dist_between_wheels)); + printf("angle: %f, ", (180.0 / PI) * (distance_diff / config.dist_between_wheels)); } else { diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index f72c0ee..bd99b81 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -263,7 +263,7 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti drive_tank(lside, rside); - //printf("dist: %f\n", sign * -1 * dist_left); + printf("dist: %f\n", sign * -1 * dist_left); fflush(stdout); // Check if the robot has reached it's destination @@ -306,7 +306,7 @@ bool TankDrive::turn_to_heading(double heading_deg, double speed) double delta_heading = OdometryBase::smallest_angle(odometry->get_position().rot, heading_deg); turn_pid.update(delta_heading); - //printf("~TURN~ delta: %f\n", delta_heading); + printf("~TURN~ delta: %f\n", delta_heading); // printf("delta heading: %f, pid: %f\n", delta_heading, turn_pid.get()); fflush(stdout); diff --git a/src/utils/pure_pursuit.cpp b/src/utils/pure_pursuit.cpp index b5e09b3..4b28a3c 100644 --- a/src/utils/pure_pursuit.cpp +++ b/src/utils/pure_pursuit.cpp @@ -223,7 +223,7 @@ std::vector PurePursuit::smooth_path_cubic(std::vector= fmin(spline.x_start, spline.x_end) && x <= fmax(spline.x_start, spline.x_end)) { new_path.push_back({x, spline.getY(x)}); From cbcc4d919eeea92128893ec1067d9ccfa25cbaaa Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 14 Oct 2022 20:28:24 -0400 Subject: [PATCH 096/243] Updated documentation and included it in the header file --- include/subsystems/flywheel.h | 143 ++++++++++++++++++++++++++++------ src/subsystems/flywheel.cpp | 17 ++-- 2 files changed, 130 insertions(+), 30 deletions(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index d9f31ad..81a1e17 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -29,31 +29,130 @@ class Flywheel{ public: // CONSTRUCTORS, GETTERS, AND SETTERS - Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio); // constructor for feedforward + pid - Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio); // constructor for only feed forward - Flywheel(motor_group &motors, double tbh_gain, const double ratio); // constructor for take back half - Flywheel(motor_group &motors, const double ratio); // constructor for bang-bang control - - - double getDesiredRPM(); // returns the desired RPM - bool isTaskRunning(); // returns if a task is running - motor_group* getMotors(); // returns a pointer to the motors - double getRPM(); // get the current velocity of the motors in RPM - PID* getPID(); // returns a pointer to the PID - double getPIDValue(); // get the current OUT value of the PID - double getFeedforwardValue(); // get the current OUT value of the feedforward - double getTBHGain(); // get the gain used for TBH control + /** + * Create the Flywheel object using PID + feedforward for control. + * @param motors - pointer to the motors on the fly wheel + * @param pid_config - pointer the pid config + * @param ff - pointer to the feedforward config + * @param ratio - ratio of the whatever just multiplies the velocity + */ + Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio); + + /** + * Create the Flywheel object using only feedforward for control + * @param motors - pointer to the motors on the fly wheel + * @param ff - pointer to the feedforward config + * @param ratio - ratio of the whatever just multiplies the velocity + */ + Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio); + + /** + * Create the Flywheel object using Take Back Half for control + * @param motors - pointer to the motors on the fly wheel + * @param TBH_gain - the TBH control paramater + * @param ratio - ratio of the whatever just multiplies the velocity + */ + Flywheel(motor_group &motors, double tbh_gain, const double ratio); + + /** + * Create the Flywheel object using Bang Bang for control + * @param motors - pointer to the motors on the fly wheel + * @param ratio - ratio of the whatever just multiplies the velocity + */ + Flywheel(motor_group &motors, const double ratio); + + /** + * Return the current value that the RPM should be set to + * @return RPM = the target rpm + */ + double getDesiredRPM(); + + /** + * Checks if the background RPM controlling task is running + * @return taskRunning - If the task is running + */ + bool isTaskRunning(); + + /** + * Returns a POINTER to the motors + */ + motor_group* getMotors(); + + /** + * return the current velocity of the flywheel motors, in RPM + */ + double getRPM(); + + /** + * Returns a POINTER to the PID. + */ + PID* getPID(); + + /** + * returns the current OUT value of the PID - the value that the PID would set the motors to + */ + double getPIDValue(); + + /** + * returns the current OUT value of the PID - the value that the PID would set the motors to + */ + double getFeedforwardValue(); - void setPIDTarget(double value); // set the PID target - void updatePID(double value); // update the PID with the current value it's tracking + /** + * get the gain used for TBH control + */ + double getTBHGain(); + + /** + * Sets the value of the PID target + * @param value - desired value of the PID + */ + void setPIDTarget(double value); + +/** +* updates the value of the PID +* @param value - value to update the PID with +*/ + void updatePID(double value); // SPINNERS AND STOPPERS - void spin_raw(double speed, directionType dir=fwd); // Spins at a given speed between -1 and 1 - void spin_manual(double speed, directionType dir=fwd); // Same as spin_raw, but check to make sure a task isn't running before doing it. - void spinRPM(int rpm); // spins the turret at a target RPM - void stop(); // stops the motors and the thread - void stopMotors(); // stops ONLY the motors - void stopNonTasks(); // stops motors IFF a task isn't running and a manual setter isn't being pressed + + /** + * Spin motors using voltage; defaults forward at 12 volts + * FOR USE BY TASKS ONLY + * @param speed - speed (between -1 and 1) to set the motor + * @param dir - direction that the motor moves in; defaults to forward + */ + void spin_raw(double speed, directionType dir=fwd); + + /** + * Spin motors using voltage; defaults forward at 12 volts + * FOR USE BY OPCONTROL AND AUTONOMOUS - this only applies if the RPM thread is not running + */ + void spin_manual(double speed, directionType dir=fwd); + + /** + * starts or sets the RPM thread at new value + * what control scheme is dependent on control_style + * @param inputRPM - set the current RPM + */ + void spinRPM(int rpm); + + /** + * stop the RPM thread and the wheel + */ + void stop(); + + + /** + * stop only the motors; exclusively for BANG BANG use + */ + void stopMotors(); + + /** + * Stop the motors if the task isn't running - stop manual control + */ + void stopNonTasks(); private: diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 29c6a13..0f1a154 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -31,9 +31,10 @@ FeedForward::ff_config_t empty_ff = FeedForward::ff_config_t{}; /** * Create the Flywheel object using PID + feedforward for control. -* @param motors - pointer to the motors on the fly wheel -* @param ff - pointer to the feedforward config -* @param ratio - ratio of the whatever just multiplies the velocity +* @param motors - pointer to the motors on the fly wheel +* @param pid_config - pointer the pid config +* @param ff - pointer to the feedforward config +* @param ratio - ratio of the whatever just multiplies the velocity */ Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio) :motors(motors), pid(pid_config), ff(ff_config), ratio(ratio), control_style(PID_Feedforward) { } @@ -41,17 +42,17 @@ Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForwa /** * Create the Flywheel object using only feedforward for control * @param motors - pointer to the motors on the fly wheel -* @param ff - pointer to the feedforward config -* @param ratio - ratio of the whatever just multiplies the velocity +* @param ff - pointer to the feedforward config +* @param ratio - ratio of the whatever just multiplies the velocity */ Flywheel::Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio) :motors(motors), pid(empty_pid), ff(ff_config), ratio(ratio), control_style(Feedforward) {} /** * Create the Flywheel object using Take Back Half for control -* @param motors - pointer to the motors on the fly wheel +* @param motors - pointer to the motors on the fly wheel * @param TBH_gain - the TBH control paramater -* @param ratio - ratio of the whatever just multiplies the velocity +* @param ratio - ratio of the whatever just multiplies the velocity */ Flywheel::Flywheel(motor_group &motors, const double TBH_gain, const double ratio) :motors(motors), pid(empty_pid), ff(empty_ff), TBH_gain(TBH_gain), ratio(ratio), control_style(Take_Back_Half) {} @@ -59,7 +60,7 @@ Flywheel::Flywheel(motor_group &motors, const double TBH_gain, const double rati /** * Create the Flywheel object using Bang Bang for control * @param motors - pointer to the motors on the fly wheel -* @param ratio - ratio of the whatever just multiplies the velocity +* @param ratio - ratio of the whatever just multiplies the velocity */ Flywheel::Flywheel(motor_group &motors, const double ratio) :motors(motors), pid(empty_pid), ff(empty_ff), ratio(ratio), control_style(Bang_Bang) {} From cd74d29a646a19a8185d5d179f45d469a38d00d5 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Tue, 1 Nov 2022 11:37:22 -0400 Subject: [PATCH 097/243] Update README.md --- README.md | 27 ++++++++++++++++++++++++++- 1 file changed, 26 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 8ce5935..3990a60 100644 --- a/README.md +++ b/README.md @@ -1,2 +1,27 @@ # Core -General robot code shared between the "BIG" and "LITTLE" repo's +This is the host repository for the custom VEX libraries used by the RIT VEXU team + +## Getting Started +In order to simply use this repo, you can either clone it into your VEXcode project folder, or download the .zip and place it into a core/ subfolder. Then follow the instructions for setting up compilation at [Wiki/BuildSystem](https://github.com/RIT-VEX-U/Core/wiki/1-%7C-Project-Setup#build-system) + +If you wish to contribute, follow the instructions at [Wiki/ProjectSetup](https://github.com/RIT-VEX-U/Core/wiki/1-%7C-Project-Setup) + +## Features +Here is the current feature list this repo provides: + +Subsystems (See [Wiki/Subsystems](https://github.com/RIT-VEX-U/Core/wiki/2-%7C-Subsystems)): +- Tank drivetrain (user control / autonomous) +- Mecanum drivetrain (user control / autonomous) +- Odometry +- Flywheel +- Lift +- Custom encoders + +Utilities (See [Wiki/Utilites](https://github.com/RIT-VEX-U/Core/wiki/3-%7C-Utilites)): +- PID controller +- FeedForward controller +- Trapezoidal motion profile controller +- Pure Pursuit +- Generic auto program builder +- Auto program UI selector +- Mathematical classes (Vector2D, Moving Average) From fb5e985a6d44c3bcd99d517f73b828c1f4611e2c Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 16 Sep 2022 20:40:06 -0400 Subject: [PATCH 098/243] Added general math utilities `sign` and `clamp` to clarify meccanum_drive --- include/utils/math_util.h | 18 ++++++++++++++++++ src/subsystems/mecanum_drive.cpp | 25 +++++++++++++------------ src/utils/math_util.cpp | 31 +++++++++++++++++++++++++++++++ 3 files changed, 62 insertions(+), 12 deletions(-) create mode 100644 include/utils/math_util.h create mode 100644 src/utils/math_util.cpp diff --git a/include/utils/math_util.h b/include/utils/math_util.h new file mode 100644 index 0000000..a27c5b2 --- /dev/null +++ b/include/utils/math_util.h @@ -0,0 +1,18 @@ +#pragma once + +/** +* Constrain the input between a minimum and a maximum value +* +* @param val the value to be restrained +* @param low the minimum value that will be returned +* @param high the maximum value that will be returned +**/ +double clamp(double value, double low, double high); + +/** +* Returns the sign of a number +* @param x +* +* returns the sign +/-1 of x. 0 if x is 0 +**/ +double sign(double x); \ No newline at end of file diff --git a/src/subsystems/mecanum_drive.cpp b/src/subsystems/mecanum_drive.cpp index 962a3bc..c69ff2c 100644 --- a/src/subsystems/mecanum_drive.cpp +++ b/src/subsystems/mecanum_drive.cpp @@ -1,5 +1,5 @@ #include "../core/include/subsystems/mecanum_drive.h" - +#include "../core/include/utils/vector.h" /** * Create the Mecanum drivetrain object */ @@ -31,20 +31,20 @@ MecanumDrive::MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex: */ void MecanumDrive::drive_raw(double direction_deg, double magnitude, double rotation) { - double direction = (PI / 180.0) * direction_deg; - + double direction = deg2rad(direction_deg); + // ALGORITHM - "rotate" the vector by 45 degrees and apply each corner to a wheel // .. Oh, and mix rotation too double lf = (magnitude * cos(direction - (PI / 4.0))) + rotation; double rf = (magnitude * cos(direction + (PI / 4.0))) - rotation; double lr = (magnitude * cos(direction + (PI / 4.0))) + rotation; double rr = (magnitude * cos(direction - (PI / 4.0))) - rotation; - + // Limit the output between -1.0 and +1.0 - lf = lf > 1.0 ? 1.0 : (lf < -1.0 ? -1.0 : lf); - rf = rf > 1.0 ? 1.0 : (rf < -1.0 ? -1.0 : rf); - lr = lr > 1.0 ? 1.0 : (lr < -1.0 ? -1.0 : lr); - rr = rr > 1.0 ? 1.0 : (rr < -1.0 ? -1.0 : rr); + lf = clamp(lf, -1.0, 1.0); + rf = clamp(rf, -1.0, 1.0); + lr = clamp(lr, -1.0, 1.0); + rr = clamp(rr, -1.0, 1.0); // Finally, spin the motors left_front.spin(vex::directionType::fwd, lf * 100.0, vex::velocityUnits::pct); @@ -68,15 +68,16 @@ void MecanumDrive::drive(double left_y, double left_x, double right_x, int power // LATERAL CONTROLS - convert cartesion to a vector double magnitude = sqrt(pow(left_y / 100.0, 2) + pow(left_x / 100.0, 2)); magnitude = pow(magnitude, power); - + double direction = atan2(left_x / 100.0, left_y / 100.0); // ROTATIONAL CONTROLS - just the right x joystick - // Ternary makes sure that if the "power" is even, the rotation keeps it's sign double rotation = right_x / 100.0; - rotation = (power%2 == 0 ? rotation < 0 ? -1.0 : 1.0 : 1.0) * pow(rotation, power); - return this->drive_raw(direction * (180.0 / PI), magnitude, rotation); + // + rotation = sign(rotation) * fabs(pow(rotation, power)); + + return this->drive_raw(rad2deg(direction), magnitude, rotation); } /** diff --git a/src/utils/math_util.cpp b/src/utils/math_util.cpp new file mode 100644 index 0000000..0e8589a --- /dev/null +++ b/src/utils/math_util.cpp @@ -0,0 +1,31 @@ +#include "../core/include/utils/math_util.h" + +/** +* Constrain the input between a minimum and a maximum value +* +* @param val the value to be restrained +* @param low the minimum value that will be returned +* @param high the maximum value that will be returned +**/ +double clamp(double val, double low, double high){ + if (val < low){ + return low; + } else if (val > high){ + return high; + } + return val; +} +/** +* Returns the sign of a number +* @param x +* +* returns the sign +/-1 of x. 0 if x is 0 +**/ +double sign(double x){ + if (x<0){ + return -1; + } else if (x>0){ + return 1; + } + return 0; +} \ No newline at end of file From 6f1ff4b50f53c136f204d77d4e6eee3bf23fbd45 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 18 Sep 2022 15:55:28 -0400 Subject: [PATCH 099/243] Changed sign(0) to be 1 to avoid issues --- src/utils/math_util.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/utils/math_util.cpp b/src/utils/math_util.cpp index 0e8589a..51b5555 100644 --- a/src/utils/math_util.cpp +++ b/src/utils/math_util.cpp @@ -19,13 +19,11 @@ double clamp(double val, double low, double high){ * Returns the sign of a number * @param x * -* returns the sign +/-1 of x. 0 if x is 0 +* returns the sign +/-1 of x. special case at 0 it returns +1 **/ double sign(double x){ if (x<0){ return -1; - } else if (x>0){ - return 1; } - return 0; + return 1; } \ No newline at end of file From e1b8630ce423711e4d2b5f701838c08bc5a45457 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 18 Sep 2022 17:33:19 -0400 Subject: [PATCH 100/243] Fixed mecanum drive compile error --- src/subsystems/mecanum_drive.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/subsystems/mecanum_drive.cpp b/src/subsystems/mecanum_drive.cpp index c69ff2c..62738bd 100644 --- a/src/subsystems/mecanum_drive.cpp +++ b/src/subsystems/mecanum_drive.cpp @@ -1,5 +1,7 @@ #include "../core/include/subsystems/mecanum_drive.h" #include "../core/include/utils/vector.h" +#include "../core/include/utils/math_util.h" + /** * Create the Mecanum drivetrain object */ From 4e4420807b8a160a54bb64c46e8832d779204982 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 18 Sep 2022 17:34:40 -0400 Subject: [PATCH 101/243] Added FeedForward class from 2021-2022-BIG/motion_profile_dev --- include/utils/feedforward.h | 61 +++++++++++++++++++++++++++++++++++++ 1 file changed, 61 insertions(+) create mode 100644 include/utils/feedforward.h diff --git a/include/utils/feedforward.h b/include/utils/feedforward.h new file mode 100644 index 0000000..f2fae43 --- /dev/null +++ b/include/utils/feedforward.h @@ -0,0 +1,61 @@ +#pragma once + +/** + * FeedForward + * + * Stores the feedfoward constants, and allows for quick computation. + * Feedfoward should be used in systems that require smooth precise movements + * and have high inertia, such as drivetrains and lifts. + * + * This is best used alongside a PID loop, with the form: + * output = pid.get() + feedforward.calculate(v, a); + * + * In this case, the feedforward does the majority of the heavy lifting, and the + * pid loop only corrects for inconsistencies + * + * For information about tuning feedforward, I reccommend looking at this post: + * https://www.chiefdelphi.com/t/paper-frc-drivetrain-characterization/160915 + * (yes I know it's for FRC but trust me, it's useful) + * + * @author Ryan McGee + * @date 6/13/2022 + */ +class FeedForward +{ + public: + + /** + * kS - Coefficient to overcome static friction: the point at which the motor *starts* to move. + * kV - Veclocity coefficient: the power required to keep the mechanism in motion. Multiplied by the requested velocity. + * kA - Acceleration coefficient: the power required to change the mechanism's speed. Multiplied by the requested acceleration. + * kG - Gravity coefficient: only needed for lifts. The power required to overcome gravity and stay at steady state. + * Should relate to acceleration due to gravity and mass of the lift. + */ + typedef struct + { + double kS, kV, kA, kG; + } ff_config_t; + + + FeedForward(ff_config_t &cfg) : cfg(cfg) {} + + /** + * @brief Perform the feedforward calculation + * + * This calculation is the equation: + * F = kG + kS*sgn(v) + kV*v + kA*a + * + * @param v Requested velocity of system + * @param a Requested acceleration of system + * @return A feedforward that should closely represent the system if tuned correctly + */ + double calculate(double v, double a) + { + return (cfg.kS * (v > 0 ? 1 : v < 0 ? -1 : 0)) + (cfg.kV * v) + (cfg.kA * a) + cfg.kG; + } + + private: + + ff_config_t &cfg; + +}; \ No newline at end of file From 2fcd0dc4a6a2ef569fa47f768bd0c004dc3faedd Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 18 Sep 2022 18:24:49 -0400 Subject: [PATCH 102/243] Merge remote-tracking branch 'Clu/main' --- include/subsystems/odometry/odometry_tank.h | 2 +- include/utils/pure_pursuit.h | 20 +- include/utils/{vector.h => vector2d.h} | 228 +++++++++--------- src/subsystems/custom_encoder.cpp | 2 +- src/subsystems/mecanum_drive.cpp | 2 +- src/subsystems/odometry/odometry_base.cpp | 2 +- src/subsystems/odometry/odometry_tank.cpp | 8 +- src/subsystems/tank_drive.cpp | 14 +- src/utils/pure_pursuit.cpp | 70 +++--- src/utils/{vector.cpp => vector2d.cpp} | 250 ++++++++++---------- 10 files changed, 299 insertions(+), 299 deletions(-) rename include/utils/{vector.h => vector2d.h} (80%) rename src/utils/{vector.cpp => vector2d.cpp} (70%) diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index d0eceed..e417efb 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -2,7 +2,7 @@ #include "../core/include/subsystems/odometry/odometry_base.h" #include "../core/include/subsystems/custom_encoder.h" -#include "../core/include/utils/vector.h" +#include "../core/include/utils/vector2d.h" #include "../core/include/robot_specs.h" static int background_task(void* odom_obj); diff --git a/include/utils/pure_pursuit.h b/include/utils/pure_pursuit.h index 818fa2f..64c56dc 100644 --- a/include/utils/pure_pursuit.h +++ b/include/utils/pure_pursuit.h @@ -1,7 +1,7 @@ #pragma once #include -#include "../core/include/utils/vector.h" +#include "../core/include/utils/vector2d.h" #include "vex.h" using namespace vex; @@ -27,12 +27,12 @@ namespace PurePursuit { double dir; double mag; - Vector::point_t getPoint() { + Vector2D::point_t getPoint() { return {x, y}; } - Vector getTangent() { - return Vector(dir, mag); + Vector2D getTangent() { + return Vector2D(dir, mag); } }; @@ -40,16 +40,16 @@ namespace PurePursuit { * Returns points of the intersections of a line segment and a circle. The line * segment is defined by two points, and the circle is defined by a center and radius. */ - static std::vector line_circle_intersections(Vector::point_t center, double r, Vector::point_t point1, Vector::point_t point2); + static std::vector line_circle_intersections(Vector2D::point_t center, double r, Vector2D::point_t point1, Vector2D::point_t point2); /** * Selects a look ahead from all the intersections in the path. */ - static Vector::point_t get_lookahead(std::vector path, Vector::point_t robot_loc, double radius); + static Vector2D::point_t get_lookahead(std::vector path, Vector2D::point_t robot_loc, double radius); /** * Injects points in a path without changing the curvature with a certain spacing. */ - static std::vector inject_path(std::vector path, double spacing); + static std::vector inject_path(std::vector path, double spacing); /** * Returns a smoothed path maintaining the start and end of the path. @@ -62,9 +62,9 @@ namespace PurePursuit { * https://medium.com/@jaems33/understanding-robot-motion-path-smoothing-5970c8363bc4 */ - static std::vector smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance); + static std::vector smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance); - static std::vector smooth_path_cubic(std::vector path, double res); + static std::vector smooth_path_cubic(std::vector path, double res); /** * Interpolates a smooth path given a list of waypoints using hermite splines. @@ -74,5 +74,5 @@ namespace PurePursuit { * @param steps The number of points interpolated between points. * @return The smoothed path. */ - static std::vector smooth_path_hermite(std::vector path, double step); + static std::vector smooth_path_hermite(std::vector path, double step); } \ No newline at end of file diff --git a/include/utils/vector.h b/include/utils/vector2d.h similarity index 80% rename from include/utils/vector.h rename to include/utils/vector2d.h index 858ce88..1e3bbb8 100644 --- a/include/utils/vector.h +++ b/include/utils/vector2d.h @@ -1,114 +1,114 @@ -#pragma once - -#include - -#ifndef PI -#define PI 3.141592654 -#endif - -class Vector -{ -public: - - /** - * Data structure representing an X,Y coordinate - */ - struct point_t - { - double x, y; - - double dist(const point_t other) - { - return sqrt(pow(this->x - other.x, 2) + pow(this->y - other.y, 2)); - } - - // Vector addition operation on points - point_t operator+(const point_t &other) - { - point_t p - { - .x = this->x + other.x, - .y = this->y + other.y - }; - return p; - } - - // Vector subtraction operation on points - point_t operator-(const point_t &other) - { - point_t p - { - .x = this->x - other.x, - .y = this->y - other.y - }; - return p; - } - }; - - /** - * Construct a vector object. - * - * @param dir Direction, in radians. 'foward' is 0, clockwise positive when viewed from the top. - * @param mag Magnitude. - */ - Vector(double dir, double mag); - - /** - * Construct a vector object from a cartesian point. - * - * @param p point_t.x , point_t.y - */ - Vector(point_t &p); - - /** - * Get the direction of the vector, in radians. - * '0' is forward, clockwise positive when viewed from the top. - * - * Use r2d() to convert. - */ - double get_dir() const; - - /** - * Get the magnitude of the vector - */ - double get_mag() const; - - /** - * Get the X component of the vector; positive to the right. - */ - double get_x() const; - - /** - * Get the Y component of the vector, positive forward. - */ - double get_y() const; - - /** - * Changes the magnetude of the vector to 1 - */ - Vector normalize(); - - /** - * Returns a point from the vector - */ - Vector::point_t point(); - - Vector operator*(const double &x); - Vector operator+(const Vector &other); - Vector operator-(const Vector &other); - -private: - - double dir, mag; - -}; - -/** - * General function for converting degrees to radians - */ -double deg2rad(double deg); - -/** - * General function for converting radians to degrees - */ -double rad2deg(double r); +#pragma once + +#include + +#ifndef PI +#define PI 3.141592654 +#endif + +class Vector2D +{ +public: + + /** + * Data structure representing an X,Y coordinate + */ + struct point_t + { + double x, y; + + double dist(const point_t other) + { + return sqrt(pow(this->x - other.x, 2) + pow(this->y - other.y, 2)); + } + + // Vector2D addition operation on points + point_t operator+(const point_t &other) + { + point_t p + { + .x = this->x + other.x, + .y = this->y + other.y + }; + return p; + } + + // Vector2D subtraction operation on points + point_t operator-(const point_t &other) + { + point_t p + { + .x = this->x - other.x, + .y = this->y - other.y + }; + return p; + } + }; + + /** + * Construct a vector object. + * + * @param dir Direction, in radians. 'foward' is 0, clockwise positive when viewed from the top. + * @param mag Magnitude. + */ + Vector2D(double dir, double mag); + + /** + * Construct a vector object from a cartesian point. + * + * @param p point_t.x , point_t.y + */ + Vector2D(point_t &p); + + /** + * Get the direction of the vector, in radians. + * '0' is forward, clockwise positive when viewed from the top. + * + * Use r2d() to convert. + */ + double get_dir() const; + + /** + * Get the magnitude of the vector + */ + double get_mag() const; + + /** + * Get the X component of the vector; positive to the right. + */ + double get_x() const; + + /** + * Get the Y component of the vector, positive forward. + */ + double get_y() const; + + /** + * Changes the magnetude of the vector to 1 + */ + Vector2D normalize(); + + /** + * Returns a point from the vector + */ + Vector2D::point_t point(); + + Vector2D operator*(const double &x); + Vector2D operator+(const Vector2D &other); + Vector2D operator-(const Vector2D &other); + +private: + + double dir, mag; + +}; + +/** + * General function for converting degrees to radians + */ +double deg2rad(double deg); + +/** + * General function for converting radians to degrees + */ +double rad2deg(double r); diff --git a/src/subsystems/custom_encoder.cpp b/src/subsystems/custom_encoder.cpp index 81472ac..64f3662 100644 --- a/src/subsystems/custom_encoder.cpp +++ b/src/subsystems/custom_encoder.cpp @@ -1,4 +1,4 @@ -#include "../core/include/subsystems/custom_encoder.h" +#include "../core/include/subsystems/custom_encoder.h" CustomEncoder::CustomEncoder(vex::triport::port &port, double ticks_per_rev) : super(port) diff --git a/src/subsystems/mecanum_drive.cpp b/src/subsystems/mecanum_drive.cpp index 62738bd..0fcf6af 100644 --- a/src/subsystems/mecanum_drive.cpp +++ b/src/subsystems/mecanum_drive.cpp @@ -1,5 +1,5 @@ #include "../core/include/subsystems/mecanum_drive.h" -#include "../core/include/utils/vector.h" +#include "../core/include/utils/vector2d.h" #include "../core/include/utils/math_util.h" /** diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index ffa872c..3c55330 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -1,5 +1,5 @@ #include "../core/include/subsystems/odometry/odometry_base.h" -#include "../core/include/utils/vector.h" +#include "../core/include/utils/vector2d.h" /** * Gets the current position and rotation diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 111cca3..c801c2f 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -143,14 +143,14 @@ position_t OdometryTank::calculate_new_pos(robot_specs_t &config, position_t &cu double angle = angle_deg * PI / 180.0; // Degrees to radians // Create a vector from the change in distance in the current direction of the robot - Vector chg_vec(angle, dist_driven); + Vector2D chg_vec(angle, dist_driven); // Create a vector from the current position in reference to X,Y=0,0 - Vector::point_t curr_point = {.x = curr_pos.x, .y = curr_pos.y}; - Vector curr_vec(curr_point); + Vector2D::point_t curr_point = {.x = curr_pos.x, .y = curr_pos.y}; + Vector2D curr_vec(curr_point); // Tack on the "difference" vector to the current vector - Vector new_vec = curr_vec + chg_vec; + Vector2D new_vec = curr_vec + chg_vec; new_pos.x = new_vec.get_x(); new_pos.y = new_vec.get_y(); diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index e9c4839..bd99b81 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -92,9 +92,9 @@ bool TankDrive::drive_forward(double inches, double speed, double correction, di drive_pid.reset(); // Use vector math to get an X and Y - Vector current_pos({saved_pos.x , saved_pos.y}); - Vector delta_pos(deg2rad(saved_pos.rot), inches); - Vector setpt_vec = current_pos + delta_pos; + Vector2D current_pos({saved_pos.x , saved_pos.y}); + Vector2D delta_pos(deg2rad(saved_pos.rot), inches); + Vector2D setpt_vec = current_pos + delta_pos; // Save the new X and Y values pos_setpt = {.x=setpt_vec.get_x(), .y=setpt_vec.get_y()}; @@ -192,13 +192,13 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti position_t end_pos = {.x=x, .y=y}; // Create a point (and vector) to get the direction - Vector::point_t pos_diff_pt = + Vector2D::point_t pos_diff_pt = { .x = x - current_pos.x, .y = y - current_pos.y }; - Vector point_vec(pos_diff_pt); + Vector2D point_vec(pos_diff_pt); // Get the distance between 2 points double dist_left = OdometryBase::pos_diff(current_pos, end_pos); @@ -334,9 +334,9 @@ double TankDrive::modify_inputs(double input, int power) bool TankDrive::pure_pursuit(std::vector path, double radius, double speed, double res, directionType dir) { is_pure_pursuit = true; - std::vector smoothed_path = PurePursuit::smooth_path_hermite(path, res); + std::vector smoothed_path = PurePursuit::smooth_path_hermite(path, res); - Vector::point_t lookahead = PurePursuit::get_lookahead(smoothed_path, {odometry->get_position().x, odometry->get_position().y}, radius); + Vector2D::point_t lookahead = PurePursuit::get_lookahead(smoothed_path, {odometry->get_position().x, odometry->get_position().y}, radius); //printf("%f\t%f\n", odometry->get_position().x, odometry->get_position().y); //printf("%f\t%f\n", lookahead.x, lookahead.y); bool is_last_point = (path.back().x == lookahead.x) && (path.back().y == lookahead.y); diff --git a/src/utils/pure_pursuit.cpp b/src/utils/pure_pursuit.cpp index 11aaea9..4b28a3c 100644 --- a/src/utils/pure_pursuit.cpp +++ b/src/utils/pure_pursuit.cpp @@ -4,9 +4,9 @@ * Returns points of the intersections of a line segment and a circle. The line * segment is defined by two points, and the circle is defined by a center and radius. */ -std::vector PurePursuit::line_circle_intersections(Vector::point_t center, double r, Vector::point_t point1, Vector::point_t point2) +std::vector PurePursuit::line_circle_intersections(Vector2D::point_t center, double r, Vector2D::point_t point1, Vector2D::point_t point2) { - std::vector intersections = {}; + std::vector intersections = {}; //Do future calculations relative to the circle's center point1.y -= center.y; @@ -38,12 +38,12 @@ std::vector PurePursuit::line_circle_intersections(Vector::poin //The equations used define an infinitely long line, so we check if the detected intersection falls on the line segment. if(x1 >= fmin(point1.x, point2.x) && x1 <= fmax(point1.x, point2.x) && y1 >= fmin(point1.y, point2.y) && y1 <= fmax(point1.y, point2.y)) { - intersections.push_back(Vector::point_t{.x = x1 + center.x, .y = y1 + center.y}); + intersections.push_back(Vector2D::point_t{.x = x1 + center.x, .y = y1 + center.y}); } if(x2 >= fmin(point1.x, point2.x) && x2 <= fmax(point1.x, point2.x) && y2 >= fmin(point1.y, point2.y) && y2 <= fmax(point1.y, point2.y)) { - intersections.push_back(Vector::point_t{.x = x2 + center.x, .y = y2 + center.y}); + intersections.push_back(Vector2D::point_t{.x = x2 + center.x, .y = y2 + center.y}); } return intersections; @@ -52,10 +52,10 @@ std::vector PurePursuit::line_circle_intersections(Vector::poin /** * Selects a look ahead from all the intersections in the path. */ -Vector::point_t PurePursuit::get_lookahead(std::vector path, Vector::point_t robot_loc, double radius) +Vector2D::point_t PurePursuit::get_lookahead(std::vector path, Vector2D::point_t robot_loc, double radius) { //Default: the end of the path - Vector::point_t target = path.back(); + Vector2D::point_t target = path.back(); if(target.dist(robot_loc) <= radius) @@ -66,13 +66,13 @@ Vector::point_t PurePursuit::get_lookahead(std::vector path, Ve //Check each line segment of the path for potential targets for(int i = 0; i < path.size() - 1; i++) { - Vector::point_t start = path[i]; - Vector::point_t end = path[i+1]; + Vector2D::point_t start = path[i]; + Vector2D::point_t end = path[i+1]; - std::vector intersections = line_circle_intersections(robot_loc, radius, start, end); + std::vector intersections = line_circle_intersections(robot_loc, radius, start, end); //Choose the intersection that is closest to the end of the line segment //This prioritizes the closest intersection to the end of the path - for(Vector::point_t intersection: intersections) + for(Vector2D::point_t intersection: intersections) { if(intersection.dist(end) < target.dist(end)) target = intersection; @@ -85,18 +85,18 @@ Vector::point_t PurePursuit::get_lookahead(std::vector path, Ve /** Injects points in a path without changing the curvature with a certain spacing. */ -std::vector PurePursuit::inject_path(std::vector path, double spacing) +std::vector PurePursuit::inject_path(std::vector path, double spacing) { - std::vector new_path; + std::vector new_path; //Injecting points for each line segment for(int i = 0; i < path.size() - 1; i++) { - Vector::point_t start = path[i]; - Vector::point_t end = path[i+1]; + Vector2D::point_t start = path[i]; + Vector2D::point_t end = path[i+1]; - Vector::point_t diff = end - start; - Vector vector = Vector(diff); + Vector2D::point_t diff = end - start; + Vector2D vector = Vector2D(diff); int num_points = ceil(vector.get_mag() / spacing); @@ -106,7 +106,7 @@ std::vector PurePursuit::inject_path(std::vector PurePursuit::inject_path(std::vector PurePursuit::smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance) +std::vector PurePursuit::smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance) { - std::vector new_path = path; + std::vector new_path = path; double change = tolerance; while(change >= tolerance) { change = 0; for(int i = 1; i < path.size() - 1; i++) { - Vector::point_t x_i = path[i]; - Vector::point_t y_i = new_path[i]; - Vector::point_t y_prev = new_path[i-1]; - Vector::point_t y_next = new_path[i+1]; + Vector2D::point_t x_i = path[i]; + Vector2D::point_t y_i = new_path[i]; + Vector2D::point_t y_prev = new_path[i-1]; + Vector2D::point_t y_next = new_path[i+1]; - Vector::point_t y_i_saved = y_i; + Vector2D::point_t y_i_saved = y_i; y_i.x += weight_data * (x_i.x - y_i.x) + weight_smooth * (y_next.x + y_prev.x - (2 * y_i.x)); y_i.y += weight_data * (x_i.y - y_i.y) + weight_smooth * (y_next.y + y_prev.y - (2 * y_i.y)); @@ -159,17 +159,17 @@ std::vector PurePursuit::smooth_path(std::vector PurePursuit::smooth_path_hermite(std::vector path, double steps) { - std::vector new_path; +std::vector PurePursuit::smooth_path_hermite(std::vector path, double steps) { + std::vector new_path; for(int i = 0; i < path.size() - 1; i++) { for(int t = 0; t < steps; t++) { - // Storing the start and end points and slopes at those points as Vectors. - Vector::point_t tmp = path[i].getPoint(); - Vector p1 = Vector(tmp); + // Storing the start and end points and slopes at those points as Vector2Ds. + Vector2D::point_t tmp = path[i].getPoint(); + Vector2D p1 = Vector2D(tmp); tmp = path[i+1].getPoint(); - Vector p2 = Vector(tmp); - Vector t1 = path[i].getTangent(); - Vector t2 = path[i+1].getTangent(); + Vector2D p2 = Vector2D(tmp); + Vector2D t1 = path[i].getTangent(); + Vector2D t2 = path[i+1].getTangent(); // Scale s from 0.0 to 1.0 @@ -182,7 +182,7 @@ std::vector PurePursuit::smooth_path_hermite(std::vector PurePursuit::smooth_path_hermite(std::vector PurePursuit::smooth_path_cubic(std::vector path, double res) { - std::vector new_path; +std::vector PurePursuit::smooth_path_cubic(std::vector path, double res) { + std::vector new_path; std::vector splines; double delta_x[path.size() - 1]; diff --git a/src/utils/vector.cpp b/src/utils/vector2d.cpp similarity index 70% rename from src/utils/vector.cpp rename to src/utils/vector2d.cpp index b29cb14..8532847 100644 --- a/src/utils/vector.cpp +++ b/src/utils/vector2d.cpp @@ -1,125 +1,125 @@ -#include "../core/include/utils/vector.h" - -/** - * Construct a vector object. - * - * @param dir Direction, in radians. 'foward' is 0, clockwise positive when viewed from the top. - * @param mag Magnitude. - */ -Vector::Vector(double dir, double mag) -: dir(dir), mag(mag) -{ - -} - -/** - * Construct a vector object from a cartesian point. - * - * @param p point_t.x , point_t.y - */ -Vector::Vector(point_t &p) -{ - this->dir = atan2(p.y, p.x); - this->mag = sqrt( (p.x*p.x) + (p.y*p.y) ); -} - -/** - * Get the direction of the vector, in radians. - * '0' is forward, clockwise positive when viewed from the top. - * - * Use r2d() to convert. - */ -double Vector::get_dir() const { return dir;} - -/** - * Get the magnitude of the vector - */ -double Vector::get_mag() const { return mag; } - -/** - * Get the X component of the vector; positive to the right. - */ -double Vector::get_x() const -{ -return mag * cos(dir); -} - -/** - * Get the Y component of the vector, positive forward. - */ -double Vector::get_y() const -{ -return mag * sin(dir); -} - -/** - * Changes the magnetude of the vector to 1 -*/ -Vector Vector::normalize() -{ - return Vector(this->dir, 1); -} - -/** - * Returns a point from the vector -*/ -Vector::point_t Vector::point() -{ - point_t p = - { - .x = this->mag * cos(this->dir), - .y = this->mag * sin(this->dir) - }; - return p; -} - -/** - * Correctly add vectors together with the + operator - */ -Vector Vector::operator+(const Vector &other) -{ - point_t p = - { - .x = this->get_x() + other.get_x(), - .y = this->get_y() + other.get_y() - }; - - return Vector( p ); -} - -/** - * Correctly subtract vectors with the - operator - */ -Vector Vector::operator-(const Vector &other) -{ - point_t p = - { - .x = this->get_x() - other.get_x(), - .y = this->get_y() - other.get_y() - }; - return Vector( p ); -} - -/** - * Multiplies a vector by a double with the * operator -*/ -Vector Vector::operator*(const double &x) -{ - return Vector(this->dir, this->mag * x); -} - -/** - * General function for converting degrees to radians - */ -double deg2rad(double deg) -{ - return deg * (PI / 180.0); -} - -/** - * General function for converting radians to degrees - */ -double rad2deg(double rad) -{ - return rad * (180.0 / PI); -} +#include "../core/include/utils/vector2d.h" + +/** + * Construct a vector object. + * + * @param dir Direction, in radians. 'foward' is 0, clockwise positive when viewed from the top. + * @param mag Magnitude. + */ +Vector2D::Vector2D(double dir, double mag) +: dir(dir), mag(mag) +{ + +} + +/** + * Construct a vector object from a cartesian point. + * + * @param p point_t.x , point_t.y + */ +Vector2D::Vector2D(point_t &p) +{ + this->dir = atan2(p.y, p.x); + this->mag = sqrt( (p.x*p.x) + (p.y*p.y) ); +} + +/** + * Get the direction of the vector, in radians. + * '0' is forward, clockwise positive when viewed from the top. + * + * Use r2d() to convert. + */ +double Vector2D::get_dir() const { return dir;} + +/** + * Get the magnitude of the vector + */ +double Vector2D::get_mag() const { return mag; } + +/** + * Get the X component of the vector; positive to the right. + */ +double Vector2D::get_x() const +{ +return mag * cos(dir); +} + +/** + * Get the Y component of the vector, positive forward. + */ +double Vector2D::get_y() const +{ +return mag * sin(dir); +} + +/** + * Changes the magnetude of the vector to 1 +*/ +Vector2D Vector2D::normalize() +{ + return Vector2D(this->dir, 1); +} + +/** + * Returns a point from the vector +*/ +Vector2D::point_t Vector2D::point() +{ + point_t p = + { + .x = this->mag * cos(this->dir), + .y = this->mag * sin(this->dir) + }; + return p; +} + +/** + * Correctly add vectors together with the + operator + */ +Vector2D Vector2D::operator+(const Vector2D &other) +{ + point_t p = + { + .x = this->get_x() + other.get_x(), + .y = this->get_y() + other.get_y() + }; + + return Vector2D( p ); +} + +/** + * Correctly subtract vectors with the - operator + */ +Vector2D Vector2D::operator-(const Vector2D &other) +{ + point_t p = + { + .x = this->get_x() - other.get_x(), + .y = this->get_y() - other.get_y() + }; + return Vector2D( p ); +} + +/** + * Multiplies a vector by a double with the * operator +*/ +Vector2D Vector2D::operator*(const double &x) +{ + return Vector2D(this->dir, this->mag * x); +} + +/** + * General function for converting degrees to radians + */ +double deg2rad(double deg) +{ + return deg * (PI / 180.0); +} + +/** + * General function for converting radians to degrees + */ +double rad2deg(double rad) +{ + return rad * (180.0 / PI); +} From 290a8b785a9f33c0b4c30cf88d6146f8aa8595a4 Mon Sep 17 00:00:00 2001 From: Dana Date: Thu, 22 Sep 2022 22:04:34 -0400 Subject: [PATCH 103/243] ACS moved from 2021-2022-BIG --- .../utils/command_structure/auto_command.h | 19 ++++++++ .../command_structure/command_controller.h | 41 ++++++++++++++++ .../utils/command_structure/delay_command.h | 34 ++++++++++++++ .../command_structure/drive_forward_command.h | 24 ++++++++++ .../command_structure/command_controller.cpp | 47 +++++++++++++++++++ .../drive_forward_command.cpp | 19 ++++++++ 6 files changed, 184 insertions(+) create mode 100644 include/utils/command_structure/auto_command.h create mode 100644 include/utils/command_structure/command_controller.h create mode 100644 include/utils/command_structure/delay_command.h create mode 100644 include/utils/command_structure/drive_forward_command.h create mode 100644 src/utils/command_structure/command_controller.cpp create mode 100644 src/utils/command_structure/drive_forward_command.cpp diff --git a/include/utils/command_structure/auto_command.h b/include/utils/command_structure/auto_command.h new file mode 100644 index 0000000..baa24e3 --- /dev/null +++ b/include/utils/command_structure/auto_command.h @@ -0,0 +1,19 @@ +/** + * File: auto_command.h + * Desc: + * Interface for module-specifc commands + */ + +#pragma once + +#include "vex.h" + +class AutoCommand { + public: + /** + * Executes the command + * Overridden by child classes + * @returns true when the command is finished, false otherwise + */ + virtual bool run(); +}; \ No newline at end of file diff --git a/include/utils/command_structure/command_controller.h b/include/utils/command_structure/command_controller.h new file mode 100644 index 0000000..6148897 --- /dev/null +++ b/include/utils/command_structure/command_controller.h @@ -0,0 +1,41 @@ +/** + * File: command_controller.h + * Desc: + * Handles autonomous command execution + * Acts like a queue (because it is one) + * Execute and remove command at the head of the queue, + * repeat until there are no more commmands in the queue + */ + +#pragma once + +#include +#include "../core/include/utils/command_structure/auto_command.h" + +class CommandController { + public: + + /** + * Adds a command to the queue + * @param cmd - AutoCommand to be added + */ + void add(AutoCommand cmd); + + /** + * Adds a command that will delay progression + * of the queue + * @param ms - number of milliseconds to wait + * before continuing execution of autonomous + */ + void add_delay(int ms); + + /** + * Begin execution of the queue + * Execute and remove command at the head of the queue, + * repeat until there are no more commmands in the queue + */ + void run(); + + private: + std::queue command_queue; +}; \ No newline at end of file diff --git a/include/utils/command_structure/delay_command.h b/include/utils/command_structure/delay_command.h new file mode 100644 index 0000000..32009af --- /dev/null +++ b/include/utils/command_structure/delay_command.h @@ -0,0 +1,34 @@ +/** + * File: delay_command.h + * Desc: + * [insert meaningful desc] + */ + +#pragma once + +#include "../core/include/utils/command_structure/auto_command.h" + +class DelayCommand: public AutoCommand { + public: + + /** + * Constructor + */ + DelayCommand(int _ms) { + ms = _ms; + } + + /** + * Delays for the amount of milliseconds stored in the command + * Overrides run from AutoCommand + * @returns true when complete + */ + bool run() override { + vexDelay(ms); + return true; + } + + private: + // amount of milliseconds to wait + int ms; +}; \ No newline at end of file diff --git a/include/utils/command_structure/drive_forward_command.h b/include/utils/command_structure/drive_forward_command.h new file mode 100644 index 0000000..5a5a1a4 --- /dev/null +++ b/include/utils/command_structure/drive_forward_command.h @@ -0,0 +1,24 @@ +/** + * File: drive_forward_command.h + * Desc: + * Command wrapper class for the drive_forward function in the TankDrive class + */ + +#pragma once + +#include "vex.h" +#include "../core/include/utils/command_structure/auto_command.h" + +using namespace vex; + +class DriveForwardCommand: public AutoCommand { + public: + DriveForwardCommand(double inches, double speed, double correction, directionType dir); + bool run(); + + private: + double inches; + double speed; + double correction; + directionType dir; +}; \ No newline at end of file diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp new file mode 100644 index 0000000..4d2c759 --- /dev/null +++ b/src/utils/command_structure/command_controller.cpp @@ -0,0 +1,47 @@ +/** + * File: command_controller.cpp + * Desc: + * Handles autonomous command execution + * Acts like a queue (because it is one) + * Execute and remove command at the head of the queue, + * repeat until there are no more commmands in the queue + */ + +#include "../core/include/utils/command_structure/command_controller.h" +#include "../core/include/utils/command_structure/delay_command.h" + +/** + * Adds a command to the queue + * @param cmd - AutoCommand to be added + */ +void CommandController::add(AutoCommand cmd) { + command_queue.push(cmd); +} + +/** + * Adds a command that will delay progression + * of the queue + * @param ms - number of milliseconds to wait + * before continuing execution of autonomous + */ +void CommandController::add_delay(int ms) { + AutoCommand delay = DelayCommand(ms); + command_queue.push(delay); +} + +/** + * Begin execution of the queue + * Execute and remove command at the head of the queue, + * repeat until there are no more commmands in the queue + */ +void CommandController::run() { + AutoCommand next_cmd; + while(!command_queue.empty()) { + // retrieve and remove command at the front of the queue + next_cmd = command_queue.front(); + command_queue.pop(); + + // run the current command + next_cmd.run(); + } +} \ No newline at end of file diff --git a/src/utils/command_structure/drive_forward_command.cpp b/src/utils/command_structure/drive_forward_command.cpp new file mode 100644 index 0000000..48e087e --- /dev/null +++ b/src/utils/command_structure/drive_forward_command.cpp @@ -0,0 +1,19 @@ +/** + * File: drive_forward_command.cpp + * Desc: + * Command wrapper class for the drive_forward function in the TankDrive class + */ + +#include "vex.h" +#include "../core/include/utils/command_structure/drive_forward_command.h" + +using namespace vex; + +DriveForwardCommand::DriveForwardCommand(double inches, double speed, double correction, directionType dir): + inches(inches), speed(speed), correction(correction), dir(dir) {} + +bool DriveForwardCommand::run() { + // while(!){statements + // } + return true; +} \ No newline at end of file From 3ea3fc44d14c4d84575e1cbb93650df1c191a6cc Mon Sep 17 00:00:00 2001 From: Dana Date: Thu, 13 Oct 2022 19:00:20 -0400 Subject: [PATCH 104/243] build fixes --- .../utils/command_structure/auto_command.h | 2 +- .../command_structure/drive_forward_command.h | 6 +++-- .../command_structure/turn_degrees_command.h | 24 +++++++++++++++++++ src/subsystems/odometry/odometry_tank.cpp | 4 ++-- .../drive_forward_command.cpp | 10 ++++---- .../turn_degrees_command.cpp | 17 +++++++++++++ 6 files changed, 53 insertions(+), 10 deletions(-) create mode 100644 include/utils/command_structure/turn_degrees_command.h create mode 100644 src/utils/command_structure/turn_degrees_command.cpp diff --git a/include/utils/command_structure/auto_command.h b/include/utils/command_structure/auto_command.h index baa24e3..8795a68 100644 --- a/include/utils/command_structure/auto_command.h +++ b/include/utils/command_structure/auto_command.h @@ -15,5 +15,5 @@ class AutoCommand { * Overridden by child classes * @returns true when the command is finished, false otherwise */ - virtual bool run(); + virtual bool run() { return true; } }; \ No newline at end of file diff --git a/include/utils/command_structure/drive_forward_command.h b/include/utils/command_structure/drive_forward_command.h index 5a5a1a4..424d84f 100644 --- a/include/utils/command_structure/drive_forward_command.h +++ b/include/utils/command_structure/drive_forward_command.h @@ -8,15 +8,17 @@ #include "vex.h" #include "../core/include/utils/command_structure/auto_command.h" +#include "../core/include/subsystems/tank_drive.h" using namespace vex; class DriveForwardCommand: public AutoCommand { public: - DriveForwardCommand(double inches, double speed, double correction, directionType dir); - bool run(); + DriveForwardCommand(TankDrive &drive_sys, double inches, double speed, double correction, directionType dir); + bool run() override; private: + TankDrive &drive_sys; double inches; double speed; double correction; diff --git a/include/utils/command_structure/turn_degrees_command.h b/include/utils/command_structure/turn_degrees_command.h new file mode 100644 index 0000000..a56aab6 --- /dev/null +++ b/include/utils/command_structure/turn_degrees_command.h @@ -0,0 +1,24 @@ +/** + * File: turn_degrees_command.h + * Desc: + * Command wrapper class for the turn_degrees function in the TankDrive class + */ + +#pragma once + +#include "vex.h" +#include "../core/include/utils/command_structure/auto_command.h" +#include "../core/include/subsystems/tank_drive.h" + +using namespace vex; + +class TurnDegreesCommand: public AutoCommand { + public: + TurnDegreesCommand(TankDrive &drive_sys, double degrees, double percent_speed); + bool run() override; + + private: + TankDrive &drive_sys; + double degrees; + double percent_speed; +}; \ No newline at end of file diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index c801c2f..1d0c9dc 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -92,12 +92,12 @@ position_t OdometryTank::update() // Get the arclength of the turning circle of the robot double distance_diff = (rside_revs - lside_revs) * PI * config.odom_wheel_diam; - printf("dist_diff: %f, ", distance_diff); + //printf("dist_diff: %f, ", distance_diff); //Use the arclength formula to calculate the angle. Add 90 to make "0 degrees" to starboard angle = ((180.0 / PI) * (distance_diff / config.dist_between_wheels)) + 90; - printf("angle: %f, ", (180.0 / PI) * (distance_diff / config.dist_between_wheels)); + //printf("angle: %f, ", (180.0 / PI) * (distance_diff / config.dist_between_wheels)); } else { diff --git a/src/utils/command_structure/drive_forward_command.cpp b/src/utils/command_structure/drive_forward_command.cpp index 48e087e..e9630fe 100644 --- a/src/utils/command_structure/drive_forward_command.cpp +++ b/src/utils/command_structure/drive_forward_command.cpp @@ -6,14 +6,14 @@ #include "vex.h" #include "../core/include/utils/command_structure/drive_forward_command.h" +#include using namespace vex; -DriveForwardCommand::DriveForwardCommand(double inches, double speed, double correction, directionType dir): - inches(inches), speed(speed), correction(correction), dir(dir) {} +DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, double inches, double speed, double correction, directionType dir): + drive_sys(drive_sys), inches(inches), speed(speed), correction(correction), dir(dir) {} bool DriveForwardCommand::run() { - // while(!){statements - // } - return true; + std::cout << "DRIVE FORWARD COMMAND RUNNING\n"; + return drive_sys.drive_forward(inches, speed, correction, dir); } \ No newline at end of file diff --git a/src/utils/command_structure/turn_degrees_command.cpp b/src/utils/command_structure/turn_degrees_command.cpp new file mode 100644 index 0000000..a4bd2b1 --- /dev/null +++ b/src/utils/command_structure/turn_degrees_command.cpp @@ -0,0 +1,17 @@ +/** + * File: turn_degrees_command.cpp + * Desc: + * Command wrapper class for the turn_degrees function in the TankDrive class + */ + +#include "vex.h" +#include "../core/include/utils/command_structure/turn_degrees_command.h" + +using namespace vex; + +TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, double degrees, double percent_speed): + drive_sys(drive_sys), degrees(degrees), percent_speed(percent_speed) {} + +bool TurnDegreesCommand::run() { + return drive_sys.turn_degrees(degrees, percent_speed); +} \ No newline at end of file From 782e06e59d44bdddec002d11745e88149e39078e Mon Sep 17 00:00:00 2001 From: Dana Date: Thu, 13 Oct 2022 21:02:56 -0400 Subject: [PATCH 105/243] commands can run --- .../utils/command_structure/command_controller.h | 4 ++-- src/utils/command_structure/command_controller.cpp | 13 ++++++++----- .../command_structure/drive_forward_command.cpp | 1 - 3 files changed, 10 insertions(+), 8 deletions(-) diff --git a/include/utils/command_structure/command_controller.h b/include/utils/command_structure/command_controller.h index 6148897..3826d11 100644 --- a/include/utils/command_structure/command_controller.h +++ b/include/utils/command_structure/command_controller.h @@ -19,7 +19,7 @@ class CommandController { * Adds a command to the queue * @param cmd - AutoCommand to be added */ - void add(AutoCommand cmd); + void add(AutoCommand *cmd); /** * Adds a command that will delay progression @@ -37,5 +37,5 @@ class CommandController { void run(); private: - std::queue command_queue; + std::queue command_queue; }; \ No newline at end of file diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index 4d2c759..cf019f1 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -14,7 +14,7 @@ * Adds a command to the queue * @param cmd - AutoCommand to be added */ -void CommandController::add(AutoCommand cmd) { +void CommandController::add(AutoCommand *cmd) { command_queue.push(cmd); } @@ -25,7 +25,7 @@ void CommandController::add(AutoCommand cmd) { * before continuing execution of autonomous */ void CommandController::add_delay(int ms) { - AutoCommand delay = DelayCommand(ms); + AutoCommand *delay = new DelayCommand(ms); command_queue.push(delay); } @@ -35,13 +35,16 @@ void CommandController::add_delay(int ms) { * repeat until there are no more commmands in the queue */ void CommandController::run() { - AutoCommand next_cmd; + AutoCommand *next_cmd; while(!command_queue.empty()) { // retrieve and remove command at the front of the queue next_cmd = command_queue.front(); command_queue.pop(); - // run the current command - next_cmd.run(); + // run the current command until it returns true + while(!next_cmd -> run()) { + vexDelay(20); + } + } } \ No newline at end of file diff --git a/src/utils/command_structure/drive_forward_command.cpp b/src/utils/command_structure/drive_forward_command.cpp index e9630fe..3fe2200 100644 --- a/src/utils/command_structure/drive_forward_command.cpp +++ b/src/utils/command_structure/drive_forward_command.cpp @@ -14,6 +14,5 @@ DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, double inches, do drive_sys(drive_sys), inches(inches), speed(speed), correction(correction), dir(dir) {} bool DriveForwardCommand::run() { - std::cout << "DRIVE FORWARD COMMAND RUNNING\n"; return drive_sys.drive_forward(inches, speed, correction, dir); } \ No newline at end of file From 46c321dea3e7210f32ffbc158976395f14694438 Mon Sep 17 00:00:00 2001 From: Dana Date: Sun, 16 Oct 2022 15:11:35 -0400 Subject: [PATCH 106/243] fixed up docs --- include/utils/command_structure/command_controller.h | 11 +++++------ include/utils/command_structure/delay_command.h | 10 +++------- .../utils/command_structure/drive_forward_command.h | 12 +++++++++++- .../utils/command_structure/turn_degrees_command.h | 12 +++++++++++- src/utils/command_structure/command_controller.cpp | 11 +++++------ .../command_structure/drive_forward_command.cpp | 8 +++++++- src/utils/command_structure/turn_degrees_command.cpp | 8 +++++++- 7 files changed, 49 insertions(+), 23 deletions(-) diff --git a/include/utils/command_structure/command_controller.h b/include/utils/command_structure/command_controller.h index 3826d11..f4a8abe 100644 --- a/include/utils/command_structure/command_controller.h +++ b/include/utils/command_structure/command_controller.h @@ -1,10 +1,10 @@ /** * File: command_controller.h * Desc: - * Handles autonomous command execution - * Acts like a queue (because it is one) - * Execute and remove command at the head of the queue, - * repeat until there are no more commmands in the queue + * A CommandController manages the AutoCommands that make + * up an autonomous route. The AutoCommands are kept in + * a queue and get executed and removed from the queue + * in FIFO order. */ #pragma once @@ -31,8 +31,7 @@ class CommandController { /** * Begin execution of the queue - * Execute and remove command at the head of the queue, - * repeat until there are no more commmands in the queue + * Execute and remove commands in FIFO order */ void run(); diff --git a/include/utils/command_structure/delay_command.h b/include/utils/command_structure/delay_command.h index 32009af..bdf1af1 100644 --- a/include/utils/command_structure/delay_command.h +++ b/include/utils/command_structure/delay_command.h @@ -1,7 +1,8 @@ /** * File: delay_command.h * Desc: - * [insert meaningful desc] + * A DelayCommand will make the robot wait the set amount of + * milliseconds before continuing execution of the autonomous route */ #pragma once @@ -11,12 +12,7 @@ class DelayCommand: public AutoCommand { public: - /** - * Constructor - */ - DelayCommand(int _ms) { - ms = _ms; - } + DelayCommand(int ms): ms(ms) {} /** * Delays for the amount of milliseconds stored in the command diff --git a/include/utils/command_structure/drive_forward_command.h b/include/utils/command_structure/drive_forward_command.h index 424d84f..5980e85 100644 --- a/include/utils/command_structure/drive_forward_command.h +++ b/include/utils/command_structure/drive_forward_command.h @@ -1,7 +1,8 @@ /** * File: drive_forward_command.h * Desc: - * Command wrapper class for the drive_forward function in the TankDrive class + * AutoCommand wrapper class for the drive_forward function in the + * TankDrive class */ #pragma once @@ -15,10 +16,19 @@ using namespace vex; class DriveForwardCommand: public AutoCommand { public: DriveForwardCommand(TankDrive &drive_sys, double inches, double speed, double correction, directionType dir); + + /** + * Run drive_forward + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ bool run() override; private: + // drive system to run the function on TankDrive &drive_sys; + + // parameters for drive_forward double inches; double speed; double correction; diff --git a/include/utils/command_structure/turn_degrees_command.h b/include/utils/command_structure/turn_degrees_command.h index a56aab6..15215a4 100644 --- a/include/utils/command_structure/turn_degrees_command.h +++ b/include/utils/command_structure/turn_degrees_command.h @@ -1,7 +1,8 @@ /** * File: turn_degrees_command.h * Desc: - * Command wrapper class for the turn_degrees function in the TankDrive class + * AutoCommand wrapper class for the turn_degrees function in the + * TankDrive class */ #pragma once @@ -15,10 +16,19 @@ using namespace vex; class TurnDegreesCommand: public AutoCommand { public: TurnDegreesCommand(TankDrive &drive_sys, double degrees, double percent_speed); + + /** + * Run turn_degrees + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ bool run() override; private: + // drive system to run the function on TankDrive &drive_sys; + + // parameters for turn_degrees double degrees; double percent_speed; }; \ No newline at end of file diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index cf019f1..fb629c2 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -1,10 +1,10 @@ /** * File: command_controller.cpp * Desc: - * Handles autonomous command execution - * Acts like a queue (because it is one) - * Execute and remove command at the head of the queue, - * repeat until there are no more commmands in the queue + * A CommandController manages the AutoCommands that make + * up an autonomous route. The AutoCommands are kept in + * a queue and get executed and removed from the queue + * in FIFO order. */ #include "../core/include/utils/command_structure/command_controller.h" @@ -31,8 +31,7 @@ void CommandController::add_delay(int ms) { /** * Begin execution of the queue - * Execute and remove command at the head of the queue, - * repeat until there are no more commmands in the queue + * Execute and remove commands in FIFO order */ void CommandController::run() { AutoCommand *next_cmd; diff --git a/src/utils/command_structure/drive_forward_command.cpp b/src/utils/command_structure/drive_forward_command.cpp index 3fe2200..e8b4129 100644 --- a/src/utils/command_structure/drive_forward_command.cpp +++ b/src/utils/command_structure/drive_forward_command.cpp @@ -1,7 +1,8 @@ /** * File: drive_forward_command.cpp * Desc: - * Command wrapper class for the drive_forward function in the TankDrive class + * AutoCommand wrapper class for the drive_forward function in the + * TankDrive class */ #include "vex.h" @@ -13,6 +14,11 @@ using namespace vex; DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, double inches, double speed, double correction, directionType dir): drive_sys(drive_sys), inches(inches), speed(speed), correction(correction), dir(dir) {} +/** + * Run drive_forward + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ bool DriveForwardCommand::run() { return drive_sys.drive_forward(inches, speed, correction, dir); } \ No newline at end of file diff --git a/src/utils/command_structure/turn_degrees_command.cpp b/src/utils/command_structure/turn_degrees_command.cpp index a4bd2b1..5cb58de 100644 --- a/src/utils/command_structure/turn_degrees_command.cpp +++ b/src/utils/command_structure/turn_degrees_command.cpp @@ -1,7 +1,8 @@ /** * File: turn_degrees_command.cpp * Desc: - * Command wrapper class for the turn_degrees function in the TankDrive class + * AutoCommand wrapper class for the turn_degrees function in the + * TankDrive class */ #include "vex.h" @@ -12,6 +13,11 @@ using namespace vex; TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, double degrees, double percent_speed): drive_sys(drive_sys), degrees(degrees), percent_speed(percent_speed) {} +/** + * Run turn_degrees + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ bool TurnDegreesCommand::run() { return drive_sys.turn_degrees(degrees, percent_speed); } \ No newline at end of file From 49533eeba48403661bca3ccc99573584ad1cd53f Mon Sep 17 00:00:00 2001 From: Dana Date: Sun, 16 Oct 2022 15:23:03 -0400 Subject: [PATCH 107/243] combined drive_forward and turn_degrees command classes into one file --- .../utils/command_structure/drive_commands.h | 67 +++++++++++++++++++ .../command_structure/drive_forward_command.h | 36 ---------- .../command_structure/turn_degrees_command.h | 34 ---------- .../command_structure/drive_commands.cpp | 41 ++++++++++++ .../drive_forward_command.cpp | 24 ------- .../turn_degrees_command.cpp | 23 ------- 6 files changed, 108 insertions(+), 117 deletions(-) create mode 100644 include/utils/command_structure/drive_commands.h delete mode 100644 include/utils/command_structure/drive_forward_command.h delete mode 100644 include/utils/command_structure/turn_degrees_command.h create mode 100644 src/utils/command_structure/drive_commands.cpp delete mode 100644 src/utils/command_structure/drive_forward_command.cpp delete mode 100644 src/utils/command_structure/turn_degrees_command.cpp diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h new file mode 100644 index 0000000..52ec404 --- /dev/null +++ b/include/utils/command_structure/drive_commands.h @@ -0,0 +1,67 @@ +/** + * File: drive_commands.h + * Desc: + * Holds all the AutoCommand subclasses that wrap TankDrive functions + * + * Currently includes: + * - drive_forward + * - turn_degrees + */ + +#pragma once + +#include "vex.h" +#include "../core/include/utils/command_structure/auto_command.h" +#include "../core/include/subsystems/tank_drive.h" + +using namespace vex; + +/** + * AutoCommand wrapper class for the drive_forward function in the + * TankDrive class + */ +class DriveForwardCommand: public AutoCommand { + public: + DriveForwardCommand(TankDrive &drive_sys, double inches, double speed, double correction, directionType dir); + + /** + * Run drive_forward + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + + private: + // drive system to run the function on + TankDrive &drive_sys; + + // parameters for drive_forward + double inches; + double speed; + double correction; + directionType dir; +}; + +/** + * AutoCommand wrapper class for the turn_degrees function in the + * TankDrive class + */ +class TurnDegreesCommand: public AutoCommand { + public: + TurnDegreesCommand(TankDrive &drive_sys, double degrees, double percent_speed); + + /** + * Run turn_degrees + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + + private: + // drive system to run the function on + TankDrive &drive_sys; + + // parameters for turn_degrees + double degrees; + double percent_speed; +}; \ No newline at end of file diff --git a/include/utils/command_structure/drive_forward_command.h b/include/utils/command_structure/drive_forward_command.h deleted file mode 100644 index 5980e85..0000000 --- a/include/utils/command_structure/drive_forward_command.h +++ /dev/null @@ -1,36 +0,0 @@ -/** - * File: drive_forward_command.h - * Desc: - * AutoCommand wrapper class for the drive_forward function in the - * TankDrive class - */ - -#pragma once - -#include "vex.h" -#include "../core/include/utils/command_structure/auto_command.h" -#include "../core/include/subsystems/tank_drive.h" - -using namespace vex; - -class DriveForwardCommand: public AutoCommand { - public: - DriveForwardCommand(TankDrive &drive_sys, double inches, double speed, double correction, directionType dir); - - /** - * Run drive_forward - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // drive system to run the function on - TankDrive &drive_sys; - - // parameters for drive_forward - double inches; - double speed; - double correction; - directionType dir; -}; \ No newline at end of file diff --git a/include/utils/command_structure/turn_degrees_command.h b/include/utils/command_structure/turn_degrees_command.h deleted file mode 100644 index 15215a4..0000000 --- a/include/utils/command_structure/turn_degrees_command.h +++ /dev/null @@ -1,34 +0,0 @@ -/** - * File: turn_degrees_command.h - * Desc: - * AutoCommand wrapper class for the turn_degrees function in the - * TankDrive class - */ - -#pragma once - -#include "vex.h" -#include "../core/include/utils/command_structure/auto_command.h" -#include "../core/include/subsystems/tank_drive.h" - -using namespace vex; - -class TurnDegreesCommand: public AutoCommand { - public: - TurnDegreesCommand(TankDrive &drive_sys, double degrees, double percent_speed); - - /** - * Run turn_degrees - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // drive system to run the function on - TankDrive &drive_sys; - - // parameters for turn_degrees - double degrees; - double percent_speed; -}; \ No newline at end of file diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp new file mode 100644 index 0000000..597f586 --- /dev/null +++ b/src/utils/command_structure/drive_commands.cpp @@ -0,0 +1,41 @@ +/** + * File: drive_commands.h + * Desc: + * Holds all the AutoCommand subclasses that wrap TankDrive functions + * + * Currently includes: + * - drive_forward + * - turn_degrees + */ + +#include "../core/include/utils/command_structure/drive_commands.h" + + +// ==== DRIVE FORWARD ==== + +DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, double inches, double speed, double correction, directionType dir): + drive_sys(drive_sys), inches(inches), speed(speed), correction(correction), dir(dir) {} + +/** + * Run drive_forward + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ +bool DriveForwardCommand::run() { + return drive_sys.drive_forward(inches, speed, correction, dir); +} + + +// ==== TURN DEGREES ==== + +TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, double degrees, double percent_speed): + drive_sys(drive_sys), degrees(degrees), percent_speed(percent_speed) {} + +/** + * Run turn_degrees + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ +bool TurnDegreesCommand::run() { + return drive_sys.turn_degrees(degrees, percent_speed); +} diff --git a/src/utils/command_structure/drive_forward_command.cpp b/src/utils/command_structure/drive_forward_command.cpp deleted file mode 100644 index e8b4129..0000000 --- a/src/utils/command_structure/drive_forward_command.cpp +++ /dev/null @@ -1,24 +0,0 @@ -/** - * File: drive_forward_command.cpp - * Desc: - * AutoCommand wrapper class for the drive_forward function in the - * TankDrive class - */ - -#include "vex.h" -#include "../core/include/utils/command_structure/drive_forward_command.h" -#include - -using namespace vex; - -DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, double inches, double speed, double correction, directionType dir): - drive_sys(drive_sys), inches(inches), speed(speed), correction(correction), dir(dir) {} - -/** - * Run drive_forward - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ -bool DriveForwardCommand::run() { - return drive_sys.drive_forward(inches, speed, correction, dir); -} \ No newline at end of file diff --git a/src/utils/command_structure/turn_degrees_command.cpp b/src/utils/command_structure/turn_degrees_command.cpp deleted file mode 100644 index 5cb58de..0000000 --- a/src/utils/command_structure/turn_degrees_command.cpp +++ /dev/null @@ -1,23 +0,0 @@ -/** - * File: turn_degrees_command.cpp - * Desc: - * AutoCommand wrapper class for the turn_degrees function in the - * TankDrive class - */ - -#include "vex.h" -#include "../core/include/utils/command_structure/turn_degrees_command.h" - -using namespace vex; - -TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, double degrees, double percent_speed): - drive_sys(drive_sys), degrees(degrees), percent_speed(percent_speed) {} - -/** - * Run turn_degrees - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ -bool TurnDegreesCommand::run() { - return drive_sys.turn_degrees(degrees, percent_speed); -} \ No newline at end of file From 3dc4a5c9dafab518fc54752d9135297a5ac827f4 Mon Sep 17 00:00:00 2001 From: Dana Date: Sun, 16 Oct 2022 15:42:48 -0400 Subject: [PATCH 108/243] Merge remote-tracking branch 'origin/main' into auto_structure --- include/subsystems/flywheel.h | 169 ++++++++++++++++++++ src/subsystems/flywheel.cpp | 289 ++++++++++++++++++++++++++++++++++ 2 files changed, 458 insertions(+) create mode 100644 include/subsystems/flywheel.h create mode 100644 src/subsystems/flywheel.cpp diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h new file mode 100644 index 0000000..81a1e17 --- /dev/null +++ b/include/subsystems/flywheel.h @@ -0,0 +1,169 @@ +/********************************************************* +* +* File: Flywheel.h +* Purpose: Generalized flywheel class for Core. +* Author: Chris Nokes +* +********************************************************** +* EDIT HISTORY +********************************************************** +* 09/23/2022 Reorganized, added documentation. +* 09/23/2022 Added functions elaborated on in .cpp. +*********************************************************/ + +#include "../core/include/utils/feedforward.h" +#include "vex.h" +#include "../core/include/robot_specs.h" +#include "../core/include/utils/pid.h" +#include + +using namespace vex; + +class Flywheel{ + enum FlywheelControlStyle{ + PID_Feedforward, + Feedforward, + Take_Back_Half, + Bang_Bang, + }; + public: + + // CONSTRUCTORS, GETTERS, AND SETTERS + /** + * Create the Flywheel object using PID + feedforward for control. + * @param motors - pointer to the motors on the fly wheel + * @param pid_config - pointer the pid config + * @param ff - pointer to the feedforward config + * @param ratio - ratio of the whatever just multiplies the velocity + */ + Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio); + + /** + * Create the Flywheel object using only feedforward for control + * @param motors - pointer to the motors on the fly wheel + * @param ff - pointer to the feedforward config + * @param ratio - ratio of the whatever just multiplies the velocity + */ + Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio); + + /** + * Create the Flywheel object using Take Back Half for control + * @param motors - pointer to the motors on the fly wheel + * @param TBH_gain - the TBH control paramater + * @param ratio - ratio of the whatever just multiplies the velocity + */ + Flywheel(motor_group &motors, double tbh_gain, const double ratio); + + /** + * Create the Flywheel object using Bang Bang for control + * @param motors - pointer to the motors on the fly wheel + * @param ratio - ratio of the whatever just multiplies the velocity + */ + Flywheel(motor_group &motors, const double ratio); + + /** + * Return the current value that the RPM should be set to + * @return RPM = the target rpm + */ + double getDesiredRPM(); + + /** + * Checks if the background RPM controlling task is running + * @return taskRunning - If the task is running + */ + bool isTaskRunning(); + + /** + * Returns a POINTER to the motors + */ + motor_group* getMotors(); + + /** + * return the current velocity of the flywheel motors, in RPM + */ + double getRPM(); + + /** + * Returns a POINTER to the PID. + */ + PID* getPID(); + + /** + * returns the current OUT value of the PID - the value that the PID would set the motors to + */ + double getPIDValue(); + + /** + * returns the current OUT value of the PID - the value that the PID would set the motors to + */ + double getFeedforwardValue(); + + /** + * get the gain used for TBH control + */ + double getTBHGain(); + + /** + * Sets the value of the PID target + * @param value - desired value of the PID + */ + void setPIDTarget(double value); + +/** +* updates the value of the PID +* @param value - value to update the PID with +*/ + void updatePID(double value); + + // SPINNERS AND STOPPERS + + /** + * Spin motors using voltage; defaults forward at 12 volts + * FOR USE BY TASKS ONLY + * @param speed - speed (between -1 and 1) to set the motor + * @param dir - direction that the motor moves in; defaults to forward + */ + void spin_raw(double speed, directionType dir=fwd); + + /** + * Spin motors using voltage; defaults forward at 12 volts + * FOR USE BY OPCONTROL AND AUTONOMOUS - this only applies if the RPM thread is not running + */ + void spin_manual(double speed, directionType dir=fwd); + + /** + * starts or sets the RPM thread at new value + * what control scheme is dependent on control_style + * @param inputRPM - set the current RPM + */ + void spinRPM(int rpm); + + /** + * stop the RPM thread and the wheel + */ + void stop(); + + + /** + * stop only the motors; exclusively for BANG BANG use + */ + void stopMotors(); + + /** + * Stop the motors if the task isn't running - stop manual control + */ + void stopNonTasks(); + + private: + + motor_group &motors; // motors that make up the flywheel + bool taskRunning = false; // is the task (thread but not) currently running? + PID pid; // PID on the flywheel + FeedForward ff; // FF constants for the flywheel + double TBH_gain; // TBH gain parameter for the flywheel + double ratio; // multiplies the velocity by this value + std::atomic RPM; // Desired RPM of the flywheel. + task rpmTask; // task (thread but not) that handles spinning the wheel at a given RPM + FlywheelControlStyle control_style; // how the flywheel should be controlled + +}; \ No newline at end of file diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp new file mode 100644 index 0000000..0f1a154 --- /dev/null +++ b/src/subsystems/flywheel.cpp @@ -0,0 +1,289 @@ +/********************************************************* +* +* File: Flywheel.cpp +* Purpose: Generalized flywheel class for Core. +* Author: Chris Nokes +* +********************************************************** +* EDIT HISTORY +********************************************************** +* 09/16/2022 Created file, added constructor, spins, RPM setting, stop. +* 09/18/2022 Added async functionality. +* 09/22/2022 Documentation improvements, fixed error if RPM is set but motor is stopped. +* 09/23/2022 Neatened up program, added getters and setters, fixed documentation and bang bang. +* 09/29/2022 Bug fixes, RPM handling. Multiplied the motor by 18. +*********************************************************/ + +#include "../core/include/subsystems/flywheel.h" +#include "../core/include/utils/feedforward.h" +#include "../core/include/utils/pid.h" +#include "../core/include/utils/math_util.h" +#include "vex.h" + +using namespace vex; + +/********************************************************* +* CONSTRUCTOR, GETTERS, SETTERS +*********************************************************/ +//used when using bang bang or TBH control +PID::pid_config_t empty_pid = PID::pid_config_t{}; +FeedForward::ff_config_t empty_ff = FeedForward::ff_config_t{}; + +/** +* Create the Flywheel object using PID + feedforward for control. +* @param motors - pointer to the motors on the fly wheel +* @param pid_config - pointer the pid config +* @param ff - pointer to the feedforward config +* @param ratio - ratio of the whatever just multiplies the velocity +*/ +Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio) + :motors(motors), pid(pid_config), ff(ff_config), ratio(ratio), control_style(PID_Feedforward) { } + +/** +* Create the Flywheel object using only feedforward for control +* @param motors - pointer to the motors on the fly wheel +* @param ff - pointer to the feedforward config +* @param ratio - ratio of the whatever just multiplies the velocity +*/ +Flywheel::Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio) + :motors(motors), pid(empty_pid), ff(ff_config), ratio(ratio), control_style(Feedforward) {} + +/** +* Create the Flywheel object using Take Back Half for control +* @param motors - pointer to the motors on the fly wheel +* @param TBH_gain - the TBH control paramater +* @param ratio - ratio of the whatever just multiplies the velocity +*/ +Flywheel::Flywheel(motor_group &motors, const double TBH_gain, const double ratio) + :motors(motors), pid(empty_pid), ff(empty_ff), TBH_gain(TBH_gain), ratio(ratio), control_style(Take_Back_Half) {} + +/** +* Create the Flywheel object using Bang Bang for control +* @param motors - pointer to the motors on the fly wheel +* @param ratio - ratio of the whatever just multiplies the velocity +*/ +Flywheel::Flywheel(motor_group &motors, const double ratio) + :motors(motors), pid(empty_pid), ff(empty_ff), ratio(ratio), control_style(Bang_Bang) {} + +/** +* Return the current value that the RPM should be set to +* @return RPM = the target rpm +*/ +double Flywheel::getDesiredRPM() { return RPM; } + +/** +* Checks if the background RPM controlling task is running +* @return taskRunning - If the task is running +*/ +bool Flywheel::isTaskRunning() { return taskRunning; } + +/** +* Returns a POINTER TO the motors; not currently used. +*/ +motor_group* Flywheel::getMotors() { return &motors; } // TODO -- Remove? + +/** +* return the current velocity of the flywheel motors, in RPM +*/ +double Flywheel::getRPM() { return ratio * motors.velocity(velocityUnits::rpm); } + +/** +* Returns a POINTER TO the PID; not currently used. +*/ +PID* Flywheel::getPID() { return &pid; } // TODO -- Remove? + +/** +* returns the current OUT value of the PID - the value that the PID would set the motors to +*/ +double Flywheel::getPIDValue() { return pid.get(); } + +/** +* returns the current OUT value of the Feedforward - the value that the Feedforward would set the motors to +*/ +double Flywheel::getFeedforwardValue() { + double v = getDesiredRPM(); + return ff.calculate(v, 0); +} + +/** +* get the gain used for TBH control +*/ +double Flywheel::getTBHGain(){ + return TBH_gain; +} + +/** +* Sets the value of the PID target +* @param value - desired value of the PID +*/ +void Flywheel::setPIDTarget(double value) { pid.set_target(value); } + +/** +* updates the value of the PID +* @param value - value to update the PID with +*/ +void Flywheel::updatePID(double value) { pid.update(value); } + +/********************************************************* +* RPM SETTING THREADS +* ALL OF THE FOLLOWING PROGRAMS HAVE THE SAME PARAMETERS AND RESULTS: +* spin this flywheel at a given RPM, async; runs until stop(), stopThread(), or a new spinRPM() is called. +* @param wheelPointer - points to the current wheel object +*********************************************************/ + +/** +* Runs a Feedforward variant to control rpm +*/ +int spinRPMTask_BangBang(void* wheelPointer) { + Flywheel* wheel = (Flywheel*) wheelPointer; + while(true) { + // if it below the RPM, go, otherwise don't + if(wheel->getRPM() < wheel->getDesiredRPM()) { + wheel->spin_raw(1, fwd); + } + else { wheel->stopMotors(); } + vexDelay(1); + } + return 0; +} + +/** +* Runs a Feedforward variant to control rpm +*/ +int spinRPMTask_Feedforward(void* wheelPointer) { + Flywheel* wheel = (Flywheel*) wheelPointer; + // get the pid from the wheel and set its target to the RPM stored in the wheel. + while(true) { + wheel->updatePID(wheel->getRPM()); // check the current velocity and update the PID with it. + double output = wheel->getFeedforwardValue(); + wheel->spin_raw(output, fwd); // set the motors to whatever feedforward tells them to do + vexDelay(1); + } + return 0; +} +/** +* Runs a PID + Feedforward variant to control rpm +*/ +int spinRPMTask_PID_Feedforward(void* wheelPointer) { + Flywheel* wheel = (Flywheel*) wheelPointer; + // get the pid from the wheel and set its target to the RPM stored in the wheel. + while(true) { + wheel->updatePID(wheel->getRPM()); // check the current velocity and update the PID with it. + double output = wheel->getPIDValue() + wheel->getFeedforwardValue(); + wheel->spin_raw(output, fwd); // set the motors to whatever PID tells them to do + vexDelay(1); + } + return 0; +} + +/** +* Runs a Take Back Half variant to control RPM +* https://www.vexwiki.org/programming/controls_algorithms/tbh +*/ +int spinRPMTask_TBH(void* wheelPointer) { + Flywheel* wheel = (Flywheel*) wheelPointer; + + double tbh = 0.0; + double output = 0.0; + double previous_error = 0.0; + + while (true){ + //reset if set to 0, this keeps the tbh val from screwing us up when we start up again + if (wheel->getDesiredRPM()==0){ + output = 0; + tbh = 0; + } + + double error = wheel->getDesiredRPM() - wheel->getRPM(); + output += wheel->getTBHGain() * error; + wheel->spin_raw(clamp(output, 0, 1), fwd); + + if (sign(error)!=sign(previous_error)){ + output = .5 * (output + tbh); + tbh = output; + previous_error = error; + } + + vexDelay(1); + } + + return 0; +} + +// Runs a 'Moving average filter with above closed loop systems' variant, whatever that means; FUNCTION STUB +int spinRPMTask_ClosedLoop(void* wheelPointer) { return 0; } + +/********************************************************* +* SPINNERS AND STOPPERS +*********************************************************/ + +/** +* Spin motors using voltage; defaults forward at 12 volts +* FOR USE BY TASKS ONLY +* @param speed - speed (between -1 and 1) to set the motor +* @param dir - direction that the motor moves in; defaults to forward +*/ +void Flywheel::spin_raw(double speed, directionType dir){ + motors.spin(dir, speed * 12, voltageUnits::volt); +} + +/** +* Spin motors using voltage; defaults forward at 12 volts +* FOR USE BY OPCONTROL AND AUTONOMOUS - this only applies if the RPM thread is not running +*/ +void Flywheel::spin_manual(double speed, directionType dir){ + if(!taskRunning) motors.spin(dir, speed * 12, voltageUnits::volt); +} + +/** +* starts or sets the RPM thread at new value +* what control scheme is dependent on control_style +* @param inputRPM - set the current RPM +*/ +void Flywheel::spinRPM(int inputRPM) { + // only run if the RPM is different or it isn't already running + if(!taskRunning) { + + int (*rpm_control_task)(void *); // this just means a function that returns int and takes a void pointer as an argument aka a spinRPMTask function + // choose which version to use based on how the flywheel was constructed + switch(control_style){ + case Bang_Bang: + rpm_control_task = spinRPMTask_BangBang; + break; + case Take_Back_Half: + rpm_control_task = spinRPMTask_TBH; + break; + case Feedforward: + rpm_control_task = spinRPMTask_Feedforward; + break; + case PID_Feedforward: + rpm_control_task = spinRPMTask_PID_Feedforward; + break; + } + + + rpmTask = task(rpm_control_task, this); + taskRunning = true; + } + RPM = inputRPM; + setPIDTarget(RPM); +} + +/** +* stop the RPM thread and the wheel +*/ +void Flywheel::stop() { + rpmTask.stop(); + taskRunning = false; + motors.stop(); +} + +/** +* stop only the motors; exclusively for BANG BANG use +*/ +void Flywheel::stopMotors() { motors.stop(); } + +/** +* Stop the motors if the task isn't running - stop manual control +*/ +void Flywheel::stopNonTasks() { if(!taskRunning) { motors.stop(); }} \ No newline at end of file From 603802efa01069b0dbdde175ff38d006ac4f771c Mon Sep 17 00:00:00 2001 From: Dana Date: Thu, 20 Oct 2022 21:29:30 -0400 Subject: [PATCH 109/243] added more drive functions --- .../utils/command_structure/drive_commands.h | 66 ++++++++++++++++++- .../command_structure/drive_commands.cpp | 51 +++++++++++++- 2 files changed, 115 insertions(+), 2 deletions(-) diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index 52ec404..dd6df45 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -64,4 +64,68 @@ class TurnDegreesCommand: public AutoCommand { // parameters for turn_degrees double degrees; double percent_speed; -}; \ No newline at end of file +}; + +/** + * AutoCommand wrapper class for the drive_to_point function in the + * TankDrive class + */ +class DriveToPointCommand: public AutoCommand { + public: + DriveToPointCommand(TankDrive &drive_sys, double x, double y, double speed, double correction_speed, directionType dir=directionType::fwd); + + /** + * Run drive_to_point + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + + private: + // drive system to run the function on + TankDrive &drive_sys; + + // parameters for drive_to_point + double x; + double y; + double speed; + double correction_speed; + directionType dir; +}; + + +class TurnToHeadingCommand: public AutoCommand { + public: + TurnToHeadingCommand(TankDrive &drive_sys, double heading_deg, double speed); + + /** + * Run turn_to_heading + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + + private: + // drive system to run the function on + TankDrive &drive_sys; + + // parameters for turn_to_heading + double heading_deg; + double speed; +}; + +class DriveStopCommand: public AutoCommand { + public: + DriveStopCommand(TankDrive &drive_sys); + + /** + * Stop the drive system + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + + private: + // drive system to run the function on + TankDrive &drive_sys; +}; diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index 597f586..cca5244 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -1,11 +1,14 @@ /** * File: drive_commands.h * Desc: - * Holds all the AutoCommand subclasses that wrap TankDrive functions + * Holds all the AutoCommand subclasses that wrap (currently) TankDrive functions * * Currently includes: * - drive_forward * - turn_degrees + * - drive_to_point + * - turn_to_heading + * - stop */ #include "../core/include/utils/command_structure/drive_commands.h" @@ -39,3 +42,49 @@ TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, double degrees, dou bool TurnDegreesCommand::run() { return drive_sys.turn_degrees(degrees, percent_speed); } + + +// ==== DRIVE TO POINT ==== + +DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, double x, double y, double speed, double correction_speed, directionType dir): + drive_sys(drive_sys), x(x), y(y), speed(speed), correction_speed(correction_speed), dir(dir) {} + +/** + * Run drive_to_point + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ +bool DriveToPointCommand::run() { + return drive_sys.drive_to_point(x, y, speed, correction_speed); +} + + +// ==== TURN TO HEADING ==== + +TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, double heading_deg, double speed): + drive_sys(drive_sys), heading_deg(heading_deg), speed(speed) {} + +/** + * Run turn_to_heading + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ +bool TurnToHeadingCommand::run() { + return drive_sys.turn_to_heading(heading_deg, speed); +} + + +// ==== STOP ==== + +DriveStopCommand::DriveStopCommand(TankDrive &drive_sys): + drive_sys(drive_sys) {} + +/** + * Stop the drive train + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ +bool DriveStopCommand::run() { + drive_sys.stop(); + return true; +} From 294135fd71ef4a872d03352c93b663840ba880e8 Mon Sep 17 00:00:00 2001 From: Dana Date: Sun, 23 Oct 2022 14:53:02 -0400 Subject: [PATCH 110/243] odom set_position --- .../utils/command_structure/drive_commands.h | 33 ++++++++++++++++++- .../command_structure/drive_commands.cpp | 25 +++++++++++--- 2 files changed, 52 insertions(+), 6 deletions(-) diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index dd6df45..0bb5e7e 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -1,11 +1,19 @@ /** * File: drive_commands.h * Desc: - * Holds all the AutoCommand subclasses that wrap TankDrive functions + * Holds all the AutoCommand subclasses that wrap (currently) TankDrive functions * * Currently includes: * - drive_forward * - turn_degrees + * - drive_to_point + * - turn_to_heading + * - stop + * + * Also holds AutoCommand subclasses that wrap OdometryBase functions + * + * Currently includes: + * - set_position */ #pragma once @@ -16,6 +24,9 @@ using namespace vex; + +// ==== DRIVING ==== + /** * AutoCommand wrapper class for the drive_forward function in the * TankDrive class @@ -129,3 +140,23 @@ class DriveStopCommand: public AutoCommand { // drive system to run the function on TankDrive &drive_sys; }; + + +// ==== ODOMETRY ==== + +class OdomSetPosition: public AutoCommand { + public: + OdomSetPosition(OdometryBase &odom, const position_t &newpos=OdometryBase::zero_pos); + + /** + * Run set_position + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + + private: + // drive system with an odometry config + OdometryBase &odom; + position_t newpos; +}; diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index cca5244..0acd4e2 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -9,12 +9,19 @@ * - drive_to_point * - turn_to_heading * - stop + * + * Also holds AutoCommand subclasses that wrap OdometryBase functions + * + * Currently includes: + * - set_position */ #include "../core/include/utils/command_structure/drive_commands.h" -// ==== DRIVE FORWARD ==== +// ==== DRIVING ==== + +// Drive Forward DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, double inches, double speed, double correction, directionType dir): drive_sys(drive_sys), inches(inches), speed(speed), correction(correction), dir(dir) {} @@ -29,7 +36,7 @@ bool DriveForwardCommand::run() { } -// ==== TURN DEGREES ==== +// Turn Degrees TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, double degrees, double percent_speed): drive_sys(drive_sys), degrees(degrees), percent_speed(percent_speed) {} @@ -44,7 +51,7 @@ bool TurnDegreesCommand::run() { } -// ==== DRIVE TO POINT ==== +// Drive to Point DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, double x, double y, double speed, double correction_speed, directionType dir): drive_sys(drive_sys), x(x), y(y), speed(speed), correction_speed(correction_speed), dir(dir) {} @@ -59,7 +66,7 @@ bool DriveToPointCommand::run() { } -// ==== TURN TO HEADING ==== +// Turn to Heading TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, double heading_deg, double speed): drive_sys(drive_sys), heading_deg(heading_deg), speed(speed) {} @@ -74,7 +81,7 @@ bool TurnToHeadingCommand::run() { } -// ==== STOP ==== +// Stop DriveStopCommand::DriveStopCommand(TankDrive &drive_sys): drive_sys(drive_sys) {} @@ -88,3 +95,11 @@ bool DriveStopCommand::run() { drive_sys.stop(); return true; } + + +// ==== ODOMETRY ==== + +bool OdomSetPosition::run() { + odom.set_position(newpos); + return true; +} From 7a525038a844caef44c4635ab85b6bc58904f567 Mon Sep 17 00:00:00 2001 From: Dana Date: Fri, 11 Nov 2022 23:17:09 -0500 Subject: [PATCH 111/243] flywheel commands --- .../command_structure/flywheel_commands.h | 112 ++++++++++++++++++ .../command_structure/flywheel_commands.cpp | 60 ++++++++++ 2 files changed, 172 insertions(+) create mode 100644 include/utils/command_structure/flywheel_commands.h create mode 100644 src/utils/command_structure/flywheel_commands.cpp diff --git a/include/utils/command_structure/flywheel_commands.h b/include/utils/command_structure/flywheel_commands.h new file mode 100644 index 0000000..62759af --- /dev/null +++ b/include/utils/command_structure/flywheel_commands.h @@ -0,0 +1,112 @@ +/** + * File: flywheel_commands.h + * Desc: + * [insert meaningful desc] + */ + +#pragma once + +#include "../core/include/subsystems/flywheel.h" +#include "../core/include/utils/command_structure/auto_command.h" + +class SpinRawCommand: public AutoCommand { + public: + SpinRawCommand(Flywheel &flywheel, double speed, directionType dir=fwd); + + /** + * Run spin_raw + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + + private: + // Flywheel instance to run the function on + Flywheel &flywheel; + + // parameters for spin_raw + double speed; + directionType dir; +}; + +class SpinManualCommand: public AutoCommand { + SpinManualCommand(Flywheel &flywheel, double speed, directionType dir=fwd); + + /** + * Run spin_manual + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + + private: + // Flywheel instance to run the function on + Flywheel &flywheel; + + // parameters for spin_manual + double speed; + directionType dir; +}; + +class SpinRPMCommand: AutoCommand { + SpinRPMCommand(Flywheel &flywheel, int rpm); + + /** + * Run spin_manual + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + + private: + // Flywheel instance to run the function on + Flywheel &flywheel; + + // parameters for spinRPM + int rpm; +}; + +class FlywheelStopCommand: public AutoCommand { + FlywheelStopCommand(Flywheel &flywheel); + + /** + * Run stop + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + + private: + // Flywheel instance to run the function on + Flywheel &flywheel; +}; + +class FlywheelStopMotorsCommand: public AutoCommand { + FlywheelStopMotorsCommand(Flywheel &flywheel); + + /** + * Run stop + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + + private: + // Flywheel instance to run the function on + Flywheel &flywheel; +}; + +class FlywheelStopNonTasksCommand: public AutoCommand { + FlywheelStopNonTasksCommand(Flywheel &flywheel); + + /** + * Run stop + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + + private: + // Flywheel instance to run the function on + Flywheel &flywheel; +}; diff --git a/src/utils/command_structure/flywheel_commands.cpp b/src/utils/command_structure/flywheel_commands.cpp new file mode 100644 index 0000000..37609ee --- /dev/null +++ b/src/utils/command_structure/flywheel_commands.cpp @@ -0,0 +1,60 @@ +/** + * File: flywheel_commands.cpp + * Desc: + * [insert meaningful desc] + */ + +#include "../core/include/utils/command_structure/flywheel_commands.h" + +SpinRawCommand::SpinRawCommand(Flywheel &flywheel, double speed, directionType dir): + flywheel(flywheel), speed(speed), dir(dir) {} + +bool SpinRawCommand::run() { + flywheel.spin_raw(speed, dir); + return true; +} + + +SpinManualCommand::SpinManualCommand(Flywheel &flywheel, double speed, directionType dir): + flywheel(flywheel), speed(speed), dir(dir) {} + +bool SpinManualCommand::run() { + flywheel.spin_manual(speed, dir); + return true; +} + + +SpinRPMCommand::SpinRPMCommand(Flywheel &flywheel, int rpm): + flywheel(flywheel), rpm(rpm) {} + +bool SpinRPMCommand::run() { + flywheel.spinRPM(rpm); + return true; +} + + +FlywheelStopCommand::FlywheelStopCommand(Flywheel &flywheel): + flywheel(flywheel) {} + +bool FlywheelStopCommand::run() { + flywheel.stop(); + return true; +} + + +FlywheelStopMotorsCommand::FlywheelStopMotorsCommand(Flywheel &flywheel): + flywheel(flywheel) {} + +bool FlywheelStopMotorsCommand::run() { + flywheel.stopMotors(); + return true; +} + + +FlywheelStopNonTasksCommand::FlywheelStopNonTasksCommand(Flywheel &flywheel): + flywheel(flywheel) {} + +bool FlywheelStopNonTasksCommand::run() { + flywheel.stopNonTasks(); + return true; +} From 14333c8f7df2a22d4a744c4bde74d296cbf02ce2 Mon Sep 17 00:00:00 2001 From: Dana Date: Fri, 11 Nov 2022 23:36:21 -0500 Subject: [PATCH 112/243] removed internal and manual spin commands --- .../command_structure/flywheel_commands.h | 39 ------------------- .../command_structure/flywheel_commands.cpp | 17 -------- 2 files changed, 56 deletions(-) diff --git a/include/utils/command_structure/flywheel_commands.h b/include/utils/command_structure/flywheel_commands.h index 62759af..8af93f3 100644 --- a/include/utils/command_structure/flywheel_commands.h +++ b/include/utils/command_structure/flywheel_commands.h @@ -9,45 +9,6 @@ #include "../core/include/subsystems/flywheel.h" #include "../core/include/utils/command_structure/auto_command.h" -class SpinRawCommand: public AutoCommand { - public: - SpinRawCommand(Flywheel &flywheel, double speed, directionType dir=fwd); - - /** - * Run spin_raw - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // Flywheel instance to run the function on - Flywheel &flywheel; - - // parameters for spin_raw - double speed; - directionType dir; -}; - -class SpinManualCommand: public AutoCommand { - SpinManualCommand(Flywheel &flywheel, double speed, directionType dir=fwd); - - /** - * Run spin_manual - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // Flywheel instance to run the function on - Flywheel &flywheel; - - // parameters for spin_manual - double speed; - directionType dir; -}; - class SpinRPMCommand: AutoCommand { SpinRPMCommand(Flywheel &flywheel, int rpm); diff --git a/src/utils/command_structure/flywheel_commands.cpp b/src/utils/command_structure/flywheel_commands.cpp index 37609ee..29a0b98 100644 --- a/src/utils/command_structure/flywheel_commands.cpp +++ b/src/utils/command_structure/flywheel_commands.cpp @@ -6,23 +6,6 @@ #include "../core/include/utils/command_structure/flywheel_commands.h" -SpinRawCommand::SpinRawCommand(Flywheel &flywheel, double speed, directionType dir): - flywheel(flywheel), speed(speed), dir(dir) {} - -bool SpinRawCommand::run() { - flywheel.spin_raw(speed, dir); - return true; -} - - -SpinManualCommand::SpinManualCommand(Flywheel &flywheel, double speed, directionType dir): - flywheel(flywheel), speed(speed), dir(dir) {} - -bool SpinManualCommand::run() { - flywheel.spin_manual(speed, dir); - return true; -} - SpinRPMCommand::SpinRPMCommand(Flywheel &flywheel, int rpm): flywheel(flywheel), rpm(rpm) {} From 8d9e839a93c5b436d32726b1a08f66582a781971 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 19 Jan 2023 22:00:08 -0500 Subject: [PATCH 113/243] Merge main into ACS --- include/robot_specs.h | 8 +- include/subsystems/odometry/odometry_tank.h | 3 + include/subsystems/tank_drive.h | 102 +++++++-- .../utils/command_structure/drive_commands.h | 17 +- include/utils/feedback_base.h | 48 ++++ include/utils/math_util.h | 36 ++- include/utils/motion_controller.h | 117 ++++++++++ include/utils/moving_average.h | 59 +++++ include/utils/pid.h | 64 ++++-- include/utils/trapezoid_profile.h | 65 ++++++ src/subsystems/odometry/odometry_tank.cpp | 56 ++++- src/subsystems/tank_drive.cpp | 213 ++++++++++++------ .../command_structure/drive_commands.cpp | 24 +- src/utils/math_util.cpp | 71 +++++- src/utils/motion_controller.cpp | 177 +++++++++++++++ src/utils/moving_average.cpp | 82 +++++++ src/utils/pid.cpp | 59 ++--- src/utils/trapezoid_profile.cpp | 122 ++++++++++ 18 files changed, 1145 insertions(+), 178 deletions(-) create mode 100644 include/utils/feedback_base.h create mode 100644 include/utils/motion_controller.h create mode 100644 include/utils/moving_average.h create mode 100644 include/utils/trapezoid_profile.h create mode 100644 src/utils/motion_controller.cpp create mode 100644 src/utils/moving_average.cpp create mode 100644 src/utils/trapezoid_profile.cpp diff --git a/include/robot_specs.h b/include/robot_specs.h index 95dae0a..3559dfa 100644 --- a/include/robot_specs.h +++ b/include/robot_specs.h @@ -7,8 +7,8 @@ * that require info about the robot. * All distance measurements are in inches. */ -typedef struct -{ +typedef struct +{ double robot_radius; double odom_wheel_diam; @@ -17,8 +17,8 @@ typedef struct double drive_correction_cutoff; - PID::pid_config_t drive_pid; - PID::pid_config_t turn_pid; + Feedback *drive_feedback; + Feedback *turn_feedback; PID::pid_config_t correction_pid; } robot_specs_t; \ No newline at end of file diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index e417efb..f418b4a 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -37,6 +37,7 @@ class OdometryTank : public OdometryBase void set_position(const position_t &newpos=zero_pos) override; double get_speed(); + double get_accel(); private: /** @@ -49,6 +50,8 @@ class OdometryTank : public OdometryBase vex::inertial *imu; robot_specs_t &config; + double speed, accel; + double rotation_offset = 0; }; \ No newline at end of file diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index aebd086..9fdbff2 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -5,11 +5,13 @@ #endif #include "vex.h" -#include "../core/include/utils/pid.h" #include "../core/include/subsystems/odometry/odometry_tank.h" +#include "../core/include/utils/pid.h" +#include "../core/include/utils/feedback_base.h" #include "../core/include/robot_specs.h" -#include #include "../core/src/utils/pure_pursuit.cpp" +#include + using namespace vex; @@ -44,35 +46,95 @@ class TankDrive void drive_arcade(double forward_back, double left_right, int power=1); /** - * Autonomously drive forward or backwards, X inches infront or behind the robot's current position. - * This driving method is relative, so excessive use may cause the robot to get off course! + * Use odometry to automatically drive the robot to a point on the field. + * X and Y is the final point we want the robot. * - * @param inches Distance to drive in a straight line - * @param speed How fast the robot should travel, 0 -> 1.0 - * @param correction How much the robot should correct for being off angle - * @param dir Whether the robot is travelling forwards or backwards + * Returns whether or not the robot has reached it's destination. + * @param x the x position of the target + * @param y the y position of the target + * @param dir the direction we want to travel forward and backward + * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + */ + bool drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed=1); + /** + * Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed + * of percent_speed (-1.0 -> 1.0) + * + * Uses the specified feedback for it's control. + * + * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw + * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ - bool drive_forward(double inches, double speed, double correction, directionType dir); + + bool drive_forward(double inches, directionType dir, double max_speed=1); /** * Autonomously turn the robot X degrees to the right (negative for left), with a maximum motor speed * of percent_speed (-1.0 -> 1.0) * - * Uses a PID loop for it's control. + * Uses PID + Feedforward for it's control. + * + * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw + * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ - bool turn_degrees(double degrees, double percent_speed); + bool turn_degrees(double degrees, Feedback &feedback, double max_speed=1); + /** + * Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed + * of percent_speed (-1.0 -> 1.0) + * + * Uses the defualt turning feedback of the drive system. + * + * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw + * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + */ bool turn_degrees(double degrees, double max_speed=1); /** * Use odometry to automatically drive the robot to a point on the field. * X and Y is the final point we want the robot. + * + * Returns whether or not the robot has reached it's destination. + * @param x the x position of the target + * @param y the y position of the target + * @param dir the direction we want to travel forward and backward + * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ - bool drive_to_point(double x, double y, double speed, double correction_speed, vex::directionType direction=vex::directionType::fwd); + bool drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed=1); + + /** + * Use odometry to automatically drive the robot to a point on the field. + * X and Y is the final point we want the robot. + * Here we use the default feedback controller from the drive_sys + * + * Returns whether or not the robot has reached it's destination. + * @param x the x position of the target + * @param y the y position of the target + * @param dir the direction we want to travel forward and backward + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + */ + bool drive_to_point(double x, double y, vex::directionType dir, double max_speed=1); /** * Turn the robot in place to an exact heading relative to the field. - * 0 is forward, and 0->360 is clockwise. + * 0 is forward. + * + * @param heading_deg the heading to which we will turn + * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ - bool turn_to_heading(double heading_deg, double speed); + bool turn_to_heading(double heading_deg, Feedback &feedback, double max_speed=1); + /** + * Turn the robot in place to an exact heading relative to the field. + * 0 is forward. Uses the defualt turn feedback of the drive system + * + * @param heading_deg the heading to which we will turn + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + */ + bool turn_to_heading(double heading_deg, double max_speed=1); /** * Reset the initialization for autonomous drive functions @@ -89,24 +151,24 @@ class TankDrive * Follow a hermite curve using the pure pursuit algorithm. * * @param path The hermite curve for the robot to take. Must have 2 or more points. + * @param dir Whether the robot should move forward or backwards * @param radius How the pure pursuit radius, in inches, for finding the lookahead point - * @param speed Robot's maximum speed throughout the path, between 0 and 1.0 * @param res The number of points to use along the path; the hermite curve is split up into "res" individual points. + * @param feedback The feedback controller to use + * @param max_speed Robot's maximum speed throughout the path, between 0 and 1.0 */ - bool pure_pursuit(std::vector path, double radius, double speed, double res, directionType dir=fwd); + bool pure_pursuit(std::vector path, directionType dir, double radius, double res, Feedback &feedback, double max_speed=1); private: motor_group &left_motors; motor_group &right_motors; - PID drive_pid; - PID turn_pid; PID correction_pid; + Feedback *drive_default_feedback = NULL; + Feedback *turn_default_feedback = NULL; OdometryTank *odometry; - position_t saved_pos; - robot_specs_t &config; bool func_initialized = false; diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index 0bb5e7e..b02925b 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -33,7 +33,7 @@ using namespace vex; */ class DriveForwardCommand: public AutoCommand { public: - DriveForwardCommand(TankDrive &drive_sys, double inches, double speed, double correction, directionType dir); + DriveForwardCommand(TankDrive &drive_sys, double inches, directionType dir, double max_speed); /** * Run drive_forward @@ -48,9 +48,8 @@ class DriveForwardCommand: public AutoCommand { // parameters for drive_forward double inches; - double speed; - double correction; directionType dir; + double max_speed; }; /** @@ -59,7 +58,7 @@ class DriveForwardCommand: public AutoCommand { */ class TurnDegreesCommand: public AutoCommand { public: - TurnDegreesCommand(TankDrive &drive_sys, double degrees, double percent_speed); + TurnDegreesCommand(TankDrive &drive_sys, double degrees, double max_speed); /** * Run turn_degrees @@ -74,7 +73,7 @@ class TurnDegreesCommand: public AutoCommand { // parameters for turn_degrees double degrees; - double percent_speed; + double max_speed; }; /** @@ -83,7 +82,7 @@ class TurnDegreesCommand: public AutoCommand { */ class DriveToPointCommand: public AutoCommand { public: - DriveToPointCommand(TankDrive &drive_sys, double x, double y, double speed, double correction_speed, directionType dir=directionType::fwd); + DriveToPointCommand(TankDrive &drive_sys, double x, double y, directionType dir, double max_speed); /** * Run drive_to_point @@ -99,9 +98,9 @@ class DriveToPointCommand: public AutoCommand { // parameters for drive_to_point double x; double y; - double speed; - double correction_speed; directionType dir; + double max_speed; + }; @@ -122,7 +121,7 @@ class TurnToHeadingCommand: public AutoCommand { // parameters for turn_to_heading double heading_deg; - double speed; + double max_speed; }; class DriveStopCommand: public AutoCommand { diff --git a/include/utils/feedback_base.h b/include/utils/feedback_base.h new file mode 100644 index 0000000..3096520 --- /dev/null +++ b/include/utils/feedback_base.h @@ -0,0 +1,48 @@ +#pragma once + +/** + * Interface so that subsystems can easily switch between feedback loops + * + * @author Ryan McGee + * @date 9/25/2022 + * + */ +class Feedback +{ + public: + + /** + * Initialize the feedback controller for a movement + * + * @param start_pt the current sensor value + * @param set_pt where the sensor value should be + */ + virtual void init(double start_pt, double set_pt) = 0; + + /** + * Iterate the feedback loop once with an updated sensor value + * + * @param val value from the sensor + * @return feedback loop result + */ + virtual double update(double val) = 0; + + /** + * @return the last saved result from the feedback controller + */ + virtual double get() = 0; + + /** + * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * + * @param lower Upper limit + * @param upper Lower limit + * @return double + */ + virtual void set_limits(double lower, double upper) = 0; + + /** + * @return true if the feedback controller has reached it's setpoint + */ + virtual bool is_on_target() = 0; +}; \ No newline at end of file diff --git a/include/utils/math_util.h b/include/utils/math_util.h index a27c5b2..db028bd 100644 --- a/include/utils/math_util.h +++ b/include/utils/math_util.h @@ -1,4 +1,5 @@ #pragma once +#include /** * Constrain the input between a minimum and a maximum value @@ -15,4 +16,37 @@ double clamp(double value, double low, double high); * * returns the sign +/-1 of x. 0 if x is 0 **/ -double sign(double x); \ No newline at end of file +double sign(double x); + + +/* +Calculates the variance of a set of numbers (needed for linear regression) +https://en.wikipedia.org/wiki/Variance +@param values the values for which the variance is taken +@param mean the average of values +*/ +double variance(std::vector const &values, double mean); + + +/* +Calculates the average of a vector of doubles +@param values the list of values for which the average is taken +*/ +double mean(std::vector const &values); + +/* +Calculates the covariance of a set of points (needed for linear regression) +https://en.wikipedia.org/wiki/Covariance + +@param points the points for which the covariance is taken +@param meanx the mean value of all x coordinates in points +@param meany the mean value of all y coordinates in points +*/ +double covariance(std::vector> const &points, double meanx, double meany); + +/* +Calculates the slope and y intercept of the line of best fit for the data +@param points the points for the data +*/ +std::pair calculate_linear_regression(std::vector> const &points); + diff --git a/include/utils/motion_controller.h b/include/utils/motion_controller.h new file mode 100644 index 0000000..9dc0cc0 --- /dev/null +++ b/include/utils/motion_controller.h @@ -0,0 +1,117 @@ +#pragma once +#include "../core/include/utils/pid.h" +#include "../core/include/utils/feedforward.h" +#include "../core/include/utils/trapezoid_profile.h" +#include "../core/include/utils/feedback_base.h" +#include "../core/include/subsystems/tank_drive.h" +#include "vex.h" + +/** + * Motion Controller class + * + * This class defines a top-level motion profile, which can act as an intermediate between + * a subsystem class and the motors themselves + * + * This takes the constants kS, kV, kA, kP, kI, kD, max_v and acceleration and wraps around + * a feedforward, PID and trapezoid profile. It does so with the following formula: + * + * out = feedfoward.calculate(motion_profile.get(time_s)) + pid.get(motion_profile.get(time_s)) + * + * For PID and Feedforward specific formulae, see pid.h, feedforward.h, and trapezoid_profile.h + * + * @author Ryan McGee + * @date 7/13/2022 + */ +class MotionController : public Feedback +{ + public: + + typedef struct + { + double max_v; + double accel; + PID::pid_config_t pid_cfg; + FeedForward::ff_config_t ff_cfg; + } m_profile_cfg_t; + + /** + * @brief Construct a new Motion Controller object + * + * @param max_v Maximum velocity the movement is capable of + * @param accel Acceleration / deceleration of the movement + * @param pid_cfg Definitions of kP, kI, and kD + * @param ff_cfg Definitions of kS, kV, and kA + */ + MotionController(m_profile_cfg_t &config); + + /** + * @brief Initialize the motion profile for a new movement + * This will also reset the PID and profile timers. + * + * @param start_pt Movement starting position + * @param end_pt Movement ending posiiton + */ + void init(double start_pt, double end_pt) override; + + /** + * @brief Update the motion profile with a new sensor value + * + * @param sensor_val Value from the sensor + * @return The motor input generated from the motion profile + */ + double update(double sensor_val) override; + + /** + * @return the last saved result from the feedback controller + */ + double get() override; + + /** + * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * + * @param lower Upper limit + * @param upper Lower limit + * @return double + */ + void set_limits(double lower, double upper) override; + + /** + * @return Whether or not the movement has finished, and the PID + * confirms it is on target + */ + bool is_on_target() override; + + /** + * This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. + * It does this by first calculating the kS (voltage to overcome static friction) by slowly increasing + * the voltage until it moves. + * + * Next is kV (voltage to sustain a certain velocity), where the robot will record it's steady-state velocity + * at 'pct' speed. + * + * Finally, kA (voltage needed to accelerate by a certain rate), where the robot will record the entire movement's + * velocity and acceleration, record a plot of [X=(pct-kV*V-kS), Y=(Acceleration)] along the movement, + * and since kA*Accel = pct-kV*V-kS, the reciprocal of the linear regression is the kA value. + * + * @param drive The tankdrive to operate on + * @param odometry The robot's odometry subsystem + * @param pct Maximum velocity in percent (0->1.0) + * @param duration Amount of time the robot should be moving for the test + * @return A tuned feedforward object + */ + static FeedForward::ff_config_t tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct=0.6, double duration=2); + + private: + + m_profile_cfg_t config; + + PID pid; + FeedForward ff; + TrapezoidProfile profile; + + double lower_limit = 0, upper_limit = 0; + double out = 0; + + vex::timer tmr; + +}; \ No newline at end of file diff --git a/include/utils/moving_average.h b/include/utils/moving_average.h new file mode 100644 index 0000000..093d1cc --- /dev/null +++ b/include/utils/moving_average.h @@ -0,0 +1,59 @@ +#include + +/* +* MovingAverage +* +* A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. +* This means that if you collect enough samples those that are too high are cancelled out by the samples that are too low leaving the real value. +* +* The MovingAverage class provides a simple interface to do this smoothing from our noisy sensor values. +* +* WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' behind the actual value that the sensor is reading. +* Using a MovingAverage is thus a tradeoff between accuracy and lag time (more samples) vs. less accuracy and faster updating (less samples). +* +*/ + +class MovingAverage { + public: + /* + * Create a moving average calculator with 0 as the default value + * + * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading + */ + MovingAverage(int buffer_size); + /* + * Create a moving average calculator with a specified default value + * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading + * @param starting_value The value that the average will be before any data is added + */ + MovingAverage(int buffer_size, double starting_value); + + /* + * Add a reading to the buffer + * Before: + * [ 1 1 2 2 3 3] => 2 + * ^ + * After: + * [ 2 1 2 2 3 3] => 2.16 + * ^ + * @param n the sample that will be added to the moving average. + */ + void add_entry(double n); + + /* + * Returns the average based off of all the samples collected so far + * @return sum(samples)/numsamples + */ + double get_average(); + + // How many samples the average is made from + int get_size(); + + + private: + int buffer_index; //index of the next value to be overridden + std::vector buffer; //all current data readings we've taken + bool is_ready; //if the average is ready to be read (stil can read before this but it will be taken a limited number of samples) + + +}; \ No newline at end of file diff --git a/include/utils/pid.h b/include/utils/pid.h index 0636785..a43a272 100644 --- a/include/utils/pid.h +++ b/include/utils/pid.h @@ -2,15 +2,30 @@ #include #include "vex.h" +#include "../core/include/utils/feedback_base.h" using namespace vex; -class PID +/** + * PID Class + * + * Defines a standard feedback loop using the constants kP, kI, kD, deadband, and on_target_time. + * The formula is: + * + * out = kP*error + kI*integral(d Error) + kD*(dError/dt) + * + * The PID object will determine it is "on target" when the error is within the deadband, for + * a duration of on_target_time + * + * @author Ryan McGee + * @date 4/3/2020 + */ +class PID : Feedback { public: struct pid_config_t { - double p, i, d, f, k; + double p, i, d; double deadband, on_target_time; }; @@ -19,45 +34,56 @@ class PID */ PID(pid_config_t &config); + /** + * Inherited from Feedback for interoperability. + * Update the setpoint and reset integral accumulation + * + * start_pt can be safely ignored in this feedback controller + */ + void init(double start_pt, double set_pt) override; + /** * Update the PID loop by taking the time difference from last update, * and running the PID formula with the new sensor data */ - void update(double sensorVal); + double update(double sensorVal) override; /** - * Reset the PID loop by resetting time since 0 and accumulated error. + * Gets the current PID out value, from when update() was last run */ - void reset(); + double get() override; /** - * Gets the current PID out value, from when update() was last run + * Set the limits on the PID out. The PID out will "clip" itself to be + * between the limits. */ - double get(); + void set_limits(double lower, double upper) override; /** - * Get the delta between the current sensor data and the target + * Returns true if the loop is within [deadband] for [on_target_time] + * seconds */ - double get_error(); + bool is_on_target() override; - double get_target(); + /** + * Reset the PID loop by resetting time since 0 and accumulated error. + */ + void reset(); /** - * Set the target for the PID loop, where the robot is trying to end up + * Get the delta between the current sensor data and the target */ - void set_target(double target); + double get_error(); /** - * Set the limits on the PID out. The PID out will "clip" itself to be - * between the limits. + * Get the PID's target */ - void set_limits(double lower, double upper); + double get_target(); /** - * Returns true if the loop is within [deadband] for [on_target_time] - * seconds + * Set the target for the PID loop, where the robot is trying to end up */ - bool is_on_target(); + void set_target(double target); private: pid_config_t &config; @@ -70,4 +96,4 @@ class PID bool is_checking_on_target = false; timer pid_timer; -}; \ No newline at end of file +}; diff --git a/include/utils/trapezoid_profile.h b/include/utils/trapezoid_profile.h new file mode 100644 index 0000000..5933853 --- /dev/null +++ b/include/utils/trapezoid_profile.h @@ -0,0 +1,65 @@ +#pragma once + +typedef struct +{ + double pos; + double vel; + double accel; + +} motion_t; + +/** + * Trapezoid Profile + * + * This is a motion profile defined by an acceleration, maximum velocity, start point and end point. + * Using this information, a parametric function is generated, with a period of acceleration, constant + * velocity, and deceleration. The velocity graph looks like a trapezoid, giving it it's name. + * + * If the maximum velocity is set high enough, this will become a S-curve profile, with only acceleration and deceleration. + * + * This class is designed for use in properly modelling the motion of the robots to create a feedfoward + * and target for PID. Acceleration and Maximum velocity should be measured on the robot and tuned down + * slightly to account for battery drop. + * + * Here are the equations graphed for ease of understanding: + * https://www.desmos.com/calculator/rkm3ivu1yk + * + * @author Ryan McGee + * @date 7/12/2022 + * + */ +class TrapezoidProfile +{ + public: + + /** + * @brief Construct a new Trapezoid Profile object + * + * @param max_v Maximum velocity the robot can run at + * @param accel Maximum acceleration of the robot + */ + TrapezoidProfile(double max_v, double accel); + + /** + * @brief Run the trapezoidal profile based on the time that's ellapsed + * + * @param time_s Time since start of movement + * @return motion_t Position, velocity and acceleration + */ + motion_t calculate(double time_s); + + void set_endpts(double start, double end); + + void set_accel(double accel); + + void set_max_v(double max_v); + + double get_movement_time(); + + private: + double start, end; + double max_v, accel; + double time; + + +}; \ No newline at end of file diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 1d0c9dc..1b91cc6 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -55,7 +55,8 @@ int background_task(void* odom_obj) { odom.update(); - vexDelay(DOWNTIME); + if (DOWNTIME != 0) + vexDelay(DOWNTIME); } return 0; @@ -116,9 +117,37 @@ position_t OdometryTank::update() updated_pos = calculate_new_pos(config, current_pos, lside_revs, rside_revs, angle); + + static position_t last_pos = updated_pos; + static double last_speed = 0; + static timer tmr; + + double speed_local = 0; + double accel_local = 0; + bool update_vel_accel = tmr.time(sec) > 0.1; + + // This loop runs too fast. Only check at LEAST every 1/10th sec + if(update_vel_accel) + { + // Calculate robot velocity + speed_local = pos_diff(updated_pos, last_pos) / tmr.time(sec); + + // Calculate robot acceleration + accel_local = (speed_local - last_speed) / tmr.time(sec); + + tmr.reset(); + last_pos = updated_pos; + last_speed = speed_local; + } + // Update the class' stored position mut.lock(); this->current_pos = updated_pos; + if(update_vel_accel) + { + this->speed = speed_local; + this->accel = accel_local; + } mut.unlock(); return updated_pos; @@ -165,15 +194,18 @@ position_t OdometryTank::calculate_new_pos(robot_specs_t &config, position_t &cu double OdometryTank::get_speed() { - static position_t last_pos = get_position(); - static timer speed_tmr; - - double out = 0; - if(speed_tmr.value() != 0) - { - out = pos_diff(last_pos, get_position()) / speed_tmr.time(timeUnits::sec); - speed_tmr.reset(); - } - last_pos = get_position(); - return out; + mut.lock(); + double retval = speed; + mut.unlock(); + + return retval; +} + +double OdometryTank::get_accel() +{ + mut.lock(); + double retval = accel; + mut.unlock(); + + return retval; } \ No newline at end of file diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index bd99b81..8805b4c 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -1,10 +1,11 @@ #include "../core/include/subsystems/tank_drive.h" +#include "../core/include/utils/math_util.h" TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryTank *odom) - : left_motors(left_motors), right_motors(right_motors), - drive_pid(config.drive_pid), turn_pid(config.turn_pid), correction_pid(config.correction_pid), odometry(odom), config(config) + : left_motors(left_motors), right_motors(right_motors), correction_pid(config.correction_pid), odometry(odom), config(config) { - + drive_default_feedback = config.drive_feedback; + turn_default_feedback = config.turn_feedback; } /** @@ -69,11 +70,11 @@ void TankDrive::drive_arcade(double forward_back, double left_right, int power) * This driving method is relative, so excessive use may cause the robot to get off course! * * @param inches Distance to drive in a straight line - * @param speed How fast the robot should travel, 0 -> 1.0 - * @param correction How much the robot should correct for being off angle * @param dir Whether the robot is travelling forwards or backwards + * @param correction How much the robot should correct for being off angle + * @param speed How fast the robot should travel, 0 -> 1.0 */ -bool TankDrive::drive_forward(double inches, double speed, double correction, directionType dir) +bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed) { static position_t pos_setpt; @@ -88,31 +89,57 @@ bool TankDrive::drive_forward(double inches, double speed, double correction, di // Generate a point X inches forward of the current position, on first startup if (!func_initialized) { - saved_pos = odometry->get_position(); - drive_pid.reset(); + position_t cur_pos = odometry->get_position(); + + // forwards is positive Y axis, backwards is negative + if (dir == directionType::rev) + inches = -fabs(inches); + else + inches = fabs(inches); // Use vector math to get an X and Y - Vector2D current_pos({saved_pos.x , saved_pos.y}); - Vector2D delta_pos(deg2rad(saved_pos.rot), inches); - Vector2D setpt_vec = current_pos + delta_pos; + Vector2D cur_pos_vec({cur_pos.x , cur_pos.y}); + Vector2D delta_pos_vec(deg2rad(cur_pos.rot), inches); + Vector2D setpt_vec = cur_pos_vec + delta_pos_vec; // Save the new X and Y values pos_setpt = {.x=setpt_vec.get_x(), .y=setpt_vec.get_y()}; - func_initialized = true; } // Call the drive_to_point with updated point values - return drive_to_point(pos_setpt.x, pos_setpt.y, speed, correction, dir); + return drive_to_point(pos_setpt.x, pos_setpt.y, dir, feedback, max_speed); +} +/** + * Autonomously drive forward or backwards, X inches infront or behind the robot's current position. + * This driving method is relative, so excessive use may cause the robot to get off course! + * + * @param inches Distance to drive in a straight line + * @param speed How fast the robot should travel, 0 -> 1.0 + * @param correction How much the robot should correct for being off angle + * @param dir Whether the robot is travelling forwards or backwards + */ +bool TankDrive::drive_forward(double inches, directionType dir, double max_speed) +{ + if(drive_default_feedback != NULL) + return drive_forward(inches, dir, *drive_default_feedback, max_speed); + + printf("tank_drive.cpp: Cannot run drive_forward without a feedback controller!\n"); + fflush(stdout); + return true; } /** - * Autonomously turn the robot X degrees to the right (negative for left), with a maximum motor speed + * Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed * of percent_speed (-1.0 -> 1.0) * - * Uses a PID loop for it's control. + * Uses the specified feedback for it's control. + * + * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw + * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ -bool TankDrive::turn_degrees(double degrees, double percent_speed) +bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_speed) { // We can't run the auto drive function without odometry if(odometry == NULL) @@ -122,34 +149,37 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) return true; } + static double target_heading = 0; + // On the first run of the funciton, reset the gyro position and PID if (!func_initialized) { - saved_pos = odometry->get_position(); - turn_pid.reset(); - - turn_pid.set_limits(-fabs(percent_speed), fabs(percent_speed)); - turn_pid.set_target(0); + double start_heading = odometry->get_position().rot; + target_heading = start_heading + degrees; - func_initialized = true; } - double heading = odometry->get_position().rot - saved_pos.rot; - double delta_heading = OdometryBase::smallest_angle(heading, degrees); - turn_pid.update(delta_heading); - - // printf("heading: %f, delta_heading: %f\n", heading, delta_heading); - drive_tank(turn_pid.get(), -turn_pid.get()); - - // If the robot is at it's target, return true - if (turn_pid.is_on_target()) - { - drive_tank(0, 0); - func_initialized = false; - return true; - } + return turn_to_heading(target_heading); +} - return false; +/** + * Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed + * of percent_speed (-1.0 -> 1.0) + * + * Uses the defualt turning feedback of the drive system. + * + * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw + * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + */ +bool TankDrive::turn_degrees(double degrees, double max_speed) +{ + if(turn_default_feedback != NULL) + return turn_degrees(degrees, *turn_default_feedback, max_speed); + + printf("tank_drive.cpp: Cannot run turn_degrees without a feedback controller!\n"); + fflush(stdout); + return true; } /** @@ -157,8 +187,13 @@ bool TankDrive::turn_degrees(double degrees, double percent_speed) * X and Y is the final point we want the robot. * * Returns whether or not the robot has reached it's destination. + * @param x the x position of the target + * @param y the y position of the target + * @param dir the direction we want to travel forward and backward + * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ -bool TankDrive::drive_to_point(double x, double y, double speed, double correction_speed, vex::directionType dir) +bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed) { // We can't run the auto drive function without odometry if(odometry == NULL) @@ -170,19 +205,15 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti if(!func_initialized) { - // Reset the control loops - drive_pid.reset(); - correction_pid.reset(); - - drive_pid.set_limits(-fabs(speed), fabs(speed)); - correction_pid.set_limits(-fabs(correction_speed), fabs(correction_speed)); + + double initial_dist = OdometryBase::pos_diff(odometry->get_position(), {.x=x, .y=y}); - // Set the targets to 0, because we update with the change in distance and angle between the current point - // and the new point. - drive_pid.set_target(0); - correction_pid.set_target(0); + // Reset the control loops + correction_pid.init(0, 0); + feedback.init(-initial_dist, 0); - // point_orientation_deg = atan2(y - odometry->get_position().y, x - odometry->get_position().x) * 180.0 / PI; + correction_pid.set_limits(-1, 1); + feedback.set_limits(-1, 1); func_initialized = true; } @@ -210,9 +241,11 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti double angle_to_point = atan2(y - current_pos.y, x - current_pos.x) * 180.0 / PI; double angle = fmod(current_pos.rot - angle_to_point, 360.0); + // Normalize the angle between 0 and 360 if (angle > 360) angle -= 360; if (angle < 0) angle += 360; + // If the angle is behind the robot, report negative. if (dir == directionType::fwd && angle > 90 && angle < 270) sign = -1; @@ -239,7 +272,7 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti // Update the PID controllers with new information correction_pid.update(delta_heading); - drive_pid.update(sign * -1 * dist_left); + feedback.update(sign * -1 * dist_left); // Disable correction when we're close enough to the point double correction = 0; @@ -249,25 +282,22 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti // Reverse the drive_pid output if we're going backwards double drive_pid_rval; if(dir == directionType::rev) - drive_pid_rval = drive_pid.get() * -1; + drive_pid_rval = feedback.get() * -1; else - drive_pid_rval = drive_pid.get(); + drive_pid_rval = feedback.get(); // Combine the two pid outputs double lside = drive_pid_rval + correction; double rside = drive_pid_rval - correction; // limit the outputs between -1 and +1 - lside = (lside > 1) ? 1 : (lside < -1) ? -1 : lside; - rside = (rside > 1) ? 1 : (rside < -1) ? -1 : rside; + lside = clamp(lside, -1, 1); + rside = clamp(rside, -1, 1); drive_tank(lside, rside); - printf("dist: %f\n", sign * -1 * dist_left); - fflush(stdout); - // Check if the robot has reached it's destination - if(drive_pid.is_on_target()) + if(feedback.is_on_target()) { stop(); func_initialized = false; @@ -277,11 +307,37 @@ bool TankDrive::drive_to_point(double x, double y, double speed, double correcti return false; } +/** + * Use odometry to automatically drive the robot to a point on the field. + * X and Y is the final point we want the robot. + * Here we use the default feedback controller from the drive_sys + * + * Returns whether or not the robot has reached it's destination. + * @param x the x position of the target + * @param y the y position of the target + * @param dir the direction we want to travel forward and backward + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + */ +bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, double max_speed) +{ + if(drive_default_feedback != NULL) + return this->drive_to_point(x, y, dir, *drive_default_feedback, max_speed); + + printf("tank_drive.cpp: Cannot run drive_to_point without a feedback controller!\n"); + fflush(stdout); + return true; +} + /** * Turn the robot in place to an exact heading relative to the field. - * 0 is forward, and 0->360 is clockwise. + * 0 is forward. + * + * @param heading_deg the heading to which we will turn + * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ -bool TankDrive::turn_to_heading(double heading_deg, double speed) + +bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double max_speed) { // We can't run the auto drive function without odometry if(odometry == NULL) @@ -293,27 +349,23 @@ bool TankDrive::turn_to_heading(double heading_deg, double speed) if(!func_initialized) { - turn_pid.reset(); - turn_pid.set_limits(-fabs(speed), fabs(speed)); - - // Set the target to zero, and the input will be a delta. - turn_pid.set_target(0); + double initial_delta = OdometryBase::smallest_angle(odometry->get_position().rot, heading_deg); + feedback.init(-initial_delta, 0); + feedback.set_limits(-fabs(max_speed), fabs(max_speed)); func_initialized = true; } // Get the difference between the new heading and the current, and decide whether to turn left or right. double delta_heading = OdometryBase::smallest_angle(odometry->get_position().rot, heading_deg); - turn_pid.update(delta_heading); + feedback.update(-delta_heading); - printf("~TURN~ delta: %f\n", delta_heading); - // printf("delta heading: %f, pid: %f\n", delta_heading, turn_pid.get()); fflush(stdout); - drive_tank(turn_pid.get(), -turn_pid.get()); + drive_tank(-feedback.get(), feedback.get()); // When the robot has reached it's angle, return true. - if(turn_pid.is_on_target()) + if(feedback.is_on_target()) { func_initialized = false; stop(); @@ -322,6 +374,22 @@ bool TankDrive::turn_to_heading(double heading_deg, double speed) return false; } +/** + * Turn the robot in place to an exact heading relative to the field. + * 0 is forward. Uses the defualt turn feedback of the drive system + * + * @param heading_deg the heading to which we will turn + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + */ +bool TankDrive::turn_to_heading(double heading_deg, double max_speed) +{ + if(turn_default_feedback != NULL) + return turn_to_heading(heading_deg, *turn_default_feedback, max_speed); + + printf("tank_drive.cpp: Cannot run turn_to_heading without a feedback controller!\n"); + fflush(stdout); + return true; +} /** * Modify the inputs from the controller by squaring / cubing, etc @@ -332,7 +400,8 @@ double TankDrive::modify_inputs(double input, int power) return (power % 2 == 0 ? (input < 0 ? -1 : 1) : 1) * pow(input, power); } -bool TankDrive::pure_pursuit(std::vector path, double radius, double speed, double res, directionType dir) { +bool TankDrive::pure_pursuit(std::vector path, directionType dir, double radius, double res, Feedback &feedback, double max_speed) +{ is_pure_pursuit = true; std::vector smoothed_path = PurePursuit::smooth_path_hermite(path, res); @@ -344,7 +413,7 @@ bool TankDrive::pure_pursuit(std::vector path, doubl if(is_last_point) is_pure_pursuit = false; - bool retval = drive_to_point(lookahead.x, lookahead.y, speed, 1, dir); + bool retval = drive_to_point(lookahead.x, lookahead.y, dir, feedback, max_speed); if(is_last_point) return retval; diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index 0acd4e2..cc80b96 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -23,8 +23,8 @@ // Drive Forward -DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, double inches, double speed, double correction, directionType dir): - drive_sys(drive_sys), inches(inches), speed(speed), correction(correction), dir(dir) {} +DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, double inches, directionType dir, double max_speed): + drive_sys(drive_sys), inches(inches), dir(dir), max_speed(max_speed) {} /** * Run drive_forward @@ -32,14 +32,14 @@ DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, double inches, do * @returns true when execution is complete, false otherwise */ bool DriveForwardCommand::run() { - return drive_sys.drive_forward(inches, speed, correction, dir); + return drive_sys.drive_forward(inches, dir, max_speed); } // Turn Degrees -TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, double degrees, double percent_speed): - drive_sys(drive_sys), degrees(degrees), percent_speed(percent_speed) {} +TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, double degrees, double max_speed): + drive_sys(drive_sys), degrees(degrees), max_speed(max_speed) {} /** * Run turn_degrees @@ -47,14 +47,14 @@ TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, double degrees, dou * @returns true when execution is complete, false otherwise */ bool TurnDegreesCommand::run() { - return drive_sys.turn_degrees(degrees, percent_speed); + return drive_sys.turn_degrees(degrees, max_speed); } // Drive to Point -DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, double x, double y, double speed, double correction_speed, directionType dir): - drive_sys(drive_sys), x(x), y(y), speed(speed), correction_speed(correction_speed), dir(dir) {} +DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, double x, double y, directionType dir, double max_speed): + drive_sys(drive_sys), x(x), y(y), dir(dir), max_speed(max_speed) {} /** * Run drive_to_point @@ -62,14 +62,14 @@ DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, double x, double * @returns true when execution is complete, false otherwise */ bool DriveToPointCommand::run() { - return drive_sys.drive_to_point(x, y, speed, correction_speed); + return drive_sys.drive_to_point(x, y, dir, max_speed); } // Turn to Heading -TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, double heading_deg, double speed): - drive_sys(drive_sys), heading_deg(heading_deg), speed(speed) {} +TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, double heading_deg, double max_speed): + drive_sys(drive_sys), heading_deg(heading_deg), max_speed(max_speed) {} /** * Run turn_to_heading @@ -77,7 +77,7 @@ TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, double heading_ * @returns true when execution is complete, false otherwise */ bool TurnToHeadingCommand::run() { - return drive_sys.turn_to_heading(heading_deg, speed); + return drive_sys.turn_to_heading(heading_deg, max_speed); } diff --git a/src/utils/math_util.cpp b/src/utils/math_util.cpp index 51b5555..4bccc52 100644 --- a/src/utils/math_util.cpp +++ b/src/utils/math_util.cpp @@ -1,4 +1,5 @@ #include "../core/include/utils/math_util.h" +#include /** * Constrain the input between a minimum and a maximum value @@ -26,4 +27,72 @@ double sign(double x){ return -1; } return 1; -} \ No newline at end of file +} + + +/* +Calculates the average of a vector of doubles +@param values the list of values for which the average is taken +*/ +double mean(std::vector const &values){ + double total=0; + for (int i=0; i const &values, double mean) { + double total = 0.0; + for (int i=0; i> const &points, double meanx, double meany){ + double covar = 0.0; + for (int i=0; i +*/ +std::pair calculate_linear_regression(std::vector> const &points){ + //Purely for convenience and the ability to reuse mean() and variance() - can be easily rewritten to avoid allocating these if the code is repeatedly called + std::vector xs(points.size(), 0.0); + std::vector ys(points.size(), 0.0); + for (int i =0; i(slope, y_intercept); +} diff --git a/src/utils/motion_controller.cpp b/src/utils/motion_controller.cpp new file mode 100644 index 0000000..6fde9cb --- /dev/null +++ b/src/utils/motion_controller.cpp @@ -0,0 +1,177 @@ +#include "../core/include/utils/motion_controller.h" +#include "../core/include/utils/math_util.h" +#include "../core/include/utils/moving_average.h" +#include + +/** + * @brief Construct a new Motion Controller object + * + * @param max_v Maximum velocity the movement is capable of + * @param accel Acceleration / deceleration of the movement + * @param pid_cfg Definitions of kP, kI, and kD + * @param ff_cfg Definitions of kS, kV, and kA + */ +MotionController::MotionController(m_profile_cfg_t &config) +: config(config), pid(config.pid_cfg), ff(config.ff_cfg), profile(config.max_v, config.accel) +{} + +/** + * @brief Initialize the motion profile for a new movement + * This will also reset the PID and profile timers. + * @param start_pt Movement starting position + * @param end_pt Movement ending posiiton + */ +void MotionController::init(double start_pt, double end_pt) +{ + profile.set_endpts(start_pt, end_pt); + pid.reset(); + tmr.reset(); +} + +/** + * @brief Update the motion profile with a new sensor value + * + * @param sensor_val Value from the sensor + * @return The motor input generated from the motion profile + */ +double MotionController::update(double sensor_val) +{ + motion_t motion = profile.calculate(tmr.time(timeUnits::sec)); + pid.set_target(motion.pos); + pid.update(sensor_val); + + out = pid.get() + ff.calculate(motion.vel, motion.accel); + + if(lower_limit != upper_limit) + out = clamp(out, lower_limit, upper_limit); + + return out; +} + +/** + * @return the last saved result from the feedback controller + */ +double MotionController::get() +{ + return out; +} + +/** + * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * + * @param lower Upper limit + * @param upper Lower limit + * @return double + */ +void MotionController::set_limits(double lower, double upper) +{ + lower_limit = lower; + upper_limit = upper; +} + +/** + * @return Whether or not the movement has finished, and the PID + * confirms it is on target + */ +bool MotionController::is_on_target() +{ + return (tmr.time(timeUnits::sec) > profile.get_movement_time()) && pid.is_on_target(); +} + +/** + * This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. + * It does this by first calculating the kS (voltage to overcome static friction) by slowly increasing + * the voltage until it moves. + * + * Next is kV (voltage to sustain a certain velocity), where the robot will record it's steady-state velocity + * at 'pct' speed. + * + * Finally, kA (voltage needed to accelerate by a certain rate), where the robot will record the entire movement's + * velocity and acceleration, record a plot of [X=(pct-kV*V-kS), Y=(Acceleration)] along the movement, + * and since kA*Accel = pct-kV*V-kS, the reciprocal of the linear regression is the kA value. + * + * @param drive The tankdrive to operate on + * @param odometry The robot's odometry subsystem + * @param pct Maximum velocity in percent (0->1.0) + * @param duration Amount of time the robot should be moving for the test + * @return A tuned feedforward object + */ +FeedForward::ff_config_t MotionController::tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct, double duration) +{ + FeedForward::ff_config_t out = {}; + + position_t start_pos = odometry.get_position(); + + // ========== kS Tuning ========= + // Start at 0 and slowly increase the power until the robot starts moving + double power = 0; + while(odometry.pos_diff(start_pos, odometry.get_position()) < 0.05) + { + drive.drive_tank(power, power, 1); + power += 0.001; + vexDelay(100); + } + out.kS = power; + drive.stop(); + + + // ========== kV / kA Tuning ========= + + std::vector> vel_data_points; // time, velocity + std::vector> accel_data_points; // time, accel + + double max_speed = 0; + timer tmr; + double time; + + MovingAverage vel_ma(3); + MovingAverage accel_ma(3); + + // Move the robot forward at a fixed percentage for X seconds while taking velocity and accel measurements + do + { + time = tmr.time(sec); + + vel_ma.add_entry(odometry.get_speed()); + accel_ma.add_entry(odometry.get_accel()); + + double speed = vel_ma.get_average(); + double accel = accel_ma.get_average(); + + // For kV: + if(speed > max_speed) + max_speed = speed; + + // For kA: + // Filter out the acceleration dampening due to motor inductance + if(time > 0.25) + { + vel_data_points.push_back(std::pair(time, speed)); + accel_data_points.push_back(std::pair(time, accel)); + } + + // Theoretical polling rate = 100hz (it won't be that much, cause, y'know, vex.) + vexDelay(10); + } while(time < duration); + + drive.stop(); + + // Calculate kV (volts/12 per unit per second) + out.kV = (pct - out.kS) / max_speed; + + // Calculate kA (volts/12 per unit per second^2) + std::vector> accel_per_pct; + for (int i = 0; i < vel_data_points.size(); i++) + { + accel_per_pct.push_back(std::pair( + pct - out.kS - (vel_data_points[i].second * out.kV), // Acceleration-causing percent (X variable) + accel_data_points[i].second // Measured acceleration (Y variable) + )); + } + + // kA is the reciprocal of the slope of the linear regression + double regres_slope = calculate_linear_regression(accel_per_pct).first; + out.kA = 1.0 / regres_slope; + + return out; +} \ No newline at end of file diff --git a/src/utils/moving_average.cpp b/src/utils/moving_average.cpp new file mode 100644 index 0000000..a36b56b --- /dev/null +++ b/src/utils/moving_average.cpp @@ -0,0 +1,82 @@ +#include +#include "../core/include/utils/moving_average.h" +/* +* MovingAverage +* +* A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. +* This means that if you collect enough samples those that are too high are cancelled out by the samples that are too low leaving the real value. +* +* The MovingAverage class provides a simple interface to do this smoothing from our noisy sensor values. +* +* WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' behind the actual value that the sensor is reading. +* Using a MovingAverage is thus a tradeoff between accuracy and lag time (more samples) vs. less accuracy and faster updating (less samples). +* +*/ + +/* + * Create a moving average calculator with 0 as the default value + * + * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading + */ +MovingAverage::MovingAverage(int buffer_size) { + buffer = std::vector(buffer_size, 0.0); buffer_index = 0; is_ready = false; +} + +/* + * Create a moving average calculator with a specified default value + * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading + * @param starting_value The value that the average will be before any data is added + */ +MovingAverage::MovingAverage(int buffer_size, double starting_value) { + buffer = std::vector(buffer_size, starting_value); + buffer_index = 0; + is_ready = true; +} + + + +/* + * Add a reading to the buffer + * Before: + * [ 1 1 2 2 3 3] => 2 + * ^ + * After: + * [ 2 1 2 2 3 3] => 2.16 + * ^ + * @param n the sample that will be added to the moving average. + */ +void MovingAverage::add_entry(double n){ + buffer[buffer_index] = n; + buffer_index++; + // if weve filled the buffer once, then we're ready + if (!is_ready && buffer_index==buffer.size()-1){ + is_ready = true; + } + //wrap around + buffer_index%=buffer.size(); +} + +/* + * Returns the average based off of all the samples collected so far + * @return sum(samples)/numsamples + */ +double MovingAverage::get_average(){ + double total = 0; + + int upto = buffer.size(); + if (!is_ready){ //if we're not completely ready, only make average out of the samples we have + upto = buffer_index; + } + + for (int i=0; isensor_val = sensor_val; @@ -27,15 +35,9 @@ void PID::update(double sensor_val) else if(last_time != 0) printf("(pid.cpp): Warning - running PID without a delay is just a P loop!\n"); - double k_term = 0; - if(get_error() > 0) - k_term = config.k; - else if(get_error() < 0) - k_term = -config.k; - - // F, P, D and K terms - out = (config.f * target) + (config.p * get_error()) + d_term + k_term; + // P and D terms + out = (config.p * get_error()) + d_term; bool limits_exist = lower_limit != 0 || upper_limit != 0; @@ -54,11 +56,12 @@ void PID::update(double sensor_val) if (limits_exist) out = (out < lower_limit) ? lower_limit : (out > upper_limit) ? upper_limit : out; + return out; } /** - * Reset the PID loop by resetting time since 0 and accumulated error. - */ + * Reset the PID loop by resetting time since 0 and accumulated error. + */ void PID::reset() { pid_timer.reset(); @@ -72,16 +75,16 @@ void PID::reset() } /** - * Gets the current PID out value, from when update() was last run - */ + * Gets the current PID out value, from when update() was last run + */ double PID::get() { return out; } /** - * Get the delta between the current sensor data and the target - */ + * Get the delta between the current sensor data and the target + */ double PID::get_error() { return target - sensor_val; @@ -93,17 +96,17 @@ double PID::get_target() } /** - * Set the target for the PID loop, where the robot is trying to end up - */ + * Set the target for the PID loop, where the robot is trying to end up + */ void PID::set_target(double target) { this->target = target; } /** - * Set the limits on the PID out. The PID out will "clip" itself to be - * between the limits. - */ + * Set the limits on the PID out. The PID out will "clip" itself to be + * between the limits. + */ void PID::set_limits(double lower, double upper) { lower_limit = lower; @@ -111,9 +114,9 @@ void PID::set_limits(double lower, double upper) } /** - * Returns true if the loop is within [deadband] for [on_target_time] - * seconds - */ + * Returns true if the loop is within [deadband] for [on_target_time] + * seconds + */ bool PID::is_on_target() { if (fabs(get_error()) < config.deadband) diff --git a/src/utils/trapezoid_profile.cpp b/src/utils/trapezoid_profile.cpp new file mode 100644 index 0000000..16915e6 --- /dev/null +++ b/src/utils/trapezoid_profile.cpp @@ -0,0 +1,122 @@ +#include "../core/include/utils/trapezoid_profile.h" +#include "../core/include/utils/math_util.h" +#include + +/** + * @brief Construct a new Trapezoid Profile object + * + * @param max_v Maximum velocity the robot can run at + * @param accel Maximum acceleration of the robot + */ +TrapezoidProfile::TrapezoidProfile(double max_v, double accel) +: start(0), end(0), max_v(max_v), accel(accel) {} + +void TrapezoidProfile::set_max_v(double max_v) +{ + this->max_v = max_v; +} + +void TrapezoidProfile::set_accel(double accel) +{ + this->accel = accel; +} + +void TrapezoidProfile::set_endpts(double start, double end) +{ + this->start = start; + this->end = end; +} + +// Kinematic equations as macros +#define CALC_POS(time_s,a,v,s) ((0.5*(a)*(time_s)*(time_s))+((v)*(time_s))+(s)) +#define CALC_VEL(time_s,a,v) (((a)*(time_s))+(v)) + +/** + * @brief Run the trapezoidal profile based on the time that's ellapsed + * + * @param time_s Time since start of movement + * @return motion_t Position, velocity and acceleration + */ +motion_t TrapezoidProfile::calculate(double time_s) +{ + double delta_pos = end - start; + + // redefine accel and max_v in this scope for negative calcs + double accel_local = this->accel; + double max_v_local = this->max_v; + if(delta_pos < 0) + { + accel_local = -this->accel; + max_v_local = -this->max_v; + } + + // Calculate the time spent during the acceleration / maximum velocity / deceleration stages + double accel_time = max_v_local / accel_local; + double max_vel_time = (delta_pos - (accel_local * accel_time * accel_time)) / max_v_local; + this->time = (2 * accel_time) + max_vel_time; + + // If the time during the "max velocity" state is negative, use an S profile + if (max_vel_time < 0) + { + accel_time = sqrt(fabs(delta_pos / accel)); + max_vel_time = 0; + this->time = 2 * accel_time; + } + + motion_t out; + + // Handle if a bad time is put in + if (time_s < 0) + { + out.pos = start; + out.vel = 0; + out.accel = 0; + return out; + } + + // Handle after the setpoint is reached + if (time_s > 2*accel_time + max_vel_time) + { + out.pos = end; + out.vel = 0; + out.accel = 0; + return out; + } + + // ======== KINEMATIC EQUATIONS ======== + + // Displacement from initial acceleration + if(time_s < accel_time) + { + out.pos = start + CALC_POS(time_s, accel_local, 0, 0); + out.vel = CALC_VEL(time_s, accel_local, 0); + out.accel = accel_local; + return out; + } + + double s_accel = CALC_POS(accel_time, accel_local, 0, 0); + + // Displacement during maximum velocity + if (time_s < accel_time + max_vel_time) + { + out.pos = start + CALC_POS(time_s - accel_time, 0, max_v_local, s_accel); + out.vel = sign(delta_pos) * max_v; + out.accel = 0; + return out; + } + + double s_max_vel = CALC_POS(max_vel_time, 0, max_v_local, s_accel); + + // Displacement during deceleration + out.pos = start + CALC_POS(time_s - (2*accel_time) - max_vel_time, -accel_local, 0, s_accel + s_max_vel); + out.vel = CALC_VEL(time_s - accel_time - max_vel_time, -accel_local, max_v_local); + out.accel = -accel_local; + return out; + +} + +double TrapezoidProfile::get_movement_time() +{ + return time; +} + From 9313e46353985d22178b6f4c59a45ad46b46e9b1 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 19 Jan 2023 22:37:25 -0500 Subject: [PATCH 114/243] Merge branch 'main' into auto_structure --- include/subsystems/odometry/odometry_3wheel.h | 91 +++++++++ include/subsystems/odometry/odometry_base.h | 34 +++- include/utils/math_util.h | 4 + include/utils/vector2d.h | 2 +- src/subsystems/odometry/odometry_3wheel.cpp | 180 ++++++++++++++++++ src/subsystems/odometry/odometry_base.cpp | 51 +++-- src/subsystems/odometry/odometry_tank.cpp | 37 +--- src/subsystems/tank_drive.cpp | 2 +- src/utils/math_util.cpp | 21 ++ src/utils/vector2d.cpp | 2 +- 10 files changed, 372 insertions(+), 52 deletions(-) create mode 100644 include/subsystems/odometry/odometry_3wheel.h create mode 100644 src/subsystems/odometry/odometry_3wheel.cpp diff --git a/include/subsystems/odometry/odometry_3wheel.h b/include/subsystems/odometry/odometry_3wheel.h new file mode 100644 index 0000000..a5d252f --- /dev/null +++ b/include/subsystems/odometry/odometry_3wheel.h @@ -0,0 +1,91 @@ +#pragma once +#include "../core/include/subsystems/odometry/odometry_base.h" +#include "../core/include/subsystems/tank_drive.h" +#include "../core/include/subsystems/custom_encoder.h" + +/** + * Odometry3Wheel + * + * This class handles the code for a standard 3-pod odometry setup, where there are 3 "pods" made up of undriven + * (dead) wheels connected to encoders in the following configuration: + * + * --------------- + * | | + * | | + * | || X || | + * | | + * | === | + * --------------- + * + * Where X is the center of rotation. The robot will monitor the changes in rotation of these wheels and calculate + * the robot's X, Y and rotation on the field. + * + * This is a "set and forget" class, meaning once the object is created, the robot will immediately begin + * tracking it's movement in the background. + * + * @author Ryan McGee + * @date Oct 31 2022 + * + */ +class Odometry3Wheel : public OdometryBase +{ + public: + + typedef struct + { + double wheelbase_dist; + double off_axis_center_dist; + double wheel_diam; + + } odometry3wheel_cfg_t; + + /** + * Construct a new Odometry 3 Wheel object + * + * @param lside_fwd left-side encoder reference + * @param rside_fwd right-side encoder reference + * @param off_axis off-axis (perpendicular) encoder reference + * @param cfg robot odometry configuration + * @param is_async true to constantly run in the background + */ + Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, odometry3wheel_cfg_t &cfg, bool is_async=true); + + /** + * Update the current position of the robot once, using the current state of + * the encoders and the previous known location + * + * @return the robot's updated position + */ + position_t update() override; + + /** + * A guided tuning process to automatically find tuning parameters. + * This method is blocking, and returns when tuning has finished. Follow + * the instructions on the controller to complete the tuning process + * + * @param con Controller reference, for screen and button control + * @param drive Drivetrain reference for robot control + */ + void tune(vex::controller &con, TankDrive &drive); + + private: + + /** + * Calculation method for the robot's new position using the change in encoders, the old position, and the robot's configuration. + * This uses a series of arclength formulae for finding distance driven and change in angle. + * Then vector math is used to combine it with the robot's old position data + * + * @param lside_delta_deg Left encoder change in rotation, in degrees + * @param rside_delta_deg Right encoder change in rotation, in degrees + * @param offax_delta_deg Off-axis (perpendicular) encoder change in rotation, in degrees + * @param old_pos Robot's old position, for integration + * @param cfg Data on robot's configuration (wheel diameter, wheelbase, off-axis distance from center) + * @return The robot's new position (x, y, rot) + */ + static position_t calculate_new_pos(double lside_delta_deg, double rside_delta_deg, double offax_delta_deg, position_t old_pos, odometry3wheel_cfg_t cfg); + + CustomEncoder &lside_fwd, &rside_fwd, &off_axis; + odometry3wheel_cfg_t &cfg; + + +}; \ No newline at end of file diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index 9c9b840..6d031ab 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -7,8 +7,6 @@ #define PI 3.141592654 #endif -#define DOWNTIME 0 //milliseconds - // Describes a single position and rotation typedef struct { @@ -18,11 +16,28 @@ typedef struct } position_t; /** - * Base odometry class to simplify implementations of multiple drivetrains. + * OdometryBase + * + * This base class contains all the shared code between different implementations of odometry. + * It handles the asynchronous management, position input/output and basic math functions, and + * holds positional types specific to field orientation. + * + * All future odometry implementations should extend this file and redefine update() function. + * + * @author Ryan McGee + * @date Aug 11 2021 */ class OdometryBase { public: + + /** + * Construct a new Odometry Base object + * + * @param is_async True to run constantly in the background, false to call update() manually + */ + OdometryBase(bool is_async); + /** * Gets the current position and rotation */ @@ -38,6 +53,15 @@ class OdometryBase */ virtual position_t update() = 0; + /** + * Function that runs in the background task. This function pointer is passed + * to the vex::task constructor. + * + * @param ptr Pointer to OdometryBase object + * @return Required integer return code. Unused. + */ + static int background_task(void* ptr); + /** * End the background task. Cannot be restarted. * If the user wants to end the thread but keep the data up to date, @@ -53,7 +77,7 @@ class OdometryBase /** * Get the change in rotation between two points */ - static double rot_diff(position_t &pos1, position_t &pos2); + static double rot_diff(position_t pos1, position_t pos2); /** * Get the smallest difference in angle between a start heading and end heading. @@ -64,7 +88,7 @@ class OdometryBase bool end_task = false; - inline static constexpr position_t zero_pos = {.x=0, .y=0, .rot=90}; + inline static constexpr position_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}; protected: vex::task *handle; diff --git a/include/utils/math_util.h b/include/utils/math_util.h index db028bd..71fbe30 100644 --- a/include/utils/math_util.h +++ b/include/utils/math_util.h @@ -1,4 +1,6 @@ #pragma once +#include "math.h" +#include "vex.h" #include /** @@ -18,6 +20,8 @@ double clamp(double value, double low, double high); **/ double sign(double x); +double wrap_angle_deg(double input); +double wrap_angle_rad(double input); /* Calculates the variance of a set of numbers (needed for linear regression) diff --git a/include/utils/vector2d.h b/include/utils/vector2d.h index 1e3bbb8..a854839 100644 --- a/include/utils/vector2d.h +++ b/include/utils/vector2d.h @@ -58,7 +58,7 @@ class Vector2D * * @param p point_t.x , point_t.y */ - Vector2D(point_t &p); + Vector2D(point_t p); /** * Get the direction of the vector, in radians. diff --git a/src/subsystems/odometry/odometry_3wheel.cpp b/src/subsystems/odometry/odometry_3wheel.cpp new file mode 100644 index 0000000..ed8e262 --- /dev/null +++ b/src/subsystems/odometry/odometry_3wheel.cpp @@ -0,0 +1,180 @@ +#include "../core/include/subsystems/odometry/odometry_3wheel.h" +#include "../core/include/utils/vector2d.h" +#include "../core/include/utils/math_util.h" + +Odometry3Wheel::Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, odometry3wheel_cfg_t &cfg, bool is_async) +: OdometryBase(is_async), lside_fwd(lside_fwd), rside_fwd(rside_fwd), off_axis(off_axis), cfg(cfg) +{} + +/** + * Update the current position of the robot once, using the current state of + * the encoders and the previous known location + * + * @return the robot's updated position + */ +position_t Odometry3Wheel::update() +{ + static double lside_old=0, rside_old=0, offax_old=0; + + double lside = lside_fwd.position(deg); + double rside = rside_fwd.position(deg); + double offax = off_axis.position(deg); + + double lside_delta = lside - lside_old; + double rside_delta = rside - rside_old; + double offax_delta = offax - offax_old; + + lside_old = lside; + rside_old = rside; + offax_old = offax; + + mut.lock(); + current_pos = calculate_new_pos(lside_delta, rside_delta, offax_delta, current_pos, cfg); + mut.unlock(); + + return current_pos; +} + +/** + * Calculation method for the robot's new position using the change in encoders, the old position, and the robot's configuration. + * This uses a series of arclength formulae for finding distance driven and change in angle. + * Then vector math is used to combine it with the robot's old position data + * + * @param lside_delta_deg Left encoder change in rotation, in degrees + * @param rside_delta_deg Right encoder change in rotation, in degrees + * @param offax_delta_deg Off-axis (perpendicular) encoder change in rotation, in degrees + * @param old_pos Robot's old position, for integration + * @param cfg Data on robot's configuration (wheel diameter, wheelbase, off-axis distance from center) + * @return The robot's new position (x, y, rot) + */ +position_t Odometry3Wheel::calculate_new_pos(double lside_delta_deg, double rside_delta_deg, double offax_delta_deg, position_t old_pos, odometry3wheel_cfg_t cfg) +{ + position_t retval = {}; + + // Arclength formula for encoder degrees -> single wheel distance driven + double lside_dist = (cfg.wheel_diam / 2.0) * deg2rad(lside_delta_deg); + double rside_dist = (cfg.wheel_diam / 2.0) * deg2rad(rside_delta_deg); + double offax_dist = (cfg.wheel_diam / 2.0) * deg2rad(offax_delta_deg); + + // Inverse arclength formula for arc distance driven -> robot angle + double delta_angle_rad = (rside_dist - lside_dist) / cfg.wheelbase_dist; + double delta_angle_deg = rad2deg(delta_angle_rad); + + // Distance along the robot's local Y axis (forward/backward) + double dist_local_y = (lside_dist + rside_dist) / 2.0; + + // Distance along the robot's local X axis (right/left) + double dist_local_x = offax_dist - (delta_angle_rad * cfg.off_axis_center_dist); + + // Change in displacement as a vector, on the local coordinate system (+y = robot fwd) + Vector2D local_displacement({.x=dist_local_x, .y=dist_local_y}); + + // Rotate the local displacement to match the old robot's rotation + double dir_delta_from_trans_rad = local_displacement.get_dir() - (PI/2.0); + double global_dir_rad = wrap_angle_rad(dir_delta_from_trans_rad + deg2rad(old_pos.rot)); + Vector2D global_displacement(global_dir_rad, local_displacement.get_mag()); + + // Tack on the position change to the old position + Vector2D old_pos_vec({.x=old_pos.x, .y=old_pos.y}); + Vector2D new_pos_vec = old_pos_vec + global_displacement; + + retval.x = new_pos_vec.get_x(); + retval.y = new_pos_vec.get_y(); + retval.rot = wrap_angle_deg(old_pos.rot + delta_angle_deg); + + return retval; +} + +/** + * A guided tuning process to automatically find tuning parameters. + * This method is blocking, and returns when tuning has finished. Follow + * the instructions on the controller to complete the tuning process + * + * It is assumed the gear ratio and encoder PPR have been set correctly + * + * @param con Controller reference, for screen and button control + * @param drive Drivetrain reference for robot control + */ +void Odometry3Wheel::tune(vex::controller &con, TankDrive &drive) +{ + + // TODO check if all the messages fit on the controller screen + // STEP 1: Align robot and reset odometry + con.Screen.clearScreen(); + con.Screen.setCursor(1,1); + con.Screen.print("Wheel Diameter Test"); + con.Screen.newLine(); + con.Screen.print("Align robot with ref"); + con.Screen.newLine(); + con.Screen.newLine(); + con.Screen.print("Press A to continue"); + while(!con.ButtonA.pressing()) { vexDelay(20); } + + double old_lval = lside_fwd.position(deg); + double old_rval = rside_fwd.position(deg); + + // Step 2: Drive robot a known distance + con.Screen.clearLine(2); + con.Screen.setCursor(2,1); + con.Screen.print("Drive or Push robot"); + con.Screen.newLine(); + con.Screen.print("10 feet (5 tiles)"); + con.Screen.newLine(); + con.Screen.print("Press A to continue"); + while(!con.ButtonA.pressing()) + { + drive.drive_arcade(con.Axis3.position() / 100.0, con.Axis1.position() / 100.0); + vexDelay(20); + } + + // Wheel diameter is ratio of expected distance / measured distance + double avg_deg = ((lside_fwd.position(deg) - old_lval) + (rside_fwd.position(deg) - old_rval)) / 2.0; + double measured_dist = 0.5 * deg2rad(avg_deg); // Simulate diam=1", radius=1/2" + double found_diam = 120.0 / measured_dist; + + // Step 3: Reset alignment for turning test + con.Screen.clearScreen(); + con.Screen.setCursor(1,1); + con.Screen.print("Wheelbase Test"); + con.Screen.newLine(); + con.Screen.print("Align robot with ref"); + con.Screen.newLine(); + con.Screen.newLine(); + con.Screen.print("Press A to continue"); + while(!con.ButtonA.pressing()) { vexDelay(20); } + + old_lval = lside_fwd.position(deg); + old_rval = rside_fwd.position(deg); + double old_offax = off_axis.position(deg); + + con.Screen.setCursor(2,1); + con.Screen.clearLine(); + con.Screen.print("Turn robot 10"); + con.Screen.newLine(); + con.Screen.print("times in place"); + con.Screen.newLine(); + con.Screen.print("Press A to continue"); + while(!con.ButtonA.pressing()) + { + drive.drive_arcade(0, con.Axis1.position() / 100.0); + vexDelay(20); + } + + double lside_dist = deg2rad(lside_fwd.position(deg) - old_lval) * (found_diam / 2.0); + double rside_dist = deg2rad(rside_fwd.position(deg) - old_rval) * (found_diam / 2.0); + double offax_dist = deg2rad(off_axis.position(deg) - old_offax) * (found_diam / 2.0); + + double expected_angle = 10 * (2*PI); + double found_wheelbase = fabs(rside_dist - lside_dist) / expected_angle; + double found_offax_center_dist = offax_dist / expected_angle; + + con.Screen.clearScreen(); + con.Screen.setCursor(1,1); + con.Screen.print("Diam: %f", found_diam); + con.Screen.newLine(); + con.Screen.print("whlbase: %f", found_wheelbase); + con.Screen.newLine(); + con.Screen.print("offax: %f", found_offax_center_dist); + + printf("Tuning completed.\n Wheel Diameter: %f\n Wheelbase: %f\n Off Axis Distance: %f\n"); +} \ No newline at end of file diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index 3c55330..420e966 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -1,6 +1,45 @@ #include "../core/include/subsystems/odometry/odometry_base.h" #include "../core/include/utils/vector2d.h" +/** + * Construct a new Odometry Base object + * + * @param is_async True to run constantly in the background, false to call update() manually + */ +OdometryBase::OdometryBase(bool is_async) : current_pos(zero_pos) +{ + if(is_async) + handle = new vex::task(background_task, (void*) this); +} + +/** + * Function that runs in the background task. This function pointer is passed + * to the vex::task constructor. + * + * @param ptr Pointer to OdometryBase object + * @return Required integer return code. Unused. + */ +int OdometryBase::background_task(void* ptr) +{ + OdometryBase &obj = *((OdometryBase*) ptr); + while(!obj.end_task) + { + obj.update(); + } + + return 0; +} + +/** + * End the background task. Cannot be restarted. + * If the user wants to end the thread but keep the data up to date, + * they must run the update() function manually from then on. + */ +void OdometryBase::end_async() +{ + this->end_task = true; +} + /** * Gets the current position and rotation */ @@ -35,16 +74,6 @@ void OdometryBase::set_position(const position_t &newpos) mut.unlock(); } -/** - * End the background task. Cannot be restarted. - * If the user wants to end the thread but keep the data up to date, - * they must run the update() function manually from then on. - */ -void OdometryBase::end_async() -{ - this->end_task = true; -} - /** * Get the distance between two points */ @@ -59,7 +88,7 @@ double OdometryBase::pos_diff(position_t start_pos, position_t end_pos) /** * Get the change in rotation between two points */ -double OdometryBase::rot_diff(position_t &pos1, position_t &pos2) +double OdometryBase::rot_diff(position_t pos1, position_t pos2) { return pos1.rot - pos2.rot; } diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 1b91cc6..389ced1 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -7,14 +7,8 @@ * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. */ OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu, bool is_async) -: left_side(&left_side), right_side(&right_side), left_enc(NULL), right_enc(NULL), imu(imu), config(config) +: OdometryBase(is_async), left_side(&left_side), right_side(&right_side), left_enc(NULL), right_enc(NULL), imu(imu), config(config) { - // Make sure the last known info starts zeroed - memset(¤t_pos, 0, sizeof(position_t)); - - // Start the asynchronous background thread - if (is_async) - handle = new vex::task(background_task, this); } /** @@ -24,14 +18,8 @@ OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_ * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. */ OdometryTank::OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu, bool is_async) -: left_side(NULL), right_side(NULL), left_enc(&left_enc), right_enc(&right_enc), imu(imu), config(config) +: OdometryBase(is_async), left_side(NULL), right_side(NULL), left_enc(&left_enc), right_enc(&right_enc), imu(imu), config(config) { - // Make sure the last known info starts zeroed - memset(¤t_pos, 0, sizeof(position_t)); - - // Start the asynchronous background thread - if (is_async) - handle = new vex::task(background_task, this); } /** @@ -45,23 +33,6 @@ void OdometryTank::set_position(const position_t &newpos) OdometryBase::set_position(newpos); } -/** - * The background task constantly polling the motors and updating the position. - */ -int background_task(void* odom_obj) -{ - OdometryTank &odom = *((OdometryTank*) odom_obj); - while(!odom.end_task) - { - odom.update(); - - if (DOWNTIME != 0) - vexDelay(DOWNTIME); - } - - return 0; -} - /** * Update, store and return the current position of the robot. Only use if not initializing * with a separate thread. @@ -93,12 +64,12 @@ position_t OdometryTank::update() // Get the arclength of the turning circle of the robot double distance_diff = (rside_revs - lside_revs) * PI * config.odom_wheel_diam; - //printf("dist_diff: %f, ", distance_diff); + // printf("dist_diff: %f, ", distance_diff); //Use the arclength formula to calculate the angle. Add 90 to make "0 degrees" to starboard angle = ((180.0 / PI) * (distance_diff / config.dist_between_wheels)) + 90; - //printf("angle: %f, ", (180.0 / PI) * (distance_diff / config.dist_between_wheels)); + // printf("angle: %f, ", (180.0 / PI) * (distance_diff / config.dist_between_wheels)); } else { diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 8805b4c..6c7e45d 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -98,7 +98,7 @@ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedba inches = fabs(inches); // Use vector math to get an X and Y - Vector2D cur_pos_vec({cur_pos.x , cur_pos.y}); + Vector2D cur_pos_vec({.x=cur_pos.x , .y=cur_pos.y}); Vector2D delta_pos_vec(deg2rad(cur_pos.rot), inches); Vector2D setpt_vec = cur_pos_vec + delta_pos_vec; diff --git a/src/utils/math_util.cpp b/src/utils/math_util.cpp index 4bccc52..4ab2406 100644 --- a/src/utils/math_util.cpp +++ b/src/utils/math_util.cpp @@ -1,6 +1,10 @@ #include "../core/include/utils/math_util.h" #include +#ifndef PI +#define PI 3.141592654 +#endif + /** * Constrain the input between a minimum and a maximum value * @@ -30,6 +34,23 @@ double sign(double x){ } +double wrap_angle_deg(double input) +{ + double angle = fmod(input, 360); + if(angle < 0) + angle += 360; + + return angle; +} + +double wrap_angle_rad(double input) +{ + double angle = fmod(input, 2*PI); + if(angle < 0) + angle += 2*PI; + + return angle; +} /* Calculates the average of a vector of doubles @param values the list of values for which the average is taken diff --git a/src/utils/vector2d.cpp b/src/utils/vector2d.cpp index 8532847..6d8ff96 100644 --- a/src/utils/vector2d.cpp +++ b/src/utils/vector2d.cpp @@ -17,7 +17,7 @@ Vector2D::Vector2D(double dir, double mag) * * @param p point_t.x , point_t.y */ -Vector2D::Vector2D(point_t &p) +Vector2D::Vector2D(point_t p) { this->dir = atan2(p.y, p.x); this->mag = sqrt( (p.x*p.x) + (p.y*p.y) ); From 49f08c4769d9f92a0e222d1f7e91017542cb18b8 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 19 Jan 2023 22:38:57 -0500 Subject: [PATCH 115/243] Merge branch 'main' into auto_structure --- include/utils/feedforward.h | 18 ++++++- src/utils/feedforward.cpp | 91 +++++++++++++++++++++++++++++++++ src/utils/motion_controller.cpp | 1 - 3 files changed, 108 insertions(+), 2 deletions(-) create mode 100644 src/utils/feedforward.cpp diff --git a/include/utils/feedforward.h b/include/utils/feedforward.h index f2fae43..a7afe3c 100644 --- a/include/utils/feedforward.h +++ b/include/utils/feedforward.h @@ -20,6 +20,12 @@ * @author Ryan McGee * @date 6/13/2022 */ +#include +#include +#include "../core/include/utils/math_util.h" +#include "../core/include/utils/moving_average.h" +#include "vex.h" + class FeedForward { public: @@ -58,4 +64,14 @@ class FeedForward ff_config_t &cfg; -}; \ No newline at end of file +}; + + +/** +* tune_feedforward takes a group of motors and finds the feedforward conifg parameters automagically. +* @param motor the motor group to use +* @param pct Maximum velocity in percent (0->1.0) + * @param duration Amount of time the motors spin for the test + * @return A tuned feedforward object + */ +FeedForward::ff_config_t tune_feedforward(vex::motor_group &motor, double pct, double duration); \ No newline at end of file diff --git a/src/utils/feedforward.cpp b/src/utils/feedforward.cpp new file mode 100644 index 0000000..1b4ff99 --- /dev/null +++ b/src/utils/feedforward.cpp @@ -0,0 +1,91 @@ +#include "../core/include/utils/feedforward.h" + + +/** +* tune_feedforward takes a group of motors and finds the feedforward conifg parameters automagically. +* @param motor the motor group to use +* @param pct Maximum velocity in percent (0->1.0) + * @param duration Amount of time the motors spin for the test + * @return A tuned feedforward object + */ +FeedForward::ff_config_t tune_feedforward(vex::motor_group &motor, double pct, double duration) +{ + FeedForward::ff_config_t out = {}; + + double start_pos = motor.position(vex::rotationUnits::rev); + + // ========== kS Tuning ========= + // Start at 0 and slowly increase the power until the robot starts moving + double power = 0; + while(fabs(motor.position(vex::rotationUnits::rev) - start_pos) < 0.05) + { + motor.spin(vex::directionType::fwd, power, vex::voltageUnits::volt); + power += 0.001; + vexDelay(100); + } + out.kS = power; + motor.stop(); + + + // ========== kV / kA Tuning ========= + + std::vector> vel_data_points; // time, velocity + std::vector> accel_data_points; // time, accel + + double max_speed = 0; + vex::timer tmr; + double time = 0; + + MovingAverage vel_ma(3); + MovingAverage accel_ma(3); + + // Move the robot forward at a fixed percentage for X seconds while taking velocity and accel measurements + do + { + double last_time = time; + time = tmr.time(vex::sec); + double dt = time - last_time; + + vel_ma.add_entry(motor.velocity(vex::velocityUnits::rpm)); + accel_ma.add_entry(motor.velocity(vex::velocityUnits::rpm)/dt); + + double speed = vel_ma.get_average(); + double accel = accel_ma.get_average(); + + // For kV: + if(speed > max_speed) + max_speed = speed; + + // For kA: + // Filter out the acceleration dampening due to motor inductance + if(time > 0.25) + { + vel_data_points.push_back(std::pair(time, speed)); + accel_data_points.push_back(std::pair(time, accel)); + } + + // Theoretical polling rate = 100hz (it won't be that much, cause, y'know, vex.) + vexDelay(10); + } while(time < duration); + + motor.stop(); + + // Calculate kV (volts/12 per unit per second) + out.kV = (pct - out.kS) / max_speed; + + // Calculate kA (volts/12 per unit per second^2) + std::vector> accel_per_pct; + for (int i = 0; i < vel_data_points.size(); i++) + { + accel_per_pct.push_back(std::pair( + pct - out.kS - (vel_data_points[i].second * out.kV), // Acceleration-causing percent (X variable) + accel_data_points[i].second // Measured acceleration (Y variable) + )); + } + + // kA is the reciprocal of the slope of the linear regression + double regres_slope = calculate_linear_regression(accel_per_pct).first; + out.kA = 1.0 / regres_slope; + + return out; +} \ No newline at end of file diff --git a/src/utils/motion_controller.cpp b/src/utils/motion_controller.cpp index 6fde9cb..8d8a438 100644 --- a/src/utils/motion_controller.cpp +++ b/src/utils/motion_controller.cpp @@ -1,6 +1,5 @@ #include "../core/include/utils/motion_controller.h" #include "../core/include/utils/math_util.h" -#include "../core/include/utils/moving_average.h" #include /** From cb112e47bf5425bce62858fd3669010d9f46b538 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Fri, 20 Jan 2023 19:57:46 -0500 Subject: [PATCH 116/243] Added hardware and subsystem definitions --- include/subsystems/tank_drive.h | 4 ++-- src/subsystems/tank_drive.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 9fdbff2..a82f01b 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -22,7 +22,7 @@ class TankDrive /** * Create the TankDrive object */ - TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryTank *odom=NULL); + TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom=NULL); /** * Stops rotation of all the motors using their "brake mode" @@ -167,7 +167,7 @@ class TankDrive Feedback *drive_default_feedback = NULL; Feedback *turn_default_feedback = NULL; - OdometryTank *odometry; + OdometryBase *odometry; robot_specs_t &config; diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 6c7e45d..698b521 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -1,7 +1,7 @@ #include "../core/include/subsystems/tank_drive.h" #include "../core/include/utils/math_util.h" -TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryTank *odom) +TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom) : left_motors(left_motors), right_motors(right_motors), correction_pid(config.correction_pid), odometry(odom), config(config) { drive_default_feedback = config.drive_feedback; From 01e53017287635611845eaf2c605350014174bce Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 20 Jan 2023 21:09:35 -0500 Subject: [PATCH 117/243] Stopped being a fool and started using Fancy New Auto Command Structure the sequel 2 --- .../command_structure/flywheel_commands.h | 24 ++++++++++++++++++- .../command_structure/flywheel_commands.cpp | 13 ++++++++++ 2 files changed, 36 insertions(+), 1 deletion(-) diff --git a/include/utils/command_structure/flywheel_commands.h b/include/utils/command_structure/flywheel_commands.h index 8af93f3..a153356 100644 --- a/include/utils/command_structure/flywheel_commands.h +++ b/include/utils/command_structure/flywheel_commands.h @@ -9,7 +9,8 @@ #include "../core/include/subsystems/flywheel.h" #include "../core/include/utils/command_structure/auto_command.h" -class SpinRPMCommand: AutoCommand { +class SpinRPMCommand: public AutoCommand { + public: SpinRPMCommand(Flywheel &flywheel, int rpm); /** @@ -27,7 +28,27 @@ class SpinRPMCommand: AutoCommand { int rpm; }; +class WaitUntilUpToSpeedCommand: public AutoCommand { + public: + WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshold_rpm); + + /** + * Run spin_manual + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + + private: + // Flywheel instance to run the function on + Flywheel &flywheel; + + // if the actual speed is equal to the desired speed +/- this value, we are ready to fire + int threshhold_rpm; +}; + class FlywheelStopCommand: public AutoCommand { + public: FlywheelStopCommand(Flywheel &flywheel); /** @@ -43,6 +64,7 @@ class FlywheelStopCommand: public AutoCommand { }; class FlywheelStopMotorsCommand: public AutoCommand { + public: FlywheelStopMotorsCommand(Flywheel &flywheel); /** diff --git a/src/utils/command_structure/flywheel_commands.cpp b/src/utils/command_structure/flywheel_commands.cpp index 29a0b98..3d027b2 100644 --- a/src/utils/command_structure/flywheel_commands.cpp +++ b/src/utils/command_structure/flywheel_commands.cpp @@ -15,6 +15,19 @@ bool SpinRPMCommand::run() { return true; } +WaitUntilUpToSpeedCommand::WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshhold_rpm): + flywheel(flywheel), threshhold_rpm(threshhold_rpm) {} + +bool WaitUntilUpToSpeedCommand::run() { + // If we're withing the specified threshhold, we're ready to fire + if (fabs(flywheel.getDesiredRPM() - flywheel.getRPM()) < threshhold_rpm){ + return true; + } + // else, keep waiting + return false; +} + + FlywheelStopCommand::FlywheelStopCommand(Flywheel &flywheel): flywheel(flywheel) {} From 180aeeec998169f0ccfebd28b25f8603779d5d0b Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 20 Jan 2023 21:12:01 -0500 Subject: [PATCH 118/243] Pragma Onced Flywheel. Finally it builds maybe --- include/subsystems/flywheel.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index 81a1e17..367fea1 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -1,3 +1,4 @@ +#pragma once /********************************************************* * * File: Flywheel.h @@ -10,7 +11,6 @@ * 09/23/2022 Reorganized, added documentation. * 09/23/2022 Added functions elaborated on in .cpp. *********************************************************/ - #include "../core/include/utils/feedforward.h" #include "vex.h" #include "../core/include/robot_specs.h" From 01bdff00e41f81a5d96f3bcfd31c1c22b4e1d520 Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 20 Jan 2023 22:01:24 -0500 Subject: [PATCH 119/243] Implemented Debug printing in CommandController Prints Starting Command X ... Finished Command X. where X is the number of the command. The first command to run is #1, not 0 --- src/utils/command_structure/command_controller.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index fb629c2..b33fb59 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -35,15 +35,21 @@ void CommandController::add_delay(int ms) { */ void CommandController::run() { AutoCommand *next_cmd; + printf("Beginning Auto. Starting from 1"); + int command_count = 1; while(!command_queue.empty()) { // retrieve and remove command at the front of the queue next_cmd = command_queue.front(); command_queue.pop(); + printf("Beginning Command %d", command_count); + // run the current command until it returns true while(!next_cmd -> run()) { vexDelay(20); } - + + printf("Finished Command %d", command_count); + command_count++; } } \ No newline at end of file From 2fd52db12b0606de9ead9738f7a6d47a036882a8 Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 20 Jan 2023 22:05:16 -0500 Subject: [PATCH 120/243] Fixed format error & Screen overwriting issue in 3 pod odom tuning function --- src/subsystems/odometry/odometry_3wheel.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/subsystems/odometry/odometry_3wheel.cpp b/src/subsystems/odometry/odometry_3wheel.cpp index ed8e262..034d70c 100644 --- a/src/subsystems/odometry/odometry_3wheel.cpp +++ b/src/subsystems/odometry/odometry_3wheel.cpp @@ -142,6 +142,7 @@ void Odometry3Wheel::tune(vex::controller &con, TankDrive &drive) con.Screen.newLine(); con.Screen.print("Press A to continue"); while(!con.ButtonA.pressing()) { vexDelay(20); } + con.Screen.clearScreen(); old_lval = lside_fwd.position(deg); old_rval = rside_fwd.position(deg); @@ -176,5 +177,5 @@ void Odometry3Wheel::tune(vex::controller &con, TankDrive &drive) con.Screen.newLine(); con.Screen.print("offax: %f", found_offax_center_dist); - printf("Tuning completed.\n Wheel Diameter: %f\n Wheelbase: %f\n Off Axis Distance: %f\n"); + printf("Tuning completed.\n Wheel Diameter: %f\n Wheelbase: %f\n Off Axis Distance: %f\n", found_diam, found_wheelbase, found_offax_center_dist); } \ No newline at end of file From e0a8892abca7c9ab13da130a7c1800cb3b58c3d1 Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 20 Jan 2023 23:39:15 -0500 Subject: [PATCH 121/243] Merge branch 'main' of https://github.com/RIT-VEX-U/2022-2023-Flynn --- include/subsystems/odometry/odometry_base.h | 5 ++++ include/subsystems/odometry/odometry_tank.h | 5 +--- src/subsystems/odometry/odometry_3wheel.cpp | 31 ++++++++++++++++++++- src/subsystems/odometry/odometry_base.cpp | 18 ++++++++++++ src/subsystems/odometry/odometry_tank.cpp | 18 ------------ 5 files changed, 54 insertions(+), 23 deletions(-) diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index 6d031ab..80c9e50 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -88,10 +88,15 @@ class OdometryBase bool end_task = false; + double get_speed(); + double get_accel(); + inline static constexpr position_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}; protected: vex::task *handle; vex::mutex mut; position_t current_pos; + + double speed, accel; }; \ No newline at end of file diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index f418b4a..263f371 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -36,8 +36,7 @@ class OdometryTank : public OdometryBase void set_position(const position_t &newpos=zero_pos) override; - double get_speed(); - double get_accel(); + private: /** @@ -50,8 +49,6 @@ class OdometryTank : public OdometryBase vex::inertial *imu; robot_specs_t &config; - double speed, accel; - double rotation_offset = 0; }; \ No newline at end of file diff --git a/src/subsystems/odometry/odometry_3wheel.cpp b/src/subsystems/odometry/odometry_3wheel.cpp index 034d70c..3142a15 100644 --- a/src/subsystems/odometry/odometry_3wheel.cpp +++ b/src/subsystems/odometry/odometry_3wheel.cpp @@ -28,8 +28,37 @@ position_t Odometry3Wheel::update() rside_old = rside; offax_old = offax; + position_t updated_pos = calculate_new_pos(lside_delta, rside_delta, offax_delta, current_pos, cfg); + + static position_t last_pos = updated_pos; + static double last_speed = 0; + static timer tmr; + + double speed_local = 0; + double accel_local = 0; + bool update_vel_accel = tmr.time(sec) > 0.1; + + // This loop runs too fast. Only check at LEAST every 1/10th sec + if(update_vel_accel) + { + // Calculate robot velocity + speed_local = pos_diff(updated_pos, last_pos) / tmr.time(sec); + + // Calculate robot acceleration + accel_local = (speed_local - last_speed) / tmr.time(sec); + + tmr.reset(); + last_pos = updated_pos; + last_speed = speed_local; + } + mut.lock(); - current_pos = calculate_new_pos(lside_delta, rside_delta, offax_delta, current_pos, cfg); + this->current_pos = updated_pos; + if(update_vel_accel) + { + this->speed = speed_local; + this->accel = accel_local; + } mut.unlock(); return current_pos; diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index 420e966..142be37 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -110,5 +110,23 @@ double OdometryBase::smallest_angle(double start_deg, double end_deg) if(retval > 180) retval -= 360; + return retval; +} + +double OdometryBase::get_speed() +{ + mut.lock(); + double retval = speed; + mut.unlock(); + + return retval; +} + +double OdometryBase::get_accel() +{ + mut.lock(); + double retval = accel; + mut.unlock(); + return retval; } \ No newline at end of file diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 389ced1..28971a3 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -161,22 +161,4 @@ position_t OdometryTank::calculate_new_pos(robot_specs_t &config, position_t &cu stored_rside_revs = rside_revs; return new_pos; -} - -double OdometryTank::get_speed() -{ - mut.lock(); - double retval = speed; - mut.unlock(); - - return retval; -} - -double OdometryTank::get_accel() -{ - mut.lock(); - double retval = accel; - mut.unlock(); - - return retval; } \ No newline at end of file From 1279ed0122dbfb660a5b6b9a384ba1a5a9ea3a8c Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 22 Jan 2023 14:59:40 -0500 Subject: [PATCH 122/243] Merge branch 'main' of https://github.com/RIT-VEX-U/2022-2023-Flynn --- include/subsystems/odometry/odometry_base.h | 5 ++++- src/subsystems/odometry/odometry_3wheel.cpp | 12 ++++++++++++ src/subsystems/odometry/odometry_base.cpp | 18 ++++++++++++++++++ 3 files changed, 34 insertions(+), 1 deletion(-) diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index 80c9e50..2213486 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -91,6 +91,9 @@ class OdometryBase double get_speed(); double get_accel(); + double get_angular_speed_deg(); + double get_angular_accel_deg(); + inline static constexpr position_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}; protected: @@ -98,5 +101,5 @@ class OdometryBase vex::mutex mut; position_t current_pos; - double speed, accel; + double speed, accel, ang_speed_deg, ang_accel_deg; }; \ No newline at end of file diff --git a/src/subsystems/odometry/odometry_3wheel.cpp b/src/subsystems/odometry/odometry_3wheel.cpp index 3142a15..1dc2ecf 100644 --- a/src/subsystems/odometry/odometry_3wheel.cpp +++ b/src/subsystems/odometry/odometry_3wheel.cpp @@ -32,10 +32,13 @@ position_t Odometry3Wheel::update() static position_t last_pos = updated_pos; static double last_speed = 0; + static double last_ang_speed = 0; static timer tmr; double speed_local = 0; double accel_local = 0; + double ang_speed_local = 0; + double ang_accel_local = 0; bool update_vel_accel = tmr.time(sec) > 0.1; // This loop runs too fast. Only check at LEAST every 1/10th sec @@ -47,9 +50,16 @@ position_t Odometry3Wheel::update() // Calculate robot acceleration accel_local = (speed_local - last_speed) / tmr.time(sec); + // Calculate robot angular velocity (deg/sec) + ang_speed_local = smallest_angle(updated_pos.rot, last_pos.rot) / tmr.time(sec); + + // Calculate robot angular acceleration (deg/sec^2) + ang_accel_local = (ang_speed_local - last_ang_speed) / tmr.time(sec); + tmr.reset(); last_pos = updated_pos; last_speed = speed_local; + last_ang_speed = ang_speed_local; } mut.lock(); @@ -58,6 +68,8 @@ position_t Odometry3Wheel::update() { this->speed = speed_local; this->accel = accel_local; + this->ang_speed_deg = ang_speed_local; + this->ang_accel_deg = ang_accel_local; } mut.unlock(); diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index 142be37..1b1ae35 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -128,5 +128,23 @@ double OdometryBase::get_accel() double retval = accel; mut.unlock(); + return retval; +} + +double OdometryBase::get_angular_speed_deg() +{ + mut.lock(); + double retval = ang_speed_deg; + mut.unlock(); + + return retval; +} + +double OdometryBase::get_angular_accel_deg() +{ + mut.lock(); + double retval = ang_accel_deg; + mut.unlock(); + return retval; } \ No newline at end of file From 71af0a0bb58545a330f3fdea1c9b9ced54a5b29a Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 22 Jan 2023 15:42:34 -0500 Subject: [PATCH 123/243] Added feedback as an argument to all the drive forward commands rumor has it that it even builds --- .../utils/command_structure/drive_commands.h | 21 +++++++++++++++---- .../command_structure/drive_commands.cpp | 21 +++++++++---------- 2 files changed, 27 insertions(+), 15 deletions(-) diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index b02925b..3b3eae3 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -30,10 +30,11 @@ using namespace vex; /** * AutoCommand wrapper class for the drive_forward function in the * TankDrive class + * */ class DriveForwardCommand: public AutoCommand { public: - DriveForwardCommand(TankDrive &drive_sys, double inches, directionType dir, double max_speed); + DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed=1); /** * Run drive_forward @@ -46,6 +47,9 @@ class DriveForwardCommand: public AutoCommand { // drive system to run the function on TankDrive &drive_sys; + // feedback controller to use + Feedback &feedback; + // parameters for drive_forward double inches; directionType dir; @@ -58,7 +62,7 @@ class DriveForwardCommand: public AutoCommand { */ class TurnDegreesCommand: public AutoCommand { public: - TurnDegreesCommand(TankDrive &drive_sys, double degrees, double max_speed); + TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed); /** * Run turn_degrees @@ -70,6 +74,9 @@ class TurnDegreesCommand: public AutoCommand { private: // drive system to run the function on TankDrive &drive_sys; + + // feedback controller to use + Feedback &feedback; // parameters for turn_degrees double degrees; @@ -82,7 +89,7 @@ class TurnDegreesCommand: public AutoCommand { */ class DriveToPointCommand: public AutoCommand { public: - DriveToPointCommand(TankDrive &drive_sys, double x, double y, directionType dir, double max_speed); + DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed); /** * Run drive_to_point @@ -95,6 +102,9 @@ class DriveToPointCommand: public AutoCommand { // drive system to run the function on TankDrive &drive_sys; + // feedback controller to use + Feedback &feedback; + // parameters for drive_to_point double x; double y; @@ -106,7 +116,7 @@ class DriveToPointCommand: public AutoCommand { class TurnToHeadingCommand: public AutoCommand { public: - TurnToHeadingCommand(TankDrive &drive_sys, double heading_deg, double speed); + TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed); /** * Run turn_to_heading @@ -119,6 +129,9 @@ class TurnToHeadingCommand: public AutoCommand { // drive system to run the function on TankDrive &drive_sys; + // feedback controller to use + Feedback &feedback; + // parameters for turn_to_heading double heading_deg; double max_speed; diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index cc80b96..5c67661 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -21,10 +21,9 @@ // ==== DRIVING ==== -// Drive Forward -DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, double inches, directionType dir, double max_speed): - drive_sys(drive_sys), inches(inches), dir(dir), max_speed(max_speed) {} +DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed): + drive_sys(drive_sys), feedback(feedback), inches(inches), dir(dir), max_speed(max_speed) {} /** * Run drive_forward @@ -32,14 +31,14 @@ DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, double inches, di * @returns true when execution is complete, false otherwise */ bool DriveForwardCommand::run() { - return drive_sys.drive_forward(inches, dir, max_speed); + return drive_sys.drive_forward(inches, dir, feedback, max_speed); } // Turn Degrees -TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, double degrees, double max_speed): - drive_sys(drive_sys), degrees(degrees), max_speed(max_speed) {} +TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed): + drive_sys(drive_sys), feedback(feedback), degrees(degrees), max_speed(max_speed) {} /** * Run turn_degrees @@ -53,8 +52,8 @@ bool TurnDegreesCommand::run() { // Drive to Point -DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, double x, double y, directionType dir, double max_speed): - drive_sys(drive_sys), x(x), y(y), dir(dir), max_speed(max_speed) {} +DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed): + drive_sys(drive_sys), feedback(feedback), x(x), y(y), dir(dir), max_speed(max_speed) {} /** * Run drive_to_point @@ -68,8 +67,8 @@ bool DriveToPointCommand::run() { // Turn to Heading -TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, double heading_deg, double max_speed): - drive_sys(drive_sys), heading_deg(heading_deg), max_speed(max_speed) {} +TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double max_speed): + drive_sys(drive_sys), feedback(feedback), heading_deg(heading_deg), max_speed(max_speed) {} /** * Run turn_to_heading @@ -77,7 +76,7 @@ TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, double heading_ * @returns true when execution is complete, false otherwise */ bool TurnToHeadingCommand::run() { - return drive_sys.turn_to_heading(heading_deg, max_speed); + return drive_sys.turn_to_heading(heading_deg, feedback, max_speed); } From 048f53b66f41e657d9f9fd0b561fa23e87184639 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 22 Jan 2023 16:35:14 -0500 Subject: [PATCH 124/243] Added doxygen comment and diagram --- include/subsystems/odometry/odometry_3wheel.h | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/include/subsystems/odometry/odometry_3wheel.h b/include/subsystems/odometry/odometry_3wheel.h index a5d252f..f53ac58 100644 --- a/include/subsystems/odometry/odometry_3wheel.h +++ b/include/subsystems/odometry/odometry_3wheel.h @@ -9,15 +9,17 @@ * This class handles the code for a standard 3-pod odometry setup, where there are 3 "pods" made up of undriven * (dead) wheels connected to encoders in the following configuration: * - * --------------- - * | | - * | | - * | || X || | - * | | - * | === | - * --------------- + * +Y --------------- + * ^ | | + * | | | + * | | || O || | + * | | | + * | | === | + * | --------------- + * | + * +-------------------> + X * - * Where X is the center of rotation. The robot will monitor the changes in rotation of these wheels and calculate + * Where O is the center of rotation. The robot will monitor the changes in rotation of these wheels and calculate * the robot's X, Y and rotation on the field. * * This is a "set and forget" class, meaning once the object is created, the robot will immediately begin From c9d87829c49a8735229541218a59dc7933d717c2 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 22 Jan 2023 16:35:19 -0500 Subject: [PATCH 125/243] Merge branch 'main' of https://github.com/RIT-VEX-U/2022-2023-Flynn --- include/robot_specs.h | 1 + include/utils/motion_controller.h | 9 +++++---- include/utils/pid.h | 12 ++++++++++++ src/utils/motion_controller.cpp | 9 +++++---- src/utils/pid.cpp | 4 ++++ 5 files changed, 27 insertions(+), 8 deletions(-) diff --git a/include/robot_specs.h b/include/robot_specs.h index 3559dfa..488627a 100644 --- a/include/robot_specs.h +++ b/include/robot_specs.h @@ -1,5 +1,6 @@ #pragma once #include "../core/include/utils/pid.h" +#include "../core/include/utils/feedback_base.h" /** * Main robot characterization struct. diff --git a/include/utils/motion_controller.h b/include/utils/motion_controller.h index 9dc0cc0..d816fff 100644 --- a/include/utils/motion_controller.h +++ b/include/utils/motion_controller.h @@ -37,10 +37,11 @@ class MotionController : public Feedback /** * @brief Construct a new Motion Controller object * - * @param max_v Maximum velocity the movement is capable of - * @param accel Acceleration / deceleration of the movement - * @param pid_cfg Definitions of kP, kI, and kD - * @param ff_cfg Definitions of kS, kV, and kA + * @param config The definition of how the robot is able to move + * max_v Maximum velocity the movement is capable of + * accel Acceleration / deceleration of the movement + * pid_cfg Definitions of kP, kI, and kD + * ff_cfg Definitions of kS, kV, and kA */ MotionController(m_profile_cfg_t &config); diff --git a/include/utils/pid.h b/include/utils/pid.h index a43a272..4aa280f 100644 --- a/include/utils/pid.h +++ b/include/utils/pid.h @@ -23,17 +23,28 @@ using namespace vex; class PID : Feedback { public: + /** + *An enum to distinguish between a linear and angular caluclation of PID error. + */ + enum ERROR_TYPE{ + LINEAR, + ANGULAR + }; struct pid_config_t { double p, i, d; double deadband, on_target_time; + ERROR_TYPE error_method; }; + + /** * Create the PID object */ PID(pid_config_t &config); + /** * Inherited from Feedback for interoperability. * Update the setpoint and reset integral accumulation @@ -88,6 +99,7 @@ class PID : Feedback private: pid_config_t &config; + double last_error = 0, accum_error = 0; double last_time = 0, on_target_last_time = 0; double lower_limit = 0, upper_limit = 0; diff --git a/src/utils/motion_controller.cpp b/src/utils/motion_controller.cpp index 8d8a438..86c8383 100644 --- a/src/utils/motion_controller.cpp +++ b/src/utils/motion_controller.cpp @@ -5,10 +5,11 @@ /** * @brief Construct a new Motion Controller object * - * @param max_v Maximum velocity the movement is capable of - * @param accel Acceleration / deceleration of the movement - * @param pid_cfg Definitions of kP, kI, and kD - * @param ff_cfg Definitions of kS, kV, and kA + * @param config The definition of how the robot is able to move + * max_v Maximum velocity the movement is capable of + * accel Acceleration / deceleration of the movement + * pid_cfg Definitions of kP, kI, and kD + * ff_cfg Definitions of kS, kV, and kA */ MotionController::MotionController(m_profile_cfg_t &config) : config(config), pid(config.pid_cfg), ff(config.ff_cfg), profile(config.max_v, config.accel) diff --git a/src/utils/pid.cpp b/src/utils/pid.cpp index 7002cc5..cdd4933 100644 --- a/src/utils/pid.cpp +++ b/src/utils/pid.cpp @@ -1,4 +1,5 @@ #include "../core/include/utils/pid.h" +#include "../core/include/subsystems/odometry/odometry_base.h" /** * Create the PID object @@ -87,6 +88,9 @@ double PID::get() */ double PID::get_error() { + if (config.error_method==ERROR_TYPE::ANGULAR){ + return OdometryBase::smallest_angle(target, sensor_val); + } return target - sensor_val; } From 8618da90a10ed3269ae21c9c2ee7101d6aade374 Mon Sep 17 00:00:00 2001 From: cowsed Date: Mon, 23 Jan 2023 20:45:05 -0500 Subject: [PATCH 126/243] tuning merge with stuff --- README.md | 27 ++++++++++++++++++++++- include/utils/feedforward.h | 16 +++++++++----- src/subsystems/odometry/odometry_tank.cpp | 12 ++++++++++ 3 files changed, 48 insertions(+), 7 deletions(-) diff --git a/README.md b/README.md index 8ce5935..3990a60 100644 --- a/README.md +++ b/README.md @@ -1,2 +1,27 @@ # Core -General robot code shared between the "BIG" and "LITTLE" repo's +This is the host repository for the custom VEX libraries used by the RIT VEXU team + +## Getting Started +In order to simply use this repo, you can either clone it into your VEXcode project folder, or download the .zip and place it into a core/ subfolder. Then follow the instructions for setting up compilation at [Wiki/BuildSystem](https://github.com/RIT-VEX-U/Core/wiki/1-%7C-Project-Setup#build-system) + +If you wish to contribute, follow the instructions at [Wiki/ProjectSetup](https://github.com/RIT-VEX-U/Core/wiki/1-%7C-Project-Setup) + +## Features +Here is the current feature list this repo provides: + +Subsystems (See [Wiki/Subsystems](https://github.com/RIT-VEX-U/Core/wiki/2-%7C-Subsystems)): +- Tank drivetrain (user control / autonomous) +- Mecanum drivetrain (user control / autonomous) +- Odometry +- Flywheel +- Lift +- Custom encoders + +Utilities (See [Wiki/Utilites](https://github.com/RIT-VEX-U/Core/wiki/3-%7C-Utilites)): +- PID controller +- FeedForward controller +- Trapezoidal motion profile controller +- Pure Pursuit +- Generic auto program builder +- Auto program UI selector +- Mathematical classes (Vector2D, Moving Average) diff --git a/include/utils/feedforward.h b/include/utils/feedforward.h index a7afe3c..e61000f 100644 --- a/include/utils/feedforward.h +++ b/include/utils/feedforward.h @@ -1,5 +1,11 @@ #pragma once +#include +#include +#include "../core/include/utils/math_util.h" +#include "../core/include/utils/moving_average.h" +#include "vex.h" + /** * FeedForward * @@ -20,12 +26,6 @@ * @author Ryan McGee * @date 6/13/2022 */ -#include -#include -#include "../core/include/utils/math_util.h" -#include "../core/include/utils/moving_average.h" -#include "vex.h" - class FeedForward { public: @@ -43,6 +43,10 @@ class FeedForward } ff_config_t; + /** + * Creates a FeedForward object. + * @param cfg Configuration Struct for tuning + */ FeedForward(ff_config_t &cfg) : cfg(cfg) {} /** diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 28971a3..f09e331 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -91,10 +91,13 @@ position_t OdometryTank::update() static position_t last_pos = updated_pos; static double last_speed = 0; + static double last_ang_speed = 0; static timer tmr; double speed_local = 0; double accel_local = 0; + double ang_speed_local = 0; + double ang_accel_local = 0; bool update_vel_accel = tmr.time(sec) > 0.1; // This loop runs too fast. Only check at LEAST every 1/10th sec @@ -106,9 +109,16 @@ position_t OdometryTank::update() // Calculate robot acceleration accel_local = (speed_local - last_speed) / tmr.time(sec); + // Calculate robot angular velocity (deg/sec) + ang_speed_local = smallest_angle(updated_pos.rot, last_pos.rot) / tmr.time(sec); + + // Calculate robot angular acceleration (deg/sec^2) + ang_accel_local = (ang_speed_local - last_ang_speed) / tmr.time(sec); + tmr.reset(); last_pos = updated_pos; last_speed = speed_local; + last_ang_speed = ang_speed_local; } // Update the class' stored position @@ -118,6 +128,8 @@ position_t OdometryTank::update() { this->speed = speed_local; this->accel = accel_local; + this->ang_speed_deg = ang_speed_local; + this->ang_accel_deg = ang_accel_local; } mut.unlock(); From f8db7a128f39e2368f64554842b16b306ce91536 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Mon, 23 Jan 2023 21:38:01 -0500 Subject: [PATCH 127/243] Wrapped stuff in mutexes --- src/subsystems/odometry/odometry_tank.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index f09e331..18d472d 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -28,7 +28,9 @@ OdometryTank::OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, ro */ void OdometryTank::set_position(const position_t &newpos) { + mut.lock(); rotation_offset = newpos.rot - (current_pos.rot - rotation_offset); + mut.unlock(); OdometryBase::set_position(newpos); } @@ -86,7 +88,11 @@ position_t OdometryTank::update() if(angle < 0) angle += 360; - updated_pos = calculate_new_pos(config, current_pos, lside_revs, rside_revs, angle); + mut.lock(); + position_t current_pos_local = current_pos; + mut.unlock(); + + updated_pos = calculate_new_pos(config, current_pos_local, lside_revs, rside_revs, angle); static position_t last_pos = updated_pos; From ec85a00d5a1fe82393f0d0ea15ee8426f820ad34 Mon Sep 17 00:00:00 2001 From: cowsed Date: Tue, 24 Jan 2023 23:29:07 -0500 Subject: [PATCH 128/243] Fixed Doxygen comments that contradicted the function signature -Wdocumentation is fun --- include/subsystems/odometry/odometry_tank.h | 4 ++-- src/subsystems/flywheel.cpp | 4 ++-- src/subsystems/mecanum_drive.cpp | 6 +++--- src/subsystems/odometry/odometry_tank.cpp | 4 ++-- src/subsystems/tank_drive.cpp | 7 ++----- src/utils/motion_controller.cpp | 1 - 6 files changed, 11 insertions(+), 15 deletions(-) diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index 263f371..903cb11 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -21,8 +21,8 @@ class OdometryTank : public OdometryBase /** * Initialize the Odometry module, calculating posiiton from encoders on "dead wheels" - * @param left_side The left motors - * @param right_side The right motors + * @param left_enc The left motors + * @param right_enc The right motors * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). */ diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 0f1a154..7ab0f2b 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -33,7 +33,7 @@ FeedForward::ff_config_t empty_ff = FeedForward::ff_config_t{}; * Create the Flywheel object using PID + feedforward for control. * @param motors - pointer to the motors on the fly wheel * @param pid_config - pointer the pid config -* @param ff - pointer to the feedforward config +* @param ff_config - pointer to the feedforward config * @param ratio - ratio of the whatever just multiplies the velocity */ Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio) @@ -42,7 +42,7 @@ Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForwa /** * Create the Flywheel object using only feedforward for control * @param motors - pointer to the motors on the fly wheel -* @param ff - pointer to the feedforward config +* @param ff_config - pointer to the feedforward config * @param ratio - ratio of the whatever just multiplies the velocity */ Flywheel::Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio) diff --git a/src/subsystems/mecanum_drive.cpp b/src/subsystems/mecanum_drive.cpp index 0fcf6af..641fe57 100644 --- a/src/subsystems/mecanum_drive.cpp +++ b/src/subsystems/mecanum_drive.cpp @@ -62,7 +62,7 @@ void MecanumDrive::drive_raw(double direction_deg, double magnitude, double rota * @param left_y left joystick, Y axis (forward / backwards) * @param left_x left joystick, X axis (strafe left / right) * @param right_x right joystick, X axis (rotation left / right) - * @param power=2 how much of a "curve" there should be on drive controls; better for low speed maneuvers. + * @param power = 2 how much of a "curve" there should be on drive controls; better for low speed maneuvers. * Leave blank for a default curve of 2 (higher means more fidelity) */ void MecanumDrive::drive(double left_y, double left_x, double right_x, int power) @@ -91,7 +91,7 @@ void MecanumDrive::drive(double left_y, double left_x, double right_x, int power * @param direction What direction the robot should travel in, in degrees. * 0 is forward, +/-180 is reverse, clockwise is positive. * @param speed The maximum speed the robot should travel, in percent: -1.0->+1.0 - * @param gyro_correction=true Whether or not to use the gyro to help correct while driving. + * @param gyro_correction = true Whether or not to use the gyro to help correct while driving. * Will always be false if no gyro was declared in the constructor. * @return Whether or not the maneuver is complete. */ @@ -210,7 +210,7 @@ bool MecanumDrive::auto_drive(double inches, double direction, double speed, boo * for control. * @param degrees How many degrees to rotate the robot. Clockwise postive. * @param speed What percentage to run the motors at: 0.0 -> 1.0 -* @param ignore_imu=false Whether or not to use the Inertial for determining angle. +* @param ignore_imu = false Whether or not to use the Inertial for determining angle. * Will instead use circumference formula + robot's wheelbase + encoders to determine. * * @return whether or not the robot has finished the maneuver diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 18d472d..7281cfc 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -13,8 +13,8 @@ OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_ /** * Initialize the Odometry module, calculating posiiton from encoders on "dead wheels" - * @param left_side The left motors - * @param right_side The right motors + * @param left_enc The left motors + * @param right_enc The right motors * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. */ OdometryTank::OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu, bool is_async) diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 698b521..2bffaf6 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -71,8 +71,7 @@ void TankDrive::drive_arcade(double forward_back, double left_right, int power) * * @param inches Distance to drive in a straight line * @param dir Whether the robot is travelling forwards or backwards - * @param correction How much the robot should correct for being off angle - * @param speed How fast the robot should travel, 0 -> 1.0 + * @param max_speed How fast the robot should travel, 0 -> 1.0 */ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed) { @@ -115,9 +114,8 @@ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedba * This driving method is relative, so excessive use may cause the robot to get off course! * * @param inches Distance to drive in a straight line - * @param speed How fast the robot should travel, 0 -> 1.0 - * @param correction How much the robot should correct for being off angle * @param dir Whether the robot is travelling forwards or backwards + * @param max_speed How fast the robot should travel, 0 -> 1.0 */ bool TankDrive::drive_forward(double inches, directionType dir, double max_speed) { @@ -169,7 +167,6 @@ bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_spee * Uses the defualt turning feedback of the drive system. * * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw - * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ bool TankDrive::turn_degrees(double degrees, double max_speed) diff --git a/src/utils/motion_controller.cpp b/src/utils/motion_controller.cpp index 86c8383..06f2862 100644 --- a/src/utils/motion_controller.cpp +++ b/src/utils/motion_controller.cpp @@ -61,7 +61,6 @@ double MotionController::get() * * @param lower Upper limit * @param upper Lower limit - * @return double */ void MotionController::set_limits(double lower, double upper) { From b7534d571501397c0ab9a069a14537f7ed82197e Mon Sep 17 00:00:00 2001 From: cowsed Date: Wed, 25 Jan 2023 11:46:32 -0500 Subject: [PATCH 129/243] Began the laborious task of adding comments to all uncommented things --- include/subsystems/flywheel.h | 7 ++++++ include/utils/auto_chooser.h | 11 +++++++++ .../utils/command_structure/drive_commands.h | 11 ++++++++- .../command_structure/flywheel_commands.h | 24 +++++++++++++++++++ include/utils/generic_auto.h | 4 ++++ src/utils/auto_chooser.cpp | 2 ++ 6 files changed, 58 insertions(+), 1 deletion(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index 367fea1..fe97b20 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -19,6 +19,13 @@ using namespace vex; +/** + * a Flywheel class that handles all control of a high inertia spinning disk + * It gives multiple options for what control system to use in order to control wheel velocity and functions alerting the user when the flywheel is up to speed. + * Flywheel is a set and forget class. + * Once you create it you can call spinRPM or stop on it at any time and it will take all necessary steps to accomplish this + * +*/ class Flywheel{ enum FlywheelControlStyle{ PID_Feedforward, diff --git a/include/utils/auto_chooser.h b/include/utils/auto_chooser.h index b2f3544..82db319 100644 --- a/include/utils/auto_chooser.h +++ b/include/utils/auto_chooser.h @@ -3,9 +3,19 @@ #include #include + +/** + * Autochooser is a utility to make selecting robot autonomous programs easier + * source: RIT VexU Wiki + * During a season, we usually code between 4 and 6 autonomous programs. + * Most teams will change their entire robot program as a way of choosing autonomi + * but this may cause issues if you have an emergency patch to upload during a competition. + * This class was built as a way of using the robot screen to list autonomous programs, and the touchscreen to select them. + */ class AutoChooser { public: + AutoChooser(vex::brain &brain); void add(std::string name); @@ -13,6 +23,7 @@ class AutoChooser protected: + // entry_t is a datatype used to store information that the chooser knows about an auto selection button struct entry_t { int x, y, width, height; diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index 3b3eae3..cda5a55 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -113,7 +113,11 @@ class DriveToPointCommand: public AutoCommand { }; - +/** + * AutoCommand wrapper class for the turn_to_heading() function in the + * TankDrive class + * + */ class TurnToHeadingCommand: public AutoCommand { public: TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed); @@ -137,6 +141,11 @@ class TurnToHeadingCommand: public AutoCommand { double max_speed; }; +/** + * AutoCommand wrapper class for the stop() function in the + * TankDrive class + * + */ class DriveStopCommand: public AutoCommand { public: DriveStopCommand(TankDrive &drive_sys); diff --git a/include/utils/command_structure/flywheel_commands.h b/include/utils/command_structure/flywheel_commands.h index a153356..6918325 100644 --- a/include/utils/command_structure/flywheel_commands.h +++ b/include/utils/command_structure/flywheel_commands.h @@ -9,6 +9,11 @@ #include "../core/include/subsystems/flywheel.h" #include "../core/include/utils/command_structure/auto_command.h" +/** + * AutoCommand wrapper class for the spinRPM function + * in the Flywheel class + * + */ class SpinRPMCommand: public AutoCommand { public: SpinRPMCommand(Flywheel &flywheel, int rpm); @@ -28,6 +33,10 @@ class SpinRPMCommand: public AutoCommand { int rpm; }; +/** + * AutoCommand that listens to the Flywheel and waits until it is at its target speed +/- the specified threshold + * + */ class WaitUntilUpToSpeedCommand: public AutoCommand { public: WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshold_rpm); @@ -47,6 +56,11 @@ class WaitUntilUpToSpeedCommand: public AutoCommand { int threshhold_rpm; }; +/** + * AutoCommand wrapper class for the stop function + * in the Flywheel class + * + */ class FlywheelStopCommand: public AutoCommand { public: FlywheelStopCommand(Flywheel &flywheel); @@ -63,6 +77,11 @@ class FlywheelStopCommand: public AutoCommand { Flywheel &flywheel; }; +/** + * AutoCommand wrapper class for the stopMotors function + * in the Flywheel class + * + */ class FlywheelStopMotorsCommand: public AutoCommand { public: FlywheelStopMotorsCommand(Flywheel &flywheel); @@ -79,6 +98,11 @@ class FlywheelStopMotorsCommand: public AutoCommand { Flywheel &flywheel; }; +/** + * AutoCommand wrapper class for the stopNonTasks function + * in the Flywheel class + * + */ class FlywheelStopNonTasksCommand: public AutoCommand { FlywheelStopNonTasksCommand(Flywheel &flywheel); diff --git a/include/utils/generic_auto.h b/include/utils/generic_auto.h index 092c1e5..665c28f 100644 --- a/include/utils/generic_auto.h +++ b/include/utils/generic_auto.h @@ -7,6 +7,10 @@ typedef std::function state_ptr; +/** + * GenericAuto provides a pleasant interface for organizing an auto path + * steps of the path can be added with add() and when ready, calling run() will begin executing the path +*/ class GenericAuto { public: diff --git a/src/utils/auto_chooser.cpp b/src/utils/auto_chooser.cpp index a768179..d2dcaeb 100644 --- a/src/utils/auto_chooser.cpp +++ b/src/utils/auto_chooser.cpp @@ -3,6 +3,7 @@ /** * Initialize the auto-chooser. This class places a choice menu on the brain screen, * so the driver can choose which autonomous to run. + * @param brain the brain on which to draw the selection boxes */ AutoChooser::AutoChooser(vex::brain &brain) : brain(brain) { @@ -41,6 +42,7 @@ AutoChooser::AutoChooser(vex::brain &brain) : brain(brain) /** * Place all the autonomous choices on the screen. * If one is selected, change it's color + * @param render the chouce that is to be rendered */ void AutoChooser::render(entry_t *selected) { From ab2e4b1d0474496be19c064012880aff3c95df3f Mon Sep 17 00:00:00 2001 From: cowsed Date: Wed, 25 Jan 2023 15:54:40 -0500 Subject: [PATCH 130/243] Doxygen my enemy --- include/subsystems/custom_encoder.h | 30 +++++++++++++ include/subsystems/flywheel.h | 30 ++++++------- include/subsystems/odometry/odometry_3wheel.h | 4 ++ include/subsystems/odometry/odometry_base.h | 4 +- include/subsystems/odometry/odometry_tank.h | 7 +++ include/subsystems/tank_drive.h | 4 ++ include/utils/auto_chooser.h | 35 +++++++++++---- .../utils/command_structure/delay_command.h | 5 ++- .../utils/command_structure/drive_commands.h | 5 ++- .../command_structure/flywheel_commands.h | 9 ++++ include/utils/motion_controller.h | 5 +++ include/utils/moving_average.h | 25 +++++------ include/utils/pid.h | 9 +++- include/utils/trapezoid_profile.h | 3 ++ include/utils/vector2d.h | 38 +++++++++++++--- src/subsystems/flywheel.cpp | 4 ++ src/utils/auto_chooser.cpp | 2 +- .../command_structure/command_controller.cpp | 1 - .../command_structure/drive_commands.cpp | 44 +++++++++++++++---- 19 files changed, 208 insertions(+), 56 deletions(-) diff --git a/include/subsystems/custom_encoder.h b/include/subsystems/custom_encoder.h index 19df840..2b87b86 100644 --- a/include/subsystems/custom_encoder.h +++ b/include/subsystems/custom_encoder.h @@ -10,16 +10,46 @@ class CustomEncoder : public vex::encoder typedef vex::encoder super; public: + /** + * Construct an encoder with a custom number of ticks + * @param port the triport port on the brain the encoder is plugged into + * @param ticks_per_rev the number of ticks the encoder will report for one revolution + */ CustomEncoder(vex::triport::port &port, double ticks_per_rev); + /** + * sets the stored rotation of the encoder. Any further movements will be from this value + * @param val the numerical value of the angle we are setting to + * @param units the unit of val + */ void setRotation(double val, vex::rotationUnits units); + /** + * sets the stored position of the encoder. Any further movements will be from this value + * @param val the numerical value of the position we are setting to + * @param units the unit of val + */ void setPosition(double val, vex::rotationUnits units); + /** + * get the rotation that the encoder is at + * @param units the unit we want the return value to be in + * @return the rotation of the encoder in the units specified + */ double rotation(vex::rotationUnits units); + /** + * get the position that the encoder is at + * @param units the unit we want the return value to be in + * @return the position of the encoder in the units specified + */ double position(vex::rotationUnits units); + /** + * get the velocity that the encoder is moving at + * @param units the unit we want the return value to be in + * @return the velocity of the encoder in the units specified + */ double velocity(vex::velocityUnits units); diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index fe97b20..fbcd4db 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -38,45 +38,45 @@ class Flywheel{ // CONSTRUCTORS, GETTERS, AND SETTERS /** * Create the Flywheel object using PID + feedforward for control. - * @param motors - pointer to the motors on the fly wheel - * @param pid_config - pointer the pid config - * @param ff - pointer to the feedforward config - * @param ratio - ratio of the whatever just multiplies the velocity + * @param motors pointer to the motors on the fly wheel + * @param pid_config pointer the pid config to use + * @param ff_config the feedforward config to use + * @param ratio ratio of the whatever just multiplies the velocity */ Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio); /** * Create the Flywheel object using only feedforward for control - * @param motors - pointer to the motors on the fly wheel - * @param ff - pointer to the feedforward config - * @param ratio - ratio of the whatever just multiplies the velocity + * @param motors the motors on the fly wheel + * @param ff_config the feedforward config to use + * @param ratio ratio of the whatever just multiplies the velocity */ Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio); /** * Create the Flywheel object using Take Back Half for control - * @param motors - pointer to the motors on the fly wheel - * @param TBH_gain - the TBH control paramater - * @param ratio - ratio of the whatever just multiplies the velocity + * @param motors the motors on the fly wheel + * @param tbh_gain the TBH control paramater + * @param ratio ratio of the whatever just multiplies the velocity */ Flywheel(motor_group &motors, double tbh_gain, const double ratio); /** * Create the Flywheel object using Bang Bang for control - * @param motors - pointer to the motors on the fly wheel - * @param ratio - ratio of the whatever just multiplies the velocity + * @param motors the motors on the fly wheel + * @param ratio ratio of the whatever just multiplies the velocity */ Flywheel(motor_group &motors, const double ratio); /** - * Return the current value that the RPM should be set to - * @return RPM = the target rpm + * Return the RPM that the flywheel is currently trying to achieve + * @return RPM the target rpm */ double getDesiredRPM(); /** * Checks if the background RPM controlling task is running - * @return taskRunning - If the task is running + * @return true if the task is running */ bool isTaskRunning(); diff --git a/include/subsystems/odometry/odometry_3wheel.h b/include/subsystems/odometry/odometry_3wheel.h index f53ac58..44db64a 100644 --- a/include/subsystems/odometry/odometry_3wheel.h +++ b/include/subsystems/odometry/odometry_3wheel.h @@ -33,6 +33,10 @@ class Odometry3Wheel : public OdometryBase { public: + /** + * odometry3wheel_cfg_t holds all the specifications for how to calculate position with 3 encoders + * see the wiki for what exactly each of these parameters measures + */ typedef struct { double wheelbase_dist; diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index 2213486..862dc85 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -7,7 +7,9 @@ #define PI 3.141592654 #endif -// Describes a single position and rotation +/** + * Describes a single position and rotation + */ typedef struct { double x; diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index 903cb11..a0b115d 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -7,6 +7,13 @@ static int background_task(void* odom_obj); + +/** + * OdometryTank defines an odometry system for a tank drivetrain + * This requires encoders in the same orientation as the drive wheels + * Odometry is a "start and forget" subsystem, which means once it's created and configured, + * it will constantly run in the background and track the robot's X, Y and rotation coordinates. +*/ class OdometryTank : public OdometryBase { public: diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index a82f01b..5c20e2c 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -15,6 +15,10 @@ using namespace vex; +/** + * TankDrive is a class to run a tank drive system. + * A tank drive system, sometimes called differential drive, has a motor (or group of synchronized motors) on the left and right side +*/ class TankDrive { public: diff --git a/include/utils/auto_chooser.h b/include/utils/auto_chooser.h index 82db319..e42f1d4 100644 --- a/include/utils/auto_chooser.h +++ b/include/utils/auto_chooser.h @@ -15,25 +15,44 @@ class AutoChooser { public: - +/** + * Initialize the auto-chooser. This class places a choice menu on the brain screen, + * so the driver can choose which autonomous to run. + * @param brain the brain on which to draw the selection boxes + */ AutoChooser(vex::brain &brain); - + + /** + * Add an auto path to the chooser + * @param name The name of the path. This should be used as an human readable identifier to the auto path + */ void add(std::string name); + + /** + * Get the currently selected auto choice + * @return the identifier to the auto path + */ std::string get_choice(); protected: - // entry_t is a datatype used to store information that the chooser knows about an auto selection button + /** + * entry_t is a datatype used to store information that the chooser knows about an auto selection button + */ struct entry_t { - int x, y, width, height; - std::string name; + int x; /**< screen x position of the block*/ + int y; /**< screen y position of the block*/ + int width; /**< width of the block*/ + int height; /**< height of the block*/ + std::string name; /**< name of the auto repretsented by the block*/ }; void render(entry_t *selected); - std::string choice; - std::vector list; - vex::brain &brain; + + std::string choice; /**< the current choice of auto*/ + std::vector list /**< a list of all possible auto choices*/; + vex::brain &brain; /**< the brain to show the choices on*/ }; \ No newline at end of file diff --git a/include/utils/command_structure/delay_command.h b/include/utils/command_structure/delay_command.h index bdf1af1..c82b9bd 100644 --- a/include/utils/command_structure/delay_command.h +++ b/include/utils/command_structure/delay_command.h @@ -11,7 +11,10 @@ class DelayCommand: public AutoCommand { public: - + /** + * Construct a delay command + * @param ms the number of milliseconds to delay for + */ DelayCommand(int ms): ms(ms) {} /** diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index cda5a55..a544811 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -144,7 +144,6 @@ class TurnToHeadingCommand: public AutoCommand { /** * AutoCommand wrapper class for the stop() function in the * TankDrive class - * */ class DriveStopCommand: public AutoCommand { public: @@ -165,6 +164,10 @@ class DriveStopCommand: public AutoCommand { // ==== ODOMETRY ==== +/** + * AutoCommand wrapper class for the set_position function in the + * Odometry class + */ class OdomSetPosition: public AutoCommand { public: OdomSetPosition(OdometryBase &odom, const position_t &newpos=OdometryBase::zero_pos); diff --git a/include/utils/command_structure/flywheel_commands.h b/include/utils/command_structure/flywheel_commands.h index 6918325..efe59f9 100644 --- a/include/utils/command_structure/flywheel_commands.h +++ b/include/utils/command_structure/flywheel_commands.h @@ -39,6 +39,11 @@ class SpinRPMCommand: public AutoCommand { */ class WaitUntilUpToSpeedCommand: public AutoCommand { public: + /** + * Creat a WaitUntilUpToSpeedCommand + * @param flywheel the flywheel system we are commanding + * @param threshold_rpm the threshold over and under the flywheel target RPM that we define to be acceptable + */ WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshold_rpm); /** @@ -63,6 +68,10 @@ class WaitUntilUpToSpeedCommand: public AutoCommand { */ class FlywheelStopCommand: public AutoCommand { public: + /** + * Construct a FlywheelStopCommand + * @param flywheel the flywheel system we are commanding + */ FlywheelStopCommand(Flywheel &flywheel); /** diff --git a/include/utils/motion_controller.h b/include/utils/motion_controller.h index d816fff..8ee00e7 100644 --- a/include/utils/motion_controller.h +++ b/include/utils/motion_controller.h @@ -26,6 +26,11 @@ class MotionController : public Feedback { public: + /** + * m_profile_config holds all data the motion controller uses to plan paths + * When motion pofile is given a target to drive to, max_v and accel are used to make the trapezoid profile instructing the controller how to drive + * pid_cfg, ff_cfg are used to find the motor outputs necessary to execute this path + */ typedef struct { double max_v; diff --git a/include/utils/moving_average.h b/include/utils/moving_average.h index 093d1cc..5cc8eaa 100644 --- a/include/utils/moving_average.h +++ b/include/utils/moving_average.h @@ -1,18 +1,17 @@ #include -/* -* MovingAverage -* -* A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. -* This means that if you collect enough samples those that are too high are cancelled out by the samples that are too low leaving the real value. -* -* The MovingAverage class provides a simple interface to do this smoothing from our noisy sensor values. -* -* WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' behind the actual value that the sensor is reading. -* Using a MovingAverage is thus a tradeoff between accuracy and lag time (more samples) vs. less accuracy and faster updating (less samples). -* -*/ - +/** + * MovingAverage + * + * A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. + * This means that if you collect enough samples those that are too high are cancelled out by the samples that are too low leaving the real value. + * + * The MovingAverage class provides a simple interface to do this smoothing from our noisy sensor values. + * + * WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' behind the actual value that the sensor is reading. + * Using a MovingAverage is thus a tradeoff between accuracy and lag time (more samples) vs. less accuracy and faster updating (less samples). + * + */ class MovingAverage { public: /* diff --git a/include/utils/pid.h b/include/utils/pid.h index 4aa280f..32afd38 100644 --- a/include/utils/pid.h +++ b/include/utils/pid.h @@ -24,12 +24,19 @@ class PID : Feedback { public: /** - *An enum to distinguish between a linear and angular caluclation of PID error. + * An enum to distinguish between a linear and angular caluclation of PID error. */ enum ERROR_TYPE{ LINEAR, ANGULAR }; + /** + * pid_config_t holds the configuration parameters for a pid controller + * In addtion to the constant of proportional, integral and derivative, these parameters include: + * - deadband - at what point are we close enough to be finished + * - on_target_time - for how long do we have to be at the target to stop + * As well, pid_config_t holds an error type which determines whether errors should be calculated as if the sensor position is a measure of distance or an angle + */ struct pid_config_t { double p, i, d; diff --git a/include/utils/trapezoid_profile.h b/include/utils/trapezoid_profile.h index 5933853..11cba85 100644 --- a/include/utils/trapezoid_profile.h +++ b/include/utils/trapezoid_profile.h @@ -1,5 +1,8 @@ #pragma once +/** + * motion_t is a description of 1 dimensional motion at a point in time +*/ typedef struct { double pos; diff --git a/include/utils/vector2d.h b/include/utils/vector2d.h index a854839..d2e672e 100644 --- a/include/utils/vector2d.h +++ b/include/utils/vector2d.h @@ -5,7 +5,11 @@ #ifndef PI #define PI 3.141592654 #endif - +/** + * Vector2D is an x,y pair + * Used to represent 2D locations on the field. + * It can also be treated as a direction and magnitude +*/ class Vector2D { public: @@ -65,36 +69,55 @@ class Vector2D * '0' is forward, clockwise positive when viewed from the top. * * Use r2d() to convert. + * @return the direction of the vetctor in radians */ double get_dir() const; /** - * Get the magnitude of the vector + * @return the magnitude of the vector */ double get_mag() const; /** - * Get the X component of the vector; positive to the right. + * @return the X component of the vector; positive to the right. */ double get_x() const; /** - * Get the Y component of the vector, positive forward. + * @return the Y component of the vector, positive forward. */ double get_y() const; /** - * Changes the magnetude of the vector to 1 + * Changes the magnitude of the vector to 1 + * @return the normalized vector */ Vector2D normalize(); /** * Returns a point from the vector + * @return the point represented by the vector */ Vector2D::point_t point(); + /** + * Multiply the components of a vector by x + * (self.x * x, self.y * x) + * @param x the scalar value by which to multiply the components of the vector + * @return the vector after scaling by s + */ Vector2D operator*(const double &x); + /** + * Add the components of two vectors together + * Vector2D + Vector2D = (self.x + other.x, self.y + other.y) + * @return the sum of the vectors + */ Vector2D operator+(const Vector2D &other); + /** + * Subtract the components of two vectors together + * Vector2D - Vector2D = (self.x - other.x, self.y - other.y) + * @return the difference of the vectors + */ Vector2D operator-(const Vector2D &other); private: @@ -105,10 +128,15 @@ class Vector2D /** * General function for converting degrees to radians + * @param deg the angle in degrees + * @return the angle in radians */ double deg2rad(double deg); /** * General function for converting radians to degrees + * @param rad the angle in radians + * @return the angle in degrees + */ double rad2deg(double r); diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 7ab0f2b..2cd7990 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -84,6 +84,7 @@ motor_group* Flywheel::getMotors() { return &motors; } // TODO -- Remove? /** * return the current velocity of the flywheel motors, in RPM +* @return the measured velocity of the flywheel */ double Flywheel::getRPM() { return ratio * motors.velocity(velocityUnits::rpm); } @@ -94,11 +95,13 @@ PID* Flywheel::getPID() { return &pid; } // TODO -- Remove? /** * returns the current OUT value of the PID - the value that the PID would set the motors to +* @return the voltage that PID wants the motors at to achieve the target RPM */ double Flywheel::getPIDValue() { return pid.get(); } /** * returns the current OUT value of the Feedforward - the value that the Feedforward would set the motors to +* @return the voltage that feedforward wants the motors at to achieve the target RPM */ double Flywheel::getFeedforwardValue() { double v = getDesiredRPM(); @@ -107,6 +110,7 @@ double Flywheel::getFeedforwardValue() { /** * get the gain used for TBH control +* @return the gain used in TBH control */ double Flywheel::getTBHGain(){ return TBH_gain; diff --git a/src/utils/auto_chooser.cpp b/src/utils/auto_chooser.cpp index d2dcaeb..4edd072 100644 --- a/src/utils/auto_chooser.cpp +++ b/src/utils/auto_chooser.cpp @@ -42,7 +42,7 @@ AutoChooser::AutoChooser(vex::brain &brain) : brain(brain) /** * Place all the autonomous choices on the screen. * If one is selected, change it's color - * @param render the chouce that is to be rendered + * @param selected the choice that is currently selected */ void AutoChooser::render(entry_t *selected) { diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index b33fb59..afcc3ed 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -12,7 +12,6 @@ /** * Adds a command to the queue - * @param cmd - AutoCommand to be added */ void CommandController::add(AutoCommand *cmd) { command_queue.push(cmd); diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index 5c67661..9f25f96 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -21,7 +21,14 @@ // ==== DRIVING ==== - +/** + * Construct a DriveForward Command + * @param drive_sys the drive system we are commanding + * @param feedback the feedback controller we are using to execute the drive + * @param inches how far forward to drive + * @param dir the direction to drive + * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at +*/ DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed): drive_sys(drive_sys), feedback(feedback), inches(inches), dir(dir), max_speed(max_speed) {} @@ -35,8 +42,13 @@ bool DriveForwardCommand::run() { } -// Turn Degrees - +/** + * Construct a TurnDegreesCommand Command + * @param drive_sys the drive system we are commanding + * @param feedback the feedback controller we are using to execute the turn + * @param degrees how many degrees to rotate + * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at +*/ TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed): drive_sys(drive_sys), feedback(feedback), degrees(degrees), max_speed(max_speed) {} @@ -50,8 +62,15 @@ bool TurnDegreesCommand::run() { } -// Drive to Point - +/** + * Construct a DriveForward Command + * @param drive_sys the drive system we are commanding + * @param feedback the feedback controller we are using to execute the drive + * @param x where to drive in the x dimension + * @param y where to drive in the y dimension + * @param dir the direction to drive + * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at +*/ DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed): drive_sys(drive_sys), feedback(feedback), x(x), y(y), dir(dir), max_speed(max_speed) {} @@ -65,8 +84,13 @@ bool DriveToPointCommand::run() { } -// Turn to Heading - +/** + * Construct a TurnToHeadingCommand Command + * @param drive_sys the drive system we are commanding + * @param feedback the feedback controller we are using to execute the drive + * @param heading_deg the heading to turn to in degrees + * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at +*/ TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double max_speed): drive_sys(drive_sys), feedback(feedback), heading_deg(heading_deg), max_speed(max_speed) {} @@ -80,8 +104,10 @@ bool TurnToHeadingCommand::run() { } -// Stop - +/** + * Construct a DriveStop Command + * @param drive_sys the drive system we are commanding + */ DriveStopCommand::DriveStopCommand(TankDrive &drive_sys): drive_sys(drive_sys) {} From 703d7586eef146c9e3cbbdec943806eef1e5dc04 Mon Sep 17 00:00:00 2001 From: Victor Rabinovich Date: Wed, 25 Jan 2023 20:01:36 -0500 Subject: [PATCH 131/243] Documentation Added some documentation listed as missing by Doxygen --- include/subsystems/flywheel.h | 2 ++ include/subsystems/odometry/odometry_base.h | 25 +++++++++++++++++++++ src/subsystems/flywheel.cpp | 4 ++++ 3 files changed, 31 insertions(+) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index fbcd4db..c4babce 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -135,6 +135,8 @@ class Flywheel{ /** * Spin motors using voltage; defaults forward at 12 volts * FOR USE BY OPCONTROL AND AUTONOMOUS - this only applies if the RPM thread is not running + * @param speed - speed (between -1 and 1) to set the motor + * @param dir - direction that the motor moves in; defaults to forward */ void spin_manual(double speed, directionType dir=fwd); diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index 862dc85..f4cf7de 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -90,17 +90,42 @@ class OdometryBase bool end_task = false; + /** + * Get the current speed + */ double get_speed(); + + /** + * Get the current acceleration + */ double get_accel(); + /** + * Get the current angular speed in degrees + */ double get_angular_speed_deg(); + + /** + * Get the current angular acceleration in degrees + */ double get_angular_accel_deg(); + /** + * Zeroed position. X=0, Y=0, Rotation= 90 degrees + */ inline static constexpr position_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}; protected: vex::task *handle; + + /** + * Mutex to control multithreading + */ vex::mutex mut; + + /** + * Current position of the robot in terms of x,y,rotation + */ position_t current_pos; double speed, accel, ang_speed_deg, ang_accel_deg; diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 2cd7990..c098ea9 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -79,6 +79,7 @@ bool Flywheel::isTaskRunning() { return taskRunning; } /** * Returns a POINTER TO the motors; not currently used. +* @return motorPointer -pointer to the motors */ motor_group* Flywheel::getMotors() { return &motors; } // TODO -- Remove? @@ -90,6 +91,7 @@ double Flywheel::getRPM() { return ratio * motors.velocity(velocityUnits::rpm); /** * Returns a POINTER TO the PID; not currently used. +* @return pidPointer -pointer to the PID */ PID* Flywheel::getPID() { return &pid; } // TODO -- Remove? @@ -234,6 +236,8 @@ void Flywheel::spin_raw(double speed, directionType dir){ /** * Spin motors using voltage; defaults forward at 12 volts * FOR USE BY OPCONTROL AND AUTONOMOUS - this only applies if the RPM thread is not running +* @param speed - speed (between -1 and 1) to set the motor +* @param dir - direction that the motor moves in; defaults to forward */ void Flywheel::spin_manual(double speed, directionType dir){ if(!taskRunning) motors.spin(dir, speed * 12, voltageUnits::volt); From b856e43b9654433af25b4468d758a9bd4efa8841 Mon Sep 17 00:00:00 2001 From: cowsed Date: Wed, 25 Jan 2023 22:00:52 -0500 Subject: [PATCH 132/243] Documentation from richie --- include/subsystems/lift.h | 6 ++ include/subsystems/odometry/odometry_3wheel.h | 8 +-- include/subsystems/odometry/odometry_base.h | 30 +++++++-- include/subsystems/odometry/odometry_tank.h | 11 +++- include/subsystems/tank_drive.h | 64 ++++++++++++------- .../utils/command_structure/drive_commands.h | 5 ++ .../command_structure/flywheel_commands.h | 6 +- include/utils/feedback_base.h | 1 - include/utils/feedforward.h | 16 +++-- include/utils/generic_auto.h | 9 +++ include/utils/pid.h | 50 +++++++++++---- include/utils/pure_pursuit.h | 5 +- include/utils/vector2d.h | 17 ++++- src/subsystems/flywheel.cpp | 13 ---- src/subsystems/odometry/odometry_3wheel.cpp | 2 - src/subsystems/odometry/odometry_tank.cpp | 24 ++++--- .../command_structure/flywheel_commands.cpp | 8 +-- 17 files changed, 186 insertions(+), 89 deletions(-) diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index f99bec6..947c7a3 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -22,6 +22,12 @@ class Lift { public: + /** + * lift_cfg_t holds the physical parameter specifications of a lify system. + * includes: + * - maximum speeds for the system + * - softstops to stop the lift from hitting the hard stops too hard + */ struct lift_cfg_t { double up_speed, down_speed; diff --git a/include/subsystems/odometry/odometry_3wheel.h b/include/subsystems/odometry/odometry_3wheel.h index 44db64a..f66da93 100644 --- a/include/subsystems/odometry/odometry_3wheel.h +++ b/include/subsystems/odometry/odometry_3wheel.h @@ -35,13 +35,13 @@ class Odometry3Wheel : public OdometryBase /** * odometry3wheel_cfg_t holds all the specifications for how to calculate position with 3 encoders - * see the wiki for what exactly each of these parameters measures + * See the core wiki for what exactly each of these parameters measures */ typedef struct { - double wheelbase_dist; - double off_axis_center_dist; - double wheel_diam; + double wheelbase_dist; /**< distance from the center of the left wheel to the center of the right wheel*/ + double off_axis_center_dist; /**< distance from the center of the robot to the center off axis wheel*/ + double wheel_diam; /**< the diameter of the tracking wheel*/ } odometry3wheel_cfg_t; diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index f4cf7de..1ba75f0 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -12,9 +12,9 @@ */ typedef struct { - double x; - double y; - double rot; + double x; ///< x position in the world + double y; ///< y position in the world + double rot; ///< rotation in the world } position_t; /** @@ -42,16 +42,19 @@ class OdometryBase /** * Gets the current position and rotation + * @return the position that the odometry believes the robot is at */ position_t get_position(void); /** * Sets the current position of the robot + * @param newpos the new position that the odometry will believe it is at */ virtual void set_position(const position_t &newpos=zero_pos); /** * Update the current position on the field based on the sensors + * @return the location that the robot is at after the odometry does its calculations */ virtual position_t update() = 0; @@ -73,11 +76,17 @@ class OdometryBase /** * Get the distance between two points + * @param pos1 distance from this point + * @param pos2 to this point + * @return the euclidean distance between pos1 and pos2 */ static double pos_diff(position_t pos1, position_t pos2); /** * Get the change in rotation between two points + * @param pos1 position with initial rotation + * @param pos2 position with final rotation + * @return change in rotation between pos1 and pos2 */ static double rot_diff(position_t pos1, position_t pos2); @@ -85,6 +94,9 @@ class OdometryBase * Get the smallest difference in angle between a start heading and end heading. * Returns the difference between -180 degrees and +180 degrees, representing the robot * turning left or right, respectively. + * @param start_deg intitial angle (degrees) + * @param end_deg final angle (degrees) + * @return the smallest angle from the initial to the final angle. This takes into account the wrapping of rotations around 360 degrees */ static double smallest_angle(double start_deg, double end_deg); @@ -92,21 +104,25 @@ class OdometryBase /** * Get the current speed + * @return the speed at which the robot is moving and grooving (inch/s) */ double get_speed(); /** * Get the current acceleration + * @return the acceleration rate of the robot (inch/s^2) */ double get_accel(); /** * Get the current angular speed in degrees + * @return the angular velocity at which we are turning (deg/s) */ double get_angular_speed_deg(); /** * Get the current angular acceleration in degrees + * @return the angular acceleration at which we are turning (deg/s^2) */ double get_angular_accel_deg(); @@ -116,6 +132,9 @@ class OdometryBase inline static constexpr position_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}; protected: + /** + * handle to the vex task that is running the odometry code + */ vex::task *handle; /** @@ -128,5 +147,8 @@ class OdometryBase */ position_t current_pos; - double speed, accel, ang_speed_deg, ang_accel_deg; + double speed; /**< the speed at which we are travelling (inch/s)*/ + double accel; /**< the rate at which we are accelerating (inch/s^2)*/ + double ang_speed_deg; /**< the speed at which we are turning (deg/s)*/ + double ang_accel_deg; /**< the rate at which we are accelerating our turn (deg/s^2)*/ }; \ No newline at end of file diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index a0b115d..2a2a92f 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -21,26 +21,33 @@ class OdometryTank : public OdometryBase * Initialize the Odometry module, calculating position from the drive motors. * @param left_side The left motors * @param right_side The right motors + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). */ OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true); /** - * Initialize the Odometry module, calculating posiiton from encoders on "dead wheels" + * Initialize the Odometry module, calculating position from the drive motors. * @param left_enc The left motors * @param right_enc The right motors + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). */ + OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true); /** * Update the current position on the field based on the sensors + * @return the position that odometry has calculated itself to be at */ position_t update() override; - + /** + * set_position tells the odometry to place itself at a position + * @param newpos the position the odometry will take + */ void set_position(const position_t &newpos=zero_pos) override; diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 5c20e2c..77da22c 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -25,6 +25,10 @@ class TankDrive /** * Create the TankDrive object + * @param left_motors left side drive motors + * @param right_motors right side drive motors + * @param config the configuration specification defining physical dimensions about the robot. See robot_specs_t for more info + * @param odom an odometry system to track position and rotation. this is necessary to execute autonomous paths */ TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom=NULL); @@ -38,6 +42,10 @@ class TankDrive * right_motors controls the right motors. * * left_motors and right_motors are in "percent": -1.0 -> 1.0 + * @param left the percent to run the left motors + * @param right the percent to run the right motors + * @param power modifies the input velocities left^power, right^power + * @param is_driver default false. if true uses motor percentage. if false uses plain percentage of maximum voltage */ void drive_tank(double left, double right, int power=1, bool isdriver=false); @@ -46,36 +54,39 @@ class TankDrive * left_right controls the turning. * * left_motors and right_motors are in "percent": -1.0 -> 1.0 + * Drive the robot using differential style controls. left_motors controls the left motors, + * right_motors controls the right motors. + * + * left_motors and right_motors are in "percent": -1.0 -> 1.0 + * @param left the percent to run the left motors + * @param right the percent to run the right motors + * @param power modifies the input velocities left^power, right^power */ void drive_arcade(double forward_back, double left_right, int power=1); /** - * Use odometry to automatically drive the robot to a point on the field. - * X and Y is the final point we want the robot. + * Use odometry to drive forward a certain distance using a custom feedback controller * * Returns whether or not the robot has reached it's destination. - * @param x the x position of the target - * @param y the y position of the target + * @param inches the distance to drive forward * @param dir the direction we want to travel forward and backward - * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param feedback the custom feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ bool drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed=1); + /** - * Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed - * of percent_speed (-1.0 -> 1.0) + * Autonomously drive the robot forward a certain distance * - * Uses the specified feedback for it's control. * - * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw - * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param inches degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw + * @param dir the direction we want to travel forward and backward * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ - bool drive_forward(double inches, directionType dir, double max_speed=1); /** - * Autonomously turn the robot X degrees to the right (negative for left), with a maximum motor speed + * Autonomously turn the robot X degrees counterclockwise (negative for clockwise), with a maximum motor speed * of percent_speed (-1.0 -> 1.0) * * Uses PID + Feedforward for it's control. @@ -85,6 +96,7 @@ class TankDrive * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ bool turn_degrees(double degrees, Feedback &feedback, double max_speed=1); + /** * Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed * of percent_speed (-1.0 -> 1.0) @@ -92,9 +104,9 @@ class TankDrive * Uses the defualt turning feedback of the drive system. * * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw - * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - */ bool turn_degrees(double degrees, double max_speed=1); + */ + bool turn_degrees(double degrees, double max_speed=1); /** * Use odometry to automatically drive the robot to a point on the field. @@ -147,7 +159,11 @@ class TankDrive /** * Create a curve for the inputs, so that drivers have more control at lower speeds. - * Curves are exponential, with the deault being squaring the inputs. + * Curves are exponential, with the default being squaring the inputs. + * + * @param input the input before modification + * @param power the power to raise input to + * @return input ^ power (accounts for negative inputs and odd numbered powers) */ static double modify_inputs(double input, int power=2); @@ -164,17 +180,17 @@ class TankDrive bool pure_pursuit(std::vector path, directionType dir, double radius, double res, Feedback &feedback, double max_speed=1); private: - motor_group &left_motors; - motor_group &right_motors; + motor_group &left_motors; ///< left drive motors + motor_group &right_motors; ///< right drive motors - PID correction_pid; - Feedback *drive_default_feedback = NULL; - Feedback *turn_default_feedback = NULL; + PID correction_pid; ///< PID controller used to drive in as straight a line as possible + Feedback *drive_default_feedback = NULL; ///< feedback to use to drive if none is specified + Feedback *turn_default_feedback = NULL; ///< feedback to use to turn if none is specified - OdometryBase *odometry; + OdometryBase *odometry; ///< odometry system to track position and rotation. necessary for autonomous driving - robot_specs_t &config; + robot_specs_t &config; ///< configuration holding physical dimensions of the robot. see robot_specs_t for more information - bool func_initialized = false; - bool is_pure_pursuit = false; + bool func_initialized = false; ///< used to control initialization of autonomous driving. (you only wan't to set the target once, not every iteration that you're driving) + bool is_pure_pursuit = false; ///< true if we are driving with a pure pursuit system }; diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index a544811..a6a2f45 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -170,6 +170,11 @@ class DriveStopCommand: public AutoCommand { */ class OdomSetPosition: public AutoCommand { public: + /** + * constructs a new OdomSetPosition command + * @param odom the odometry system we are setting + * @param newpos the position we are telling the odometry to take. defaults to (0, 0), angle = 90 + */ OdomSetPosition(OdometryBase &odom, const position_t &newpos=OdometryBase::zero_pos); /** diff --git a/include/utils/command_structure/flywheel_commands.h b/include/utils/command_structure/flywheel_commands.h index efe59f9..c0a090b 100644 --- a/include/utils/command_structure/flywheel_commands.h +++ b/include/utils/command_structure/flywheel_commands.h @@ -58,7 +58,7 @@ class WaitUntilUpToSpeedCommand: public AutoCommand { Flywheel &flywheel; // if the actual speed is equal to the desired speed +/- this value, we are ready to fire - int threshhold_rpm; + int threshold_rpm; }; /** @@ -93,6 +93,10 @@ class FlywheelStopCommand: public AutoCommand { */ class FlywheelStopMotorsCommand: public AutoCommand { public: + /** + * Construct a FlywheeStopMotors Command + * @param flywheel the flywheel system we are commanding + */ FlywheelStopMotorsCommand(Flywheel &flywheel); /** diff --git a/include/utils/feedback_base.h b/include/utils/feedback_base.h index 3096520..a716f53 100644 --- a/include/utils/feedback_base.h +++ b/include/utils/feedback_base.h @@ -37,7 +37,6 @@ class Feedback * * @param lower Upper limit * @param upper Lower limit - * @return double */ virtual void set_limits(double lower, double upper) = 0; diff --git a/include/utils/feedforward.h b/include/utils/feedforward.h index e61000f..2592107 100644 --- a/include/utils/feedforward.h +++ b/include/utils/feedforward.h @@ -31,15 +31,19 @@ class FeedForward public: /** - * kS - Coefficient to overcome static friction: the point at which the motor *starts* to move. - * kV - Veclocity coefficient: the power required to keep the mechanism in motion. Multiplied by the requested velocity. - * kA - Acceleration coefficient: the power required to change the mechanism's speed. Multiplied by the requested acceleration. - * kG - Gravity coefficient: only needed for lifts. The power required to overcome gravity and stay at steady state. - * Should relate to acceleration due to gravity and mass of the lift. + * ff_config_t holds the parameters to make the theoretical model of a real world system + * equation is of the form + * kS if the system is not stopped, 0 otherwise + * + kV * desired velocity + * + kA * desired acceleration + * + kG */ typedef struct { - double kS, kV, kA, kG; + double kS; /**< Coefficient to overcome static friction: the point at which the motor *starts* to move.*/ + double kV; /**< Veclocity coefficient: the power required to keep the mechanism in motion. Multiplied by the requested velocity.*/ + double kA; /**< kA - Acceleration coefficient: the power required to change the mechanism's speed. Multiplied by the requested acceleration.*/ + double kG; /**< kG - Gravity coefficient: only needed for lifts. The power required to overcome gravity and stay at steady state.*/ } ff_config_t; diff --git a/include/utils/generic_auto.h b/include/utils/generic_auto.h index 665c28f..1cdffe7 100644 --- a/include/utils/generic_auto.h +++ b/include/utils/generic_auto.h @@ -32,11 +32,20 @@ class GenericAuto /** * Add a new state to the autonomous via function point of type "bool (ptr*)()" + * @param state_ptr the function to run */ void add(state_ptr); + /** + * Add a new state to the autonomous via function point of type "bool (ptr*)()" that will run asynchronously + * @param state_ptr the function to run + */ void add_async(state_ptr); + /** + * add_delay adds a period where the auto system will simply wait for the specified time + * @param ms how long to wait in milliseconds + */ void add_delay(int ms); private: diff --git a/include/utils/pid.h b/include/utils/pid.h index 32afd38..8c021b5 100644 --- a/include/utils/pid.h +++ b/include/utils/pid.h @@ -28,26 +28,30 @@ class PID : Feedback */ enum ERROR_TYPE{ LINEAR, - ANGULAR + ANGULAR // assumes degrees }; /** * pid_config_t holds the configuration parameters for a pid controller * In addtion to the constant of proportional, integral and derivative, these parameters include: - * - deadband - at what point are we close enough to be finished + * - deadband - * - on_target_time - for how long do we have to be at the target to stop * As well, pid_config_t holds an error type which determines whether errors should be calculated as if the sensor position is a measure of distance or an angle */ struct pid_config_t { - double p, i, d; - double deadband, on_target_time; - ERROR_TYPE error_method; + double p; ///< proportional coeffecient p * error() + double i; ///< integral coeffecient i * integral(error) + double d; ///< derivitave coeffecient d * derivative(error) + double deadband; ///< at what threshold are we close enough to be finished + double on_target_time; ///< the time in seconds that we have to be on target for to say we are officially at the target + ERROR_TYPE error_method; ///< Linear or angular. wheter to do error as a simple subtraction or to wrap }; /** * Create the PID object + * @param config the configuration data for this controller */ PID(pid_config_t &config); @@ -57,29 +61,36 @@ class PID : Feedback * Update the setpoint and reset integral accumulation * * start_pt can be safely ignored in this feedback controller + * @param start_pt commpletely ignored for PID. necessary to satisfy Feedback base + * @param set_pt sets the target of the PID controller */ void init(double start_pt, double set_pt) override; /** * Update the PID loop by taking the time difference from last update, * and running the PID formula with the new sensor data + * @param sensorVal update the PID controller with the most recent sensor measurement + * @return the updated Out value of the controller (voltage, RPM, whatever the PID controller is controlling) */ double update(double sensorVal) override; /** * Gets the current PID out value, from when update() was last run + * @return the Out value of the controller (voltage, RPM, whatever the PID controller is controlling) */ double get() override; /** * Set the limits on the PID out. The PID out will "clip" itself to be * between the limits. + * @param lower the lower limit. the PID controller will never command the output go below `lower` + * @param upper the upper limit. the PID controller will never command the output go higher than `upper` */ void set_limits(double lower, double upper) override; /** - * Returns true if the loop is within [deadband] for [on_target_time] - * seconds + * Checks if the PID controller is on target. + * @return true if the loop is within [deadband] for [on_target_time] seconds */ bool is_on_target() override; @@ -90,29 +101,40 @@ class PID : Feedback /** * Get the delta between the current sensor data and the target + * @return the error calculated. how it is calculated depends on error_method specified in pid_config_t */ double get_error(); /** * Get the PID's target + * @return the target the PID controller is trying to achieve */ double get_target(); /** * Set the target for the PID loop, where the robot is trying to end up + * @param target the sensor reading we would like to achieve */ void set_target(double target); private: - pid_config_t &config; + pid_config_t &config; ///< configuration struct for this controller. see pid_config_t for information about what this contains - double last_error = 0, accum_error = 0; - double last_time = 0, on_target_last_time = 0; - double lower_limit = 0, upper_limit = 0; + double last_error = 0; ///< the error measured on the last iteration of update() + double accum_error = 0; ///< the integral of error over time since we called init() + + double last_time = 0; ///< the time measured the last time update() was called + double on_target_last_time = 0; ///< the time at which we started being on target + + double lower_limit = 0; ///< the PID controller will never set a target to go lower than this + double upper_limit = 0; ///< the PID controller will never set a target to go higher than this + + double target = 0; ///< the target position of the PID controller (lower_limit <= target <= upper_limit) + double sensor_val = 0; ///< the last recorded value of the sensor we use to feed the PID controller + double out = 0; ///< the last calculated output value. we save it here so that we don't have to recalculate if we ask for it more than once between update() calls - double target = 0, sensor_val = 0, out = 0; - bool is_checking_on_target = false; + bool is_checking_on_target = false; ///< true if the sensor reading is within target +/- deadband - timer pid_timer; + timer pid_timer; ///< used for calculating integrals and derivatives in line with the real world times and checking the time we are on target }; diff --git a/include/utils/pure_pursuit.h b/include/utils/pure_pursuit.h index 64c56dc..e14f8f6 100644 --- a/include/utils/pure_pursuit.h +++ b/include/utils/pure_pursuit.h @@ -19,7 +19,10 @@ namespace PurePursuit { return a * pow((x - x_start), 3) + b * pow((x - x_start), 2) + c * (x - x_start) + d; } }; - + /** + * a position along the hermite path + * contains a position and orientation information that the robot would be at at this point + */ struct hermite_point { double x; diff --git a/include/utils/vector2d.h b/include/utils/vector2d.h index d2e672e..2162c97 100644 --- a/include/utils/vector2d.h +++ b/include/utils/vector2d.h @@ -19,14 +19,22 @@ class Vector2D */ struct point_t { - double x, y; + double x, y; ///< x and y position in space + + /** + * dist calculates the euclidian distance using the pythagorean theorem + * @return the euclidian distance between this and other + */ double dist(const point_t other) { return sqrt(pow(this->x - other.x, 2) + pow(this->y - other.y, 2)); } - // Vector2D addition operation on points + /** + * Vector2D addition operation on points + * @return this + other (this.x + other.x, this.y + other.y) + */ point_t operator+(const point_t &other) { point_t p @@ -37,7 +45,10 @@ class Vector2D return p; } - // Vector2D subtraction operation on points + /** + * Vector2D subtraction operation on points + * @return this - other (this.x - other.x, this.y - other.y) + */ point_t operator-(const point_t &other) { point_t p diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index c098ea9..bdc1a6a 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -31,43 +31,30 @@ FeedForward::ff_config_t empty_ff = FeedForward::ff_config_t{}; /** * Create the Flywheel object using PID + feedforward for control. -* @param motors - pointer to the motors on the fly wheel -* @param pid_config - pointer the pid config -* @param ff_config - pointer to the feedforward config -* @param ratio - ratio of the whatever just multiplies the velocity */ Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio) :motors(motors), pid(pid_config), ff(ff_config), ratio(ratio), control_style(PID_Feedforward) { } /** * Create the Flywheel object using only feedforward for control -* @param motors - pointer to the motors on the fly wheel -* @param ff_config - pointer to the feedforward config -* @param ratio - ratio of the whatever just multiplies the velocity */ Flywheel::Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio) :motors(motors), pid(empty_pid), ff(ff_config), ratio(ratio), control_style(Feedforward) {} /** * Create the Flywheel object using Take Back Half for control -* @param motors - pointer to the motors on the fly wheel -* @param TBH_gain - the TBH control paramater -* @param ratio - ratio of the whatever just multiplies the velocity */ Flywheel::Flywheel(motor_group &motors, const double TBH_gain, const double ratio) :motors(motors), pid(empty_pid), ff(empty_ff), TBH_gain(TBH_gain), ratio(ratio), control_style(Take_Back_Half) {} /** * Create the Flywheel object using Bang Bang for control -* @param motors - pointer to the motors on the fly wheel -* @param ratio - ratio of the whatever just multiplies the velocity */ Flywheel::Flywheel(motor_group &motors, const double ratio) :motors(motors), pid(empty_pid), ff(empty_ff), ratio(ratio), control_style(Bang_Bang) {} /** * Return the current value that the RPM should be set to -* @return RPM = the target rpm */ double Flywheel::getDesiredRPM() { return RPM; } diff --git a/src/subsystems/odometry/odometry_3wheel.cpp b/src/subsystems/odometry/odometry_3wheel.cpp index 1dc2ecf..004354f 100644 --- a/src/subsystems/odometry/odometry_3wheel.cpp +++ b/src/subsystems/odometry/odometry_3wheel.cpp @@ -133,8 +133,6 @@ position_t Odometry3Wheel::calculate_new_pos(double lside_delta_deg, double rsid * * It is assumed the gear ratio and encoder PPR have been set correctly * - * @param con Controller reference, for screen and button control - * @param drive Drivetrain reference for robot control */ void Odometry3Wheel::tune(vex::controller &con, TankDrive &drive) { diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 7281cfc..3d4414c 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -1,22 +1,26 @@ #include "../core/include/subsystems/odometry/odometry_tank.h" /** - * Initialize the Odometry module, calculating position from the drive motors. - * @param left_side The left motors - * @param right_side The right motors - * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. - */ +* Initialize the Odometry module, calculating position from the drive motors. +* @param left_side The left motors +* @param right_side The right motors +* @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained +* @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. +* @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). +*/ OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu, bool is_async) : OdometryBase(is_async), left_side(&left_side), right_side(&right_side), left_enc(NULL), right_enc(NULL), imu(imu), config(config) { } /** - * Initialize the Odometry module, calculating posiiton from encoders on "dead wheels" - * @param left_enc The left motors - * @param right_enc The right motors - * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. - */ +* Initialize the Odometry module, calculating position from the drive motors. +* @param left_enc The left motors +* @param right_enc The right motors +* @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained +* @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. +* @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). +*/ OdometryTank::OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu, bool is_async) : OdometryBase(is_async), left_side(NULL), right_side(NULL), left_enc(&left_enc), right_enc(&right_enc), imu(imu), config(config) { diff --git a/src/utils/command_structure/flywheel_commands.cpp b/src/utils/command_structure/flywheel_commands.cpp index 3d027b2..a4aa4d0 100644 --- a/src/utils/command_structure/flywheel_commands.cpp +++ b/src/utils/command_structure/flywheel_commands.cpp @@ -15,12 +15,12 @@ bool SpinRPMCommand::run() { return true; } -WaitUntilUpToSpeedCommand::WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshhold_rpm): - flywheel(flywheel), threshhold_rpm(threshhold_rpm) {} +WaitUntilUpToSpeedCommand::WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshold_rpm): + flywheel(flywheel), threshold_rpm(threshold_rpm) {} bool WaitUntilUpToSpeedCommand::run() { - // If we're withing the specified threshhold, we're ready to fire - if (fabs(flywheel.getDesiredRPM() - flywheel.getRPM()) < threshhold_rpm){ + // If we're withing the specified threshold, we're ready to fire + if (fabs(flywheel.getDesiredRPM() - flywheel.getRPM()) < threshold_rpm){ return true; } // else, keep waiting From 050ecf518952c0315782efae07559d657f27ae3c Mon Sep 17 00:00:00 2001 From: cowsed Date: Wed, 25 Jan 2023 22:04:50 -0500 Subject: [PATCH 133/243] merge victors docs into mine --- include/utils/vector2d.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/utils/vector2d.h b/include/utils/vector2d.h index 2162c97..1bb2490 100644 --- a/include/utils/vector2d.h +++ b/include/utils/vector2d.h @@ -23,7 +23,7 @@ class Vector2D /** - * dist calculates the euclidian distance using the pythagorean theorem + * dist calculates the euclidian distance between this point and another point using the pythagorean theorem * @return the euclidian distance between this and other */ double dist(const point_t other) From 56967afb9110cde8b93fdbae3bbc94e84b2d4755 Mon Sep 17 00:00:00 2001 From: cowsed Date: Wed, 25 Jan 2023 22:04:58 -0500 Subject: [PATCH 134/243] merge victors docs into richies pt2 --- src/utils/vector2d.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/utils/vector2d.cpp b/src/utils/vector2d.cpp index 6d8ff96..c462864 100644 --- a/src/utils/vector2d.cpp +++ b/src/utils/vector2d.cpp @@ -75,6 +75,7 @@ Vector2D::point_t Vector2D::point() /** * Correctly add vectors together with the + operator + * @param &other -The point on which to do the operation */ Vector2D Vector2D::operator+(const Vector2D &other) { @@ -89,6 +90,7 @@ Vector2D Vector2D::operator+(const Vector2D &other) /** * Correctly subtract vectors with the - operator + * @param &other -The point on which to do the operation */ Vector2D Vector2D::operator-(const Vector2D &other) { From a3ea3376f792eb4e5706d14cfb6b18a77dc17cae Mon Sep 17 00:00:00 2001 From: cowsed Date: Wed, 25 Jan 2023 22:08:43 -0500 Subject: [PATCH 135/243] @param &name -> @param name --- src/utils/vector2d.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/utils/vector2d.cpp b/src/utils/vector2d.cpp index c462864..cd7234f 100644 --- a/src/utils/vector2d.cpp +++ b/src/utils/vector2d.cpp @@ -75,7 +75,7 @@ Vector2D::point_t Vector2D::point() /** * Correctly add vectors together with the + operator - * @param &other -The point on which to do the operation + * @param other -The point on which to do the operation */ Vector2D Vector2D::operator+(const Vector2D &other) { @@ -90,7 +90,7 @@ Vector2D Vector2D::operator+(const Vector2D &other) /** * Correctly subtract vectors with the - operator - * @param &other -The point on which to do the operation + * @param other -The point on which to do the operation */ Vector2D Vector2D::operator-(const Vector2D &other) { From 1486116b54dd6b1cf785f5202e133115e0fdc23a Mon Sep 17 00:00:00 2001 From: cowsed Date: Thu, 26 Jan 2023 00:01:22 -0500 Subject: [PATCH 136/243] Final Documentation --- include/robot_specs.h | 16 ++++----- include/subsystems/odometry/odometry_base.h | 13 +++---- include/subsystems/tank_drive.h | 13 ++++--- .../command_structure/flywheel_commands.h | 5 +++ include/utils/generic_auto.h | 8 ++--- include/utils/motion_controller.h | 19 +++++------ include/utils/moving_average.h | 9 +++-- include/utils/pid.h | 6 ++-- include/utils/trapezoid_profile.h | 33 ++++++++++++++---- include/utils/vector2d.h | 23 ++++++++----- src/subsystems/odometry/odometry_base.cpp | 3 ++ src/subsystems/tank_drive.cpp | 34 ++++++++++++------- src/utils/motion_controller.cpp | 26 +++++++------- src/utils/moving_average.cpp | 18 +++++----- src/utils/trapezoid_profile.cpp | 7 +--- src/utils/vector2d.cpp | 24 ++++++++----- 16 files changed, 152 insertions(+), 105 deletions(-) diff --git a/include/robot_specs.h b/include/robot_specs.h index 488627a..baf9877 100644 --- a/include/robot_specs.h +++ b/include/robot_specs.h @@ -10,16 +10,16 @@ */ typedef struct { - double robot_radius; + double robot_radius; ///< if you were to draw a circle with this radius, the robot would be entirely contained within it - double odom_wheel_diam; - double odom_gear_ratio; - double dist_between_wheels; + double odom_wheel_diam; ///< the diameter of the wheels used for + double odom_gear_ratio; ///< the ratio of the odometry wheel to the encoder reading odometry data + double dist_between_wheels; ///< the distance between centers of the central drive wheels - double drive_correction_cutoff; + double drive_correction_cutoff; ///< the distance at which to stop trying to turn towards the target. If we are less than this value, we can continue driving forward to minimize our distance but will not try to spin around to point directly at the target - Feedback *drive_feedback; - Feedback *turn_feedback; - PID::pid_config_t correction_pid; + Feedback *drive_feedback; ///< the default feedback for autonomous driving + Feedback *turn_feedback; ///< the defualt feedback for autonomous turning + PID::pid_config_t correction_pid; ///< the pid controller to keep the robot driving in as straight a line as possible } robot_specs_t; \ No newline at end of file diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index 1ba75f0..65d3001 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -12,8 +12,8 @@ */ typedef struct { - double x; ///< x position in the world - double y; ///< y position in the world + double x; ///< x position in the world + double y; ///< y position in the world double rot; ///< rotation in the world } position_t; @@ -76,11 +76,11 @@ class OdometryBase /** * Get the distance between two points - * @param pos1 distance from this point - * @param pos2 to this point - * @return the euclidean distance between pos1 and pos2 + * @param start_pos distance from this point + * @param end_pos to this point + * @return the euclidean distance between start_pos and end_pos */ - static double pos_diff(position_t pos1, position_t pos2); + double OdometryBase::pos_diff(position_t start_pos, position_t end_pos); /** * Get the change in rotation between two points @@ -100,6 +100,7 @@ class OdometryBase */ static double smallest_angle(double start_deg, double end_deg); + /// @brief end_task is true if we instruct the odometry thread to shut down bool end_task = false; /** diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 77da22c..d55125a 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -45,7 +45,7 @@ class TankDrive * @param left the percent to run the left motors * @param right the percent to run the right motors * @param power modifies the input velocities left^power, right^power - * @param is_driver default false. if true uses motor percentage. if false uses plain percentage of maximum voltage + * @param isdriver default false. if true uses motor percentage. if false uses plain percentage of maximum voltage */ void drive_tank(double left, double right, int power=1, bool isdriver=false); @@ -53,13 +53,10 @@ class TankDrive * Drive the robot using arcade style controls. forward_back controls the linear motion, * left_right controls the turning. * - * left_motors and right_motors are in "percent": -1.0 -> 1.0 - * Drive the robot using differential style controls. left_motors controls the left motors, - * right_motors controls the right motors. + * forward_back and left_right are in "percent": -1.0 -> 1.0 * - * left_motors and right_motors are in "percent": -1.0 -> 1.0 - * @param left the percent to run the left motors - * @param right the percent to run the right motors + * @param forward_back the percent to move forward or backward + * @param left_right the percent to turn left or right * @param power modifies the input velocities left^power, right^power */ void drive_arcade(double forward_back, double left_right, int power=1); @@ -72,6 +69,7 @@ class TankDrive * @param dir the direction we want to travel forward and backward * @param feedback the custom feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @return true when we have reached our target distance */ bool drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed=1); @@ -176,6 +174,7 @@ class TankDrive * @param res The number of points to use along the path; the hermite curve is split up into "res" individual points. * @param feedback The feedback controller to use * @param max_speed Robot's maximum speed throughout the path, between 0 and 1.0 + * @return true when we reach the end of the path */ bool pure_pursuit(std::vector path, directionType dir, double radius, double res, Feedback &feedback, double max_speed=1); diff --git a/include/utils/command_structure/flywheel_commands.h b/include/utils/command_structure/flywheel_commands.h index c0a090b..133c210 100644 --- a/include/utils/command_structure/flywheel_commands.h +++ b/include/utils/command_structure/flywheel_commands.h @@ -16,6 +16,11 @@ */ class SpinRPMCommand: public AutoCommand { public: + /** + * Construct a SpinRPM Command + * @param flywheel the flywheel sys to command + * @param rpm the rpm that we should spin at + */ SpinRPMCommand(Flywheel &flywheel, int rpm); /** diff --git a/include/utils/generic_auto.h b/include/utils/generic_auto.h index 1cdffe7..d344847 100644 --- a/include/utils/generic_auto.h +++ b/include/utils/generic_auto.h @@ -32,15 +32,15 @@ class GenericAuto /** * Add a new state to the autonomous via function point of type "bool (ptr*)()" - * @param state_ptr the function to run + * @param new_state the function to run */ - void add(state_ptr); + void add(state_ptr new_state); /** * Add a new state to the autonomous via function point of type "bool (ptr*)()" that will run asynchronously - * @param state_ptr the function to run + * @param async_state the function to run */ - void add_async(state_ptr); + void add_async(state_ptr async_state); /** * add_delay adds a period where the auto system will simply wait for the specified time diff --git a/include/utils/motion_controller.h b/include/utils/motion_controller.h index 8ee00e7..4341f80 100644 --- a/include/utils/motion_controller.h +++ b/include/utils/motion_controller.h @@ -33,10 +33,10 @@ class MotionController : public Feedback */ typedef struct { - double max_v; - double accel; - PID::pid_config_t pid_cfg; - FeedForward::ff_config_t ff_cfg; + double max_v; ///< the maximum velocity the robot can drive + double accel; ///< the most acceleration the robot can do + PID::pid_config_t pid_cfg; ///< configuration parameters for the internal PID controller + FeedForward::ff_config_t ff_cfg; ///< configuration parameters for the internal } m_profile_cfg_t; /** @@ -53,9 +53,6 @@ class MotionController : public Feedback /** * @brief Initialize the motion profile for a new movement * This will also reset the PID and profile timers. - * - * @param start_pt Movement starting position - * @param end_pt Movement ending posiiton */ void init(double start_pt, double end_pt) override; @@ -63,7 +60,7 @@ class MotionController : public Feedback * @brief Update the motion profile with a new sensor value * * @param sensor_val Value from the sensor - * @return The motor input generated from the motion profile + * @return the motor input generated from the motion profile */ double update(double sensor_val) override; @@ -74,10 +71,10 @@ class MotionController : public Feedback /** * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * if limits are applied, the controller will not target any value below lower or above upper * - * @param lower Upper limit - * @param upper Lower limit - * @return double + * @param lower upper limit + * @param upper lower limiet */ void set_limits(double lower, double upper) override; diff --git a/include/utils/moving_average.h b/include/utils/moving_average.h index 5cc8eaa..c52e946 100644 --- a/include/utils/moving_average.h +++ b/include/utils/moving_average.h @@ -39,13 +39,16 @@ class MovingAverage { */ void add_entry(double n); - /* + /** * Returns the average based off of all the samples collected so far - * @return sum(samples)/numsamples + * @return the calculated average. sum(samples)/numsamples */ double get_average(); - // How many samples the average is made from + /** + * How many samples the average is made from + * @return the number of samples used to calculate this average + */ int get_size(); diff --git a/include/utils/pid.h b/include/utils/pid.h index 8c021b5..c055871 100644 --- a/include/utils/pid.h +++ b/include/utils/pid.h @@ -69,10 +69,10 @@ class PID : Feedback /** * Update the PID loop by taking the time difference from last update, * and running the PID formula with the new sensor data - * @param sensorVal update the PID controller with the most recent sensor measurement - * @return the updated Out value of the controller (voltage, RPM, whatever the PID controller is controlling) + * @param sensor_val the distance, angle, encoder position or whatever it is we are measuring + * @return the new output. What would be returned by PID::get() */ - double update(double sensorVal) override; + double update(double sensor_val) override; /** * Gets the current PID out value, from when update() was last run diff --git a/include/utils/trapezoid_profile.h b/include/utils/trapezoid_profile.h index 11cba85..865d342 100644 --- a/include/utils/trapezoid_profile.h +++ b/include/utils/trapezoid_profile.h @@ -1,13 +1,13 @@ #pragma once /** - * motion_t is a description of 1 dimensional motion at a point in time + * motion_t is a description of 1 dimensional motion at a point in time. */ typedef struct { - double pos; - double vel; - double accel; + double pos; ///< 1d position at this point in time + double vel; ///< 1d velocity at this point in time + double accel; ///< 1d acceleration at this point in time } motion_t; @@ -51,18 +51,37 @@ class TrapezoidProfile */ motion_t calculate(double time_s); + /** + * set_endpts defines a start and end position + * @param start the starting position of the path + * @param end the ending position of the path + */ void set_endpts(double start, double end); + /** + * set_accel sets the acceleration this profile will use (the left and right legs of the trapezoid) + * @param accel the acceleration amount to use + */ void set_accel(double accel); + /** + * sets the maximum velocity for the profile + * (the height of the top of the trapezoid) + * @param max_v the maximum velocity the robot can travel at + */ void set_max_v(double max_v); + /** + * uses the kinematic equations to and specified accel and max_v to figure out how long moving along the profile would take + * @return the time the path will take to travel + */ double get_movement_time(); private: - double start, end; - double max_v, accel; - double time; + double start, end; ///< the start and ending position of the profile + double max_v; ///< the maximum velocity to travel at for this profile + double accel; ///< the rate of acceleration to use for this profile. + double time; ///< the current point in time along the path }; \ No newline at end of file diff --git a/include/utils/vector2d.h b/include/utils/vector2d.h index 1bb2490..7d805c5 100644 --- a/include/utils/vector2d.h +++ b/include/utils/vector2d.h @@ -19,11 +19,13 @@ class Vector2D */ struct point_t { - double x, y; ///< x and y position in space + double x; ///< the x position in space + double y; ///< the y position in space /** * dist calculates the euclidian distance between this point and another point using the pythagorean theorem + * @param other the point to measure the distance from * @return the euclidian distance between this and other */ double dist(const point_t other) @@ -33,6 +35,7 @@ class Vector2D /** * Vector2D addition operation on points + * @param other the point to add on to this * @return this + other (this.x + other.x, this.y + other.y) */ point_t operator+(const point_t &other) @@ -47,6 +50,7 @@ class Vector2D /** * Vector2D subtraction operation on points + * @param other the point_t to subtract from this * @return this - other (this.x - other.x, this.y - other.y) */ point_t operator-(const point_t &other) @@ -111,22 +115,23 @@ class Vector2D */ Vector2D::point_t point(); - /** - * Multiply the components of a vector by x - * (self.x * x, self.y * x) - * @param x the scalar value by which to multiply the components of the vector - * @return the vector after scaling by s - */ +/** + * Scales a Vector2D by a scalar with the * operator + * @param x the value to scale the vector by + * @return the this Vector2D scaled by x +*/ Vector2D operator*(const double &x); /** * Add the components of two vectors together - * Vector2D + Vector2D = (self.x + other.x, self.y + other.y) + * Vector2D + Vector2D = (this.x + other.x, this.y + other.y) + * @param other the vector to add to this * @return the sum of the vectors */ Vector2D operator+(const Vector2D &other); /** * Subtract the components of two vectors together - * Vector2D - Vector2D = (self.x - other.x, self.y - other.y) + * Vector2D - Vector2D = (this.x - other.x, this.y - other.y) + * @param other the vector to subtract from this * @return the difference of the vectors */ Vector2D operator-(const Vector2D &other); diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index 1b1ae35..a2125d6 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -76,6 +76,9 @@ void OdometryBase::set_position(const position_t &newpos) /** * Get the distance between two points + * @param start_pos distance from this point + * @param end_pos to this point + * @return the euclidean distance between start_pos and end_pos */ double OdometryBase::pos_diff(position_t start_pos, position_t end_pos) { diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 2bffaf6..370173a 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -66,12 +66,13 @@ void TankDrive::drive_arcade(double forward_back, double left_right, int power) } /** - * Autonomously drive forward or backwards, X inches infront or behind the robot's current position. - * This driving method is relative, so excessive use may cause the robot to get off course! + * Use odometry to drive forward a certain distance using a custom feedback controller * - * @param inches Distance to drive in a straight line - * @param dir Whether the robot is travelling forwards or backwards - * @param max_speed How fast the robot should travel, 0 -> 1.0 + * Returns whether or not the robot has reached it's destination. + * @param inches the distance to drive forward + * @param dir the direction we want to travel forward and backward + * @param feedback the custom feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed) { @@ -110,12 +111,13 @@ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedba return drive_to_point(pos_setpt.x, pos_setpt.y, dir, feedback, max_speed); } /** - * Autonomously drive forward or backwards, X inches infront or behind the robot's current position. - * This driving method is relative, so excessive use may cause the robot to get off course! - * - * @param inches Distance to drive in a straight line - * @param dir Whether the robot is travelling forwards or backwards - * @param max_speed How fast the robot should travel, 0 -> 1.0 + * Autonomously drive the robot forward a certain distance + * + * + * @param inches degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw + * @param dir the direction we want to travel forward and backward + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @return true if we have finished driving to our point */ bool TankDrive::drive_forward(double inches, directionType dir, double max_speed) { @@ -136,6 +138,7 @@ bool TankDrive::drive_forward(double inches, directionType dir, double max_speed * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @return true if we have turned our target number of degrees */ bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_speed) { @@ -168,6 +171,7 @@ bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_spee * * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @return true if we turned te target number of degrees */ bool TankDrive::turn_degrees(double degrees, double max_speed) { @@ -189,6 +193,7 @@ bool TankDrive::turn_degrees(double degrees, double max_speed) * @param dir the direction we want to travel forward and backward * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @return true if we have reached our target point */ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed) { @@ -314,6 +319,7 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb * @param y the y position of the target * @param dir the direction we want to travel forward and backward * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @return true if we have reached our target point */ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, double max_speed) { @@ -332,8 +338,8 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, doubl * @param heading_deg the heading to which we will turn * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @return true if we have reached our target heading */ - bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double max_speed) { // We can't run the auto drive function without odometry @@ -377,6 +383,7 @@ bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double m * * @param heading_deg the heading to which we will turn * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @return true if we have reached our target heading */ bool TankDrive::turn_to_heading(double heading_deg, double max_speed) { @@ -391,6 +398,9 @@ bool TankDrive::turn_to_heading(double heading_deg, double max_speed) /** * Modify the inputs from the controller by squaring / cubing, etc * Allows for better control of the robot at slower speeds + * @param input the input signal -1 -> 1 + * @param power the power to raise the signal to + * @return input^power accounting for any sign issues that would arise with this naive solution */ double TankDrive::modify_inputs(double input, int power) { diff --git a/src/utils/motion_controller.cpp b/src/utils/motion_controller.cpp index 06f2862..a458f81 100644 --- a/src/utils/motion_controller.cpp +++ b/src/utils/motion_controller.cpp @@ -3,14 +3,14 @@ #include /** - * @brief Construct a new Motion Controller object - * - * @param config The definition of how the robot is able to move - * max_v Maximum velocity the movement is capable of - * accel Acceleration / deceleration of the movement - * pid_cfg Definitions of kP, kI, and kD - * ff_cfg Definitions of kS, kV, and kA - */ +* @brief Construct a new Motion Controller object +* +* @param config The definition of how the robot is able to move +* max_v Maximum velocity the movement is capable of +* accel Acceleration / deceleration of the movement +* pid_cfg Definitions of kP, kI, and kD +* ff_cfg Definitions of kS, kV, and kA +*/ MotionController::MotionController(m_profile_cfg_t &config) : config(config), pid(config.pid_cfg), ff(config.ff_cfg), profile(config.max_v, config.accel) {} @@ -29,11 +29,11 @@ void MotionController::init(double start_pt, double end_pt) } /** - * @brief Update the motion profile with a new sensor value - * - * @param sensor_val Value from the sensor - * @return The motor input generated from the motion profile - */ +* @brief Update the motion profile with a new sensor value +* +* @param sensor_val Value from the sensor +* @return the motor input generated from the motion profile +*/ double MotionController::update(double sensor_val) { motion_t motion = profile.calculate(tmr.time(timeUnits::sec)); diff --git a/src/utils/moving_average.cpp b/src/utils/moving_average.cpp index a36b56b..98ef289 100644 --- a/src/utils/moving_average.cpp +++ b/src/utils/moving_average.cpp @@ -13,16 +13,18 @@ * */ -/* +/** * Create a moving average calculator with 0 as the default value * * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading */ MovingAverage::MovingAverage(int buffer_size) { - buffer = std::vector(buffer_size, 0.0); buffer_index = 0; is_ready = false; + buffer = std::vector(buffer_size, 0.0); + buffer_index = 0; + is_ready = false; } -/* +/** * Create a moving average calculator with a specified default value * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading * @param starting_value The value that the average will be before any data is added @@ -35,7 +37,7 @@ MovingAverage::MovingAverage(int buffer_size, double starting_value) { -/* +/** * Add a reading to the buffer * Before: * [ 1 1 2 2 3 3] => 2 @@ -56,10 +58,10 @@ void MovingAverage::add_entry(double n){ buffer_index%=buffer.size(); } -/* - * Returns the average based off of all the samples collected so far - * @return sum(samples)/numsamples - */ +/** + * How many samples the average is made from + * @return the number of samples used to calculate this average + */ double MovingAverage::get_average(){ double total = 0; diff --git a/src/utils/trapezoid_profile.cpp b/src/utils/trapezoid_profile.cpp index 16915e6..fba334f 100644 --- a/src/utils/trapezoid_profile.cpp +++ b/src/utils/trapezoid_profile.cpp @@ -2,12 +2,7 @@ #include "../core/include/utils/math_util.h" #include -/** - * @brief Construct a new Trapezoid Profile object - * - * @param max_v Maximum velocity the robot can run at - * @param accel Maximum acceleration of the robot - */ + TrapezoidProfile::TrapezoidProfile(double max_v, double accel) : start(0), end(0), max_v(max_v), accel(accel) {} diff --git a/src/utils/vector2d.cpp b/src/utils/vector2d.cpp index cd7234f..322dd6f 100644 --- a/src/utils/vector2d.cpp +++ b/src/utils/vector2d.cpp @@ -61,7 +61,8 @@ Vector2D Vector2D::normalize() } /** - * Returns a point from the vector + * Convert a direction and magnitude representation to an x, y representation + * @return the x, y representation of the vector */ Vector2D::point_t Vector2D::point() { @@ -74,9 +75,12 @@ Vector2D::point_t Vector2D::point() } /** - * Correctly add vectors together with the + operator - * @param other -The point on which to do the operation - */ + * Add the components of two vectors together + * Vector2D + Vector2D = (this.x + other.x, this.y + other.y) + * @param other the vector to add to this + * @return the sum of the vectors +*/ + Vector2D Vector2D::operator+(const Vector2D &other) { point_t p = @@ -89,9 +93,11 @@ Vector2D Vector2D::operator+(const Vector2D &other) } /** - * Correctly subtract vectors with the - operator - * @param other -The point on which to do the operation - */ + * Subtract the components of two vectors together + * Vector2D - Vector2D = (this.x - other.x, this.y - other.y) + * @param other the vector to subtract from this + * @return the difference of the vectors +*/ Vector2D Vector2D::operator-(const Vector2D &other) { point_t p = @@ -103,7 +109,9 @@ Vector2D Vector2D::operator-(const Vector2D &other) } /** - * Multiplies a vector by a double with the * operator + * Scales a Vector2D by a scalar with the * operator + * @param x the value to scale the vector by + * @return the this Vector2D scaled by x */ Vector2D Vector2D::operator*(const double &x) { From 2c0a9088b996b08af2fb7f39039a0b915074bc3f Mon Sep 17 00:00:00 2001 From: cowsed Date: Thu, 26 Jan 2023 00:04:11 -0500 Subject: [PATCH 137/243] FIxed Compile error from typo --- include/subsystems/odometry/odometry_base.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index 65d3001..f1cab19 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -80,7 +80,7 @@ class OdometryBase * @param end_pos to this point * @return the euclidean distance between start_pos and end_pos */ - double OdometryBase::pos_diff(position_t start_pos, position_t end_pos); + static double pos_diff(position_t start_pos, position_t end_pos); /** * Get the change in rotation between two points From 1d72cf37e8b118101db82f1d37dd2c514c780ba9 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 26 Jan 2023 00:52:44 -0500 Subject: [PATCH 138/243] git subrepo push core subrepo: subdir: "core" merged: "43e35b6" upstream: origin: "git@github.com:RIT-VEX-U/Core.git" branch: "master" commit: "43e35b6" git-subrepo: version: "0.4.5" origin: "https://github.com/ingydotnet/git-subrepo" commit: "dbb99be" --- src/subsystems/odometry/odometry_tank.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 3d4414c..a60c369 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -70,7 +70,6 @@ position_t OdometryTank::update() // Get the arclength of the turning circle of the robot double distance_diff = (rside_revs - lside_revs) * PI * config.odom_wheel_diam; - // printf("dist_diff: %f, ", distance_diff); //Use the arclength formula to calculate the angle. Add 90 to make "0 degrees" to starboard angle = ((180.0 / PI) * (distance_diff / config.dist_between_wheels)) + 90; @@ -165,6 +164,7 @@ position_t OdometryTank::calculate_new_pos(robot_specs_t &config, position_t &cu double angle = angle_deg * PI / 180.0; // Degrees to radians // Create a vector from the change in distance in the current direction of the robot + //deg2rad((smallest_angle(curr_pos.rot, angle_deg)/2 + curr_pos.rot, dist_driven) Vector2D chg_vec(angle, dist_driven); // Create a vector from the current position in reference to X,Y=0,0 From 3fb6d963666fafeeb2e1c5c876351f00d3ed7084 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 26 Jan 2023 19:16:03 -0500 Subject: [PATCH 139/243] Initial Drive Tunings --- include/utils/motion_controller.h | 6 ++++++ src/utils/motion_controller.cpp | 14 +++++++++++--- 2 files changed, 17 insertions(+), 3 deletions(-) diff --git a/include/utils/motion_controller.h b/include/utils/motion_controller.h index 4341f80..6683934 100644 --- a/include/utils/motion_controller.h +++ b/include/utils/motion_controller.h @@ -84,6 +84,11 @@ class MotionController : public Feedback */ bool is_on_target() override; + /** + * @return The current postion, velocity and acceleration setpoints + */ + motion_t get_motion(); + /** * This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. * It does this by first calculating the kS (voltage to overcome static friction) by slowly increasing @@ -114,6 +119,7 @@ class MotionController : public Feedback double lower_limit = 0, upper_limit = 0; double out = 0; + motion_t cur_motion; vex::timer tmr; diff --git a/src/utils/motion_controller.cpp b/src/utils/motion_controller.cpp index a458f81..1b495e0 100644 --- a/src/utils/motion_controller.cpp +++ b/src/utils/motion_controller.cpp @@ -36,11 +36,11 @@ void MotionController::init(double start_pt, double end_pt) */ double MotionController::update(double sensor_val) { - motion_t motion = profile.calculate(tmr.time(timeUnits::sec)); - pid.set_target(motion.pos); + cur_motion = profile.calculate(tmr.time(timeUnits::sec)); + pid.set_target(cur_motion.pos); pid.update(sensor_val); - out = pid.get() + ff.calculate(motion.vel, motion.accel); + out = pid.get() + ff.calculate(cur_motion.vel, cur_motion.accel); if(lower_limit != upper_limit) out = clamp(out, lower_limit, upper_limit); @@ -77,6 +77,14 @@ bool MotionController::is_on_target() return (tmr.time(timeUnits::sec) > profile.get_movement_time()) && pid.is_on_target(); } +/** + * @return The current postion, velocity and acceleration setpoints +*/ +motion_t MotionController::get_motion() +{ + return cur_motion; +} + /** * This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. * It does this by first calculating the kS (voltage to overcome static friction) by slowly increasing From 772f851a1d574af91360e8b80ee2a08491bddddd Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 26 Jan 2023 19:21:40 -0500 Subject: [PATCH 140/243] Merge remote-tracking branch 'refs/remotes/origin/main' --- include/subsystems/flywheel.h | 13 +++++++++---- src/subsystems/flywheel.cpp | 33 +++++++++++++++++++++++++++------ 2 files changed, 36 insertions(+), 10 deletions(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index c4babce..3f0202a 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -86,10 +86,14 @@ class Flywheel{ motor_group* getMotors(); /** - * return the current velocity of the flywheel motors, in RPM + * make a measurement of the current RPM of the flywheel motor and return a smoothed version */ - double getRPM(); + double measureRPM(); + /** + * return the current smoothed velocity of the flywheel motors, in RPM + */ + double getRPM(); /** * Returns a POINTER to the PID. */ @@ -174,5 +178,6 @@ class Flywheel{ std::atomic RPM; // Desired RPM of the flywheel. task rpmTask; // task (thread but not) that handles spinning the wheel at a given RPM FlywheelControlStyle control_style; // how the flywheel should be controlled - -}; \ No newline at end of file + double smoothedRPM; + MovingAverage RPM_avger; + }; \ No newline at end of file diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index bdc1a6a..c90bba7 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -2,7 +2,7 @@ * * File: Flywheel.cpp * Purpose: Generalized flywheel class for Core. -* Author: Chris Nokes +* Author: Chris Nokes, Richie Sommers * ********************************************************** * EDIT HISTORY @@ -22,6 +22,8 @@ using namespace vex; +const int FlywheelWindowSize = 30; + /********************************************************* * CONSTRUCTOR, GETTERS, SETTERS *********************************************************/ @@ -33,25 +35,26 @@ FeedForward::ff_config_t empty_ff = FeedForward::ff_config_t{}; * Create the Flywheel object using PID + feedforward for control. */ Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio) - :motors(motors), pid(pid_config), ff(ff_config), ratio(ratio), control_style(PID_Feedforward) { } + :motors(motors), pid(pid_config), ff(ff_config), ratio(ratio), control_style(PID_Feedforward), smoothedRPM(0), RPM_avger(MovingAverage(FlywheelWindowSize)) { + } /** * Create the Flywheel object using only feedforward for control */ Flywheel::Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio) - :motors(motors), pid(empty_pid), ff(ff_config), ratio(ratio), control_style(Feedforward) {} + :motors(motors), pid(empty_pid), ff(ff_config), ratio(ratio), control_style(Feedforward), smoothedRPM(0), RPM_avger(MovingAverage(FlywheelWindowSize)) {} /** * Create the Flywheel object using Take Back Half for control */ Flywheel::Flywheel(motor_group &motors, const double TBH_gain, const double ratio) - :motors(motors), pid(empty_pid), ff(empty_ff), TBH_gain(TBH_gain), ratio(ratio), control_style(Take_Back_Half) {} + :motors(motors), pid(empty_pid), ff(empty_ff), TBH_gain(TBH_gain), ratio(ratio), control_style(Take_Back_Half), smoothedRPM(0), RPM_avger(MovingAverage(FlywheelWindowSize)) {} /** * Create the Flywheel object using Bang Bang for control */ Flywheel::Flywheel(motor_group &motors, const double ratio) - :motors(motors), pid(empty_pid), ff(empty_ff), ratio(ratio), control_style(Bang_Bang) {} + :motors(motors), pid(empty_pid), ff(empty_ff), ratio(ratio), control_style(Bang_Bang), smoothedRPM(0), RPM_avger(MovingAverage(FlywheelWindowSize)) {} /** * Return the current value that the RPM should be set to @@ -74,8 +77,16 @@ motor_group* Flywheel::getMotors() { return &motors; } // TODO -- Remove? * return the current velocity of the flywheel motors, in RPM * @return the measured velocity of the flywheel */ -double Flywheel::getRPM() { return ratio * motors.velocity(velocityUnits::rpm); } +double Flywheel::measureRPM() { + double rawRPM = ratio * motors.velocity(velocityUnits::rpm); + RPM_avger.add_entry(rawRPM); + smoothedRPM = RPM_avger.get_average(); + return smoothedRPM; +} +double Flywheel::getRPM(){ + return smoothedRPM; +} /** * Returns a POINTER TO the PID; not currently used. * @return pidPointer -pointer to the PID @@ -131,6 +142,8 @@ int spinRPMTask_BangBang(void* wheelPointer) { Flywheel* wheel = (Flywheel*) wheelPointer; while(true) { // if it below the RPM, go, otherwise don't + wheel->measureRPM(); + if(wheel->getRPM() < wheel->getDesiredRPM()) { wheel->spin_raw(1, fwd); } @@ -147,6 +160,7 @@ int spinRPMTask_Feedforward(void* wheelPointer) { Flywheel* wheel = (Flywheel*) wheelPointer; // get the pid from the wheel and set its target to the RPM stored in the wheel. while(true) { + wheel->measureRPM(); wheel->updatePID(wheel->getRPM()); // check the current velocity and update the PID with it. double output = wheel->getFeedforwardValue(); wheel->spin_raw(output, fwd); // set the motors to whatever feedforward tells them to do @@ -161,6 +175,7 @@ int spinRPMTask_PID_Feedforward(void* wheelPointer) { Flywheel* wheel = (Flywheel*) wheelPointer; // get the pid from the wheel and set its target to the RPM stored in the wheel. while(true) { + wheel->measureRPM(); wheel->updatePID(wheel->getRPM()); // check the current velocity and update the PID with it. double output = wheel->getPIDValue() + wheel->getFeedforwardValue(); wheel->spin_raw(output, fwd); // set the motors to whatever PID tells them to do @@ -181,6 +196,8 @@ int spinRPMTask_TBH(void* wheelPointer) { double previous_error = 0.0; while (true){ + wheel->measureRPM(); + //reset if set to 0, this keeps the tbh val from screwing us up when we start up again if (wheel->getDesiredRPM()==0){ output = 0; @@ -236,6 +253,10 @@ void Flywheel::spin_manual(double speed, directionType dir){ * @param inputRPM - set the current RPM */ void Flywheel::spinRPM(int inputRPM) { + // setting to 0 is equivelent to stopping + if (inputRPM==0){ + stop(); + } // only run if the RPM is different or it isn't already running if(!taskRunning) { From b286de02c5ac3c21ff5d59841c101fdb7fdda399 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Fri, 27 Jan 2023 00:30:12 -0500 Subject: [PATCH 141/243] Tuned Turn with PID --- include/utils/pid.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/utils/pid.h b/include/utils/pid.h index c055871..b349131 100644 --- a/include/utils/pid.h +++ b/include/utils/pid.h @@ -20,7 +20,7 @@ using namespace vex; * @author Ryan McGee * @date 4/3/2020 */ -class PID : Feedback +class PID : public Feedback { public: /** From 597a7f9ae3efb1bf3a455c9ddf1e6ac71ce2080c Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Fri, 27 Jan 2023 00:33:48 -0500 Subject: [PATCH 142/243] Merge remote-tracking branch 'refs/remotes/origin/main' --- include/utils/command_structure/drive_commands.h | 2 +- src/utils/command_structure/command_controller.cpp | 9 ++++++--- src/utils/command_structure/drive_commands.cpp | 6 ++++++ 3 files changed, 13 insertions(+), 4 deletions(-) diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index a6a2f45..36a2248 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -120,7 +120,7 @@ class DriveToPointCommand: public AutoCommand { */ class TurnToHeadingCommand: public AutoCommand { public: - TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed); + TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed = 1); /** * Run turn_to_heading diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index afcc3ed..7bc4e79 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -34,21 +34,24 @@ void CommandController::add_delay(int ms) { */ void CommandController::run() { AutoCommand *next_cmd; - printf("Beginning Auto. Starting from 1"); + printf("Beginning Auto. Commands 1 to %d\n", command_queue.size()); + fflush(stdout); int command_count = 1; while(!command_queue.empty()) { // retrieve and remove command at the front of the queue next_cmd = command_queue.front(); command_queue.pop(); - printf("Beginning Command %d", command_count); + printf("Beginning Command %d\n", command_count); + fflush(stdout); // run the current command until it returns true while(!next_cmd -> run()) { vexDelay(20); } - printf("Finished Command %d", command_count); + printf("Finished Command %d\n", command_count); + fflush(stdout); command_count++; } } \ No newline at end of file diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index 9f25f96..28f704f 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -123,6 +123,12 @@ bool DriveStopCommand::run() { // ==== ODOMETRY ==== +/** + * Construct an Odometry set pos + * @param odom the odometry system we are setting + * @param newpos the now position to set the odometry to + */ +OdomSetPosition::OdomSetPosition(OdometryBase &odom, const position_t &newpos): odom(odom), newpos(newpos){} bool OdomSetPosition::run() { odom.set_position(newpos); From 72d0dde0a02b5aedb9a62855e24bfe72eea1e317 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Fri, 27 Jan 2023 01:24:49 -0500 Subject: [PATCH 143/243] Fixed mutex issues --- include/subsystems/odometry/odometry_base.h | 2 +- src/subsystems/odometry/odometry_3wheel.cpp | 2 - src/subsystems/odometry/odometry_base.cpp | 15 +++---- src/subsystems/odometry/odometry_tank.cpp | 43 +++++---------------- 4 files changed, 16 insertions(+), 46 deletions(-) diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index f1cab19..25128d8 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -50,7 +50,7 @@ class OdometryBase * Sets the current position of the robot * @param newpos the new position that the odometry will believe it is at */ - virtual void set_position(const position_t &newpos=zero_pos); + virtual void set_position(const position_t& newpos=zero_pos); /** * Update the current position on the field based on the sensors diff --git a/src/subsystems/odometry/odometry_3wheel.cpp b/src/subsystems/odometry/odometry_3wheel.cpp index 004354f..a032512 100644 --- a/src/subsystems/odometry/odometry_3wheel.cpp +++ b/src/subsystems/odometry/odometry_3wheel.cpp @@ -62,7 +62,6 @@ position_t Odometry3Wheel::update() last_ang_speed = ang_speed_local; } - mut.lock(); this->current_pos = updated_pos; if(update_vel_accel) { @@ -71,7 +70,6 @@ position_t Odometry3Wheel::update() this->ang_speed_deg = ang_speed_local; this->ang_accel_deg = ang_accel_local; } - mut.unlock(); return current_pos; } diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index a2125d6..ecbfae0 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -24,7 +24,9 @@ int OdometryBase::background_task(void* ptr) OdometryBase &obj = *((OdometryBase*) ptr); while(!obj.end_task) { + obj.mut.lock(); obj.update(); + obj.mut.unlock(); } return 0; @@ -48,12 +50,7 @@ position_t OdometryBase::get_position(void) mut.lock(); // Create a new struct to pass-by-value - position_t out = - { - .x = current_pos.x, - .y = current_pos.y, - .rot = current_pos.rot - }; + position_t out = current_pos; mut.unlock(); @@ -63,13 +60,11 @@ position_t OdometryBase::get_position(void) /** * Sets the current position of the robot */ -void OdometryBase::set_position(const position_t &newpos) +void OdometryBase::set_position(const position_t& newpos) { mut.lock(); - current_pos.x = newpos.x; - current_pos.y = newpos.y; - current_pos.rot = newpos.rot; + current_pos = newpos; mut.unlock(); } diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index a60c369..8dd3e25 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -45,8 +45,6 @@ void OdometryTank::set_position(const position_t &newpos) */ position_t OdometryTank::update() { - position_t updated_pos; - double lside_revs = 0, rside_revs = 0; if(left_side != NULL && right_side != NULL) @@ -91,58 +89,37 @@ position_t OdometryTank::update() if(angle < 0) angle += 360; - mut.lock(); - position_t current_pos_local = current_pos; - mut.unlock(); - - updated_pos = calculate_new_pos(config, current_pos_local, lside_revs, rside_revs, angle); + current_pos = calculate_new_pos(config, current_pos, lside_revs, rside_revs, angle); - static position_t last_pos = updated_pos; + static position_t last_pos = current_pos; static double last_speed = 0; static double last_ang_speed = 0; static timer tmr; - - double speed_local = 0; - double accel_local = 0; - double ang_speed_local = 0; - double ang_accel_local = 0; bool update_vel_accel = tmr.time(sec) > 0.1; // This loop runs too fast. Only check at LEAST every 1/10th sec if(update_vel_accel) { // Calculate robot velocity - speed_local = pos_diff(updated_pos, last_pos) / tmr.time(sec); + speed = pos_diff(current_pos, last_pos) / tmr.time(sec); // Calculate robot acceleration - accel_local = (speed_local - last_speed) / tmr.time(sec); + accel = (speed - last_speed) / tmr.time(sec); // Calculate robot angular velocity (deg/sec) - ang_speed_local = smallest_angle(updated_pos.rot, last_pos.rot) / tmr.time(sec); + ang_speed_deg = smallest_angle(current_pos.rot, last_pos.rot) / tmr.time(sec); // Calculate robot angular acceleration (deg/sec^2) - ang_accel_local = (ang_speed_local - last_ang_speed) / tmr.time(sec); + ang_accel_deg = (ang_speed_deg - last_ang_speed) / tmr.time(sec); tmr.reset(); - last_pos = updated_pos; - last_speed = speed_local; - last_ang_speed = ang_speed_local; - } - - // Update the class' stored position - mut.lock(); - this->current_pos = updated_pos; - if(update_vel_accel) - { - this->speed = speed_local; - this->accel = accel_local; - this->ang_speed_deg = ang_speed_local; - this->ang_accel_deg = ang_accel_local; + last_pos = current_pos; + last_speed = speed; + last_ang_speed = ang_speed_deg; } - mut.unlock(); - return updated_pos; + return current_pos; } /** From 43a4e08af4388e76d9aa23023675a92316703581 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sat, 28 Jan 2023 20:57:14 -0500 Subject: [PATCH 144/243] MCCCCCCCCCC Final --- src/subsystems/flywheel.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index c90bba7..9a40231 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -22,7 +22,7 @@ using namespace vex; -const int FlywheelWindowSize = 30; +const int FlywheelWindowSize = 2; /********************************************************* * CONSTRUCTOR, GETTERS, SETTERS From 6b0becfbb0c91a91b946070ff27f95eae4519abe Mon Sep 17 00:00:00 2001 From: cowsed Date: Thu, 2 Feb 2023 18:11:06 -0500 Subject: [PATCH 145/243] Merge branch 'main' of https://github.com/RIT-VEX-U/2022-2023-Flynn --- include/utils/moving_average.h | 3 +-- src/utils/moving_average.cpp | 28 +++++++--------------------- 2 files changed, 8 insertions(+), 23 deletions(-) diff --git a/include/utils/moving_average.h b/include/utils/moving_average.h index c52e946..07acc79 100644 --- a/include/utils/moving_average.h +++ b/include/utils/moving_average.h @@ -55,7 +55,6 @@ class MovingAverage { private: int buffer_index; //index of the next value to be overridden std::vector buffer; //all current data readings we've taken - bool is_ready; //if the average is ready to be read (stil can read before this but it will be taken a limited number of samples) - + double current_avg; //the current value of the data }; \ No newline at end of file diff --git a/src/utils/moving_average.cpp b/src/utils/moving_average.cpp index 98ef289..d61695e 100644 --- a/src/utils/moving_average.cpp +++ b/src/utils/moving_average.cpp @@ -21,7 +21,7 @@ MovingAverage::MovingAverage(int buffer_size) { buffer = std::vector(buffer_size, 0.0); buffer_index = 0; - is_ready = false; + current_avg = 0; } /** @@ -32,7 +32,7 @@ MovingAverage::MovingAverage(int buffer_size) { MovingAverage::MovingAverage(int buffer_size, double starting_value) { buffer = std::vector(buffer_size, starting_value); buffer_index = 0; - is_ready = true; + current_avg = starting_value; } @@ -48,14 +48,12 @@ MovingAverage::MovingAverage(int buffer_size, double starting_value) { * @param n the sample that will be added to the moving average. */ void MovingAverage::add_entry(double n){ + current_avg -= buffer[buffer_index]/get_size(); + current_avg += n/get_size(); buffer[buffer_index] = n; + buffer_index++; - // if weve filled the buffer once, then we're ready - if (!is_ready && buffer_index==buffer.size()-1){ - is_ready = true; - } - //wrap around - buffer_index%=buffer.size(); + buffer_index%=get_size(); } /** @@ -63,19 +61,7 @@ void MovingAverage::add_entry(double n){ * @return the number of samples used to calculate this average */ double MovingAverage::get_average(){ - double total = 0; - - int upto = buffer.size(); - if (!is_ready){ //if we're not completely ready, only make average out of the samples we have - upto = buffer_index; - } - - for (int i=0; i Date: Thu, 2 Feb 2023 19:42:07 -0500 Subject: [PATCH 146/243] CommandController Updates Drive commands now take an optional timeout parameter that will stop the command if it does not finish after that amount of time The CommandController also now has a function called last_command_timed_out which returns true if the last command it ran finished by timing out. --- .../utils/command_structure/auto_command.h | 23 +++++++++++++ .../command_structure/command_controller.h | 12 +++++-- .../utils/command_structure/drive_commands.h | 29 ++++++++++++++-- .../command_structure/command_controller.cpp | 34 ++++++++++++++++--- .../command_structure/drive_commands.cpp | 26 +++++++++++--- 5 files changed, 112 insertions(+), 12 deletions(-) diff --git a/include/utils/command_structure/auto_command.h b/include/utils/command_structure/auto_command.h index 8795a68..942c652 100644 --- a/include/utils/command_structure/auto_command.h +++ b/include/utils/command_structure/auto_command.h @@ -10,10 +10,33 @@ class AutoCommand { public: + /** + * Constructs an autocommand with a specified timeout + */ + AutoCommand(double timeout_seconds): timeout_seconds(timeout_seconds){} + /** + * Constructs an autocommand with no timeout + */ + AutoCommand(): timeout_seconds(0.0){} /** * Executes the command * Overridden by child classes * @returns true when the command is finished, false otherwise */ virtual bool run() { return true; } + /** + * What to do if we timeout instead of finishing. timeout is specified by the timeout seconds in the constructor + */ + virtual void on_timeout(){} + /** + * How long to run until we cancel this command. + * If the command is cancelled, on_timeout() is called to allow any cleanup from the function. + * If the timeout_seconds <= 0, no timeout will be applied and this command will run forever + * A timeout can come in handy for some commands that can not reach the end due to some physical limitation such as + * - a drive command hitting a wall and not being able to reach its target + * - a command that waits until something is up to speed that never gets up to speed because of battery voltage + * - something else... + */ + double timeout_seconds; + }; \ No newline at end of file diff --git a/include/utils/command_structure/command_controller.h b/include/utils/command_structure/command_controller.h index f4a8abe..0f6befb 100644 --- a/include/utils/command_structure/command_controller.h +++ b/include/utils/command_structure/command_controller.h @@ -17,9 +17,10 @@ class CommandController { /** * Adds a command to the queue - * @param cmd - AutoCommand to be added + * @param cmd the AutoCommand we want to add to our list + * @param timeout_seconds the number of seconds we will let the command run for. If it exceeds this, we cancel it and run on_timeout. if it is <= 0 no time out will be applied */ - void add(AutoCommand *cmd); + void add(AutoCommand *cmd, double timeout_seconds = 0); /** * Adds a command that will delay progression @@ -34,7 +35,14 @@ class CommandController { * Execute and remove commands in FIFO order */ void run(); + /** + * last_command_timed_out tells how the last command ended + * Use this if you want to make decisions based on the end of the last command + * @return true if the last command timed out. false if it finished regularly + */ + bool last_command_timed_out(); private: std::queue command_queue; + bool command_timed_out = false; }; \ No newline at end of file diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index 36a2248..fda76a7 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -42,6 +42,10 @@ class DriveForwardCommand: public AutoCommand { * @returns true when execution is complete, false otherwise */ bool run() override; + /** + * Cleans up drive system if we time out before finishing + */ + void on_timeout() override; private: // drive system to run the function on @@ -62,7 +66,7 @@ class DriveForwardCommand: public AutoCommand { */ class TurnDegreesCommand: public AutoCommand { public: - TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed); + TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed = 1); /** * Run turn_degrees @@ -70,6 +74,11 @@ class TurnDegreesCommand: public AutoCommand { * @returns true when execution is complete, false otherwise */ bool run() override; + /** + * Cleans up drive system if we time out before finishing + */ + void on_timeout() override; + private: // drive system to run the function on @@ -89,7 +98,7 @@ class TurnDegreesCommand: public AutoCommand { */ class DriveToPointCommand: public AutoCommand { public: - DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed); + DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed = 1); /** * Run drive_to_point @@ -101,6 +110,12 @@ class DriveToPointCommand: public AutoCommand { private: // drive system to run the function on TankDrive &drive_sys; + + /** + * Cleans up drive system if we time out before finishing + */ + void on_timeout() override; + // feedback controller to use Feedback &feedback; @@ -128,6 +143,11 @@ class TurnToHeadingCommand: public AutoCommand { * @returns true when execution is complete, false otherwise */ bool run() override; + /** + * Cleans up drive system if we time out before finishing + */ + void on_timeout() override; + private: // drive system to run the function on @@ -155,6 +175,11 @@ class DriveStopCommand: public AutoCommand { * @returns true when execution is complete, false otherwise */ bool run() override; + /** + * Cleans up drive system if we time out before finishing + */ + void on_timeout() override; + private: // drive system to run the function on diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index 7bc4e79..d5d6b5f 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -12,8 +12,11 @@ /** * Adds a command to the queue + * @param cmd the AutoCommand we want to add to our list + * @param timeout_seconds the number of seconds we will let the command run for. If it exceeds this, we cancel it and run on_timeout */ -void CommandController::add(AutoCommand *cmd) { +void CommandController::add(AutoCommand *cmd, double timeout_seconds) { + cmd->timeout_seconds = timeout_seconds; command_queue.push(cmd); } @@ -34,24 +37,47 @@ void CommandController::add_delay(int ms) { */ void CommandController::run() { AutoCommand *next_cmd; - printf("Beginning Auto. Commands 1 to %d\n", command_queue.size()); + printf("Running Auto. Commands 1 to %d\n", command_queue.size()); fflush(stdout); int command_count = 1; + while(!command_queue.empty()) { // retrieve and remove command at the front of the queue next_cmd = command_queue.front(); command_queue.pop(); + command_timed_out = false; printf("Beginning Command %d\n", command_count); fflush(stdout); - // run the current command until it returns true + + vex::timer timeout_timer; + timeout_timer.reset(); + bool doTimeout = next_cmd->timeout_seconds > 0.0; + + // run the current command until it returns true or we timeout while(!next_cmd -> run()) { vexDelay(20); + + if (!doTimeout){ + continue; + } + + // If we do want to check for timeout, check and end the command if we should + double cmd_elapsed_sec = ((double)timeout_timer.time())/1000.0; + if (cmd_elapsed_sec > next_cmd->timeout_seconds){ + next_cmd->on_timeout(); + command_timed_out = true; + break; + } } - printf("Finished Command %d\n", command_count); + printf("Finished Command %d. Timed out: %s\n", command_count, command_timed_out ? "true" : "false" ); fflush(stdout); command_count++; } +} + +bool CommandController::last_command_timed_out(){ + return command_timed_out; } \ No newline at end of file diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index 28f704f..19f938c 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -40,6 +40,9 @@ DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, Feedback &feedbac bool DriveForwardCommand::run() { return drive_sys.drive_forward(inches, dir, feedback, max_speed); } +void DriveForwardCommand::on_timeout(){ + drive_sys.reset_auto(); +} /** @@ -48,9 +51,9 @@ bool DriveForwardCommand::run() { * @param feedback the feedback controller we are using to execute the turn * @param degrees how many degrees to rotate * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at -*/ + */ TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed): - drive_sys(drive_sys), feedback(feedback), degrees(degrees), max_speed(max_speed) {} + drive_sys(drive_sys), feedback(feedback), degrees(degrees), max_speed(max_speed){} /** * Run turn_degrees @@ -60,6 +63,9 @@ TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, bool TurnDegreesCommand::run() { return drive_sys.turn_degrees(degrees, max_speed); } +void TurnDegreesCommand::on_timeout(){ + drive_sys.reset_auto(); +} /** @@ -70,7 +76,7 @@ bool TurnDegreesCommand::run() { * @param y where to drive in the y dimension * @param dir the direction to drive * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at -*/ + */ DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed): drive_sys(drive_sys), feedback(feedback), x(x), y(y), dir(dir), max_speed(max_speed) {} @@ -82,6 +88,12 @@ DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedbac bool DriveToPointCommand::run() { return drive_sys.drive_to_point(x, y, dir, max_speed); } +/** + * reset the drive system if we don't hit our target +*/ +void DriveToPointCommand::on_timeout(){ + drive_sys.reset_auto(); +} /** @@ -90,7 +102,7 @@ bool DriveToPointCommand::run() { * @param feedback the feedback controller we are using to execute the drive * @param heading_deg the heading to turn to in degrees * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at -*/ + */ TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double max_speed): drive_sys(drive_sys), feedback(feedback), heading_deg(heading_deg), max_speed(max_speed) {} @@ -102,6 +114,12 @@ TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedb bool TurnToHeadingCommand::run() { return drive_sys.turn_to_heading(heading_deg, feedback, max_speed); } +/** + * reset the drive system if we don't hit our target +*/ +void TurnToHeadingCommand::on_timeout(){ + drive_sys.reset_auto(); +} /** From 8a9495788cdcd015dc9bf4097182143c92b4b7f1 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 26 Jan 2023 00:52:44 -0500 Subject: [PATCH 147/243] git subrepo push core subrepo: subdir: "core" merged: "43e35b6" upstream: origin: "git@github.com:RIT-VEX-U/Core.git" branch: "master" commit: "43e35b6" git-subrepo: version: "0.4.5" origin: "https://github.com/ingydotnet/git-subrepo" commit: "dbb99be" --- src/subsystems/odometry/odometry_tank.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 3d4414c..a60c369 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -70,7 +70,6 @@ position_t OdometryTank::update() // Get the arclength of the turning circle of the robot double distance_diff = (rside_revs - lside_revs) * PI * config.odom_wheel_diam; - // printf("dist_diff: %f, ", distance_diff); //Use the arclength formula to calculate the angle. Add 90 to make "0 degrees" to starboard angle = ((180.0 / PI) * (distance_diff / config.dist_between_wheels)) + 90; @@ -165,6 +164,7 @@ position_t OdometryTank::calculate_new_pos(robot_specs_t &config, position_t &cu double angle = angle_deg * PI / 180.0; // Degrees to radians // Create a vector from the change in distance in the current direction of the robot + //deg2rad((smallest_angle(curr_pos.rot, angle_deg)/2 + curr_pos.rot, dist_driven) Vector2D chg_vec(angle, dist_driven); // Create a vector from the current position in reference to X,Y=0,0 From b6ad515967a9c24f4cbcfad6ba2cc257fe508dd0 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 26 Jan 2023 19:16:03 -0500 Subject: [PATCH 148/243] Initial Drive Tunings --- include/utils/motion_controller.h | 6 ++++++ src/utils/motion_controller.cpp | 14 +++++++++++--- 2 files changed, 17 insertions(+), 3 deletions(-) diff --git a/include/utils/motion_controller.h b/include/utils/motion_controller.h index 4341f80..6683934 100644 --- a/include/utils/motion_controller.h +++ b/include/utils/motion_controller.h @@ -84,6 +84,11 @@ class MotionController : public Feedback */ bool is_on_target() override; + /** + * @return The current postion, velocity and acceleration setpoints + */ + motion_t get_motion(); + /** * This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. * It does this by first calculating the kS (voltage to overcome static friction) by slowly increasing @@ -114,6 +119,7 @@ class MotionController : public Feedback double lower_limit = 0, upper_limit = 0; double out = 0; + motion_t cur_motion; vex::timer tmr; diff --git a/src/utils/motion_controller.cpp b/src/utils/motion_controller.cpp index a458f81..1b495e0 100644 --- a/src/utils/motion_controller.cpp +++ b/src/utils/motion_controller.cpp @@ -36,11 +36,11 @@ void MotionController::init(double start_pt, double end_pt) */ double MotionController::update(double sensor_val) { - motion_t motion = profile.calculate(tmr.time(timeUnits::sec)); - pid.set_target(motion.pos); + cur_motion = profile.calculate(tmr.time(timeUnits::sec)); + pid.set_target(cur_motion.pos); pid.update(sensor_val); - out = pid.get() + ff.calculate(motion.vel, motion.accel); + out = pid.get() + ff.calculate(cur_motion.vel, cur_motion.accel); if(lower_limit != upper_limit) out = clamp(out, lower_limit, upper_limit); @@ -77,6 +77,14 @@ bool MotionController::is_on_target() return (tmr.time(timeUnits::sec) > profile.get_movement_time()) && pid.is_on_target(); } +/** + * @return The current postion, velocity and acceleration setpoints +*/ +motion_t MotionController::get_motion() +{ + return cur_motion; +} + /** * This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. * It does this by first calculating the kS (voltage to overcome static friction) by slowly increasing From 1a7519d78b95f321d6d3d34492c187f3c1922026 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 26 Jan 2023 19:21:40 -0500 Subject: [PATCH 149/243] Merge remote-tracking branch 'refs/remotes/origin/main' --- include/subsystems/flywheel.h | 13 +++++++++---- src/subsystems/flywheel.cpp | 33 +++++++++++++++++++++++++++------ 2 files changed, 36 insertions(+), 10 deletions(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index c4babce..3f0202a 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -86,10 +86,14 @@ class Flywheel{ motor_group* getMotors(); /** - * return the current velocity of the flywheel motors, in RPM + * make a measurement of the current RPM of the flywheel motor and return a smoothed version */ - double getRPM(); + double measureRPM(); + /** + * return the current smoothed velocity of the flywheel motors, in RPM + */ + double getRPM(); /** * Returns a POINTER to the PID. */ @@ -174,5 +178,6 @@ class Flywheel{ std::atomic RPM; // Desired RPM of the flywheel. task rpmTask; // task (thread but not) that handles spinning the wheel at a given RPM FlywheelControlStyle control_style; // how the flywheel should be controlled - -}; \ No newline at end of file + double smoothedRPM; + MovingAverage RPM_avger; + }; \ No newline at end of file diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index bdc1a6a..c90bba7 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -2,7 +2,7 @@ * * File: Flywheel.cpp * Purpose: Generalized flywheel class for Core. -* Author: Chris Nokes +* Author: Chris Nokes, Richie Sommers * ********************************************************** * EDIT HISTORY @@ -22,6 +22,8 @@ using namespace vex; +const int FlywheelWindowSize = 30; + /********************************************************* * CONSTRUCTOR, GETTERS, SETTERS *********************************************************/ @@ -33,25 +35,26 @@ FeedForward::ff_config_t empty_ff = FeedForward::ff_config_t{}; * Create the Flywheel object using PID + feedforward for control. */ Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio) - :motors(motors), pid(pid_config), ff(ff_config), ratio(ratio), control_style(PID_Feedforward) { } + :motors(motors), pid(pid_config), ff(ff_config), ratio(ratio), control_style(PID_Feedforward), smoothedRPM(0), RPM_avger(MovingAverage(FlywheelWindowSize)) { + } /** * Create the Flywheel object using only feedforward for control */ Flywheel::Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio) - :motors(motors), pid(empty_pid), ff(ff_config), ratio(ratio), control_style(Feedforward) {} + :motors(motors), pid(empty_pid), ff(ff_config), ratio(ratio), control_style(Feedforward), smoothedRPM(0), RPM_avger(MovingAverage(FlywheelWindowSize)) {} /** * Create the Flywheel object using Take Back Half for control */ Flywheel::Flywheel(motor_group &motors, const double TBH_gain, const double ratio) - :motors(motors), pid(empty_pid), ff(empty_ff), TBH_gain(TBH_gain), ratio(ratio), control_style(Take_Back_Half) {} + :motors(motors), pid(empty_pid), ff(empty_ff), TBH_gain(TBH_gain), ratio(ratio), control_style(Take_Back_Half), smoothedRPM(0), RPM_avger(MovingAverage(FlywheelWindowSize)) {} /** * Create the Flywheel object using Bang Bang for control */ Flywheel::Flywheel(motor_group &motors, const double ratio) - :motors(motors), pid(empty_pid), ff(empty_ff), ratio(ratio), control_style(Bang_Bang) {} + :motors(motors), pid(empty_pid), ff(empty_ff), ratio(ratio), control_style(Bang_Bang), smoothedRPM(0), RPM_avger(MovingAverage(FlywheelWindowSize)) {} /** * Return the current value that the RPM should be set to @@ -74,8 +77,16 @@ motor_group* Flywheel::getMotors() { return &motors; } // TODO -- Remove? * return the current velocity of the flywheel motors, in RPM * @return the measured velocity of the flywheel */ -double Flywheel::getRPM() { return ratio * motors.velocity(velocityUnits::rpm); } +double Flywheel::measureRPM() { + double rawRPM = ratio * motors.velocity(velocityUnits::rpm); + RPM_avger.add_entry(rawRPM); + smoothedRPM = RPM_avger.get_average(); + return smoothedRPM; +} +double Flywheel::getRPM(){ + return smoothedRPM; +} /** * Returns a POINTER TO the PID; not currently used. * @return pidPointer -pointer to the PID @@ -131,6 +142,8 @@ int spinRPMTask_BangBang(void* wheelPointer) { Flywheel* wheel = (Flywheel*) wheelPointer; while(true) { // if it below the RPM, go, otherwise don't + wheel->measureRPM(); + if(wheel->getRPM() < wheel->getDesiredRPM()) { wheel->spin_raw(1, fwd); } @@ -147,6 +160,7 @@ int spinRPMTask_Feedforward(void* wheelPointer) { Flywheel* wheel = (Flywheel*) wheelPointer; // get the pid from the wheel and set its target to the RPM stored in the wheel. while(true) { + wheel->measureRPM(); wheel->updatePID(wheel->getRPM()); // check the current velocity and update the PID with it. double output = wheel->getFeedforwardValue(); wheel->spin_raw(output, fwd); // set the motors to whatever feedforward tells them to do @@ -161,6 +175,7 @@ int spinRPMTask_PID_Feedforward(void* wheelPointer) { Flywheel* wheel = (Flywheel*) wheelPointer; // get the pid from the wheel and set its target to the RPM stored in the wheel. while(true) { + wheel->measureRPM(); wheel->updatePID(wheel->getRPM()); // check the current velocity and update the PID with it. double output = wheel->getPIDValue() + wheel->getFeedforwardValue(); wheel->spin_raw(output, fwd); // set the motors to whatever PID tells them to do @@ -181,6 +196,8 @@ int spinRPMTask_TBH(void* wheelPointer) { double previous_error = 0.0; while (true){ + wheel->measureRPM(); + //reset if set to 0, this keeps the tbh val from screwing us up when we start up again if (wheel->getDesiredRPM()==0){ output = 0; @@ -236,6 +253,10 @@ void Flywheel::spin_manual(double speed, directionType dir){ * @param inputRPM - set the current RPM */ void Flywheel::spinRPM(int inputRPM) { + // setting to 0 is equivelent to stopping + if (inputRPM==0){ + stop(); + } // only run if the RPM is different or it isn't already running if(!taskRunning) { From 17f35fc8122cd8df83572de077863e6f4c194e38 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Fri, 27 Jan 2023 00:30:12 -0500 Subject: [PATCH 150/243] Tuned Turn with PID --- include/utils/pid.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/utils/pid.h b/include/utils/pid.h index c055871..b349131 100644 --- a/include/utils/pid.h +++ b/include/utils/pid.h @@ -20,7 +20,7 @@ using namespace vex; * @author Ryan McGee * @date 4/3/2020 */ -class PID : Feedback +class PID : public Feedback { public: /** From bb04d54b1e762ed21d575855aa45d089977dbd96 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Fri, 27 Jan 2023 00:33:48 -0500 Subject: [PATCH 151/243] Merge remote-tracking branch 'refs/remotes/origin/main' --- include/utils/command_structure/drive_commands.h | 2 +- src/utils/command_structure/command_controller.cpp | 9 ++++++--- src/utils/command_structure/drive_commands.cpp | 6 ++++++ 3 files changed, 13 insertions(+), 4 deletions(-) diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index a6a2f45..36a2248 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -120,7 +120,7 @@ class DriveToPointCommand: public AutoCommand { */ class TurnToHeadingCommand: public AutoCommand { public: - TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed); + TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed = 1); /** * Run turn_to_heading diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index afcc3ed..7bc4e79 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -34,21 +34,24 @@ void CommandController::add_delay(int ms) { */ void CommandController::run() { AutoCommand *next_cmd; - printf("Beginning Auto. Starting from 1"); + printf("Beginning Auto. Commands 1 to %d\n", command_queue.size()); + fflush(stdout); int command_count = 1; while(!command_queue.empty()) { // retrieve and remove command at the front of the queue next_cmd = command_queue.front(); command_queue.pop(); - printf("Beginning Command %d", command_count); + printf("Beginning Command %d\n", command_count); + fflush(stdout); // run the current command until it returns true while(!next_cmd -> run()) { vexDelay(20); } - printf("Finished Command %d", command_count); + printf("Finished Command %d\n", command_count); + fflush(stdout); command_count++; } } \ No newline at end of file diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index 9f25f96..28f704f 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -123,6 +123,12 @@ bool DriveStopCommand::run() { // ==== ODOMETRY ==== +/** + * Construct an Odometry set pos + * @param odom the odometry system we are setting + * @param newpos the now position to set the odometry to + */ +OdomSetPosition::OdomSetPosition(OdometryBase &odom, const position_t &newpos): odom(odom), newpos(newpos){} bool OdomSetPosition::run() { odom.set_position(newpos); From ece04d1b33f2758c43aad0a91345fafdb5f67dd2 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Fri, 27 Jan 2023 01:24:49 -0500 Subject: [PATCH 152/243] Fixed mutex issues --- include/subsystems/odometry/odometry_base.h | 2 +- src/subsystems/odometry/odometry_3wheel.cpp | 2 - src/subsystems/odometry/odometry_base.cpp | 15 +++---- src/subsystems/odometry/odometry_tank.cpp | 43 +++++---------------- 4 files changed, 16 insertions(+), 46 deletions(-) diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index f1cab19..25128d8 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -50,7 +50,7 @@ class OdometryBase * Sets the current position of the robot * @param newpos the new position that the odometry will believe it is at */ - virtual void set_position(const position_t &newpos=zero_pos); + virtual void set_position(const position_t& newpos=zero_pos); /** * Update the current position on the field based on the sensors diff --git a/src/subsystems/odometry/odometry_3wheel.cpp b/src/subsystems/odometry/odometry_3wheel.cpp index 004354f..a032512 100644 --- a/src/subsystems/odometry/odometry_3wheel.cpp +++ b/src/subsystems/odometry/odometry_3wheel.cpp @@ -62,7 +62,6 @@ position_t Odometry3Wheel::update() last_ang_speed = ang_speed_local; } - mut.lock(); this->current_pos = updated_pos; if(update_vel_accel) { @@ -71,7 +70,6 @@ position_t Odometry3Wheel::update() this->ang_speed_deg = ang_speed_local; this->ang_accel_deg = ang_accel_local; } - mut.unlock(); return current_pos; } diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index a2125d6..ecbfae0 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -24,7 +24,9 @@ int OdometryBase::background_task(void* ptr) OdometryBase &obj = *((OdometryBase*) ptr); while(!obj.end_task) { + obj.mut.lock(); obj.update(); + obj.mut.unlock(); } return 0; @@ -48,12 +50,7 @@ position_t OdometryBase::get_position(void) mut.lock(); // Create a new struct to pass-by-value - position_t out = - { - .x = current_pos.x, - .y = current_pos.y, - .rot = current_pos.rot - }; + position_t out = current_pos; mut.unlock(); @@ -63,13 +60,11 @@ position_t OdometryBase::get_position(void) /** * Sets the current position of the robot */ -void OdometryBase::set_position(const position_t &newpos) +void OdometryBase::set_position(const position_t& newpos) { mut.lock(); - current_pos.x = newpos.x; - current_pos.y = newpos.y; - current_pos.rot = newpos.rot; + current_pos = newpos; mut.unlock(); } diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index a60c369..8dd3e25 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -45,8 +45,6 @@ void OdometryTank::set_position(const position_t &newpos) */ position_t OdometryTank::update() { - position_t updated_pos; - double lside_revs = 0, rside_revs = 0; if(left_side != NULL && right_side != NULL) @@ -91,58 +89,37 @@ position_t OdometryTank::update() if(angle < 0) angle += 360; - mut.lock(); - position_t current_pos_local = current_pos; - mut.unlock(); - - updated_pos = calculate_new_pos(config, current_pos_local, lside_revs, rside_revs, angle); + current_pos = calculate_new_pos(config, current_pos, lside_revs, rside_revs, angle); - static position_t last_pos = updated_pos; + static position_t last_pos = current_pos; static double last_speed = 0; static double last_ang_speed = 0; static timer tmr; - - double speed_local = 0; - double accel_local = 0; - double ang_speed_local = 0; - double ang_accel_local = 0; bool update_vel_accel = tmr.time(sec) > 0.1; // This loop runs too fast. Only check at LEAST every 1/10th sec if(update_vel_accel) { // Calculate robot velocity - speed_local = pos_diff(updated_pos, last_pos) / tmr.time(sec); + speed = pos_diff(current_pos, last_pos) / tmr.time(sec); // Calculate robot acceleration - accel_local = (speed_local - last_speed) / tmr.time(sec); + accel = (speed - last_speed) / tmr.time(sec); // Calculate robot angular velocity (deg/sec) - ang_speed_local = smallest_angle(updated_pos.rot, last_pos.rot) / tmr.time(sec); + ang_speed_deg = smallest_angle(current_pos.rot, last_pos.rot) / tmr.time(sec); // Calculate robot angular acceleration (deg/sec^2) - ang_accel_local = (ang_speed_local - last_ang_speed) / tmr.time(sec); + ang_accel_deg = (ang_speed_deg - last_ang_speed) / tmr.time(sec); tmr.reset(); - last_pos = updated_pos; - last_speed = speed_local; - last_ang_speed = ang_speed_local; - } - - // Update the class' stored position - mut.lock(); - this->current_pos = updated_pos; - if(update_vel_accel) - { - this->speed = speed_local; - this->accel = accel_local; - this->ang_speed_deg = ang_speed_local; - this->ang_accel_deg = ang_accel_local; + last_pos = current_pos; + last_speed = speed; + last_ang_speed = ang_speed_deg; } - mut.unlock(); - return updated_pos; + return current_pos; } /** From 2cf5bd3f47918dcbf7ec94c4fda015f9d3c41cd7 Mon Sep 17 00:00:00 2001 From: cowsed Date: Thu, 2 Feb 2023 21:07:19 -0500 Subject: [PATCH 153/243] Merge branch 'main' of https://github.com/RIT-VEX-U/2022-2023-Flynn --- include/utils/command_structure/auto_command.h | 8 -------- src/utils/command_structure/drive_commands.cpp | 7 +++++++ 2 files changed, 7 insertions(+), 8 deletions(-) diff --git a/include/utils/command_structure/auto_command.h b/include/utils/command_structure/auto_command.h index 942c652..008f31e 100644 --- a/include/utils/command_structure/auto_command.h +++ b/include/utils/command_structure/auto_command.h @@ -10,14 +10,6 @@ class AutoCommand { public: - /** - * Constructs an autocommand with a specified timeout - */ - AutoCommand(double timeout_seconds): timeout_seconds(timeout_seconds){} - /** - * Constructs an autocommand with no timeout - */ - AutoCommand(): timeout_seconds(0.0){} /** * Executes the command * Overridden by child classes diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index 19f938c..86880a0 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -40,6 +40,10 @@ DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, Feedback &feedbac bool DriveForwardCommand::run() { return drive_sys.drive_forward(inches, dir, feedback, max_speed); } + +/** + * reset the drive system if we timeout +*/ void DriveForwardCommand::on_timeout(){ drive_sys.reset_auto(); } @@ -63,6 +67,9 @@ TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, bool TurnDegreesCommand::run() { return drive_sys.turn_degrees(degrees, max_speed); } +/** + * reset the drive system if we timeout +*/ void TurnDegreesCommand::on_timeout(){ drive_sys.reset_auto(); } From 9569d195f76353d372f25e76b6c754d27b32565c Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 3 Feb 2023 23:01:44 -0500 Subject: [PATCH 154/243] Testing Timeout, added PrintOdomCommand for debugging --- src/utils/command_structure/drive_commands.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index 86880a0..9addbda 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -46,6 +46,7 @@ bool DriveForwardCommand::run() { */ void DriveForwardCommand::on_timeout(){ drive_sys.reset_auto(); + drive_sys.stop(); } @@ -72,6 +73,7 @@ bool TurnDegreesCommand::run() { */ void TurnDegreesCommand::on_timeout(){ drive_sys.reset_auto(); + drive_sys.stop(); } @@ -100,6 +102,7 @@ bool DriveToPointCommand::run() { */ void DriveToPointCommand::on_timeout(){ drive_sys.reset_auto(); + drive_sys.stop(); } @@ -126,6 +129,7 @@ bool TurnToHeadingCommand::run() { */ void TurnToHeadingCommand::on_timeout(){ drive_sys.reset_auto(); + drive_sys.stop(); } From 219388326d915287bfd7ae4cff56566bc0f5ef11 Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 3 Feb 2023 20:30:45 -0500 Subject: [PATCH 155/243] Separate FLynn auto file Defines for commonly used functions --- src/subsystems/flywheel.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index c90bba7..f9c42a7 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -148,7 +148,7 @@ int spinRPMTask_BangBang(void* wheelPointer) { wheel->spin_raw(1, fwd); } else { wheel->stopMotors(); } - vexDelay(1); + vexDelay(10); } return 0; } From 2392809e74dcd665ff6fa7f5dd7f7d5d8ba93e0c Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 3 Feb 2023 22:19:51 -0500 Subject: [PATCH 156/243] See previous commit message --- include/subsystems/mecanum_drive.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/include/subsystems/mecanum_drive.h b/include/subsystems/mecanum_drive.h index cf01c3d..fdc4777 100644 --- a/include/subsystems/mecanum_drive.h +++ b/include/subsystems/mecanum_drive.h @@ -60,7 +60,7 @@ class MecanumDrive * @param left_y left joystick, Y axis (forward / backwards) * @param left_x left joystick, X axis (strafe left / right) * @param right_x right joystick, X axis (rotation left / right) - * @param power=2 how much of a "curve" there should be on drive controls; better for low speed maneuvers. + * @param power =2 how much of a "curve" there should be on drive controls; better for low speed maneuvers. * Leave blank for a default curve of 2 (higher means more fidelity) */ void drive(double left_y, double left_x, double right_x, int power=2); @@ -74,7 +74,7 @@ class MecanumDrive * @param direction What direction the robot should travel in, in degrees. * 0 is forward, +/-180 is reverse, clockwise is positive. * @param speed The maximum speed the robot should travel, in percent: -1.0->+1.0 - * @param gyro_correction=true Whether or not to use the gyro to help correct while driving. + * @param gyro_correction =true Whether or not to use the gyro to help correct while driving. * Will always be false if no gyro was declared in the constructor. */ bool auto_drive(double inches, double direction, double speed, bool gyro_correction=true); @@ -84,7 +84,7 @@ class MecanumDrive * for control. * @param degrees How many degrees to rotate the robot. Clockwise postive. * @param speed What percentage to run the motors at: 0.0 -> 1.0 - * @param ignore_imu=false Whether or not to use the Inertial for determining angle. + * @param ignore_imu =false Whether or not to use the Inertial for determining angle. * Will instead use circumference formula + robot's wheelbase + encoders to determine. * * @return whether or not the robot has finished the maneuver From e68e0816bf1fd06441ff7f729a9ebf43cb2329fa Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 5 Feb 2023 18:53:35 -0500 Subject: [PATCH 157/243] skills tuning fixed drivetopoint not accepting a feedback --- src/utils/command_structure/drive_commands.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index 9addbda..c1417e9 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -95,7 +95,7 @@ DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedbac * @returns true when execution is complete, false otherwise */ bool DriveToPointCommand::run() { - return drive_sys.drive_to_point(x, y, dir, max_speed); + return drive_sys.drive_to_point(x, y, dir, feedback, max_speed); } /** * reset the drive system if we don't hit our target From 87e1ff3fd4ebcc8cf69d3b35e477c667d121f65e Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 5 Feb 2023 15:11:33 -0500 Subject: [PATCH 158/243] Added PIDFF class, implemented in turn tuning. --- include/utils/pidff.h | 67 +++++++++++++++++++++++++++++++++++ src/utils/pidff.cpp | 82 +++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 149 insertions(+) create mode 100644 include/utils/pidff.h create mode 100644 src/utils/pidff.cpp diff --git a/include/utils/pidff.h b/include/utils/pidff.h new file mode 100644 index 0000000..4bd475d --- /dev/null +++ b/include/utils/pidff.h @@ -0,0 +1,67 @@ +#pragma once +#include "../core/include/utils/feedback_base.h" +#include "../core/include/utils/pid.h" +#include "../core/include/utils/feedforward.h" + +class PIDFF : public Feedback +{ + public: + + PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg); + + /** + * Initialize the feedback controller for a movement + * + * @param start_pt the current sensor value + * @param set_pt where the sensor value should be + */ + void init(double start_pt, double set_pt) override; + + /** + * Iterate the feedback loop once with an updated sensor value. + * Only kS for feedfoward will be applied. + * + * @param val value from the sensor + * @return feedback loop result + */ + double update(double val) override; + + /** + * Iterate the feedback loop once with an updated sensor value + * + * @param val value from the sensor + * @param vel_setpt Velocity for feedforward + * @param a_setpt Acceleration for feedfoward + * @return feedback loop result + */ + double update(double val, double vel_setpt, double a_setpt=0); + + /** + * @return the last saved result from the feedback controller + */ + double get() override; + + /** + * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * + * @param lower Upper limit + * @param upper Lower limit + */ + void set_limits(double lower, double upper) override; + + /** + * @return true if the feedback controller has reached it's setpoint + */ + bool is_on_target() override; + + private: + + FeedForward::ff_config_t &ff_cfg; + + PID pid; + FeedForward ff; + + double out; + double lower_lim, upper_lim; + +}; \ No newline at end of file diff --git a/src/utils/pidff.cpp b/src/utils/pidff.cpp new file mode 100644 index 0000000..7d4e8ad --- /dev/null +++ b/src/utils/pidff.cpp @@ -0,0 +1,82 @@ +#include "../core/include/utils/pidff.h" +#include "../core/include/utils/math_util.h" + +PIDFF::PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg): ff_cfg(ff_cfg), pid(pid_cfg), ff(ff_cfg) +{ + out = 0; + lower_lim = 0; + upper_lim = 0; +} + +/** + * Initialize the feedback controller for a movement + * + * @param start_pt the current sensor value + * @param set_pt where the sensor value should be + */ +void PIDFF::init(double start_pt, double set_pt) +{ + pid.init(start_pt, set_pt); +} + +/** + * Iterate the feedback loop once with an updated sensor value. + * Only kS for feedfoward will be applied. + * + * @param val value from the sensor + * @return feedback loop result + */ +double PIDFF::update(double val) +{ + double pid_out = pid.update(val); + double ff_out = ff_cfg.kS * sign(pid_out); + out = clamp(pid_out + ff_out, lower_lim, upper_lim); + + return out; +} + +/** + * Iterate the feedback loop once with an updated sensor value + * + * @param val value from the sensor + * @param vel_setpt Velocity for feedforward + * @param a_setpt Acceleration for feedfoward + * @return feedback loop result +*/ +double PIDFF::update(double val, double vel_setpt, double a_setpt) +{ + + double pid_out = pid.update(val); + double ff_out = ff.calculate(vel_setpt, a_setpt); + out = clamp(ff_out + pid_out, lower_lim, upper_lim); + + return out; +} + +/** + * @return the last saved result from the feedback controller + */ +double PIDFF::get() +{ + return out; +} + +/** + * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * + * @param lower Upper limit + * @param upper Lower limit + */ +void PIDFF::set_limits(double lower, double upper) +{ + upper_lim = upper; + lower_lim = lower; +} + +/** + * @return true if the feedback controller has reached it's setpoint + */ +bool PIDFF::is_on_target() +{ + return pid.is_on_target(); +} \ No newline at end of file From 84e5f9428cc6eac51784376ae40cc4e67895a13a Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 9 Feb 2023 13:26:17 -0500 Subject: [PATCH 159/243] Updated vision code --- include/utils/pidff.h | 6 ++++++ src/utils/pidff.cpp | 5 +++++ 2 files changed, 11 insertions(+) diff --git a/include/utils/pidff.h b/include/utils/pidff.h index 4bd475d..43c0498 100644 --- a/include/utils/pidff.h +++ b/include/utils/pidff.h @@ -17,6 +17,12 @@ class PIDFF : public Feedback */ void init(double start_pt, double set_pt) override; + /** + * Set the target of the PID loop + * @param set_pt Setpoint / target value + */ + void set_target(double set_pt); + /** * Iterate the feedback loop once with an updated sensor value. * Only kS for feedfoward will be applied. diff --git a/src/utils/pidff.cpp b/src/utils/pidff.cpp index 7d4e8ad..01286de 100644 --- a/src/utils/pidff.cpp +++ b/src/utils/pidff.cpp @@ -19,6 +19,11 @@ void PIDFF::init(double start_pt, double set_pt) pid.init(start_pt, set_pt); } +void PIDFF::set_target(double set_pt) +{ + pid.set_target(set_pt); +} + /** * Iterate the feedback loop once with an updated sensor value. * Only kS for feedfoward will be applied. From 18544869f8a972f019a9bb3b47581fef3b9cfd97 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 9 Feb 2023 13:37:56 -0500 Subject: [PATCH 160/243] Merge remote-tracking branch 'refs/remotes/origin/main' --- include/utils/command_structure/command_controller.h | 6 ++++++ include/utils/command_structure/drive_commands.h | 1 + src/utils/command_structure/command_controller.cpp | 10 ++++++++++ src/utils/command_structure/drive_commands.cpp | 11 +++++++++++ 4 files changed, 28 insertions(+) diff --git a/include/utils/command_structure/command_controller.h b/include/utils/command_structure/command_controller.h index 0f6befb..a78abbf 100644 --- a/include/utils/command_structure/command_controller.h +++ b/include/utils/command_structure/command_controller.h @@ -21,6 +21,12 @@ class CommandController { * @param timeout_seconds the number of seconds we will let the command run for. If it exceeds this, we cancel it and run on_timeout. if it is <= 0 no time out will be applied */ void add(AutoCommand *cmd, double timeout_seconds = 0); + + /** + * Add multiple commands to the queue. No timeout here. + * @param cmds the AutoCommands we want to add to our list + */ + void add(std::vector cmds); /** * Adds a command that will delay progression diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index fda76a7..3419a18 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -99,6 +99,7 @@ class TurnDegreesCommand: public AutoCommand { class DriveToPointCommand: public AutoCommand { public: DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed = 1); + DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, Vector2D::point_t point, directionType dir, double max_speed=1); /** * Run drive_to_point diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index d5d6b5f..557c2f9 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -20,6 +20,16 @@ void CommandController::add(AutoCommand *cmd, double timeout_seconds) { command_queue.push(cmd); } +/** + * Add multiple commands to the queue. No timeout here. + * @param cmds the AutoCommands we want to add to our list + */ +void CommandController::add(std::vector cmds) { + for(AutoCommand * cmd : cmds){ + command_queue.push(cmd); + } +} + /** * Adds a command that will delay progression * of the queue diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index c1417e9..3e1dc37 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -89,6 +89,17 @@ void TurnDegreesCommand::on_timeout(){ DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed): drive_sys(drive_sys), feedback(feedback), x(x), y(y), dir(dir), max_speed(max_speed) {} +/** + * Construct a DriveForward Command + * @param drive_sys the drive system we are commanding + * @param feedback the feedback controller we are using to execute the drive + * @param y the point to drive to + * @param dir the direction to drive + * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at + */ +DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, Vector2D::point_t point, directionType dir, double max_speed): + drive_sys(drive_sys), feedback(feedback), x(point.x), y(point.y), dir(dir), max_speed(max_speed) {} + /** * Run drive_to_point * Overrides run from AutoCommand From bebf09ac686441e15e37071cbe0be9b18bdba833 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 9 Feb 2023 21:02:57 -0500 Subject: [PATCH 161/243] Merge remote-tracking branch 'refs/remotes/origin/main' --- src/subsystems/flywheel.cpp | 4 ++-- src/utils/moving_average.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index f9c42a7..d3f0e4a 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -22,7 +22,7 @@ using namespace vex; -const int FlywheelWindowSize = 30; +const int FlywheelWindowSize = 1; /********************************************************* * CONSTRUCTOR, GETTERS, SETTERS @@ -81,7 +81,7 @@ double Flywheel::measureRPM() { double rawRPM = ratio * motors.velocity(velocityUnits::rpm); RPM_avger.add_entry(rawRPM); smoothedRPM = RPM_avger.get_average(); - return smoothedRPM; + return rawRPM; //TODO Change back } double Flywheel::getRPM(){ diff --git a/src/utils/moving_average.cpp b/src/utils/moving_average.cpp index d61695e..08cf344 100644 --- a/src/utils/moving_average.cpp +++ b/src/utils/moving_average.cpp @@ -48,7 +48,7 @@ MovingAverage::MovingAverage(int buffer_size, double starting_value) { * @param n the sample that will be added to the moving average. */ void MovingAverage::add_entry(double n){ - current_avg -= buffer[buffer_index]/get_size(); + current_avg -= buffer[buffer_index]/(double)get_size(); current_avg += n/get_size(); buffer[buffer_index] = n; From f2d04f2ca9b8b269ef4dcb3f4e8067f532bf40ff Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 10 Feb 2023 21:31:37 -0500 Subject: [PATCH 162/243] Graph Drawer + No Comments --- include/utils/graph_drawer.h | 104 +++++++++++++++++++++++++++++++++++ src/subsystems/flywheel.cpp | 6 +- 2 files changed, 108 insertions(+), 2 deletions(-) create mode 100644 include/utils/graph_drawer.h diff --git a/include/utils/graph_drawer.h b/include/utils/graph_drawer.h new file mode 100644 index 0000000..8e672f6 --- /dev/null +++ b/include/utils/graph_drawer.h @@ -0,0 +1,104 @@ +#pragma once + +#include +#include +#include "vex.h" + +class GraphDrawer +{ +public: + GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound) : Screen(screen), sample_index(0), xlabel(x_label), ylabel(y_label), col(col), border(draw_border), upper(upper_bound), lower(lower_bound) + { + std::vector temp(num_samples, Vector2D::point_t{.x = 0.0, .y = 0.0}); + samples = temp; + } + void add_sample(Vector2D::point_t sample) + { + samples[sample_index] = sample; + sample_index++; + sample_index %= samples.size(); + } + void draw(int x, int y, int width, int height) + { + if (samples.size() < 1) + { + return; + } + + double current_min = samples[0].y; + double current_max = samples[0].y; + double earliest_time = samples[0].x; + double latest_time = samples[0].x; + // collect data + for (int i = 0; i < samples.size(); i++) + { + Vector2D::point_t p = samples[i]; + if (p.x < earliest_time) + { + earliest_time = p.x; + } + else if (p.x > latest_time) + { + latest_time = p.x; + } + + if (p.y < current_min) + { + current_min = p.y; + } + else if (p.y > current_max) + { + current_max = p.y; + } + } + if (fabs(latest_time - earliest_time) < 0.001) + { + Screen.printAt(width / 2, height / 2, "Not enough Data"); + return; + } + if (upper != lower) + { + current_min = lower; + current_max = upper; + } + + if (border) + { + Screen.setPenWidth(1); + Screen.setPenColor(vex::white); + Screen.setFillColor(bgcol); + Screen.drawRectangle(x, y, width, height); + } + + double time_range = latest_time - earliest_time; + double sample_range = current_max - current_min; + double x_s = (double)x; + double y_s = (double)y + (double)height; + Screen.setPenWidth(4); + Screen.setPenColor(col); + for (int i = sample_index; i < samples.size() + sample_index - 1; i++) + { + Vector2D::point_t p = samples[i % samples.size()]; + double x_pos = x_s + ((p.x - earliest_time) / time_range) * (double)width; + double y_pos = y_s + ((p.y - current_min) / sample_range) * (double)(-height); + + Vector2D::point_t p2 = samples[(i + 1) % samples.size()]; + double x_pos2 = x_s + ((p2.x - earliest_time) / time_range) * (double)width; + double y_pos2 = y_s + ((p2.y - current_min) / sample_range) * (double)(-height); + + Screen.drawLine((int)x_pos, (int)y_pos, (int)x_pos2, (int)y_pos2); + } + } + +private: + vex::brain::lcd &Screen; + std::vector samples; + int sample_index = 0; + std::string xlabel; + std::string ylabel; + vex::color col = vex::red; + vex::color bgcol = vex::transparent; + bool border; + double upper; + double lower; +}; diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index d3f0e4a..be44f1d 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -22,7 +22,7 @@ using namespace vex; -const int FlywheelWindowSize = 1; +const int FlywheelWindowSize = 10; /********************************************************* * CONSTRUCTOR, GETTERS, SETTERS @@ -81,7 +81,7 @@ double Flywheel::measureRPM() { double rawRPM = ratio * motors.velocity(velocityUnits::rpm); RPM_avger.add_entry(rawRPM); smoothedRPM = RPM_avger.get_average(); - return rawRPM; //TODO Change back + return smoothedRPM; //TODO Change back } double Flywheel::getRPM(){ @@ -291,6 +291,8 @@ void Flywheel::spinRPM(int inputRPM) { void Flywheel::stop() { rpmTask.stop(); taskRunning = false; + RPM = 0.0; + smoothedRPM = 0.0; motors.stop(); } From 29a9f749d660938a26947aa8fc96cbab3a0614ea Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 10 Feb 2023 23:58:04 -0500 Subject: [PATCH 163/243] =?UTF-8?q?tuning=20auto=20tuning=20function/=20gi?= =?UTF-8?q?ves=20you=20control=20over=20the=20pid=20config=20as=20you=20ru?= =?UTF-8?q?n=20the=20autos=20something=20like=20whlie=20true{=20=20=20=20?= =?UTF-8?q?=20=20tune=5Fsomething();=20=20=20=20=20tune=5Fgeneric=5Fpid(fe?= =?UTF-8?q?edback=20that=20controls=20something);=20=20=20=20=20delay(20?= =?UTF-8?q?=20or=20so);=20}=20this=20features=20unsafe(kinda=20safe)=20cas?= =?UTF-8?q?ts,=20function=20pointers,=20AND=20ternaries=20=E2=98=BA?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- include/utils/feedback_base.h | 27 +++++++++++++++++++-------- include/utils/graph_drawer.h | 2 ++ include/utils/pid.h | 5 ++++- include/utils/pidff.h | 4 +++- src/utils/pid.cpp | 4 ++++ 5 files changed, 32 insertions(+), 10 deletions(-) diff --git a/include/utils/feedback_base.h b/include/utils/feedback_base.h index a716f53..19d45a9 100644 --- a/include/utils/feedback_base.h +++ b/include/utils/feedback_base.h @@ -2,18 +2,24 @@ /** * Interface so that subsystems can easily switch between feedback loops - * + * * @author Ryan McGee * @date 9/25/2022 - * + * */ -class Feedback +class Feedback { - public: +public: + enum FeedbackType + { + PIDType, + FeedforwardType, + OtherType, + }; /** * Initialize the feedback controller for a movement - * + * * @param start_pt the current sensor value * @param set_pt where the sensor value should be */ @@ -21,7 +27,7 @@ class Feedback /** * Iterate the feedback loop once with an updated sensor value - * + * * @param val value from the sensor * @return feedback loop result */ @@ -34,14 +40,19 @@ class Feedback /** * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. - * + * * @param lower Upper limit * @param upper Lower limit */ virtual void set_limits(double lower, double upper) = 0; - /** + /** * @return true if the feedback controller has reached it's setpoint */ virtual bool is_on_target() = 0; + + virtual Feedback::FeedbackType get_type() + { + return FeedbackType::OtherType; + } }; \ No newline at end of file diff --git a/include/utils/graph_drawer.h b/include/utils/graph_drawer.h index 8e672f6..d113f3c 100644 --- a/include/utils/graph_drawer.h +++ b/include/utils/graph_drawer.h @@ -2,7 +2,9 @@ #include #include +#include #include "vex.h" +#include "../core/include/utils/vector2d.h" class GraphDrawer { diff --git a/include/utils/pid.h b/include/utils/pid.h index b349131..4ff41e3 100644 --- a/include/utils/pid.h +++ b/include/utils/pid.h @@ -117,9 +117,12 @@ class PID : public Feedback */ void set_target(double target); -private: + Feedback::FeedbackType get_type() override; + pid_config_t &config; ///< configuration struct for this controller. see pid_config_t for information about what this contains +private: + double last_error = 0; ///< the error measured on the last iteration of update() double accum_error = 0; ///< the integral of error over time since we called init() diff --git a/include/utils/pidff.h b/include/utils/pidff.h index 43c0498..a09c6d3 100644 --- a/include/utils/pidff.h +++ b/include/utils/pidff.h @@ -60,11 +60,13 @@ class PIDFF : public Feedback */ bool is_on_target() override; + PID pid; + + private: FeedForward::ff_config_t &ff_cfg; - PID pid; FeedForward ff; double out; diff --git a/src/utils/pid.cpp b/src/utils/pid.cpp index cdd4933..ae35cd5 100644 --- a/src/utils/pid.cpp +++ b/src/utils/pid.cpp @@ -141,4 +141,8 @@ bool PID::is_on_target() } return false; +} + +Feedback::FeedbackType PID::get_type(){ + return Feedback::FeedbackType::PIDType; } \ No newline at end of file From b8eadcc9e19daa426d673102f1a5c0b1801da9a5 Mon Sep 17 00:00:00 2001 From: cowsed Date: Thu, 16 Feb 2023 23:14:46 -0500 Subject: [PATCH 164/243] Fixed Comments that triggered -Wdocumentation --- include/subsystems/flywheel.h | 2 +- include/utils/graph_drawer.h | 23 +++++++++++++++++++ .../command_structure/drive_commands.cpp | 2 +- 3 files changed, 25 insertions(+), 2 deletions(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index 3f0202a..199cf3e 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -147,7 +147,7 @@ class Flywheel{ /** * starts or sets the RPM thread at new value * what control scheme is dependent on control_style - * @param inputRPM - set the current RPM + * @param rpm - the RPM we want to spin at */ void spinRPM(int rpm); diff --git a/include/utils/graph_drawer.h b/include/utils/graph_drawer.h index d113f3c..f4f3f97 100644 --- a/include/utils/graph_drawer.h +++ b/include/utils/graph_drawer.h @@ -9,17 +9,40 @@ class GraphDrawer { public: +/** + * Construct a GraphDrawer + * @brief a helper class to graph values on the brain screen + * @param screen a reference to Brain.screen we can save for later + * @param num_samples the graph works on a fixed window and will plot the last `num_samples` before the history is forgotten. Larger values give more context but may slow down if you have many graphs or an exceptionally high + * @param x_label the name of the x axis (currently unused) + * @param y_label the name of the y axis (currently unused) + * @param draw_border whether to draw the border around the graph. can be turned off if there are multiple graphs in the same space ie. a graph of error and output + * @param lower_bound the bottom of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints + * @param upper_bound the top of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints +*/ GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound) : Screen(screen), sample_index(0), xlabel(x_label), ylabel(y_label), col(col), border(draw_border), upper(upper_bound), lower(lower_bound) { std::vector temp(num_samples, Vector2D::point_t{.x = 0.0, .y = 0.0}); samples = temp; } + + /** + * add_sample adds a point to the graph, removing one from the back + * @param sample an x, y coordinate of the next point to graph + */ void add_sample(Vector2D::point_t sample) { samples[sample_index] = sample; sample_index++; sample_index %= samples.size(); } + /** + * draws the graph to the screen in the constructor + * @param x x position of the top left of the graphed region + * @param y y position of the top left of the graphed region + * @param width the width of the graphed region + * @param height the height of the graphed region + */ void draw(int x, int y, int width, int height) { if (samples.size() < 1) diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index 3e1dc37..833f9ee 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -93,7 +93,7 @@ DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedbac * Construct a DriveForward Command * @param drive_sys the drive system we are commanding * @param feedback the feedback controller we are using to execute the drive - * @param y the point to drive to + * @param point the point to drive to * @param dir the direction to drive * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at */ From a6783f1da80ccccd2869ada90a104297372a31dd Mon Sep 17 00:00:00 2001 From: cowsed Date: Thu, 16 Feb 2023 20:00:27 -0500 Subject: [PATCH 165/243] withTImeout for initializer list auto path declaring also added disks to auto path --- include/intense_milk.h | 4 ++++ include/utils/command_structure/auto_command.h | 4 ++++ src/utils/command_structure/command_controller.cpp | 2 +- 3 files changed, 9 insertions(+), 1 deletion(-) create mode 100644 include/intense_milk.h diff --git a/include/intense_milk.h b/include/intense_milk.h new file mode 100644 index 0000000..3b9e4f9 --- /dev/null +++ b/include/intense_milk.h @@ -0,0 +1,4 @@ +#include +int intense_milk_width = 426; +int intense_milk_height = 244 +;uint32_t intense_milk[103944] = {0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00221e1f, 0x001e1a1b, 0x00191617, 0x00151313, 0x0011ff, 0x00cbb, 0x00877, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001e1b1c, 0x001a1718, 0x00161314, 0x0011f10, 0x00dbc, 0x00988, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001b1818, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001f1b1c, 0x001b1818, 0x00161414, 0x00121011, 0x00ecd, 0x00989, 0x00545, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x001b1819, 0x00171415, 0x00131111, 0x00edd, 0x00a99, 0x00655, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1e, 0x001c191a, 0x00181516, 0x00131112, 0x00fde, 0x00baa, 0x00666, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a89, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x001d191a, 0x00191616, 0x00141212, 0x0010ee, 0x00baa, 0x00767, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001e1a1b, 0x00191617, 0x00151213, 0x0011ff, 0x00cbb, 0x00877, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001e1b1b, 0x001a1718, 0x00161314, 0x0011f10, 0x00dbc, 0x00988, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151313, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001f1b1c, 0x001b1718, 0x00161414, 0x00121010, 0x00ecc, 0x00988, 0x00545, 0x00101, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x009e2822, 0x00d12c23, 0x00b72a23, 0x009e2822, 0x00862622, 0x006c2421, 0x00532321, 0x003a2120, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x001b1819, 0x00171415, 0x00131011, 0x00ecd, 0x00a99, 0x00655, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00323, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2020, 0x00b42a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00d42c23, 0x00bb2a23, 0x00a22823, 0x00892722, 0x00702522, 0x00582321, 0x003e2121, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x001c1919, 0x00171515, 0x00131112, 0x00fde, 0x00b9a, 0x00656, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00545, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00352020, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00d92c24, 0x00bf2b23, 0x00a62923, 0x008e2722, 0x00742522, 0x005b2321, 0x00432121, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x001d191a, 0x00181516, 0x00141212, 0x0010ee, 0x00baa, 0x00766, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00412121, 0x00d42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00d12920, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2d24, 0x00c22b23, 0x00aa2923, 0x00912722, 0x00772522, 0x00602321, 0x00462221, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001d1a1b, 0x00181516, 0x00121011, 0x00cab, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00512221, 0x00de2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x004e1411, 0x00477, 0x00788, 0x001ffe, 0x003c12f, 0x00591512, 0x00761a15, 0x00921f19, 0x00b0241c, 0x00cc2820, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02d24, 0x00c72b23, 0x00ae2923, 0x00952722, 0x007c2622, 0x00632421, 0x004a2221, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d191a, 0x0011ff, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00632421, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x003912f, 0x00477, 0x006a6c6c, 0x00767878, 0x00585a5a, 0x00383b3b, 0x00191a1a, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x001bed, 0x003811f, 0x00541411, 0x00711915, 0x008f1e18, 0x00ab231c, 0x00c7281f, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00cb2b23, 0x00b22a23, 0x00992822, 0x007f2622, 0x00672421, 0x004e2221, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00782522, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2920, 0x0027fe, 0x00799, 0x009fa0a0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00d8d8d8, 0x00b8b9b9, 0x009a9b9b, 0x007b7d7d, 0x005c5e5e, 0x003d3f3f, 0x001e1f1f, 0x00588, 0x00477, 0x00477, 0x00477, 0x00477, 0x0017dc, 0x003311f, 0x00501410, 0x006e1914, 0x00891d17, 0x00a6221b, 0x00c4271f, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00cf2c23, 0x00b52a23, 0x009d2822, 0x00842622, 0x006b2421, 0x00512221, 0x00392120, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00656, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171415, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x0018dc, 0x00f1010, 0x00b8b9b9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00dcdcdc, 0x00bebfbf, 0x009fa0a0, 0x007f8181, 0x00626363, 0x00424444, 0x00222424, 0x00799, 0x00477, 0x00477, 0x00477, 0x00477, 0x0012cb, 0x002f11f, 0x004b1310, 0x00681813, 0x00851d17, 0x00a2211b, 0x00be261e, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00d22c23, 0x00ba2a23, 0x00a12822, 0x00872622, 0x006f2522, 0x00562321, 0x003c2121, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00121011, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00a62923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ab231c, 0x00daa, 0x001b1c1c, 0x00cdcdcd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00e1e2e2, 0x00c2c3c3, 0x00a3a5a5, 0x00858686, 0x00656767, 0x00474949, 0x00282a2a, 0x00acc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00daa, 0x002a10f, 0x004712f, 0x00631713, 0x00801c16, 0x009d211a, 0x00bb251e, 0x00d72a21, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00d72c24, 0x00bd2a23, 0x00a52923, 0x008c2722, 0x00732522, 0x005a2321, 0x00412121, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00788, 0x00292b2b, 0x00dfdfdf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00e5e6e6, 0x00c8c9c9, 0x00a8a9a9, 0x00898a8a, 0x006a6c6c, 0x004c4e4e, 0x002c2e2e, 0x00e10f, 0x00477, 0x00477, 0x00477, 0x00477, 0x00a99, 0x002610f, 0x00421210, 0x005f1612, 0x007c1b16, 0x00992019, 0x00b5251d, 0x00d22921, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2d24, 0x00c22b23, 0x00a92923, 0x008f2722, 0x00772522, 0x005e2321, 0x00442121, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00c92b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00791a15, 0x00477, 0x003d3f3f, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x00cccccc, 0x00acadad, 0x008f9090, 0x006f7171, 0x00505252, 0x00323434, 0x00131414, 0x00477, 0x00477, 0x00477, 0x00477, 0x00888, 0x0021fe, 0x003e12f, 0x005b1612, 0x00771a15, 0x00941f19, 0x00b1241c, 0x00cd2820, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00c52b23, 0x00ac2923, 0x00942722, 0x007b2522, 0x00612421, 0x00492221, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00452221, 0x00d82c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x005d1612, 0x00477, 0x00555757, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00d1d1d1, 0x00b2b3b3, 0x00939494, 0x00747676, 0x00565858, 0x00363838, 0x00181919, 0x00477, 0x00477, 0x00477, 0x00477, 0x00577, 0x001dfe, 0x003911f, 0x00561511, 0x00731a15, 0x008f1e18, 0x00ac231c, 0x00c9281f, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00c92b23, 0x00b12923, 0x00972822, 0x007f2622, 0x00662421, 0x004c2221, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00451310, 0x00477, 0x006e7070, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00d6d6d6, 0x00b6b7b7, 0x00999a9a, 0x00797b7b, 0x005a5c5c, 0x003b3d3d, 0x001c1d1d, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x0018dd, 0x003511f, 0x00521411, 0x006e1914, 0x008b1d18, 0x00a8221b, 0x00c5271f, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00ab2923, 0x00722522, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00692421, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82a21, 0x003211f, 0x00477, 0x008c8d8d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00dbdbdb, 0x00bcbdbd, 0x009d9e9e, 0x007d7f7f, 0x00606161, 0x00404242, 0x00202221, 0x00799, 0x00477, 0x00477, 0x00477, 0x00477, 0x0014cc, 0x003111f, 0x004c1310, 0x006a1814, 0x00871d17, 0x00a3211b, 0x00c0261e, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00a32823, 0x00412121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007f2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2820, 0x0022fd, 0x009bb, 0x00a7a8a8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00e0e0e0, 0x00c0c1c1, 0x00a1a3a3, 0x00838484, 0x00636565, 0x00454747, 0x00262828, 0x009bb, 0x00477, 0x00477, 0x00477, 0x00477, 0x00eba, 0x002c11f, 0x00491210, 0x00651713, 0x00821c17, 0x009f211a, 0x00bc261e, 0x00d82a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x008e2722, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00962822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b8251d, 0x0015cc, 0x00121313, 0x00bfc0c0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00e4e5e5, 0x00c6c7c7, 0x00a6a7a7, 0x00878888, 0x00696b6b, 0x004a4c4c, 0x002a2c2c, 0x00cee, 0x00477, 0x00477, 0x00477, 0x00477, 0x00b99, 0x002810f, 0x004312f, 0x00611612, 0x00851d17, 0x00b4241d, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf2b23, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131011, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00ad2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a2211b, 0x00caa, 0x001e2020, 0x00d4d4d4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e9eaea, 0x00cacaca, 0x00abacac, 0x008d8e8e, 0x006d6f6f, 0x004e5050, 0x00303232, 0x00101111, 0x00477, 0x00477, 0x00eba, 0x005a1612, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322020, 0x00bf2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00688, 0x00303232, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00d8d8d8, 0x00a5a6a6, 0x005e6060, 0x00cee, 0x00477, 0x00611713, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a22822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x006e1914, 0x00477, 0x00434545, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x00686a6a, 0x00477, 0x003611f, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00502221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00767, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004b2221, 0x00dc2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00551512, 0x00477, 0x005c5e5e, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a2a4a4, 0x00477, 0x005d1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ab2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005b2321, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02c22, 0x003f1310, 0x00477, 0x00777979, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x00577, 0x00c8281f, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00682421, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x002c10e, 0x00699, 0x00949595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00477, 0x007e1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00612421, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c4271f, 0x001ded, 0x00dff, 0x00aeafaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00171818, 0x00581511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00602421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00542321, 0x00e92e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b5251d, 0x0011bb, 0x00171818, 0x00c5c6c6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00202222, 0x00521411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00caa, 0x00212323, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00bdd, 0x00661713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00572321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00c32b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ba251e, 0x00caa, 0x00262828, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c6c7c7, 0x00477, 0x00961f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00777, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00832622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22920, 0x0018dc, 0x001e2020, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007a7c7c, 0x00477, 0x00d52a21, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x003712f, 0x00cee, 0x00cdcdcd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00252727, 0x003911f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009d2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009c2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00811c16, 0x00477, 0x009a9b9b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c8c9c9, 0x00477, 0x008a1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005b2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbb, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00656, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00d72a21, 0x00daa, 0x00444646, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00727474, 0x00688, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00772522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006e1914, 0x00477, 0x00cfcfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x001d1e1e, 0x00411310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00992822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b22a23, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x0017dc, 0x00484a4a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c0c1c1, 0x00477, 0x00931f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00e22d24, 0x00ee2e24, 0x00ee2e24, 0x00be261e, 0x00477, 0x009d9e9e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00696b6b, 0x00999, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00d72c24, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00362020, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00171818, 0x004a1311, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791a15, 0x00477, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00477, 0x009b201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00412121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007e1b16, 0x00477, 0x00e6e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x00baa, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00a5221b, 0x00477, 0x00b2b3b3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00121313, 0x00531411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008b2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x0010bb, 0x00464848, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00adaeae, 0x00477, 0x00a3211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00432121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008e2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f1b16, 0x00477, 0x00878888, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00585a5a, 0x0011bb, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003b2120, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00471411, 0x00477, 0x006d6f6f, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00cee, 0x005a1512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008d2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x005f1713, 0x00477, 0x00171818, 0x007b7d7d, 0x00c6c7c7, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a4a6a6, 0x00477, 0x00ac231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003d2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00be2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x003f12f, 0x00477, 0x00477, 0x00acc, 0x002c2e2e, 0x004c4e4e, 0x00696b6b, 0x00898a8a, 0x00a8a9a9, 0x00c6c7c7, 0x00e5e6e6, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004f5151, 0x0018dc, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00c22b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302020, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00931f19, 0x00671813, 0x004612f, 0x002a10f, 0x00daa, 0x00477, 0x00477, 0x00477, 0x00477, 0x009bb, 0x00262828, 0x00444646, 0x00636565, 0x00818383, 0x00a1a2a2, 0x00bebfbf, 0x00dedede, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x008aa, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007b2522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171415, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2020, 0x009e2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x00bf261e, 0x00a3211b, 0x00851d17, 0x006a1814, 0x004c1310, 0x003111f, 0x0014cc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00588, 0x001e1f1f, 0x003d3f3f, 0x005c5e5e, 0x007a7c7c, 0x00999a9a, 0x00b8b9b9, 0x00d6d6d6, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009d9e9e, 0x00477, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00582321, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00c6271f, 0x00aa231c, 0x008d1e18, 0x00711915, 0x00541411, 0x003711f, 0x001bed, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00181919, 0x00363838, 0x00555757, 0x00737575, 0x00929393, 0x00b0b1b1, 0x00cfcfcf, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00454747, 0x001ced, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00b92a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00542321, 0x009e2822, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00cd2820, 0x00b0241c, 0x00941f19, 0x00771a15, 0x005b1612, 0x003e12f, 0x002310f, 0x00888, 0x00477, 0x00477, 0x00477, 0x00477, 0x00101111, 0x002e3030, 0x004e5050, 0x006b6d6d, 0x008b8c8c, 0x00a8a9a9, 0x00c8c9c9, 0x00e6e7e7, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00699, 0x006d1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00742522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x005a2321, 0x00732522, 0x008c2722, 0x00a42923, 0x00bd2a23, 0x00d52c24, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00d32a21, 0x00b7251d, 0x009a201a, 0x007e1b16, 0x00621713, 0x004512f, 0x002810f, 0x00caa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00acc, 0x00272929, 0x00464848, 0x00656767, 0x00838484, 0x00a2a4a4, 0x00c0c1c1, 0x00e0e0e0, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00929393, 0x00477, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00434, 0x001f1c1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x003b2120, 0x00542321, 0x006c2421, 0x00862622, 0x009e2822, 0x00b72a23, 0x00d02c23, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2b21, 0x00be261e, 0x00a1211a, 0x00851d17, 0x00681813, 0x004c1310, 0x002f11f, 0x0013cc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00699, 0x00202121, 0x003e4040, 0x005e6060, 0x007b7d7d, 0x009b9c9c, 0x00b9baba, 0x00d8d8d8, 0x00f7f7f7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x002b2d2d, 0x002a10e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b22a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00362020, 0x004e2221, 0x00672421, 0x007f2622, 0x00992822, 0x00b12a23, 0x00ca2b23, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00c5271f, 0x00a8221b, 0x008c1e18, 0x006f1914, 0x00531411, 0x003712f, 0x0019ed, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00191a1a, 0x00383a3a, 0x00565858, 0x00757777, 0x00939494, 0x00b2b3b3, 0x00d1d1d1, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a1a2a2, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302020, 0x00482221, 0x00612421, 0x007a2522, 0x00922722, 0x00ab2923, 0x00c42b23, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00cb2820, 0x00af231c, 0x00921f19, 0x00761a15, 0x00591512, 0x003d12f, 0x0021fe, 0x00788, 0x00477, 0x00477, 0x00477, 0x00477, 0x00121313, 0x00303232, 0x004f5151, 0x006d6f6f, 0x008c8d8d, 0x00aaabab, 0x00c9caca, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x00151616, 0x002d10f, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00de2d24, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00532321, 0x008a2722, 0x00bd2a23, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00d22921, 0x00b5251d, 0x009a201a, 0x007c1b16, 0x00611612, 0x004312f, 0x002810f, 0x00b99, 0x00477, 0x00477, 0x00477, 0x00477, 0x00bdd, 0x00292b2b, 0x00484a4a, 0x00666868, 0x00858686, 0x00a3a5a5, 0x00e4e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x002c2e2e, 0x00daa, 0x00c5271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00502221, 0x00a62923, 0x00e22d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x00d62a21, 0x00c7271f, 0x00b6251d, 0x00a6221b, 0x00941f19, 0x00841c17, 0x00741a15, 0x004e1310, 0x0021cb, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00aeafaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c2c3c3, 0x00202222, 0x00caa, 0x00ac231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131011, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x00ae2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x00d22920, 0x00c0261e, 0x00b0241c, 0x00a0211a, 0x008f1e18, 0x007f1b16, 0x006f1914, 0x005f1612, 0x004e1310, 0x003e12f, 0x002d11f, 0x001ced, 0x00caa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00101111, 0x00222323, 0x00343636, 0x00464848, 0x00585a5a, 0x00686a6a, 0x007a7c7c, 0x008c8d8d, 0x009d9e9e, 0x00aeafaf, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00959696, 0x00b3b4b4, 0x00d2d2d2, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00bebfbf, 0x00525454, 0x00477, 0x0020fe, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00522221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00191516, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00542321, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00dc2b22, 0x00cc2820, 0x00bc261e, 0x00ab231c, 0x009b201a, 0x008b1d18, 0x007a1b16, 0x006a1814, 0x00581511, 0x00491210, 0x003911f, 0x002810f, 0x0018dd, 0x00888, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00588, 0x00171818, 0x00272929, 0x00393c3c, 0x004b4d4d, 0x005d5f5f, 0x006d6f6f, 0x007f8181, 0x00929393, 0x00a3a5a5, 0x00b5b6b6, 0x00c6c7c7, 0x00d8d8d8, 0x00e9eaea, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b5b6b6, 0x00477, 0x00477, 0x00477, 0x00477, 0x00131414, 0x00313333, 0x00505252, 0x006c6e6e, 0x00808282, 0x00909191, 0x008a8b8b, 0x00787a7a, 0x00505252, 0x00171818, 0x00477, 0x00eba, 0x00721915, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00732522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00b9a, 0x00131112, 0x001a1717, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00492221, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00ac231c, 0x005a1512, 0x0023fe, 0x00888, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00acc, 0x001b1c1c, 0x002c2e2e, 0x003e4040, 0x00505252, 0x00626363, 0x00747676, 0x00858686, 0x00979898, 0x00a8a9a9, 0x00babbbb, 0x00cbcbcb, 0x00dddddd, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e8e8, 0x00477, 0x005f1612, 0x00982019, 0x007b1b16, 0x005f1612, 0x00421210, 0x002610f, 0x00caa, 0x00477, 0x00477, 0x00477, 0x00999, 0x0020fe, 0x00511411, 0x00951f19, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x007b2522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00544, 0x00988, 0x00dcc, 0x00111010, 0x00161314, 0x001b1718, 0x001f1b1c, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x003611f, 0x00477, 0x00111212, 0x004d4f4f, 0x00737575, 0x008a8b8b, 0x009c9d9d, 0x00adaeae, 0x00bebfbf, 0x00d2d2d2, 0x00e3e4e4, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e6e6, 0x00477, 0x00831c17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00da2b21, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00602321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00877, 0x00cbb, 0x0011ef, 0x00151313, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007a2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x0016dc, 0x00141515, 0x00979898, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cbcbcb, 0x00477, 0x009e211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00a12822, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x002a10e, 0x00161717, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a5a6a6, 0x00477, 0x00bf261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00db2d24, 0x00942722, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201d1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a6221b, 0x00477, 0x00a1a2a2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00828383, 0x00477, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00c02b23, 0x00772522, 0x008f2722, 0x00a62923, 0x00b72a23, 0x00bc2a23, 0x00bb2a23, 0x00ad2923, 0x00972822, 0x00762522, 0x00492221, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151313, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00592321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00691814, 0x008aa, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x0017dc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00662421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00561511, 0x00212222, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003b3d3d, 0x003811f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00732522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191717, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00622421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00e10f, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00181919, 0x00581511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00582321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171415, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004b2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00941f19, 0x00477, 0x00c5c6c6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00477, 0x00791b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003c2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00fee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00271f20, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00caa, 0x00555757, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cdcdcd, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191616, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aa2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a1814, 0x00477, 0x00cfcfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00522221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92a21, 0x00eba, 0x004d4f4f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00858686, 0x00477, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00b02923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00191616, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bc2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00721915, 0x00477, 0x00c7c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x0013cb, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00952722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1b, 0x00151314, 0x00dbc, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00101, 0x00767, 0x00dcc, 0x00121010, 0x00161314, 0x00181516, 0x00171515, 0x00141212, 0x0010ee, 0x00988, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00522221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x0012cb, 0x00424444, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003e4040, 0x003411f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00782522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fde, 0x00656, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00dbb, 0x00141212, 0x001b1819, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00161414, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b42a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c1b16, 0x00477, 0x00bcbdbd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00101111, 0x005f1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00592321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00b9a, 0x00121010, 0x00191617, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004a2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0016cc, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00babbbb, 0x00477, 0x00982019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00878, 0x0010ee, 0x00171515, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00878, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ab2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00871d17, 0x00477, 0x00b0b1b1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003c3e3e, 0x0012bb, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00656, 0x00ecd, 0x00151313, 0x001d191a, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00992822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2920, 0x00477, 0x004c4e4e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00727474, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008b2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00cab, 0x00131111, 0x001b1818, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00656, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006d2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00381210, 0x00bdd, 0x00cbcbcb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d5d5d5, 0x004c4e4e, 0x00477, 0x005a1612, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00372020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00a89, 0x0011ff, 0x00191616, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00101, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004a2221, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00477, 0x009e9f9f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00e7e8e8, 0x00d6d6d6, 0x00c5c6c6, 0x00b3b4b4, 0x00a2a4a4, 0x00909191, 0x007e8080, 0x00626464, 0x002f3131, 0x00477, 0x00baa, 0x007d1b16, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00892722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00767, 0x00fde, 0x00161414, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00d32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00477, 0x00686a6a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00e0e0e0, 0x00cecece, 0x00bcbdbd, 0x00aaabab, 0x009a9b9b, 0x00888989, 0x00777979, 0x00656767, 0x00555757, 0x00434545, 0x00303232, 0x001f2020, 0x00eff, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x0015dc, 0x003b1210, 0x007d1b16, 0x00d72a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bd2a23, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00dbc, 0x00141213, 0x001c1819, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ae2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bd261e, 0x00ba9, 0x00393b3b, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00e8e9e9, 0x00d8d8d8, 0x00c6c7c7, 0x00b5b6b6, 0x00a3a5a5, 0x00929393, 0x007f8181, 0x006e7070, 0x005d5f5f, 0x004c4e4e, 0x003a3c3c, 0x00292b2b, 0x00181919, 0x00799, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00577, 0x0016dc, 0x002510f, 0x003612f, 0x004512f, 0x00561511, 0x00651713, 0x00761a15, 0x00851d17, 0x00971f19, 0x00a7221b, 0x00b7251d, 0x00c7281f, 0x00d72a21, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c32b23, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00b9a, 0x00121010, 0x001a1717, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00712522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x001eed, 0x001b1c1c, 0x00e4e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x00565858, 0x00444646, 0x00323434, 0x00202121, 0x00f1010, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00caa, 0x001cee, 0x002d11f, 0x003c12f, 0x004d1310, 0x005e1612, 0x006e1914, 0x007e1b16, 0x008e1e18, 0x009e211a, 0x00ae231c, 0x00be261e, 0x00cf2920, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00888, 0x0010ef, 0x00171516, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00423f3f, 0x006b6869, 0x00828080, 0x00807e7e, 0x00555253, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00471310, 0x00699, 0x00c2c3c3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x001e2020, 0x0011bb, 0x00351110, 0x004412f, 0x00551411, 0x00641713, 0x00751a15, 0x00841c17, 0x00961f19, 0x00a6221b, 0x00b7251d, 0x00c7271f, 0x00d72a21, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00b52a23, 0x00532321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00766, 0x00ecc, 0x00151314, 0x001d191a, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00646162, 0x00929091, 0x00c2c1c1, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c4c4, 0x002f2b2c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a62923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c1e18, 0x00477, 0x007d7f7f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00525454, 0x00688, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x00d32c23, 0x00c52b23, 0x00b32a23, 0x00952722, 0x006f2521, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00565354, 0x00858384, 0x00b4b3b3, 0x00e3e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a09e9f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004e2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00eba, 0x00383a3a, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00969797, 0x00477, 0x00771a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00db2d24, 0x00cd2c23, 0x00bf2b23, 0x00b12a23, 0x00a32823, 0x00942722, 0x00872622, 0x00782522, 0x006b2421, 0x005c2321, 0x004e2221, 0x00402121, 0x00322020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00484546, 0x00787677, 0x00a6a5a5, 0x00d6d5d5, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00877, 0x00cbb, 0x00fdd, 0x00211e1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b32a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00531411, 0x008aa, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d2d2d2, 0x00bdd, 0x003a1210, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00d42c23, 0x00c62b23, 0x00b82a23, 0x00aa2923, 0x009c2822, 0x008e2722, 0x00802622, 0x00732522, 0x00642421, 0x00562321, 0x00482221, 0x00392120, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003b3838, 0x006b6869, 0x00999798, 0x00c8c7c7, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00dbc, 0x00161414, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003e2121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x00707272, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x002c2e2e, 0x0013cb, 0x00d22921, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12923, 0x00792522, 0x006b2421, 0x005d2321, 0x00502221, 0x00412121, 0x00342020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302c2d, 0x005e5b5b, 0x008c8a8b, 0x00bbbaba, 0x00e9e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00181616, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00852622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005d1612, 0x00bdd, 0x00e6e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00676969, 0x00477, 0x00a3211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2b23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x003b2120, 0x003b2120, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00272324, 0x00514e4e, 0x007e7c7d, 0x00aeacad, 0x00dcdcdc, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bf2b23, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x0010bb, 0x00585a5a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00452221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00342020, 0x00412121, 0x00502221, 0x005d2321, 0x006b2421, 0x007a2522, 0x00872622, 0x00962822, 0x00a52923, 0x00b32a23, 0x00c12b23, 0x00cf2c23, 0x00dc2d24, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00ca2b23, 0x00842622, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00726f70, 0x00a09e9f, 0x00d0cfcf, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x001c1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00b9251d, 0x00477, 0x00a6a7a7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00131414, 0x002c10e, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00742522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2020, 0x00382120, 0x00472221, 0x00542321, 0x00642421, 0x00722522, 0x00802622, 0x008e2722, 0x009c2822, 0x00aa2923, 0x00b82a23, 0x00c62b23, 0x00d42c23, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2d24, 0x005d2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00646162, 0x00939192, 0x00c2c1c1, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0012f10, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00362020, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003c3e3e, 0x00baa, 0x00c6271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00be2a23, 0x004d2221, 0x005c2321, 0x00692421, 0x00772522, 0x00852622, 0x00932722, 0x00a12822, 0x00b12923, 0x00be2a23, 0x00cd2c23, 0x00da2d24, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00642421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2829, 0x00575454, 0x00868485, 0x00b4b3b3, 0x00e3e3e3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00442121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007e1b16, 0x00477, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007e8080, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92d23, 0x00d92a21, 0x00c8281f, 0x00b9251d, 0x00a8221b, 0x00992019, 0x00871d17, 0x00771a15, 0x00661713, 0x005b1612, 0x005c1612, 0x00801c16, 0x00d22921, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52d24, 0x003e2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00494646, 0x00797777, 0x00a7a5a6, 0x00d6d6d6, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00e2e3e3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00799, 0x004d1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00d32a21, 0x00c2271f, 0x00b1241c, 0x00a1211a, 0x00911f19, 0x00811c16, 0x00701914, 0x00611612, 0x00501410, 0x004112f, 0x002f11f, 0x001ffe, 0x00eba, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00dff, 0x001d1e1e, 0x001b1c1c, 0x00477, 0x00a99, 0x00982019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a82923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c3839, 0x00c9c8c8, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2020, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00477, 0x00a4a6a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003a3c3c, 0x0019ed, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00dc2b22, 0x00cb2820, 0x00bc261e, 0x00ab231c, 0x009b201a, 0x008b1d18, 0x007a1b16, 0x006a1814, 0x00591512, 0x00491210, 0x003911f, 0x002911f, 0x0018dd, 0x00999, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00151616, 0x00262727, 0x00373a3a, 0x00494b4b, 0x005a5c5c, 0x006b6d6d, 0x007d7f7f, 0x008e8f8f, 0x00a0a1a1, 0x00b2b3b3, 0x00c3c4c4, 0x00d5d5d5, 0x00e6e7e7, 0x00f7f7f7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dadada, 0x003b3d3d, 0x00788, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00502221, 0x00812622, 0x00a42923, 0x00bc2a23, 0x00c92b23, 0x00c92b23, 0x00ba2a23, 0x00a22822, 0x00732522, 0x003a2120, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x001ced, 0x00393b3b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00477, 0x004c1310, 0x00a5221b, 0x00a4221b, 0x00941f19, 0x00841c17, 0x00731a15, 0x00631713, 0x00531411, 0x004312f, 0x00331210, 0x002310f, 0x0012cb, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00acc, 0x001a1c1b, 0x002c2e2e, 0x003e4040, 0x004f5151, 0x00616262, 0x00737575, 0x00858686, 0x00969797, 0x00a7a8a8, 0x00b8b9b9, 0x00cacaca, 0x00dcdcdc, 0x00eceded, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x00151616, 0x004d1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00982822, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00b72a23, 0x00562321, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00821c17, 0x00477, 0x00bebfbf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x003e4040, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00101111, 0x00222323, 0x00343636, 0x00464848, 0x00575959, 0x00686a6a, 0x007a7c7c, 0x008b8c8c, 0x009d9e9e, 0x00adaeae, 0x00c0c1c1, 0x00d2d2d2, 0x00e3e4e4, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00616262, 0x0012cb, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008e2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c6c5c5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003a2120, 0x00a82923, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c42b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0012bb, 0x00464848, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dadada, 0x00c2c3c3, 0x00cdcdcd, 0x00d9d9d9, 0x00e9eaea, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007f8181, 0x00477, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bab9b9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00722522, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x00c6271f, 0x00b1241c, 0x00ab231c, 0x00bd261e, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00761a15, 0x00477, 0x00cacaca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00eba, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00932722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bdbbbc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x009a2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82a21, 0x007f1b16, 0x003712f, 0x00788, 0x00477, 0x00477, 0x00477, 0x00477, 0x00688, 0x00391210, 0x00971f19, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x00daa, 0x00535555, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x001c1d1d, 0x00451310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00772522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cfcece, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00383435, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00631713, 0x00898, 0x00477, 0x00373939, 0x00787a7a, 0x00a7a8a8, 0x00bbbcbc, 0x00bbbcbc, 0x00a5a6a6, 0x00707272, 0x00212323, 0x00477, 0x002d10f, 0x00c5271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a1814, 0x00588, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a0a1a1, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00492221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00e8e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00862622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a5221b, 0x0015cc, 0x00699, 0x00676969, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00a2a4a4, 0x00151616, 0x0011cb, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00999, 0x00616262, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eceded, 0x001a1b1b, 0x002d10f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332f30, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccbcb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c2221, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008b1d18, 0x00477, 0x00323434, 0x00d1d1d1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dbdbdb, 0x001d1f1f, 0x0019dc, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005d1612, 0x00799, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00565858, 0x00688, 0x00b9251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00782522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00676465, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00747272, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c12b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c201a, 0x00477, 0x004b4d4d, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c6c7c7, 0x00588, 0x00671813, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2820, 0x00577, 0x006d6f6f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a0a1a1, 0x00477, 0x00731a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a7a5a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9c8c8, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1717, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00582321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00fbb, 0x00353737, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00565858, 0x00eba, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00511511, 0x00cee, 0x00e9eaea, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x00f1010, 0x003311f, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005c2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cbcacb, 0x00302c2d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ae2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005d1612, 0x00799, 0x00d7d7d7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a7a8a8, 0x00477, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c0261e, 0x00477, 0x007a7c7c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00393b3b, 0x00eba, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00727070, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x007f7d7e, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2b21, 0x00a99, 0x005f6060, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cdcdcd, 0x00477, 0x00992019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00451310, 0x00131414, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007d7f7f, 0x00477, 0x00901e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00dbdada, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00d1d0d1, 0x00a4a2a2, 0x00737171, 0x00413e3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151313, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00912722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c1b16, 0x00477, 0x00cdcdcd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cacaca, 0x00477, 0x00982019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b3241d, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x00699, 0x004d1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x004b2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00757273, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dedede, 0x00b0afaf, 0x00817f7f, 0x00524f50, 0x00292526, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x001ded, 0x003b3d3d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a9aaaa, 0x00477, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00bf2b23, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003811f, 0x001a1b1b, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00222424, 0x001bed, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00822622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2a2b, 0x00e7e6e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ececec, 0x00bdbcbd, 0x008e8c8c, 0x005f5c5d, 0x00322e2f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00722522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009f211a, 0x00477, 0x00a6a7a7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005d5f5f, 0x00baa, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x007e2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a7221b, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005d5f5f, 0x00477, 0x00af231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bb2a23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a4a2a2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cac9ca, 0x009b999a, 0x006c6a6a, 0x003e3a3b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131011, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c92b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003b1210, 0x001c1d1d, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00dff, 0x00561511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006e2521, 0x002d2020, 0x00df2d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x002d10e, 0x00212323, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a7a7, 0x00477, 0x006c1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00464344, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00d7d7d7, 0x00a9a7a8, 0x007a7878, 0x004b4748, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c3271f, 0x00477, 0x00828383, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008e8f8f, 0x00477, 0x00b8251d, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00302020, 0x00231f20, 0x00892722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c201a, 0x00477, 0x00a2a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00121313, 0x002e10f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00e5e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e4e4e4, 0x00b6b4b5, 0x00878585, 0x00585555, 0x002c292a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aa2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e1612, 0x009bb, 0x00e6e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00232525, 0x003010f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a32823, 0x00231f20, 0x00231f20, 0x00322020, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x0024fe, 0x002c2e2e, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x003f4141, 0x00b99, 0x00c7281f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a22822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00807e7f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c3c2c2, 0x00949293, 0x00656262, 0x00373334, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00baa, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b1b2b2, 0x00477, 0x00951f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00932722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00b0b1b1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00858686, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32c23, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2c2c, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0cfcf, 0x00a2a0a1, 0x00726f70, 0x00444041, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008e2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00811c16, 0x00477, 0x00c8c9c9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00474949, 0x0017dc, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00c12b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x001adc, 0x00393b3b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cacaca, 0x008aa, 0x00471310, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00502221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a7a6a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dddddd, 0x00aeacad, 0x007f7d7e, 0x00514e4e, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x0021fd, 0x00363838, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x00477, 0x00711915, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009e2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00831c17, 0x00477, 0x00b7b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00262828, 0x0018dc, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00882622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c3839, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00423f3f, 0x00423f3f, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2521, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a4221b, 0x00477, 0x00a1a3a3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x00788, 0x00d22921, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2d24, 0x00c62b23, 0x00a92923, 0x00832622, 0x005c2321, 0x00342020, 0x00402121, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x001eed, 0x00232525, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00e8e9e9, 0x00d8d8d8, 0x00c6c7c7, 0x00b5b6b6, 0x00a3a5a5, 0x00939494, 0x00808282, 0x006f7171, 0x005e6060, 0x00343737, 0x00477, 0x00a9231b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c02b23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aeacad, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x003b3838, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x006c6a6a, 0x009a9899, 0x00c9c8c8, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00dedede, 0x00555253, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00989, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c62b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003f1210, 0x00191a1a, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00f1111, 0x004f1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b2241d, 0x00999, 0x002a2c2c, 0x00d2d2d2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00dedede, 0x00cdcdcd, 0x00bcbdbd, 0x00aaabab, 0x009a9b9b, 0x00888989, 0x00777979, 0x00656767, 0x00555757, 0x00444646, 0x00313333, 0x001f2020, 0x00f1010, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00baa, 0x001bed, 0x002c11f, 0x00741a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x003e2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00474445, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322e2f, 0x005f5c5d, 0x008d8b8c, 0x00bdbcbd, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00502221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c7271f, 0x00477, 0x007d7f7f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00929393, 0x00477, 0x00b3241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ad231c, 0x0014cc, 0x00799, 0x005c5e5e, 0x00b2b3b3, 0x00e2e3e3, 0x00efefef, 0x00e6e7e7, 0x00d5d5d5, 0x00c4c5c5, 0x00b2b3b3, 0x00a1a3a3, 0x008f9090, 0x007e8080, 0x006c6e6e, 0x005c5e5e, 0x004a4c4c, 0x00393c3c, 0x00282a2a, 0x00171818, 0x00699, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00577, 0x0015dc, 0x002510f, 0x00351110, 0x004512f, 0x00551411, 0x00641713, 0x00751a15, 0x00841c17, 0x00951f19, 0x00a6221b, 0x00b6251d, 0x00c6271f, 0x00d62a21, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b0aeaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00535051, 0x00828080, 0x00b1b0b0, 0x00dfdedf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009d9b9b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a72923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00799, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00272929, 0x002d10f, 0x00ee2e24, 0x00df2c22, 0x00bd261e, 0x00a2211b, 0x00961f19, 0x009b201a, 0x00b7251d, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92a21, 0x00651713, 0x00daa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00daa, 0x001dfe, 0x002d11f, 0x003e11f, 0x004e1310, 0x005f1612, 0x006e1914, 0x007e1b16, 0x008f1e18, 0x009e211a, 0x00af231c, 0x00be261e, 0x00cf2920, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a92923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302c2d, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00484546, 0x00777475, 0x00a5a4a4, 0x00d3d2d2, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcece, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x00daa, 0x00585a5a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b6b7b7, 0x00477, 0x002eec, 0x002e11f, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x001bed, 0x00481310, 0x00761a15, 0x00a3211b, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00af231c, 0x008c1e18, 0x00871d17, 0x00881d17, 0x00982019, 0x00a8221b, 0x00b8251d, 0x00c8281f, 0x00d82a21, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72c24, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00636061, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c3839, 0x006b6969, 0x00999798, 0x00c8c7c7, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008a2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00861d17, 0x00477, 0x00c3c4c4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004b4d4d, 0x00477, 0x00588, 0x003d3f3f, 0x00787a7a, 0x00adaeae, 0x00c6c7c7, 0x00d6d6d6, 0x00d2d2d2, 0x00b3b4b4, 0x00888989, 0x00575959, 0x00262828, 0x00477, 0x00477, 0x00477, 0x0014cc, 0x00411210, 0x006e1914, 0x009a201a, 0x00c9281f, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00d62c24, 0x00c72b23, 0x00b92a23, 0x00ab2923, 0x009e2822, 0x00902722, 0x00822622, 0x004a2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00848182, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322e2f, 0x005f5c5d, 0x008d8b8c, 0x00bdbbbc, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c1c0c0, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00db2d24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x0023fe, 0x00313333, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dbdbdb, 0x001e2020, 0x00828383, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c1c2c2, 0x008f9090, 0x00606161, 0x002d2f2f, 0x00799, 0x00477, 0x00477, 0x00daa, 0x00391210, 0x00651713, 0x00941f19, 0x00c0261e, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00dc2d24, 0x00cd2c23, 0x00c02b23, 0x00b22a23, 0x00a42923, 0x00962722, 0x00872622, 0x00792522, 0x006b2421, 0x005e2321, 0x00502221, 0x00422121, 0x00342020, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00918f90, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00535051, 0x00828080, 0x00b1b0b0, 0x00dfdedf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008e8c8c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006b2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a7221b, 0x00477, 0x009e9f9f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e1e2e2, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00c9caca, 0x00999a9a, 0x00676969, 0x00373939, 0x00acc, 0x00477, 0x00477, 0x00999, 0x003111f, 0x005f1612, 0x008c1e18, 0x00b9251d, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2d24, 0x00b32a23, 0x008b2722, 0x00642421, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a3a1a1, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00474445, 0x00777475, 0x00a5a4a4, 0x00d3d2d2, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00441310, 0x00161717, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00d2d2d2, 0x00a1a2a2, 0x006f7171, 0x003f4141, 0x00101111, 0x00477, 0x00477, 0x00688, 0x002910f, 0x00571511, 0x00841c17, 0x00b1241c, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02d24, 0x00b92a23, 0x00922722, 0x006b2421, 0x00432121, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00636061, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00494646, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003b3838, 0x006b6869, 0x00989697, 0x00c7c6c6, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bab9b9, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ff, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004d2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2820, 0x00477, 0x00787a7a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00dadada, 0x00a8a9a9, 0x00787a7a, 0x00474949, 0x00171818, 0x00477, 0x00477, 0x00477, 0x0023fe, 0x004e1310, 0x007d1b16, 0x00a9231b, 0x00d72a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d24, 0x00c02b23, 0x009a2822, 0x00712522, 0x004b2221, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00625f60, 0x00413e3f, 0x00615e5f, 0x008d8b8c, 0x00bcbabb, 0x00eaeaea, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004d4a4b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00434, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a32823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00671813, 0x00699, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e1e2e2, 0x00b1b2b2, 0x00808282, 0x00505252, 0x001e2020, 0x00477, 0x00477, 0x00477, 0x0019dd, 0x00471310, 0x00741a15, 0x00a2211b, 0x00cf2920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00c72b23, 0x009c2822, 0x00682421, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bbbaba, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00352020, 0x00e92e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00fba, 0x00535555, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00b9baba, 0x00898a8a, 0x00585a5a, 0x00272929, 0x00477, 0x00477, 0x00477, 0x0012cb, 0x004012f, 0x006d1814, 0x009a201a, 0x00c7281f, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52d24, 0x00982822, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00272324, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00484546, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00bfc0c0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00c2c3c3, 0x00919292, 0x00606161, 0x002f3131, 0x00799, 0x00477, 0x00477, 0x00daa, 0x003812f, 0x00651713, 0x00911f19, 0x00c0261e, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00662421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00494646, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b4b3b3, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x0027fe, 0x002d2f2f, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cacaca, 0x00999a9a, 0x00686a6a, 0x00373939, 0x00cee, 0x00477, 0x00477, 0x00888, 0x003011f, 0x005d1612, 0x008b1d18, 0x00bb251e, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00752522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008d8b8c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00474445, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00672421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x00477, 0x00999a9a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00d2d2d2, 0x00a2a4a4, 0x00707272, 0x00404242, 0x00101111, 0x00477, 0x00477, 0x0010bb, 0x00551511, 0x00c2271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00562321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00d3d2d2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0aeaf, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00be2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00491310, 0x00141515, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dbdbdb, 0x00a4a6a6, 0x005e6060, 0x00bdd, 0x00688, 0x007d1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00494646, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171415, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00492221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ce2920, 0x00577, 0x00727474, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x004f5151, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00642421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00adacac, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a02822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b1814, 0x00588, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003d3f3f, 0x0011bb, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00a62923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00d0cfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322020, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x0011bb, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b3b4b4, 0x00477, 0x00a6221b, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00151313, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00464243, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00832622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00b8b9b9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e4e5e5, 0x00477, 0x00871d17, 0x00ee2e24, 0x00ee2e24, 0x00e02d24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00211, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00858384, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d52c24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x002b10e, 0x00292b2b, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dedede, 0x00477, 0x008a1d18, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00cbcacb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00632421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00477, 0x00949595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x00ae231c, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00838181, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00767, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004d1411, 0x00101111, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00595b5b, 0x0011bb, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00a32823, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00dbc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00e1e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00452221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12920, 0x00688, 0x006e7070, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e9e9, 0x009bb, 0x005d1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006c2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x001e1b1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00726f70, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009c2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f1914, 0x00477, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00828383, 0x00477, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00e52d24, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00dcdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00c8c7c7, 0x00787576, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x0014cb, 0x004a4c4c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x001d1f1f, 0x003a1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00686566, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfbfc, 0x00d3d2d2, 0x00a5a4a4, 0x00777475, 0x00484546, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007e2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00452221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d3d2d2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x00b1b0b0, 0x00838181, 0x00545152, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00656, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002e10f, 0x00252727, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003d3f3f, 0x001ced, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00bb2a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00655, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00615e5f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00bebdbd, 0x008f8d8d, 0x00615e5f, 0x00332f30, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00602421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b4241d, 0x00477, 0x00909191, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcfcf, 0x00477, 0x007a1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cac9c9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cac9ca, 0x009b999a, 0x006d6b6b, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b72a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00521511, 0x00e1010, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00999, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00d52c24, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbb, 0x00000, 0x001a1717, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00585555, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00d6d6d6, 0x00a8a6a7, 0x007a7878, 0x004b4748, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00788, 0x00696b6b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d5d5d5, 0x00d2d2d2, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00bdd, 0x00581512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00100, 0x00767, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e3e3, 0x00b4b3b3, 0x00868485, 0x00575454, 0x002c292a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00982822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00731a15, 0x00477, 0x00d5d5d5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00383a3a, 0x00477, 0x00acc, 0x00373939, 0x00676969, 0x00999a9a, 0x00c9caca, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00898a8a, 0x00477, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00322020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00111010, 0x00000, 0x00191516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004e4b4c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efeeee, 0x00c1c0c0, 0x00929091, 0x00646162, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2020, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x0018dc, 0x00444646, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9caca, 0x00477, 0x00571511, 0x00661713, 0x003911f, 0x00daa, 0x00477, 0x00477, 0x00799, 0x002f3131, 0x00606161, 0x00919292, 0x00c2c3c3, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00202222, 0x003511f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a02822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00545, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfbfc, 0x00cdcccc, 0x009e9d9d, 0x00706d6e, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007b2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00971f19, 0x00477, 0x00afb0b0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x00b99, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00c9281f, 0x009a201a, 0x006e1914, 0x004012f, 0x0013cb, 0x00477, 0x00477, 0x00477, 0x00272929, 0x00595b5b, 0x00898a8a, 0x00bbbcbc, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00adaeae, 0x00477, 0x00992019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00492221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00474445, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00d02c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003211f, 0x00222424, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e9e9, 0x009bb, 0x005c1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2920, 0x00a3211b, 0x00741a15, 0x00481310, 0x0019dd, 0x00477, 0x00477, 0x00477, 0x00202221, 0x00505252, 0x00828383, 0x00b2b3b3, 0x00e4e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00424444, 0x0018dc, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00be2a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b0aeaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2829, 0x00575454, 0x00868485, 0x00b0aeaf, 0x00c7c6c6, 0x00c2c1c1, 0x00918f90, 0x00332f30, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ba251e, 0x00477, 0x008b8c8c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00838484, 0x00477, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72a21, 0x00a9231b, 0x007c1b16, 0x004e1310, 0x0021fe, 0x00477, 0x00477, 0x00477, 0x00181919, 0x004a4c4c, 0x00797b7b, 0x00abacac, 0x00dcdcdc, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d3d3d3, 0x00477, 0x00761a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00545, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00413e3f, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x004a4747, 0x00797777, 0x00a8a6a7, 0x00d6d6d6, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e7e7, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b02923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00561511, 0x00cee, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x001d1f1f, 0x003a1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c42b23, 0x00bd2a23, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00b1241c, 0x00831c17, 0x00551411, 0x002810f, 0x00577, 0x00477, 0x00477, 0x00121313, 0x00414343, 0x00737575, 0x00a3a5a5, 0x00d5d5d5, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00676969, 0x00898, 0x00d52a21, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00dbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a19fa0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x006c6a6a, 0x009b999a, 0x00cac9c9, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0afaf, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00101, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82a21, 0x00999, 0x00646666, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00452221, 0x00231f20, 0x00241f20, 0x00402121, 0x00672421, 0x008f2722, 0x00b72a23, 0x00de2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00b8251d, 0x00891d17, 0x005d1612, 0x002e11f, 0x00888, 0x00477, 0x00477, 0x00cee, 0x003a3c3c, 0x006b6d6d, 0x009c9d9d, 0x00cdcdcd, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00cee, 0x00541512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00872622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00111, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312d2e, 0x005f5c5c, 0x008d8b8c, 0x00bdbbbc, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00652421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00871d17, 0x00477, 0x00c9caca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003e4040, 0x001ced, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00b92a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00522221, 0x00892722, 0x00c12b23, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00bd261e, 0x00911f19, 0x00631713, 0x003712f, 0x00baa, 0x00477, 0x00477, 0x008aa, 0x00323434, 0x00636565, 0x00959696, 0x00c5c6c6, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00636565, 0x00577, 0x00c7281f, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00474445, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00524e4f, 0x00807e7e, 0x00b0aeaf, 0x00dedede, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00363233, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008a2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1310, 0x001d1e1e, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcfcf, 0x00477, 0x007a1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x006c2421, 0x00b52a23, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x00c6271f, 0x00982019, 0x006b1814, 0x003c12f, 0x0010bb, 0x00477, 0x00477, 0x00588, 0x002a2c2c, 0x005d5f5f, 0x008c8d8d, 0x00bebfbf, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a7a7, 0x00477, 0x005e1613, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00434, 0x00000, 0x00000, 0x00171516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00625f60, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00454142, 0x00737171, 0x00a3a1a1, 0x00d1d0d1, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a02822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a11f, 0x00474949, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00999, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00d52c24, 0x00251f20, 0x00231f20, 0x00251f20, 0x00752522, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00cc2820, 0x009f211a, 0x00711915, 0x00431210, 0x0017dc, 0x00477, 0x00477, 0x00477, 0x00242626, 0x00545656, 0x00868787, 0x00b5b6b6, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009e9f9f, 0x00799, 0x002e11f, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00686566, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00383435, 0x00666464, 0x00969494, 0x00c4c3c4, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002510f, 0x004e5050, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00bdd, 0x00581512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00812622, 0x00231f20, 0x00422121, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00df2c22, 0x00df2c22, 0x00de2b22, 0x00d12920, 0x00d12920, 0x00d12920, 0x00c9281f, 0x00c2271f, 0x00c2271f, 0x00c2271f, 0x00b3241d, 0x00b3241d, 0x00b3241d, 0x00ac231c, 0x00a5221b, 0x00a5221b, 0x00a5221b, 0x009a201a, 0x00a6221b, 0x00c9281f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00a6221b, 0x00781a15, 0x004b1310, 0x001ded, 0x00477, 0x00477, 0x00477, 0x001c1d1d, 0x004d4f4f, 0x007d7f7f, 0x00aeafaf, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x004d4f4f, 0x00477, 0x002f10f, 0x00d62a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00686566, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a4a2a2, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2a2a, 0x00595657, 0x00898787, 0x00b7b5b6, 0x00e6e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00972822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003d1210, 0x002f3131, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00666868, 0x00477, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00312020, 0x00642421, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00b6251d, 0x006f1914, 0x00401210, 0x002710f, 0x002110f, 0x0018ed, 0x0012cb, 0x0012cb, 0x0011cc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x001bed, 0x00731a15, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00db2b22, 0x00ac231c, 0x00801c16, 0x00511411, 0x002510e, 0x00477, 0x00477, 0x00477, 0x00151616, 0x00414343, 0x005b5d5d, 0x00626363, 0x004e5050, 0x001c1d1d, 0x00477, 0x00a99, 0x00731a15, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004a4747, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x004c494a, 0x007c797a, 0x00aaa8a8, 0x00d9d8d9, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00777, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00772522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00731a15, 0x00588, 0x00e0e1e1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aaabab, 0x00477, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009e2822, 0x00712522, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00941f19, 0x0026fe, 0x00477, 0x00699, 0x00303232, 0x00535555, 0x00626363, 0x00626363, 0x00626464, 0x00717373, 0x00717373, 0x00717373, 0x00797b7b, 0x00818383, 0x00818383, 0x00818383, 0x00919292, 0x00919292, 0x00919292, 0x00999a9a, 0x00a1a2a2, 0x00a1a2a2, 0x00a1a2a2, 0x00b0b1b1, 0x00b0b1b1, 0x00b0b1b1, 0x00b7b8b8, 0x00c0c1c1, 0x00c0c1c1, 0x00c0c1c1, 0x00cfcfcf, 0x00d0d0d0, 0x00d0d0d0, 0x00c4c5c5, 0x00979898, 0x00484a4a, 0x00477, 0x0018dc, 0x00ae231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02c22, 0x00b5251d, 0x00851d17, 0x00591512, 0x003711f, 0x001dfe, 0x001aed, 0x002410e, 0x004d1310, 0x00871d17, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22c23, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbb, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00676465, 0x004e4b4c, 0x006f6c6d, 0x009d9b9b, 0x00cccbcb, 0x00f7f7f7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00462221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00577, 0x00656767, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aeafaf, 0x009bb, 0x003111f, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x007f2622, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2820, 0x00351110, 0x00477, 0x002b2d2d, 0x009a9b9b, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9caca, 0x00282a2a, 0x00999, 0x00ab231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008c8a8b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00477, 0x00a2a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00787a7a, 0x00588, 0x003111f, 0x00db2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ae2923, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ad231c, 0x0010bb, 0x00f1110, 0x00989999, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x002a2c2c, 0x0013cb, 0x00db2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x008e2722, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x003611f, 0x00588, 0x007b7d7d, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00a0a1a1, 0x00232524, 0x00477, 0x005a1612, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ce2c23, 0x00d52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00999, 0x00272929, 0x00dadada, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cdcdcd, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00312020, 0x00582321, 0x00802622, 0x00a72923, 0x00cf2c23, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00972822, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00585555, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c42b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x004f1411, 0x00477, 0x001b1c1c, 0x006e7070, 0x00b3b4b4, 0x00cdcdcd, 0x00dadada, 0x00c4c5c5, 0x009fa0a0, 0x005e6060, 0x00161717, 0x00477, 0x002d10f, 0x00b1241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00c12b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2820, 0x0012cb, 0x00252727, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c4e4e, 0x0014cb, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00d52c23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00522221, 0x00762522, 0x00912722, 0x009e2822, 0x00a22823, 0x00912722, 0x00782522, 0x004f2221, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a5a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003f2121, 0x00e12d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x00411310, 0x00577, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x0017dc, 0x00531411, 0x00b1241c, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x009a2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x002c10e, 0x00101111, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b2b3b3, 0x00477, 0x00961f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2b2c, 0x00e9e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00af231c, 0x00971f19, 0x00982019, 0x00ab231c, 0x00c7271f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a32823, 0x00672421, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00531512, 0x00477, 0x00aeafaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00212323, 0x003711f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00676465, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00cc2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00602421, 0x00402121, 0x00e22d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00831c17, 0x00477, 0x007b7d7d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00858686, 0x00477, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003c2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b6b4b5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00812622, 0x00df2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c72b23, 0x006f2521, 0x00281f20, 0x002d2020, 0x00cc2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00688, 0x00484a4a, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e8e8, 0x008aa, 0x00611612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008d2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00383435, 0x00f1f1f1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00373334, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x006a2421, 0x00a72923, 0x00d62c24, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00d82c24, 0x00b32a23, 0x00832622, 0x00452221, 0x00231f20, 0x00231f20, 0x00241f20, 0x00aa2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22920, 0x0016cc, 0x00232525, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00585a5a, 0x00daa, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00dc2d24, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00787576, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00272324, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00666, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00302020, 0x00302020, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007f2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x003211f, 0x00dff, 0x00d0d0d0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bfc0c0, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00888, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00c6c5c5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c7c6c6, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00582321, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005b1612, 0x00477, 0x00a4a6a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x002b2d2d, 0x002c10e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc2a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00191616, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00423f3f, 0x00f7f7f7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006d6b6b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2120, 0x00de2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008b1d18, 0x00477, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00919292, 0x00477, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00442121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001d191a, 0x00161314, 0x00dbc, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00898787, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bfbebe, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00c62b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b7251d, 0x00999, 0x00414343, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00dff, 0x00561511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00545, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00d4d3d3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bfbebe, 0x002c2829, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00777, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72a21, 0x001adc, 0x001d1f1f, 0x00e8e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00636565, 0x00999, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004e4b4c, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00d2d1d2, 0x00726f70, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00141213, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00782522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x003912f, 0x00acc, 0x00c9caca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00477, 0x00801c16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00722522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00999798, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00c4c3c4, 0x00969494, 0x00666464, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00171415, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00522221, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00641713, 0x00477, 0x009c9d9d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00363838, 0x0022fd, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00e1e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfbfc, 0x00d3d2d2, 0x00a5a4a4, 0x00767374, 0x00464344, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x00db2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00951f19, 0x00477, 0x00666868, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009e9f9f, 0x00477, 0x00aa231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c595a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e2e2, 0x00b4b3b3, 0x00848283, 0x00555253, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00c02b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bd261e, 0x00ba9, 0x00393b3b, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00131414, 0x004a1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aaa9a9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00c3c2c2, 0x00949293, 0x00646162, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009a2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00db2b22, 0x0020ed, 0x001a1b1b, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00707272, 0x00688, 0x00d22920, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00989, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312d2e, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00d1d0d1, 0x00a3a1a1, 0x00727070, 0x00454142, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x003f1210, 0x008aa, 0x00c1c2c2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x00477, 0x00751a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00696667, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x00b1b0b0, 0x00838181, 0x00535051, 0x00292526, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c2221, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d1814, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00dcdcdc, 0x00d0d0d0, 0x00d0d0d0, 0x00d0d0d0, 0x00d0d0d0, 0x00dedede, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00424444, 0x0019dc, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ce2c23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b8889, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efeeee, 0x00c1c0c0, 0x00918f90, 0x00625f60, 0x00333031, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332020, 0x00d62c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009e211a, 0x00477, 0x005e6060, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d2d2d2, 0x00646666, 0x00626363, 0x00626363, 0x00525454, 0x00525454, 0x00505252, 0x00424444, 0x00424444, 0x003d3f3f, 0x00323535, 0x00323434, 0x002a2b2b, 0x00222424, 0x00222323, 0x00181919, 0x00171919, 0x00cbcbcb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00444646, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aaabab, 0x00477, 0x009f211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00562321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dcc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00605d5e, 0x00d9d8d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0cfcf, 0x00a09e9f, 0x00716e6f, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00b12a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00daa, 0x00323434, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00252727, 0x00898, 0x0018ed, 0x0021fe, 0x0021fe, 0x002a1110, 0x002f11f, 0x002f11f, 0x003b1311, 0x003e11e, 0x003e11e, 0x004c1310, 0x004c1310, 0x004f1410, 0x0015a9, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989999, 0x00477, 0x00591512, 0x00961f19, 0x00961f19, 0x00a5221b, 0x009f211a, 0x00531411, 0x00477, 0x00dadada, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x001b1c1c, 0x003e1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a22822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x004f4c4d, 0x00838181, 0x009e9c9c, 0x00999798, 0x007e7b7c, 0x00514e4e, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00464344, 0x00767374, 0x00a19fa0, 0x00bfbebe, 0x00c0bfbf, 0x009f9d9e, 0x004c4849, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x0024fe, 0x00151616, 0x00dedede, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004d4f4f, 0x00688, 0x00ad231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009f211a, 0x00477, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cbcbcb, 0x00acc, 0x00391210, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003811f, 0x00181919, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007b7d7d, 0x00477, 0x00ce2920, 0x00ee2e24, 0x00ee2e24, 0x00d82c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003a3738, 0x00696667, 0x00979696, 0x00c6c5c5, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00666464, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004d1411, 0x00699, 0x00babbbb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00838484, 0x00477, 0x007c1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c6271f, 0x00eba, 0x00303232, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00222424, 0x0017dc, 0x00d52a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c1e18, 0x00477, 0x00939494, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cecece, 0x00477, 0x00931f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2a2b, 0x005c595a, 0x008b8889, 0x00b9b8b8, 0x00e9e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e5e5, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009d211a, 0x00477, 0x007f8181, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00588, 0x004b1411, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x0026fe, 0x00141515, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004c4e4e, 0x00688, 0x00b1241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c2271f, 0x00b99, 0x00404242, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00477, 0x00791b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00272324, 0x00504d4d, 0x007e7b7c, 0x00acabab, 0x00dcdbdb, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00413e3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x002610e, 0x00282a2a, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dfdfdf, 0x00151616, 0x0024fe, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00892722, 0x007c2622, 0x00b52a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x004b1411, 0x00588, 0x00b7b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00848585, 0x00477, 0x007d1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x0025fe, 0x00151616, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x00477, 0x007b1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00716e6f, 0x00a09e9f, 0x00cfcece, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2020, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00b2241d, 0x00477, 0x009b9c9c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00343636, 0x00daa, 0x00c4271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b72a23, 0x00251f20, 0x00231f20, 0x00442121, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007a1b16, 0x00477, 0x00848585, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bcbdbd, 0x00699, 0x00481311, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00541512, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcfcf, 0x00477, 0x00961f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1818, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00363233, 0x00646162, 0x00939192, 0x00c2c1c1, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00588, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d62c24, 0x00322020, 0x00231f20, 0x002e2020, 0x00d02c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a9231b, 0x00577, 0x00505252, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00191a1a, 0x0022fd, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00757777, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008d8e8e, 0x00477, 0x00c9281f, 0x00ee2e24, 0x00ee2e24, 0x00d62c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c292a, 0x00575454, 0x00878585, 0x00b5b3b4, 0x00e3e3e3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00692421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1310, 0x00262828, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009b9c9c, 0x00477, 0x00681813, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x004c2221, 0x00231f20, 0x00241f20, 0x00af2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2820, 0x0013cb, 0x00282a2a, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x003c3e3e, 0x00a99, 0x00be261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00baa, 0x003b3d3d, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x002e3030, 0x002910e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a42923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00101, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x004b4748, 0x007a7878, 0x00a8a6a7, 0x00d7d7d7, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00434, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003e11e, 0x003d3f3f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cacaca, 0x00acc, 0x003912f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00652421, 0x006f2522, 0x009a2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x002d10f, 0x00f1010, 0x00d5d5d5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00727474, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0028fe, 0x00151616, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ef, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003e3a3b, 0x006d6b6b, 0x009b999a, 0x00cac9ca, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006c2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004712f, 0x00292b2b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00222424, 0x0019dc, 0x00d62a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00551512, 0x00477, 0x00abacac, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x00591612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00581512, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x001d1f1f, 0x0025fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332f30, 0x00605d5e, 0x008e8c8c, 0x00bebdbd, 0x00ececec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00532321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006e1914, 0x00799, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00616262, 0x00477, 0x00ae231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00861d17, 0x00477, 0x00767878, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dadada, 0x00101111, 0x002d10f, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00921f19, 0x00477, 0x00757777, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00565858, 0x00577, 0x00b3241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00802622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00535051, 0x00828080, 0x00b1b0b0, 0x00dfdedf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00b3241d, 0x00477, 0x009c9d9d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x00477, 0x00651713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b2241d, 0x00788, 0x00454747, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x002f3131, 0x00fba, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00baa, 0x00383a3a, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9b9b, 0x00477, 0x00731a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c595a, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x0022fd, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bebfbf, 0x00477, 0x002f10e, 0x00531411, 0x005b1612, 0x005b1612, 0x00591512, 0x004c1310, 0x004c1310, 0x004c1310, 0x004111f, 0x003e11e, 0x003e12f, 0x00391311, 0x0011bb, 0x00212323, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00606161, 0x00477, 0x00a1211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0028fe, 0x00141515, 0x00dfdfdf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d4d4d4, 0x00cee, 0x003912f, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00592321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00712522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007b1b16, 0x00477, 0x00d4d4d4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00868787, 0x00373939, 0x00222323, 0x00161717, 0x00212121, 0x00222424, 0x00222424, 0x002a2b2b, 0x00323434, 0x00323535, 0x00343737, 0x00424444, 0x00424444, 0x00424444, 0x00cbcbcb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9b9b, 0x00477, 0x006b1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005b1612, 0x00477, 0x00afb0b0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x002e3030, 0x0012cb, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00787677, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00577, 0x00727474, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00acc, 0x00391210, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00961f19, 0x00477, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00686a6a, 0x00477, 0x00a0211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00656, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2a2a, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009f2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00461310, 0x00171818, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00232525, 0x0018dc, 0x00d52a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c7271f, 0x00daa, 0x00383a3a, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x00611713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171414, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00969494, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00502221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a2211b, 0x00477, 0x00abacac, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004d4f4f, 0x00688, 0x00b1241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x002b10e, 0x00141515, 0x00dfdfdf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x00141515, 0x002b10e, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201d1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00474445, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00545, 0x00ecc, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cc2b23, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x0017dc, 0x00494b4b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00868787, 0x00477, 0x007d1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005b1612, 0x00477, 0x00aeafaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003d3f3f, 0x00baa, 0x00c5271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a32823, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b3b2b2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x002c292a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00baa, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x0010ff, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007e2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d1814, 0x00588, 0x00e0e1e1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbebe, 0x00699, 0x00481311, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00961f19, 0x00477, 0x006d6f6f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x008e1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b9b8b8, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00171415, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332020, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00c7281f, 0x00477, 0x00818383, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e4e5e5, 0x00191a1a, 0x0022fe, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00daa, 0x00353737, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bebfbf, 0x00699, 0x004f1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x004a2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00cfcece, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00464243, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00101, 0x00121011, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ab2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003812f, 0x00212323, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x003d3f3f, 0x00a99, 0x00be261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x002d10f, 0x00121313, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x001d1e1e, 0x001fed, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00706d6e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x005d5a5b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00477, 0x00babbbb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00727474, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005f1713, 0x00477, 0x00acadad, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004d4f4f, 0x00788, 0x00b8251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b22a23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00e4e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00aaa8a8, 0x003a3738, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x00fbb, 0x00585a5a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x00581512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a201a, 0x00477, 0x006d6f6f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00909191, 0x00477, 0x007c1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2d24, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008c8a8b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c2c1c1, 0x00939192, 0x00615e5f, 0x002c2829, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00211e1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008a2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e1612, 0x00acc, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dadada, 0x00101111, 0x002c10e, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00eba, 0x00353737, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cecece, 0x00acc, 0x003f1310, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00572321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00383435, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0cfcf, 0x00a2a0a1, 0x00726f70, 0x00434040, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2120, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ba251e, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x002f3131, 0x00fba, 0x00ca2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x002e10f, 0x00101111, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00272929, 0x0016cc, 0x00d62a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aaa8a8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dedede, 0x00b0aeaf, 0x007f7d7e, 0x00524e4f, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00271f20, 0x00432121, 0x00602421, 0x006f2522, 0x006f2522, 0x006f2522, 0x00632421, 0x005a2321, 0x00502221, 0x00452221, 0x003b2120, 0x00302020, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a10e, 0x002f3131, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00606161, 0x00477, 0x00a0211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00781a15, 0x00477, 0x00a5a6a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00606161, 0x00477, 0x00a8221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c02b23, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00423f3f, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ececec, 0x00bdbcbd, 0x008e8c8c, 0x005f5c5d, 0x00312d2e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x006e2521, 0x00af2923, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00477, 0x00c9caca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9b9b, 0x00477, 0x006a1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x00daa, 0x004c4e4e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a3a5a5, 0x00477, 0x00691814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x003b2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a3a1a1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cccbcb, 0x009c9a9a, 0x006d6b6b, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00712522, 0x00db2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00db2b22, 0x00999, 0x00666868, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00acc, 0x003912f, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00c6c7c7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x00101111, 0x003011f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00652421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00dad9d9, 0x00aaa8a8, 0x007c797a, 0x004c494a, 0x00262323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00b12923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004f1411, 0x00111212, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00232525, 0x0018dc, 0x00d42a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1411, 0x001e2020, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00353737, 0x00eba, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00555, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171415, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004b4748, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e7e7, 0x00b8b7b7, 0x008a8888, 0x005a5758, 0x002e2a2b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2020, 0x00c32b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x009e211a, 0x005c1612, 0x00341110, 0x0017dc, 0x0012cb, 0x0018ed, 0x002410f, 0x003011f, 0x003e12f, 0x004a1310, 0x00561511, 0x00621713, 0x006e1914, 0x00791b16, 0x00871d17, 0x00931f19, 0x009f211a, 0x00701914, 0x00477, 0x00a0a1a1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004d4f4f, 0x00688, 0x00b0241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a11f, 0x004e5050, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00747676, 0x00477, 0x00971f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00d82c24, 0x00cd2c23, 0x00c32b23, 0x00b92a23, 0x00ae2923, 0x00a22823, 0x00962822, 0x00812622, 0x005e2321, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00656363, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00c6c5c5, 0x00979696, 0x00696667, 0x00393637, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00af2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x008f1e18, 0x001add, 0x00477, 0x00e1010, 0x00424444, 0x005e6060, 0x00626363, 0x00626363, 0x00545656, 0x00474949, 0x003b3d3d, 0x002e3030, 0x00212222, 0x00131414, 0x00588, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x003e4040, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00868787, 0x00477, 0x00631713, 0x00da2b21, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002710f, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b6b7b7, 0x00477, 0x00571512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00b32a23, 0x005c2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00625f60, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00d4d3d3, 0x00a6a5a5, 0x00777475, 0x00474445, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322e2f, 0x005f5c5d, 0x008b8889, 0x00a7a5a6, 0x00a5a4a4, 0x007c797a, 0x002d2a2a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006a2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x004f1411, 0x00477, 0x00363838, 0x00b0b1b1, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00e8e9e9, 0x00dcdcdc, 0x00d0d0d0, 0x00c0c1c1, 0x00b3b4b4, 0x00a6a7a7, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbebe, 0x00699, 0x00477, 0x00477, 0x00477, 0x00477, 0x00688, 0x0012cb, 0x0021fe, 0x002d1110, 0x00391210, 0x004312f, 0x0013a9, 0x00202222, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x00191a1a, 0x0024fe, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b52a23, 0x00362020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00363233, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e2e2, 0x00b4b3b3, 0x00848283, 0x00565354, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00535051, 0x00817f7f, 0x00b0afaf, 0x00dfdedf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e6e7, 0x00403d3e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e1613, 0x00477, 0x00757777, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d3d3d3, 0x00b6b7b7, 0x00a9aaaa, 0x009d9e9e, 0x00919292, 0x00818383, 0x00747676, 0x00676969, 0x005b5d5d, 0x004e5050, 0x00424444, 0x00323535, 0x00252626, 0x00191b1b, 0x00c1c2c2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x002e3131, 0x00477, 0x0019dc, 0x00341210, 0x004011e, 0x004c1310, 0x005a1512, 0x00661713, 0x00721915, 0x007e1b16, 0x008a1d18, 0x00961f19, 0x00a5221b, 0x00b1241c, 0x00bc261e, 0x00c8281f, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00baa, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009b999a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c2c1c1, 0x00939192, 0x00646162, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00464243, 0x00747272, 0x00a4a2a2, 0x00d2d1d2, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c3c2c2, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b4241d, 0x00477, 0x00676969, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x006b6d6d, 0x005f6060, 0x00525454, 0x00424444, 0x00353838, 0x00282a2a, 0x001c1d1d, 0x00101111, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00eba, 0x003d1210, 0x008a1d18, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00828080, 0x00d9d8d9, 0x00f8f8f8, 0x00f1f1f1, 0x00d0cfcf, 0x00a2a0a1, 0x00726f70, 0x00434040, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00393536, 0x00686566, 0x00979595, 0x00c4c3c4, 0x00f3f3f3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00312d2e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008e2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00511511, 0x00111212, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00e2e3e3, 0x00d6d6d6, 0x00c9caca, 0x00bcbdbd, 0x00afb0b0, 0x00a1a2a2, 0x008b8c8c, 0x006a6c6c, 0x00272929, 0x00477, 0x0019dc, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00992822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2a2b, 0x005b5859, 0x008a8888, 0x00b8b7b7, 0x00e8e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00494646, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b42a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0012cb, 0x005e6060, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00222424, 0x00daa, 0x00c8281f, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x004e4b4c, 0x007d7a7b, 0x00abaaaa, 0x00dbdada, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00d62a21, 0x00477, 0x008b8c8c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dfdfdf, 0x00cee, 0x004b1311, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00423f3f, 0x00706d6e, 0x009e9d9d, 0x00cecdcd, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d52c24, 0x00ee2e24, 0x00ee2e24, 0x00d12920, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00656767, 0x00999, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00942722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00636061, 0x00929091, 0x00c1c0c0, 0x00efeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cc2b23, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00577, 0x007b7d7d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00909191, 0x00477, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00a22823, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00565354, 0x00858384, 0x00b4b3b3, 0x00e3e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ae2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002810f, 0x003f4141, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008d8e8e, 0x00477, 0x00d72a21, 0x00ee2e24, 0x00ee2e24, 0x00a22823, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00494646, 0x00787677, 0x00a7a5a6, 0x00d6d5d5, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00882622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00701914, 0x00588, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00fba, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00211e1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c3839, 0x006c6a6a, 0x009a9899, 0x00c9c8c8, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00492221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c2271f, 0x00477, 0x008b8c8c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00252727, 0x00411310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f2521, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00504d4d, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d22c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002e10f, 0x002c2e2e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dfdfdf, 0x00477, 0x00801c16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cbcacb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00851d17, 0x00477, 0x00cacaca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009b9c9c, 0x00477, 0x00bf261e, 0x00ee2e24, 0x00ee2e24, 0x00d62c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006b6969, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92a21, 0x00898, 0x006b6d6d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x0015cc, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x009f2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00e3e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004b1311, 0x00151616, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00151616, 0x00521411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbb, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a3211b, 0x00477, 0x00acadad, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cbcbcb, 0x00477, 0x00911f19, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x0015cc, 0x004e5050, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00878888, 0x00477, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00c62b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a4a3a3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00661713, 0x00799, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00434545, 0x0024fe, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00484546, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00562321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00be261e, 0x00477, 0x008d8e8e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00acc, 0x00641713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00582321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c1c0c0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0025fd, 0x002e3030, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00477, 0x00a3211b, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00656, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00605d5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008e1e18, 0x00477, 0x00444646, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00747676, 0x00688, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00b72a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171415, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00dad9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00962822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008e1e18, 0x00477, 0x00444646, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00303232, 0x003711f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00802622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ff, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007e7b7c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00972822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00851d17, 0x00477, 0x00444646, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e9e9, 0x00477, 0x00761a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00492221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302c2d, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00801c16, 0x00477, 0x00444646, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a4a6a6, 0x00477, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00999798, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00bfbebe, 0x00908e8e, 0x00838181, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00801c16, 0x00477, 0x004f5151, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626363, 0x00eba, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00a72923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00777, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cccbcb, 0x009d9b9b, 0x006e6b6c, 0x003f3c3d, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dbc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007b2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00801c16, 0x00477, 0x00505252, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00151616, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00702522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a5a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00d9d8d9, 0x00a9a7a8, 0x007b7979, 0x004c494a, 0x00262323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00632421, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00831c17, 0x00477, 0x00505252, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x009e211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c292a, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e5e5, 0x00b7b5b6, 0x00888686, 0x00595657, 0x002c292a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00477, 0x004b4d4d, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00292b2b, 0x0022fd, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00c32b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00615e5f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00c3c2c3, 0x00959393, 0x00656363, 0x00383435, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2020, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ad231c, 0x00788, 0x003d3f3f, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x007c7e7e, 0x00898a8a, 0x00969797, 0x00a2a4a4, 0x00b0b1b1, 0x00bfc0c0, 0x00cccccc, 0x00d9d9d9, 0x00e5e6e6, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00646666, 0x00477, 0x00a0211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00742522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151313, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c797a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0d0d0, 0x00a2a0a1, 0x00727070, 0x00444041, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009b2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2820, 0x0011bb, 0x00282a2a, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00262827, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00131414, 0x00202121, 0x002d2f2f, 0x003a3c3c, 0x00474949, 0x00545656, 0x00626363, 0x00707272, 0x007d7f7f, 0x008a8b8b, 0x00979898, 0x00a3a5a5, 0x00b0b1b1, 0x00c0c1c1, 0x00cdcdcd, 0x00dadada, 0x00e7e8e8, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00616262, 0x00477, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72c24, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00676465, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dddddd, 0x00afadae, 0x007f7d7e, 0x00514e4e, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00512221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x002e10e, 0x00f1010, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x002f3131, 0x00ba9, 0x00b0241c, 0x00df2c22, 0x00d22920, 0x00c6271f, 0x00ba251e, 0x00ae231c, 0x00a2211b, 0x00961f19, 0x00871d17, 0x007b1b16, 0x006f1914, 0x00631713, 0x00571511, 0x004b1310, 0x003e11f, 0x003011f, 0x002410f, 0x0018ed, 0x00caa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00588, 0x00131414, 0x00212222, 0x002e3030, 0x003b3d3d, 0x00484a4a, 0x00555757, 0x00626363, 0x00717373, 0x007e8080, 0x008b8c8c, 0x00989999, 0x00a4a6a6, 0x00b2b3b3, 0x00c0c1c1, 0x00cfcfcf, 0x00dcdcdc, 0x00e8e9e9, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00989999, 0x00202222, 0x00477, 0x00681813, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00682421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaeaea, 0x00bbbaba, 0x008c8a8b, 0x005f5c5c, 0x00302c2d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00721915, 0x00477, 0x00a7a8a8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00393b3b, 0x00688, 0x00a6221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00df2c22, 0x00d12920, 0x00c5271f, 0x00b9251d, 0x00ad231c, 0x00a1211a, 0x00951f19, 0x00871d17, 0x00791b16, 0x006e1914, 0x00621713, 0x00561511, 0x004a1310, 0x003e12f, 0x002f11f, 0x002310e, 0x0018dd, 0x00baa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00699, 0x00131414, 0x00222323, 0x002f3131, 0x003c3e3e, 0x00494b4b, 0x00525454, 0x004b4d4d, 0x00292b2b, 0x00699, 0x00477, 0x002c10f, 0x00ad231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a52923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00524e4f, 0x00e5e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00c8c7c7, 0x00999798, 0x006b6969, 0x003b3838, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abaaaa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005e2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c7271f, 0x00788, 0x00545656, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00444646, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x00de2b22, 0x00d12920, 0x00c4271f, 0x00b8251d, 0x00ab231c, 0x009f211a, 0x00931f19, 0x00871d17, 0x00791a15, 0x006d1814, 0x00611612, 0x00551411, 0x00491210, 0x003d12f, 0x002f11f, 0x002f1311, 0x002f11f, 0x00471310, 0x00721915, 0x00b9251d, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ba2a23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x006b6969, 0x00999798, 0x009f9d9e, 0x00989697, 0x00777475, 0x00484546, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b52a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1411, 0x00cee, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00505252, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a92923, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171414, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201d1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00959393, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00352020, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2820, 0x00477, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x005e6060, 0x00477, 0x007c1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00812622, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2020, 0x00392120, 0x00442121, 0x004e2221, 0x00582321, 0x00632421, 0x006f2522, 0x007a2522, 0x00842622, 0x008e2722, 0x00992822, 0x00a32823, 0x00af2923, 0x00ba2a23, 0x00c52b23, 0x00cf2c23, 0x00d92c24, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00712522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a9a7a8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbbbc, 0x00262323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a89, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2521, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791b16, 0x00477, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006c6e6e, 0x00477, 0x006d1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008e2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00392120, 0x00442121, 0x004f2221, 0x00592321, 0x00632421, 0x006f2522, 0x007b2522, 0x00852622, 0x008f2722, 0x009a2822, 0x00a42923, 0x00af2923, 0x00bb2a23, 0x00c52b23, 0x00d02c23, 0x00da2d24, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x007f2622, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00ececec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b2b1b1, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009b2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003511f, 0x00343636, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007d7f7f, 0x00477, 0x005e1613, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009b2822, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302020, 0x003a2120, 0x00442121, 0x004f2221, 0x005a2321, 0x00642421, 0x006f2522, 0x007b2622, 0x00862622, 0x00902722, 0x009a2822, 0x00a22823, 0x009a2822, 0x00892722, 0x006b2421, 0x003d2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00464344, 0x00d7d7d7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e6e6, 0x00767374, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bd2a23, 0x00ee2e24, 0x00ee2e24, 0x00e92d23, 0x00a99, 0x006d6f6f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008d8e8e, 0x00477, 0x00511512, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a72923, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x006b6869, 0x00acabab, 0x00c5c4c4, 0x00c3c2c2, 0x00a4a3a3, 0x00676465, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00d82a21, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009d9e9e, 0x00477, 0x00441310, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001a1717, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00555, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d52c24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aaabab, 0x00699, 0x00391210, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc2a23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00577, 0x00757777, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00babbbb, 0x009bb, 0x002e10f, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312d2e, 0x003a3738, 0x00272324, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b02923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003411f, 0x00323434, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d3d3d3, 0x00f1111, 0x0023fd, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac2923, 0x00912722, 0x00872622, 0x007c2622, 0x006f2522, 0x00652421, 0x005b2321, 0x00502221, 0x00462221, 0x003c2120, 0x00302020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00fde, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00333031, 0x00625f60, 0x00918f8f, 0x00c0bfbf, 0x00eeedee, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00acabab, 0x00302c2d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00812622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007b1b16, 0x00477, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x002a2c2c, 0x0014cb, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d24, 0x00dc2d24, 0x00d12c23, 0x00c72b23, 0x00bc2a23, 0x00b02923, 0x00a62923, 0x009b2822, 0x00912722, 0x00872622, 0x007c2622, 0x006f2522, 0x00652421, 0x005b2321, 0x00512221, 0x00472221, 0x003c2121, 0x00302020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00edd, 0x00151313, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00555253, 0x00848182, 0x00b2b1b1, 0x00e1e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c6c5c5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a7a7, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00dc2d24, 0x00d22c23, 0x00c82b23, 0x00bc2a23, 0x00b12923, 0x00a62923, 0x009c2822, 0x00922722, 0x00872622, 0x007c2622, 0x00702522, 0x00662421, 0x005c2321, 0x00512221, 0x00472221, 0x003c2121, 0x00302020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00191616, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00484546, 0x00777475, 0x00a5a4a4, 0x00d4d3d3, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00535051, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cb2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002d10f, 0x00353737, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a3a5a5, 0x00477, 0x003b12f, 0x00711915, 0x008c1e18, 0x009e211a, 0x00ab231c, 0x00b7251d, 0x00c3271f, 0x00d12920, 0x00dd2b22, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00dc2d24, 0x00d22c23, 0x00c92b23, 0x00bc2a23, 0x00b12a23, 0x00a72923, 0x009d2822, 0x008e2722, 0x00752522, 0x004b2221, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00111010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003a3738, 0x006a6768, 0x00989697, 0x00c7c6c6, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00858384, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171414, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007b1b16, 0x00477, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00878888, 0x002b2d2d, 0x00699, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00b99, 0x0017dc, 0x0023fe, 0x002f11f, 0x003c12f, 0x004812f, 0x00541411, 0x00601612, 0x006c1814, 0x00791a15, 0x00861d17, 0x00921f19, 0x009e211a, 0x00aa231c, 0x00b6251d, 0x00c2271f, 0x00d12920, 0x00dd2b22, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22c23, 0x00762522, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2b2c, 0x005d5a5b, 0x008b898a, 0x00bab9b9, 0x00e9e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00e1e2e2, 0x00cecece, 0x00c0c1c1, 0x00b2b3b3, 0x00a5a6a6, 0x00999a9a, 0x008c8d8d, 0x007f8181, 0x00717373, 0x00626464, 0x00565858, 0x00494b4b, 0x003c3e3e, 0x002f3131, 0x00222323, 0x00131414, 0x00699, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00a99, 0x0016dc, 0x0022fe, 0x002f11f, 0x003c12f, 0x004812f, 0x00541411, 0x00601612, 0x006c1814, 0x00791a15, 0x00861d17, 0x00921f19, 0x009e211a, 0x00a9231b, 0x00b5251d, 0x00c2271f, 0x00d02920, 0x00dc2b22, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c42b23, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00272324, 0x00504d4d, 0x007e7c7d, 0x00adacac, 0x00dcdcdc, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cb2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002d10f, 0x00353737, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00e8e9e9, 0x00dcdcdc, 0x00cfcfcf, 0x00c0c1c1, 0x00b2b3b3, 0x00a5a6a6, 0x009a9b9b, 0x008d8e8e, 0x00808282, 0x00717373, 0x00636565, 0x00575959, 0x004a4c4c, 0x003d3f3f, 0x00303232, 0x00222323, 0x00141515, 0x00799, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00999, 0x0015dc, 0x0021fe, 0x002f1110, 0x003b12f, 0x004712f, 0x00531411, 0x005f1612, 0x006b1814, 0x00791a15, 0x00851d17, 0x00911f19, 0x009d211a, 0x00a9231b, 0x00b5251d, 0x00c2271f, 0x00d02920, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d52c23, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00726f70, 0x00a09e9f, 0x00d0cfcf, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791b16, 0x00477, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00e9eaea, 0x00dddddd, 0x00d0d0d0, 0x00c0c1c1, 0x00b3b4b4, 0x00a6a7a7, 0x009a9b9b, 0x008d8e8e, 0x00818383, 0x00717373, 0x00646666, 0x00585a5a, 0x004b4d4d, 0x003e4040, 0x00313333, 0x00222323, 0x00151616, 0x008aa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x0023fe, 0x00741a15, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bd2a23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00363233, 0x00646162, 0x00949293, 0x00c2c1c1, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00eaebeb, 0x00dedede, 0x00d0d0d0, 0x00c1c2c2, 0x00b4b5b5, 0x00a7a8a8, 0x009b9c9c, 0x00818383, 0x00454747, 0x00477, 0x001ced, 0x00c5271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c292a, 0x00575454, 0x00878585, 0x00b5b3b4, 0x00e3e3e3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cb2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0028fe, 0x00353737, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c3c4c4, 0x00181919, 0x001ded, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00c42b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1818, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x004a4747, 0x00797777, 0x00a8a6a7, 0x00d6d6d6, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00761a15, 0x00477, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b7b8b8, 0x00477, 0x007f1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x006c6a6a, 0x009b999a, 0x00cac9c9, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00303232, 0x00391210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00545152, 0x00acabab, 0x00e9e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002810e, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00636565, 0x0014cc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007a2522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302c2d, 0x00b4b3b3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00761a15, 0x00477, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x0013cc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00d0cfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00424444, 0x002f11f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00732522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00918f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002810e, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eceded, 0x00acc, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9899, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00761a15, 0x00477, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00808282, 0x00477, 0x00ba251e, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181616, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00555253, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008a8888, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d8d8d8, 0x00bdd, 0x00471411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a82923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f6c6d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00615e5f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151313, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002810e, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00303232, 0x00fba, 0x00d02920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00512221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeedee, 0x002a2627, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00477, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x004d4f4f, 0x00477, 0x00a2211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b22a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007e7c7d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00626363, 0x00477, 0x007f1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x003c2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a5a4a4, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0023fe, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00757777, 0x00477, 0x006a1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e6e7, 0x00777475, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008e2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00588, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008e8f8f, 0x00477, 0x00561511, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00902722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00c7c6c6, 0x00979696, 0x005f5c5c, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x00477, 0x00949595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a1a3a3, 0x00477, 0x00451310, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a72923, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00d5d4d4, 0x00a6a5a5, 0x00777475, 0x00484546, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0023fe, 0x003f4141, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b5b6b6, 0x00799, 0x003611f, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b52a23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e2e1e1, 0x00b4b3b3, 0x00848283, 0x00565354, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00588, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x00dff, 0x002910e, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c32b23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00c2c1c1, 0x00929091, 0x00646162, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x00477, 0x00949595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d3d3d3, 0x00141515, 0x001ded, 0x00d42a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ce2c23, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00d0cfcf, 0x00a09e9f, 0x00716e6f, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0023fe, 0x003f4141, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x001e2020, 0x0015cc, 0x00c7281f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x003a2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dcdcdc, 0x00aeacad, 0x007e7c7d, 0x00514e4e, 0x00272324, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1a1b, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00741a15, 0x00477, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00292b2b, 0x00caa, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02d24, 0x00442121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009e9c9c, 0x00302c2d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004b2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00a99, 0x004d4f4f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00373939, 0x00999, 0x00ab231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00502221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00706d6e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d9d8d9, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c82b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007d1b16, 0x00477, 0x00838484, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00474949, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x005d2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00565354, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aaa8a8, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00672421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00501411, 0x00477, 0x00717373, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00595b5b, 0x00477, 0x00861d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00e9e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006f6c6d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dbc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00ba2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x005f1713, 0x00477, 0x002b2d2d, 0x00acadad, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006e7070, 0x00477, 0x00721915, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007d2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00636061, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeedee, 0x00c0bfbf, 0x00939192, 0x00646162, 0x00383435, 0x00bbbaba, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x00dc2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a0211a, 0x0020fe, 0x00477, 0x001a1b1b, 0x005c5e5e, 0x00858686, 0x009fa0a0, 0x00abacac, 0x00b8b9b9, 0x00c6c7c7, 0x00d3d3d3, 0x00e0e0e0, 0x00efefef, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00838484, 0x00477, 0x005e1613, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00baa, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00656, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004a4747, 0x00a19fa0, 0x00bebdbd, 0x00bab9b9, 0x00989697, 0x006c6a6a, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004d4a4b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x002a2627, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92d23, 0x009e211a, 0x004f1411, 0x0016dc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00eff, 0x001a1b1b, 0x00272828, 0x00343737, 0x00424444, 0x00525454, 0x005f6060, 0x006b6d6d, 0x00787a7a, 0x00858686, 0x00939494, 0x00a1a2a2, 0x00afb0b0, 0x00bcbdbd, 0x00c9caca, 0x00d7d7d7, 0x00e3e4e4, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9b9b, 0x00477, 0x004c1411, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x004f4c4d, 0x00787677, 0x00848182, 0x00585555, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00cc2820, 0x00c0261e, 0x00b3241d, 0x00a6221b, 0x00992019, 0x008d1e18, 0x00811c16, 0x00751a15, 0x00681813, 0x005b1612, 0x004d1310, 0x004111f, 0x00361210, 0x002911f, 0x001dfe, 0x0011cb, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00111212, 0x001e1f1f, 0x002b2d2c, 0x00383b3b, 0x00454747, 0x00535555, 0x00626363, 0x006f7171, 0x007c7e7e, 0x00898a8a, 0x00979898, 0x00a3a5a5, 0x00b0b1b1, 0x00c0c1c1, 0x00cdcdcd, 0x00dbdbdb, 0x00e7e8e8, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00699, 0x003c1210, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00af2923, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006f6c6d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00413e3f, 0x006f6c6d, 0x009e9d9d, 0x00cdcccc, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0aeaf, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00992822, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00d42a21, 0x00c8281f, 0x00bc261e, 0x00b1241c, 0x00a5221b, 0x00961f19, 0x00891d17, 0x007d1b16, 0x00711915, 0x00651713, 0x00581511, 0x004c1310, 0x003e11f, 0x003211f, 0x002610f, 0x0019ed, 0x00daa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00588, 0x00131414, 0x00222323, 0x002f3131, 0x003c3e3e, 0x009bb, 0x002d10e, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00be2a23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00333031, 0x00615e5f, 0x00918f8f, 0x00bfbebe, 0x00eeedee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00737171, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00442121, 0x00a42923, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00df2c22, 0x00d22920, 0x00c5271f, 0x00b9251d, 0x00ad231c, 0x00a1211a, 0x00951f19, 0x00871d17, 0x00791b16, 0x006e1914, 0x00621713, 0x00561511, 0x00491210, 0x003d12f, 0x003d12f, 0x00d72a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2b23, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x002a2627, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00535051, 0x00838181, 0x00b2b1b1, 0x00e0dfe0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bbbaba, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x006c2421, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00d92a21, 0x00c1271e, 0x00b3241d, 0x00a9231b, 0x00c7271f, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00252122, 0x00464243, 0x00757273, 0x00a4a3a3, 0x00d2d1d2, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d5d5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d2121, 0x00c02b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00cb2820, 0x00b4241d, 0x009c201a, 0x00821c17, 0x006a1814, 0x00521411, 0x003811f, 0x0020fe, 0x00999, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x001eed, 0x008e1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2d24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccbcb, 0x00f3f3f3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d1d0d1, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00622421, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00b6251d, 0x00731a15, 0x00491310, 0x002b11f, 0x0013cc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x009bb, 0x00222423, 0x003c3e3e, 0x00595b5b, 0x00727474, 0x008c8d8d, 0x00a7a8a8, 0x00bebfbf, 0x00bebfbf, 0x009b9c9c, 0x00353737, 0x00477, 0x00841c17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a82923, 0x00562321, 0x00622421, 0x006c2421, 0x00772522, 0x00822622, 0x008c2722, 0x00962822, 0x00a22823, 0x00ae2923, 0x00b92a23, 0x00c32b23, 0x00ce2c23, 0x00d92c24, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32d24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1a1b, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00323, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b5b3b4, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00762522, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00941f19, 0x0026fe, 0x00477, 0x00699, 0x00282a2a, 0x004b4d4d, 0x00666868, 0x00808282, 0x009a9b9b, 0x00b6b7b7, 0x00d0d0d0, 0x00e8e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00474949, 0x00caa, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00cc2b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2020, 0x00392120, 0x00442121, 0x004e2221, 0x00582321, 0x00632421, 0x006f2522, 0x007b2522, 0x00852622, 0x00902722, 0x009a2822, 0x00a52923, 0x00582321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x0011f10, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00838181, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00662421, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2820, 0x003511f, 0x00477, 0x002c2e2e, 0x00999a9a, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbebe, 0x00477, 0x00a3211b, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x0010bb, 0x00f1110, 0x00979898, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e9eaea, 0x00477, 0x00871d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c1c0c0, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa231c, 0x00999, 0x00292b2b, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00477, 0x00891d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00595657, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00852622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2820, 0x0011bb, 0x00272929, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cacaca, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00352020, 0x00592321, 0x00672421, 0x006d2421, 0x00562321, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00a3a1a1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9c8c8, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x003712f, 0x00f1110, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0b1b1, 0x00477, 0x00b7251d, 0x00ee2e24, 0x00ee2e24, 0x00d82c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x008a2722, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00c12b23, 0x006f2522, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00252122, 0x00c7c6c6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00585556, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00831c17, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00979898, 0x00477, 0x00cf2920, 0x00ee2e24, 0x00ee2e24, 0x00c22b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00922722, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2b23, 0x00492221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x003a3738, 0x00231f20, 0x00393637, 0x00efeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c2c1c1, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00802622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00b99, 0x00434545, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007a7c7c, 0x00477, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ac2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004e2221, 0x00d62c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00612421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00666464, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00535051, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003711f, 0x00f1010, 0x00dfdfdf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00616262, 0x0017dc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00972822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00692421, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x00941f19, 0x005f1612, 0x004111f, 0x004112f, 0x00611612, 0x00a8221b, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00592321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a3a1a1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bcbabb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00555, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00871d17, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00474949, 0x002e11f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00822622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006b2421, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00721915, 0x00eba, 0x00477, 0x00111212, 0x00333636, 0x00373939, 0x00e10f, 0x00477, 0x002d10f, 0x00c3271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2d24, 0x00322020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c3c2c3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009c9a9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00d8d7d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004d4a4b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00802622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2820, 0x00caa, 0x00434545, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x002b2d2d, 0x004712f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00be261e, 0x0023fe, 0x00477, 0x00515353, 0x00bfc0c0, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x009c9d9d, 0x00171818, 0x00caa, 0x00b6251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00474445, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b7b6b6, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003b1210, 0x00dff, 0x00dcdcdc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00111212, 0x00621713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00572321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322020, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00af231c, 0x00caa, 0x00181919, 0x00b6b7b7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x00202222, 0x0019dc, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c9c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c797a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00474445, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c12b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00871d17, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00477, 0x00791b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00412121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a62923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x00caa, 0x00262828, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bebfbf, 0x00477, 0x00811c16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b3b2b2, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2820, 0x00caa, 0x003f4141, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d8d8d8, 0x00477, 0x00911f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a2020, 0x00231f20, 0x00231f20, 0x005f2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x001fed, 0x001c1d1d, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x002d2f2f, 0x003b12f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007d2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c9c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00918f90, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332f30, 0x00e7e6e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003b12f, 0x00dff, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbebe, 0x00477, 0x00ab231c, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x00231f20, 0x00231f20, 0x00302020, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005c1612, 0x00477, 0x00bebfbf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005e6060, 0x0018dd, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x00312d2e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00585556, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00adacac, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00be2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00881d17, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a3a5a5, 0x00477, 0x00c4271f, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00231f20, 0x00231f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ae231c, 0x00477, 0x006c6e6e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626363, 0x0015dc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00932722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00989, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c9c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008f8d8d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00939192, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d02920, 0x00eba, 0x003f4141, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00898a8a, 0x00477, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00b62a23, 0x00231f20, 0x005b2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x001fed, 0x00202222, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00434545, 0x002e11f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00852622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191616, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efeeee, 0x002d2a2a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00cdcccc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003f1310, 0x00dff, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006d6f6f, 0x00b99, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x002e2020, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00641713, 0x00477, 0x00babbbb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00e1010, 0x005c1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c9c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00888686, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003e3a3b, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00be2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c1e18, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00545656, 0x002310e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c2722, 0x009e2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b2241d, 0x00477, 0x00636565, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x00a2211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaeaea, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00696667, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c2c1c1, 0x00929091, 0x00636061, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d02920, 0x00eba, 0x003a3c3c, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00393c3c, 0x003b11f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x0023fe, 0x001d1f1f, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003a3c3c, 0x001adc, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00c62b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c3c2c3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00828080, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0d0d0, 0x00a2a0a1, 0x00726f70, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d2121, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003f1210, 0x00bdd, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x001d1e1e, 0x00541411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a1814, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a7a8a8, 0x00477, 0x00841c17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007e2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e6e6, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00aeacad, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x00b1b0b0, 0x00817f7f, 0x00524f50, 0x00292526, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c1e18, 0x00477, 0x008c8d8d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00799, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b8251d, 0x00577, 0x005d5f5f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eceded, 0x001b1c1c, 0x002a10e, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00787677, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c797a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x004b4748, 0x005a5758, 0x00524e4f, 0x00322e2f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ff, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00782522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00eba, 0x003a3c3c, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00c1c2c2, 0x00a6a7a7, 0x008a8b8b, 0x006f7171, 0x00555757, 0x003a3c3c, 0x00323535, 0x00646666, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e6e6, 0x00477, 0x00861d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x002810e, 0x001a1b1b, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005d5f5f, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00852622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009c9a9a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e1e0e0, 0x00262323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d2121, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00431310, 0x00bdd, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x00477, 0x00477, 0x00a99, 0x002310f, 0x003b12f, 0x004612f, 0x00477, 0x00868787, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9caca, 0x00477, 0x009e211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006e1914, 0x00477, 0x00abacac, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0b1b1, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a6a5a5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00767374, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00911f19, 0x00477, 0x008c8d8d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00799, 0x00491310, 0x00c1271e, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dba, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c6c7c7, 0x00477, 0x008b1d18, 0x00c6271f, 0x00ad231c, 0x00961f19, 0x007f1b16, 0x00641713, 0x00788, 0x00575959, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eceded, 0x001b1c1c, 0x002810e, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00979595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x001a1717, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00652421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x0010bb, 0x00383a3a, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x002e3030, 0x0015cb, 0x00d82a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x00477, 0x00838484, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x00191a1a, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00bdd, 0x002b2d2d, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005b5d5d, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00686566, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x004d4a4b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00222, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00461311, 0x00acc, 0x00d4d4d4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00477, 0x009d9e9e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e8e8, 0x00a3a5a5, 0x00a4a6a6, 0x00babbbb, 0x00d6d6d6, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00e4e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x005c595a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00000, 0x00000, 0x00544, 0x001e1b1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001b1819, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00632421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a8221b, 0x00477, 0x00818383, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00799, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32d24, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00b0241c, 0x00477, 0x00b8b9b9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x002810e, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00555253, 0x00f3f3f3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c0bfbf, 0x00413e3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00171516, 0x0010ef, 0x00988, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b12a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003311f, 0x00202222, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x002e3030, 0x0015cb, 0x00d82a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00742522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00982019, 0x00477, 0x00d3d3d3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003f3b3c, 0x00a09e9f, 0x00d7d7d7, 0x00ececec, 0x00e8e7e7, 0x00d1d0d1, 0x009e9d9d, 0x004f4c4d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001a1717, 0x00131111, 0x00baa, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00e92e24, 0x00ee2e24, 0x00ee2e24, 0x00bb251e, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b32a23, 0x003c2121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f1b16, 0x00477, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00171414, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001c191a, 0x00151313, 0x00ecc, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00562321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f1914, 0x00699, 0x00e9eaea, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00799, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00382120, 0x00512221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00641713, 0x00bdd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x002810e, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x0011ff, 0x001b1819, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00171515, 0x0010ef, 0x00888, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007b2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003d12f, 0x00313333, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x002e3030, 0x0015cb, 0x00d82a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f2522, 0x00231f20, 0x00682421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1310, 0x00272929, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00877, 0x00dbc, 0x0010ee, 0x0011f10, 0x0011ef, 0x00ecd, 0x00988, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00892722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0021fe, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b32a23, 0x00231f20, 0x00231f20, 0x007d2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003511f, 0x00414343, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008c2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x001cee, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c7c8c8, 0x00799, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00382120, 0x00231f20, 0x00231f20, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x001aed, 0x005b5d5d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x0028fe, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007a2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003b1210, 0x00313333, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e6e6, 0x00202222, 0x001bed, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f2522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a82923, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x00688, 0x00777979, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00572321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f1b16, 0x00477, 0x00c3c4c4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e2e3e3, 0x002d2f2f, 0x00a99, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b32a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bd2a23, 0x00ee2e24, 0x00ee2e24, 0x00d52a21, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x001add, 0x00202222, 0x00dadada, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00babbbb, 0x001b1c1c, 0x00baa, 0x00a6221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d22c23, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x00477, 0x00aaabab, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x0028fe, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00151314, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x0011bb, 0x00f1010, 0x007f8181, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00b3b4b4, 0x004a4c4c, 0x00477, 0x001fed, 0x00ba251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x005b2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00a2211b, 0x00477, 0x00c7c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00788, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00161414, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00151313, 0x00555, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00342020, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2820, 0x00461311, 0x00477, 0x00477, 0x00101111, 0x00181818, 0x00477, 0x00477, 0x0010bb, 0x00721915, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00722522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322020, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00e0e1e1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x00741a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00edd, 0x00171515, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001d1a1b, 0x00151313, 0x00b9a, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c6271f, 0x00831c17, 0x00611612, 0x005d1612, 0x00751a15, 0x00a4221b, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x006e2521, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00477, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x002c10f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00322, 0x00545, 0x00544, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00662421, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82c24, 0x00532321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00581511, 0x00191b1b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00788, 0x00be261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00932722, 0x002e2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00732522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004012f, 0x00353737, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x00741a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00a52923, 0x00e12d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00c52b23, 0x00832622, 0x00372020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00342020, 0x00732522, 0x00a42923, 0x00cb2b23, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002710f, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e9e9, 0x00181919, 0x002c10f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d2121, 0x00502221, 0x00532321, 0x00442121, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004a2221, 0x00aa2923, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00daa, 0x00696b6b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00494b4b, 0x00477, 0x00b9251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b62a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x009e2822, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00477, 0x00858686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x005b5d5d, 0x00477, 0x004a1411, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00482221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00c9281f, 0x00a4221b, 0x00831c17, 0x00601612, 0x003a11f, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008c8d8d, 0x00477, 0x00711915, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b92a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00622421, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00641713, 0x0018dc, 0x00477, 0x00477, 0x00477, 0x00101111, 0x00333535, 0x00575959, 0x00c1c2c2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005a5c5c, 0x00788, 0x00c8281f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00602321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005f2321, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x00611612, 0x00577, 0x009bb, 0x004f5151, 0x00979898, 0x00c5c6c6, 0x00e9eaea, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00cee, 0x00481310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2c23, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x0022fe, 0x00477, 0x00626464, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007d7f7f, 0x00477, 0x00b0241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00792522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x0011ff, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00cb2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b4241d, 0x0010bb, 0x001a1b1b, 0x00bdbebe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x001b1c1c, 0x002d10f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2d24, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00fde, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00892722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x0011bb, 0x00212323, 0x00dcdcdc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009d9e9e, 0x00477, 0x00921f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x002e10f, 0x00121313, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00303232, 0x001adc, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x003e2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b52a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007e1b16, 0x00477, 0x00a3a5a5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bbbcbc, 0x00477, 0x00761a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171415, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00672421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22920, 0x00caa, 0x00464848, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004d4f4f, 0x00baa, 0x00d42a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00522221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004b1411, 0x00acc, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x00799, 0x00581512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c32b23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a6221b, 0x00477, 0x007c7e7e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x00577, 0x00be261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x0021ed, 0x00232525, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00121313, 0x003c1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d52c24, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00bf2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00731a15, 0x00477, 0x00b5b6b6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008b8c8c, 0x00477, 0x00a4221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00702522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c8281f, 0x00999, 0x00525454, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00232525, 0x0025fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00de2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00401210, 0x00e1010, 0x00e0e1e1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a9aaaa, 0x00477, 0x00861d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009d2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a201a, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003b3d3d, 0x0013cb, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00462221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00edd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02c22, 0x0019dc, 0x002c2e2e, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c7c8c8, 0x00477, 0x006a1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b52a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c82b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00671813, 0x00477, 0x00c0c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005a5c5c, 0x00999, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005c2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007b2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c0261e, 0x00688, 0x005e6060, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00bdd, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2b23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003611f, 0x00131414, 0x00e8e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00e4e5e5, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00787a7a, 0x00477, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a72923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00696b6b, 0x00474949, 0x00242626, 0x00799, 0x00477, 0x00477, 0x007d7f7f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00191a1a, 0x003611f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ef, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00582321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2b21, 0x0014cb, 0x00363838, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x00acc, 0x00daa, 0x002e11f, 0x004d1310, 0x006e1914, 0x00861d17, 0x002fec, 0x001b1c1c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008e8f8f, 0x00477, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005c1612, 0x00588, 0x00cbcbcb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00c5c6c6, 0x00a1a3a3, 0x007e8080, 0x005f6060, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004e5050, 0x00b99, 0x00cf2920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x001fed, 0x00414343, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e6e6, 0x00477, 0x007f1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003f2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00852622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b7251d, 0x00477, 0x006a6c6c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00cbcbcb, 0x00a3a5a5, 0x00808282, 0x005d5f5f, 0x00373939, 0x00131414, 0x00477, 0x00477, 0x00477, 0x00477, 0x007c7e7e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b5b6b6, 0x00477, 0x00761a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00982019, 0x00477, 0x00a8a9a9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00131414, 0x00611612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00532321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x002c10e, 0x00191a1a, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00848585, 0x00616262, 0x003a3c3c, 0x00161717, 0x00477, 0x00477, 0x00477, 0x00477, 0x0019ed, 0x003b12f, 0x005e1612, 0x00801c16, 0x009a201a, 0x00fa9, 0x00232525, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00272929, 0x0020ed, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x001ded, 0x002c2e2e, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00191a1a, 0x005b1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00562321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b12a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00477, 0x00a2a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00474949, 0x00477, 0x0017dc, 0x003911f, 0x005a1512, 0x007b1b16, 0x009f211a, 0x00c1271e, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00741a15, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00888989, 0x00477, 0x00a0211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791a15, 0x00477, 0x00b5b6b6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00799, 0x006c1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00666, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00612421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00fbb, 0x00404242, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x007d1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2820, 0x00a99, 0x00505252, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e4e5e5, 0x00e1010, 0x00411310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00caa, 0x00494b4b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00477, 0x00931f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2020, 0x00d62c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00511512, 0x008aa, 0x00d5d5d5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x001f2121, 0x0025fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00421310, 0x00dff, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005a5c5c, 0x00788, 0x00c7271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00571512, 0x00799, 0x00d5d5d5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00862622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x00477, 0x00777979, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00797b7b, 0x00477, 0x00ac231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009f211a, 0x00477, 0x00868787, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c1c2c2, 0x00477, 0x006b1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bb251e, 0x00477, 0x006c6e6e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x001c1d1d, 0x003c1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009e2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00767, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x0023fe, 0x001f2121, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x009bb, 0x004e1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d52c23, 0x005c2321, 0x003f2121, 0x004f2221, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x001ced, 0x002a2c2c, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00303232, 0x0018dc, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003711f, 0x00141515, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00909191, 0x00477, 0x00a6221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00562321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ef, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00762522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00477, 0x00adaeae, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00444646, 0x00daa, 0x00d32a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00612421, 0x00231f20, 0x00251f20, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006c1814, 0x00477, 0x00bcbdbd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00959696, 0x00477, 0x00951f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a201a, 0x00477, 0x00929393, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00151616, 0x003812f, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bc2a23, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x001bed, 0x00393b3b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x00801c16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00231f20, 0x00231f20, 0x00772522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00788, 0x005a5c5c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00141515, 0x003611f, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x001ded, 0x002b2d2d, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00737575, 0x00477, 0x00b8251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00477, 0x00a1a3a3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x001d1f1f, 0x002810e, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x003d2121, 0x00231f20, 0x00352020, 0x00e12d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003a1210, 0x00111212, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00666868, 0x00577, 0x00bd261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791a15, 0x00477, 0x00b7b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dddddd, 0x009bb, 0x00511511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c82b23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00442121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791b16, 0x00477, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00767878, 0x00477, 0x00af231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a02822, 0x005c2321, 0x00792522, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00961f19, 0x00477, 0x00909191, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00588, 0x00601713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00caa, 0x004b4d4d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00565858, 0x00999, 0x00cf2920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00572321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00562321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e1612, 0x00191a1a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x008aa, 0x00511511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x0018dc, 0x00313333, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003a3c3c, 0x0013cb, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00571512, 0x00799, 0x00d7d7d7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x00477, 0x006d1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00592321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00521411, 0x00222424, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00484a4a, 0x00daa, 0x00d32a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00477, 0x00c5c6c6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a1a2a2, 0x00477, 0x00891d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b9251d, 0x00477, 0x006f7171, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003a3c3c, 0x0014cb, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00432121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00542321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00651713, 0x00dff, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bfc0c0, 0x00477, 0x00771a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x00aa231c, 0x00577, 0x00636565, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x001a1b1b, 0x002d10f, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003511f, 0x00151616, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x00881d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00cdcdcd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x0013cc, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00e02c22, 0x00bf261e, 0x009d211a, 0x007c1b16, 0x005c1612, 0x003b12f, 0x0019ed, 0x00477, 0x00477, 0x00151616, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00737575, 0x00477, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00982019, 0x00477, 0x00939494, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00232525, 0x0025fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00e32d24, 0x00342020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d82c24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00788, 0x00686a6a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003d3f3f, 0x0011ba, 0x003e11e, 0x003011f, 0x0017dc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00161717, 0x00393b3b, 0x005d5f5f, 0x00808282, 0x00a3a5a5, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x00799, 0x00541512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x001ced, 0x002b2d2d, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008d8e8e, 0x00477, 0x00a2211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009d2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00581612, 0x009bb, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9caca, 0x004b4d4d, 0x00323535, 0x00474949, 0x00616262, 0x00848585, 0x00a5a6a6, 0x00cbcbcb, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00464848, 0x00daa, 0x00d32a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00771a15, 0x00477, 0x00b7b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x00131414, 0x003a1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d62c24, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2920, 0x00999, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x007e1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00baa, 0x004b4d4d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006e7070, 0x00477, 0x00bd261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00baa, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00434, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00af2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00671813, 0x00477, 0x00cfcfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00212323, 0x0024fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00551512, 0x008aa, 0x00d7d7d7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dadada, 0x008aa, 0x00561512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00452221, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2b21, 0x00eba, 0x00484a4a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007f8181, 0x00477, 0x00a9231b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b9251d, 0x00477, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00535555, 0x00ba9, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a12822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791a15, 0x00477, 0x00bdbebe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dfdfdf, 0x00cee, 0x00481310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003511f, 0x00161717, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c1c2c2, 0x00477, 0x00701914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ae2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003b2120, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0018dc, 0x00373939, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00525454, 0x00a99, 0x00cc2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00982019, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00363838, 0x0017dc, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00abacac, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00477, 0x00721915, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x001ced, 0x002d2f2f, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a4a6a6, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00e22d24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x0023fd, 0x00272929, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x002a2c2c, 0x001ded, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00771a15, 0x00477, 0x00b9baba, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00212323, 0x0027fe, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00322020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00842622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a201a, 0x00477, 0x00989999, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008c8d8d, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d62a21, 0x00baa, 0x004d4f4f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00878888, 0x00477, 0x00a7221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00da2d24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003011f, 0x001c1d1d, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00101111, 0x003d1210, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00681813, 0x00588, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e9eaea, 0x00111212, 0x003f1310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00742522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x00477, 0x00858686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005e6060, 0x00788, 0x00c4271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x0015cc, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x00577, 0x00bf261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00d02c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00401310, 0x00131414, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c4c5c5, 0x00477, 0x00671813, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x00477, 0x00a1a2a2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x00799, 0x00591612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c12b23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00767, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00652421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x00477, 0x00737575, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00333535, 0x0017dc, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00971f19, 0x00477, 0x00d2d2d2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004e5050, 0x00baa, 0x00d42a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00512221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00c42b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00501411, 0x00acc, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00999a9a, 0x00477, 0x00911f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00961f19, 0x00477, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bcbdbd, 0x00477, 0x00751a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00572321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2820, 0x00788, 0x00616262, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00151616, 0x003311f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00a6221b, 0x00477, 0x00bcbdbd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00272929, 0x001ced, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x003e2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151313, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b52a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00611612, 0x00588, 0x00d3d3d3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00696b6b, 0x00477, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00782522, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00999, 0x00626363, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00545656, 0x00477, 0x00a7221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00932722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00492221, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72a21, 0x00caa, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcfcf, 0x00699, 0x005b1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x00261f20, 0x009e2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00588, 0x00acadad, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x004e5050, 0x00477, 0x00791b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2d24, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a62923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00731a15, 0x00477, 0x00c3c4c4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003e4040, 0x0011bb, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00552321, 0x00231f20, 0x00532321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x002d11f, 0x00699, 0x00777979, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00969797, 0x001b1c1c, 0x00688, 0x007f1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00622421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003e2121, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x0015cc, 0x003c3e3e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00939494, 0x00477, 0x00881d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a82923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b32a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x00501411, 0x00477, 0x00699, 0x00343636, 0x005c5e5e, 0x00585a5a, 0x003e4040, 0x00bdd, 0x00477, 0x003011f, 0x00b6251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00972822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00477, 0x00b1b2b2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b2b3b3, 0x00799, 0x003e1210, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52d24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x00dc2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x006b1814, 0x003711f, 0x002110f, 0x001add, 0x003211f, 0x00651713, 0x00b1241c, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009b2822, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00342020, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x0020ed, 0x00262828, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009fa0a0, 0x009bb, 0x002910e, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00d62c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00862622, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00882622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a6221b, 0x00477, 0x00494b4b, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00565858, 0x00477, 0x003511f, 0x00db2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c12b23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00342020, 0x00a92923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x00512221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00dc2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00577, 0x001e2020, 0x00959696, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x00bbbcbc, 0x00636565, 0x009bb, 0x00898, 0x00711915, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82c24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00a42923, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00b92a23, 0x00652421, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006a2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x002c10e, 0x00477, 0x00477, 0x00232424, 0x00323535, 0x00232424, 0x00699, 0x00477, 0x00a99, 0x00581512, 0x00c8281f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00442121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x004c2221, 0x006b2421, 0x00822622, 0x00832622, 0x007b2522, 0x005c2321, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00972822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00b7251d, 0x00751a15, 0x00501410, 0x004312f, 0x00521411, 0x00701914, 0x00a1211a, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00902722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00962722, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00d02c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12923, 0x00482221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1818, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x006a2421, 0x00b22a23, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00c72b23, 0x008b2722, 0x00422121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00482221, 0x005c2321, 0x00642421, 0x005c2321, 0x004b2221, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x0011f10, 0x001e1b1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x0011f10, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00877, 0x00000, 0x00000, 0x00b9a, 0x00191616, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x0010ef, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00323, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00baa, 0x00141112, 0x001b1819, 0x00201d1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00191617, 0x0011f10, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00433, 0x00544, 0x00434, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00211e1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00151314, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00111010, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00131011, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00fdd, 0x00161314, 0x001c1919, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x001c191a, 0x00161314, 0x00fee, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000}; \ No newline at end of file diff --git a/include/utils/command_structure/auto_command.h b/include/utils/command_structure/auto_command.h index 008f31e..532fcbe 100644 --- a/include/utils/command_structure/auto_command.h +++ b/include/utils/command_structure/auto_command.h @@ -20,6 +20,10 @@ class AutoCommand { * What to do if we timeout instead of finishing. timeout is specified by the timeout seconds in the constructor */ virtual void on_timeout(){} + AutoCommand* withTimeout(double t_seconds){ + timeout_seconds = t_seconds; + return this; + } /** * How long to run until we cancel this command. * If the command is cancelled, on_timeout() is called to allow any cleanup from the function. diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index 557c2f9..14be25e 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -57,7 +57,7 @@ void CommandController::run() { command_queue.pop(); command_timed_out = false; - printf("Beginning Command %d\n", command_count); + printf("Beginning Command %d : timeout = %f\n", command_count, next_cmd->timeout_seconds); fflush(stdout); From 26b77f3ff67e71b11154e547fa5aba06b49e67a7 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sat, 18 Feb 2023 00:26:57 -0500 Subject: [PATCH 166/243] take 2 --- src/subsystems/flywheel.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index be44f1d..2c41114 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -22,7 +22,7 @@ using namespace vex; -const int FlywheelWindowSize = 10; +const int FlywheelWindowSize = 1; /********************************************************* * CONSTRUCTOR, GETTERS, SETTERS From 4652c8ad3b376b63a39400bc4f629a4e036fbdc4 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Fri, 17 Feb 2023 19:47:28 -0500 Subject: [PATCH 167/243] Fixed kS after trapezoid curve --- include/utils/feedforward.h | 10 ++++++++-- src/utils/motion_controller.cpp | 2 +- 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/include/utils/feedforward.h b/include/utils/feedforward.h index 2592107..c6700e7 100644 --- a/include/utils/feedforward.h +++ b/include/utils/feedforward.h @@ -63,9 +63,15 @@ class FeedForward * @param a Requested acceleration of system * @return A feedforward that should closely represent the system if tuned correctly */ - double calculate(double v, double a) + double calculate(double v, double a, double pid_ref=0.0) { - return (cfg.kS * (v > 0 ? 1 : v < 0 ? -1 : 0)) + (cfg.kV * v) + (cfg.kA * a) + cfg.kG; + double ks_sign = 0; + if(v != 0) + ks_sign = sign(v); + else if(pid_ref != 0) + ks_sign = sign(pid_ref); + + return (cfg.kS * ks_sign) + (cfg.kV * v) + (cfg.kA * a) + cfg.kG; } private: diff --git a/src/utils/motion_controller.cpp b/src/utils/motion_controller.cpp index 1b495e0..9d915ca 100644 --- a/src/utils/motion_controller.cpp +++ b/src/utils/motion_controller.cpp @@ -40,7 +40,7 @@ double MotionController::update(double sensor_val) pid.set_target(cur_motion.pos); pid.update(sensor_val); - out = pid.get() + ff.calculate(cur_motion.vel, cur_motion.accel); + out = pid.get() + ff.calculate(cur_motion.vel, cur_motion.accel, pid.get()); if(lower_limit != upper_limit) out = clamp(out, lower_limit, upper_limit); From 555fd532395ca40efabf3eefa36c94d444b2c343 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sat, 18 Feb 2023 00:26:03 -0500 Subject: [PATCH 168/243] Worked on tuning skills --- src/utils/command_structure/drive_commands.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index 833f9ee..6e8ea45 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -151,6 +151,11 @@ void TurnToHeadingCommand::on_timeout(){ DriveStopCommand::DriveStopCommand(TankDrive &drive_sys): drive_sys(drive_sys) {} +void DriveStopCommand::on_timeout() +{ + drive_sys.reset_auto(); +} + /** * Stop the drive train * Overrides run from AutoCommand From d9c1e982eaa6b3497ba1020e6034f447dbddbde9 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Thu, 9 Feb 2023 21:02:57 -0500 Subject: [PATCH 169/243] Merge remote-tracking branch 'refs/remotes/origin/main' --- src/subsystems/flywheel.cpp | 4 ++-- src/utils/moving_average.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index f9c42a7..d3f0e4a 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -22,7 +22,7 @@ using namespace vex; -const int FlywheelWindowSize = 30; +const int FlywheelWindowSize = 1; /********************************************************* * CONSTRUCTOR, GETTERS, SETTERS @@ -81,7 +81,7 @@ double Flywheel::measureRPM() { double rawRPM = ratio * motors.velocity(velocityUnits::rpm); RPM_avger.add_entry(rawRPM); smoothedRPM = RPM_avger.get_average(); - return smoothedRPM; + return rawRPM; //TODO Change back } double Flywheel::getRPM(){ diff --git a/src/utils/moving_average.cpp b/src/utils/moving_average.cpp index d61695e..08cf344 100644 --- a/src/utils/moving_average.cpp +++ b/src/utils/moving_average.cpp @@ -48,7 +48,7 @@ MovingAverage::MovingAverage(int buffer_size, double starting_value) { * @param n the sample that will be added to the moving average. */ void MovingAverage::add_entry(double n){ - current_avg -= buffer[buffer_index]/get_size(); + current_avg -= buffer[buffer_index]/(double)get_size(); current_avg += n/get_size(); buffer[buffer_index] = n; From bc1e236838a8a09c5f48d449b2e2936a372c1c04 Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 10 Feb 2023 21:31:37 -0500 Subject: [PATCH 170/243] Graph Drawer + No Comments --- include/utils/graph_drawer.h | 104 +++++++++++++++++++++++++++++++++++ src/subsystems/flywheel.cpp | 6 +- 2 files changed, 108 insertions(+), 2 deletions(-) create mode 100644 include/utils/graph_drawer.h diff --git a/include/utils/graph_drawer.h b/include/utils/graph_drawer.h new file mode 100644 index 0000000..8e672f6 --- /dev/null +++ b/include/utils/graph_drawer.h @@ -0,0 +1,104 @@ +#pragma once + +#include +#include +#include "vex.h" + +class GraphDrawer +{ +public: + GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound) : Screen(screen), sample_index(0), xlabel(x_label), ylabel(y_label), col(col), border(draw_border), upper(upper_bound), lower(lower_bound) + { + std::vector temp(num_samples, Vector2D::point_t{.x = 0.0, .y = 0.0}); + samples = temp; + } + void add_sample(Vector2D::point_t sample) + { + samples[sample_index] = sample; + sample_index++; + sample_index %= samples.size(); + } + void draw(int x, int y, int width, int height) + { + if (samples.size() < 1) + { + return; + } + + double current_min = samples[0].y; + double current_max = samples[0].y; + double earliest_time = samples[0].x; + double latest_time = samples[0].x; + // collect data + for (int i = 0; i < samples.size(); i++) + { + Vector2D::point_t p = samples[i]; + if (p.x < earliest_time) + { + earliest_time = p.x; + } + else if (p.x > latest_time) + { + latest_time = p.x; + } + + if (p.y < current_min) + { + current_min = p.y; + } + else if (p.y > current_max) + { + current_max = p.y; + } + } + if (fabs(latest_time - earliest_time) < 0.001) + { + Screen.printAt(width / 2, height / 2, "Not enough Data"); + return; + } + if (upper != lower) + { + current_min = lower; + current_max = upper; + } + + if (border) + { + Screen.setPenWidth(1); + Screen.setPenColor(vex::white); + Screen.setFillColor(bgcol); + Screen.drawRectangle(x, y, width, height); + } + + double time_range = latest_time - earliest_time; + double sample_range = current_max - current_min; + double x_s = (double)x; + double y_s = (double)y + (double)height; + Screen.setPenWidth(4); + Screen.setPenColor(col); + for (int i = sample_index; i < samples.size() + sample_index - 1; i++) + { + Vector2D::point_t p = samples[i % samples.size()]; + double x_pos = x_s + ((p.x - earliest_time) / time_range) * (double)width; + double y_pos = y_s + ((p.y - current_min) / sample_range) * (double)(-height); + + Vector2D::point_t p2 = samples[(i + 1) % samples.size()]; + double x_pos2 = x_s + ((p2.x - earliest_time) / time_range) * (double)width; + double y_pos2 = y_s + ((p2.y - current_min) / sample_range) * (double)(-height); + + Screen.drawLine((int)x_pos, (int)y_pos, (int)x_pos2, (int)y_pos2); + } + } + +private: + vex::brain::lcd &Screen; + std::vector samples; + int sample_index = 0; + std::string xlabel; + std::string ylabel; + vex::color col = vex::red; + vex::color bgcol = vex::transparent; + bool border; + double upper; + double lower; +}; diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index d3f0e4a..be44f1d 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -22,7 +22,7 @@ using namespace vex; -const int FlywheelWindowSize = 1; +const int FlywheelWindowSize = 10; /********************************************************* * CONSTRUCTOR, GETTERS, SETTERS @@ -81,7 +81,7 @@ double Flywheel::measureRPM() { double rawRPM = ratio * motors.velocity(velocityUnits::rpm); RPM_avger.add_entry(rawRPM); smoothedRPM = RPM_avger.get_average(); - return rawRPM; //TODO Change back + return smoothedRPM; //TODO Change back } double Flywheel::getRPM(){ @@ -291,6 +291,8 @@ void Flywheel::spinRPM(int inputRPM) { void Flywheel::stop() { rpmTask.stop(); taskRunning = false; + RPM = 0.0; + smoothedRPM = 0.0; motors.stop(); } From 89ed8078b10ec62928003f477256271edec99e65 Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 10 Feb 2023 23:58:04 -0500 Subject: [PATCH 171/243] =?UTF-8?q?tuning=20auto=20tuning=20function/=20gi?= =?UTF-8?q?ves=20you=20control=20over=20the=20pid=20config=20as=20you=20ru?= =?UTF-8?q?n=20the=20autos=20something=20like=20whlie=20true{=20=20=20=20?= =?UTF-8?q?=20=20tune=5Fsomething();=20=20=20=20=20tune=5Fgeneric=5Fpid(fe?= =?UTF-8?q?edback=20that=20controls=20something);=20=20=20=20=20delay(20?= =?UTF-8?q?=20or=20so);=20}=20this=20features=20unsafe(kinda=20safe)=20cas?= =?UTF-8?q?ts,=20function=20pointers,=20AND=20ternaries=20=E2=98=BA?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- include/utils/feedback_base.h | 27 +++++++++++++++++++-------- include/utils/graph_drawer.h | 2 ++ include/utils/pid.h | 5 ++++- include/utils/pidff.h | 4 +++- src/utils/pid.cpp | 4 ++++ 5 files changed, 32 insertions(+), 10 deletions(-) diff --git a/include/utils/feedback_base.h b/include/utils/feedback_base.h index a716f53..19d45a9 100644 --- a/include/utils/feedback_base.h +++ b/include/utils/feedback_base.h @@ -2,18 +2,24 @@ /** * Interface so that subsystems can easily switch between feedback loops - * + * * @author Ryan McGee * @date 9/25/2022 - * + * */ -class Feedback +class Feedback { - public: +public: + enum FeedbackType + { + PIDType, + FeedforwardType, + OtherType, + }; /** * Initialize the feedback controller for a movement - * + * * @param start_pt the current sensor value * @param set_pt where the sensor value should be */ @@ -21,7 +27,7 @@ class Feedback /** * Iterate the feedback loop once with an updated sensor value - * + * * @param val value from the sensor * @return feedback loop result */ @@ -34,14 +40,19 @@ class Feedback /** * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. - * + * * @param lower Upper limit * @param upper Lower limit */ virtual void set_limits(double lower, double upper) = 0; - /** + /** * @return true if the feedback controller has reached it's setpoint */ virtual bool is_on_target() = 0; + + virtual Feedback::FeedbackType get_type() + { + return FeedbackType::OtherType; + } }; \ No newline at end of file diff --git a/include/utils/graph_drawer.h b/include/utils/graph_drawer.h index 8e672f6..d113f3c 100644 --- a/include/utils/graph_drawer.h +++ b/include/utils/graph_drawer.h @@ -2,7 +2,9 @@ #include #include +#include #include "vex.h" +#include "../core/include/utils/vector2d.h" class GraphDrawer { diff --git a/include/utils/pid.h b/include/utils/pid.h index b349131..4ff41e3 100644 --- a/include/utils/pid.h +++ b/include/utils/pid.h @@ -117,9 +117,12 @@ class PID : public Feedback */ void set_target(double target); -private: + Feedback::FeedbackType get_type() override; + pid_config_t &config; ///< configuration struct for this controller. see pid_config_t for information about what this contains +private: + double last_error = 0; ///< the error measured on the last iteration of update() double accum_error = 0; ///< the integral of error over time since we called init() diff --git a/include/utils/pidff.h b/include/utils/pidff.h index 43c0498..a09c6d3 100644 --- a/include/utils/pidff.h +++ b/include/utils/pidff.h @@ -60,11 +60,13 @@ class PIDFF : public Feedback */ bool is_on_target() override; + PID pid; + + private: FeedForward::ff_config_t &ff_cfg; - PID pid; FeedForward ff; double out; diff --git a/src/utils/pid.cpp b/src/utils/pid.cpp index cdd4933..ae35cd5 100644 --- a/src/utils/pid.cpp +++ b/src/utils/pid.cpp @@ -141,4 +141,8 @@ bool PID::is_on_target() } return false; +} + +Feedback::FeedbackType PID::get_type(){ + return Feedback::FeedbackType::PIDType; } \ No newline at end of file From 909fdf21663fbf2993679c43943fcaaa15f4f3ae Mon Sep 17 00:00:00 2001 From: cowsed Date: Thu, 16 Feb 2023 23:14:46 -0500 Subject: [PATCH 172/243] Fixed Comments that triggered -Wdocumentation --- include/subsystems/flywheel.h | 2 +- include/utils/graph_drawer.h | 23 +++++++++++++++++++ .../command_structure/drive_commands.cpp | 2 +- 3 files changed, 25 insertions(+), 2 deletions(-) diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index 3f0202a..199cf3e 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -147,7 +147,7 @@ class Flywheel{ /** * starts or sets the RPM thread at new value * what control scheme is dependent on control_style - * @param inputRPM - set the current RPM + * @param rpm - the RPM we want to spin at */ void spinRPM(int rpm); diff --git a/include/utils/graph_drawer.h b/include/utils/graph_drawer.h index d113f3c..f4f3f97 100644 --- a/include/utils/graph_drawer.h +++ b/include/utils/graph_drawer.h @@ -9,17 +9,40 @@ class GraphDrawer { public: +/** + * Construct a GraphDrawer + * @brief a helper class to graph values on the brain screen + * @param screen a reference to Brain.screen we can save for later + * @param num_samples the graph works on a fixed window and will plot the last `num_samples` before the history is forgotten. Larger values give more context but may slow down if you have many graphs or an exceptionally high + * @param x_label the name of the x axis (currently unused) + * @param y_label the name of the y axis (currently unused) + * @param draw_border whether to draw the border around the graph. can be turned off if there are multiple graphs in the same space ie. a graph of error and output + * @param lower_bound the bottom of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints + * @param upper_bound the top of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints +*/ GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound) : Screen(screen), sample_index(0), xlabel(x_label), ylabel(y_label), col(col), border(draw_border), upper(upper_bound), lower(lower_bound) { std::vector temp(num_samples, Vector2D::point_t{.x = 0.0, .y = 0.0}); samples = temp; } + + /** + * add_sample adds a point to the graph, removing one from the back + * @param sample an x, y coordinate of the next point to graph + */ void add_sample(Vector2D::point_t sample) { samples[sample_index] = sample; sample_index++; sample_index %= samples.size(); } + /** + * draws the graph to the screen in the constructor + * @param x x position of the top left of the graphed region + * @param y y position of the top left of the graphed region + * @param width the width of the graphed region + * @param height the height of the graphed region + */ void draw(int x, int y, int width, int height) { if (samples.size() < 1) diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index 3e1dc37..833f9ee 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -93,7 +93,7 @@ DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedbac * Construct a DriveForward Command * @param drive_sys the drive system we are commanding * @param feedback the feedback controller we are using to execute the drive - * @param y the point to drive to + * @param point the point to drive to * @param dir the direction to drive * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at */ From 8d08d3b5d73d5dd3cf3e211e3f3f9724801b2ad3 Mon Sep 17 00:00:00 2001 From: cowsed Date: Thu, 16 Feb 2023 20:00:27 -0500 Subject: [PATCH 173/243] withTImeout for initializer list auto path declaring also added disks to auto path --- include/intense_milk.h | 4 ++++ include/utils/command_structure/auto_command.h | 4 ++++ src/utils/command_structure/command_controller.cpp | 2 +- 3 files changed, 9 insertions(+), 1 deletion(-) create mode 100644 include/intense_milk.h diff --git a/include/intense_milk.h b/include/intense_milk.h new file mode 100644 index 0000000..3b9e4f9 --- /dev/null +++ b/include/intense_milk.h @@ -0,0 +1,4 @@ +#include +int intense_milk_width = 426; +int intense_milk_height = 244 +;uint32_t intense_milk[103944] = {0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00221e1f, 0x001e1a1b, 0x00191617, 0x00151313, 0x0011ff, 0x00cbb, 0x00877, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001e1b1c, 0x001a1718, 0x00161314, 0x0011f10, 0x00dbc, 0x00988, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001b1818, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001f1b1c, 0x001b1818, 0x00161414, 0x00121011, 0x00ecd, 0x00989, 0x00545, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x001b1819, 0x00171415, 0x00131111, 0x00edd, 0x00a99, 0x00655, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1e, 0x001c191a, 0x00181516, 0x00131112, 0x00fde, 0x00baa, 0x00666, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a89, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x001d191a, 0x00191616, 0x00141212, 0x0010ee, 0x00baa, 0x00767, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001e1a1b, 0x00191617, 0x00151213, 0x0011ff, 0x00cbb, 0x00877, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001e1b1b, 0x001a1718, 0x00161314, 0x0011f10, 0x00dbc, 0x00988, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151313, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001f1b1c, 0x001b1718, 0x00161414, 0x00121010, 0x00ecc, 0x00988, 0x00545, 0x00101, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x009e2822, 0x00d12c23, 0x00b72a23, 0x009e2822, 0x00862622, 0x006c2421, 0x00532321, 0x003a2120, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x001b1819, 0x00171415, 0x00131011, 0x00ecd, 0x00a99, 0x00655, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00323, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2020, 0x00b42a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00d42c23, 0x00bb2a23, 0x00a22823, 0x00892722, 0x00702522, 0x00582321, 0x003e2121, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x001c1919, 0x00171515, 0x00131112, 0x00fde, 0x00b9a, 0x00656, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00545, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00352020, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00d92c24, 0x00bf2b23, 0x00a62923, 0x008e2722, 0x00742522, 0x005b2321, 0x00432121, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x001d191a, 0x00181516, 0x00141212, 0x0010ee, 0x00baa, 0x00766, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00412121, 0x00d42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00d12920, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2d24, 0x00c22b23, 0x00aa2923, 0x00912722, 0x00772522, 0x00602321, 0x00462221, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001d1a1b, 0x00181516, 0x00121011, 0x00cab, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00512221, 0x00de2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x004e1411, 0x00477, 0x00788, 0x001ffe, 0x003c12f, 0x00591512, 0x00761a15, 0x00921f19, 0x00b0241c, 0x00cc2820, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02d24, 0x00c72b23, 0x00ae2923, 0x00952722, 0x007c2622, 0x00632421, 0x004a2221, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d191a, 0x0011ff, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00632421, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x003912f, 0x00477, 0x006a6c6c, 0x00767878, 0x00585a5a, 0x00383b3b, 0x00191a1a, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x001bed, 0x003811f, 0x00541411, 0x00711915, 0x008f1e18, 0x00ab231c, 0x00c7281f, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00cb2b23, 0x00b22a23, 0x00992822, 0x007f2622, 0x00672421, 0x004e2221, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00782522, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2920, 0x0027fe, 0x00799, 0x009fa0a0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00d8d8d8, 0x00b8b9b9, 0x009a9b9b, 0x007b7d7d, 0x005c5e5e, 0x003d3f3f, 0x001e1f1f, 0x00588, 0x00477, 0x00477, 0x00477, 0x00477, 0x0017dc, 0x003311f, 0x00501410, 0x006e1914, 0x00891d17, 0x00a6221b, 0x00c4271f, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00cf2c23, 0x00b52a23, 0x009d2822, 0x00842622, 0x006b2421, 0x00512221, 0x00392120, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00656, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171415, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x0018dc, 0x00f1010, 0x00b8b9b9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00dcdcdc, 0x00bebfbf, 0x009fa0a0, 0x007f8181, 0x00626363, 0x00424444, 0x00222424, 0x00799, 0x00477, 0x00477, 0x00477, 0x00477, 0x0012cb, 0x002f11f, 0x004b1310, 0x00681813, 0x00851d17, 0x00a2211b, 0x00be261e, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00d22c23, 0x00ba2a23, 0x00a12822, 0x00872622, 0x006f2522, 0x00562321, 0x003c2121, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00121011, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00a62923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ab231c, 0x00daa, 0x001b1c1c, 0x00cdcdcd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00e1e2e2, 0x00c2c3c3, 0x00a3a5a5, 0x00858686, 0x00656767, 0x00474949, 0x00282a2a, 0x00acc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00daa, 0x002a10f, 0x004712f, 0x00631713, 0x00801c16, 0x009d211a, 0x00bb251e, 0x00d72a21, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00d72c24, 0x00bd2a23, 0x00a52923, 0x008c2722, 0x00732522, 0x005a2321, 0x00412121, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00788, 0x00292b2b, 0x00dfdfdf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00e5e6e6, 0x00c8c9c9, 0x00a8a9a9, 0x00898a8a, 0x006a6c6c, 0x004c4e4e, 0x002c2e2e, 0x00e10f, 0x00477, 0x00477, 0x00477, 0x00477, 0x00a99, 0x002610f, 0x00421210, 0x005f1612, 0x007c1b16, 0x00992019, 0x00b5251d, 0x00d22921, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2d24, 0x00c22b23, 0x00a92923, 0x008f2722, 0x00772522, 0x005e2321, 0x00442121, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00c92b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00791a15, 0x00477, 0x003d3f3f, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x00cccccc, 0x00acadad, 0x008f9090, 0x006f7171, 0x00505252, 0x00323434, 0x00131414, 0x00477, 0x00477, 0x00477, 0x00477, 0x00888, 0x0021fe, 0x003e12f, 0x005b1612, 0x00771a15, 0x00941f19, 0x00b1241c, 0x00cd2820, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00c52b23, 0x00ac2923, 0x00942722, 0x007b2522, 0x00612421, 0x00492221, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00452221, 0x00d82c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x005d1612, 0x00477, 0x00555757, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00d1d1d1, 0x00b2b3b3, 0x00939494, 0x00747676, 0x00565858, 0x00363838, 0x00181919, 0x00477, 0x00477, 0x00477, 0x00477, 0x00577, 0x001dfe, 0x003911f, 0x00561511, 0x00731a15, 0x008f1e18, 0x00ac231c, 0x00c9281f, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00c92b23, 0x00b12923, 0x00972822, 0x007f2622, 0x00662421, 0x004c2221, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00451310, 0x00477, 0x006e7070, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00d6d6d6, 0x00b6b7b7, 0x00999a9a, 0x00797b7b, 0x005a5c5c, 0x003b3d3d, 0x001c1d1d, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x0018dd, 0x003511f, 0x00521411, 0x006e1914, 0x008b1d18, 0x00a8221b, 0x00c5271f, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00ab2923, 0x00722522, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00692421, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82a21, 0x003211f, 0x00477, 0x008c8d8d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00dbdbdb, 0x00bcbdbd, 0x009d9e9e, 0x007d7f7f, 0x00606161, 0x00404242, 0x00202221, 0x00799, 0x00477, 0x00477, 0x00477, 0x00477, 0x0014cc, 0x003111f, 0x004c1310, 0x006a1814, 0x00871d17, 0x00a3211b, 0x00c0261e, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00a32823, 0x00412121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007f2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2820, 0x0022fd, 0x009bb, 0x00a7a8a8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00e0e0e0, 0x00c0c1c1, 0x00a1a3a3, 0x00838484, 0x00636565, 0x00454747, 0x00262828, 0x009bb, 0x00477, 0x00477, 0x00477, 0x00477, 0x00eba, 0x002c11f, 0x00491210, 0x00651713, 0x00821c17, 0x009f211a, 0x00bc261e, 0x00d82a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x008e2722, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00962822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b8251d, 0x0015cc, 0x00121313, 0x00bfc0c0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00e4e5e5, 0x00c6c7c7, 0x00a6a7a7, 0x00878888, 0x00696b6b, 0x004a4c4c, 0x002a2c2c, 0x00cee, 0x00477, 0x00477, 0x00477, 0x00477, 0x00b99, 0x002810f, 0x004312f, 0x00611612, 0x00851d17, 0x00b4241d, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf2b23, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131011, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00ad2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a2211b, 0x00caa, 0x001e2020, 0x00d4d4d4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e9eaea, 0x00cacaca, 0x00abacac, 0x008d8e8e, 0x006d6f6f, 0x004e5050, 0x00303232, 0x00101111, 0x00477, 0x00477, 0x00eba, 0x005a1612, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322020, 0x00bf2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00688, 0x00303232, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00d8d8d8, 0x00a5a6a6, 0x005e6060, 0x00cee, 0x00477, 0x00611713, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a22822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x006e1914, 0x00477, 0x00434545, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x00686a6a, 0x00477, 0x003611f, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00502221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00767, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004b2221, 0x00dc2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00551512, 0x00477, 0x005c5e5e, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a2a4a4, 0x00477, 0x005d1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ab2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005b2321, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02c22, 0x003f1310, 0x00477, 0x00777979, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x00577, 0x00c8281f, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00682421, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x002c10e, 0x00699, 0x00949595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00477, 0x007e1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00612421, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c4271f, 0x001ded, 0x00dff, 0x00aeafaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00171818, 0x00581511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00602421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00542321, 0x00e92e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b5251d, 0x0011bb, 0x00171818, 0x00c5c6c6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00202222, 0x00521411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00caa, 0x00212323, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00bdd, 0x00661713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00572321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00c32b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ba251e, 0x00caa, 0x00262828, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c6c7c7, 0x00477, 0x00961f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00777, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00832622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22920, 0x0018dc, 0x001e2020, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007a7c7c, 0x00477, 0x00d52a21, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x003712f, 0x00cee, 0x00cdcdcd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00252727, 0x003911f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009d2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009c2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00811c16, 0x00477, 0x009a9b9b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c8c9c9, 0x00477, 0x008a1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005b2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbb, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00656, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00d72a21, 0x00daa, 0x00444646, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00727474, 0x00688, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00772522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006e1914, 0x00477, 0x00cfcfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x001d1e1e, 0x00411310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00992822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b22a23, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x0017dc, 0x00484a4a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c0c1c1, 0x00477, 0x00931f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00e22d24, 0x00ee2e24, 0x00ee2e24, 0x00be261e, 0x00477, 0x009d9e9e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00696b6b, 0x00999, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00d72c24, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00362020, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00171818, 0x004a1311, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791a15, 0x00477, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00477, 0x009b201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00412121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007e1b16, 0x00477, 0x00e6e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x00baa, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00a5221b, 0x00477, 0x00b2b3b3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00121313, 0x00531411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008b2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x0010bb, 0x00464848, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00adaeae, 0x00477, 0x00a3211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00432121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008e2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f1b16, 0x00477, 0x00878888, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00585a5a, 0x0011bb, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003b2120, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00471411, 0x00477, 0x006d6f6f, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00cee, 0x005a1512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008d2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x005f1713, 0x00477, 0x00171818, 0x007b7d7d, 0x00c6c7c7, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a4a6a6, 0x00477, 0x00ac231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003d2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00be2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x003f12f, 0x00477, 0x00477, 0x00acc, 0x002c2e2e, 0x004c4e4e, 0x00696b6b, 0x00898a8a, 0x00a8a9a9, 0x00c6c7c7, 0x00e5e6e6, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004f5151, 0x0018dc, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00c22b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302020, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00931f19, 0x00671813, 0x004612f, 0x002a10f, 0x00daa, 0x00477, 0x00477, 0x00477, 0x00477, 0x009bb, 0x00262828, 0x00444646, 0x00636565, 0x00818383, 0x00a1a2a2, 0x00bebfbf, 0x00dedede, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x008aa, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007b2522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171415, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2020, 0x009e2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x00bf261e, 0x00a3211b, 0x00851d17, 0x006a1814, 0x004c1310, 0x003111f, 0x0014cc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00588, 0x001e1f1f, 0x003d3f3f, 0x005c5e5e, 0x007a7c7c, 0x00999a9a, 0x00b8b9b9, 0x00d6d6d6, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009d9e9e, 0x00477, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00582321, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00c6271f, 0x00aa231c, 0x008d1e18, 0x00711915, 0x00541411, 0x003711f, 0x001bed, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00181919, 0x00363838, 0x00555757, 0x00737575, 0x00929393, 0x00b0b1b1, 0x00cfcfcf, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00454747, 0x001ced, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00b92a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00542321, 0x009e2822, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00cd2820, 0x00b0241c, 0x00941f19, 0x00771a15, 0x005b1612, 0x003e12f, 0x002310f, 0x00888, 0x00477, 0x00477, 0x00477, 0x00477, 0x00101111, 0x002e3030, 0x004e5050, 0x006b6d6d, 0x008b8c8c, 0x00a8a9a9, 0x00c8c9c9, 0x00e6e7e7, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00699, 0x006d1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00742522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x005a2321, 0x00732522, 0x008c2722, 0x00a42923, 0x00bd2a23, 0x00d52c24, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00d32a21, 0x00b7251d, 0x009a201a, 0x007e1b16, 0x00621713, 0x004512f, 0x002810f, 0x00caa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00acc, 0x00272929, 0x00464848, 0x00656767, 0x00838484, 0x00a2a4a4, 0x00c0c1c1, 0x00e0e0e0, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00929393, 0x00477, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00434, 0x001f1c1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x003b2120, 0x00542321, 0x006c2421, 0x00862622, 0x009e2822, 0x00b72a23, 0x00d02c23, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2b21, 0x00be261e, 0x00a1211a, 0x00851d17, 0x00681813, 0x004c1310, 0x002f11f, 0x0013cc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00699, 0x00202121, 0x003e4040, 0x005e6060, 0x007b7d7d, 0x009b9c9c, 0x00b9baba, 0x00d8d8d8, 0x00f7f7f7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x002b2d2d, 0x002a10e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b22a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00362020, 0x004e2221, 0x00672421, 0x007f2622, 0x00992822, 0x00b12a23, 0x00ca2b23, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00c5271f, 0x00a8221b, 0x008c1e18, 0x006f1914, 0x00531411, 0x003712f, 0x0019ed, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00191a1a, 0x00383a3a, 0x00565858, 0x00757777, 0x00939494, 0x00b2b3b3, 0x00d1d1d1, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a1a2a2, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302020, 0x00482221, 0x00612421, 0x007a2522, 0x00922722, 0x00ab2923, 0x00c42b23, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00cb2820, 0x00af231c, 0x00921f19, 0x00761a15, 0x00591512, 0x003d12f, 0x0021fe, 0x00788, 0x00477, 0x00477, 0x00477, 0x00477, 0x00121313, 0x00303232, 0x004f5151, 0x006d6f6f, 0x008c8d8d, 0x00aaabab, 0x00c9caca, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x00151616, 0x002d10f, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00de2d24, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00532321, 0x008a2722, 0x00bd2a23, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00d22921, 0x00b5251d, 0x009a201a, 0x007c1b16, 0x00611612, 0x004312f, 0x002810f, 0x00b99, 0x00477, 0x00477, 0x00477, 0x00477, 0x00bdd, 0x00292b2b, 0x00484a4a, 0x00666868, 0x00858686, 0x00a3a5a5, 0x00e4e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x002c2e2e, 0x00daa, 0x00c5271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00502221, 0x00a62923, 0x00e22d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x00d62a21, 0x00c7271f, 0x00b6251d, 0x00a6221b, 0x00941f19, 0x00841c17, 0x00741a15, 0x004e1310, 0x0021cb, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00aeafaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c2c3c3, 0x00202222, 0x00caa, 0x00ac231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131011, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x00ae2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x00d22920, 0x00c0261e, 0x00b0241c, 0x00a0211a, 0x008f1e18, 0x007f1b16, 0x006f1914, 0x005f1612, 0x004e1310, 0x003e12f, 0x002d11f, 0x001ced, 0x00caa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00101111, 0x00222323, 0x00343636, 0x00464848, 0x00585a5a, 0x00686a6a, 0x007a7c7c, 0x008c8d8d, 0x009d9e9e, 0x00aeafaf, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00959696, 0x00b3b4b4, 0x00d2d2d2, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00bebfbf, 0x00525454, 0x00477, 0x0020fe, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00522221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00191516, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00542321, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00dc2b22, 0x00cc2820, 0x00bc261e, 0x00ab231c, 0x009b201a, 0x008b1d18, 0x007a1b16, 0x006a1814, 0x00581511, 0x00491210, 0x003911f, 0x002810f, 0x0018dd, 0x00888, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00588, 0x00171818, 0x00272929, 0x00393c3c, 0x004b4d4d, 0x005d5f5f, 0x006d6f6f, 0x007f8181, 0x00929393, 0x00a3a5a5, 0x00b5b6b6, 0x00c6c7c7, 0x00d8d8d8, 0x00e9eaea, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b5b6b6, 0x00477, 0x00477, 0x00477, 0x00477, 0x00131414, 0x00313333, 0x00505252, 0x006c6e6e, 0x00808282, 0x00909191, 0x008a8b8b, 0x00787a7a, 0x00505252, 0x00171818, 0x00477, 0x00eba, 0x00721915, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00732522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00b9a, 0x00131112, 0x001a1717, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00492221, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00ac231c, 0x005a1512, 0x0023fe, 0x00888, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00acc, 0x001b1c1c, 0x002c2e2e, 0x003e4040, 0x00505252, 0x00626363, 0x00747676, 0x00858686, 0x00979898, 0x00a8a9a9, 0x00babbbb, 0x00cbcbcb, 0x00dddddd, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e8e8, 0x00477, 0x005f1612, 0x00982019, 0x007b1b16, 0x005f1612, 0x00421210, 0x002610f, 0x00caa, 0x00477, 0x00477, 0x00477, 0x00999, 0x0020fe, 0x00511411, 0x00951f19, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x007b2522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00544, 0x00988, 0x00dcc, 0x00111010, 0x00161314, 0x001b1718, 0x001f1b1c, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x003611f, 0x00477, 0x00111212, 0x004d4f4f, 0x00737575, 0x008a8b8b, 0x009c9d9d, 0x00adaeae, 0x00bebfbf, 0x00d2d2d2, 0x00e3e4e4, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e6e6, 0x00477, 0x00831c17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00da2b21, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00602321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00877, 0x00cbb, 0x0011ef, 0x00151313, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007a2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x0016dc, 0x00141515, 0x00979898, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cbcbcb, 0x00477, 0x009e211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00a12822, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x002a10e, 0x00161717, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a5a6a6, 0x00477, 0x00bf261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00db2d24, 0x00942722, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201d1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a6221b, 0x00477, 0x00a1a2a2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00828383, 0x00477, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00c02b23, 0x00772522, 0x008f2722, 0x00a62923, 0x00b72a23, 0x00bc2a23, 0x00bb2a23, 0x00ad2923, 0x00972822, 0x00762522, 0x00492221, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151313, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00592321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00691814, 0x008aa, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x0017dc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00662421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00561511, 0x00212222, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003b3d3d, 0x003811f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00732522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191717, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00622421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00e10f, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00181919, 0x00581511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00582321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171415, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004b2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00941f19, 0x00477, 0x00c5c6c6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00477, 0x00791b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003c2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00fee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00271f20, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00caa, 0x00555757, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cdcdcd, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191616, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aa2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a1814, 0x00477, 0x00cfcfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00522221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92a21, 0x00eba, 0x004d4f4f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00858686, 0x00477, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00b02923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00191616, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bc2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00721915, 0x00477, 0x00c7c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x0013cb, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00952722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1b, 0x00151314, 0x00dbc, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00101, 0x00767, 0x00dcc, 0x00121010, 0x00161314, 0x00181516, 0x00171515, 0x00141212, 0x0010ee, 0x00988, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00522221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x0012cb, 0x00424444, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003e4040, 0x003411f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00782522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fde, 0x00656, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00dbb, 0x00141212, 0x001b1819, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00161414, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b42a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c1b16, 0x00477, 0x00bcbdbd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00101111, 0x005f1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00592321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00b9a, 0x00121010, 0x00191617, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004a2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0016cc, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00babbbb, 0x00477, 0x00982019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00878, 0x0010ee, 0x00171515, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00878, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ab2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00871d17, 0x00477, 0x00b0b1b1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003c3e3e, 0x0012bb, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00656, 0x00ecd, 0x00151313, 0x001d191a, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00992822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2920, 0x00477, 0x004c4e4e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00727474, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008b2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00cab, 0x00131111, 0x001b1818, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00656, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006d2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00381210, 0x00bdd, 0x00cbcbcb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d5d5d5, 0x004c4e4e, 0x00477, 0x005a1612, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00372020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00a89, 0x0011ff, 0x00191616, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00101, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004a2221, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00477, 0x009e9f9f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00e7e8e8, 0x00d6d6d6, 0x00c5c6c6, 0x00b3b4b4, 0x00a2a4a4, 0x00909191, 0x007e8080, 0x00626464, 0x002f3131, 0x00477, 0x00baa, 0x007d1b16, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00892722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00767, 0x00fde, 0x00161414, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00d32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00477, 0x00686a6a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00e0e0e0, 0x00cecece, 0x00bcbdbd, 0x00aaabab, 0x009a9b9b, 0x00888989, 0x00777979, 0x00656767, 0x00555757, 0x00434545, 0x00303232, 0x001f2020, 0x00eff, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x0015dc, 0x003b1210, 0x007d1b16, 0x00d72a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bd2a23, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00dbc, 0x00141213, 0x001c1819, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ae2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bd261e, 0x00ba9, 0x00393b3b, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00e8e9e9, 0x00d8d8d8, 0x00c6c7c7, 0x00b5b6b6, 0x00a3a5a5, 0x00929393, 0x007f8181, 0x006e7070, 0x005d5f5f, 0x004c4e4e, 0x003a3c3c, 0x00292b2b, 0x00181919, 0x00799, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00577, 0x0016dc, 0x002510f, 0x003612f, 0x004512f, 0x00561511, 0x00651713, 0x00761a15, 0x00851d17, 0x00971f19, 0x00a7221b, 0x00b7251d, 0x00c7281f, 0x00d72a21, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c32b23, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00b9a, 0x00121010, 0x001a1717, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00712522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x001eed, 0x001b1c1c, 0x00e4e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x00565858, 0x00444646, 0x00323434, 0x00202121, 0x00f1010, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00caa, 0x001cee, 0x002d11f, 0x003c12f, 0x004d1310, 0x005e1612, 0x006e1914, 0x007e1b16, 0x008e1e18, 0x009e211a, 0x00ae231c, 0x00be261e, 0x00cf2920, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00888, 0x0010ef, 0x00171516, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00423f3f, 0x006b6869, 0x00828080, 0x00807e7e, 0x00555253, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00471310, 0x00699, 0x00c2c3c3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x001e2020, 0x0011bb, 0x00351110, 0x004412f, 0x00551411, 0x00641713, 0x00751a15, 0x00841c17, 0x00961f19, 0x00a6221b, 0x00b7251d, 0x00c7271f, 0x00d72a21, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00b52a23, 0x00532321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00766, 0x00ecc, 0x00151314, 0x001d191a, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00646162, 0x00929091, 0x00c2c1c1, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c4c4, 0x002f2b2c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a62923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c1e18, 0x00477, 0x007d7f7f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00525454, 0x00688, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x00d32c23, 0x00c52b23, 0x00b32a23, 0x00952722, 0x006f2521, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00565354, 0x00858384, 0x00b4b3b3, 0x00e3e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a09e9f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004e2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00eba, 0x00383a3a, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00969797, 0x00477, 0x00771a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00db2d24, 0x00cd2c23, 0x00bf2b23, 0x00b12a23, 0x00a32823, 0x00942722, 0x00872622, 0x00782522, 0x006b2421, 0x005c2321, 0x004e2221, 0x00402121, 0x00322020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00484546, 0x00787677, 0x00a6a5a5, 0x00d6d5d5, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00877, 0x00cbb, 0x00fdd, 0x00211e1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b32a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00531411, 0x008aa, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d2d2d2, 0x00bdd, 0x003a1210, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00d42c23, 0x00c62b23, 0x00b82a23, 0x00aa2923, 0x009c2822, 0x008e2722, 0x00802622, 0x00732522, 0x00642421, 0x00562321, 0x00482221, 0x00392120, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003b3838, 0x006b6869, 0x00999798, 0x00c8c7c7, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00dbc, 0x00161414, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003e2121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x00707272, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x002c2e2e, 0x0013cb, 0x00d22921, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12923, 0x00792522, 0x006b2421, 0x005d2321, 0x00502221, 0x00412121, 0x00342020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302c2d, 0x005e5b5b, 0x008c8a8b, 0x00bbbaba, 0x00e9e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00181616, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00852622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005d1612, 0x00bdd, 0x00e6e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00676969, 0x00477, 0x00a3211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2b23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x003b2120, 0x003b2120, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00272324, 0x00514e4e, 0x007e7c7d, 0x00aeacad, 0x00dcdcdc, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bf2b23, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x0010bb, 0x00585a5a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00452221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00342020, 0x00412121, 0x00502221, 0x005d2321, 0x006b2421, 0x007a2522, 0x00872622, 0x00962822, 0x00a52923, 0x00b32a23, 0x00c12b23, 0x00cf2c23, 0x00dc2d24, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00ca2b23, 0x00842622, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00726f70, 0x00a09e9f, 0x00d0cfcf, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x001c1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00b9251d, 0x00477, 0x00a6a7a7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00131414, 0x002c10e, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00742522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2020, 0x00382120, 0x00472221, 0x00542321, 0x00642421, 0x00722522, 0x00802622, 0x008e2722, 0x009c2822, 0x00aa2923, 0x00b82a23, 0x00c62b23, 0x00d42c23, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2d24, 0x005d2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00646162, 0x00939192, 0x00c2c1c1, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0012f10, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00362020, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003c3e3e, 0x00baa, 0x00c6271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00be2a23, 0x004d2221, 0x005c2321, 0x00692421, 0x00772522, 0x00852622, 0x00932722, 0x00a12822, 0x00b12923, 0x00be2a23, 0x00cd2c23, 0x00da2d24, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00642421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2829, 0x00575454, 0x00868485, 0x00b4b3b3, 0x00e3e3e3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00442121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007e1b16, 0x00477, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007e8080, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92d23, 0x00d92a21, 0x00c8281f, 0x00b9251d, 0x00a8221b, 0x00992019, 0x00871d17, 0x00771a15, 0x00661713, 0x005b1612, 0x005c1612, 0x00801c16, 0x00d22921, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52d24, 0x003e2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00494646, 0x00797777, 0x00a7a5a6, 0x00d6d6d6, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00e2e3e3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00799, 0x004d1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00d32a21, 0x00c2271f, 0x00b1241c, 0x00a1211a, 0x00911f19, 0x00811c16, 0x00701914, 0x00611612, 0x00501410, 0x004112f, 0x002f11f, 0x001ffe, 0x00eba, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00dff, 0x001d1e1e, 0x001b1c1c, 0x00477, 0x00a99, 0x00982019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a82923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c3839, 0x00c9c8c8, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2020, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00477, 0x00a4a6a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003a3c3c, 0x0019ed, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00dc2b22, 0x00cb2820, 0x00bc261e, 0x00ab231c, 0x009b201a, 0x008b1d18, 0x007a1b16, 0x006a1814, 0x00591512, 0x00491210, 0x003911f, 0x002911f, 0x0018dd, 0x00999, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00151616, 0x00262727, 0x00373a3a, 0x00494b4b, 0x005a5c5c, 0x006b6d6d, 0x007d7f7f, 0x008e8f8f, 0x00a0a1a1, 0x00b2b3b3, 0x00c3c4c4, 0x00d5d5d5, 0x00e6e7e7, 0x00f7f7f7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dadada, 0x003b3d3d, 0x00788, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00502221, 0x00812622, 0x00a42923, 0x00bc2a23, 0x00c92b23, 0x00c92b23, 0x00ba2a23, 0x00a22822, 0x00732522, 0x003a2120, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x001ced, 0x00393b3b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00477, 0x004c1310, 0x00a5221b, 0x00a4221b, 0x00941f19, 0x00841c17, 0x00731a15, 0x00631713, 0x00531411, 0x004312f, 0x00331210, 0x002310f, 0x0012cb, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00acc, 0x001a1c1b, 0x002c2e2e, 0x003e4040, 0x004f5151, 0x00616262, 0x00737575, 0x00858686, 0x00969797, 0x00a7a8a8, 0x00b8b9b9, 0x00cacaca, 0x00dcdcdc, 0x00eceded, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x00151616, 0x004d1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00982822, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00b72a23, 0x00562321, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00821c17, 0x00477, 0x00bebfbf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x003e4040, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00101111, 0x00222323, 0x00343636, 0x00464848, 0x00575959, 0x00686a6a, 0x007a7c7c, 0x008b8c8c, 0x009d9e9e, 0x00adaeae, 0x00c0c1c1, 0x00d2d2d2, 0x00e3e4e4, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00616262, 0x0012cb, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008e2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c6c5c5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003a2120, 0x00a82923, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c42b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0012bb, 0x00464848, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dadada, 0x00c2c3c3, 0x00cdcdcd, 0x00d9d9d9, 0x00e9eaea, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007f8181, 0x00477, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bab9b9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00722522, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x00c6271f, 0x00b1241c, 0x00ab231c, 0x00bd261e, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00761a15, 0x00477, 0x00cacaca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00eba, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00932722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bdbbbc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x009a2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82a21, 0x007f1b16, 0x003712f, 0x00788, 0x00477, 0x00477, 0x00477, 0x00477, 0x00688, 0x00391210, 0x00971f19, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x00daa, 0x00535555, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x001c1d1d, 0x00451310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00772522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cfcece, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00383435, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00631713, 0x00898, 0x00477, 0x00373939, 0x00787a7a, 0x00a7a8a8, 0x00bbbcbc, 0x00bbbcbc, 0x00a5a6a6, 0x00707272, 0x00212323, 0x00477, 0x002d10f, 0x00c5271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a1814, 0x00588, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a0a1a1, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00492221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00e8e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00862622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a5221b, 0x0015cc, 0x00699, 0x00676969, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00a2a4a4, 0x00151616, 0x0011cb, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00999, 0x00616262, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eceded, 0x001a1b1b, 0x002d10f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332f30, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccbcb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c2221, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008b1d18, 0x00477, 0x00323434, 0x00d1d1d1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dbdbdb, 0x001d1f1f, 0x0019dc, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005d1612, 0x00799, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00565858, 0x00688, 0x00b9251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00782522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00676465, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00747272, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c12b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c201a, 0x00477, 0x004b4d4d, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c6c7c7, 0x00588, 0x00671813, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2820, 0x00577, 0x006d6f6f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a0a1a1, 0x00477, 0x00731a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a7a5a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9c8c8, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1717, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00582321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00fbb, 0x00353737, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00565858, 0x00eba, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00511511, 0x00cee, 0x00e9eaea, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x00f1010, 0x003311f, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005c2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cbcacb, 0x00302c2d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ae2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005d1612, 0x00799, 0x00d7d7d7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a7a8a8, 0x00477, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c0261e, 0x00477, 0x007a7c7c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00393b3b, 0x00eba, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00727070, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x007f7d7e, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2b21, 0x00a99, 0x005f6060, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cdcdcd, 0x00477, 0x00992019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00451310, 0x00131414, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007d7f7f, 0x00477, 0x00901e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00dbdada, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00d1d0d1, 0x00a4a2a2, 0x00737171, 0x00413e3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151313, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00912722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c1b16, 0x00477, 0x00cdcdcd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cacaca, 0x00477, 0x00982019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b3241d, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x00699, 0x004d1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x004b2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00757273, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dedede, 0x00b0afaf, 0x00817f7f, 0x00524f50, 0x00292526, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x001ded, 0x003b3d3d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a9aaaa, 0x00477, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00bf2b23, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003811f, 0x001a1b1b, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00222424, 0x001bed, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00822622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2a2b, 0x00e7e6e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ececec, 0x00bdbcbd, 0x008e8c8c, 0x005f5c5d, 0x00322e2f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00722522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009f211a, 0x00477, 0x00a6a7a7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005d5f5f, 0x00baa, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x007e2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a7221b, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005d5f5f, 0x00477, 0x00af231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bb2a23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a4a2a2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cac9ca, 0x009b999a, 0x006c6a6a, 0x003e3a3b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131011, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c92b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003b1210, 0x001c1d1d, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00dff, 0x00561511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006e2521, 0x002d2020, 0x00df2d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x002d10e, 0x00212323, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a7a7, 0x00477, 0x006c1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00464344, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00d7d7d7, 0x00a9a7a8, 0x007a7878, 0x004b4748, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c3271f, 0x00477, 0x00828383, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008e8f8f, 0x00477, 0x00b8251d, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00302020, 0x00231f20, 0x00892722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c201a, 0x00477, 0x00a2a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00121313, 0x002e10f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00e5e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e4e4e4, 0x00b6b4b5, 0x00878585, 0x00585555, 0x002c292a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aa2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e1612, 0x009bb, 0x00e6e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00232525, 0x003010f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a32823, 0x00231f20, 0x00231f20, 0x00322020, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x0024fe, 0x002c2e2e, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x003f4141, 0x00b99, 0x00c7281f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a22822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00807e7f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c3c2c2, 0x00949293, 0x00656262, 0x00373334, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00baa, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b1b2b2, 0x00477, 0x00951f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00932722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00b0b1b1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00858686, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32c23, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2c2c, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0cfcf, 0x00a2a0a1, 0x00726f70, 0x00444041, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008e2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00811c16, 0x00477, 0x00c8c9c9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00474949, 0x0017dc, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00c12b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x001adc, 0x00393b3b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cacaca, 0x008aa, 0x00471310, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00502221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a7a6a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dddddd, 0x00aeacad, 0x007f7d7e, 0x00514e4e, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x0021fd, 0x00363838, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x00477, 0x00711915, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009e2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00831c17, 0x00477, 0x00b7b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00262828, 0x0018dc, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00882622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c3839, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00423f3f, 0x00423f3f, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2521, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a4221b, 0x00477, 0x00a1a3a3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x00788, 0x00d22921, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2d24, 0x00c62b23, 0x00a92923, 0x00832622, 0x005c2321, 0x00342020, 0x00402121, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x001eed, 0x00232525, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00e8e9e9, 0x00d8d8d8, 0x00c6c7c7, 0x00b5b6b6, 0x00a3a5a5, 0x00939494, 0x00808282, 0x006f7171, 0x005e6060, 0x00343737, 0x00477, 0x00a9231b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c02b23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aeacad, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x003b3838, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x006c6a6a, 0x009a9899, 0x00c9c8c8, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00dedede, 0x00555253, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00989, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c62b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003f1210, 0x00191a1a, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00f1111, 0x004f1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b2241d, 0x00999, 0x002a2c2c, 0x00d2d2d2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00dedede, 0x00cdcdcd, 0x00bcbdbd, 0x00aaabab, 0x009a9b9b, 0x00888989, 0x00777979, 0x00656767, 0x00555757, 0x00444646, 0x00313333, 0x001f2020, 0x00f1010, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00baa, 0x001bed, 0x002c11f, 0x00741a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x003e2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00474445, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322e2f, 0x005f5c5d, 0x008d8b8c, 0x00bdbcbd, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00502221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c7271f, 0x00477, 0x007d7f7f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00929393, 0x00477, 0x00b3241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ad231c, 0x0014cc, 0x00799, 0x005c5e5e, 0x00b2b3b3, 0x00e2e3e3, 0x00efefef, 0x00e6e7e7, 0x00d5d5d5, 0x00c4c5c5, 0x00b2b3b3, 0x00a1a3a3, 0x008f9090, 0x007e8080, 0x006c6e6e, 0x005c5e5e, 0x004a4c4c, 0x00393c3c, 0x00282a2a, 0x00171818, 0x00699, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00577, 0x0015dc, 0x002510f, 0x00351110, 0x004512f, 0x00551411, 0x00641713, 0x00751a15, 0x00841c17, 0x00951f19, 0x00a6221b, 0x00b6251d, 0x00c6271f, 0x00d62a21, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b0aeaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00535051, 0x00828080, 0x00b1b0b0, 0x00dfdedf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009d9b9b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a72923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00799, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00272929, 0x002d10f, 0x00ee2e24, 0x00df2c22, 0x00bd261e, 0x00a2211b, 0x00961f19, 0x009b201a, 0x00b7251d, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92a21, 0x00651713, 0x00daa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00daa, 0x001dfe, 0x002d11f, 0x003e11f, 0x004e1310, 0x005f1612, 0x006e1914, 0x007e1b16, 0x008f1e18, 0x009e211a, 0x00af231c, 0x00be261e, 0x00cf2920, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a92923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302c2d, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00484546, 0x00777475, 0x00a5a4a4, 0x00d3d2d2, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcece, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x00daa, 0x00585a5a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b6b7b7, 0x00477, 0x002eec, 0x002e11f, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x001bed, 0x00481310, 0x00761a15, 0x00a3211b, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00af231c, 0x008c1e18, 0x00871d17, 0x00881d17, 0x00982019, 0x00a8221b, 0x00b8251d, 0x00c8281f, 0x00d82a21, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72c24, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00636061, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c3839, 0x006b6969, 0x00999798, 0x00c8c7c7, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008a2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00861d17, 0x00477, 0x00c3c4c4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004b4d4d, 0x00477, 0x00588, 0x003d3f3f, 0x00787a7a, 0x00adaeae, 0x00c6c7c7, 0x00d6d6d6, 0x00d2d2d2, 0x00b3b4b4, 0x00888989, 0x00575959, 0x00262828, 0x00477, 0x00477, 0x00477, 0x0014cc, 0x00411210, 0x006e1914, 0x009a201a, 0x00c9281f, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00d62c24, 0x00c72b23, 0x00b92a23, 0x00ab2923, 0x009e2822, 0x00902722, 0x00822622, 0x004a2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00848182, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322e2f, 0x005f5c5d, 0x008d8b8c, 0x00bdbbbc, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c1c0c0, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00db2d24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x0023fe, 0x00313333, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dbdbdb, 0x001e2020, 0x00828383, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c1c2c2, 0x008f9090, 0x00606161, 0x002d2f2f, 0x00799, 0x00477, 0x00477, 0x00daa, 0x00391210, 0x00651713, 0x00941f19, 0x00c0261e, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00dc2d24, 0x00cd2c23, 0x00c02b23, 0x00b22a23, 0x00a42923, 0x00962722, 0x00872622, 0x00792522, 0x006b2421, 0x005e2321, 0x00502221, 0x00422121, 0x00342020, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00918f90, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00535051, 0x00828080, 0x00b1b0b0, 0x00dfdedf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008e8c8c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006b2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a7221b, 0x00477, 0x009e9f9f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e1e2e2, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00c9caca, 0x00999a9a, 0x00676969, 0x00373939, 0x00acc, 0x00477, 0x00477, 0x00999, 0x003111f, 0x005f1612, 0x008c1e18, 0x00b9251d, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2d24, 0x00b32a23, 0x008b2722, 0x00642421, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a3a1a1, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00474445, 0x00777475, 0x00a5a4a4, 0x00d3d2d2, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00441310, 0x00161717, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00d2d2d2, 0x00a1a2a2, 0x006f7171, 0x003f4141, 0x00101111, 0x00477, 0x00477, 0x00688, 0x002910f, 0x00571511, 0x00841c17, 0x00b1241c, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02d24, 0x00b92a23, 0x00922722, 0x006b2421, 0x00432121, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00636061, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00494646, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003b3838, 0x006b6869, 0x00989697, 0x00c7c6c6, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bab9b9, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ff, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004d2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2820, 0x00477, 0x00787a7a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00dadada, 0x00a8a9a9, 0x00787a7a, 0x00474949, 0x00171818, 0x00477, 0x00477, 0x00477, 0x0023fe, 0x004e1310, 0x007d1b16, 0x00a9231b, 0x00d72a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d24, 0x00c02b23, 0x009a2822, 0x00712522, 0x004b2221, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00625f60, 0x00413e3f, 0x00615e5f, 0x008d8b8c, 0x00bcbabb, 0x00eaeaea, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004d4a4b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00434, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a32823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00671813, 0x00699, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e1e2e2, 0x00b1b2b2, 0x00808282, 0x00505252, 0x001e2020, 0x00477, 0x00477, 0x00477, 0x0019dd, 0x00471310, 0x00741a15, 0x00a2211b, 0x00cf2920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00c72b23, 0x009c2822, 0x00682421, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bbbaba, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00352020, 0x00e92e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00fba, 0x00535555, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00b9baba, 0x00898a8a, 0x00585a5a, 0x00272929, 0x00477, 0x00477, 0x00477, 0x0012cb, 0x004012f, 0x006d1814, 0x009a201a, 0x00c7281f, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52d24, 0x00982822, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00272324, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00484546, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00bfc0c0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00c2c3c3, 0x00919292, 0x00606161, 0x002f3131, 0x00799, 0x00477, 0x00477, 0x00daa, 0x003812f, 0x00651713, 0x00911f19, 0x00c0261e, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00662421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00494646, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b4b3b3, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x0027fe, 0x002d2f2f, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cacaca, 0x00999a9a, 0x00686a6a, 0x00373939, 0x00cee, 0x00477, 0x00477, 0x00888, 0x003011f, 0x005d1612, 0x008b1d18, 0x00bb251e, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00752522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008d8b8c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00474445, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00672421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x00477, 0x00999a9a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00d2d2d2, 0x00a2a4a4, 0x00707272, 0x00404242, 0x00101111, 0x00477, 0x00477, 0x0010bb, 0x00551511, 0x00c2271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00562321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00d3d2d2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0aeaf, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00be2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00491310, 0x00141515, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dbdbdb, 0x00a4a6a6, 0x005e6060, 0x00bdd, 0x00688, 0x007d1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00494646, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171415, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00492221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ce2920, 0x00577, 0x00727474, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x004f5151, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00642421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00adacac, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a02822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b1814, 0x00588, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003d3f3f, 0x0011bb, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00a62923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00d0cfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322020, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x0011bb, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b3b4b4, 0x00477, 0x00a6221b, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00151313, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00464243, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00832622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00b8b9b9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e4e5e5, 0x00477, 0x00871d17, 0x00ee2e24, 0x00ee2e24, 0x00e02d24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00211, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00858384, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d52c24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x002b10e, 0x00292b2b, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dedede, 0x00477, 0x008a1d18, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00cbcacb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00632421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00477, 0x00949595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x00ae231c, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00838181, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00767, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004d1411, 0x00101111, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00595b5b, 0x0011bb, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00a32823, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00dbc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00e1e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00452221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12920, 0x00688, 0x006e7070, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e9e9, 0x009bb, 0x005d1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006c2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x001e1b1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00726f70, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009c2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f1914, 0x00477, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00828383, 0x00477, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00e52d24, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00dcdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00c8c7c7, 0x00787576, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x0014cb, 0x004a4c4c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x001d1f1f, 0x003a1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00686566, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfbfc, 0x00d3d2d2, 0x00a5a4a4, 0x00777475, 0x00484546, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007e2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00452221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d3d2d2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x00b1b0b0, 0x00838181, 0x00545152, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00656, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002e10f, 0x00252727, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003d3f3f, 0x001ced, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00bb2a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00655, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00615e5f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00bebdbd, 0x008f8d8d, 0x00615e5f, 0x00332f30, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00602421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b4241d, 0x00477, 0x00909191, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcfcf, 0x00477, 0x007a1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cac9c9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cac9ca, 0x009b999a, 0x006d6b6b, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b72a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00521511, 0x00e1010, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00999, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00d52c24, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbb, 0x00000, 0x001a1717, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00585555, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00d6d6d6, 0x00a8a6a7, 0x007a7878, 0x004b4748, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00788, 0x00696b6b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d5d5d5, 0x00d2d2d2, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00bdd, 0x00581512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00100, 0x00767, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e3e3, 0x00b4b3b3, 0x00868485, 0x00575454, 0x002c292a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00982822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00731a15, 0x00477, 0x00d5d5d5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00383a3a, 0x00477, 0x00acc, 0x00373939, 0x00676969, 0x00999a9a, 0x00c9caca, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00898a8a, 0x00477, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00322020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00111010, 0x00000, 0x00191516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004e4b4c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efeeee, 0x00c1c0c0, 0x00929091, 0x00646162, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2020, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x0018dc, 0x00444646, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9caca, 0x00477, 0x00571511, 0x00661713, 0x003911f, 0x00daa, 0x00477, 0x00477, 0x00799, 0x002f3131, 0x00606161, 0x00919292, 0x00c2c3c3, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00202222, 0x003511f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a02822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00545, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfbfc, 0x00cdcccc, 0x009e9d9d, 0x00706d6e, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007b2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00971f19, 0x00477, 0x00afb0b0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x00b99, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00c9281f, 0x009a201a, 0x006e1914, 0x004012f, 0x0013cb, 0x00477, 0x00477, 0x00477, 0x00272929, 0x00595b5b, 0x00898a8a, 0x00bbbcbc, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00adaeae, 0x00477, 0x00992019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00492221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00474445, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00d02c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003211f, 0x00222424, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e9e9, 0x009bb, 0x005c1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2920, 0x00a3211b, 0x00741a15, 0x00481310, 0x0019dd, 0x00477, 0x00477, 0x00477, 0x00202221, 0x00505252, 0x00828383, 0x00b2b3b3, 0x00e4e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00424444, 0x0018dc, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00be2a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b0aeaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2829, 0x00575454, 0x00868485, 0x00b0aeaf, 0x00c7c6c6, 0x00c2c1c1, 0x00918f90, 0x00332f30, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ba251e, 0x00477, 0x008b8c8c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00838484, 0x00477, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72a21, 0x00a9231b, 0x007c1b16, 0x004e1310, 0x0021fe, 0x00477, 0x00477, 0x00477, 0x00181919, 0x004a4c4c, 0x00797b7b, 0x00abacac, 0x00dcdcdc, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d3d3d3, 0x00477, 0x00761a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00545, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00413e3f, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x004a4747, 0x00797777, 0x00a8a6a7, 0x00d6d6d6, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e7e7, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b02923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00561511, 0x00cee, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x001d1f1f, 0x003a1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c42b23, 0x00bd2a23, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00b1241c, 0x00831c17, 0x00551411, 0x002810f, 0x00577, 0x00477, 0x00477, 0x00121313, 0x00414343, 0x00737575, 0x00a3a5a5, 0x00d5d5d5, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00676969, 0x00898, 0x00d52a21, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00dbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a19fa0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x006c6a6a, 0x009b999a, 0x00cac9c9, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0afaf, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00101, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82a21, 0x00999, 0x00646666, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00452221, 0x00231f20, 0x00241f20, 0x00402121, 0x00672421, 0x008f2722, 0x00b72a23, 0x00de2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00b8251d, 0x00891d17, 0x005d1612, 0x002e11f, 0x00888, 0x00477, 0x00477, 0x00cee, 0x003a3c3c, 0x006b6d6d, 0x009c9d9d, 0x00cdcdcd, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00cee, 0x00541512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00872622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00111, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312d2e, 0x005f5c5c, 0x008d8b8c, 0x00bdbbbc, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00652421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00871d17, 0x00477, 0x00c9caca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003e4040, 0x001ced, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00b92a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00522221, 0x00892722, 0x00c12b23, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00bd261e, 0x00911f19, 0x00631713, 0x003712f, 0x00baa, 0x00477, 0x00477, 0x008aa, 0x00323434, 0x00636565, 0x00959696, 0x00c5c6c6, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00636565, 0x00577, 0x00c7281f, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00474445, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00524e4f, 0x00807e7e, 0x00b0aeaf, 0x00dedede, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00363233, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008a2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1310, 0x001d1e1e, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcfcf, 0x00477, 0x007a1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x006c2421, 0x00b52a23, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x00c6271f, 0x00982019, 0x006b1814, 0x003c12f, 0x0010bb, 0x00477, 0x00477, 0x00588, 0x002a2c2c, 0x005d5f5f, 0x008c8d8d, 0x00bebfbf, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a7a7, 0x00477, 0x005e1613, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00434, 0x00000, 0x00000, 0x00171516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00625f60, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00454142, 0x00737171, 0x00a3a1a1, 0x00d1d0d1, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a02822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a11f, 0x00474949, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00999, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00d52c24, 0x00251f20, 0x00231f20, 0x00251f20, 0x00752522, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00cc2820, 0x009f211a, 0x00711915, 0x00431210, 0x0017dc, 0x00477, 0x00477, 0x00477, 0x00242626, 0x00545656, 0x00868787, 0x00b5b6b6, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009e9f9f, 0x00799, 0x002e11f, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00686566, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00383435, 0x00666464, 0x00969494, 0x00c4c3c4, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002510f, 0x004e5050, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00bdd, 0x00581512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00812622, 0x00231f20, 0x00422121, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00df2c22, 0x00df2c22, 0x00de2b22, 0x00d12920, 0x00d12920, 0x00d12920, 0x00c9281f, 0x00c2271f, 0x00c2271f, 0x00c2271f, 0x00b3241d, 0x00b3241d, 0x00b3241d, 0x00ac231c, 0x00a5221b, 0x00a5221b, 0x00a5221b, 0x009a201a, 0x00a6221b, 0x00c9281f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00a6221b, 0x00781a15, 0x004b1310, 0x001ded, 0x00477, 0x00477, 0x00477, 0x001c1d1d, 0x004d4f4f, 0x007d7f7f, 0x00aeafaf, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x004d4f4f, 0x00477, 0x002f10f, 0x00d62a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00686566, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a4a2a2, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2a2a, 0x00595657, 0x00898787, 0x00b7b5b6, 0x00e6e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00972822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003d1210, 0x002f3131, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00666868, 0x00477, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00312020, 0x00642421, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00b6251d, 0x006f1914, 0x00401210, 0x002710f, 0x002110f, 0x0018ed, 0x0012cb, 0x0012cb, 0x0011cc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x001bed, 0x00731a15, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00db2b22, 0x00ac231c, 0x00801c16, 0x00511411, 0x002510e, 0x00477, 0x00477, 0x00477, 0x00151616, 0x00414343, 0x005b5d5d, 0x00626363, 0x004e5050, 0x001c1d1d, 0x00477, 0x00a99, 0x00731a15, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004a4747, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x004c494a, 0x007c797a, 0x00aaa8a8, 0x00d9d8d9, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00777, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00772522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00731a15, 0x00588, 0x00e0e1e1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aaabab, 0x00477, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009e2822, 0x00712522, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00941f19, 0x0026fe, 0x00477, 0x00699, 0x00303232, 0x00535555, 0x00626363, 0x00626363, 0x00626464, 0x00717373, 0x00717373, 0x00717373, 0x00797b7b, 0x00818383, 0x00818383, 0x00818383, 0x00919292, 0x00919292, 0x00919292, 0x00999a9a, 0x00a1a2a2, 0x00a1a2a2, 0x00a1a2a2, 0x00b0b1b1, 0x00b0b1b1, 0x00b0b1b1, 0x00b7b8b8, 0x00c0c1c1, 0x00c0c1c1, 0x00c0c1c1, 0x00cfcfcf, 0x00d0d0d0, 0x00d0d0d0, 0x00c4c5c5, 0x00979898, 0x00484a4a, 0x00477, 0x0018dc, 0x00ae231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02c22, 0x00b5251d, 0x00851d17, 0x00591512, 0x003711f, 0x001dfe, 0x001aed, 0x002410e, 0x004d1310, 0x00871d17, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22c23, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbb, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00676465, 0x004e4b4c, 0x006f6c6d, 0x009d9b9b, 0x00cccbcb, 0x00f7f7f7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00462221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00577, 0x00656767, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aeafaf, 0x009bb, 0x003111f, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x007f2622, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2820, 0x00351110, 0x00477, 0x002b2d2d, 0x009a9b9b, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9caca, 0x00282a2a, 0x00999, 0x00ab231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008c8a8b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00477, 0x00a2a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00787a7a, 0x00588, 0x003111f, 0x00db2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ae2923, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ad231c, 0x0010bb, 0x00f1110, 0x00989999, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x002a2c2c, 0x0013cb, 0x00db2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x008e2722, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x003611f, 0x00588, 0x007b7d7d, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00a0a1a1, 0x00232524, 0x00477, 0x005a1612, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ce2c23, 0x00d52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00999, 0x00272929, 0x00dadada, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cdcdcd, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00312020, 0x00582321, 0x00802622, 0x00a72923, 0x00cf2c23, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00972822, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00585555, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c42b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x004f1411, 0x00477, 0x001b1c1c, 0x006e7070, 0x00b3b4b4, 0x00cdcdcd, 0x00dadada, 0x00c4c5c5, 0x009fa0a0, 0x005e6060, 0x00161717, 0x00477, 0x002d10f, 0x00b1241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00c12b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2820, 0x0012cb, 0x00252727, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c4e4e, 0x0014cb, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00d52c23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00522221, 0x00762522, 0x00912722, 0x009e2822, 0x00a22823, 0x00912722, 0x00782522, 0x004f2221, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a5a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003f2121, 0x00e12d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x00411310, 0x00577, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x0017dc, 0x00531411, 0x00b1241c, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x009a2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x002c10e, 0x00101111, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b2b3b3, 0x00477, 0x00961f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2b2c, 0x00e9e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00af231c, 0x00971f19, 0x00982019, 0x00ab231c, 0x00c7271f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a32823, 0x00672421, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00531512, 0x00477, 0x00aeafaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00212323, 0x003711f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00676465, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00cc2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00602421, 0x00402121, 0x00e22d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00831c17, 0x00477, 0x007b7d7d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00858686, 0x00477, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003c2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b6b4b5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00812622, 0x00df2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c72b23, 0x006f2521, 0x00281f20, 0x002d2020, 0x00cc2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00688, 0x00484a4a, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e8e8, 0x008aa, 0x00611612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008d2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00383435, 0x00f1f1f1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00373334, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x006a2421, 0x00a72923, 0x00d62c24, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00d82c24, 0x00b32a23, 0x00832622, 0x00452221, 0x00231f20, 0x00231f20, 0x00241f20, 0x00aa2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22920, 0x0016cc, 0x00232525, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00585a5a, 0x00daa, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00dc2d24, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00787576, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00272324, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00666, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00302020, 0x00302020, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007f2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x003211f, 0x00dff, 0x00d0d0d0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bfc0c0, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00888, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00c6c5c5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c7c6c6, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00582321, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005b1612, 0x00477, 0x00a4a6a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x002b2d2d, 0x002c10e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc2a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00191616, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00423f3f, 0x00f7f7f7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006d6b6b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2120, 0x00de2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008b1d18, 0x00477, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00919292, 0x00477, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00442121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001d191a, 0x00161314, 0x00dbc, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00898787, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bfbebe, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00c62b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b7251d, 0x00999, 0x00414343, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00dff, 0x00561511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00545, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00d4d3d3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bfbebe, 0x002c2829, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00777, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72a21, 0x001adc, 0x001d1f1f, 0x00e8e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00636565, 0x00999, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004e4b4c, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00d2d1d2, 0x00726f70, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00141213, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00782522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x003912f, 0x00acc, 0x00c9caca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00477, 0x00801c16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00722522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00999798, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00c4c3c4, 0x00969494, 0x00666464, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00171415, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00522221, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00641713, 0x00477, 0x009c9d9d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00363838, 0x0022fd, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00e1e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfbfc, 0x00d3d2d2, 0x00a5a4a4, 0x00767374, 0x00464344, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x00db2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00951f19, 0x00477, 0x00666868, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009e9f9f, 0x00477, 0x00aa231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c595a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e2e2, 0x00b4b3b3, 0x00848283, 0x00555253, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00c02b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bd261e, 0x00ba9, 0x00393b3b, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00131414, 0x004a1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aaa9a9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00c3c2c2, 0x00949293, 0x00646162, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009a2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00db2b22, 0x0020ed, 0x001a1b1b, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00707272, 0x00688, 0x00d22920, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00989, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312d2e, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00d1d0d1, 0x00a3a1a1, 0x00727070, 0x00454142, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x003f1210, 0x008aa, 0x00c1c2c2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x00477, 0x00751a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00696667, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x00b1b0b0, 0x00838181, 0x00535051, 0x00292526, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c2221, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d1814, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00dcdcdc, 0x00d0d0d0, 0x00d0d0d0, 0x00d0d0d0, 0x00d0d0d0, 0x00dedede, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00424444, 0x0019dc, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ce2c23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b8889, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efeeee, 0x00c1c0c0, 0x00918f90, 0x00625f60, 0x00333031, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332020, 0x00d62c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009e211a, 0x00477, 0x005e6060, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d2d2d2, 0x00646666, 0x00626363, 0x00626363, 0x00525454, 0x00525454, 0x00505252, 0x00424444, 0x00424444, 0x003d3f3f, 0x00323535, 0x00323434, 0x002a2b2b, 0x00222424, 0x00222323, 0x00181919, 0x00171919, 0x00cbcbcb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00444646, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aaabab, 0x00477, 0x009f211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00562321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dcc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00605d5e, 0x00d9d8d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0cfcf, 0x00a09e9f, 0x00716e6f, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00b12a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00daa, 0x00323434, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00252727, 0x00898, 0x0018ed, 0x0021fe, 0x0021fe, 0x002a1110, 0x002f11f, 0x002f11f, 0x003b1311, 0x003e11e, 0x003e11e, 0x004c1310, 0x004c1310, 0x004f1410, 0x0015a9, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989999, 0x00477, 0x00591512, 0x00961f19, 0x00961f19, 0x00a5221b, 0x009f211a, 0x00531411, 0x00477, 0x00dadada, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x001b1c1c, 0x003e1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a22822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x004f4c4d, 0x00838181, 0x009e9c9c, 0x00999798, 0x007e7b7c, 0x00514e4e, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00464344, 0x00767374, 0x00a19fa0, 0x00bfbebe, 0x00c0bfbf, 0x009f9d9e, 0x004c4849, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x0024fe, 0x00151616, 0x00dedede, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004d4f4f, 0x00688, 0x00ad231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009f211a, 0x00477, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cbcbcb, 0x00acc, 0x00391210, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003811f, 0x00181919, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007b7d7d, 0x00477, 0x00ce2920, 0x00ee2e24, 0x00ee2e24, 0x00d82c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003a3738, 0x00696667, 0x00979696, 0x00c6c5c5, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00666464, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004d1411, 0x00699, 0x00babbbb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00838484, 0x00477, 0x007c1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c6271f, 0x00eba, 0x00303232, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00222424, 0x0017dc, 0x00d52a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c1e18, 0x00477, 0x00939494, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cecece, 0x00477, 0x00931f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2a2b, 0x005c595a, 0x008b8889, 0x00b9b8b8, 0x00e9e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e5e5, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009d211a, 0x00477, 0x007f8181, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00588, 0x004b1411, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x0026fe, 0x00141515, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004c4e4e, 0x00688, 0x00b1241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c2271f, 0x00b99, 0x00404242, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00477, 0x00791b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00272324, 0x00504d4d, 0x007e7b7c, 0x00acabab, 0x00dcdbdb, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00413e3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x002610e, 0x00282a2a, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dfdfdf, 0x00151616, 0x0024fe, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00892722, 0x007c2622, 0x00b52a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x004b1411, 0x00588, 0x00b7b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00848585, 0x00477, 0x007d1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x0025fe, 0x00151616, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x00477, 0x007b1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00716e6f, 0x00a09e9f, 0x00cfcece, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2020, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00b2241d, 0x00477, 0x009b9c9c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00343636, 0x00daa, 0x00c4271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b72a23, 0x00251f20, 0x00231f20, 0x00442121, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007a1b16, 0x00477, 0x00848585, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bcbdbd, 0x00699, 0x00481311, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00541512, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcfcf, 0x00477, 0x00961f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1818, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00363233, 0x00646162, 0x00939192, 0x00c2c1c1, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00588, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d62c24, 0x00322020, 0x00231f20, 0x002e2020, 0x00d02c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a9231b, 0x00577, 0x00505252, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00191a1a, 0x0022fd, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00757777, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008d8e8e, 0x00477, 0x00c9281f, 0x00ee2e24, 0x00ee2e24, 0x00d62c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c292a, 0x00575454, 0x00878585, 0x00b5b3b4, 0x00e3e3e3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00692421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1310, 0x00262828, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009b9c9c, 0x00477, 0x00681813, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x004c2221, 0x00231f20, 0x00241f20, 0x00af2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2820, 0x0013cb, 0x00282a2a, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x003c3e3e, 0x00a99, 0x00be261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00baa, 0x003b3d3d, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x002e3030, 0x002910e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a42923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00101, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x004b4748, 0x007a7878, 0x00a8a6a7, 0x00d7d7d7, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00434, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003e11e, 0x003d3f3f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cacaca, 0x00acc, 0x003912f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00652421, 0x006f2522, 0x009a2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x002d10f, 0x00f1010, 0x00d5d5d5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00727474, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0028fe, 0x00151616, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ef, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003e3a3b, 0x006d6b6b, 0x009b999a, 0x00cac9ca, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006c2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004712f, 0x00292b2b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00222424, 0x0019dc, 0x00d62a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00551512, 0x00477, 0x00abacac, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x00591612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00581512, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x001d1f1f, 0x0025fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332f30, 0x00605d5e, 0x008e8c8c, 0x00bebdbd, 0x00ececec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00532321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006e1914, 0x00799, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00616262, 0x00477, 0x00ae231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00861d17, 0x00477, 0x00767878, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dadada, 0x00101111, 0x002d10f, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00921f19, 0x00477, 0x00757777, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00565858, 0x00577, 0x00b3241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00802622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00535051, 0x00828080, 0x00b1b0b0, 0x00dfdedf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00b3241d, 0x00477, 0x009c9d9d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x00477, 0x00651713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b2241d, 0x00788, 0x00454747, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x002f3131, 0x00fba, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00baa, 0x00383a3a, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9b9b, 0x00477, 0x00731a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c595a, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x0022fd, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bebfbf, 0x00477, 0x002f10e, 0x00531411, 0x005b1612, 0x005b1612, 0x00591512, 0x004c1310, 0x004c1310, 0x004c1310, 0x004111f, 0x003e11e, 0x003e12f, 0x00391311, 0x0011bb, 0x00212323, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00606161, 0x00477, 0x00a1211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0028fe, 0x00141515, 0x00dfdfdf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d4d4d4, 0x00cee, 0x003912f, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00592321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00712522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007b1b16, 0x00477, 0x00d4d4d4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00868787, 0x00373939, 0x00222323, 0x00161717, 0x00212121, 0x00222424, 0x00222424, 0x002a2b2b, 0x00323434, 0x00323535, 0x00343737, 0x00424444, 0x00424444, 0x00424444, 0x00cbcbcb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9b9b, 0x00477, 0x006b1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005b1612, 0x00477, 0x00afb0b0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x002e3030, 0x0012cb, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00787677, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00577, 0x00727474, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00acc, 0x00391210, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00961f19, 0x00477, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00686a6a, 0x00477, 0x00a0211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00656, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2a2a, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009f2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00461310, 0x00171818, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00232525, 0x0018dc, 0x00d52a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c7271f, 0x00daa, 0x00383a3a, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x00611713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171414, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00969494, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00502221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a2211b, 0x00477, 0x00abacac, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004d4f4f, 0x00688, 0x00b1241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x002b10e, 0x00141515, 0x00dfdfdf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x00141515, 0x002b10e, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201d1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00474445, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00545, 0x00ecc, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cc2b23, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x0017dc, 0x00494b4b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00868787, 0x00477, 0x007d1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005b1612, 0x00477, 0x00aeafaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003d3f3f, 0x00baa, 0x00c5271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a32823, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b3b2b2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x002c292a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00baa, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x0010ff, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007e2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d1814, 0x00588, 0x00e0e1e1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbebe, 0x00699, 0x00481311, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00961f19, 0x00477, 0x006d6f6f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x008e1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b9b8b8, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00171415, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332020, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00c7281f, 0x00477, 0x00818383, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e4e5e5, 0x00191a1a, 0x0022fe, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00daa, 0x00353737, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bebfbf, 0x00699, 0x004f1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x004a2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00cfcece, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00464243, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00101, 0x00121011, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ab2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003812f, 0x00212323, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x003d3f3f, 0x00a99, 0x00be261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x002d10f, 0x00121313, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x001d1e1e, 0x001fed, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00706d6e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x005d5a5b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00477, 0x00babbbb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00727474, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005f1713, 0x00477, 0x00acadad, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004d4f4f, 0x00788, 0x00b8251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b22a23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00e4e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00aaa8a8, 0x003a3738, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x00fbb, 0x00585a5a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x00581512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a201a, 0x00477, 0x006d6f6f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00909191, 0x00477, 0x007c1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2d24, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008c8a8b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c2c1c1, 0x00939192, 0x00615e5f, 0x002c2829, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00211e1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008a2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e1612, 0x00acc, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dadada, 0x00101111, 0x002c10e, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00eba, 0x00353737, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cecece, 0x00acc, 0x003f1310, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00572321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00383435, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0cfcf, 0x00a2a0a1, 0x00726f70, 0x00434040, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2120, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ba251e, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x002f3131, 0x00fba, 0x00ca2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x002e10f, 0x00101111, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00272929, 0x0016cc, 0x00d62a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aaa8a8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dedede, 0x00b0aeaf, 0x007f7d7e, 0x00524e4f, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00271f20, 0x00432121, 0x00602421, 0x006f2522, 0x006f2522, 0x006f2522, 0x00632421, 0x005a2321, 0x00502221, 0x00452221, 0x003b2120, 0x00302020, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a10e, 0x002f3131, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00606161, 0x00477, 0x00a0211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00781a15, 0x00477, 0x00a5a6a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00606161, 0x00477, 0x00a8221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c02b23, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00423f3f, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ececec, 0x00bdbcbd, 0x008e8c8c, 0x005f5c5d, 0x00312d2e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x006e2521, 0x00af2923, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00477, 0x00c9caca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9b9b, 0x00477, 0x006a1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x00daa, 0x004c4e4e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a3a5a5, 0x00477, 0x00691814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x003b2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a3a1a1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cccbcb, 0x009c9a9a, 0x006d6b6b, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00712522, 0x00db2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00db2b22, 0x00999, 0x00666868, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00acc, 0x003912f, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00c6c7c7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x00101111, 0x003011f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00652421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00dad9d9, 0x00aaa8a8, 0x007c797a, 0x004c494a, 0x00262323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00b12923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004f1411, 0x00111212, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00232525, 0x0018dc, 0x00d42a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1411, 0x001e2020, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00353737, 0x00eba, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00555, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171415, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004b4748, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e7e7, 0x00b8b7b7, 0x008a8888, 0x005a5758, 0x002e2a2b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2020, 0x00c32b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x009e211a, 0x005c1612, 0x00341110, 0x0017dc, 0x0012cb, 0x0018ed, 0x002410f, 0x003011f, 0x003e12f, 0x004a1310, 0x00561511, 0x00621713, 0x006e1914, 0x00791b16, 0x00871d17, 0x00931f19, 0x009f211a, 0x00701914, 0x00477, 0x00a0a1a1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004d4f4f, 0x00688, 0x00b0241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a11f, 0x004e5050, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00747676, 0x00477, 0x00971f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00d82c24, 0x00cd2c23, 0x00c32b23, 0x00b92a23, 0x00ae2923, 0x00a22823, 0x00962822, 0x00812622, 0x005e2321, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00656363, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00c6c5c5, 0x00979696, 0x00696667, 0x00393637, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00af2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x008f1e18, 0x001add, 0x00477, 0x00e1010, 0x00424444, 0x005e6060, 0x00626363, 0x00626363, 0x00545656, 0x00474949, 0x003b3d3d, 0x002e3030, 0x00212222, 0x00131414, 0x00588, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x003e4040, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00868787, 0x00477, 0x00631713, 0x00da2b21, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002710f, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b6b7b7, 0x00477, 0x00571512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00b32a23, 0x005c2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00625f60, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00d4d3d3, 0x00a6a5a5, 0x00777475, 0x00474445, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322e2f, 0x005f5c5d, 0x008b8889, 0x00a7a5a6, 0x00a5a4a4, 0x007c797a, 0x002d2a2a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006a2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x004f1411, 0x00477, 0x00363838, 0x00b0b1b1, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00e8e9e9, 0x00dcdcdc, 0x00d0d0d0, 0x00c0c1c1, 0x00b3b4b4, 0x00a6a7a7, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbebe, 0x00699, 0x00477, 0x00477, 0x00477, 0x00477, 0x00688, 0x0012cb, 0x0021fe, 0x002d1110, 0x00391210, 0x004312f, 0x0013a9, 0x00202222, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x00191a1a, 0x0024fe, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b52a23, 0x00362020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00363233, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e2e2, 0x00b4b3b3, 0x00848283, 0x00565354, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00535051, 0x00817f7f, 0x00b0afaf, 0x00dfdedf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e6e7, 0x00403d3e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e1613, 0x00477, 0x00757777, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d3d3d3, 0x00b6b7b7, 0x00a9aaaa, 0x009d9e9e, 0x00919292, 0x00818383, 0x00747676, 0x00676969, 0x005b5d5d, 0x004e5050, 0x00424444, 0x00323535, 0x00252626, 0x00191b1b, 0x00c1c2c2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x002e3131, 0x00477, 0x0019dc, 0x00341210, 0x004011e, 0x004c1310, 0x005a1512, 0x00661713, 0x00721915, 0x007e1b16, 0x008a1d18, 0x00961f19, 0x00a5221b, 0x00b1241c, 0x00bc261e, 0x00c8281f, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00baa, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009b999a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c2c1c1, 0x00939192, 0x00646162, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00464243, 0x00747272, 0x00a4a2a2, 0x00d2d1d2, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c3c2c2, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b4241d, 0x00477, 0x00676969, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x006b6d6d, 0x005f6060, 0x00525454, 0x00424444, 0x00353838, 0x00282a2a, 0x001c1d1d, 0x00101111, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00eba, 0x003d1210, 0x008a1d18, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00828080, 0x00d9d8d9, 0x00f8f8f8, 0x00f1f1f1, 0x00d0cfcf, 0x00a2a0a1, 0x00726f70, 0x00434040, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00393536, 0x00686566, 0x00979595, 0x00c4c3c4, 0x00f3f3f3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00312d2e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008e2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00511511, 0x00111212, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00e2e3e3, 0x00d6d6d6, 0x00c9caca, 0x00bcbdbd, 0x00afb0b0, 0x00a1a2a2, 0x008b8c8c, 0x006a6c6c, 0x00272929, 0x00477, 0x0019dc, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00992822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2a2b, 0x005b5859, 0x008a8888, 0x00b8b7b7, 0x00e8e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00494646, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b42a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0012cb, 0x005e6060, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00222424, 0x00daa, 0x00c8281f, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x004e4b4c, 0x007d7a7b, 0x00abaaaa, 0x00dbdada, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00d62a21, 0x00477, 0x008b8c8c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dfdfdf, 0x00cee, 0x004b1311, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00423f3f, 0x00706d6e, 0x009e9d9d, 0x00cecdcd, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d52c24, 0x00ee2e24, 0x00ee2e24, 0x00d12920, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00656767, 0x00999, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00942722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00636061, 0x00929091, 0x00c1c0c0, 0x00efeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cc2b23, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00577, 0x007b7d7d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00909191, 0x00477, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00a22823, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00565354, 0x00858384, 0x00b4b3b3, 0x00e3e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ae2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002810f, 0x003f4141, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008d8e8e, 0x00477, 0x00d72a21, 0x00ee2e24, 0x00ee2e24, 0x00a22823, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00494646, 0x00787677, 0x00a7a5a6, 0x00d6d5d5, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00882622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00701914, 0x00588, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00fba, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00211e1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c3839, 0x006c6a6a, 0x009a9899, 0x00c9c8c8, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00492221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c2271f, 0x00477, 0x008b8c8c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00252727, 0x00411310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f2521, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00504d4d, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d22c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002e10f, 0x002c2e2e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dfdfdf, 0x00477, 0x00801c16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cbcacb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00851d17, 0x00477, 0x00cacaca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009b9c9c, 0x00477, 0x00bf261e, 0x00ee2e24, 0x00ee2e24, 0x00d62c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006b6969, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92a21, 0x00898, 0x006b6d6d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x0015cc, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x009f2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00e3e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004b1311, 0x00151616, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00151616, 0x00521411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbb, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a3211b, 0x00477, 0x00acadad, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cbcbcb, 0x00477, 0x00911f19, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x0015cc, 0x004e5050, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00878888, 0x00477, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00c62b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a4a3a3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00661713, 0x00799, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00434545, 0x0024fe, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00484546, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00562321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00be261e, 0x00477, 0x008d8e8e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00acc, 0x00641713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00582321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c1c0c0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0025fd, 0x002e3030, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00477, 0x00a3211b, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00656, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00605d5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008e1e18, 0x00477, 0x00444646, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00747676, 0x00688, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00b72a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171415, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00dad9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00962822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008e1e18, 0x00477, 0x00444646, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00303232, 0x003711f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00802622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ff, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007e7b7c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00972822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00851d17, 0x00477, 0x00444646, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e9e9, 0x00477, 0x00761a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00492221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302c2d, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00801c16, 0x00477, 0x00444646, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a4a6a6, 0x00477, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00999798, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00bfbebe, 0x00908e8e, 0x00838181, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00801c16, 0x00477, 0x004f5151, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626363, 0x00eba, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00a72923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00777, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cccbcb, 0x009d9b9b, 0x006e6b6c, 0x003f3c3d, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dbc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007b2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00801c16, 0x00477, 0x00505252, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00151616, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00702522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a5a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00d9d8d9, 0x00a9a7a8, 0x007b7979, 0x004c494a, 0x00262323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00632421, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00831c17, 0x00477, 0x00505252, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x009e211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c292a, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e5e5, 0x00b7b5b6, 0x00888686, 0x00595657, 0x002c292a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00477, 0x004b4d4d, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00292b2b, 0x0022fd, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00c32b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00615e5f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00c3c2c3, 0x00959393, 0x00656363, 0x00383435, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2020, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ad231c, 0x00788, 0x003d3f3f, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x007c7e7e, 0x00898a8a, 0x00969797, 0x00a2a4a4, 0x00b0b1b1, 0x00bfc0c0, 0x00cccccc, 0x00d9d9d9, 0x00e5e6e6, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00646666, 0x00477, 0x00a0211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00742522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151313, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c797a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0d0d0, 0x00a2a0a1, 0x00727070, 0x00444041, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009b2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2820, 0x0011bb, 0x00282a2a, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00262827, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00131414, 0x00202121, 0x002d2f2f, 0x003a3c3c, 0x00474949, 0x00545656, 0x00626363, 0x00707272, 0x007d7f7f, 0x008a8b8b, 0x00979898, 0x00a3a5a5, 0x00b0b1b1, 0x00c0c1c1, 0x00cdcdcd, 0x00dadada, 0x00e7e8e8, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00616262, 0x00477, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72c24, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00676465, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dddddd, 0x00afadae, 0x007f7d7e, 0x00514e4e, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00512221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x002e10e, 0x00f1010, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x002f3131, 0x00ba9, 0x00b0241c, 0x00df2c22, 0x00d22920, 0x00c6271f, 0x00ba251e, 0x00ae231c, 0x00a2211b, 0x00961f19, 0x00871d17, 0x007b1b16, 0x006f1914, 0x00631713, 0x00571511, 0x004b1310, 0x003e11f, 0x003011f, 0x002410f, 0x0018ed, 0x00caa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00588, 0x00131414, 0x00212222, 0x002e3030, 0x003b3d3d, 0x00484a4a, 0x00555757, 0x00626363, 0x00717373, 0x007e8080, 0x008b8c8c, 0x00989999, 0x00a4a6a6, 0x00b2b3b3, 0x00c0c1c1, 0x00cfcfcf, 0x00dcdcdc, 0x00e8e9e9, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00989999, 0x00202222, 0x00477, 0x00681813, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00682421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaeaea, 0x00bbbaba, 0x008c8a8b, 0x005f5c5c, 0x00302c2d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00721915, 0x00477, 0x00a7a8a8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00393b3b, 0x00688, 0x00a6221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00df2c22, 0x00d12920, 0x00c5271f, 0x00b9251d, 0x00ad231c, 0x00a1211a, 0x00951f19, 0x00871d17, 0x00791b16, 0x006e1914, 0x00621713, 0x00561511, 0x004a1310, 0x003e12f, 0x002f11f, 0x002310e, 0x0018dd, 0x00baa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00699, 0x00131414, 0x00222323, 0x002f3131, 0x003c3e3e, 0x00494b4b, 0x00525454, 0x004b4d4d, 0x00292b2b, 0x00699, 0x00477, 0x002c10f, 0x00ad231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a52923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00524e4f, 0x00e5e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00c8c7c7, 0x00999798, 0x006b6969, 0x003b3838, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abaaaa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005e2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c7271f, 0x00788, 0x00545656, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00444646, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x00de2b22, 0x00d12920, 0x00c4271f, 0x00b8251d, 0x00ab231c, 0x009f211a, 0x00931f19, 0x00871d17, 0x00791a15, 0x006d1814, 0x00611612, 0x00551411, 0x00491210, 0x003d12f, 0x002f11f, 0x002f1311, 0x002f11f, 0x00471310, 0x00721915, 0x00b9251d, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ba2a23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x006b6969, 0x00999798, 0x009f9d9e, 0x00989697, 0x00777475, 0x00484546, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b52a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1411, 0x00cee, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00505252, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a92923, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171414, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201d1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00959393, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00352020, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2820, 0x00477, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x005e6060, 0x00477, 0x007c1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00812622, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2020, 0x00392120, 0x00442121, 0x004e2221, 0x00582321, 0x00632421, 0x006f2522, 0x007a2522, 0x00842622, 0x008e2722, 0x00992822, 0x00a32823, 0x00af2923, 0x00ba2a23, 0x00c52b23, 0x00cf2c23, 0x00d92c24, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00712522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a9a7a8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbbbc, 0x00262323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a89, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2521, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791b16, 0x00477, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006c6e6e, 0x00477, 0x006d1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008e2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00392120, 0x00442121, 0x004f2221, 0x00592321, 0x00632421, 0x006f2522, 0x007b2522, 0x00852622, 0x008f2722, 0x009a2822, 0x00a42923, 0x00af2923, 0x00bb2a23, 0x00c52b23, 0x00d02c23, 0x00da2d24, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x007f2622, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00ececec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b2b1b1, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009b2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003511f, 0x00343636, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007d7f7f, 0x00477, 0x005e1613, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009b2822, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302020, 0x003a2120, 0x00442121, 0x004f2221, 0x005a2321, 0x00642421, 0x006f2522, 0x007b2622, 0x00862622, 0x00902722, 0x009a2822, 0x00a22823, 0x009a2822, 0x00892722, 0x006b2421, 0x003d2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00464344, 0x00d7d7d7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e6e6, 0x00767374, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bd2a23, 0x00ee2e24, 0x00ee2e24, 0x00e92d23, 0x00a99, 0x006d6f6f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008d8e8e, 0x00477, 0x00511512, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a72923, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x006b6869, 0x00acabab, 0x00c5c4c4, 0x00c3c2c2, 0x00a4a3a3, 0x00676465, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00d82a21, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009d9e9e, 0x00477, 0x00441310, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001a1717, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00555, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d52c24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aaabab, 0x00699, 0x00391210, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc2a23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00577, 0x00757777, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00babbbb, 0x009bb, 0x002e10f, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312d2e, 0x003a3738, 0x00272324, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b02923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003411f, 0x00323434, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d3d3d3, 0x00f1111, 0x0023fd, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac2923, 0x00912722, 0x00872622, 0x007c2622, 0x006f2522, 0x00652421, 0x005b2321, 0x00502221, 0x00462221, 0x003c2120, 0x00302020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00fde, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00333031, 0x00625f60, 0x00918f8f, 0x00c0bfbf, 0x00eeedee, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00acabab, 0x00302c2d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00812622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007b1b16, 0x00477, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x002a2c2c, 0x0014cb, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d24, 0x00dc2d24, 0x00d12c23, 0x00c72b23, 0x00bc2a23, 0x00b02923, 0x00a62923, 0x009b2822, 0x00912722, 0x00872622, 0x007c2622, 0x006f2522, 0x00652421, 0x005b2321, 0x00512221, 0x00472221, 0x003c2121, 0x00302020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00edd, 0x00151313, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00555253, 0x00848182, 0x00b2b1b1, 0x00e1e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c6c5c5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a7a7, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00dc2d24, 0x00d22c23, 0x00c82b23, 0x00bc2a23, 0x00b12923, 0x00a62923, 0x009c2822, 0x00922722, 0x00872622, 0x007c2622, 0x00702522, 0x00662421, 0x005c2321, 0x00512221, 0x00472221, 0x003c2121, 0x00302020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00191616, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00484546, 0x00777475, 0x00a5a4a4, 0x00d4d3d3, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00535051, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cb2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002d10f, 0x00353737, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a3a5a5, 0x00477, 0x003b12f, 0x00711915, 0x008c1e18, 0x009e211a, 0x00ab231c, 0x00b7251d, 0x00c3271f, 0x00d12920, 0x00dd2b22, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00dc2d24, 0x00d22c23, 0x00c92b23, 0x00bc2a23, 0x00b12a23, 0x00a72923, 0x009d2822, 0x008e2722, 0x00752522, 0x004b2221, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00111010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003a3738, 0x006a6768, 0x00989697, 0x00c7c6c6, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00858384, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171414, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007b1b16, 0x00477, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00878888, 0x002b2d2d, 0x00699, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00b99, 0x0017dc, 0x0023fe, 0x002f11f, 0x003c12f, 0x004812f, 0x00541411, 0x00601612, 0x006c1814, 0x00791a15, 0x00861d17, 0x00921f19, 0x009e211a, 0x00aa231c, 0x00b6251d, 0x00c2271f, 0x00d12920, 0x00dd2b22, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22c23, 0x00762522, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2b2c, 0x005d5a5b, 0x008b898a, 0x00bab9b9, 0x00e9e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00e1e2e2, 0x00cecece, 0x00c0c1c1, 0x00b2b3b3, 0x00a5a6a6, 0x00999a9a, 0x008c8d8d, 0x007f8181, 0x00717373, 0x00626464, 0x00565858, 0x00494b4b, 0x003c3e3e, 0x002f3131, 0x00222323, 0x00131414, 0x00699, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00a99, 0x0016dc, 0x0022fe, 0x002f11f, 0x003c12f, 0x004812f, 0x00541411, 0x00601612, 0x006c1814, 0x00791a15, 0x00861d17, 0x00921f19, 0x009e211a, 0x00a9231b, 0x00b5251d, 0x00c2271f, 0x00d02920, 0x00dc2b22, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c42b23, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00272324, 0x00504d4d, 0x007e7c7d, 0x00adacac, 0x00dcdcdc, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cb2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002d10f, 0x00353737, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00e8e9e9, 0x00dcdcdc, 0x00cfcfcf, 0x00c0c1c1, 0x00b2b3b3, 0x00a5a6a6, 0x009a9b9b, 0x008d8e8e, 0x00808282, 0x00717373, 0x00636565, 0x00575959, 0x004a4c4c, 0x003d3f3f, 0x00303232, 0x00222323, 0x00141515, 0x00799, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00999, 0x0015dc, 0x0021fe, 0x002f1110, 0x003b12f, 0x004712f, 0x00531411, 0x005f1612, 0x006b1814, 0x00791a15, 0x00851d17, 0x00911f19, 0x009d211a, 0x00a9231b, 0x00b5251d, 0x00c2271f, 0x00d02920, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d52c23, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00726f70, 0x00a09e9f, 0x00d0cfcf, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791b16, 0x00477, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00e9eaea, 0x00dddddd, 0x00d0d0d0, 0x00c0c1c1, 0x00b3b4b4, 0x00a6a7a7, 0x009a9b9b, 0x008d8e8e, 0x00818383, 0x00717373, 0x00646666, 0x00585a5a, 0x004b4d4d, 0x003e4040, 0x00313333, 0x00222323, 0x00151616, 0x008aa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x0023fe, 0x00741a15, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bd2a23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00363233, 0x00646162, 0x00949293, 0x00c2c1c1, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00eaebeb, 0x00dedede, 0x00d0d0d0, 0x00c1c2c2, 0x00b4b5b5, 0x00a7a8a8, 0x009b9c9c, 0x00818383, 0x00454747, 0x00477, 0x001ced, 0x00c5271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c292a, 0x00575454, 0x00878585, 0x00b5b3b4, 0x00e3e3e3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cb2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0028fe, 0x00353737, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c3c4c4, 0x00181919, 0x001ded, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00c42b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1818, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x004a4747, 0x00797777, 0x00a8a6a7, 0x00d6d6d6, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00761a15, 0x00477, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b7b8b8, 0x00477, 0x007f1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x006c6a6a, 0x009b999a, 0x00cac9c9, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00303232, 0x00391210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00545152, 0x00acabab, 0x00e9e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002810e, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00636565, 0x0014cc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007a2522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302c2d, 0x00b4b3b3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00761a15, 0x00477, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x0013cc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00d0cfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00424444, 0x002f11f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00732522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00918f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002810e, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eceded, 0x00acc, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9899, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00761a15, 0x00477, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00808282, 0x00477, 0x00ba251e, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181616, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00555253, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008a8888, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d8d8d8, 0x00bdd, 0x00471411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a82923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f6c6d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00615e5f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151313, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002810e, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00303232, 0x00fba, 0x00d02920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00512221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeedee, 0x002a2627, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00477, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x004d4f4f, 0x00477, 0x00a2211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b22a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007e7c7d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00626363, 0x00477, 0x007f1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x003c2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a5a4a4, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0023fe, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00757777, 0x00477, 0x006a1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e6e7, 0x00777475, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008e2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00588, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008e8f8f, 0x00477, 0x00561511, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00902722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00c7c6c6, 0x00979696, 0x005f5c5c, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x00477, 0x00949595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a1a3a3, 0x00477, 0x00451310, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a72923, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00d5d4d4, 0x00a6a5a5, 0x00777475, 0x00484546, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0023fe, 0x003f4141, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b5b6b6, 0x00799, 0x003611f, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b52a23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e2e1e1, 0x00b4b3b3, 0x00848283, 0x00565354, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00588, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x00dff, 0x002910e, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c32b23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00c2c1c1, 0x00929091, 0x00646162, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x00477, 0x00949595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d3d3d3, 0x00141515, 0x001ded, 0x00d42a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ce2c23, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00d0cfcf, 0x00a09e9f, 0x00716e6f, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0023fe, 0x003f4141, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x001e2020, 0x0015cc, 0x00c7281f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x003a2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dcdcdc, 0x00aeacad, 0x007e7c7d, 0x00514e4e, 0x00272324, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1a1b, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00741a15, 0x00477, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00292b2b, 0x00caa, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02d24, 0x00442121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009e9c9c, 0x00302c2d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004b2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00a99, 0x004d4f4f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00373939, 0x00999, 0x00ab231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00502221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00706d6e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d9d8d9, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c82b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007d1b16, 0x00477, 0x00838484, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00474949, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x005d2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00565354, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aaa8a8, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00672421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00501411, 0x00477, 0x00717373, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00595b5b, 0x00477, 0x00861d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00e9e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006f6c6d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dbc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00ba2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x005f1713, 0x00477, 0x002b2d2d, 0x00acadad, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006e7070, 0x00477, 0x00721915, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007d2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00636061, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeedee, 0x00c0bfbf, 0x00939192, 0x00646162, 0x00383435, 0x00bbbaba, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x00dc2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a0211a, 0x0020fe, 0x00477, 0x001a1b1b, 0x005c5e5e, 0x00858686, 0x009fa0a0, 0x00abacac, 0x00b8b9b9, 0x00c6c7c7, 0x00d3d3d3, 0x00e0e0e0, 0x00efefef, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00838484, 0x00477, 0x005e1613, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00baa, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00656, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004a4747, 0x00a19fa0, 0x00bebdbd, 0x00bab9b9, 0x00989697, 0x006c6a6a, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004d4a4b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x002a2627, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92d23, 0x009e211a, 0x004f1411, 0x0016dc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00eff, 0x001a1b1b, 0x00272828, 0x00343737, 0x00424444, 0x00525454, 0x005f6060, 0x006b6d6d, 0x00787a7a, 0x00858686, 0x00939494, 0x00a1a2a2, 0x00afb0b0, 0x00bcbdbd, 0x00c9caca, 0x00d7d7d7, 0x00e3e4e4, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9b9b, 0x00477, 0x004c1411, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x004f4c4d, 0x00787677, 0x00848182, 0x00585555, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00cc2820, 0x00c0261e, 0x00b3241d, 0x00a6221b, 0x00992019, 0x008d1e18, 0x00811c16, 0x00751a15, 0x00681813, 0x005b1612, 0x004d1310, 0x004111f, 0x00361210, 0x002911f, 0x001dfe, 0x0011cb, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00111212, 0x001e1f1f, 0x002b2d2c, 0x00383b3b, 0x00454747, 0x00535555, 0x00626363, 0x006f7171, 0x007c7e7e, 0x00898a8a, 0x00979898, 0x00a3a5a5, 0x00b0b1b1, 0x00c0c1c1, 0x00cdcdcd, 0x00dbdbdb, 0x00e7e8e8, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00699, 0x003c1210, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00af2923, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006f6c6d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00413e3f, 0x006f6c6d, 0x009e9d9d, 0x00cdcccc, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0aeaf, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00992822, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00d42a21, 0x00c8281f, 0x00bc261e, 0x00b1241c, 0x00a5221b, 0x00961f19, 0x00891d17, 0x007d1b16, 0x00711915, 0x00651713, 0x00581511, 0x004c1310, 0x003e11f, 0x003211f, 0x002610f, 0x0019ed, 0x00daa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00588, 0x00131414, 0x00222323, 0x002f3131, 0x003c3e3e, 0x009bb, 0x002d10e, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00be2a23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00333031, 0x00615e5f, 0x00918f8f, 0x00bfbebe, 0x00eeedee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00737171, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00442121, 0x00a42923, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00df2c22, 0x00d22920, 0x00c5271f, 0x00b9251d, 0x00ad231c, 0x00a1211a, 0x00951f19, 0x00871d17, 0x00791b16, 0x006e1914, 0x00621713, 0x00561511, 0x00491210, 0x003d12f, 0x003d12f, 0x00d72a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2b23, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x002a2627, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00535051, 0x00838181, 0x00b2b1b1, 0x00e0dfe0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bbbaba, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x006c2421, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00d92a21, 0x00c1271e, 0x00b3241d, 0x00a9231b, 0x00c7271f, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00252122, 0x00464243, 0x00757273, 0x00a4a3a3, 0x00d2d1d2, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d5d5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d2121, 0x00c02b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00cb2820, 0x00b4241d, 0x009c201a, 0x00821c17, 0x006a1814, 0x00521411, 0x003811f, 0x0020fe, 0x00999, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x001eed, 0x008e1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2d24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccbcb, 0x00f3f3f3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d1d0d1, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00622421, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00b6251d, 0x00731a15, 0x00491310, 0x002b11f, 0x0013cc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x009bb, 0x00222423, 0x003c3e3e, 0x00595b5b, 0x00727474, 0x008c8d8d, 0x00a7a8a8, 0x00bebfbf, 0x00bebfbf, 0x009b9c9c, 0x00353737, 0x00477, 0x00841c17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a82923, 0x00562321, 0x00622421, 0x006c2421, 0x00772522, 0x00822622, 0x008c2722, 0x00962822, 0x00a22823, 0x00ae2923, 0x00b92a23, 0x00c32b23, 0x00ce2c23, 0x00d92c24, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32d24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1a1b, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00323, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b5b3b4, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00762522, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00941f19, 0x0026fe, 0x00477, 0x00699, 0x00282a2a, 0x004b4d4d, 0x00666868, 0x00808282, 0x009a9b9b, 0x00b6b7b7, 0x00d0d0d0, 0x00e8e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00474949, 0x00caa, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00cc2b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2020, 0x00392120, 0x00442121, 0x004e2221, 0x00582321, 0x00632421, 0x006f2522, 0x007b2522, 0x00852622, 0x00902722, 0x009a2822, 0x00a52923, 0x00582321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x0011f10, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00838181, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00662421, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2820, 0x003511f, 0x00477, 0x002c2e2e, 0x00999a9a, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbebe, 0x00477, 0x00a3211b, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x0010bb, 0x00f1110, 0x00979898, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e9eaea, 0x00477, 0x00871d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c1c0c0, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa231c, 0x00999, 0x00292b2b, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00477, 0x00891d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00595657, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00852622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2820, 0x0011bb, 0x00272929, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cacaca, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00352020, 0x00592321, 0x00672421, 0x006d2421, 0x00562321, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00a3a1a1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9c8c8, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x003712f, 0x00f1110, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0b1b1, 0x00477, 0x00b7251d, 0x00ee2e24, 0x00ee2e24, 0x00d82c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x008a2722, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00c12b23, 0x006f2522, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00252122, 0x00c7c6c6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00585556, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00831c17, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00979898, 0x00477, 0x00cf2920, 0x00ee2e24, 0x00ee2e24, 0x00c22b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00922722, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2b23, 0x00492221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x003a3738, 0x00231f20, 0x00393637, 0x00efeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c2c1c1, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00802622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00b99, 0x00434545, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007a7c7c, 0x00477, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ac2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004e2221, 0x00d62c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00612421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00666464, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00535051, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003711f, 0x00f1010, 0x00dfdfdf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00616262, 0x0017dc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00972822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00692421, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x00941f19, 0x005f1612, 0x004111f, 0x004112f, 0x00611612, 0x00a8221b, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00592321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a3a1a1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bcbabb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00555, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00871d17, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00474949, 0x002e11f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00822622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006b2421, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00721915, 0x00eba, 0x00477, 0x00111212, 0x00333636, 0x00373939, 0x00e10f, 0x00477, 0x002d10f, 0x00c3271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2d24, 0x00322020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c3c2c3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009c9a9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00d8d7d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004d4a4b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00802622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2820, 0x00caa, 0x00434545, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x002b2d2d, 0x004712f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00be261e, 0x0023fe, 0x00477, 0x00515353, 0x00bfc0c0, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x009c9d9d, 0x00171818, 0x00caa, 0x00b6251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00474445, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b7b6b6, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003b1210, 0x00dff, 0x00dcdcdc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00111212, 0x00621713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00572321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322020, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00af231c, 0x00caa, 0x00181919, 0x00b6b7b7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x00202222, 0x0019dc, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c9c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c797a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00474445, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c12b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00871d17, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00477, 0x00791b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00412121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a62923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x00caa, 0x00262828, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bebfbf, 0x00477, 0x00811c16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b3b2b2, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2820, 0x00caa, 0x003f4141, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d8d8d8, 0x00477, 0x00911f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a2020, 0x00231f20, 0x00231f20, 0x005f2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x001fed, 0x001c1d1d, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x002d2f2f, 0x003b12f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007d2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c9c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00918f90, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332f30, 0x00e7e6e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003b12f, 0x00dff, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbebe, 0x00477, 0x00ab231c, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x00231f20, 0x00231f20, 0x00302020, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005c1612, 0x00477, 0x00bebfbf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005e6060, 0x0018dd, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x00312d2e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00585556, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00adacac, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00be2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00881d17, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a3a5a5, 0x00477, 0x00c4271f, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00231f20, 0x00231f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ae231c, 0x00477, 0x006c6e6e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626363, 0x0015dc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00932722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00989, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c9c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008f8d8d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00939192, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d02920, 0x00eba, 0x003f4141, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00898a8a, 0x00477, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00b62a23, 0x00231f20, 0x005b2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x001fed, 0x00202222, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00434545, 0x002e11f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00852622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191616, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efeeee, 0x002d2a2a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00cdcccc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003f1310, 0x00dff, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006d6f6f, 0x00b99, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x002e2020, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00641713, 0x00477, 0x00babbbb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00e1010, 0x005c1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c9c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00888686, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003e3a3b, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00be2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c1e18, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00545656, 0x002310e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c2722, 0x009e2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b2241d, 0x00477, 0x00636565, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x00a2211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaeaea, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00696667, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c2c1c1, 0x00929091, 0x00636061, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d02920, 0x00eba, 0x003a3c3c, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00393c3c, 0x003b11f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x0023fe, 0x001d1f1f, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003a3c3c, 0x001adc, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00c62b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c3c2c3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00828080, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0d0d0, 0x00a2a0a1, 0x00726f70, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d2121, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003f1210, 0x00bdd, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x001d1e1e, 0x00541411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a1814, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a7a8a8, 0x00477, 0x00841c17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007e2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e6e6, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00aeacad, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x00b1b0b0, 0x00817f7f, 0x00524f50, 0x00292526, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c1e18, 0x00477, 0x008c8d8d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00799, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b8251d, 0x00577, 0x005d5f5f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eceded, 0x001b1c1c, 0x002a10e, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00787677, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c797a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x004b4748, 0x005a5758, 0x00524e4f, 0x00322e2f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ff, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00782522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00eba, 0x003a3c3c, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00c1c2c2, 0x00a6a7a7, 0x008a8b8b, 0x006f7171, 0x00555757, 0x003a3c3c, 0x00323535, 0x00646666, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e6e6, 0x00477, 0x00861d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x002810e, 0x001a1b1b, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005d5f5f, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00852622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009c9a9a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e1e0e0, 0x00262323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d2121, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00431310, 0x00bdd, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x00477, 0x00477, 0x00a99, 0x002310f, 0x003b12f, 0x004612f, 0x00477, 0x00868787, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9caca, 0x00477, 0x009e211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006e1914, 0x00477, 0x00abacac, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0b1b1, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a6a5a5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00767374, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00911f19, 0x00477, 0x008c8d8d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00799, 0x00491310, 0x00c1271e, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dba, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c6c7c7, 0x00477, 0x008b1d18, 0x00c6271f, 0x00ad231c, 0x00961f19, 0x007f1b16, 0x00641713, 0x00788, 0x00575959, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eceded, 0x001b1c1c, 0x002810e, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00979595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x001a1717, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00652421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x0010bb, 0x00383a3a, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x002e3030, 0x0015cb, 0x00d82a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x00477, 0x00838484, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x00191a1a, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00bdd, 0x002b2d2d, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005b5d5d, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00686566, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x004d4a4b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00222, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00461311, 0x00acc, 0x00d4d4d4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00477, 0x009d9e9e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e8e8, 0x00a3a5a5, 0x00a4a6a6, 0x00babbbb, 0x00d6d6d6, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00e4e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x005c595a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00000, 0x00000, 0x00544, 0x001e1b1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001b1819, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00632421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a8221b, 0x00477, 0x00818383, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00799, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32d24, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00b0241c, 0x00477, 0x00b8b9b9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x002810e, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00555253, 0x00f3f3f3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c0bfbf, 0x00413e3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00171516, 0x0010ef, 0x00988, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b12a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003311f, 0x00202222, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x002e3030, 0x0015cb, 0x00d82a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00742522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00982019, 0x00477, 0x00d3d3d3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003f3b3c, 0x00a09e9f, 0x00d7d7d7, 0x00ececec, 0x00e8e7e7, 0x00d1d0d1, 0x009e9d9d, 0x004f4c4d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001a1717, 0x00131111, 0x00baa, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00e92e24, 0x00ee2e24, 0x00ee2e24, 0x00bb251e, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b32a23, 0x003c2121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f1b16, 0x00477, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00171414, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001c191a, 0x00151313, 0x00ecc, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00562321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f1914, 0x00699, 0x00e9eaea, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00799, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00382120, 0x00512221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00641713, 0x00bdd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x002810e, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x0011ff, 0x001b1819, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00171515, 0x0010ef, 0x00888, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007b2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003d12f, 0x00313333, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x002e3030, 0x0015cb, 0x00d82a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f2522, 0x00231f20, 0x00682421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1310, 0x00272929, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00877, 0x00dbc, 0x0010ee, 0x0011f10, 0x0011ef, 0x00ecd, 0x00988, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00892722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0021fe, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b32a23, 0x00231f20, 0x00231f20, 0x007d2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003511f, 0x00414343, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008c2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x001cee, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c7c8c8, 0x00799, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00382120, 0x00231f20, 0x00231f20, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x001aed, 0x005b5d5d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x0028fe, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007a2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003b1210, 0x00313333, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e6e6, 0x00202222, 0x001bed, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f2522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a82923, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x00688, 0x00777979, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00572321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f1b16, 0x00477, 0x00c3c4c4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e2e3e3, 0x002d2f2f, 0x00a99, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b32a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bd2a23, 0x00ee2e24, 0x00ee2e24, 0x00d52a21, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x001add, 0x00202222, 0x00dadada, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00babbbb, 0x001b1c1c, 0x00baa, 0x00a6221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d22c23, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x00477, 0x00aaabab, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x0028fe, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00151314, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x0011bb, 0x00f1010, 0x007f8181, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00b3b4b4, 0x004a4c4c, 0x00477, 0x001fed, 0x00ba251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x005b2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00a2211b, 0x00477, 0x00c7c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00788, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00161414, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00151313, 0x00555, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00342020, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2820, 0x00461311, 0x00477, 0x00477, 0x00101111, 0x00181818, 0x00477, 0x00477, 0x0010bb, 0x00721915, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00722522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322020, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00e0e1e1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x00741a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00edd, 0x00171515, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001d1a1b, 0x00151313, 0x00b9a, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c6271f, 0x00831c17, 0x00611612, 0x005d1612, 0x00751a15, 0x00a4221b, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x006e2521, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00477, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x002c10f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00322, 0x00545, 0x00544, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00662421, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82c24, 0x00532321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00581511, 0x00191b1b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00788, 0x00be261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00932722, 0x002e2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00732522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004012f, 0x00353737, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x00741a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00a52923, 0x00e12d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00c52b23, 0x00832622, 0x00372020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00342020, 0x00732522, 0x00a42923, 0x00cb2b23, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002710f, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e9e9, 0x00181919, 0x002c10f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d2121, 0x00502221, 0x00532321, 0x00442121, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004a2221, 0x00aa2923, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00daa, 0x00696b6b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00494b4b, 0x00477, 0x00b9251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b62a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x009e2822, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00477, 0x00858686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x005b5d5d, 0x00477, 0x004a1411, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00482221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00c9281f, 0x00a4221b, 0x00831c17, 0x00601612, 0x003a11f, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008c8d8d, 0x00477, 0x00711915, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b92a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00622421, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00641713, 0x0018dc, 0x00477, 0x00477, 0x00477, 0x00101111, 0x00333535, 0x00575959, 0x00c1c2c2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005a5c5c, 0x00788, 0x00c8281f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00602321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005f2321, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x00611612, 0x00577, 0x009bb, 0x004f5151, 0x00979898, 0x00c5c6c6, 0x00e9eaea, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00cee, 0x00481310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2c23, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x0022fe, 0x00477, 0x00626464, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007d7f7f, 0x00477, 0x00b0241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00792522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x0011ff, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00cb2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b4241d, 0x0010bb, 0x001a1b1b, 0x00bdbebe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x001b1c1c, 0x002d10f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2d24, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00fde, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00892722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x0011bb, 0x00212323, 0x00dcdcdc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009d9e9e, 0x00477, 0x00921f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x002e10f, 0x00121313, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00303232, 0x001adc, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x003e2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b52a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007e1b16, 0x00477, 0x00a3a5a5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bbbcbc, 0x00477, 0x00761a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171415, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00672421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22920, 0x00caa, 0x00464848, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004d4f4f, 0x00baa, 0x00d42a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00522221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004b1411, 0x00acc, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x00799, 0x00581512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c32b23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a6221b, 0x00477, 0x007c7e7e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x00577, 0x00be261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x0021ed, 0x00232525, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00121313, 0x003c1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d52c24, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00bf2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00731a15, 0x00477, 0x00b5b6b6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008b8c8c, 0x00477, 0x00a4221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00702522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c8281f, 0x00999, 0x00525454, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00232525, 0x0025fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00de2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00401210, 0x00e1010, 0x00e0e1e1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a9aaaa, 0x00477, 0x00861d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009d2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a201a, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003b3d3d, 0x0013cb, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00462221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00edd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02c22, 0x0019dc, 0x002c2e2e, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c7c8c8, 0x00477, 0x006a1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b52a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c82b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00671813, 0x00477, 0x00c0c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005a5c5c, 0x00999, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005c2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007b2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c0261e, 0x00688, 0x005e6060, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00bdd, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2b23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003611f, 0x00131414, 0x00e8e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00e4e5e5, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00787a7a, 0x00477, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a72923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00696b6b, 0x00474949, 0x00242626, 0x00799, 0x00477, 0x00477, 0x007d7f7f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00191a1a, 0x003611f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ef, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00582321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2b21, 0x0014cb, 0x00363838, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x00acc, 0x00daa, 0x002e11f, 0x004d1310, 0x006e1914, 0x00861d17, 0x002fec, 0x001b1c1c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008e8f8f, 0x00477, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005c1612, 0x00588, 0x00cbcbcb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00c5c6c6, 0x00a1a3a3, 0x007e8080, 0x005f6060, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004e5050, 0x00b99, 0x00cf2920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x001fed, 0x00414343, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e6e6, 0x00477, 0x007f1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003f2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00852622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b7251d, 0x00477, 0x006a6c6c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00cbcbcb, 0x00a3a5a5, 0x00808282, 0x005d5f5f, 0x00373939, 0x00131414, 0x00477, 0x00477, 0x00477, 0x00477, 0x007c7e7e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b5b6b6, 0x00477, 0x00761a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00982019, 0x00477, 0x00a8a9a9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00131414, 0x00611612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00532321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x002c10e, 0x00191a1a, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00848585, 0x00616262, 0x003a3c3c, 0x00161717, 0x00477, 0x00477, 0x00477, 0x00477, 0x0019ed, 0x003b12f, 0x005e1612, 0x00801c16, 0x009a201a, 0x00fa9, 0x00232525, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00272929, 0x0020ed, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x001ded, 0x002c2e2e, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00191a1a, 0x005b1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00562321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b12a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00477, 0x00a2a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00474949, 0x00477, 0x0017dc, 0x003911f, 0x005a1512, 0x007b1b16, 0x009f211a, 0x00c1271e, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00741a15, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00888989, 0x00477, 0x00a0211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791a15, 0x00477, 0x00b5b6b6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00799, 0x006c1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00666, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00612421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00fbb, 0x00404242, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x007d1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2820, 0x00a99, 0x00505252, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e4e5e5, 0x00e1010, 0x00411310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00caa, 0x00494b4b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00477, 0x00931f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2020, 0x00d62c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00511512, 0x008aa, 0x00d5d5d5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x001f2121, 0x0025fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00421310, 0x00dff, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005a5c5c, 0x00788, 0x00c7271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00571512, 0x00799, 0x00d5d5d5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00862622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x00477, 0x00777979, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00797b7b, 0x00477, 0x00ac231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009f211a, 0x00477, 0x00868787, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c1c2c2, 0x00477, 0x006b1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bb251e, 0x00477, 0x006c6e6e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x001c1d1d, 0x003c1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009e2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00767, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x0023fe, 0x001f2121, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x009bb, 0x004e1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d52c23, 0x005c2321, 0x003f2121, 0x004f2221, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x001ced, 0x002a2c2c, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00303232, 0x0018dc, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003711f, 0x00141515, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00909191, 0x00477, 0x00a6221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00562321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ef, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00762522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00477, 0x00adaeae, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00444646, 0x00daa, 0x00d32a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00612421, 0x00231f20, 0x00251f20, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006c1814, 0x00477, 0x00bcbdbd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00959696, 0x00477, 0x00951f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a201a, 0x00477, 0x00929393, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00151616, 0x003812f, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bc2a23, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x001bed, 0x00393b3b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x00801c16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00231f20, 0x00231f20, 0x00772522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00788, 0x005a5c5c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00141515, 0x003611f, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x001ded, 0x002b2d2d, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00737575, 0x00477, 0x00b8251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00477, 0x00a1a3a3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x001d1f1f, 0x002810e, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x003d2121, 0x00231f20, 0x00352020, 0x00e12d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003a1210, 0x00111212, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00666868, 0x00577, 0x00bd261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791a15, 0x00477, 0x00b7b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dddddd, 0x009bb, 0x00511511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c82b23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00442121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791b16, 0x00477, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00767878, 0x00477, 0x00af231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a02822, 0x005c2321, 0x00792522, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00961f19, 0x00477, 0x00909191, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00588, 0x00601713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00caa, 0x004b4d4d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00565858, 0x00999, 0x00cf2920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00572321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00562321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e1612, 0x00191a1a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x008aa, 0x00511511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x0018dc, 0x00313333, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003a3c3c, 0x0013cb, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00571512, 0x00799, 0x00d7d7d7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x00477, 0x006d1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00592321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00521411, 0x00222424, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00484a4a, 0x00daa, 0x00d32a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00477, 0x00c5c6c6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a1a2a2, 0x00477, 0x00891d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b9251d, 0x00477, 0x006f7171, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003a3c3c, 0x0014cb, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00432121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00542321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00651713, 0x00dff, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bfc0c0, 0x00477, 0x00771a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x00aa231c, 0x00577, 0x00636565, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x001a1b1b, 0x002d10f, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003511f, 0x00151616, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x00881d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00cdcdcd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x0013cc, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00e02c22, 0x00bf261e, 0x009d211a, 0x007c1b16, 0x005c1612, 0x003b12f, 0x0019ed, 0x00477, 0x00477, 0x00151616, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00737575, 0x00477, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00982019, 0x00477, 0x00939494, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00232525, 0x0025fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00e32d24, 0x00342020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d82c24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00788, 0x00686a6a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003d3f3f, 0x0011ba, 0x003e11e, 0x003011f, 0x0017dc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00161717, 0x00393b3b, 0x005d5f5f, 0x00808282, 0x00a3a5a5, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x00799, 0x00541512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x001ced, 0x002b2d2d, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008d8e8e, 0x00477, 0x00a2211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009d2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00581612, 0x009bb, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9caca, 0x004b4d4d, 0x00323535, 0x00474949, 0x00616262, 0x00848585, 0x00a5a6a6, 0x00cbcbcb, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00464848, 0x00daa, 0x00d32a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00771a15, 0x00477, 0x00b7b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x00131414, 0x003a1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d62c24, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2920, 0x00999, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x007e1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00baa, 0x004b4d4d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006e7070, 0x00477, 0x00bd261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00baa, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00434, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00af2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00671813, 0x00477, 0x00cfcfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00212323, 0x0024fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00551512, 0x008aa, 0x00d7d7d7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dadada, 0x008aa, 0x00561512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00452221, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2b21, 0x00eba, 0x00484a4a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007f8181, 0x00477, 0x00a9231b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b9251d, 0x00477, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00535555, 0x00ba9, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a12822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791a15, 0x00477, 0x00bdbebe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dfdfdf, 0x00cee, 0x00481310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003511f, 0x00161717, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c1c2c2, 0x00477, 0x00701914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ae2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003b2120, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0018dc, 0x00373939, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00525454, 0x00a99, 0x00cc2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00982019, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00363838, 0x0017dc, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00abacac, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00477, 0x00721915, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x001ced, 0x002d2f2f, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a4a6a6, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00e22d24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x0023fd, 0x00272929, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x002a2c2c, 0x001ded, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00771a15, 0x00477, 0x00b9baba, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00212323, 0x0027fe, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00322020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00842622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a201a, 0x00477, 0x00989999, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008c8d8d, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d62a21, 0x00baa, 0x004d4f4f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00878888, 0x00477, 0x00a7221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00da2d24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003011f, 0x001c1d1d, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00101111, 0x003d1210, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00681813, 0x00588, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e9eaea, 0x00111212, 0x003f1310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00742522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x00477, 0x00858686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005e6060, 0x00788, 0x00c4271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x0015cc, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x00577, 0x00bf261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00d02c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00401310, 0x00131414, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c4c5c5, 0x00477, 0x00671813, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x00477, 0x00a1a2a2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x00799, 0x00591612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c12b23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00767, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00652421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x00477, 0x00737575, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00333535, 0x0017dc, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00971f19, 0x00477, 0x00d2d2d2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004e5050, 0x00baa, 0x00d42a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00512221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00c42b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00501411, 0x00acc, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00999a9a, 0x00477, 0x00911f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00961f19, 0x00477, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bcbdbd, 0x00477, 0x00751a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00572321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2820, 0x00788, 0x00616262, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00151616, 0x003311f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00a6221b, 0x00477, 0x00bcbdbd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00272929, 0x001ced, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x003e2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151313, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b52a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00611612, 0x00588, 0x00d3d3d3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00696b6b, 0x00477, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00782522, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00999, 0x00626363, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00545656, 0x00477, 0x00a7221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00932722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00492221, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72a21, 0x00caa, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcfcf, 0x00699, 0x005b1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x00261f20, 0x009e2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00588, 0x00acadad, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x004e5050, 0x00477, 0x00791b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2d24, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a62923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00731a15, 0x00477, 0x00c3c4c4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003e4040, 0x0011bb, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00552321, 0x00231f20, 0x00532321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x002d11f, 0x00699, 0x00777979, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00969797, 0x001b1c1c, 0x00688, 0x007f1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00622421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003e2121, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x0015cc, 0x003c3e3e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00939494, 0x00477, 0x00881d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a82923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b32a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x00501411, 0x00477, 0x00699, 0x00343636, 0x005c5e5e, 0x00585a5a, 0x003e4040, 0x00bdd, 0x00477, 0x003011f, 0x00b6251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00972822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00477, 0x00b1b2b2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b2b3b3, 0x00799, 0x003e1210, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52d24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x00dc2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x006b1814, 0x003711f, 0x002110f, 0x001add, 0x003211f, 0x00651713, 0x00b1241c, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009b2822, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00342020, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x0020ed, 0x00262828, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009fa0a0, 0x009bb, 0x002910e, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00d62c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00862622, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00882622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a6221b, 0x00477, 0x00494b4b, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00565858, 0x00477, 0x003511f, 0x00db2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c12b23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00342020, 0x00a92923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x00512221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00dc2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00577, 0x001e2020, 0x00959696, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x00bbbcbc, 0x00636565, 0x009bb, 0x00898, 0x00711915, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82c24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00a42923, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00b92a23, 0x00652421, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006a2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x002c10e, 0x00477, 0x00477, 0x00232424, 0x00323535, 0x00232424, 0x00699, 0x00477, 0x00a99, 0x00581512, 0x00c8281f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00442121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x004c2221, 0x006b2421, 0x00822622, 0x00832622, 0x007b2522, 0x005c2321, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00972822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00b7251d, 0x00751a15, 0x00501410, 0x004312f, 0x00521411, 0x00701914, 0x00a1211a, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00902722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00962722, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00d02c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12923, 0x00482221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1818, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x006a2421, 0x00b22a23, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00c72b23, 0x008b2722, 0x00422121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00482221, 0x005c2321, 0x00642421, 0x005c2321, 0x004b2221, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x0011f10, 0x001e1b1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x0011f10, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00877, 0x00000, 0x00000, 0x00b9a, 0x00191616, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x0010ef, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00323, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00baa, 0x00141112, 0x001b1819, 0x00201d1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00191617, 0x0011f10, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00433, 0x00544, 0x00434, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00211e1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00151314, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00111010, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00131011, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00fdd, 0x00161314, 0x001c1919, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x001c191a, 0x00161314, 0x00fee, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000}; \ No newline at end of file diff --git a/include/utils/command_structure/auto_command.h b/include/utils/command_structure/auto_command.h index 008f31e..532fcbe 100644 --- a/include/utils/command_structure/auto_command.h +++ b/include/utils/command_structure/auto_command.h @@ -20,6 +20,10 @@ class AutoCommand { * What to do if we timeout instead of finishing. timeout is specified by the timeout seconds in the constructor */ virtual void on_timeout(){} + AutoCommand* withTimeout(double t_seconds){ + timeout_seconds = t_seconds; + return this; + } /** * How long to run until we cancel this command. * If the command is cancelled, on_timeout() is called to allow any cleanup from the function. diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index 557c2f9..14be25e 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -57,7 +57,7 @@ void CommandController::run() { command_queue.pop(); command_timed_out = false; - printf("Beginning Command %d\n", command_count); + printf("Beginning Command %d : timeout = %f\n", command_count, next_cmd->timeout_seconds); fflush(stdout); From 55252051243d23ae1c6f0091a0a523663cf50f06 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sat, 18 Feb 2023 00:26:57 -0500 Subject: [PATCH 174/243] take 2 --- src/subsystems/flywheel.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index be44f1d..2c41114 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -22,7 +22,7 @@ using namespace vex; -const int FlywheelWindowSize = 10; +const int FlywheelWindowSize = 1; /********************************************************* * CONSTRUCTOR, GETTERS, SETTERS From 7e38802396c2397064828637d0dfd0a26fe825a3 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Fri, 17 Feb 2023 19:47:28 -0500 Subject: [PATCH 175/243] Fixed kS after trapezoid curve --- include/utils/feedforward.h | 10 ++++++++-- src/utils/motion_controller.cpp | 2 +- 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/include/utils/feedforward.h b/include/utils/feedforward.h index 2592107..c6700e7 100644 --- a/include/utils/feedforward.h +++ b/include/utils/feedforward.h @@ -63,9 +63,15 @@ class FeedForward * @param a Requested acceleration of system * @return A feedforward that should closely represent the system if tuned correctly */ - double calculate(double v, double a) + double calculate(double v, double a, double pid_ref=0.0) { - return (cfg.kS * (v > 0 ? 1 : v < 0 ? -1 : 0)) + (cfg.kV * v) + (cfg.kA * a) + cfg.kG; + double ks_sign = 0; + if(v != 0) + ks_sign = sign(v); + else if(pid_ref != 0) + ks_sign = sign(pid_ref); + + return (cfg.kS * ks_sign) + (cfg.kV * v) + (cfg.kA * a) + cfg.kG; } private: diff --git a/src/utils/motion_controller.cpp b/src/utils/motion_controller.cpp index 1b495e0..9d915ca 100644 --- a/src/utils/motion_controller.cpp +++ b/src/utils/motion_controller.cpp @@ -40,7 +40,7 @@ double MotionController::update(double sensor_val) pid.set_target(cur_motion.pos); pid.update(sensor_val); - out = pid.get() + ff.calculate(cur_motion.vel, cur_motion.accel); + out = pid.get() + ff.calculate(cur_motion.vel, cur_motion.accel, pid.get()); if(lower_limit != upper_limit) out = clamp(out, lower_limit, upper_limit); From 43e2140add116c52947b858a23ddf971fae43f5c Mon Sep 17 00:00:00 2001 From: cowsed Date: Sat, 18 Feb 2023 13:08:54 -0500 Subject: [PATCH 176/243] =?UTF-8?q?RIT=20VEX=20YOU=20COMP=20(=E2=95=AF?= =?UTF-8?q?=C2=B0=E2=96=A1=C2=B0)=E2=95=AF=EF=B8=B5=20=E2=94=BB=E2=94=81?= =?UTF-8?q?=E2=94=BB?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- include/intense_milk.h | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/include/intense_milk.h b/include/intense_milk.h index 3b9e4f9..0fa910b 100644 --- a/include/intense_milk.h +++ b/include/intense_milk.h @@ -1,4 +1,5 @@ -#include -int intense_milk_width = 426; -int intense_milk_height = 244 -;uint32_t intense_milk[103944] = {0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00221e1f, 0x001e1a1b, 0x00191617, 0x00151313, 0x0011ff, 0x00cbb, 0x00877, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001e1b1c, 0x001a1718, 0x00161314, 0x0011f10, 0x00dbc, 0x00988, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001b1818, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001f1b1c, 0x001b1818, 0x00161414, 0x00121011, 0x00ecd, 0x00989, 0x00545, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x001b1819, 0x00171415, 0x00131111, 0x00edd, 0x00a99, 0x00655, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1e, 0x001c191a, 0x00181516, 0x00131112, 0x00fde, 0x00baa, 0x00666, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a89, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x001d191a, 0x00191616, 0x00141212, 0x0010ee, 0x00baa, 0x00767, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001e1a1b, 0x00191617, 0x00151213, 0x0011ff, 0x00cbb, 0x00877, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001e1b1b, 0x001a1718, 0x00161314, 0x0011f10, 0x00dbc, 0x00988, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151313, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001f1b1c, 0x001b1718, 0x00161414, 0x00121010, 0x00ecc, 0x00988, 0x00545, 0x00101, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x009e2822, 0x00d12c23, 0x00b72a23, 0x009e2822, 0x00862622, 0x006c2421, 0x00532321, 0x003a2120, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x001b1819, 0x00171415, 0x00131011, 0x00ecd, 0x00a99, 0x00655, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00323, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2020, 0x00b42a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00d42c23, 0x00bb2a23, 0x00a22823, 0x00892722, 0x00702522, 0x00582321, 0x003e2121, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x001c1919, 0x00171515, 0x00131112, 0x00fde, 0x00b9a, 0x00656, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00545, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00352020, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00d92c24, 0x00bf2b23, 0x00a62923, 0x008e2722, 0x00742522, 0x005b2321, 0x00432121, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x001d191a, 0x00181516, 0x00141212, 0x0010ee, 0x00baa, 0x00766, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00412121, 0x00d42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00d12920, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2d24, 0x00c22b23, 0x00aa2923, 0x00912722, 0x00772522, 0x00602321, 0x00462221, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001d1a1b, 0x00181516, 0x00121011, 0x00cab, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00512221, 0x00de2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x004e1411, 0x00477, 0x00788, 0x001ffe, 0x003c12f, 0x00591512, 0x00761a15, 0x00921f19, 0x00b0241c, 0x00cc2820, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02d24, 0x00c72b23, 0x00ae2923, 0x00952722, 0x007c2622, 0x00632421, 0x004a2221, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d191a, 0x0011ff, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00632421, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x003912f, 0x00477, 0x006a6c6c, 0x00767878, 0x00585a5a, 0x00383b3b, 0x00191a1a, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x001bed, 0x003811f, 0x00541411, 0x00711915, 0x008f1e18, 0x00ab231c, 0x00c7281f, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00cb2b23, 0x00b22a23, 0x00992822, 0x007f2622, 0x00672421, 0x004e2221, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00782522, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2920, 0x0027fe, 0x00799, 0x009fa0a0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00d8d8d8, 0x00b8b9b9, 0x009a9b9b, 0x007b7d7d, 0x005c5e5e, 0x003d3f3f, 0x001e1f1f, 0x00588, 0x00477, 0x00477, 0x00477, 0x00477, 0x0017dc, 0x003311f, 0x00501410, 0x006e1914, 0x00891d17, 0x00a6221b, 0x00c4271f, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00cf2c23, 0x00b52a23, 0x009d2822, 0x00842622, 0x006b2421, 0x00512221, 0x00392120, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00656, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171415, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x0018dc, 0x00f1010, 0x00b8b9b9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00dcdcdc, 0x00bebfbf, 0x009fa0a0, 0x007f8181, 0x00626363, 0x00424444, 0x00222424, 0x00799, 0x00477, 0x00477, 0x00477, 0x00477, 0x0012cb, 0x002f11f, 0x004b1310, 0x00681813, 0x00851d17, 0x00a2211b, 0x00be261e, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00d22c23, 0x00ba2a23, 0x00a12822, 0x00872622, 0x006f2522, 0x00562321, 0x003c2121, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00121011, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00a62923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ab231c, 0x00daa, 0x001b1c1c, 0x00cdcdcd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00e1e2e2, 0x00c2c3c3, 0x00a3a5a5, 0x00858686, 0x00656767, 0x00474949, 0x00282a2a, 0x00acc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00daa, 0x002a10f, 0x004712f, 0x00631713, 0x00801c16, 0x009d211a, 0x00bb251e, 0x00d72a21, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00d72c24, 0x00bd2a23, 0x00a52923, 0x008c2722, 0x00732522, 0x005a2321, 0x00412121, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00788, 0x00292b2b, 0x00dfdfdf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00e5e6e6, 0x00c8c9c9, 0x00a8a9a9, 0x00898a8a, 0x006a6c6c, 0x004c4e4e, 0x002c2e2e, 0x00e10f, 0x00477, 0x00477, 0x00477, 0x00477, 0x00a99, 0x002610f, 0x00421210, 0x005f1612, 0x007c1b16, 0x00992019, 0x00b5251d, 0x00d22921, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2d24, 0x00c22b23, 0x00a92923, 0x008f2722, 0x00772522, 0x005e2321, 0x00442121, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00c92b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00791a15, 0x00477, 0x003d3f3f, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x00cccccc, 0x00acadad, 0x008f9090, 0x006f7171, 0x00505252, 0x00323434, 0x00131414, 0x00477, 0x00477, 0x00477, 0x00477, 0x00888, 0x0021fe, 0x003e12f, 0x005b1612, 0x00771a15, 0x00941f19, 0x00b1241c, 0x00cd2820, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00c52b23, 0x00ac2923, 0x00942722, 0x007b2522, 0x00612421, 0x00492221, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00452221, 0x00d82c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x005d1612, 0x00477, 0x00555757, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00d1d1d1, 0x00b2b3b3, 0x00939494, 0x00747676, 0x00565858, 0x00363838, 0x00181919, 0x00477, 0x00477, 0x00477, 0x00477, 0x00577, 0x001dfe, 0x003911f, 0x00561511, 0x00731a15, 0x008f1e18, 0x00ac231c, 0x00c9281f, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00c92b23, 0x00b12923, 0x00972822, 0x007f2622, 0x00662421, 0x004c2221, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00451310, 0x00477, 0x006e7070, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00d6d6d6, 0x00b6b7b7, 0x00999a9a, 0x00797b7b, 0x005a5c5c, 0x003b3d3d, 0x001c1d1d, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x0018dd, 0x003511f, 0x00521411, 0x006e1914, 0x008b1d18, 0x00a8221b, 0x00c5271f, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00ab2923, 0x00722522, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00692421, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82a21, 0x003211f, 0x00477, 0x008c8d8d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00dbdbdb, 0x00bcbdbd, 0x009d9e9e, 0x007d7f7f, 0x00606161, 0x00404242, 0x00202221, 0x00799, 0x00477, 0x00477, 0x00477, 0x00477, 0x0014cc, 0x003111f, 0x004c1310, 0x006a1814, 0x00871d17, 0x00a3211b, 0x00c0261e, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00a32823, 0x00412121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007f2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2820, 0x0022fd, 0x009bb, 0x00a7a8a8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00e0e0e0, 0x00c0c1c1, 0x00a1a3a3, 0x00838484, 0x00636565, 0x00454747, 0x00262828, 0x009bb, 0x00477, 0x00477, 0x00477, 0x00477, 0x00eba, 0x002c11f, 0x00491210, 0x00651713, 0x00821c17, 0x009f211a, 0x00bc261e, 0x00d82a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x008e2722, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00962822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b8251d, 0x0015cc, 0x00121313, 0x00bfc0c0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00e4e5e5, 0x00c6c7c7, 0x00a6a7a7, 0x00878888, 0x00696b6b, 0x004a4c4c, 0x002a2c2c, 0x00cee, 0x00477, 0x00477, 0x00477, 0x00477, 0x00b99, 0x002810f, 0x004312f, 0x00611612, 0x00851d17, 0x00b4241d, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf2b23, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131011, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00ad2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a2211b, 0x00caa, 0x001e2020, 0x00d4d4d4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e9eaea, 0x00cacaca, 0x00abacac, 0x008d8e8e, 0x006d6f6f, 0x004e5050, 0x00303232, 0x00101111, 0x00477, 0x00477, 0x00eba, 0x005a1612, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322020, 0x00bf2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00688, 0x00303232, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00d8d8d8, 0x00a5a6a6, 0x005e6060, 0x00cee, 0x00477, 0x00611713, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a22822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x006e1914, 0x00477, 0x00434545, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x00686a6a, 0x00477, 0x003611f, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00502221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00767, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004b2221, 0x00dc2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00551512, 0x00477, 0x005c5e5e, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a2a4a4, 0x00477, 0x005d1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ab2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005b2321, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02c22, 0x003f1310, 0x00477, 0x00777979, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x00577, 0x00c8281f, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00682421, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x002c10e, 0x00699, 0x00949595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00477, 0x007e1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00612421, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c4271f, 0x001ded, 0x00dff, 0x00aeafaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00171818, 0x00581511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00602421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00542321, 0x00e92e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b5251d, 0x0011bb, 0x00171818, 0x00c5c6c6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00202222, 0x00521411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00caa, 0x00212323, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00bdd, 0x00661713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00572321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00c32b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ba251e, 0x00caa, 0x00262828, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c6c7c7, 0x00477, 0x00961f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00777, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00832622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22920, 0x0018dc, 0x001e2020, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007a7c7c, 0x00477, 0x00d52a21, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x003712f, 0x00cee, 0x00cdcdcd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00252727, 0x003911f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009d2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009c2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00811c16, 0x00477, 0x009a9b9b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c8c9c9, 0x00477, 0x008a1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005b2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbb, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00656, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00d72a21, 0x00daa, 0x00444646, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00727474, 0x00688, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00772522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006e1914, 0x00477, 0x00cfcfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x001d1e1e, 0x00411310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00992822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b22a23, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x0017dc, 0x00484a4a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c0c1c1, 0x00477, 0x00931f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00e22d24, 0x00ee2e24, 0x00ee2e24, 0x00be261e, 0x00477, 0x009d9e9e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00696b6b, 0x00999, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00d72c24, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00362020, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00171818, 0x004a1311, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791a15, 0x00477, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00477, 0x009b201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00412121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007e1b16, 0x00477, 0x00e6e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x00baa, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00a5221b, 0x00477, 0x00b2b3b3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00121313, 0x00531411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008b2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x0010bb, 0x00464848, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00adaeae, 0x00477, 0x00a3211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00432121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008e2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f1b16, 0x00477, 0x00878888, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00585a5a, 0x0011bb, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003b2120, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00471411, 0x00477, 0x006d6f6f, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00cee, 0x005a1512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008d2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x005f1713, 0x00477, 0x00171818, 0x007b7d7d, 0x00c6c7c7, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a4a6a6, 0x00477, 0x00ac231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003d2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00be2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x003f12f, 0x00477, 0x00477, 0x00acc, 0x002c2e2e, 0x004c4e4e, 0x00696b6b, 0x00898a8a, 0x00a8a9a9, 0x00c6c7c7, 0x00e5e6e6, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004f5151, 0x0018dc, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00c22b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302020, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00931f19, 0x00671813, 0x004612f, 0x002a10f, 0x00daa, 0x00477, 0x00477, 0x00477, 0x00477, 0x009bb, 0x00262828, 0x00444646, 0x00636565, 0x00818383, 0x00a1a2a2, 0x00bebfbf, 0x00dedede, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x008aa, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007b2522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171415, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2020, 0x009e2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x00bf261e, 0x00a3211b, 0x00851d17, 0x006a1814, 0x004c1310, 0x003111f, 0x0014cc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00588, 0x001e1f1f, 0x003d3f3f, 0x005c5e5e, 0x007a7c7c, 0x00999a9a, 0x00b8b9b9, 0x00d6d6d6, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009d9e9e, 0x00477, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00582321, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00c6271f, 0x00aa231c, 0x008d1e18, 0x00711915, 0x00541411, 0x003711f, 0x001bed, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00181919, 0x00363838, 0x00555757, 0x00737575, 0x00929393, 0x00b0b1b1, 0x00cfcfcf, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00454747, 0x001ced, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00b92a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00542321, 0x009e2822, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00cd2820, 0x00b0241c, 0x00941f19, 0x00771a15, 0x005b1612, 0x003e12f, 0x002310f, 0x00888, 0x00477, 0x00477, 0x00477, 0x00477, 0x00101111, 0x002e3030, 0x004e5050, 0x006b6d6d, 0x008b8c8c, 0x00a8a9a9, 0x00c8c9c9, 0x00e6e7e7, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00699, 0x006d1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00742522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x005a2321, 0x00732522, 0x008c2722, 0x00a42923, 0x00bd2a23, 0x00d52c24, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00d32a21, 0x00b7251d, 0x009a201a, 0x007e1b16, 0x00621713, 0x004512f, 0x002810f, 0x00caa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00acc, 0x00272929, 0x00464848, 0x00656767, 0x00838484, 0x00a2a4a4, 0x00c0c1c1, 0x00e0e0e0, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00929393, 0x00477, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00434, 0x001f1c1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x003b2120, 0x00542321, 0x006c2421, 0x00862622, 0x009e2822, 0x00b72a23, 0x00d02c23, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2b21, 0x00be261e, 0x00a1211a, 0x00851d17, 0x00681813, 0x004c1310, 0x002f11f, 0x0013cc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00699, 0x00202121, 0x003e4040, 0x005e6060, 0x007b7d7d, 0x009b9c9c, 0x00b9baba, 0x00d8d8d8, 0x00f7f7f7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x002b2d2d, 0x002a10e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b22a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00362020, 0x004e2221, 0x00672421, 0x007f2622, 0x00992822, 0x00b12a23, 0x00ca2b23, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00c5271f, 0x00a8221b, 0x008c1e18, 0x006f1914, 0x00531411, 0x003712f, 0x0019ed, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00191a1a, 0x00383a3a, 0x00565858, 0x00757777, 0x00939494, 0x00b2b3b3, 0x00d1d1d1, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a1a2a2, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302020, 0x00482221, 0x00612421, 0x007a2522, 0x00922722, 0x00ab2923, 0x00c42b23, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00cb2820, 0x00af231c, 0x00921f19, 0x00761a15, 0x00591512, 0x003d12f, 0x0021fe, 0x00788, 0x00477, 0x00477, 0x00477, 0x00477, 0x00121313, 0x00303232, 0x004f5151, 0x006d6f6f, 0x008c8d8d, 0x00aaabab, 0x00c9caca, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x00151616, 0x002d10f, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00de2d24, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00532321, 0x008a2722, 0x00bd2a23, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00d22921, 0x00b5251d, 0x009a201a, 0x007c1b16, 0x00611612, 0x004312f, 0x002810f, 0x00b99, 0x00477, 0x00477, 0x00477, 0x00477, 0x00bdd, 0x00292b2b, 0x00484a4a, 0x00666868, 0x00858686, 0x00a3a5a5, 0x00e4e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x002c2e2e, 0x00daa, 0x00c5271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00502221, 0x00a62923, 0x00e22d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x00d62a21, 0x00c7271f, 0x00b6251d, 0x00a6221b, 0x00941f19, 0x00841c17, 0x00741a15, 0x004e1310, 0x0021cb, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00aeafaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c2c3c3, 0x00202222, 0x00caa, 0x00ac231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131011, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x00ae2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x00d22920, 0x00c0261e, 0x00b0241c, 0x00a0211a, 0x008f1e18, 0x007f1b16, 0x006f1914, 0x005f1612, 0x004e1310, 0x003e12f, 0x002d11f, 0x001ced, 0x00caa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00101111, 0x00222323, 0x00343636, 0x00464848, 0x00585a5a, 0x00686a6a, 0x007a7c7c, 0x008c8d8d, 0x009d9e9e, 0x00aeafaf, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00959696, 0x00b3b4b4, 0x00d2d2d2, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00bebfbf, 0x00525454, 0x00477, 0x0020fe, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00522221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00191516, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00542321, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00dc2b22, 0x00cc2820, 0x00bc261e, 0x00ab231c, 0x009b201a, 0x008b1d18, 0x007a1b16, 0x006a1814, 0x00581511, 0x00491210, 0x003911f, 0x002810f, 0x0018dd, 0x00888, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00588, 0x00171818, 0x00272929, 0x00393c3c, 0x004b4d4d, 0x005d5f5f, 0x006d6f6f, 0x007f8181, 0x00929393, 0x00a3a5a5, 0x00b5b6b6, 0x00c6c7c7, 0x00d8d8d8, 0x00e9eaea, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b5b6b6, 0x00477, 0x00477, 0x00477, 0x00477, 0x00131414, 0x00313333, 0x00505252, 0x006c6e6e, 0x00808282, 0x00909191, 0x008a8b8b, 0x00787a7a, 0x00505252, 0x00171818, 0x00477, 0x00eba, 0x00721915, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00732522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00b9a, 0x00131112, 0x001a1717, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00492221, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00ac231c, 0x005a1512, 0x0023fe, 0x00888, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00acc, 0x001b1c1c, 0x002c2e2e, 0x003e4040, 0x00505252, 0x00626363, 0x00747676, 0x00858686, 0x00979898, 0x00a8a9a9, 0x00babbbb, 0x00cbcbcb, 0x00dddddd, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e8e8, 0x00477, 0x005f1612, 0x00982019, 0x007b1b16, 0x005f1612, 0x00421210, 0x002610f, 0x00caa, 0x00477, 0x00477, 0x00477, 0x00999, 0x0020fe, 0x00511411, 0x00951f19, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x007b2522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00544, 0x00988, 0x00dcc, 0x00111010, 0x00161314, 0x001b1718, 0x001f1b1c, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x003611f, 0x00477, 0x00111212, 0x004d4f4f, 0x00737575, 0x008a8b8b, 0x009c9d9d, 0x00adaeae, 0x00bebfbf, 0x00d2d2d2, 0x00e3e4e4, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e6e6, 0x00477, 0x00831c17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00da2b21, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00602321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00877, 0x00cbb, 0x0011ef, 0x00151313, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007a2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x0016dc, 0x00141515, 0x00979898, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cbcbcb, 0x00477, 0x009e211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00a12822, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x002a10e, 0x00161717, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a5a6a6, 0x00477, 0x00bf261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00db2d24, 0x00942722, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201d1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a6221b, 0x00477, 0x00a1a2a2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00828383, 0x00477, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00c02b23, 0x00772522, 0x008f2722, 0x00a62923, 0x00b72a23, 0x00bc2a23, 0x00bb2a23, 0x00ad2923, 0x00972822, 0x00762522, 0x00492221, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151313, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00592321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00691814, 0x008aa, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x0017dc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00662421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00561511, 0x00212222, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003b3d3d, 0x003811f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00732522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191717, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00622421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00e10f, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00181919, 0x00581511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00582321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171415, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004b2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00941f19, 0x00477, 0x00c5c6c6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00477, 0x00791b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003c2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00fee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00271f20, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00caa, 0x00555757, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cdcdcd, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191616, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aa2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a1814, 0x00477, 0x00cfcfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00522221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92a21, 0x00eba, 0x004d4f4f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00858686, 0x00477, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00b02923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00191616, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bc2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00721915, 0x00477, 0x00c7c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x0013cb, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00952722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1b, 0x00151314, 0x00dbc, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00101, 0x00767, 0x00dcc, 0x00121010, 0x00161314, 0x00181516, 0x00171515, 0x00141212, 0x0010ee, 0x00988, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00522221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x0012cb, 0x00424444, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003e4040, 0x003411f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00782522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fde, 0x00656, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00dbb, 0x00141212, 0x001b1819, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00161414, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b42a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c1b16, 0x00477, 0x00bcbdbd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00101111, 0x005f1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00592321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00b9a, 0x00121010, 0x00191617, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004a2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0016cc, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00babbbb, 0x00477, 0x00982019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00878, 0x0010ee, 0x00171515, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00878, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ab2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00871d17, 0x00477, 0x00b0b1b1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003c3e3e, 0x0012bb, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00656, 0x00ecd, 0x00151313, 0x001d191a, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00992822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2920, 0x00477, 0x004c4e4e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00727474, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008b2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00cab, 0x00131111, 0x001b1818, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00656, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006d2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00381210, 0x00bdd, 0x00cbcbcb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d5d5d5, 0x004c4e4e, 0x00477, 0x005a1612, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00372020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00a89, 0x0011ff, 0x00191616, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00101, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004a2221, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00477, 0x009e9f9f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00e7e8e8, 0x00d6d6d6, 0x00c5c6c6, 0x00b3b4b4, 0x00a2a4a4, 0x00909191, 0x007e8080, 0x00626464, 0x002f3131, 0x00477, 0x00baa, 0x007d1b16, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00892722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00767, 0x00fde, 0x00161414, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00d32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00477, 0x00686a6a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00e0e0e0, 0x00cecece, 0x00bcbdbd, 0x00aaabab, 0x009a9b9b, 0x00888989, 0x00777979, 0x00656767, 0x00555757, 0x00434545, 0x00303232, 0x001f2020, 0x00eff, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x0015dc, 0x003b1210, 0x007d1b16, 0x00d72a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bd2a23, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00dbc, 0x00141213, 0x001c1819, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ae2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bd261e, 0x00ba9, 0x00393b3b, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00e8e9e9, 0x00d8d8d8, 0x00c6c7c7, 0x00b5b6b6, 0x00a3a5a5, 0x00929393, 0x007f8181, 0x006e7070, 0x005d5f5f, 0x004c4e4e, 0x003a3c3c, 0x00292b2b, 0x00181919, 0x00799, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00577, 0x0016dc, 0x002510f, 0x003612f, 0x004512f, 0x00561511, 0x00651713, 0x00761a15, 0x00851d17, 0x00971f19, 0x00a7221b, 0x00b7251d, 0x00c7281f, 0x00d72a21, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c32b23, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00b9a, 0x00121010, 0x001a1717, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00712522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x001eed, 0x001b1c1c, 0x00e4e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x00565858, 0x00444646, 0x00323434, 0x00202121, 0x00f1010, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00caa, 0x001cee, 0x002d11f, 0x003c12f, 0x004d1310, 0x005e1612, 0x006e1914, 0x007e1b16, 0x008e1e18, 0x009e211a, 0x00ae231c, 0x00be261e, 0x00cf2920, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00888, 0x0010ef, 0x00171516, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00423f3f, 0x006b6869, 0x00828080, 0x00807e7e, 0x00555253, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00471310, 0x00699, 0x00c2c3c3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x001e2020, 0x0011bb, 0x00351110, 0x004412f, 0x00551411, 0x00641713, 0x00751a15, 0x00841c17, 0x00961f19, 0x00a6221b, 0x00b7251d, 0x00c7271f, 0x00d72a21, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00b52a23, 0x00532321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00766, 0x00ecc, 0x00151314, 0x001d191a, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00646162, 0x00929091, 0x00c2c1c1, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c4c4, 0x002f2b2c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a62923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c1e18, 0x00477, 0x007d7f7f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00525454, 0x00688, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x00d32c23, 0x00c52b23, 0x00b32a23, 0x00952722, 0x006f2521, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00565354, 0x00858384, 0x00b4b3b3, 0x00e3e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a09e9f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004e2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00eba, 0x00383a3a, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00969797, 0x00477, 0x00771a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00db2d24, 0x00cd2c23, 0x00bf2b23, 0x00b12a23, 0x00a32823, 0x00942722, 0x00872622, 0x00782522, 0x006b2421, 0x005c2321, 0x004e2221, 0x00402121, 0x00322020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00484546, 0x00787677, 0x00a6a5a5, 0x00d6d5d5, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00877, 0x00cbb, 0x00fdd, 0x00211e1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b32a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00531411, 0x008aa, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d2d2d2, 0x00bdd, 0x003a1210, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00d42c23, 0x00c62b23, 0x00b82a23, 0x00aa2923, 0x009c2822, 0x008e2722, 0x00802622, 0x00732522, 0x00642421, 0x00562321, 0x00482221, 0x00392120, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003b3838, 0x006b6869, 0x00999798, 0x00c8c7c7, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00dbc, 0x00161414, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003e2121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x00707272, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x002c2e2e, 0x0013cb, 0x00d22921, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12923, 0x00792522, 0x006b2421, 0x005d2321, 0x00502221, 0x00412121, 0x00342020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302c2d, 0x005e5b5b, 0x008c8a8b, 0x00bbbaba, 0x00e9e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00181616, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00852622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005d1612, 0x00bdd, 0x00e6e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00676969, 0x00477, 0x00a3211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2b23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x003b2120, 0x003b2120, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00272324, 0x00514e4e, 0x007e7c7d, 0x00aeacad, 0x00dcdcdc, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bf2b23, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x0010bb, 0x00585a5a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00452221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00342020, 0x00412121, 0x00502221, 0x005d2321, 0x006b2421, 0x007a2522, 0x00872622, 0x00962822, 0x00a52923, 0x00b32a23, 0x00c12b23, 0x00cf2c23, 0x00dc2d24, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00ca2b23, 0x00842622, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00726f70, 0x00a09e9f, 0x00d0cfcf, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x001c1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00b9251d, 0x00477, 0x00a6a7a7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00131414, 0x002c10e, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00742522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2020, 0x00382120, 0x00472221, 0x00542321, 0x00642421, 0x00722522, 0x00802622, 0x008e2722, 0x009c2822, 0x00aa2923, 0x00b82a23, 0x00c62b23, 0x00d42c23, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2d24, 0x005d2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00646162, 0x00939192, 0x00c2c1c1, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0012f10, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00362020, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003c3e3e, 0x00baa, 0x00c6271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00be2a23, 0x004d2221, 0x005c2321, 0x00692421, 0x00772522, 0x00852622, 0x00932722, 0x00a12822, 0x00b12923, 0x00be2a23, 0x00cd2c23, 0x00da2d24, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00642421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2829, 0x00575454, 0x00868485, 0x00b4b3b3, 0x00e3e3e3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00442121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007e1b16, 0x00477, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007e8080, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92d23, 0x00d92a21, 0x00c8281f, 0x00b9251d, 0x00a8221b, 0x00992019, 0x00871d17, 0x00771a15, 0x00661713, 0x005b1612, 0x005c1612, 0x00801c16, 0x00d22921, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52d24, 0x003e2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00494646, 0x00797777, 0x00a7a5a6, 0x00d6d6d6, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00e2e3e3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00799, 0x004d1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00d32a21, 0x00c2271f, 0x00b1241c, 0x00a1211a, 0x00911f19, 0x00811c16, 0x00701914, 0x00611612, 0x00501410, 0x004112f, 0x002f11f, 0x001ffe, 0x00eba, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00dff, 0x001d1e1e, 0x001b1c1c, 0x00477, 0x00a99, 0x00982019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a82923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c3839, 0x00c9c8c8, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2020, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00477, 0x00a4a6a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003a3c3c, 0x0019ed, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00dc2b22, 0x00cb2820, 0x00bc261e, 0x00ab231c, 0x009b201a, 0x008b1d18, 0x007a1b16, 0x006a1814, 0x00591512, 0x00491210, 0x003911f, 0x002911f, 0x0018dd, 0x00999, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00151616, 0x00262727, 0x00373a3a, 0x00494b4b, 0x005a5c5c, 0x006b6d6d, 0x007d7f7f, 0x008e8f8f, 0x00a0a1a1, 0x00b2b3b3, 0x00c3c4c4, 0x00d5d5d5, 0x00e6e7e7, 0x00f7f7f7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dadada, 0x003b3d3d, 0x00788, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00502221, 0x00812622, 0x00a42923, 0x00bc2a23, 0x00c92b23, 0x00c92b23, 0x00ba2a23, 0x00a22822, 0x00732522, 0x003a2120, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x001ced, 0x00393b3b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00477, 0x004c1310, 0x00a5221b, 0x00a4221b, 0x00941f19, 0x00841c17, 0x00731a15, 0x00631713, 0x00531411, 0x004312f, 0x00331210, 0x002310f, 0x0012cb, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00acc, 0x001a1c1b, 0x002c2e2e, 0x003e4040, 0x004f5151, 0x00616262, 0x00737575, 0x00858686, 0x00969797, 0x00a7a8a8, 0x00b8b9b9, 0x00cacaca, 0x00dcdcdc, 0x00eceded, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x00151616, 0x004d1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00982822, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00b72a23, 0x00562321, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00821c17, 0x00477, 0x00bebfbf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x003e4040, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00101111, 0x00222323, 0x00343636, 0x00464848, 0x00575959, 0x00686a6a, 0x007a7c7c, 0x008b8c8c, 0x009d9e9e, 0x00adaeae, 0x00c0c1c1, 0x00d2d2d2, 0x00e3e4e4, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00616262, 0x0012cb, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008e2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c6c5c5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003a2120, 0x00a82923, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c42b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0012bb, 0x00464848, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dadada, 0x00c2c3c3, 0x00cdcdcd, 0x00d9d9d9, 0x00e9eaea, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007f8181, 0x00477, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bab9b9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00722522, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x00c6271f, 0x00b1241c, 0x00ab231c, 0x00bd261e, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00761a15, 0x00477, 0x00cacaca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00eba, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00932722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bdbbbc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x009a2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82a21, 0x007f1b16, 0x003712f, 0x00788, 0x00477, 0x00477, 0x00477, 0x00477, 0x00688, 0x00391210, 0x00971f19, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x00daa, 0x00535555, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x001c1d1d, 0x00451310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00772522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cfcece, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00383435, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00631713, 0x00898, 0x00477, 0x00373939, 0x00787a7a, 0x00a7a8a8, 0x00bbbcbc, 0x00bbbcbc, 0x00a5a6a6, 0x00707272, 0x00212323, 0x00477, 0x002d10f, 0x00c5271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a1814, 0x00588, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a0a1a1, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00492221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00e8e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00862622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a5221b, 0x0015cc, 0x00699, 0x00676969, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00a2a4a4, 0x00151616, 0x0011cb, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00999, 0x00616262, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eceded, 0x001a1b1b, 0x002d10f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332f30, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccbcb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c2221, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008b1d18, 0x00477, 0x00323434, 0x00d1d1d1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dbdbdb, 0x001d1f1f, 0x0019dc, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005d1612, 0x00799, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00565858, 0x00688, 0x00b9251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00782522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00676465, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00747272, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c12b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c201a, 0x00477, 0x004b4d4d, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c6c7c7, 0x00588, 0x00671813, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2820, 0x00577, 0x006d6f6f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a0a1a1, 0x00477, 0x00731a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a7a5a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9c8c8, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1717, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00582321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00fbb, 0x00353737, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00565858, 0x00eba, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00511511, 0x00cee, 0x00e9eaea, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x00f1010, 0x003311f, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005c2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cbcacb, 0x00302c2d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ae2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005d1612, 0x00799, 0x00d7d7d7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a7a8a8, 0x00477, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c0261e, 0x00477, 0x007a7c7c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00393b3b, 0x00eba, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00727070, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x007f7d7e, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2b21, 0x00a99, 0x005f6060, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cdcdcd, 0x00477, 0x00992019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00451310, 0x00131414, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007d7f7f, 0x00477, 0x00901e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00dbdada, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00d1d0d1, 0x00a4a2a2, 0x00737171, 0x00413e3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151313, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00912722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c1b16, 0x00477, 0x00cdcdcd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cacaca, 0x00477, 0x00982019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b3241d, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x00699, 0x004d1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x004b2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00757273, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dedede, 0x00b0afaf, 0x00817f7f, 0x00524f50, 0x00292526, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x001ded, 0x003b3d3d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a9aaaa, 0x00477, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00bf2b23, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003811f, 0x001a1b1b, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00222424, 0x001bed, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00822622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2a2b, 0x00e7e6e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ececec, 0x00bdbcbd, 0x008e8c8c, 0x005f5c5d, 0x00322e2f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00722522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009f211a, 0x00477, 0x00a6a7a7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005d5f5f, 0x00baa, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x007e2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a7221b, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005d5f5f, 0x00477, 0x00af231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bb2a23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a4a2a2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cac9ca, 0x009b999a, 0x006c6a6a, 0x003e3a3b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131011, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c92b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003b1210, 0x001c1d1d, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00dff, 0x00561511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006e2521, 0x002d2020, 0x00df2d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x002d10e, 0x00212323, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a7a7, 0x00477, 0x006c1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00464344, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00d7d7d7, 0x00a9a7a8, 0x007a7878, 0x004b4748, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c3271f, 0x00477, 0x00828383, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008e8f8f, 0x00477, 0x00b8251d, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00302020, 0x00231f20, 0x00892722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c201a, 0x00477, 0x00a2a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00121313, 0x002e10f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00e5e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e4e4e4, 0x00b6b4b5, 0x00878585, 0x00585555, 0x002c292a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aa2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e1612, 0x009bb, 0x00e6e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00232525, 0x003010f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a32823, 0x00231f20, 0x00231f20, 0x00322020, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x0024fe, 0x002c2e2e, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x003f4141, 0x00b99, 0x00c7281f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a22822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00807e7f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c3c2c2, 0x00949293, 0x00656262, 0x00373334, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00baa, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b1b2b2, 0x00477, 0x00951f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00932722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00b0b1b1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00858686, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32c23, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2c2c, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0cfcf, 0x00a2a0a1, 0x00726f70, 0x00444041, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008e2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00811c16, 0x00477, 0x00c8c9c9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00474949, 0x0017dc, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00c12b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x001adc, 0x00393b3b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cacaca, 0x008aa, 0x00471310, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00502221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a7a6a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dddddd, 0x00aeacad, 0x007f7d7e, 0x00514e4e, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x0021fd, 0x00363838, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x00477, 0x00711915, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009e2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00831c17, 0x00477, 0x00b7b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00262828, 0x0018dc, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00882622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c3839, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00423f3f, 0x00423f3f, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2521, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a4221b, 0x00477, 0x00a1a3a3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x00788, 0x00d22921, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2d24, 0x00c62b23, 0x00a92923, 0x00832622, 0x005c2321, 0x00342020, 0x00402121, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x001eed, 0x00232525, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00e8e9e9, 0x00d8d8d8, 0x00c6c7c7, 0x00b5b6b6, 0x00a3a5a5, 0x00939494, 0x00808282, 0x006f7171, 0x005e6060, 0x00343737, 0x00477, 0x00a9231b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c02b23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aeacad, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x003b3838, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x006c6a6a, 0x009a9899, 0x00c9c8c8, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00dedede, 0x00555253, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00989, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c62b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003f1210, 0x00191a1a, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00f1111, 0x004f1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b2241d, 0x00999, 0x002a2c2c, 0x00d2d2d2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00dedede, 0x00cdcdcd, 0x00bcbdbd, 0x00aaabab, 0x009a9b9b, 0x00888989, 0x00777979, 0x00656767, 0x00555757, 0x00444646, 0x00313333, 0x001f2020, 0x00f1010, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00baa, 0x001bed, 0x002c11f, 0x00741a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x003e2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00474445, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322e2f, 0x005f5c5d, 0x008d8b8c, 0x00bdbcbd, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00502221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c7271f, 0x00477, 0x007d7f7f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00929393, 0x00477, 0x00b3241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ad231c, 0x0014cc, 0x00799, 0x005c5e5e, 0x00b2b3b3, 0x00e2e3e3, 0x00efefef, 0x00e6e7e7, 0x00d5d5d5, 0x00c4c5c5, 0x00b2b3b3, 0x00a1a3a3, 0x008f9090, 0x007e8080, 0x006c6e6e, 0x005c5e5e, 0x004a4c4c, 0x00393c3c, 0x00282a2a, 0x00171818, 0x00699, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00577, 0x0015dc, 0x002510f, 0x00351110, 0x004512f, 0x00551411, 0x00641713, 0x00751a15, 0x00841c17, 0x00951f19, 0x00a6221b, 0x00b6251d, 0x00c6271f, 0x00d62a21, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b0aeaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00535051, 0x00828080, 0x00b1b0b0, 0x00dfdedf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009d9b9b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a72923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00799, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00272929, 0x002d10f, 0x00ee2e24, 0x00df2c22, 0x00bd261e, 0x00a2211b, 0x00961f19, 0x009b201a, 0x00b7251d, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92a21, 0x00651713, 0x00daa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00daa, 0x001dfe, 0x002d11f, 0x003e11f, 0x004e1310, 0x005f1612, 0x006e1914, 0x007e1b16, 0x008f1e18, 0x009e211a, 0x00af231c, 0x00be261e, 0x00cf2920, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a92923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302c2d, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00484546, 0x00777475, 0x00a5a4a4, 0x00d3d2d2, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcece, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x00daa, 0x00585a5a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b6b7b7, 0x00477, 0x002eec, 0x002e11f, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x001bed, 0x00481310, 0x00761a15, 0x00a3211b, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00af231c, 0x008c1e18, 0x00871d17, 0x00881d17, 0x00982019, 0x00a8221b, 0x00b8251d, 0x00c8281f, 0x00d82a21, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72c24, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00636061, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c3839, 0x006b6969, 0x00999798, 0x00c8c7c7, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008a2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00861d17, 0x00477, 0x00c3c4c4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004b4d4d, 0x00477, 0x00588, 0x003d3f3f, 0x00787a7a, 0x00adaeae, 0x00c6c7c7, 0x00d6d6d6, 0x00d2d2d2, 0x00b3b4b4, 0x00888989, 0x00575959, 0x00262828, 0x00477, 0x00477, 0x00477, 0x0014cc, 0x00411210, 0x006e1914, 0x009a201a, 0x00c9281f, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00d62c24, 0x00c72b23, 0x00b92a23, 0x00ab2923, 0x009e2822, 0x00902722, 0x00822622, 0x004a2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00848182, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322e2f, 0x005f5c5d, 0x008d8b8c, 0x00bdbbbc, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c1c0c0, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00db2d24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x0023fe, 0x00313333, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dbdbdb, 0x001e2020, 0x00828383, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c1c2c2, 0x008f9090, 0x00606161, 0x002d2f2f, 0x00799, 0x00477, 0x00477, 0x00daa, 0x00391210, 0x00651713, 0x00941f19, 0x00c0261e, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00dc2d24, 0x00cd2c23, 0x00c02b23, 0x00b22a23, 0x00a42923, 0x00962722, 0x00872622, 0x00792522, 0x006b2421, 0x005e2321, 0x00502221, 0x00422121, 0x00342020, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00918f90, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00535051, 0x00828080, 0x00b1b0b0, 0x00dfdedf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008e8c8c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006b2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a7221b, 0x00477, 0x009e9f9f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e1e2e2, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00c9caca, 0x00999a9a, 0x00676969, 0x00373939, 0x00acc, 0x00477, 0x00477, 0x00999, 0x003111f, 0x005f1612, 0x008c1e18, 0x00b9251d, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2d24, 0x00b32a23, 0x008b2722, 0x00642421, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a3a1a1, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00474445, 0x00777475, 0x00a5a4a4, 0x00d3d2d2, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00441310, 0x00161717, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00d2d2d2, 0x00a1a2a2, 0x006f7171, 0x003f4141, 0x00101111, 0x00477, 0x00477, 0x00688, 0x002910f, 0x00571511, 0x00841c17, 0x00b1241c, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02d24, 0x00b92a23, 0x00922722, 0x006b2421, 0x00432121, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00636061, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00494646, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003b3838, 0x006b6869, 0x00989697, 0x00c7c6c6, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bab9b9, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ff, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004d2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2820, 0x00477, 0x00787a7a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00dadada, 0x00a8a9a9, 0x00787a7a, 0x00474949, 0x00171818, 0x00477, 0x00477, 0x00477, 0x0023fe, 0x004e1310, 0x007d1b16, 0x00a9231b, 0x00d72a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d24, 0x00c02b23, 0x009a2822, 0x00712522, 0x004b2221, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00625f60, 0x00413e3f, 0x00615e5f, 0x008d8b8c, 0x00bcbabb, 0x00eaeaea, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004d4a4b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00434, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a32823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00671813, 0x00699, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e1e2e2, 0x00b1b2b2, 0x00808282, 0x00505252, 0x001e2020, 0x00477, 0x00477, 0x00477, 0x0019dd, 0x00471310, 0x00741a15, 0x00a2211b, 0x00cf2920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00c72b23, 0x009c2822, 0x00682421, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bbbaba, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00352020, 0x00e92e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00fba, 0x00535555, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00b9baba, 0x00898a8a, 0x00585a5a, 0x00272929, 0x00477, 0x00477, 0x00477, 0x0012cb, 0x004012f, 0x006d1814, 0x009a201a, 0x00c7281f, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52d24, 0x00982822, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00272324, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00484546, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00bfc0c0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00c2c3c3, 0x00919292, 0x00606161, 0x002f3131, 0x00799, 0x00477, 0x00477, 0x00daa, 0x003812f, 0x00651713, 0x00911f19, 0x00c0261e, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00662421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00494646, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b4b3b3, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x0027fe, 0x002d2f2f, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cacaca, 0x00999a9a, 0x00686a6a, 0x00373939, 0x00cee, 0x00477, 0x00477, 0x00888, 0x003011f, 0x005d1612, 0x008b1d18, 0x00bb251e, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00752522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008d8b8c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00474445, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00672421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x00477, 0x00999a9a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00d2d2d2, 0x00a2a4a4, 0x00707272, 0x00404242, 0x00101111, 0x00477, 0x00477, 0x0010bb, 0x00551511, 0x00c2271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00562321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00d3d2d2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0aeaf, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00be2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00491310, 0x00141515, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dbdbdb, 0x00a4a6a6, 0x005e6060, 0x00bdd, 0x00688, 0x007d1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00494646, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171415, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00492221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ce2920, 0x00577, 0x00727474, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x004f5151, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00642421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00adacac, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a02822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b1814, 0x00588, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003d3f3f, 0x0011bb, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00a62923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00d0cfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322020, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x0011bb, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b3b4b4, 0x00477, 0x00a6221b, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00151313, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00464243, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00832622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00b8b9b9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e4e5e5, 0x00477, 0x00871d17, 0x00ee2e24, 0x00ee2e24, 0x00e02d24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00211, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00858384, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d52c24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x002b10e, 0x00292b2b, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dedede, 0x00477, 0x008a1d18, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00cbcacb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00632421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00477, 0x00949595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x00ae231c, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00838181, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00767, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004d1411, 0x00101111, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00595b5b, 0x0011bb, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00a32823, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00dbc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00e1e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00452221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12920, 0x00688, 0x006e7070, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e9e9, 0x009bb, 0x005d1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006c2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x001e1b1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00726f70, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009c2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f1914, 0x00477, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00828383, 0x00477, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00e52d24, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00dcdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00c8c7c7, 0x00787576, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x0014cb, 0x004a4c4c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x001d1f1f, 0x003a1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00686566, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfbfc, 0x00d3d2d2, 0x00a5a4a4, 0x00777475, 0x00484546, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007e2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00452221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d3d2d2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x00b1b0b0, 0x00838181, 0x00545152, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00656, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002e10f, 0x00252727, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003d3f3f, 0x001ced, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00bb2a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00655, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00615e5f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00bebdbd, 0x008f8d8d, 0x00615e5f, 0x00332f30, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00602421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b4241d, 0x00477, 0x00909191, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcfcf, 0x00477, 0x007a1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cac9c9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cac9ca, 0x009b999a, 0x006d6b6b, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b72a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00521511, 0x00e1010, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00999, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00d52c24, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbb, 0x00000, 0x001a1717, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00585555, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00d6d6d6, 0x00a8a6a7, 0x007a7878, 0x004b4748, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00788, 0x00696b6b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d5d5d5, 0x00d2d2d2, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00bdd, 0x00581512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00100, 0x00767, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e3e3, 0x00b4b3b3, 0x00868485, 0x00575454, 0x002c292a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00982822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00731a15, 0x00477, 0x00d5d5d5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00383a3a, 0x00477, 0x00acc, 0x00373939, 0x00676969, 0x00999a9a, 0x00c9caca, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00898a8a, 0x00477, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00322020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00111010, 0x00000, 0x00191516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004e4b4c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efeeee, 0x00c1c0c0, 0x00929091, 0x00646162, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2020, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x0018dc, 0x00444646, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9caca, 0x00477, 0x00571511, 0x00661713, 0x003911f, 0x00daa, 0x00477, 0x00477, 0x00799, 0x002f3131, 0x00606161, 0x00919292, 0x00c2c3c3, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00202222, 0x003511f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a02822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00545, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfbfc, 0x00cdcccc, 0x009e9d9d, 0x00706d6e, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007b2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00971f19, 0x00477, 0x00afb0b0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x00b99, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00c9281f, 0x009a201a, 0x006e1914, 0x004012f, 0x0013cb, 0x00477, 0x00477, 0x00477, 0x00272929, 0x00595b5b, 0x00898a8a, 0x00bbbcbc, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00adaeae, 0x00477, 0x00992019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00492221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00474445, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00d02c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003211f, 0x00222424, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e9e9, 0x009bb, 0x005c1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2920, 0x00a3211b, 0x00741a15, 0x00481310, 0x0019dd, 0x00477, 0x00477, 0x00477, 0x00202221, 0x00505252, 0x00828383, 0x00b2b3b3, 0x00e4e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00424444, 0x0018dc, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00be2a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b0aeaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2829, 0x00575454, 0x00868485, 0x00b0aeaf, 0x00c7c6c6, 0x00c2c1c1, 0x00918f90, 0x00332f30, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ba251e, 0x00477, 0x008b8c8c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00838484, 0x00477, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72a21, 0x00a9231b, 0x007c1b16, 0x004e1310, 0x0021fe, 0x00477, 0x00477, 0x00477, 0x00181919, 0x004a4c4c, 0x00797b7b, 0x00abacac, 0x00dcdcdc, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d3d3d3, 0x00477, 0x00761a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00545, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00413e3f, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x004a4747, 0x00797777, 0x00a8a6a7, 0x00d6d6d6, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e7e7, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b02923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00561511, 0x00cee, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x001d1f1f, 0x003a1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c42b23, 0x00bd2a23, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00b1241c, 0x00831c17, 0x00551411, 0x002810f, 0x00577, 0x00477, 0x00477, 0x00121313, 0x00414343, 0x00737575, 0x00a3a5a5, 0x00d5d5d5, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00676969, 0x00898, 0x00d52a21, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00dbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a19fa0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x006c6a6a, 0x009b999a, 0x00cac9c9, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0afaf, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00101, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82a21, 0x00999, 0x00646666, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00452221, 0x00231f20, 0x00241f20, 0x00402121, 0x00672421, 0x008f2722, 0x00b72a23, 0x00de2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00b8251d, 0x00891d17, 0x005d1612, 0x002e11f, 0x00888, 0x00477, 0x00477, 0x00cee, 0x003a3c3c, 0x006b6d6d, 0x009c9d9d, 0x00cdcdcd, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00cee, 0x00541512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00872622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00111, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312d2e, 0x005f5c5c, 0x008d8b8c, 0x00bdbbbc, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00652421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00871d17, 0x00477, 0x00c9caca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003e4040, 0x001ced, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00b92a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00522221, 0x00892722, 0x00c12b23, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00bd261e, 0x00911f19, 0x00631713, 0x003712f, 0x00baa, 0x00477, 0x00477, 0x008aa, 0x00323434, 0x00636565, 0x00959696, 0x00c5c6c6, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00636565, 0x00577, 0x00c7281f, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00474445, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00524e4f, 0x00807e7e, 0x00b0aeaf, 0x00dedede, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00363233, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008a2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1310, 0x001d1e1e, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcfcf, 0x00477, 0x007a1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x006c2421, 0x00b52a23, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x00c6271f, 0x00982019, 0x006b1814, 0x003c12f, 0x0010bb, 0x00477, 0x00477, 0x00588, 0x002a2c2c, 0x005d5f5f, 0x008c8d8d, 0x00bebfbf, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a7a7, 0x00477, 0x005e1613, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00434, 0x00000, 0x00000, 0x00171516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00625f60, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00454142, 0x00737171, 0x00a3a1a1, 0x00d1d0d1, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a02822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a11f, 0x00474949, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00999, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00d52c24, 0x00251f20, 0x00231f20, 0x00251f20, 0x00752522, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00cc2820, 0x009f211a, 0x00711915, 0x00431210, 0x0017dc, 0x00477, 0x00477, 0x00477, 0x00242626, 0x00545656, 0x00868787, 0x00b5b6b6, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009e9f9f, 0x00799, 0x002e11f, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00686566, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00383435, 0x00666464, 0x00969494, 0x00c4c3c4, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002510f, 0x004e5050, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00bdd, 0x00581512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00812622, 0x00231f20, 0x00422121, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00df2c22, 0x00df2c22, 0x00de2b22, 0x00d12920, 0x00d12920, 0x00d12920, 0x00c9281f, 0x00c2271f, 0x00c2271f, 0x00c2271f, 0x00b3241d, 0x00b3241d, 0x00b3241d, 0x00ac231c, 0x00a5221b, 0x00a5221b, 0x00a5221b, 0x009a201a, 0x00a6221b, 0x00c9281f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00a6221b, 0x00781a15, 0x004b1310, 0x001ded, 0x00477, 0x00477, 0x00477, 0x001c1d1d, 0x004d4f4f, 0x007d7f7f, 0x00aeafaf, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x004d4f4f, 0x00477, 0x002f10f, 0x00d62a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00686566, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a4a2a2, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2a2a, 0x00595657, 0x00898787, 0x00b7b5b6, 0x00e6e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00972822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003d1210, 0x002f3131, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00666868, 0x00477, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00312020, 0x00642421, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00b6251d, 0x006f1914, 0x00401210, 0x002710f, 0x002110f, 0x0018ed, 0x0012cb, 0x0012cb, 0x0011cc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x001bed, 0x00731a15, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00db2b22, 0x00ac231c, 0x00801c16, 0x00511411, 0x002510e, 0x00477, 0x00477, 0x00477, 0x00151616, 0x00414343, 0x005b5d5d, 0x00626363, 0x004e5050, 0x001c1d1d, 0x00477, 0x00a99, 0x00731a15, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004a4747, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x004c494a, 0x007c797a, 0x00aaa8a8, 0x00d9d8d9, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00777, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00772522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00731a15, 0x00588, 0x00e0e1e1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aaabab, 0x00477, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009e2822, 0x00712522, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00941f19, 0x0026fe, 0x00477, 0x00699, 0x00303232, 0x00535555, 0x00626363, 0x00626363, 0x00626464, 0x00717373, 0x00717373, 0x00717373, 0x00797b7b, 0x00818383, 0x00818383, 0x00818383, 0x00919292, 0x00919292, 0x00919292, 0x00999a9a, 0x00a1a2a2, 0x00a1a2a2, 0x00a1a2a2, 0x00b0b1b1, 0x00b0b1b1, 0x00b0b1b1, 0x00b7b8b8, 0x00c0c1c1, 0x00c0c1c1, 0x00c0c1c1, 0x00cfcfcf, 0x00d0d0d0, 0x00d0d0d0, 0x00c4c5c5, 0x00979898, 0x00484a4a, 0x00477, 0x0018dc, 0x00ae231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02c22, 0x00b5251d, 0x00851d17, 0x00591512, 0x003711f, 0x001dfe, 0x001aed, 0x002410e, 0x004d1310, 0x00871d17, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22c23, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbb, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00676465, 0x004e4b4c, 0x006f6c6d, 0x009d9b9b, 0x00cccbcb, 0x00f7f7f7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00462221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00577, 0x00656767, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aeafaf, 0x009bb, 0x003111f, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x007f2622, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2820, 0x00351110, 0x00477, 0x002b2d2d, 0x009a9b9b, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9caca, 0x00282a2a, 0x00999, 0x00ab231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008c8a8b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00477, 0x00a2a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00787a7a, 0x00588, 0x003111f, 0x00db2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ae2923, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ad231c, 0x0010bb, 0x00f1110, 0x00989999, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x002a2c2c, 0x0013cb, 0x00db2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x008e2722, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x003611f, 0x00588, 0x007b7d7d, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00a0a1a1, 0x00232524, 0x00477, 0x005a1612, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ce2c23, 0x00d52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00999, 0x00272929, 0x00dadada, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cdcdcd, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00312020, 0x00582321, 0x00802622, 0x00a72923, 0x00cf2c23, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00972822, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00585555, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c42b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x004f1411, 0x00477, 0x001b1c1c, 0x006e7070, 0x00b3b4b4, 0x00cdcdcd, 0x00dadada, 0x00c4c5c5, 0x009fa0a0, 0x005e6060, 0x00161717, 0x00477, 0x002d10f, 0x00b1241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00c12b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2820, 0x0012cb, 0x00252727, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c4e4e, 0x0014cb, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00d52c23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00522221, 0x00762522, 0x00912722, 0x009e2822, 0x00a22823, 0x00912722, 0x00782522, 0x004f2221, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a5a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003f2121, 0x00e12d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x00411310, 0x00577, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x0017dc, 0x00531411, 0x00b1241c, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x009a2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x002c10e, 0x00101111, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b2b3b3, 0x00477, 0x00961f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2b2c, 0x00e9e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00af231c, 0x00971f19, 0x00982019, 0x00ab231c, 0x00c7271f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a32823, 0x00672421, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00531512, 0x00477, 0x00aeafaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00212323, 0x003711f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00676465, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00cc2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00602421, 0x00402121, 0x00e22d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00831c17, 0x00477, 0x007b7d7d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00858686, 0x00477, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003c2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b6b4b5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00812622, 0x00df2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c72b23, 0x006f2521, 0x00281f20, 0x002d2020, 0x00cc2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00688, 0x00484a4a, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e8e8, 0x008aa, 0x00611612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008d2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00383435, 0x00f1f1f1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00373334, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x006a2421, 0x00a72923, 0x00d62c24, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00d82c24, 0x00b32a23, 0x00832622, 0x00452221, 0x00231f20, 0x00231f20, 0x00241f20, 0x00aa2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22920, 0x0016cc, 0x00232525, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00585a5a, 0x00daa, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00dc2d24, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00787576, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00272324, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00666, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00302020, 0x00302020, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007f2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x003211f, 0x00dff, 0x00d0d0d0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bfc0c0, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00888, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00c6c5c5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c7c6c6, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00582321, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005b1612, 0x00477, 0x00a4a6a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x002b2d2d, 0x002c10e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc2a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00191616, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00423f3f, 0x00f7f7f7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006d6b6b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2120, 0x00de2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008b1d18, 0x00477, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00919292, 0x00477, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00442121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001d191a, 0x00161314, 0x00dbc, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00898787, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bfbebe, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00c62b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b7251d, 0x00999, 0x00414343, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00dff, 0x00561511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00545, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00d4d3d3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bfbebe, 0x002c2829, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00777, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72a21, 0x001adc, 0x001d1f1f, 0x00e8e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00636565, 0x00999, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004e4b4c, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00d2d1d2, 0x00726f70, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00141213, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00782522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x003912f, 0x00acc, 0x00c9caca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00477, 0x00801c16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00722522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00999798, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00c4c3c4, 0x00969494, 0x00666464, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00171415, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00522221, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00641713, 0x00477, 0x009c9d9d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00363838, 0x0022fd, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00e1e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfbfc, 0x00d3d2d2, 0x00a5a4a4, 0x00767374, 0x00464344, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x00db2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00951f19, 0x00477, 0x00666868, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009e9f9f, 0x00477, 0x00aa231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c595a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e2e2, 0x00b4b3b3, 0x00848283, 0x00555253, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00c02b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bd261e, 0x00ba9, 0x00393b3b, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00131414, 0x004a1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aaa9a9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00c3c2c2, 0x00949293, 0x00646162, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009a2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00db2b22, 0x0020ed, 0x001a1b1b, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00707272, 0x00688, 0x00d22920, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00989, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312d2e, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00d1d0d1, 0x00a3a1a1, 0x00727070, 0x00454142, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x003f1210, 0x008aa, 0x00c1c2c2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x00477, 0x00751a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00696667, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x00b1b0b0, 0x00838181, 0x00535051, 0x00292526, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c2221, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d1814, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00dcdcdc, 0x00d0d0d0, 0x00d0d0d0, 0x00d0d0d0, 0x00d0d0d0, 0x00dedede, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00424444, 0x0019dc, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ce2c23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b8889, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efeeee, 0x00c1c0c0, 0x00918f90, 0x00625f60, 0x00333031, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332020, 0x00d62c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009e211a, 0x00477, 0x005e6060, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d2d2d2, 0x00646666, 0x00626363, 0x00626363, 0x00525454, 0x00525454, 0x00505252, 0x00424444, 0x00424444, 0x003d3f3f, 0x00323535, 0x00323434, 0x002a2b2b, 0x00222424, 0x00222323, 0x00181919, 0x00171919, 0x00cbcbcb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00444646, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aaabab, 0x00477, 0x009f211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00562321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dcc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00605d5e, 0x00d9d8d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0cfcf, 0x00a09e9f, 0x00716e6f, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00b12a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00daa, 0x00323434, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00252727, 0x00898, 0x0018ed, 0x0021fe, 0x0021fe, 0x002a1110, 0x002f11f, 0x002f11f, 0x003b1311, 0x003e11e, 0x003e11e, 0x004c1310, 0x004c1310, 0x004f1410, 0x0015a9, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989999, 0x00477, 0x00591512, 0x00961f19, 0x00961f19, 0x00a5221b, 0x009f211a, 0x00531411, 0x00477, 0x00dadada, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x001b1c1c, 0x003e1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a22822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x004f4c4d, 0x00838181, 0x009e9c9c, 0x00999798, 0x007e7b7c, 0x00514e4e, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00464344, 0x00767374, 0x00a19fa0, 0x00bfbebe, 0x00c0bfbf, 0x009f9d9e, 0x004c4849, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x0024fe, 0x00151616, 0x00dedede, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004d4f4f, 0x00688, 0x00ad231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009f211a, 0x00477, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cbcbcb, 0x00acc, 0x00391210, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003811f, 0x00181919, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007b7d7d, 0x00477, 0x00ce2920, 0x00ee2e24, 0x00ee2e24, 0x00d82c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003a3738, 0x00696667, 0x00979696, 0x00c6c5c5, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00666464, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004d1411, 0x00699, 0x00babbbb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00838484, 0x00477, 0x007c1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c6271f, 0x00eba, 0x00303232, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00222424, 0x0017dc, 0x00d52a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c1e18, 0x00477, 0x00939494, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cecece, 0x00477, 0x00931f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2a2b, 0x005c595a, 0x008b8889, 0x00b9b8b8, 0x00e9e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e5e5, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009d211a, 0x00477, 0x007f8181, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00588, 0x004b1411, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x0026fe, 0x00141515, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004c4e4e, 0x00688, 0x00b1241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c2271f, 0x00b99, 0x00404242, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00477, 0x00791b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00272324, 0x00504d4d, 0x007e7b7c, 0x00acabab, 0x00dcdbdb, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00413e3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x002610e, 0x00282a2a, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dfdfdf, 0x00151616, 0x0024fe, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00892722, 0x007c2622, 0x00b52a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x004b1411, 0x00588, 0x00b7b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00848585, 0x00477, 0x007d1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x0025fe, 0x00151616, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x00477, 0x007b1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00716e6f, 0x00a09e9f, 0x00cfcece, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2020, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00b2241d, 0x00477, 0x009b9c9c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00343636, 0x00daa, 0x00c4271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b72a23, 0x00251f20, 0x00231f20, 0x00442121, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007a1b16, 0x00477, 0x00848585, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bcbdbd, 0x00699, 0x00481311, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00541512, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcfcf, 0x00477, 0x00961f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1818, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00363233, 0x00646162, 0x00939192, 0x00c2c1c1, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00588, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d62c24, 0x00322020, 0x00231f20, 0x002e2020, 0x00d02c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a9231b, 0x00577, 0x00505252, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00191a1a, 0x0022fd, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00757777, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008d8e8e, 0x00477, 0x00c9281f, 0x00ee2e24, 0x00ee2e24, 0x00d62c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c292a, 0x00575454, 0x00878585, 0x00b5b3b4, 0x00e3e3e3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00692421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1310, 0x00262828, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009b9c9c, 0x00477, 0x00681813, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x004c2221, 0x00231f20, 0x00241f20, 0x00af2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2820, 0x0013cb, 0x00282a2a, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x003c3e3e, 0x00a99, 0x00be261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00baa, 0x003b3d3d, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x002e3030, 0x002910e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a42923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00101, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x004b4748, 0x007a7878, 0x00a8a6a7, 0x00d7d7d7, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00434, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003e11e, 0x003d3f3f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cacaca, 0x00acc, 0x003912f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00652421, 0x006f2522, 0x009a2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x002d10f, 0x00f1010, 0x00d5d5d5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00727474, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0028fe, 0x00151616, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ef, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003e3a3b, 0x006d6b6b, 0x009b999a, 0x00cac9ca, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006c2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004712f, 0x00292b2b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00222424, 0x0019dc, 0x00d62a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00551512, 0x00477, 0x00abacac, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x00591612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00581512, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x001d1f1f, 0x0025fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332f30, 0x00605d5e, 0x008e8c8c, 0x00bebdbd, 0x00ececec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00532321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006e1914, 0x00799, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00616262, 0x00477, 0x00ae231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00861d17, 0x00477, 0x00767878, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dadada, 0x00101111, 0x002d10f, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00921f19, 0x00477, 0x00757777, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00565858, 0x00577, 0x00b3241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00802622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00535051, 0x00828080, 0x00b1b0b0, 0x00dfdedf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00b3241d, 0x00477, 0x009c9d9d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x00477, 0x00651713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b2241d, 0x00788, 0x00454747, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x002f3131, 0x00fba, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00baa, 0x00383a3a, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9b9b, 0x00477, 0x00731a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c595a, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x0022fd, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bebfbf, 0x00477, 0x002f10e, 0x00531411, 0x005b1612, 0x005b1612, 0x00591512, 0x004c1310, 0x004c1310, 0x004c1310, 0x004111f, 0x003e11e, 0x003e12f, 0x00391311, 0x0011bb, 0x00212323, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00606161, 0x00477, 0x00a1211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0028fe, 0x00141515, 0x00dfdfdf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d4d4d4, 0x00cee, 0x003912f, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00592321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00712522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007b1b16, 0x00477, 0x00d4d4d4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00868787, 0x00373939, 0x00222323, 0x00161717, 0x00212121, 0x00222424, 0x00222424, 0x002a2b2b, 0x00323434, 0x00323535, 0x00343737, 0x00424444, 0x00424444, 0x00424444, 0x00cbcbcb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9b9b, 0x00477, 0x006b1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005b1612, 0x00477, 0x00afb0b0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x002e3030, 0x0012cb, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00787677, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00577, 0x00727474, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00acc, 0x00391210, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00961f19, 0x00477, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00686a6a, 0x00477, 0x00a0211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00656, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2a2a, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009f2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00461310, 0x00171818, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00232525, 0x0018dc, 0x00d52a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c7271f, 0x00daa, 0x00383a3a, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x00611713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171414, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00969494, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00502221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a2211b, 0x00477, 0x00abacac, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004d4f4f, 0x00688, 0x00b1241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x002b10e, 0x00141515, 0x00dfdfdf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x00141515, 0x002b10e, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201d1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00474445, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00545, 0x00ecc, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cc2b23, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x0017dc, 0x00494b4b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00868787, 0x00477, 0x007d1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005b1612, 0x00477, 0x00aeafaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003d3f3f, 0x00baa, 0x00c5271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a32823, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b3b2b2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x002c292a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00baa, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x0010ff, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007e2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d1814, 0x00588, 0x00e0e1e1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbebe, 0x00699, 0x00481311, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00961f19, 0x00477, 0x006d6f6f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x008e1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b9b8b8, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00171415, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332020, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00c7281f, 0x00477, 0x00818383, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e4e5e5, 0x00191a1a, 0x0022fe, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00daa, 0x00353737, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bebfbf, 0x00699, 0x004f1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x004a2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00cfcece, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00464243, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00101, 0x00121011, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ab2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003812f, 0x00212323, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x003d3f3f, 0x00a99, 0x00be261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x002d10f, 0x00121313, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x001d1e1e, 0x001fed, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00706d6e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x005d5a5b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00477, 0x00babbbb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00727474, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005f1713, 0x00477, 0x00acadad, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004d4f4f, 0x00788, 0x00b8251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b22a23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00e4e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00aaa8a8, 0x003a3738, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x00fbb, 0x00585a5a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x00581512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a201a, 0x00477, 0x006d6f6f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00909191, 0x00477, 0x007c1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2d24, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008c8a8b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c2c1c1, 0x00939192, 0x00615e5f, 0x002c2829, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00211e1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008a2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e1612, 0x00acc, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dadada, 0x00101111, 0x002c10e, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00eba, 0x00353737, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cecece, 0x00acc, 0x003f1310, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00572321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00383435, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0cfcf, 0x00a2a0a1, 0x00726f70, 0x00434040, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2120, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ba251e, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x002f3131, 0x00fba, 0x00ca2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x002e10f, 0x00101111, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00272929, 0x0016cc, 0x00d62a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aaa8a8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dedede, 0x00b0aeaf, 0x007f7d7e, 0x00524e4f, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00271f20, 0x00432121, 0x00602421, 0x006f2522, 0x006f2522, 0x006f2522, 0x00632421, 0x005a2321, 0x00502221, 0x00452221, 0x003b2120, 0x00302020, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a10e, 0x002f3131, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00606161, 0x00477, 0x00a0211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00781a15, 0x00477, 0x00a5a6a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00606161, 0x00477, 0x00a8221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c02b23, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00423f3f, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ececec, 0x00bdbcbd, 0x008e8c8c, 0x005f5c5d, 0x00312d2e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x006e2521, 0x00af2923, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00477, 0x00c9caca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9b9b, 0x00477, 0x006a1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x00daa, 0x004c4e4e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a3a5a5, 0x00477, 0x00691814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x003b2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a3a1a1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cccbcb, 0x009c9a9a, 0x006d6b6b, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00712522, 0x00db2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00db2b22, 0x00999, 0x00666868, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00acc, 0x003912f, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00c6c7c7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x00101111, 0x003011f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00652421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00dad9d9, 0x00aaa8a8, 0x007c797a, 0x004c494a, 0x00262323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00b12923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004f1411, 0x00111212, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00232525, 0x0018dc, 0x00d42a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1411, 0x001e2020, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00353737, 0x00eba, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00555, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171415, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004b4748, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e7e7, 0x00b8b7b7, 0x008a8888, 0x005a5758, 0x002e2a2b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2020, 0x00c32b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x009e211a, 0x005c1612, 0x00341110, 0x0017dc, 0x0012cb, 0x0018ed, 0x002410f, 0x003011f, 0x003e12f, 0x004a1310, 0x00561511, 0x00621713, 0x006e1914, 0x00791b16, 0x00871d17, 0x00931f19, 0x009f211a, 0x00701914, 0x00477, 0x00a0a1a1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004d4f4f, 0x00688, 0x00b0241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a11f, 0x004e5050, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00747676, 0x00477, 0x00971f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00d82c24, 0x00cd2c23, 0x00c32b23, 0x00b92a23, 0x00ae2923, 0x00a22823, 0x00962822, 0x00812622, 0x005e2321, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00656363, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00c6c5c5, 0x00979696, 0x00696667, 0x00393637, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00af2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x008f1e18, 0x001add, 0x00477, 0x00e1010, 0x00424444, 0x005e6060, 0x00626363, 0x00626363, 0x00545656, 0x00474949, 0x003b3d3d, 0x002e3030, 0x00212222, 0x00131414, 0x00588, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x003e4040, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00868787, 0x00477, 0x00631713, 0x00da2b21, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002710f, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b6b7b7, 0x00477, 0x00571512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00b32a23, 0x005c2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00625f60, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00d4d3d3, 0x00a6a5a5, 0x00777475, 0x00474445, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322e2f, 0x005f5c5d, 0x008b8889, 0x00a7a5a6, 0x00a5a4a4, 0x007c797a, 0x002d2a2a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006a2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x004f1411, 0x00477, 0x00363838, 0x00b0b1b1, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00e8e9e9, 0x00dcdcdc, 0x00d0d0d0, 0x00c0c1c1, 0x00b3b4b4, 0x00a6a7a7, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbebe, 0x00699, 0x00477, 0x00477, 0x00477, 0x00477, 0x00688, 0x0012cb, 0x0021fe, 0x002d1110, 0x00391210, 0x004312f, 0x0013a9, 0x00202222, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x00191a1a, 0x0024fe, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b52a23, 0x00362020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00363233, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e2e2, 0x00b4b3b3, 0x00848283, 0x00565354, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00535051, 0x00817f7f, 0x00b0afaf, 0x00dfdedf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e6e7, 0x00403d3e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e1613, 0x00477, 0x00757777, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d3d3d3, 0x00b6b7b7, 0x00a9aaaa, 0x009d9e9e, 0x00919292, 0x00818383, 0x00747676, 0x00676969, 0x005b5d5d, 0x004e5050, 0x00424444, 0x00323535, 0x00252626, 0x00191b1b, 0x00c1c2c2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x002e3131, 0x00477, 0x0019dc, 0x00341210, 0x004011e, 0x004c1310, 0x005a1512, 0x00661713, 0x00721915, 0x007e1b16, 0x008a1d18, 0x00961f19, 0x00a5221b, 0x00b1241c, 0x00bc261e, 0x00c8281f, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00baa, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009b999a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c2c1c1, 0x00939192, 0x00646162, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00464243, 0x00747272, 0x00a4a2a2, 0x00d2d1d2, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c3c2c2, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b4241d, 0x00477, 0x00676969, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x006b6d6d, 0x005f6060, 0x00525454, 0x00424444, 0x00353838, 0x00282a2a, 0x001c1d1d, 0x00101111, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00eba, 0x003d1210, 0x008a1d18, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00828080, 0x00d9d8d9, 0x00f8f8f8, 0x00f1f1f1, 0x00d0cfcf, 0x00a2a0a1, 0x00726f70, 0x00434040, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00393536, 0x00686566, 0x00979595, 0x00c4c3c4, 0x00f3f3f3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00312d2e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008e2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00511511, 0x00111212, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00e2e3e3, 0x00d6d6d6, 0x00c9caca, 0x00bcbdbd, 0x00afb0b0, 0x00a1a2a2, 0x008b8c8c, 0x006a6c6c, 0x00272929, 0x00477, 0x0019dc, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00992822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2a2b, 0x005b5859, 0x008a8888, 0x00b8b7b7, 0x00e8e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00494646, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b42a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0012cb, 0x005e6060, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00222424, 0x00daa, 0x00c8281f, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x004e4b4c, 0x007d7a7b, 0x00abaaaa, 0x00dbdada, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00d62a21, 0x00477, 0x008b8c8c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dfdfdf, 0x00cee, 0x004b1311, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00423f3f, 0x00706d6e, 0x009e9d9d, 0x00cecdcd, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d52c24, 0x00ee2e24, 0x00ee2e24, 0x00d12920, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00656767, 0x00999, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00942722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00636061, 0x00929091, 0x00c1c0c0, 0x00efeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cc2b23, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00577, 0x007b7d7d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00909191, 0x00477, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00a22823, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00565354, 0x00858384, 0x00b4b3b3, 0x00e3e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ae2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002810f, 0x003f4141, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008d8e8e, 0x00477, 0x00d72a21, 0x00ee2e24, 0x00ee2e24, 0x00a22823, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00494646, 0x00787677, 0x00a7a5a6, 0x00d6d5d5, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00882622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00701914, 0x00588, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00fba, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00211e1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c3839, 0x006c6a6a, 0x009a9899, 0x00c9c8c8, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00492221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c2271f, 0x00477, 0x008b8c8c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00252727, 0x00411310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f2521, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00504d4d, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d22c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002e10f, 0x002c2e2e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dfdfdf, 0x00477, 0x00801c16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cbcacb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00851d17, 0x00477, 0x00cacaca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009b9c9c, 0x00477, 0x00bf261e, 0x00ee2e24, 0x00ee2e24, 0x00d62c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006b6969, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92a21, 0x00898, 0x006b6d6d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x0015cc, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x009f2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00e3e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004b1311, 0x00151616, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00151616, 0x00521411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbb, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a3211b, 0x00477, 0x00acadad, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cbcbcb, 0x00477, 0x00911f19, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x0015cc, 0x004e5050, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00878888, 0x00477, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00c62b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a4a3a3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00661713, 0x00799, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00434545, 0x0024fe, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00484546, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00562321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00be261e, 0x00477, 0x008d8e8e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00acc, 0x00641713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00582321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c1c0c0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0025fd, 0x002e3030, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00477, 0x00a3211b, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00656, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00605d5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008e1e18, 0x00477, 0x00444646, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00747676, 0x00688, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00b72a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171415, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00dad9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00962822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008e1e18, 0x00477, 0x00444646, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00303232, 0x003711f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00802622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ff, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007e7b7c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00972822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00851d17, 0x00477, 0x00444646, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e9e9, 0x00477, 0x00761a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00492221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302c2d, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00801c16, 0x00477, 0x00444646, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a4a6a6, 0x00477, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00999798, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00bfbebe, 0x00908e8e, 0x00838181, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00801c16, 0x00477, 0x004f5151, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626363, 0x00eba, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00a72923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00777, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cccbcb, 0x009d9b9b, 0x006e6b6c, 0x003f3c3d, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dbc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007b2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00801c16, 0x00477, 0x00505252, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00151616, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00702522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a5a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00d9d8d9, 0x00a9a7a8, 0x007b7979, 0x004c494a, 0x00262323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00632421, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00831c17, 0x00477, 0x00505252, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x009e211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c292a, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e5e5, 0x00b7b5b6, 0x00888686, 0x00595657, 0x002c292a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00477, 0x004b4d4d, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00292b2b, 0x0022fd, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00c32b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00615e5f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00c3c2c3, 0x00959393, 0x00656363, 0x00383435, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2020, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ad231c, 0x00788, 0x003d3f3f, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x007c7e7e, 0x00898a8a, 0x00969797, 0x00a2a4a4, 0x00b0b1b1, 0x00bfc0c0, 0x00cccccc, 0x00d9d9d9, 0x00e5e6e6, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00646666, 0x00477, 0x00a0211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00742522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151313, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c797a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0d0d0, 0x00a2a0a1, 0x00727070, 0x00444041, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009b2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2820, 0x0011bb, 0x00282a2a, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00262827, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00131414, 0x00202121, 0x002d2f2f, 0x003a3c3c, 0x00474949, 0x00545656, 0x00626363, 0x00707272, 0x007d7f7f, 0x008a8b8b, 0x00979898, 0x00a3a5a5, 0x00b0b1b1, 0x00c0c1c1, 0x00cdcdcd, 0x00dadada, 0x00e7e8e8, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00616262, 0x00477, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72c24, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00676465, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dddddd, 0x00afadae, 0x007f7d7e, 0x00514e4e, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00512221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x002e10e, 0x00f1010, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x002f3131, 0x00ba9, 0x00b0241c, 0x00df2c22, 0x00d22920, 0x00c6271f, 0x00ba251e, 0x00ae231c, 0x00a2211b, 0x00961f19, 0x00871d17, 0x007b1b16, 0x006f1914, 0x00631713, 0x00571511, 0x004b1310, 0x003e11f, 0x003011f, 0x002410f, 0x0018ed, 0x00caa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00588, 0x00131414, 0x00212222, 0x002e3030, 0x003b3d3d, 0x00484a4a, 0x00555757, 0x00626363, 0x00717373, 0x007e8080, 0x008b8c8c, 0x00989999, 0x00a4a6a6, 0x00b2b3b3, 0x00c0c1c1, 0x00cfcfcf, 0x00dcdcdc, 0x00e8e9e9, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00989999, 0x00202222, 0x00477, 0x00681813, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00682421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaeaea, 0x00bbbaba, 0x008c8a8b, 0x005f5c5c, 0x00302c2d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00721915, 0x00477, 0x00a7a8a8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00393b3b, 0x00688, 0x00a6221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00df2c22, 0x00d12920, 0x00c5271f, 0x00b9251d, 0x00ad231c, 0x00a1211a, 0x00951f19, 0x00871d17, 0x00791b16, 0x006e1914, 0x00621713, 0x00561511, 0x004a1310, 0x003e12f, 0x002f11f, 0x002310e, 0x0018dd, 0x00baa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00699, 0x00131414, 0x00222323, 0x002f3131, 0x003c3e3e, 0x00494b4b, 0x00525454, 0x004b4d4d, 0x00292b2b, 0x00699, 0x00477, 0x002c10f, 0x00ad231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a52923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00524e4f, 0x00e5e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00c8c7c7, 0x00999798, 0x006b6969, 0x003b3838, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abaaaa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005e2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c7271f, 0x00788, 0x00545656, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00444646, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x00de2b22, 0x00d12920, 0x00c4271f, 0x00b8251d, 0x00ab231c, 0x009f211a, 0x00931f19, 0x00871d17, 0x00791a15, 0x006d1814, 0x00611612, 0x00551411, 0x00491210, 0x003d12f, 0x002f11f, 0x002f1311, 0x002f11f, 0x00471310, 0x00721915, 0x00b9251d, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ba2a23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x006b6969, 0x00999798, 0x009f9d9e, 0x00989697, 0x00777475, 0x00484546, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b52a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1411, 0x00cee, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00505252, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a92923, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171414, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201d1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00959393, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00352020, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2820, 0x00477, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x005e6060, 0x00477, 0x007c1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00812622, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2020, 0x00392120, 0x00442121, 0x004e2221, 0x00582321, 0x00632421, 0x006f2522, 0x007a2522, 0x00842622, 0x008e2722, 0x00992822, 0x00a32823, 0x00af2923, 0x00ba2a23, 0x00c52b23, 0x00cf2c23, 0x00d92c24, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00712522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a9a7a8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbbbc, 0x00262323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a89, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2521, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791b16, 0x00477, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006c6e6e, 0x00477, 0x006d1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008e2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00392120, 0x00442121, 0x004f2221, 0x00592321, 0x00632421, 0x006f2522, 0x007b2522, 0x00852622, 0x008f2722, 0x009a2822, 0x00a42923, 0x00af2923, 0x00bb2a23, 0x00c52b23, 0x00d02c23, 0x00da2d24, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x007f2622, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00ececec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b2b1b1, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009b2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003511f, 0x00343636, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007d7f7f, 0x00477, 0x005e1613, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009b2822, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302020, 0x003a2120, 0x00442121, 0x004f2221, 0x005a2321, 0x00642421, 0x006f2522, 0x007b2622, 0x00862622, 0x00902722, 0x009a2822, 0x00a22823, 0x009a2822, 0x00892722, 0x006b2421, 0x003d2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00464344, 0x00d7d7d7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e6e6, 0x00767374, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bd2a23, 0x00ee2e24, 0x00ee2e24, 0x00e92d23, 0x00a99, 0x006d6f6f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008d8e8e, 0x00477, 0x00511512, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a72923, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x006b6869, 0x00acabab, 0x00c5c4c4, 0x00c3c2c2, 0x00a4a3a3, 0x00676465, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00d82a21, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009d9e9e, 0x00477, 0x00441310, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001a1717, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00555, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d52c24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aaabab, 0x00699, 0x00391210, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc2a23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00577, 0x00757777, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00babbbb, 0x009bb, 0x002e10f, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312d2e, 0x003a3738, 0x00272324, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b02923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003411f, 0x00323434, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d3d3d3, 0x00f1111, 0x0023fd, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac2923, 0x00912722, 0x00872622, 0x007c2622, 0x006f2522, 0x00652421, 0x005b2321, 0x00502221, 0x00462221, 0x003c2120, 0x00302020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00fde, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00333031, 0x00625f60, 0x00918f8f, 0x00c0bfbf, 0x00eeedee, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00acabab, 0x00302c2d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00812622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007b1b16, 0x00477, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x002a2c2c, 0x0014cb, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d24, 0x00dc2d24, 0x00d12c23, 0x00c72b23, 0x00bc2a23, 0x00b02923, 0x00a62923, 0x009b2822, 0x00912722, 0x00872622, 0x007c2622, 0x006f2522, 0x00652421, 0x005b2321, 0x00512221, 0x00472221, 0x003c2121, 0x00302020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00edd, 0x00151313, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00555253, 0x00848182, 0x00b2b1b1, 0x00e1e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c6c5c5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a7a7, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00dc2d24, 0x00d22c23, 0x00c82b23, 0x00bc2a23, 0x00b12923, 0x00a62923, 0x009c2822, 0x00922722, 0x00872622, 0x007c2622, 0x00702522, 0x00662421, 0x005c2321, 0x00512221, 0x00472221, 0x003c2121, 0x00302020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00191616, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00484546, 0x00777475, 0x00a5a4a4, 0x00d4d3d3, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00535051, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cb2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002d10f, 0x00353737, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a3a5a5, 0x00477, 0x003b12f, 0x00711915, 0x008c1e18, 0x009e211a, 0x00ab231c, 0x00b7251d, 0x00c3271f, 0x00d12920, 0x00dd2b22, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00dc2d24, 0x00d22c23, 0x00c92b23, 0x00bc2a23, 0x00b12a23, 0x00a72923, 0x009d2822, 0x008e2722, 0x00752522, 0x004b2221, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00111010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003a3738, 0x006a6768, 0x00989697, 0x00c7c6c6, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00858384, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171414, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007b1b16, 0x00477, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00878888, 0x002b2d2d, 0x00699, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00b99, 0x0017dc, 0x0023fe, 0x002f11f, 0x003c12f, 0x004812f, 0x00541411, 0x00601612, 0x006c1814, 0x00791a15, 0x00861d17, 0x00921f19, 0x009e211a, 0x00aa231c, 0x00b6251d, 0x00c2271f, 0x00d12920, 0x00dd2b22, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22c23, 0x00762522, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2b2c, 0x005d5a5b, 0x008b898a, 0x00bab9b9, 0x00e9e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00e1e2e2, 0x00cecece, 0x00c0c1c1, 0x00b2b3b3, 0x00a5a6a6, 0x00999a9a, 0x008c8d8d, 0x007f8181, 0x00717373, 0x00626464, 0x00565858, 0x00494b4b, 0x003c3e3e, 0x002f3131, 0x00222323, 0x00131414, 0x00699, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00a99, 0x0016dc, 0x0022fe, 0x002f11f, 0x003c12f, 0x004812f, 0x00541411, 0x00601612, 0x006c1814, 0x00791a15, 0x00861d17, 0x00921f19, 0x009e211a, 0x00a9231b, 0x00b5251d, 0x00c2271f, 0x00d02920, 0x00dc2b22, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c42b23, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00272324, 0x00504d4d, 0x007e7c7d, 0x00adacac, 0x00dcdcdc, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cb2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002d10f, 0x00353737, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00e8e9e9, 0x00dcdcdc, 0x00cfcfcf, 0x00c0c1c1, 0x00b2b3b3, 0x00a5a6a6, 0x009a9b9b, 0x008d8e8e, 0x00808282, 0x00717373, 0x00636565, 0x00575959, 0x004a4c4c, 0x003d3f3f, 0x00303232, 0x00222323, 0x00141515, 0x00799, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00999, 0x0015dc, 0x0021fe, 0x002f1110, 0x003b12f, 0x004712f, 0x00531411, 0x005f1612, 0x006b1814, 0x00791a15, 0x00851d17, 0x00911f19, 0x009d211a, 0x00a9231b, 0x00b5251d, 0x00c2271f, 0x00d02920, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d52c23, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00726f70, 0x00a09e9f, 0x00d0cfcf, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791b16, 0x00477, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00e9eaea, 0x00dddddd, 0x00d0d0d0, 0x00c0c1c1, 0x00b3b4b4, 0x00a6a7a7, 0x009a9b9b, 0x008d8e8e, 0x00818383, 0x00717373, 0x00646666, 0x00585a5a, 0x004b4d4d, 0x003e4040, 0x00313333, 0x00222323, 0x00151616, 0x008aa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x0023fe, 0x00741a15, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bd2a23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00363233, 0x00646162, 0x00949293, 0x00c2c1c1, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00eaebeb, 0x00dedede, 0x00d0d0d0, 0x00c1c2c2, 0x00b4b5b5, 0x00a7a8a8, 0x009b9c9c, 0x00818383, 0x00454747, 0x00477, 0x001ced, 0x00c5271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c292a, 0x00575454, 0x00878585, 0x00b5b3b4, 0x00e3e3e3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cb2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0028fe, 0x00353737, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c3c4c4, 0x00181919, 0x001ded, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00c42b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1818, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x004a4747, 0x00797777, 0x00a8a6a7, 0x00d6d6d6, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00761a15, 0x00477, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b7b8b8, 0x00477, 0x007f1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x006c6a6a, 0x009b999a, 0x00cac9c9, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00303232, 0x00391210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00545152, 0x00acabab, 0x00e9e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002810e, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00636565, 0x0014cc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007a2522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302c2d, 0x00b4b3b3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00761a15, 0x00477, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x0013cc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00d0cfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00424444, 0x002f11f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00732522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00918f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002810e, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eceded, 0x00acc, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9899, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00761a15, 0x00477, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00808282, 0x00477, 0x00ba251e, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181616, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00555253, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008a8888, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d8d8d8, 0x00bdd, 0x00471411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a82923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f6c6d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00615e5f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151313, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002810e, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00303232, 0x00fba, 0x00d02920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00512221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeedee, 0x002a2627, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00477, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x004d4f4f, 0x00477, 0x00a2211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b22a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007e7c7d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00626363, 0x00477, 0x007f1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x003c2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a5a4a4, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0023fe, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00757777, 0x00477, 0x006a1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e6e7, 0x00777475, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008e2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00588, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008e8f8f, 0x00477, 0x00561511, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00902722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00c7c6c6, 0x00979696, 0x005f5c5c, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x00477, 0x00949595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a1a3a3, 0x00477, 0x00451310, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a72923, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00d5d4d4, 0x00a6a5a5, 0x00777475, 0x00484546, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0023fe, 0x003f4141, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b5b6b6, 0x00799, 0x003611f, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b52a23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e2e1e1, 0x00b4b3b3, 0x00848283, 0x00565354, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00588, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x00dff, 0x002910e, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c32b23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00c2c1c1, 0x00929091, 0x00646162, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x00477, 0x00949595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d3d3d3, 0x00141515, 0x001ded, 0x00d42a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ce2c23, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00d0cfcf, 0x00a09e9f, 0x00716e6f, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0023fe, 0x003f4141, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x001e2020, 0x0015cc, 0x00c7281f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x003a2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dcdcdc, 0x00aeacad, 0x007e7c7d, 0x00514e4e, 0x00272324, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1a1b, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00741a15, 0x00477, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00292b2b, 0x00caa, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02d24, 0x00442121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009e9c9c, 0x00302c2d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004b2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00a99, 0x004d4f4f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00373939, 0x00999, 0x00ab231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00502221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00706d6e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d9d8d9, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c82b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007d1b16, 0x00477, 0x00838484, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00474949, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x005d2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00565354, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aaa8a8, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00672421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00501411, 0x00477, 0x00717373, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00595b5b, 0x00477, 0x00861d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00e9e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006f6c6d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dbc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00ba2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x005f1713, 0x00477, 0x002b2d2d, 0x00acadad, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006e7070, 0x00477, 0x00721915, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007d2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00636061, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeedee, 0x00c0bfbf, 0x00939192, 0x00646162, 0x00383435, 0x00bbbaba, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x00dc2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a0211a, 0x0020fe, 0x00477, 0x001a1b1b, 0x005c5e5e, 0x00858686, 0x009fa0a0, 0x00abacac, 0x00b8b9b9, 0x00c6c7c7, 0x00d3d3d3, 0x00e0e0e0, 0x00efefef, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00838484, 0x00477, 0x005e1613, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00baa, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00656, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004a4747, 0x00a19fa0, 0x00bebdbd, 0x00bab9b9, 0x00989697, 0x006c6a6a, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004d4a4b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x002a2627, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92d23, 0x009e211a, 0x004f1411, 0x0016dc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00eff, 0x001a1b1b, 0x00272828, 0x00343737, 0x00424444, 0x00525454, 0x005f6060, 0x006b6d6d, 0x00787a7a, 0x00858686, 0x00939494, 0x00a1a2a2, 0x00afb0b0, 0x00bcbdbd, 0x00c9caca, 0x00d7d7d7, 0x00e3e4e4, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9b9b, 0x00477, 0x004c1411, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x004f4c4d, 0x00787677, 0x00848182, 0x00585555, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00cc2820, 0x00c0261e, 0x00b3241d, 0x00a6221b, 0x00992019, 0x008d1e18, 0x00811c16, 0x00751a15, 0x00681813, 0x005b1612, 0x004d1310, 0x004111f, 0x00361210, 0x002911f, 0x001dfe, 0x0011cb, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00111212, 0x001e1f1f, 0x002b2d2c, 0x00383b3b, 0x00454747, 0x00535555, 0x00626363, 0x006f7171, 0x007c7e7e, 0x00898a8a, 0x00979898, 0x00a3a5a5, 0x00b0b1b1, 0x00c0c1c1, 0x00cdcdcd, 0x00dbdbdb, 0x00e7e8e8, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00699, 0x003c1210, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00af2923, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006f6c6d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00413e3f, 0x006f6c6d, 0x009e9d9d, 0x00cdcccc, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0aeaf, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00992822, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00d42a21, 0x00c8281f, 0x00bc261e, 0x00b1241c, 0x00a5221b, 0x00961f19, 0x00891d17, 0x007d1b16, 0x00711915, 0x00651713, 0x00581511, 0x004c1310, 0x003e11f, 0x003211f, 0x002610f, 0x0019ed, 0x00daa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00588, 0x00131414, 0x00222323, 0x002f3131, 0x003c3e3e, 0x009bb, 0x002d10e, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00be2a23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00333031, 0x00615e5f, 0x00918f8f, 0x00bfbebe, 0x00eeedee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00737171, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00442121, 0x00a42923, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00df2c22, 0x00d22920, 0x00c5271f, 0x00b9251d, 0x00ad231c, 0x00a1211a, 0x00951f19, 0x00871d17, 0x00791b16, 0x006e1914, 0x00621713, 0x00561511, 0x00491210, 0x003d12f, 0x003d12f, 0x00d72a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2b23, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x002a2627, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00535051, 0x00838181, 0x00b2b1b1, 0x00e0dfe0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bbbaba, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x006c2421, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00d92a21, 0x00c1271e, 0x00b3241d, 0x00a9231b, 0x00c7271f, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00252122, 0x00464243, 0x00757273, 0x00a4a3a3, 0x00d2d1d2, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d5d5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d2121, 0x00c02b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00cb2820, 0x00b4241d, 0x009c201a, 0x00821c17, 0x006a1814, 0x00521411, 0x003811f, 0x0020fe, 0x00999, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x001eed, 0x008e1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2d24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccbcb, 0x00f3f3f3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d1d0d1, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00622421, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00b6251d, 0x00731a15, 0x00491310, 0x002b11f, 0x0013cc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x009bb, 0x00222423, 0x003c3e3e, 0x00595b5b, 0x00727474, 0x008c8d8d, 0x00a7a8a8, 0x00bebfbf, 0x00bebfbf, 0x009b9c9c, 0x00353737, 0x00477, 0x00841c17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a82923, 0x00562321, 0x00622421, 0x006c2421, 0x00772522, 0x00822622, 0x008c2722, 0x00962822, 0x00a22823, 0x00ae2923, 0x00b92a23, 0x00c32b23, 0x00ce2c23, 0x00d92c24, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32d24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1a1b, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00323, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b5b3b4, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00762522, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00941f19, 0x0026fe, 0x00477, 0x00699, 0x00282a2a, 0x004b4d4d, 0x00666868, 0x00808282, 0x009a9b9b, 0x00b6b7b7, 0x00d0d0d0, 0x00e8e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00474949, 0x00caa, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00cc2b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2020, 0x00392120, 0x00442121, 0x004e2221, 0x00582321, 0x00632421, 0x006f2522, 0x007b2522, 0x00852622, 0x00902722, 0x009a2822, 0x00a52923, 0x00582321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x0011f10, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00838181, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00662421, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2820, 0x003511f, 0x00477, 0x002c2e2e, 0x00999a9a, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbebe, 0x00477, 0x00a3211b, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x0010bb, 0x00f1110, 0x00979898, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e9eaea, 0x00477, 0x00871d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c1c0c0, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa231c, 0x00999, 0x00292b2b, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00477, 0x00891d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00595657, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00852622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2820, 0x0011bb, 0x00272929, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cacaca, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00352020, 0x00592321, 0x00672421, 0x006d2421, 0x00562321, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00a3a1a1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9c8c8, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x003712f, 0x00f1110, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0b1b1, 0x00477, 0x00b7251d, 0x00ee2e24, 0x00ee2e24, 0x00d82c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x008a2722, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00c12b23, 0x006f2522, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00252122, 0x00c7c6c6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00585556, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00831c17, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00979898, 0x00477, 0x00cf2920, 0x00ee2e24, 0x00ee2e24, 0x00c22b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00922722, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2b23, 0x00492221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x003a3738, 0x00231f20, 0x00393637, 0x00efeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c2c1c1, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00802622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00b99, 0x00434545, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007a7c7c, 0x00477, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ac2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004e2221, 0x00d62c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00612421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00666464, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00535051, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003711f, 0x00f1010, 0x00dfdfdf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00616262, 0x0017dc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00972822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00692421, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x00941f19, 0x005f1612, 0x004111f, 0x004112f, 0x00611612, 0x00a8221b, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00592321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a3a1a1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bcbabb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00555, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00871d17, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00474949, 0x002e11f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00822622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006b2421, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00721915, 0x00eba, 0x00477, 0x00111212, 0x00333636, 0x00373939, 0x00e10f, 0x00477, 0x002d10f, 0x00c3271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2d24, 0x00322020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c3c2c3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009c9a9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00d8d7d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004d4a4b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00802622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2820, 0x00caa, 0x00434545, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x002b2d2d, 0x004712f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00be261e, 0x0023fe, 0x00477, 0x00515353, 0x00bfc0c0, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x009c9d9d, 0x00171818, 0x00caa, 0x00b6251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00474445, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b7b6b6, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003b1210, 0x00dff, 0x00dcdcdc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00111212, 0x00621713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00572321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322020, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00af231c, 0x00caa, 0x00181919, 0x00b6b7b7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x00202222, 0x0019dc, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c9c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c797a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00474445, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c12b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00871d17, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00477, 0x00791b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00412121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a62923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x00caa, 0x00262828, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bebfbf, 0x00477, 0x00811c16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b3b2b2, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2820, 0x00caa, 0x003f4141, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d8d8d8, 0x00477, 0x00911f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a2020, 0x00231f20, 0x00231f20, 0x005f2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x001fed, 0x001c1d1d, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x002d2f2f, 0x003b12f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007d2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c9c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00918f90, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332f30, 0x00e7e6e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003b12f, 0x00dff, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbebe, 0x00477, 0x00ab231c, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x00231f20, 0x00231f20, 0x00302020, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005c1612, 0x00477, 0x00bebfbf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005e6060, 0x0018dd, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x00312d2e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00585556, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00adacac, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00be2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00881d17, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a3a5a5, 0x00477, 0x00c4271f, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00231f20, 0x00231f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ae231c, 0x00477, 0x006c6e6e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626363, 0x0015dc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00932722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00989, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c9c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008f8d8d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00939192, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d02920, 0x00eba, 0x003f4141, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00898a8a, 0x00477, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00b62a23, 0x00231f20, 0x005b2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x001fed, 0x00202222, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00434545, 0x002e11f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00852622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191616, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efeeee, 0x002d2a2a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00cdcccc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003f1310, 0x00dff, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006d6f6f, 0x00b99, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x002e2020, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00641713, 0x00477, 0x00babbbb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00e1010, 0x005c1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c9c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00888686, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003e3a3b, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00be2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c1e18, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00545656, 0x002310e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c2722, 0x009e2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b2241d, 0x00477, 0x00636565, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x00a2211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaeaea, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00696667, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c2c1c1, 0x00929091, 0x00636061, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d02920, 0x00eba, 0x003a3c3c, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00393c3c, 0x003b11f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x0023fe, 0x001d1f1f, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003a3c3c, 0x001adc, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00c62b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c3c2c3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00828080, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0d0d0, 0x00a2a0a1, 0x00726f70, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d2121, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003f1210, 0x00bdd, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x001d1e1e, 0x00541411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a1814, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a7a8a8, 0x00477, 0x00841c17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007e2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e6e6, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00aeacad, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x00b1b0b0, 0x00817f7f, 0x00524f50, 0x00292526, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c1e18, 0x00477, 0x008c8d8d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00799, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b8251d, 0x00577, 0x005d5f5f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eceded, 0x001b1c1c, 0x002a10e, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00787677, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c797a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x004b4748, 0x005a5758, 0x00524e4f, 0x00322e2f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ff, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00782522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00eba, 0x003a3c3c, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00c1c2c2, 0x00a6a7a7, 0x008a8b8b, 0x006f7171, 0x00555757, 0x003a3c3c, 0x00323535, 0x00646666, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e6e6, 0x00477, 0x00861d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x002810e, 0x001a1b1b, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005d5f5f, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00852622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009c9a9a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e1e0e0, 0x00262323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d2121, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00431310, 0x00bdd, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x00477, 0x00477, 0x00a99, 0x002310f, 0x003b12f, 0x004612f, 0x00477, 0x00868787, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9caca, 0x00477, 0x009e211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006e1914, 0x00477, 0x00abacac, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0b1b1, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a6a5a5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00767374, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00911f19, 0x00477, 0x008c8d8d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00799, 0x00491310, 0x00c1271e, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dba, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c6c7c7, 0x00477, 0x008b1d18, 0x00c6271f, 0x00ad231c, 0x00961f19, 0x007f1b16, 0x00641713, 0x00788, 0x00575959, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eceded, 0x001b1c1c, 0x002810e, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00979595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x001a1717, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00652421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x0010bb, 0x00383a3a, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x002e3030, 0x0015cb, 0x00d82a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x00477, 0x00838484, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x00191a1a, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00bdd, 0x002b2d2d, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005b5d5d, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00686566, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x004d4a4b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00222, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00461311, 0x00acc, 0x00d4d4d4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00477, 0x009d9e9e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e8e8, 0x00a3a5a5, 0x00a4a6a6, 0x00babbbb, 0x00d6d6d6, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00e4e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x005c595a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00000, 0x00000, 0x00544, 0x001e1b1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001b1819, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00632421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a8221b, 0x00477, 0x00818383, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00799, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32d24, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00b0241c, 0x00477, 0x00b8b9b9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x002810e, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00555253, 0x00f3f3f3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c0bfbf, 0x00413e3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00171516, 0x0010ef, 0x00988, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b12a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003311f, 0x00202222, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x002e3030, 0x0015cb, 0x00d82a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00742522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00982019, 0x00477, 0x00d3d3d3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003f3b3c, 0x00a09e9f, 0x00d7d7d7, 0x00ececec, 0x00e8e7e7, 0x00d1d0d1, 0x009e9d9d, 0x004f4c4d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001a1717, 0x00131111, 0x00baa, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00e92e24, 0x00ee2e24, 0x00ee2e24, 0x00bb251e, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b32a23, 0x003c2121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f1b16, 0x00477, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00171414, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001c191a, 0x00151313, 0x00ecc, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00562321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f1914, 0x00699, 0x00e9eaea, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00799, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00382120, 0x00512221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00641713, 0x00bdd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x002810e, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x0011ff, 0x001b1819, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00171515, 0x0010ef, 0x00888, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007b2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003d12f, 0x00313333, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x002e3030, 0x0015cb, 0x00d82a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f2522, 0x00231f20, 0x00682421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1310, 0x00272929, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00877, 0x00dbc, 0x0010ee, 0x0011f10, 0x0011ef, 0x00ecd, 0x00988, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00892722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0021fe, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b32a23, 0x00231f20, 0x00231f20, 0x007d2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003511f, 0x00414343, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008c2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x001cee, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c7c8c8, 0x00799, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00382120, 0x00231f20, 0x00231f20, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x001aed, 0x005b5d5d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x0028fe, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007a2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003b1210, 0x00313333, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e6e6, 0x00202222, 0x001bed, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f2522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a82923, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x00688, 0x00777979, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00572321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f1b16, 0x00477, 0x00c3c4c4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e2e3e3, 0x002d2f2f, 0x00a99, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b32a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bd2a23, 0x00ee2e24, 0x00ee2e24, 0x00d52a21, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x001add, 0x00202222, 0x00dadada, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00babbbb, 0x001b1c1c, 0x00baa, 0x00a6221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d22c23, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x00477, 0x00aaabab, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x0028fe, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00151314, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x0011bb, 0x00f1010, 0x007f8181, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00b3b4b4, 0x004a4c4c, 0x00477, 0x001fed, 0x00ba251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x005b2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00a2211b, 0x00477, 0x00c7c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00788, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00161414, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00151313, 0x00555, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00342020, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2820, 0x00461311, 0x00477, 0x00477, 0x00101111, 0x00181818, 0x00477, 0x00477, 0x0010bb, 0x00721915, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00722522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322020, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00e0e1e1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x00741a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00edd, 0x00171515, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001d1a1b, 0x00151313, 0x00b9a, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c6271f, 0x00831c17, 0x00611612, 0x005d1612, 0x00751a15, 0x00a4221b, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x006e2521, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00477, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x002c10f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00322, 0x00545, 0x00544, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00662421, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82c24, 0x00532321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00581511, 0x00191b1b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00788, 0x00be261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00932722, 0x002e2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00732522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004012f, 0x00353737, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x00741a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00a52923, 0x00e12d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00c52b23, 0x00832622, 0x00372020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00342020, 0x00732522, 0x00a42923, 0x00cb2b23, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002710f, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e9e9, 0x00181919, 0x002c10f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d2121, 0x00502221, 0x00532321, 0x00442121, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004a2221, 0x00aa2923, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00daa, 0x00696b6b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00494b4b, 0x00477, 0x00b9251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b62a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x009e2822, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00477, 0x00858686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x005b5d5d, 0x00477, 0x004a1411, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00482221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00c9281f, 0x00a4221b, 0x00831c17, 0x00601612, 0x003a11f, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008c8d8d, 0x00477, 0x00711915, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b92a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00622421, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00641713, 0x0018dc, 0x00477, 0x00477, 0x00477, 0x00101111, 0x00333535, 0x00575959, 0x00c1c2c2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005a5c5c, 0x00788, 0x00c8281f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00602321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005f2321, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x00611612, 0x00577, 0x009bb, 0x004f5151, 0x00979898, 0x00c5c6c6, 0x00e9eaea, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00cee, 0x00481310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2c23, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x0022fe, 0x00477, 0x00626464, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007d7f7f, 0x00477, 0x00b0241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00792522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x0011ff, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00cb2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b4241d, 0x0010bb, 0x001a1b1b, 0x00bdbebe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x001b1c1c, 0x002d10f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2d24, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00fde, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00892722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x0011bb, 0x00212323, 0x00dcdcdc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009d9e9e, 0x00477, 0x00921f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x002e10f, 0x00121313, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00303232, 0x001adc, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x003e2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b52a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007e1b16, 0x00477, 0x00a3a5a5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bbbcbc, 0x00477, 0x00761a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171415, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00672421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22920, 0x00caa, 0x00464848, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004d4f4f, 0x00baa, 0x00d42a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00522221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004b1411, 0x00acc, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x00799, 0x00581512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c32b23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a6221b, 0x00477, 0x007c7e7e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x00577, 0x00be261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x0021ed, 0x00232525, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00121313, 0x003c1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d52c24, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00bf2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00731a15, 0x00477, 0x00b5b6b6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008b8c8c, 0x00477, 0x00a4221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00702522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c8281f, 0x00999, 0x00525454, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00232525, 0x0025fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00de2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00401210, 0x00e1010, 0x00e0e1e1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a9aaaa, 0x00477, 0x00861d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009d2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a201a, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003b3d3d, 0x0013cb, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00462221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00edd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02c22, 0x0019dc, 0x002c2e2e, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c7c8c8, 0x00477, 0x006a1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b52a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c82b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00671813, 0x00477, 0x00c0c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005a5c5c, 0x00999, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005c2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007b2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c0261e, 0x00688, 0x005e6060, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00bdd, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2b23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003611f, 0x00131414, 0x00e8e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00e4e5e5, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00787a7a, 0x00477, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a72923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00696b6b, 0x00474949, 0x00242626, 0x00799, 0x00477, 0x00477, 0x007d7f7f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00191a1a, 0x003611f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ef, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00582321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2b21, 0x0014cb, 0x00363838, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x00acc, 0x00daa, 0x002e11f, 0x004d1310, 0x006e1914, 0x00861d17, 0x002fec, 0x001b1c1c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008e8f8f, 0x00477, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005c1612, 0x00588, 0x00cbcbcb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00c5c6c6, 0x00a1a3a3, 0x007e8080, 0x005f6060, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004e5050, 0x00b99, 0x00cf2920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x001fed, 0x00414343, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e6e6, 0x00477, 0x007f1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003f2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00852622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b7251d, 0x00477, 0x006a6c6c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00cbcbcb, 0x00a3a5a5, 0x00808282, 0x005d5f5f, 0x00373939, 0x00131414, 0x00477, 0x00477, 0x00477, 0x00477, 0x007c7e7e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b5b6b6, 0x00477, 0x00761a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00982019, 0x00477, 0x00a8a9a9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00131414, 0x00611612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00532321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x002c10e, 0x00191a1a, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00848585, 0x00616262, 0x003a3c3c, 0x00161717, 0x00477, 0x00477, 0x00477, 0x00477, 0x0019ed, 0x003b12f, 0x005e1612, 0x00801c16, 0x009a201a, 0x00fa9, 0x00232525, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00272929, 0x0020ed, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x001ded, 0x002c2e2e, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00191a1a, 0x005b1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00562321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b12a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00477, 0x00a2a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00474949, 0x00477, 0x0017dc, 0x003911f, 0x005a1512, 0x007b1b16, 0x009f211a, 0x00c1271e, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00741a15, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00888989, 0x00477, 0x00a0211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791a15, 0x00477, 0x00b5b6b6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00799, 0x006c1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00666, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00612421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00fbb, 0x00404242, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x007d1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2820, 0x00a99, 0x00505252, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e4e5e5, 0x00e1010, 0x00411310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00caa, 0x00494b4b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00477, 0x00931f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2020, 0x00d62c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00511512, 0x008aa, 0x00d5d5d5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x001f2121, 0x0025fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00421310, 0x00dff, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005a5c5c, 0x00788, 0x00c7271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00571512, 0x00799, 0x00d5d5d5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00862622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x00477, 0x00777979, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00797b7b, 0x00477, 0x00ac231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009f211a, 0x00477, 0x00868787, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c1c2c2, 0x00477, 0x006b1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bb251e, 0x00477, 0x006c6e6e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x001c1d1d, 0x003c1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009e2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00767, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x0023fe, 0x001f2121, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x009bb, 0x004e1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d52c23, 0x005c2321, 0x003f2121, 0x004f2221, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x001ced, 0x002a2c2c, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00303232, 0x0018dc, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003711f, 0x00141515, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00909191, 0x00477, 0x00a6221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00562321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ef, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00762522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00477, 0x00adaeae, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00444646, 0x00daa, 0x00d32a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00612421, 0x00231f20, 0x00251f20, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006c1814, 0x00477, 0x00bcbdbd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00959696, 0x00477, 0x00951f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a201a, 0x00477, 0x00929393, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00151616, 0x003812f, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bc2a23, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x001bed, 0x00393b3b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x00801c16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00231f20, 0x00231f20, 0x00772522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00788, 0x005a5c5c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00141515, 0x003611f, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x001ded, 0x002b2d2d, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00737575, 0x00477, 0x00b8251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00477, 0x00a1a3a3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x001d1f1f, 0x002810e, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x003d2121, 0x00231f20, 0x00352020, 0x00e12d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003a1210, 0x00111212, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00666868, 0x00577, 0x00bd261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791a15, 0x00477, 0x00b7b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dddddd, 0x009bb, 0x00511511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c82b23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00442121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791b16, 0x00477, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00767878, 0x00477, 0x00af231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a02822, 0x005c2321, 0x00792522, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00961f19, 0x00477, 0x00909191, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00588, 0x00601713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00caa, 0x004b4d4d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00565858, 0x00999, 0x00cf2920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00572321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00562321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e1612, 0x00191a1a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x008aa, 0x00511511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x0018dc, 0x00313333, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003a3c3c, 0x0013cb, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00571512, 0x00799, 0x00d7d7d7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x00477, 0x006d1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00592321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00521411, 0x00222424, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00484a4a, 0x00daa, 0x00d32a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00477, 0x00c5c6c6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a1a2a2, 0x00477, 0x00891d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b9251d, 0x00477, 0x006f7171, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003a3c3c, 0x0014cb, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00432121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00542321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00651713, 0x00dff, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bfc0c0, 0x00477, 0x00771a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x00aa231c, 0x00577, 0x00636565, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x001a1b1b, 0x002d10f, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003511f, 0x00151616, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x00881d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00cdcdcd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x0013cc, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00e02c22, 0x00bf261e, 0x009d211a, 0x007c1b16, 0x005c1612, 0x003b12f, 0x0019ed, 0x00477, 0x00477, 0x00151616, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00737575, 0x00477, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00982019, 0x00477, 0x00939494, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00232525, 0x0025fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00e32d24, 0x00342020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d82c24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00788, 0x00686a6a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003d3f3f, 0x0011ba, 0x003e11e, 0x003011f, 0x0017dc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00161717, 0x00393b3b, 0x005d5f5f, 0x00808282, 0x00a3a5a5, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x00799, 0x00541512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x001ced, 0x002b2d2d, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008d8e8e, 0x00477, 0x00a2211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009d2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00581612, 0x009bb, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9caca, 0x004b4d4d, 0x00323535, 0x00474949, 0x00616262, 0x00848585, 0x00a5a6a6, 0x00cbcbcb, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00464848, 0x00daa, 0x00d32a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00771a15, 0x00477, 0x00b7b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x00131414, 0x003a1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d62c24, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2920, 0x00999, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x007e1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00baa, 0x004b4d4d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006e7070, 0x00477, 0x00bd261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00baa, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00434, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00af2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00671813, 0x00477, 0x00cfcfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00212323, 0x0024fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00551512, 0x008aa, 0x00d7d7d7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dadada, 0x008aa, 0x00561512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00452221, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2b21, 0x00eba, 0x00484a4a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007f8181, 0x00477, 0x00a9231b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b9251d, 0x00477, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00535555, 0x00ba9, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a12822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791a15, 0x00477, 0x00bdbebe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dfdfdf, 0x00cee, 0x00481310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003511f, 0x00161717, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c1c2c2, 0x00477, 0x00701914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ae2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003b2120, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0018dc, 0x00373939, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00525454, 0x00a99, 0x00cc2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00982019, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00363838, 0x0017dc, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00abacac, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00477, 0x00721915, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x001ced, 0x002d2f2f, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a4a6a6, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00e22d24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x0023fd, 0x00272929, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x002a2c2c, 0x001ded, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00771a15, 0x00477, 0x00b9baba, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00212323, 0x0027fe, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00322020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00842622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a201a, 0x00477, 0x00989999, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008c8d8d, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d62a21, 0x00baa, 0x004d4f4f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00878888, 0x00477, 0x00a7221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00da2d24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003011f, 0x001c1d1d, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00101111, 0x003d1210, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00681813, 0x00588, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e9eaea, 0x00111212, 0x003f1310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00742522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x00477, 0x00858686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005e6060, 0x00788, 0x00c4271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x0015cc, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x00577, 0x00bf261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00d02c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00401310, 0x00131414, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c4c5c5, 0x00477, 0x00671813, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x00477, 0x00a1a2a2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x00799, 0x00591612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c12b23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00767, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00652421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x00477, 0x00737575, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00333535, 0x0017dc, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00971f19, 0x00477, 0x00d2d2d2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004e5050, 0x00baa, 0x00d42a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00512221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00c42b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00501411, 0x00acc, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00999a9a, 0x00477, 0x00911f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00961f19, 0x00477, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bcbdbd, 0x00477, 0x00751a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00572321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2820, 0x00788, 0x00616262, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00151616, 0x003311f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00a6221b, 0x00477, 0x00bcbdbd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00272929, 0x001ced, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x003e2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151313, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b52a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00611612, 0x00588, 0x00d3d3d3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00696b6b, 0x00477, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00782522, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00999, 0x00626363, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00545656, 0x00477, 0x00a7221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00932722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00492221, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72a21, 0x00caa, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcfcf, 0x00699, 0x005b1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x00261f20, 0x009e2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00588, 0x00acadad, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x004e5050, 0x00477, 0x00791b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2d24, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a62923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00731a15, 0x00477, 0x00c3c4c4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003e4040, 0x0011bb, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00552321, 0x00231f20, 0x00532321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x002d11f, 0x00699, 0x00777979, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00969797, 0x001b1c1c, 0x00688, 0x007f1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00622421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003e2121, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x0015cc, 0x003c3e3e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00939494, 0x00477, 0x00881d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a82923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b32a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x00501411, 0x00477, 0x00699, 0x00343636, 0x005c5e5e, 0x00585a5a, 0x003e4040, 0x00bdd, 0x00477, 0x003011f, 0x00b6251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00972822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00477, 0x00b1b2b2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b2b3b3, 0x00799, 0x003e1210, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52d24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x00dc2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x006b1814, 0x003711f, 0x002110f, 0x001add, 0x003211f, 0x00651713, 0x00b1241c, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009b2822, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00342020, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x0020ed, 0x00262828, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009fa0a0, 0x009bb, 0x002910e, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00d62c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00862622, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00882622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a6221b, 0x00477, 0x00494b4b, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00565858, 0x00477, 0x003511f, 0x00db2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c12b23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00342020, 0x00a92923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x00512221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00dc2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00577, 0x001e2020, 0x00959696, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x00bbbcbc, 0x00636565, 0x009bb, 0x00898, 0x00711915, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82c24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00a42923, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00b92a23, 0x00652421, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006a2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x002c10e, 0x00477, 0x00477, 0x00232424, 0x00323535, 0x00232424, 0x00699, 0x00477, 0x00a99, 0x00581512, 0x00c8281f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00442121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x004c2221, 0x006b2421, 0x00822622, 0x00832622, 0x007b2522, 0x005c2321, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00972822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00b7251d, 0x00751a15, 0x00501410, 0x004312f, 0x00521411, 0x00701914, 0x00a1211a, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00902722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00962722, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00d02c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12923, 0x00482221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1818, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x006a2421, 0x00b22a23, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00c72b23, 0x008b2722, 0x00422121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00482221, 0x005c2321, 0x00642421, 0x005c2321, 0x004b2221, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x0011f10, 0x001e1b1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x0011f10, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00877, 0x00000, 0x00000, 0x00b9a, 0x00191616, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x0010ef, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00323, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00baa, 0x00141112, 0x001b1819, 0x00201d1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00191617, 0x0011f10, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00433, 0x00544, 0x00434, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00211e1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00151314, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00111010, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00131011, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00fdd, 0x00161314, 0x001c1919, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x001c191a, 0x00161314, 0x00fee, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000}; \ No newline at end of file +#include +// file: flynn.png +int intense_milk_width = 430; +int intense_milk_height = 244; +uint32_t intense_milk[104920] = {0x000a1118, 0x000b1219, 0x000b1219, 0x000c131c, 0x000c141d, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b141d, 0x000b131c, 0x000b131c, 0x000a121b, 0x000a121b, 0x00081119, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00081018, 0x00081018, 0x0009101a, 0x0009101a, 0x0009101a, 0x000a111b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000c141d, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c161f, 0x000c161f, 0x000e1823, 0x000d1824, 0x000d1925, 0x000d1925, 0x000e1a26, 0x00101926, 0x00131b25, 0x00151d27, 0x00151e27, 0x00131b24, 0x00111a23, 0x00141c25, 0x0018202a, 0x001a242d, 0x001e2830, 0x001c2830, 0x0019252e, 0x0019252e, 0x0019252f, 0x0017212c, 0x00161f2a, 0x00182029, 0x00151d26, 0x00131c24, 0x00121a21, 0x0010171f, 0x000d151c, 0x000d151c, 0x00121a20, 0x00182027, 0x001c242c, 0x00212931, 0x00232c34, 0x00212b34, 0x00202a33, 0x00202a33, 0x00222a34, 0x00222a34, 0x00232b34, 0x00262c36, 0x00282f38, 0x00293039, 0x00282e37, 0x00272d37, 0x00272d37, 0x00272d37, 0x00262c36, 0x00252c35, 0x00252c35, 0x00252c35, 0x00252c35, 0x00252c35, 0x00252c34, 0x00262c34, 0x00262d35, 0x00272d36, 0x00282e37, 0x00282f38, 0x002a303a, 0x002b313b, 0x002b313c, 0x002b313d, 0x002c333e, 0x002e3440, 0x002f3440, 0x002e3440, 0x002d333f, 0x002d333f, 0x002d333f, 0x002d333f, 0x002d333f, 0x002e3440, 0x002f3440, 0x002f3541, 0x00303540, 0x002f3540, 0x002f3540, 0x002f3540, 0x00303641, 0x00303742, 0x00303641, 0x002f3540, 0x002f353f, 0x002e343e, 0x002e343d, 0x0030343f, 0x00313640, 0x00333741, 0x00333741, 0x00333742, 0x00333743, 0x00333743, 0x00333743, 0x00313742, 0x00303642, 0x00303541, 0x00303541, 0x00313640, 0x00313640, 0x00313640, 0x00313642, 0x00303541, 0x002e3440, 0x002f3440, 0x00303541, 0x00303742, 0x00333843, 0x00333843, 0x00333843, 0x00323742, 0x00323742, 0x00323642, 0x00313642, 0x00303744, 0x00303744, 0x00313844, 0x00303744, 0x00303744, 0x00303742, 0x00303641, 0x00313541, 0x00303541, 0x002f3440, 0x002f3440, 0x002e3440, 0x00303441, 0x00313542, 0x00313541, 0x002f343f, 0x002c323c, 0x002c323c, 0x002d333c, 0x002d333c, 0x002d323c, 0x002d323c, 0x002c303b, 0x002b303a, 0x002b303a, 0x002b3039, 0x00292e38, 0x00282d37, 0x00282c36, 0x00282c36, 0x00282c36, 0x00282c36, 0x00282c36, 0x00282c36, 0x00272c35, 0x00262a34, 0x00262a34, 0x00262a34, 0x00262a34, 0x00252934, 0x00242934, 0x00242832, 0x00232831, 0x00232831, 0x00222830, 0x0021282f, 0x0022282f, 0x00232930, 0x00232832, 0x00222730, 0x00212630, 0x00212630, 0x00222730, 0x00232831, 0x00222831, 0x00212831, 0x00222831, 0x00222831, 0x00212831, 0x00202630, 0x001f242e, 0x001e242d, 0x001d232c, 0x001d232c, 0x001c232c, 0x001c222b, 0x00181f26, 0x00141b23, 0x0010171f, 0x000f151d, 0x0010161e, 0x00121820, 0x00141921, 0x00141b23, 0x00181d24, 0x001a2028, 0x001a2028, 0x00191e27, 0x00141924, 0x00121822, 0x00141a24, 0x00161c26, 0x00181f28, 0x00192029, 0x0019212c, 0x001a2430, 0x001c2733, 0x001e2834, 0x00202a36, 0x00202b37, 0x00202b34, 0x00202b34, 0x00202a34, 0x001e2831, 0x001a2430, 0x00182430, 0x00182632, 0x001c2834, 0x001c2a35, 0x001d2a35, 0x001e2a36, 0x001e2a36, 0x001d2935, 0x001a2531, 0x0014202c, 0x00152330, 0x001a2835, 0x001d2b38, 0x00202e3a, 0x0022303d, 0x00253340, 0x00253240, 0x00202d3a, 0x00182532, 0x0013202c, 0x00101d28, 0x000f1c26, 0x000c1823, 0x000a141e, 0x000a111c, 0x000c1019, 0x000b1017, 0x000b1016, 0x000b1016, 0x000b1016, 0x000b1017, 0x000b1017, 0x000b1016, 0x000b1016, 0x000b1016, 0x00081018, 0x00081118, 0x00081118, 0x00081118, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x000a1018, 0x000a1018, 0x000a1018, 0x000a1018, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x00080f18, 0x00080e18, 0x00080e18, 0x00080e18, 0x00080e18, 0x000b1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a121b, 0x000b131b, 0x000b131c, 0x000c141c, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141e, 0x000c141e, 0x000c141e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b141c, 0x000b131c, 0x000b131b, 0x000a1219, 0x000a1219, 0x0009121a, 0x000a121b, 0x0009111a, 0x0008111a, 0x0008111a, 0x0009121b, 0x000a121b, 0x000a121b, 0x0009111a, 0x0009111a, 0x0009111a, 0x000a121b, 0x000a121b, 0x000b131d, 0x000c131d, 0x000b131d, 0x000b131d, 0x000b131d, 0x000b141d, 0x000b151e, 0x000b151e, 0x000a151e, 0x000a161e, 0x000a161f, 0x000b171f, 0x000c1820, 0x000c1821, 0x000e1a24, 0x00101c28, 0x00111c28, 0x00121c28, 0x00121b24, 0x00141c25, 0x00151d26, 0x00141c25, 0x00131c24, 0x00151d26, 0x0018202a, 0x001b252e, 0x001f2831, 0x001b272f, 0x0018242e, 0x0019252f, 0x0017232c, 0x00141f29, 0x0016202a, 0x00172028, 0x00141d25, 0x00131c24, 0x00101922, 0x00101821, 0x00101a20, 0x00111b22, 0x00152026, 0x0018222a, 0x001b252d, 0x001e2730, 0x00202933, 0x00202b34, 0x001f2b34, 0x00202c35, 0x00222c36, 0x00232b35, 0x00232b35, 0x00252c38, 0x00282e3a, 0x00292f39, 0x00282f38, 0x00272d37, 0x00272d37, 0x00272d37, 0x00272d37, 0x00262c36, 0x00262c36, 0x00262d36, 0x00262c36, 0x00262c36, 0x00272d36, 0x00272e36, 0x00272e35, 0x00282e36, 0x00282f38, 0x00293038, 0x002a303a, 0x002c323c, 0x002c333d, 0x002c333e, 0x002e3440, 0x00303541, 0x002f3541, 0x002f3440, 0x002f3540, 0x002f3540, 0x002f3541, 0x002f3440, 0x00303541, 0x00303743, 0x00313843, 0x00313843, 0x00313843, 0x00323844, 0x00323844, 0x00313843, 0x00313843, 0x00313843, 0x00303743, 0x00303742, 0x00303641, 0x00303641, 0x00303740, 0x00323841, 0x00343842, 0x00343842, 0x00343842, 0x00343843, 0x00343844, 0x00343844, 0x00343844, 0x00313843, 0x00313742, 0x00333743, 0x00333844, 0x00313843, 0x00313842, 0x00313841, 0x00313842, 0x00303742, 0x00303742, 0x00303641, 0x00303742, 0x00313843, 0x00343844, 0x00343944, 0x00343944, 0x00343944, 0x00343944, 0x00343944, 0x00343944, 0x00313844, 0x00313844, 0x00313843, 0x00313843, 0x00303742, 0x00303742, 0x002f3641, 0x00303541, 0x00303641, 0x00303641, 0x002f3440, 0x00303540, 0x00313541, 0x00313542, 0x00303540, 0x002d343d, 0x002c333c, 0x002c333c, 0x002c333c, 0x002d333d, 0x002e333e, 0x002e333e, 0x002c303b, 0x002a2f39, 0x00292f38, 0x002a2f39, 0x00292e38, 0x00292e38, 0x00282d37, 0x00282c36, 0x00282c36, 0x00282d37, 0x00282d37, 0x00282c36, 0x00262b35, 0x00252a34, 0x00262a34, 0x00262a34, 0x00252934, 0x00272a34, 0x00272a34, 0x00252a34, 0x00242833, 0x00242832, 0x00232832, 0x00242a33, 0x00242a33, 0x00242b34, 0x00242a34, 0x00242933, 0x00222832, 0x00212731, 0x00212831, 0x00212831, 0x00212831, 0x00222831, 0x00242a33, 0x00242a33, 0x00222832, 0x00202730, 0x001f242e, 0x001e242e, 0x001e242e, 0x001e242e, 0x001d242c, 0x001c222c, 0x00192029, 0x00161d25, 0x00131921, 0x000f151d, 0x000f161d, 0x0010181f, 0x00121820, 0x00131923, 0x00171d25, 0x001c242b, 0x001b232a, 0x00181f28, 0x00151c25, 0x00141b24, 0x00141c25, 0x00161d27, 0x00181f28, 0x0018202a, 0x0019222c, 0x0018242e, 0x001a2630, 0x001c2834, 0x001e2a36, 0x001f2b38, 0x001f2b37, 0x001f2a36, 0x001f2834, 0x001d2833, 0x001a2430, 0x00141f29, 0x00131e28, 0x0018232c, 0x001c2731, 0x001c2731, 0x001c2832, 0x001d2832, 0x001d2935, 0x001c2834, 0x001a2531, 0x00182833, 0x001b2b35, 0x001c2c37, 0x001e2d38, 0x0022313c, 0x00253440, 0x0024343f, 0x001e2d38, 0x00162631, 0x0011202c, 0x000f1e27, 0x000d1a23, 0x000b161f, 0x000a131c, 0x000a101b, 0x000b1018, 0x000a1018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00091019, 0x00091019, 0x000a1019, 0x000b101a, 0x000a101a, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x000a1019, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x00091019, 0x00091019, 0x00080f18, 0x00080f17, 0x00080f17, 0x000b1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b131c, 0x000b131c, 0x000b131c, 0x000c141c, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141e, 0x000c141e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b141d, 0x000b131c, 0x000b131b, 0x000a1219, 0x000a1219, 0x000a121a, 0x000b131c, 0x000a121b, 0x0008111a, 0x0008111a, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000b131c, 0x000c141d, 0x000c141f, 0x000c1420, 0x000c141f, 0x000c141f, 0x000c141f, 0x000b151e, 0x000b151e, 0x000a151e, 0x0009161e, 0x0008161e, 0x0009171f, 0x0009171f, 0x000a1820, 0x000c1921, 0x000f1c25, 0x0014202c, 0x0016222d, 0x0015202b, 0x00131b25, 0x00131b24, 0x00141c24, 0x00131c24, 0x00131c24, 0x00141d26, 0x0018202a, 0x001b252d, 0x001d2730, 0x0018242c, 0x0017232c, 0x0017232d, 0x0017222c, 0x0016202b, 0x0017212a, 0x0017212a, 0x00162028, 0x00141f26, 0x00141e27, 0x00152028, 0x00152128, 0x00162228, 0x00182329, 0x0019232c, 0x001a242d, 0x001c2730, 0x00222b34, 0x00222c34, 0x00212d36, 0x00232f38, 0x00242e38, 0x00242c37, 0x00232b36, 0x00252c38, 0x00282e3a, 0x00292f3a, 0x00282f38, 0x00282e37, 0x00272d37, 0x00272d37, 0x00272d37, 0x00272d37, 0x00282e38, 0x00283038, 0x00282f38, 0x00282f38, 0x00282f38, 0x00282f37, 0x00272e35, 0x00272e36, 0x00282f38, 0x00293039, 0x002b313c, 0x002c333c, 0x002e343e, 0x002f343f, 0x00303742, 0x00313844, 0x00303843, 0x00303742, 0x00303743, 0x00313843, 0x00313843, 0x00303742, 0x00313843, 0x00333944, 0x00343945, 0x00333944, 0x00333944, 0x00343b46, 0x00343a46, 0x00333944, 0x00323844, 0x00313844, 0x00313843, 0x00313843, 0x00303743, 0x00313843, 0x00313842, 0x00333943, 0x00343944, 0x00343944, 0x00343944, 0x00343944, 0x00343a45, 0x00353a46, 0x00343a46, 0x00333945, 0x00333944, 0x00353b46, 0x00343b46, 0x00343a46, 0x00333a45, 0x00323944, 0x00313844, 0x00313844, 0x00313844, 0x00313843, 0x00313843, 0x00323844, 0x00333844, 0x00343945, 0x00343a46, 0x00343b46, 0x00353b46, 0x00343b46, 0x00333944, 0x00323844, 0x00313843, 0x00313843, 0x00303742, 0x00303742, 0x00303742, 0x002e3641, 0x00303641, 0x00303641, 0x00303641, 0x00303642, 0x00313642, 0x00323642, 0x00303540, 0x002f3440, 0x002e343e, 0x002e343d, 0x002e343e, 0x002e343d, 0x002e343e, 0x002f343f, 0x002f343f, 0x002c313c, 0x00292e38, 0x00282e38, 0x00292e38, 0x00292e38, 0x00292e38, 0x00292e38, 0x00282d37, 0x00292e38, 0x00292e38, 0x00282d37, 0x00272c35, 0x00252934, 0x00242833, 0x00252934, 0x00252a34, 0x00242934, 0x00272a34, 0x00272a34, 0x00262934, 0x00242833, 0x00242832, 0x00242832, 0x00242a34, 0x00242b34, 0x00242b34, 0x00252b35, 0x00252b34, 0x00242b34, 0x00242a34, 0x00232933, 0x00232932, 0x00232933, 0x00242a34, 0x00242b34, 0x00242b34, 0x00232933, 0x00202730, 0x001f252f, 0x001f252f, 0x00202630, 0x001f2530, 0x001e242d, 0x001c232c, 0x001a202a, 0x00181e27, 0x00141b23, 0x0010161e, 0x000f151d, 0x00121820, 0x00131a22, 0x00121822, 0x00131a22, 0x00182028, 0x001f272e, 0x001f2830, 0x0019222b, 0x00161e27, 0x00151d26, 0x00161e27, 0x00182029, 0x001a222c, 0x001b242e, 0x0018242d, 0x0018242e, 0x00192732, 0x001c2934, 0x001e2b38, 0x001f2b38, 0x001e2a38, 0x001e2834, 0x001e2834, 0x001c2631, 0x0018222c, 0x00131c25, 0x00111b24, 0x0018222b, 0x001b252f, 0x001a242f, 0x0018222c, 0x00182430, 0x001a2531, 0x001a2732, 0x001c2a36, 0x001d2d38, 0x001d2c38, 0x001e2e39, 0x0021313c, 0x0024343e, 0x0024343e, 0x001c2d37, 0x0015272f, 0x0010222b, 0x000f1e27, 0x000c1920, 0x0009141c, 0x000a121b, 0x000a111a, 0x000a1018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00071017, 0x00071017, 0x00081018, 0x00081018, 0x0009101a, 0x000a101a, 0x000b101b, 0x000c101c, 0x000b101b, 0x00081018, 0x00071017, 0x00071017, 0x00081018, 0x00081018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091019, 0x00091019, 0x00091019, 0x000a101a, 0x000a101a, 0x00091019, 0x00091019, 0x00080f18, 0x00080f17, 0x00080f17, 0x000b1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b131c, 0x000b131c, 0x000b131c, 0x000c141c, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141e, 0x000c141e, 0x000c141e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b141d, 0x000b141c, 0x000a131c, 0x000a121a, 0x000a121a, 0x000a121a, 0x000b141c, 0x000a131b, 0x0009111a, 0x0009111a, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000b131c, 0x000c141d, 0x000c141f, 0x000c1420, 0x000c141f, 0x000c141f, 0x000c141f, 0x000c151f, 0x000c151f, 0x000b151f, 0x0009161f, 0x0009161f, 0x0009161f, 0x000a1720, 0x000c1921, 0x000e1b24, 0x00101d28, 0x0017232f, 0x00182431, 0x0018222e, 0x00151d28, 0x00121b24, 0x00131c24, 0x00131c24, 0x00131c24, 0x00141c25, 0x00171f28, 0x0019222b, 0x001a242c, 0x0017222a, 0x0016222b, 0x0017232c, 0x0017222c, 0x0017212c, 0x0018212a, 0x0018222b, 0x0018222b, 0x0018212a, 0x0018212a, 0x0018212a, 0x0016222a, 0x00142028, 0x00152028, 0x0019242c, 0x001d2730, 0x00202a33, 0x00242c35, 0x00242d36, 0x00212c35, 0x00222c37, 0x00212c36, 0x00232c37, 0x00242d38, 0x00262e39, 0x00282f3b, 0x0029303b, 0x00293039, 0x00282e37, 0x00272d37, 0x00262c36, 0x00262c36, 0x00262c36, 0x00282f38, 0x00283039, 0x00283039, 0x0029303a, 0x00293039, 0x00282f37, 0x00262d35, 0x00262c35, 0x00282f38, 0x002b313b, 0x002d343d, 0x002f353e, 0x002f3540, 0x002f3540, 0x002f3641, 0x00303844, 0x00323a44, 0x00333944, 0x00333945, 0x00343945, 0x00333944, 0x00323944, 0x00333945, 0x00343a46, 0x00343945, 0x00333944, 0x00333944, 0x00343945, 0x00343a45, 0x00343a45, 0x00343a46, 0x00333944, 0x00313843, 0x00303742, 0x00303742, 0x00303742, 0x00323843, 0x00343a44, 0x00333944, 0x00323844, 0x00323844, 0x00333944, 0x00343a45, 0x00353b46, 0x00343a45, 0x00343a45, 0x00343b46, 0x00343c47, 0x00343c47, 0x00343c47, 0x00343c47, 0x00333b46, 0x00333b46, 0x00333b45, 0x00333a45, 0x00333944, 0x00323844, 0x00333944, 0x00343945, 0x00343a45, 0x00343b46, 0x00353c47, 0x00363c48, 0x00373d48, 0x00353b47, 0x00323844, 0x00313843, 0x00313843, 0x00323843, 0x00313742, 0x00303742, 0x002f3641, 0x00303641, 0x00303641, 0x00303641, 0x00303742, 0x00313643, 0x00313542, 0x00303440, 0x002f3440, 0x002e343e, 0x002f353f, 0x002f353e, 0x002d343d, 0x002d333d, 0x002f343f, 0x002f3440, 0x002c313d, 0x00292e38, 0x00292e38, 0x00292e38, 0x00292f38, 0x00292e38, 0x002b2f39, 0x002c303a, 0x002b303a, 0x002b2f3a, 0x00292e38, 0x00282c37, 0x00272b35, 0x00242933, 0x00232832, 0x00242934, 0x00242934, 0x00262934, 0x00252833, 0x00242731, 0x00252832, 0x00252833, 0x00242832, 0x00232831, 0x00212630, 0x00212630, 0x00242832, 0x00242a34, 0x00242b34, 0x00242b34, 0x00242a34, 0x00242a34, 0x00242b34, 0x00242b34, 0x00242b34, 0x00242b34, 0x00232932, 0x00212831, 0x00202630, 0x00202630, 0x00202730, 0x00202730, 0x001f252f, 0x001d242c, 0x001a202a, 0x00181f28, 0x00161c24, 0x00111820, 0x000e141c, 0x0010171f, 0x00141c24, 0x00121822, 0x00111921, 0x00101820, 0x00151e26, 0x001c252e, 0x00202831, 0x001b242c, 0x00141d26, 0x00141d26, 0x00172028, 0x001a232c, 0x001c252f, 0x0019252f, 0x0018252f, 0x00192731, 0x001c2934, 0x001e2b37, 0x001f2b38, 0x001e2a38, 0x001e2835, 0x001e2834, 0x001c2632, 0x0019242d, 0x00152028, 0x00101b24, 0x00111c25, 0x0017212c, 0x0017212c, 0x00101a24, 0x000d1824, 0x00101c28, 0x0015212d, 0x001a2733, 0x001e2c38, 0x001f2d38, 0x00202e39, 0x0022313c, 0x0024343d, 0x0023343d, 0x001c2e37, 0x00162730, 0x0012222c, 0x000f1d26, 0x000b1820, 0x0009141d, 0x000a121c, 0x000a111b, 0x000a1018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00071017, 0x00081018, 0x00081018, 0x00081018, 0x00081119, 0x00081119, 0x000a101a, 0x000b101b, 0x000b101b, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091019, 0x00091019, 0x0009101a, 0x000a101a, 0x000a101a, 0x00091019, 0x00091019, 0x00091018, 0x00080f18, 0x00080f18, 0x000b1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b131c, 0x000b131c, 0x000b131c, 0x000c141c, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141e, 0x000c141e, 0x000c141e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000b131c, 0x000b131c, 0x000b131b, 0x000c141b, 0x000b141b, 0x000a131c, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000b131c, 0x000b131c, 0x000b131c, 0x000b131e, 0x000c141f, 0x000c1420, 0x000c1420, 0x000c1420, 0x000d1520, 0x000d1520, 0x000c1520, 0x000a1520, 0x000a1520, 0x000b1620, 0x000b1720, 0x000c1823, 0x000f1b25, 0x00141f2a, 0x00182432, 0x001c2834, 0x001b2430, 0x0019212b, 0x00151d27, 0x00141c24, 0x00131c24, 0x00121a24, 0x00111923, 0x00121a24, 0x00141c25, 0x00151e27, 0x00152028, 0x0018222b, 0x0018222c, 0x0018222c, 0x0018232c, 0x001a242d, 0x001a242c, 0x0018222b, 0x0017212a, 0x0017212a, 0x0017212a, 0x0017222b, 0x00152129, 0x0017222b, 0x001b252e, 0x00202a33, 0x00222c35, 0x00232c35, 0x00212b34, 0x00212c35, 0x00242d38, 0x00242d38, 0x0025303a, 0x0027313c, 0x0028303c, 0x0029313c, 0x0029313c, 0x002a303a, 0x00282e38, 0x00262c36, 0x00262c36, 0x00262c36, 0x00272d37, 0x00282f38, 0x00293039, 0x00293039, 0x0029303a, 0x00293039, 0x00282f38, 0x00282e37, 0x00282e38, 0x0029303b, 0x002c323c, 0x002d343e, 0x002f3440, 0x002e3440, 0x002e343f, 0x002f3641, 0x00303844, 0x00333b45, 0x00333944, 0x00323844, 0x00303742, 0x00303641, 0x00303642, 0x00303642, 0x00313843, 0x00323844, 0x00323844, 0x00313843, 0x00303743, 0x00303742, 0x00323844, 0x00333944, 0x00323844, 0x00303742, 0x00303641, 0x00303641, 0x00303641, 0x00313843, 0x00323844, 0x00323844, 0x00303843, 0x00303843, 0x00313843, 0x00323844, 0x00323844, 0x00303742, 0x00303641, 0x00303641, 0x00313843, 0x00313843, 0x00313944, 0x00323a45, 0x00323a45, 0x00313a44, 0x00323a44, 0x00333b46, 0x00353b47, 0x00343b46, 0x00363c48, 0x00363c48, 0x00363c48, 0x00373d48, 0x00383e49, 0x00373d48, 0x00373d48, 0x00363c48, 0x00343c47, 0x00343b46, 0x00343944, 0x00333843, 0x00333743, 0x00313743, 0x00303642, 0x00303641, 0x00303541, 0x00313641, 0x00313642, 0x00313542, 0x00313541, 0x00303440, 0x002e343e, 0x002c333c, 0x002c333c, 0x002c333c, 0x002c333c, 0x002c323c, 0x002e333e, 0x002f343f, 0x002f3440, 0x002c313c, 0x002c303b, 0x002c303b, 0x002b3039, 0x002a2e38, 0x002c303b, 0x002c303b, 0x002c303a, 0x002a2f39, 0x00292e38, 0x00292e38, 0x00282d38, 0x00272c36, 0x00242934, 0x00242933, 0x00262a34, 0x00262934, 0x00242630, 0x0022242f, 0x00252832, 0x00262934, 0x00242832, 0x00222730, 0x0020252f, 0x00212530, 0x00232831, 0x00242a34, 0x00242b34, 0x00242b34, 0x00242b34, 0x00242c35, 0x00242c35, 0x00252c35, 0x00252c35, 0x00242b34, 0x00222832, 0x00202730, 0x00202730, 0x00212831, 0x00222831, 0x00222831, 0x00202730, 0x001d242d, 0x001a202b, 0x00192029, 0x00181e28, 0x00141b24, 0x000e141c, 0x000e141c, 0x00141a23, 0x00131923, 0x00111922, 0x000f1922, 0x00101a23, 0x00151f28, 0x001d2730, 0x00202a33, 0x0019232c, 0x00141d26, 0x00141d26, 0x00152028, 0x0016212a, 0x0018252d, 0x001c2931, 0x001b2832, 0x001a2832, 0x001c2936, 0x001d2a38, 0x001c2a38, 0x001d2837, 0x001d2837, 0x001c2734, 0x0018242f, 0x0014202a, 0x00101c26, 0x00101c26, 0x00121d28, 0x0014202a, 0x00131f29, 0x000a1521, 0x0007131f, 0x000e1a25, 0x0014202a, 0x00182430, 0x001b2731, 0x00202c36, 0x0022303a, 0x0023333c, 0x0022343c, 0x001d2f38, 0x00172830, 0x0014242c, 0x000e1c26, 0x00091620, 0x0009141e, 0x0009121c, 0x000a101c, 0x000a1019, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091019, 0x00091019, 0x00091019, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00081119, 0x000a101a, 0x000a101a, 0x00091118, 0x00091118, 0x00091118, 0x00081118, 0x00081118, 0x00081118, 0x00081118, 0x00091018, 0x000a1018, 0x000a1018, 0x0008111a, 0x0008111a, 0x0009111a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x00091019, 0x00091019, 0x00091019, 0x000c1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b131c, 0x000b131c, 0x000b131c, 0x000c141c, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141e, 0x000c141e, 0x000c141e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000b131c, 0x000b131c, 0x000b141b, 0x000c141b, 0x000c141b, 0x000b131c, 0x000b131c, 0x000b131c, 0x000b131c, 0x000b131c, 0x000b131c, 0x000b131c, 0x000b131c, 0x000b131c, 0x000b131c, 0x000c141e, 0x000c141f, 0x000c1420, 0x000d1520, 0x000d1520, 0x000d1520, 0x000d1520, 0x000c1520, 0x000b1520, 0x000a1520, 0x000b1620, 0x000b1720, 0x000c1823, 0x000f1b26, 0x0014202c, 0x001c2734, 0x001e2a38, 0x001d2733, 0x001c242f, 0x0018212b, 0x00151e27, 0x00131c24, 0x00131b24, 0x00121a24, 0x00111923, 0x00111923, 0x00111a24, 0x00141e27, 0x0018232c, 0x0018232c, 0x0018232c, 0x001a242e, 0x001d2831, 0x001c262f, 0x001b232c, 0x0018212a, 0x00172028, 0x00161f28, 0x0018222b, 0x0019242c, 0x001c272f, 0x00202a32, 0x00212c34, 0x00222c35, 0x00222c35, 0x00202b34, 0x00202b34, 0x00212c36, 0x00242d38, 0x00253039, 0x0027313c, 0x0028303c, 0x0028303c, 0x0028303b, 0x002a303a, 0x00293039, 0x00282f38, 0x00282f38, 0x00282f38, 0x00293039, 0x00293039, 0x00293038, 0x00282f38, 0x00282f38, 0x00293039, 0x00293038, 0x00282f38, 0x0029303a, 0x002a303c, 0x002b313c, 0x002d333e, 0x002e3440, 0x002d343f, 0x002c333e, 0x002d3440, 0x002f3641, 0x00313843, 0x00303742, 0x00303742, 0x00303641, 0x00303641, 0x00303641, 0x00303641, 0x00303743, 0x00323844, 0x00323944, 0x00313844, 0x00303743, 0x00303742, 0x00313843, 0x00313843, 0x00303742, 0x00303641, 0x00303641, 0x00303641, 0x00303641, 0x00313843, 0x00323844, 0x00313844, 0x00303843, 0x00303843, 0x00303843, 0x00313843, 0x00313843, 0x00313742, 0x00303742, 0x00303742, 0x00303742, 0x00303742, 0x00303742, 0x00303843, 0x00303844, 0x00303843, 0x00303843, 0x00323944, 0x00353c48, 0x00363d48, 0x00373e49, 0x00383f4a, 0x00383f4a, 0x00383e4a, 0x00373d48, 0x00363c48, 0x00353c47, 0x00343a45, 0x00333944, 0x00343844, 0x00343844, 0x00333743, 0x00323642, 0x00313642, 0x00303641, 0x00303541, 0x00313541, 0x00313542, 0x00323642, 0x00313542, 0x00313541, 0x00303440, 0x002d343e, 0x002c323c, 0x002c323c, 0x002c333c, 0x002e343d, 0x002e343e, 0x002e333e, 0x002f343f, 0x00313541, 0x00303541, 0x00303440, 0x002f343f, 0x002e333d, 0x002c303a, 0x002d313c, 0x002d323c, 0x002c303b, 0x002c303a, 0x002b2f3a, 0x002a2f39, 0x002a2f39, 0x00292e38, 0x00282d37, 0x00282c36, 0x00272c35, 0x00272934, 0x00232630, 0x0021242e, 0x00252833, 0x00282b35, 0x00242833, 0x00232831, 0x00232831, 0x00232832, 0x00242934, 0x00242a34, 0x00252c35, 0x00252c35, 0x00242c35, 0x00242c35, 0x00242c35, 0x00262c36, 0x00262c36, 0x00252c35, 0x00232933, 0x00202730, 0x00202730, 0x00202730, 0x00202730, 0x00212831, 0x00202730, 0x001f252f, 0x001c222c, 0x001b212b, 0x001a202a, 0x00181f28, 0x00161c24, 0x00121820, 0x00131921, 0x00141a24, 0x00121a24, 0x00101a23, 0x00101b24, 0x00121c25, 0x0018232c, 0x00202a33, 0x00232c36, 0x001c2730, 0x0019242d, 0x0018222b, 0x00152029, 0x0014222a, 0x0018262d, 0x001a2830, 0x00192730, 0x00182532, 0x001a2734, 0x001a2834, 0x001c2836, 0x001d2837, 0x001d2836, 0x001c2832, 0x0017232d, 0x00121e28, 0x00111d27, 0x00111c26, 0x00111c26, 0x0014202a, 0x00131d29, 0x00091420, 0x000d1824, 0x00111c25, 0x00141e28, 0x0016202a, 0x001c2630, 0x00212f38, 0x0023333c, 0x0022343c, 0x001d2e37, 0x00182830, 0x0014232c, 0x000c1a24, 0x0008151f, 0x0008141e, 0x0009121c, 0x000a101c, 0x000a1019, 0x00091018, 0x00080f17, 0x00080f17, 0x00091018, 0x00091019, 0x00091019, 0x00091019, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081218, 0x00081118, 0x00081119, 0x0009101a, 0x000a101a, 0x000a1119, 0x000a1219, 0x00091118, 0x00081118, 0x00081118, 0x00081118, 0x00081118, 0x00091018, 0x000a1018, 0x000a1018, 0x0009111a, 0x0008111a, 0x0009111a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x00091019, 0x00091019, 0x000c1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a121b, 0x000b131c, 0x000b131c, 0x000b141d, 0x000b141d, 0x000b141d, 0x000b151e, 0x000c151e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000b141e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000a141d, 0x000b141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000b141d, 0x000a141e, 0x000a141e, 0x000a141e, 0x000a141e, 0x000b141e, 0x000b141e, 0x000b141e, 0x000c141f, 0x000c141f, 0x000c141f, 0x000c151f, 0x000c151f, 0x000c151f, 0x000c1620, 0x000d1620, 0x000c1620, 0x000c1620, 0x000c1720, 0x000b1720, 0x000c1823, 0x000f1c28, 0x0015232e, 0x001c2936, 0x001e2b38, 0x001c2734, 0x001b2430, 0x001a232f, 0x0018202a, 0x00141c25, 0x00141c24, 0x00141c25, 0x00131c24, 0x00121a24, 0x00111a24, 0x00131e28, 0x0017232d, 0x0018242e, 0x0018242f, 0x001c2833, 0x001e2a34, 0x001c2830, 0x001a242c, 0x00162028, 0x00131c25, 0x00121b24, 0x00141c25, 0x00162028, 0x001a242c, 0x001e2830, 0x00202a33, 0x00202a33, 0x00202a33, 0x00202a33, 0x00212b35, 0x00232c37, 0x00242d37, 0x00242e38, 0x00263038, 0x00272f38, 0x00272f38, 0x0028303a, 0x002a323c, 0x002b323c, 0x002b313c, 0x002a303c, 0x00293039, 0x002a303a, 0x00293039, 0x00282f38, 0x00262c36, 0x00262c36, 0x00282e38, 0x00282f38, 0x00282f39, 0x002a303c, 0x00292f3b, 0x002a303b, 0x002c323c, 0x002e343f, 0x002f3440, 0x002e333e, 0x002d343d, 0x002e343f, 0x002f3540, 0x00303641, 0x00303742, 0x00323743, 0x00323743, 0x00333843, 0x00333844, 0x00333844, 0x00343944, 0x00343945, 0x00333944, 0x00323844, 0x00323844, 0x00323844, 0x00313843, 0x00303641, 0x00303641, 0x00303641, 0x00303541, 0x00303541, 0x00313642, 0x00313642, 0x00313642, 0x00323743, 0x00313843, 0x00323844, 0x00323944, 0x00333944, 0x00343943, 0x00343943, 0x00333943, 0x00333943, 0x00333944, 0x00323944, 0x00323a44, 0x00323944, 0x00323944, 0x00313743, 0x00313742, 0x00343844, 0x00343844, 0x00343945, 0x00353b47, 0x00343c47, 0x00333a45, 0x00333944, 0x00333944, 0x00343a45, 0x00333944, 0x00323844, 0x00343844, 0x00343844, 0x00343844, 0x00333844, 0x00323743, 0x00303642, 0x00303642, 0x00313642, 0x00313541, 0x00313541, 0x00313542, 0x00313542, 0x00303542, 0x002e343f, 0x002c323d, 0x002c323c, 0x002c343c, 0x002f353d, 0x0030363f, 0x00303440, 0x00303540, 0x00323642, 0x00323642, 0x00313541, 0x00303440, 0x00303440, 0x002e333e, 0x002f343f, 0x002f3440, 0x002e333d, 0x002c313c, 0x002c303b, 0x002c303b, 0x002c303b, 0x002b303a, 0x002c303a, 0x002a2f39, 0x00282c37, 0x00272b35, 0x00242833, 0x00242831, 0x00262934, 0x00262a34, 0x00242a34, 0x00242a34, 0x00242934, 0x00242a34, 0x00272b35, 0x00272c36, 0x00262c37, 0x00252c37, 0x00252d38, 0x00232b35, 0x00222a34, 0x00242c35, 0x00242c35, 0x00242c35, 0x00232a33, 0x00222832, 0x00212831, 0x001f2730, 0x001d252f, 0x001e2630, 0x00202730, 0x00202630, 0x001c232c, 0x001b212b, 0x001b212b, 0x00181f27, 0x00141b23, 0x0012181f, 0x00131920, 0x00151c24, 0x00141c24, 0x00131c24, 0x00131c24, 0x00131c24, 0x00141c25, 0x001a242e, 0x00222c38, 0x00212b37, 0x001f2834, 0x001c2531, 0x0018222d, 0x0015222b, 0x0015242b, 0x0018252d, 0x001a2830, 0x00192731, 0x00182632, 0x00182632, 0x001c2734, 0x001d2837, 0x001e2937, 0x001e2a35, 0x001b2631, 0x0015212c, 0x00131f28, 0x00131c27, 0x00111a24, 0x00111a24, 0x00131c26, 0x00101824, 0x00101925, 0x00101b27, 0x00131c28, 0x00141e2a, 0x0018222e, 0x00202b37, 0x0025333e, 0x0024323c, 0x001e2c35, 0x00182630, 0x0013202a, 0x00091720, 0x0008141f, 0x0008131d, 0x0009121c, 0x000a101c, 0x000a1019, 0x000a1018, 0x00091018, 0x00080f17, 0x00091018, 0x00091019, 0x00091019, 0x00091019, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00091019, 0x000a101a, 0x000a101a, 0x000a111a, 0x000a111a, 0x000a1119, 0x000a1118, 0x000a1118, 0x00091118, 0x00091118, 0x00091119, 0x000a111a, 0x000a111a, 0x000a1219, 0x00091119, 0x000a111a, 0x000a101a, 0x000a101a, 0x000b111b, 0x000b111b, 0x000a101a, 0x000a101a, 0x000a101a, 0x000c1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a121b, 0x000b131c, 0x000b131c, 0x000b141d, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c161f, 0x000d161f, 0x000d161f, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141f, 0x000b1420, 0x000b1420, 0x000b1420, 0x000b1420, 0x000a141f, 0x000b1520, 0x000b1520, 0x000b1520, 0x000c1620, 0x000c1620, 0x000c161f, 0x000c1720, 0x000c1720, 0x000d1720, 0x000d1721, 0x000e1822, 0x000e1822, 0x000c1821, 0x000c1821, 0x000c1823, 0x000d1c28, 0x0015242f, 0x001c2937, 0x001e2b38, 0x001c2734, 0x001a2430, 0x001a2430, 0x001b232e, 0x00182029, 0x00151d26, 0x00141c25, 0x00121a24, 0x00121a24, 0x00121c24, 0x00141f29, 0x0016232e, 0x00172430, 0x00182631, 0x001e2c37, 0x00202c36, 0x001b2730, 0x0017232c, 0x00162029, 0x00151f28, 0x00141c26, 0x00141c25, 0x00161f26, 0x001a222a, 0x001d262f, 0x001e2730, 0x001e2730, 0x001e2830, 0x00202b34, 0x00242d38, 0x00252f39, 0x00252f38, 0x00242e37, 0x00262f38, 0x00262e37, 0x00262e38, 0x0028313b, 0x002c343e, 0x002c343e, 0x002d333f, 0x002d343f, 0x002c333c, 0x002c323c, 0x00293039, 0x00272d37, 0x00252c35, 0x00252c35, 0x00262c36, 0x00272d37, 0x00282f39, 0x002a303c, 0x002a303c, 0x002b313c, 0x002c333e, 0x00303440, 0x00313541, 0x00303540, 0x002e343e, 0x002e343e, 0x002e343f, 0x00303742, 0x00313844, 0x00333844, 0x00333844, 0x00343844, 0x00343844, 0x00343944, 0x00343b46, 0x00343b47, 0x00343a45, 0x00333944, 0x00333944, 0x00323844, 0x00313844, 0x00303742, 0x00303742, 0x00303743, 0x00323643, 0x00323643, 0x00333743, 0x00333743, 0x00333743, 0x00333843, 0x00323844, 0x00333944, 0x00343945, 0x00343944, 0x00343943, 0x00343842, 0x00323842, 0x00343a43, 0x00353c45, 0x00343c47, 0x00333b46, 0x00343b46, 0x00343945, 0x00343844, 0x00323643, 0x00323642, 0x00323642, 0x00323642, 0x00333844, 0x00343b47, 0x00343c48, 0x00343c48, 0x00343b47, 0x00353c47, 0x00343b46, 0x00343b46, 0x00353a46, 0x00353a45, 0x00343a45, 0x00343945, 0x00333844, 0x00313844, 0x00313844, 0x00323844, 0x00333743, 0x00323742, 0x00323643, 0x00313543, 0x00303442, 0x002f3440, 0x002c333d, 0x002c333c, 0x002d343d, 0x0030373f, 0x00313840, 0x00303742, 0x00303742, 0x00323642, 0x00323642, 0x00313541, 0x00303440, 0x00303440, 0x00303440, 0x00303440, 0x00313541, 0x00323642, 0x00313640, 0x002f333d, 0x002d323c, 0x002c313b, 0x002c303b, 0x002c303b, 0x002c303b, 0x002b2f3a, 0x00292e38, 0x00282c36, 0x00272c35, 0x00272c35, 0x00262c35, 0x00252c35, 0x00242b34, 0x00242b34, 0x00242b34, 0x00272c36, 0x00292e39, 0x002a2f3b, 0x00282f3a, 0x0028303b, 0x00252d38, 0x00222b34, 0x00222a34, 0x00232b34, 0x00232b34, 0x00242a34, 0x00242a34, 0x00222a34, 0x00202831, 0x001d252f, 0x001c242d, 0x001f2630, 0x00202630, 0x001c232c, 0x001b212b, 0x001b212b, 0x00192028, 0x00141b22, 0x0010181d, 0x00131920, 0x00181f27, 0x001a2028, 0x00181f26, 0x00151e25, 0x00141e25, 0x00131c24, 0x00141e28, 0x001e2834, 0x00202936, 0x00202936, 0x001f2834, 0x001c2833, 0x001a2830, 0x0018252d, 0x0018262e, 0x0019272f, 0x00192730, 0x00182531, 0x00182531, 0x00192533, 0x001c2735, 0x001f2a38, 0x00202c38, 0x00202b37, 0x001c2833, 0x0017222c, 0x00141d28, 0x00131c24, 0x00111920, 0x00111922, 0x00121a24, 0x00111a25, 0x00101b27, 0x00101b27, 0x00131c29, 0x0018222e, 0x00202b38, 0x0026333e, 0x0022303b, 0x001c2833, 0x0018242e, 0x00121f28, 0x0008151f, 0x0008141e, 0x0008131d, 0x0009121c, 0x000a101c, 0x000a1019, 0x000a1018, 0x00091018, 0x00091018, 0x00091018, 0x00091019, 0x00091019, 0x00091019, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00091019, 0x000a101a, 0x000a101a, 0x000b111b, 0x000b111b, 0x000a111a, 0x000a1219, 0x000a1219, 0x000a1219, 0x000a1219, 0x000a121a, 0x000a121b, 0x000a121b, 0x000a1219, 0x000a1219, 0x000a121a, 0x000b111b, 0x000b111b, 0x000b111b, 0x000b111b, 0x000a101a, 0x000a101a, 0x000a101a, 0x000c1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0009121b, 0x000b131c, 0x000b131c, 0x000a141d, 0x000a141d, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c161f, 0x000d161f, 0x000d161f, 0x000c151e, 0x000c151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c151e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141f, 0x000c1420, 0x000c1420, 0x000c1420, 0x000c1420, 0x000c1420, 0x000b1520, 0x000b1520, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1720, 0x000c1720, 0x000d1720, 0x000d1720, 0x000d1822, 0x000d1822, 0x000d1822, 0x000c1822, 0x000c1822, 0x000c1823, 0x000d1c27, 0x0014242f, 0x001c2937, 0x001d2a38, 0x001a2633, 0x00182430, 0x00182430, 0x001a232e, 0x001a232c, 0x00182029, 0x00151e27, 0x00141c25, 0x00141c25, 0x00141d26, 0x0015202a, 0x0018242f, 0x00182531, 0x001a2733, 0x00202e39, 0x00202c36, 0x0019242d, 0x00152129, 0x0018232b, 0x001a242c, 0x001a232c, 0x0019212b, 0x001a2229, 0x001b232a, 0x001c242d, 0x001e2630, 0x00202832, 0x00202a32, 0x00202b34, 0x00232c37, 0x00242e39, 0x00252f38, 0x00242f37, 0x00252f37, 0x00252e37, 0x00272f38, 0x002a333c, 0x002c3440, 0x002d343f, 0x002e343f, 0x002e3440, 0x002e343f, 0x002e343e, 0x002b313b, 0x00282f38, 0x00262c36, 0x00262c36, 0x00272d37, 0x00282f38, 0x002b313c, 0x002d333f, 0x002d343f, 0x002e3440, 0x00303541, 0x00313642, 0x00323642, 0x00323642, 0x00303640, 0x002f3540, 0x00303640, 0x00313843, 0x00343b46, 0x00353b47, 0x00343844, 0x00343844, 0x00343844, 0x00343945, 0x00343b46, 0x00343a45, 0x00333944, 0x00323844, 0x00323844, 0x00323844, 0x00333944, 0x00333945, 0x00333944, 0x00323844, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00333945, 0x00343b47, 0x00343b47, 0x00353a44, 0x00343944, 0x00333841, 0x00303740, 0x00323842, 0x00353c46, 0x00353c49, 0x00343c48, 0x00343c48, 0x00353b47, 0x00363a47, 0x00343a47, 0x00343945, 0x00333844, 0x00333844, 0x00343a45, 0x00353d48, 0x00373f4a, 0x00373e4a, 0x00363c48, 0x00363c48, 0x00353c47, 0x00353c47, 0x00353a46, 0x00343944, 0x00343844, 0x00343844, 0x00333844, 0x00333945, 0x00343945, 0x00343945, 0x00343844, 0x00333743, 0x00323644, 0x00333744, 0x00333744, 0x00323744, 0x00303742, 0x00303741, 0x00313841, 0x00323940, 0x00323841, 0x00313843, 0x00303742, 0x00323642, 0x00323642, 0x00313541, 0x00313541, 0x00313541, 0x00313541, 0x00323642, 0x00323643, 0x00333843, 0x00333844, 0x00333743, 0x00313541, 0x00303440, 0x002f333e, 0x002d313c, 0x002c303b, 0x002a2f39, 0x00282c36, 0x00282c36, 0x00272c35, 0x00272b35, 0x00262c35, 0x00252c35, 0x00252c35, 0x00242b34, 0x00242933, 0x00242833, 0x00242934, 0x00252a36, 0x00262c38, 0x00282e39, 0x00272e39, 0x00242d36, 0x00222b34, 0x00212933, 0x00212932, 0x00232932, 0x00232933, 0x00222933, 0x00202831, 0x001d252f, 0x001c242c, 0x001d242e, 0x001e242e, 0x001c232c, 0x00192029, 0x00192029, 0x001b212a, 0x00161c24, 0x0012191f, 0x00131920, 0x00171d26, 0x001c232c, 0x001b232a, 0x00182128, 0x00162028, 0x00141f26, 0x00131c26, 0x0018222e, 0x001e2834, 0x00202936, 0x001f2836, 0x001d2834, 0x001d2a33, 0x001e2a33, 0x001c2830, 0x001b2830, 0x00192630, 0x00182530, 0x00182530, 0x00192531, 0x00182432, 0x001c2835, 0x00212d38, 0x00212c38, 0x00202c37, 0x001c2832, 0x0018212c, 0x00171f27, 0x00141c24, 0x00121b24, 0x00121a24, 0x00111a25, 0x00101b27, 0x00111b27, 0x00131c29, 0x0018222e, 0x00202b37, 0x0024323d, 0x001f2c38, 0x001a2732, 0x0017232d, 0x00111d28, 0x000a1720, 0x0009141f, 0x0009141d, 0x0009121c, 0x000a111b, 0x000a1019, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091019, 0x00081019, 0x00091019, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00091119, 0x000a101a, 0x000a101b, 0x000b111c, 0x000b111c, 0x000a121b, 0x000a1219, 0x000b1219, 0x000b1219, 0x000b1219, 0x000b121a, 0x000b121b, 0x000b121b, 0x000a121a, 0x000a1218, 0x000a1219, 0x000b111a, 0x000b111a, 0x000b111a, 0x000b111a, 0x000b111a, 0x000a101a, 0x000a101a, 0x000c1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0008121b, 0x000b131c, 0x000b131c, 0x000a141c, 0x000a141d, 0x000a141d, 0x000b151e, 0x000c161f, 0x000c161f, 0x000d161f, 0x000d161f, 0x000e1720, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c1620, 0x000c1721, 0x000c1721, 0x000c1822, 0x000d1823, 0x000c1821, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000d1a24, 0x000e1d26, 0x0015252e, 0x001c2a35, 0x001c2934, 0x00172430, 0x0017242f, 0x0017232f, 0x0018242f, 0x0019232d, 0x0018212c, 0x0018202a, 0x00171f28, 0x00171f28, 0x00162028, 0x0016202b, 0x00182630, 0x001a2833, 0x001c2934, 0x0022303c, 0x001f2c36, 0x0018242d, 0x00172329, 0x0018242a, 0x001a242c, 0x001b242d, 0x001c252e, 0x001c252d, 0x001d252d, 0x001e2730, 0x00202830, 0x00212a33, 0x00202b33, 0x00212b34, 0x00242e38, 0x0025303a, 0x00253039, 0x00253038, 0x00242f38, 0x00253038, 0x00273039, 0x002c333d, 0x002e3440, 0x002f3440, 0x002d343f, 0x002c323e, 0x002d343d, 0x002e343e, 0x002c333c, 0x002a3039, 0x00282e38, 0x00272d37, 0x00282f38, 0x002a313b, 0x002d343f, 0x00303641, 0x00303742, 0x00303742, 0x00303743, 0x00313642, 0x00323642, 0x00333743, 0x00313842, 0x00323842, 0x00333943, 0x00343b44, 0x00363c47, 0x00373c48, 0x00353945, 0x00343944, 0x00343944, 0x00343945, 0x00343b46, 0x00323844, 0x00313843, 0x00323843, 0x00323844, 0x00323844, 0x00343a45, 0x00343b47, 0x00343b46, 0x00343a45, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00343944, 0x00343a45, 0x00363c49, 0x00383f4c, 0x00393f4c, 0x003a3e4b, 0x00383c48, 0x00343944, 0x00303640, 0x00323842, 0x00363c48, 0x00363d4a, 0x00353d4a, 0x00363d4a, 0x00383d4a, 0x00383d4b, 0x00373c4a, 0x00353c49, 0x00343b47, 0x00343b46, 0x00343c47, 0x00353d49, 0x00373e4b, 0x00373e4b, 0x00373d4a, 0x00363c48, 0x00363c48, 0x00353c48, 0x00343a46, 0x00323844, 0x00323843, 0x00323844, 0x00333844, 0x00343b47, 0x00353c47, 0x00353b47, 0x00353a46, 0x00343944, 0x00343845, 0x00343947, 0x00353a48, 0x00353a48, 0x00343a45, 0x00343a45, 0x00343944, 0x00343a43, 0x00333943, 0x00323844, 0x00303742, 0x00323642, 0x00333743, 0x00333843, 0x00333843, 0x00333743, 0x00323642, 0x00313541, 0x00323642, 0x00333643, 0x00333743, 0x00343844, 0x00343944, 0x00343844, 0x00323642, 0x002f343f, 0x002c303c, 0x00292e39, 0x00282c36, 0x00272b35, 0x00262a34, 0x00262a34, 0x00262c35, 0x00262c36, 0x00252c35, 0x00242a34, 0x00222831, 0x00222731, 0x00222732, 0x00232833, 0x00242934, 0x00252c37, 0x00282f3a, 0x0028303a, 0x00252d36, 0x00222a34, 0x00202831, 0x00222832, 0x00232932, 0x00222933, 0x00212932, 0x00202830, 0x001d252f, 0x001d242d, 0x001c232c, 0x001a202a, 0x00171d27, 0x00151c25, 0x00181f28, 0x00181f28, 0x00141c22, 0x00111820, 0x00141c24, 0x001b232c, 0x001d272e, 0x001b252c, 0x0018242b, 0x00142027, 0x00111d26, 0x00131e2a, 0x001b2632, 0x00202a37, 0x00202a37, 0x001d2834, 0x001a2730, 0x001c2831, 0x001c2831, 0x001c2830, 0x001c2830, 0x001c2830, 0x001c2831, 0x001a2631, 0x0017232f, 0x0017232e, 0x001b2632, 0x001f2a36, 0x00202c38, 0x00202b37, 0x001c2631, 0x001a222c, 0x00172028, 0x00141d26, 0x00131b24, 0x00111a25, 0x00101b27, 0x00101b27, 0x00121c28, 0x0016202c, 0x001c2834, 0x001f2d38, 0x001a2934, 0x00182530, 0x0014222d, 0x000f1c27, 0x000c1821, 0x000c161f, 0x000b151e, 0x000c141c, 0x000b131b, 0x000a131a, 0x00081319, 0x00081319, 0x00081219, 0x00081119, 0x00081119, 0x00081019, 0x00081019, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081019, 0x0008111a, 0x0008111a, 0x0009121b, 0x000a121b, 0x000b131c, 0x000b131d, 0x000b131e, 0x000b131c, 0x000b131c, 0x000c131c, 0x000c131a, 0x000c131a, 0x000c131b, 0x000c131c, 0x000c131c, 0x000b131a, 0x000b1418, 0x000c1419, 0x000c131a, 0x000c131a, 0x000c131a, 0x000c131a, 0x000c121a, 0x000b111b, 0x000b111b, 0x000c1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0009131c, 0x000b131c, 0x000b131c, 0x000a141d, 0x000a141d, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000d161f, 0x000d161f, 0x000e1720, 0x000e1720, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d1720, 0x000c1821, 0x000c1822, 0x000c1823, 0x000d1924, 0x000c1922, 0x000b1920, 0x000b1920, 0x000c1920, 0x000d1921, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1d27, 0x0016252e, 0x001c2a35, 0x001a2833, 0x0016242f, 0x0015232e, 0x0016232f, 0x00182430, 0x001a242f, 0x001a232e, 0x0019222c, 0x0019222c, 0x001a232c, 0x0018222c, 0x0018232c, 0x001b2833, 0x001c2935, 0x001c2a35, 0x00202d38, 0x001d2a34, 0x001b272f, 0x001a262c, 0x0018242b, 0x0019232c, 0x001a242c, 0x0019232c, 0x0019242c, 0x001c262e, 0x001e2830, 0x00202830, 0x00202831, 0x00202a32, 0x00232c36, 0x0025303a, 0x0025303a, 0x00253039, 0x00253038, 0x00253038, 0x00242f38, 0x00273038, 0x002c323c, 0x002e3440, 0x002e3440, 0x002c323e, 0x002b313c, 0x002b313c, 0x002c323c, 0x002d343d, 0x002d343d, 0x002c313c, 0x002a303a, 0x002b313c, 0x002d333d, 0x002f3440, 0x00303642, 0x00303742, 0x00303742, 0x00313742, 0x00313642, 0x00323742, 0x00343844, 0x00333944, 0x00343b44, 0x00353c46, 0x00363c46, 0x00373d48, 0x00383c48, 0x00363a46, 0x00343944, 0x00343944, 0x00343944, 0x00333944, 0x00323743, 0x00323743, 0x00333743, 0x00333844, 0x00343944, 0x00353c47, 0x00353c47, 0x00353c47, 0x00343c47, 0x00343a45, 0x00353945, 0x00353945, 0x00353a45, 0x00363a46, 0x00373c48, 0x00383e4c, 0x0039404d, 0x003c414f, 0x003c414e, 0x00383e49, 0x00333944, 0x00303741, 0x00343a44, 0x00373e49, 0x00373f4c, 0x00383f4c, 0x0038404c, 0x003a404d, 0x003a3f4c, 0x00383e4c, 0x00353d4a, 0x00343c48, 0x00343c48, 0x00343c48, 0x00363d4a, 0x00373e4b, 0x00373f4c, 0x00373d4a, 0x00363c49, 0x00353c48, 0x00353c47, 0x00343a45, 0x00323844, 0x00323844, 0x00343b46, 0x00363c48, 0x00363d48, 0x00373d48, 0x00363c48, 0x00373c48, 0x00363b47, 0x00363b48, 0x00363b48, 0x00373b48, 0x00373c48, 0x00343b47, 0x00343a46, 0x00343a44, 0x00343b44, 0x00343a44, 0x00333944, 0x00323844, 0x00333743, 0x00343844, 0x00343944, 0x00343944, 0x00343844, 0x00333843, 0x00323642, 0x00323642, 0x00323642, 0x00323642, 0x00333743, 0x00343944, 0x00343944, 0x00333844, 0x00313541, 0x002f333f, 0x002c303c, 0x002a2f39, 0x00282c36, 0x00262a34, 0x00262b34, 0x00262c36, 0x00252c35, 0x00242c35, 0x00242a34, 0x00222832, 0x00222831, 0x00232832, 0x00232834, 0x00242935, 0x00242b36, 0x00282e39, 0x0029313b, 0x0028303a, 0x00252e37, 0x00222c34, 0x00222a34, 0x00232a34, 0x00232b34, 0x00222a34, 0x00212933, 0x00202831, 0x00202730, 0x001d242d, 0x0019202a, 0x00161d27, 0x00151c25, 0x00141c25, 0x00141c24, 0x00131b21, 0x00101820, 0x00121923, 0x0018202a, 0x001b262e, 0x001d2931, 0x001d2931, 0x0018242c, 0x00121e29, 0x00111c28, 0x0017222e, 0x00202a36, 0x00242d38, 0x00212c37, 0x001c2833, 0x001b2731, 0x001c2831, 0x001d2931, 0x001d2932, 0x001f2b34, 0x00202b34, 0x001d2934, 0x00182430, 0x0014202c, 0x0014202c, 0x00192430, 0x001d2935, 0x001f2a36, 0x001d2632, 0x001b232d, 0x0018202a, 0x00171f28, 0x00151d27, 0x00131c26, 0x00101b27, 0x00101b27, 0x00101b27, 0x00141e2a, 0x0018242f, 0x00192833, 0x00162631, 0x0015242f, 0x00111f2a, 0x000c1a24, 0x000c1820, 0x000d1720, 0x000d1720, 0x000e161e, 0x000e161d, 0x000c161c, 0x000b151c, 0x0009141a, 0x00081319, 0x00091219, 0x0008111a, 0x00081019, 0x00081019, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081119, 0x0009111a, 0x0009111a, 0x000a121b, 0x000b131c, 0x000b131c, 0x000c121d, 0x000c121e, 0x000c121c, 0x000c131c, 0x000c131c, 0x000c141b, 0x000d141b, 0x000d141c, 0x000d141d, 0x000d141c, 0x000c141b, 0x000c1419, 0x000c141a, 0x000c141a, 0x000c131a, 0x000c131a, 0x000c131a, 0x000c121a, 0x000b111b, 0x000b111b, 0x000c1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a141c, 0x000c141c, 0x000c141d, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000d1720, 0x000d1820, 0x000d1720, 0x000d1721, 0x000d1721, 0x000e1822, 0x000e1822, 0x000d1821, 0x000d1721, 0x000d1721, 0x000d1721, 0x000d1721, 0x000d1721, 0x000d1720, 0x000d1720, 0x000e1720, 0x000e1720, 0x000d1720, 0x000c1822, 0x000c1821, 0x000c1821, 0x000c1821, 0x000d1821, 0x000e1823, 0x000e1824, 0x000d1824, 0x000d1924, 0x000d1924, 0x000c1923, 0x000c1923, 0x000e1823, 0x000e1823, 0x000f1824, 0x000f1924, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000f1b25, 0x00101f28, 0x0017242f, 0x001b2834, 0x00182631, 0x0015232e, 0x0015232e, 0x0016232e, 0x0019242f, 0x001c2630, 0x001b2530, 0x001a2530, 0x001a2530, 0x001a2630, 0x0018242f, 0x0018242f, 0x001b2832, 0x001e2c36, 0x001e2c35, 0x001e2c36, 0x001b2832, 0x0019252f, 0x0019262c, 0x0018242b, 0x0018232b, 0x0018222b, 0x0018212a, 0x0018212a, 0x001c242d, 0x001d2630, 0x001d2830, 0x001f2831, 0x00202a34, 0x00222c36, 0x00242e38, 0x00242f38, 0x00242e38, 0x00242f38, 0x00242e37, 0x00242d36, 0x00252e37, 0x002a323b, 0x002b343d, 0x002c333c, 0x0029313c, 0x0028303a, 0x0028303a, 0x002b333c, 0x002e3540, 0x00303741, 0x00303641, 0x002e3440, 0x002e343f, 0x002e3440, 0x002e333e, 0x002e333f, 0x00303440, 0x00303540, 0x00303540, 0x00303642, 0x00323844, 0x00333a45, 0x00343b46, 0x00343c48, 0x00353d48, 0x00363d48, 0x00373e49, 0x00383e49, 0x00353b47, 0x00343944, 0x00333944, 0x00333844, 0x00333844, 0x00333743, 0x00323643, 0x00323642, 0x00333843, 0x00343945, 0x00353c47, 0x00353c48, 0x00363c48, 0x00363c48, 0x00363c48, 0x00363c48, 0x00363c48, 0x00373c48, 0x00373d4a, 0x00383e4a, 0x00383f4c, 0x00383f4c, 0x00383e4b, 0x00383e4a, 0x00363c48, 0x00343b47, 0x00343b46, 0x00373d48, 0x00383f4c, 0x0038404d, 0x0038404c, 0x0038404d, 0x003b404e, 0x003a3f4c, 0x00383e4b, 0x00363d49, 0x00363c48, 0x00363d48, 0x00373d48, 0x00383e4b, 0x00383f4c, 0x0038404c, 0x00383f4c, 0x00373c4a, 0x00353b48, 0x00353c48, 0x00353c47, 0x00353b47, 0x00343b46, 0x00343c47, 0x00363c48, 0x00373d48, 0x00383f4b, 0x00383f4c, 0x00383e4c, 0x00383d4a, 0x00373d4a, 0x00373c49, 0x00363c48, 0x00343c48, 0x00343a46, 0x00343945, 0x00343a44, 0x00343a44, 0x00343a44, 0x00333a45, 0x00343a46, 0x00343a45, 0x00333844, 0x00333944, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00333743, 0x00323642, 0x00313642, 0x00323643, 0x00333843, 0x00333944, 0x00333844, 0x00323743, 0x00313642, 0x00303440, 0x002d323d, 0x002b303b, 0x00282e39, 0x00272d38, 0x00262c37, 0x00252c36, 0x00242b35, 0x00242b34, 0x00232932, 0x00232932, 0x00232832, 0x00242934, 0x00242b35, 0x00272e38, 0x00282f39, 0x00272f39, 0x0028303b, 0x0028303b, 0x00273038, 0x00262e38, 0x00242d36, 0x00242c35, 0x00232c34, 0x00232b34, 0x00222a33, 0x00202831, 0x001e2730, 0x001b242d, 0x00162028, 0x00161e27, 0x00151d26, 0x00141c24, 0x00111a20, 0x00101820, 0x00111822, 0x00161f29, 0x001a252f, 0x001c2832, 0x00202c36, 0x001c2831, 0x0015202b, 0x00101b25, 0x00142028, 0x001e2831, 0x00242d36, 0x00232d38, 0x00202c38, 0x001e2a37, 0x001d2834, 0x001c2733, 0x001c2832, 0x001d2933, 0x00202c36, 0x00202b37, 0x001c2733, 0x0016212c, 0x00131f29, 0x00131f29, 0x0018242e, 0x001c2833, 0x001c2732, 0x001a2430, 0x0017202c, 0x0017202c, 0x00171f2c, 0x00151e2a, 0x00141c27, 0x00121b26, 0x00101b25, 0x00131c27, 0x0014202b, 0x0015242e, 0x0014242e, 0x0013222d, 0x000e1d28, 0x000a1924, 0x000b1821, 0x000c1820, 0x000d1720, 0x000f1820, 0x000f1720, 0x000e171f, 0x000c151d, 0x0009131a, 0x00081319, 0x00081219, 0x0008111a, 0x0008111a, 0x00091119, 0x00091119, 0x00091119, 0x00091219, 0x00091219, 0x00091219, 0x00091219, 0x000a1219, 0x000a121b, 0x000a121b, 0x000b131b, 0x000c141c, 0x000c141c, 0x000c141d, 0x000c131d, 0x000c141c, 0x000c141b, 0x000c141b, 0x000c151c, 0x000c141c, 0x000c141c, 0x000c141c, 0x000c141c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c141c, 0x000c141c, 0x000c141c, 0x000c141c, 0x000c141c, 0x000b131c, 0x000b131c, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a141d, 0x000c141d, 0x000c141d, 0x000c151e, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b161f, 0x000b171f, 0x000b171f, 0x000c1820, 0x000c1820, 0x000c1821, 0x000c1822, 0x000c1822, 0x000d1923, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1822, 0x000e1822, 0x000e1822, 0x00101820, 0x000f1820, 0x000d1822, 0x000c1924, 0x000c1823, 0x000b1822, 0x000b1822, 0x000d1822, 0x000f1824, 0x000f1824, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000f1824, 0x000f1824, 0x000f1924, 0x00101a24, 0x00101a24, 0x000e1a24, 0x000f1a24, 0x00101c26, 0x00122029, 0x0018242f, 0x001a2833, 0x00182530, 0x0015232e, 0x0015232e, 0x0016232e, 0x0019242f, 0x001c2630, 0x001b2630, 0x00192630, 0x001a2730, 0x00192730, 0x0018252f, 0x00182530, 0x00192730, 0x001d2b34, 0x001f2c36, 0x001d2b34, 0x001b2831, 0x0019252f, 0x0018242b, 0x0018242a, 0x0017212a, 0x00162029, 0x00182029, 0x001a222b, 0x001d252f, 0x001e2730, 0x001e2830, 0x001f2932, 0x00202b34, 0x00222c36, 0x00242d38, 0x00242e38, 0x00252f39, 0x00242e37, 0x00242d36, 0x00222c35, 0x00252e37, 0x0028323b, 0x0029333c, 0x0029323c, 0x0028303a, 0x00283039, 0x002a323b, 0x002c343d, 0x002f3640, 0x00313843, 0x00313843, 0x00303641, 0x002e343f, 0x002c333c, 0x002c303b, 0x002c303b, 0x002e333c, 0x002f343e, 0x002f353f, 0x00303642, 0x00323844, 0x00333a45, 0x00333c47, 0x00343c48, 0x00343c48, 0x00343d48, 0x00353d48, 0x00363c48, 0x00343a45, 0x00333944, 0x00343944, 0x00333843, 0x00323741, 0x00333743, 0x00323643, 0x00323642, 0x00333743, 0x00343945, 0x00353c47, 0x00353c47, 0x00363c48, 0x00363d49, 0x00373d48, 0x00373f49, 0x0037404a, 0x0038404b, 0x0038404c, 0x0038404c, 0x0038404b, 0x00363e49, 0x00343c47, 0x00333b46, 0x00343c47, 0x00363e48, 0x00383f4a, 0x0038404c, 0x0039414d, 0x0039414e, 0x0038404d, 0x00383f4c, 0x00383e4b, 0x00383e4b, 0x00373d48, 0x00373d48, 0x00373d48, 0x00383e49, 0x00383e49, 0x00383e4b, 0x00383f4c, 0x0038404c, 0x00383f4c, 0x00383e4c, 0x00353c49, 0x00363c48, 0x00373d48, 0x00373d48, 0x00353c47, 0x00343c47, 0x00343c47, 0x00353c48, 0x00373e4a, 0x00383e4c, 0x0038404c, 0x00373f4c, 0x00373e4b, 0x00373d4a, 0x00353c48, 0x00343a45, 0x00343944, 0x00343844, 0x00343944, 0x00343943, 0x00343a44, 0x00343c47, 0x00343b47, 0x00323844, 0x00303642, 0x00303641, 0x00323642, 0x00323642, 0x00333843, 0x00343945, 0x00353a46, 0x00323844, 0x00313843, 0x00303641, 0x00303641, 0x00313843, 0x00323844, 0x00323844, 0x00323844, 0x00313843, 0x00303641, 0x002e3440, 0x002c323d, 0x002a303c, 0x00282e3a, 0x00262c38, 0x00252c35, 0x00252c35, 0x00242b34, 0x00242a33, 0x00242a33, 0x00242c34, 0x00252d36, 0x00272f38, 0x00283039, 0x00262e39, 0x00272f39, 0x0028303b, 0x0028313a, 0x0028313a, 0x00283039, 0x00273038, 0x00252e37, 0x00242c35, 0x00222a34, 0x00202832, 0x001d2730, 0x001b252f, 0x0018232c, 0x0016202a, 0x00151f28, 0x00141d24, 0x00111c20, 0x0010191f, 0x00101921, 0x00141e28, 0x001c2731, 0x001c2832, 0x00202c36, 0x001f2c35, 0x001a252f, 0x00111b23, 0x00151f26, 0x001c252c, 0x00202b32, 0x00232d38, 0x00222d3b, 0x00212c3b, 0x001f2b37, 0x001c2834, 0x00192531, 0x0018242f, 0x001a2630, 0x001e2a36, 0x001f2b37, 0x001b2731, 0x0015212a, 0x00121e26, 0x00131f27, 0x0018242c, 0x001c2731, 0x001b2532, 0x00192430, 0x0019222f, 0x0019202d, 0x0018202c, 0x00171f28, 0x00141c25, 0x00131c25, 0x00141e27, 0x00142029, 0x0014232c, 0x0014242d, 0x0011222c, 0x000c1c28, 0x00091924, 0x000b1822, 0x000b1822, 0x000d1820, 0x00101820, 0x00101820, 0x000e1720, 0x000c141d, 0x0009131a, 0x00081319, 0x00081319, 0x000a121b, 0x000a121b, 0x000a121a, 0x000a1219, 0x000a1219, 0x000b131a, 0x000b131a, 0x000b131a, 0x000b131a, 0x000b131a, 0x000b131a, 0x000b131a, 0x000c141b, 0x000c141b, 0x000c141b, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000b151d, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a141d, 0x000c141d, 0x000c141d, 0x000c151f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000c1820, 0x000c1820, 0x000c1822, 0x000c1823, 0x000c1823, 0x000c1823, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1823, 0x000e1822, 0x000e1822, 0x00101821, 0x000f1821, 0x000d1822, 0x000c1924, 0x000c1924, 0x000c1923, 0x000c1924, 0x000e1824, 0x000f1824, 0x000f1924, 0x000e1924, 0x000e1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x000f1a24, 0x000f1b25, 0x00101c26, 0x00121e28, 0x0018242e, 0x001b2833, 0x00182530, 0x0015232e, 0x0015222e, 0x0016232e, 0x0019242f, 0x001b2430, 0x001a2530, 0x00192630, 0x00192731, 0x00192731, 0x00182530, 0x00182530, 0x00182630, 0x001b2833, 0x001f2c37, 0x001e2c35, 0x001b2832, 0x001a2630, 0x0018252c, 0x0018242b, 0x0017212a, 0x0017212a, 0x001a232c, 0x001c242d, 0x001c242e, 0x001c262f, 0x001d2730, 0x00202932, 0x00222c37, 0x00242d38, 0x00242e38, 0x00252f39, 0x0026303b, 0x00253038, 0x00242e37, 0x00242e37, 0x00273038, 0x00273039, 0x00273139, 0x0028313a, 0x0028303a, 0x002a323c, 0x002d343d, 0x002c343c, 0x002c343e, 0x00303641, 0x00303742, 0x00303641, 0x002f353f, 0x002d343d, 0x002c313b, 0x002c313b, 0x002e333c, 0x002f343f, 0x002f3540, 0x00303642, 0x00313843, 0x00323944, 0x00323a45, 0x00343c47, 0x00343c47, 0x00343c47, 0x00333b46, 0x00333944, 0x00343a45, 0x00343a45, 0x00343944, 0x00333843, 0x00323742, 0x00333743, 0x00333743, 0x00333743, 0x00343844, 0x00353a46, 0x00373c48, 0x00373d48, 0x00383e4b, 0x00383f4c, 0x0038404b, 0x0038404c, 0x0038404c, 0x0038404c, 0x0038404c, 0x00383f4c, 0x00373f4a, 0x00363e49, 0x00343c48, 0x00343c48, 0x00363f49, 0x0038414c, 0x003a424d, 0x003a424e, 0x0039414e, 0x003a424f, 0x0039414e, 0x00383f4c, 0x00363c48, 0x00363d48, 0x00383e49, 0x00383e49, 0x00383e49, 0x00383e49, 0x00383e49, 0x00383e4a, 0x00383f4c, 0x0038404c, 0x00383f4d, 0x00383f4e, 0x00383d4c, 0x00383e4b, 0x00373e49, 0x00373e49, 0x00363d48, 0x00353d48, 0x00343c47, 0x00333b48, 0x00333c48, 0x00343c49, 0x00353e4b, 0x00353f4b, 0x00373f4c, 0x00373e4b, 0x00343c48, 0x00343a46, 0x00343944, 0x00343944, 0x00343944, 0x00343943, 0x00343b45, 0x00343c48, 0x00353d48, 0x00343b47, 0x00333944, 0x00313843, 0x00313642, 0x00313541, 0x00313541, 0x00343945, 0x00373c48, 0x00343a45, 0x00303742, 0x002f3541, 0x002f3440, 0x00313843, 0x00333944, 0x00333944, 0x00333944, 0x00333944, 0x00313843, 0x00303742, 0x002e3440, 0x002e3440, 0x002d343f, 0x002b303c, 0x00282e38, 0x00282e38, 0x00272d38, 0x00272c37, 0x00262d37, 0x00262d37, 0x00272f38, 0x00272f38, 0x00272f3a, 0x00272f3a, 0x00272f39, 0x00272f39, 0x00252e37, 0x00252d37, 0x00252d37, 0x00252d36, 0x00252e37, 0x00242d36, 0x00242c37, 0x00222c36, 0x001f2934, 0x001c2731, 0x001b2530, 0x0018232d, 0x0017202a, 0x00162026, 0x00141e24, 0x00131c21, 0x00131c24, 0x0017212b, 0x001d2a34, 0x001f2c36, 0x00202d37, 0x00202e38, 0x001e2933, 0x00151d26, 0x00151e25, 0x0019242b, 0x001f2930, 0x00222c38, 0x00242f3c, 0x0024303d, 0x00212d39, 0x001e2a36, 0x001b2732, 0x0018242f, 0x0017222c, 0x00182430, 0x001d2935, 0x001e2a35, 0x001a262f, 0x0015212a, 0x00131f27, 0x00131f28, 0x0018222d, 0x001a2430, 0x001c2632, 0x001c2431, 0x001b2430, 0x001a232f, 0x0018212a, 0x00161f28, 0x00141f27, 0x00141f28, 0x00142029, 0x0014232c, 0x0014232c, 0x0011212c, 0x000c1c27, 0x000b1924, 0x000c1924, 0x000c1924, 0x000e1922, 0x000f1921, 0x000f1921, 0x000e1820, 0x000c151e, 0x000a141c, 0x0009141b, 0x0009131b, 0x000a121b, 0x000a121b, 0x000a121a, 0x000a1219, 0x000a121a, 0x000a131a, 0x000a131a, 0x000b131a, 0x000b131a, 0x000b131b, 0x000b131b, 0x000b131b, 0x000c141c, 0x000c151c, 0x000c151c, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000b151e, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b141e, 0x000c141e, 0x000c141e, 0x000c1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000c1720, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000d1922, 0x000d1924, 0x000d1924, 0x000c1822, 0x000c1822, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000f1824, 0x000f1824, 0x000d1824, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000d1b24, 0x000f1a24, 0x00101924, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101b25, 0x00101b25, 0x00101b25, 0x00131d28, 0x0018232d, 0x001c2733, 0x00182430, 0x0016212d, 0x0016212d, 0x0016212d, 0x0018222e, 0x0018222e, 0x0018232f, 0x00182430, 0x00182631, 0x00192732, 0x00182430, 0x00182530, 0x00182531, 0x001b2834, 0x001e2c38, 0x001e2c37, 0x001c2834, 0x001c2830, 0x001b272d, 0x0019252c, 0x0018222b, 0x0018222b, 0x0019232c, 0x001a242f, 0x001b2430, 0x001c2731, 0x001d2732, 0x001f2833, 0x00232d38, 0x00242d38, 0x00242e38, 0x00252f39, 0x0026303b, 0x0026303a, 0x0027313a, 0x0026313a, 0x00273039, 0x00262f38, 0x00242e36, 0x00252f38, 0x0028313b, 0x002c343e, 0x002f353f, 0x002c333c, 0x002a313c, 0x002e3440, 0x00303641, 0x00303540, 0x002e343e, 0x002c333c, 0x002e333d, 0x002f343e, 0x0030343f, 0x00303540, 0x00303741, 0x00303742, 0x00313843, 0x00303844, 0x00303844, 0x00323a44, 0x00323a44, 0x00323a44, 0x00323a44, 0x00343a45, 0x00343b46, 0x00343a46, 0x00343944, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00343945, 0x00353a46, 0x00383c48, 0x00383e4a, 0x0039404b, 0x003a404c, 0x003b414e, 0x003a404d, 0x0039414d, 0x0039414c, 0x0039414c, 0x0038404d, 0x0038404c, 0x0037404b, 0x0038404b, 0x0038404b, 0x0038404c, 0x003a424e, 0x003c444f, 0x003c4450, 0x003c4450, 0x003b4350, 0x003a424f, 0x003a424f, 0x00373f4c, 0x00343c48, 0x00363c48, 0x00383e4a, 0x003a404c, 0x003a404c, 0x0039404b, 0x00383f4a, 0x00383e49, 0x00383f4c, 0x00383f4c, 0x00383f4c, 0x00383f4e, 0x00383f4e, 0x00383f4d, 0x00383f4b, 0x00383f4a, 0x00383f49, 0x00373f49, 0x00353d48, 0x00343c48, 0x00343c48, 0x00343c48, 0x00343d49, 0x0035404c, 0x00373f4c, 0x00373f4c, 0x00353d4a, 0x00353c49, 0x00363b47, 0x00373b47, 0x00353a45, 0x00343943, 0x00343a44, 0x00343c48, 0x00343c48, 0x00343b47, 0x00343a45, 0x00333944, 0x00333843, 0x00323642, 0x00313541, 0x00343844, 0x00383d48, 0x00343b46, 0x00303742, 0x002f3540, 0x00303540, 0x00313843, 0x00343a45, 0x00343945, 0x00333944, 0x00323844, 0x00313843, 0x00303642, 0x00303641, 0x00303742, 0x00313843, 0x00303641, 0x002c333e, 0x002a303c, 0x002a303c, 0x002b323d, 0x002a323c, 0x0029313c, 0x0028303b, 0x00272f39, 0x00272f3a, 0x0028303c, 0x0028303c, 0x00262e3a, 0x00242c37, 0x00222a35, 0x00232b36, 0x00242c35, 0x00242c35, 0x00242d36, 0x00272f39, 0x00262f39, 0x00242d38, 0x00202b35, 0x001f2833, 0x001c2630, 0x001a242e, 0x0019242b, 0x00182228, 0x00162026, 0x00182028, 0x001c2630, 0x00202c36, 0x001e2c36, 0x00202d37, 0x00212f38, 0x00202c36, 0x0018212a, 0x00141c24, 0x00162028, 0x001c262e, 0x001f2a35, 0x00232e3c, 0x0024303e, 0x00232e3a, 0x001f2a36, 0x001c2834, 0x001a2632, 0x0018232f, 0x0016222e, 0x00182430, 0x001d2934, 0x001d2a33, 0x001c2830, 0x0018242c, 0x00142029, 0x0015202c, 0x0017222e, 0x00192430, 0x001a2430, 0x001a2430, 0x0018222e, 0x0017202a, 0x00162029, 0x00152028, 0x00152028, 0x00152029, 0x0015222a, 0x0014212a, 0x00112029, 0x000d1d26, 0x000c1c24, 0x000c1c25, 0x000e1c26, 0x000f1c24, 0x00101c24, 0x00101c24, 0x000e1922, 0x000c1720, 0x000b151e, 0x000a141d, 0x000a141c, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x0009141c, 0x0009141c, 0x000a131c, 0x000b131c, 0x000b131c, 0x000c141d, 0x000c141d, 0x000c151e, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c161f, 0x000c161f, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b151e, 0x000c151e, 0x000c151e, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000c1720, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000d1922, 0x000e1a24, 0x000d1924, 0x000c1822, 0x000c1822, 0x000d1924, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1924, 0x000e1924, 0x000e1924, 0x000c1924, 0x000c1a24, 0x000e1b24, 0x000f1b25, 0x000f1a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00131c27, 0x0018222c, 0x001b2632, 0x00182430, 0x0015212c, 0x00131f2b, 0x00131f2b, 0x0015202c, 0x0015202c, 0x0016202c, 0x0015222d, 0x0016232f, 0x00182531, 0x00182430, 0x00182530, 0x00182531, 0x001b2834, 0x001e2c38, 0x001e2c37, 0x001d2a35, 0x001e2b34, 0x001d2a30, 0x001b272d, 0x0019242c, 0x0019232c, 0x001a242e, 0x001b2530, 0x001d2731, 0x00202934, 0x00202934, 0x00202b35, 0x00212c36, 0x00232c37, 0x00242e38, 0x00242d38, 0x00242e38, 0x00252f38, 0x00253038, 0x00242f38, 0x00242d36, 0x00242d36, 0x00242d36, 0x00263038, 0x0029333c, 0x002c343d, 0x002e343d, 0x002c323c, 0x002b313b, 0x002d333e, 0x002f3540, 0x002f3440, 0x002e343d, 0x002d343c, 0x0030343f, 0x00313640, 0x00323640, 0x00313741, 0x00313841, 0x00313842, 0x00313842, 0x00303843, 0x00313944, 0x00323b45, 0x00333b46, 0x00333c46, 0x00343c47, 0x00343a44, 0x00343a45, 0x00343a45, 0x00343944, 0x00343944, 0x00343a45, 0x00343944, 0x00353a45, 0x00373b47, 0x00383c48, 0x003a3f4a, 0x003b404c, 0x003a404c, 0x003a404d, 0x003c4250, 0x003c4350, 0x003b4350, 0x003b4350, 0x003b4350, 0x003a4250, 0x0039414f, 0x003a424e, 0x003c4450, 0x003e4652, 0x003f4754, 0x00404854, 0x00404854, 0x00404854, 0x003f4754, 0x003d4653, 0x003c4552, 0x003a4450, 0x0038404d, 0x00363e4a, 0x00383f4a, 0x003a404c, 0x003b414c, 0x003a414c, 0x003a414c, 0x0039404c, 0x0039404c, 0x00383e4c, 0x00373d4a, 0x00373d4b, 0x00383e4c, 0x00383f4c, 0x00383f4c, 0x00383f4c, 0x00383f4b, 0x00383f4a, 0x00373f49, 0x00373f49, 0x00373e4a, 0x00353d4a, 0x00353d4a, 0x00363f4c, 0x0036404d, 0x0037404d, 0x0038404c, 0x00373f4c, 0x00373d4a, 0x00383c48, 0x00383c48, 0x00373b46, 0x00343a44, 0x00343a45, 0x00343c47, 0x00343c48, 0x00343a46, 0x00343a46, 0x00343a46, 0x00343a45, 0x00353945, 0x00343945, 0x00343944, 0x00343b46, 0x00343a45, 0x00303742, 0x002e3440, 0x002f3440, 0x002f3540, 0x00313843, 0x00323844, 0x00323844, 0x00303641, 0x002d333f, 0x002c323e, 0x002d343f, 0x002d343f, 0x002e3440, 0x002e3440, 0x002e3440, 0x002e343f, 0x002e3440, 0x002e3540, 0x002c3440, 0x002c3440, 0x002c343f, 0x002a323d, 0x0029313d, 0x0029313e, 0x0029313e, 0x00262f3b, 0x00242c37, 0x00232b36, 0x00232b36, 0x00242c35, 0x00242d36, 0x00262f38, 0x0027303a, 0x00262e3a, 0x00232c38, 0x00202a35, 0x001c2732, 0x00192330, 0x0018222c, 0x0018222a, 0x00182328, 0x00192329, 0x00171f27, 0x00151f28, 0x00192530, 0x001b2832, 0x001d2c35, 0x00213039, 0x00222d38, 0x001b242d, 0x00141d26, 0x00141e27, 0x0019242c, 0x001e2934, 0x00212d3b, 0x00242f3d, 0x00222e3a, 0x00202b37, 0x001d2935, 0x001d2934, 0x001b2733, 0x00182430, 0x0017232f, 0x0018242f, 0x001d2a33, 0x00202c35, 0x00202c35, 0x001c2830, 0x0018232d, 0x0018232f, 0x00182430, 0x001a2430, 0x001a2430, 0x0018222e, 0x0017212b, 0x0016202a, 0x00152029, 0x00152029, 0x00152029, 0x0015222a, 0x0014222a, 0x00112029, 0x000e1e27, 0x000d1c26, 0x000e1d27, 0x000f1e28, 0x00101e26, 0x00111d25, 0x00111d25, 0x000f1b23, 0x000c1820, 0x000b161f, 0x000b151e, 0x000a141d, 0x000a131c, 0x000b131c, 0x000b131c, 0x000b131c, 0x000a131c, 0x0009141c, 0x000a141c, 0x000a141c, 0x000b141c, 0x000c141d, 0x000c141e, 0x000c141e, 0x000d151f, 0x000d161f, 0x000e1720, 0x000e1720, 0x000f1720, 0x000f1720, 0x000f1720, 0x000f1820, 0x000f1820, 0x000f1820, 0x000f1720, 0x000f1720, 0x000e1720, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c161f, 0x000c161f, 0x000c151e, 0x000b151e, 0x000b151e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1720, 0x000c1720, 0x000c1720, 0x000c1720, 0x000c1821, 0x000c1822, 0x000c1822, 0x000c1820, 0x000d1921, 0x000d1923, 0x000d1924, 0x000d1924, 0x000d1923, 0x000d1924, 0x000f1a24, 0x00101b25, 0x00101b25, 0x000f1a24, 0x000f1a24, 0x000e1a24, 0x000d1a24, 0x000d1a24, 0x000d1a24, 0x000d1a24, 0x000e1a24, 0x000f1a24, 0x000f1a24, 0x00101b25, 0x00101b25, 0x000f1a25, 0x000f1a25, 0x000f1a25, 0x00101b26, 0x00101b26, 0x00101b26, 0x000f1b25, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00111c26, 0x0016202b, 0x00182430, 0x0018242f, 0x0014202c, 0x00121e28, 0x00111d28, 0x00141e29, 0x00141e29, 0x0015202b, 0x0014202c, 0x0016232d, 0x00182430, 0x00182430, 0x00182530, 0x00192530, 0x001b2732, 0x001e2a35, 0x001f2b36, 0x00202c36, 0x00202c35, 0x00202c34, 0x001d2830, 0x001b252d, 0x001a242c, 0x001a242d, 0x001c262f, 0x001d2830, 0x00202a34, 0x00202b35, 0x00202c36, 0x00212c36, 0x00232d38, 0x00242e38, 0x00242d38, 0x00242d36, 0x00242c36, 0x00232c35, 0x00232c35, 0x00242c36, 0x00262f38, 0x0028323c, 0x002b343d, 0x002a333d, 0x002b323c, 0x002c323c, 0x002b313b, 0x002b313b, 0x002d343d, 0x002f343f, 0x002e343e, 0x002c333b, 0x002c333c, 0x00303640, 0x00333842, 0x00333842, 0x00323842, 0x00313841, 0x00313841, 0x00313841, 0x00303841, 0x00303943, 0x00333a45, 0x00343c47, 0x00353c48, 0x00343b45, 0x00323842, 0x00323843, 0x00343a44, 0x00343b44, 0x00353c46, 0x00363c48, 0x00373c48, 0x00373c48, 0x00383d48, 0x00393f4a, 0x003a404b, 0x00393f4a, 0x00383e4a, 0x003a404e, 0x003c4350, 0x003c4451, 0x003c4450, 0x003c4451, 0x003d4452, 0x003d4454, 0x003c4553, 0x003c4553, 0x003f4754, 0x00404856, 0x00414956, 0x00424a57, 0x00404855, 0x00404854, 0x00404854, 0x00404855, 0x00404854, 0x003f4753, 0x003e4550, 0x003c424e, 0x003b414c, 0x003b424c, 0x003a424d, 0x003a424d, 0x003a424d, 0x003b424d, 0x003b434e, 0x003a424d, 0x0039404c, 0x00373f4a, 0x00363d4a, 0x00383e4b, 0x00383f4c, 0x0039404c, 0x0039404c, 0x00383f4a, 0x00383f4a, 0x00373e4a, 0x00363e4b, 0x00363d4c, 0x0038404d, 0x0038404c, 0x0038404c, 0x0039404c, 0x0039404c, 0x00383f4c, 0x00373d4b, 0x00363c48, 0x00363c48, 0x00363c47, 0x00353b46, 0x00343a47, 0x00333b48, 0x00343c48, 0x00343b48, 0x00343a47, 0x00343a46, 0x00353b47, 0x00353c47, 0x00343a45, 0x00323843, 0x00303843, 0x00313843, 0x00303642, 0x002d343f, 0x002d323e, 0x002d323e, 0x002d343e, 0x002e343f, 0x002e3440, 0x002d343f, 0x002b313c, 0x002a303c, 0x00282f3a, 0x00272d38, 0x00282d38, 0x00282e39, 0x002b313b, 0x002c333d, 0x002e3440, 0x002e3540, 0x002d3540, 0x002d3641, 0x002e3641, 0x002d3540, 0x002c3440, 0x002b333f, 0x0029313c, 0x00272f3a, 0x00242c38, 0x00232c37, 0x00222c36, 0x00242c37, 0x00253039, 0x0027303b, 0x0028303b, 0x00262e39, 0x00212c36, 0x001f2934, 0x001c2731, 0x001a242f, 0x0018212c, 0x00141f28, 0x00152027, 0x0019232a, 0x001b242c, 0x0019222c, 0x001c2832, 0x001d2933, 0x001c2833, 0x00202d36, 0x00212e38, 0x001c262f, 0x00141f27, 0x00152028, 0x0018242b, 0x001d2933, 0x00202c39, 0x00222d3b, 0x00222e39, 0x00212c38, 0x00202c38, 0x001e2a36, 0x001d2a36, 0x001c2834, 0x00182531, 0x0018242f, 0x001a262f, 0x001e2a33, 0x00232f38, 0x00222e36, 0x001c2831, 0x00192631, 0x00192631, 0x00192531, 0x00192430, 0x00182430, 0x0018222d, 0x0016212c, 0x0016212c, 0x0016202c, 0x0015212c, 0x0015232c, 0x0015232c, 0x0012212b, 0x00102028, 0x00101f28, 0x00102029, 0x00112029, 0x00111f28, 0x00131f27, 0x00121e26, 0x00101c24, 0x000d1922, 0x000c1720, 0x000c161f, 0x000b151e, 0x000b141e, 0x000b131e, 0x000b131d, 0x000b131c, 0x000c141d, 0x000a141d, 0x000a141d, 0x000b141e, 0x000b141f, 0x000b141f, 0x000c151e, 0x000c151e, 0x000c161f, 0x000d1720, 0x000d1720, 0x000e171f, 0x000e181f, 0x000e1820, 0x000f1820, 0x00101820, 0x00101820, 0x00101820, 0x00101820, 0x00101820, 0x00101820, 0x000f1720, 0x000e1720, 0x000e161f, 0x000d161f, 0x000d161f, 0x000d1720, 0x000d1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1721, 0x000d1721, 0x000c1721, 0x000b1720, 0x0009171f, 0x0009171f, 0x000a1820, 0x000a1820, 0x000c1822, 0x000d1924, 0x000d1924, 0x000d1921, 0x000d1921, 0x000d1923, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x00101b25, 0x00101c26, 0x00101c26, 0x00101b25, 0x00101b25, 0x000f1b25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000e1a26, 0x000e1a26, 0x00101b27, 0x00111c28, 0x00101c26, 0x000c1c25, 0x000c1c25, 0x000e1c25, 0x000e1c25, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00141d28, 0x0016212d, 0x0016222d, 0x0014202c, 0x00111d26, 0x00101c24, 0x00131d26, 0x00141f28, 0x0016202a, 0x0016212b, 0x0018242e, 0x00192530, 0x0018242f, 0x00192530, 0x001a2630, 0x001b2630, 0x001d2933, 0x001f2b35, 0x001f2b35, 0x00202c34, 0x001f2b33, 0x001d2830, 0x001c262f, 0x001a242c, 0x0018232a, 0x0019232a, 0x001c262e, 0x00202933, 0x00212c37, 0x00222d38, 0x00232f38, 0x0024303a, 0x00253039, 0x00242d36, 0x00232b34, 0x00232b34, 0x00232b34, 0x00232c34, 0x00242c35, 0x0028303b, 0x002c3741, 0x002e3641, 0x002c343f, 0x002a323c, 0x002c323d, 0x002c333d, 0x002c323c, 0x002d343d, 0x00303640, 0x00303740, 0x002d343d, 0x002e343d, 0x00303740, 0x00323842, 0x00313841, 0x00303740, 0x002f353f, 0x002f353e, 0x002e343e, 0x002e343e, 0x002e343f, 0x002e333e, 0x00303440, 0x00303440, 0x002e343e, 0x002d333c, 0x002f343e, 0x00323841, 0x00353b44, 0x00373d47, 0x00383f4a, 0x003a404c, 0x0038404c, 0x00383f4a, 0x0039404b, 0x00383f4a, 0x00363c48, 0x00373d4a, 0x0039404d, 0x003b424f, 0x003a424f, 0x0039414e, 0x0038424e, 0x0039424f, 0x0039414f, 0x0039414e, 0x0038404e, 0x003a4150, 0x003b4150, 0x003b424f, 0x003b424f, 0x003a414e, 0x0039404d, 0x003a414e, 0x003d4451, 0x003e4651, 0x00404852, 0x00414854, 0x00404653, 0x003f4552, 0x00404651, 0x003c4551, 0x003c4550, 0x003b4450, 0x003c4551, 0x003c4550, 0x003b4450, 0x0039434f, 0x0038414d, 0x0037404d, 0x00394250, 0x003a434f, 0x003c4450, 0x003d4450, 0x003b434f, 0x003c4350, 0x003a4250, 0x0039404f, 0x003a4250, 0x003c4452, 0x0038434d, 0x0039414c, 0x003a414c, 0x003c414d, 0x003b414d, 0x003b414f, 0x0039414c, 0x0038404b, 0x00363e49, 0x00363d48, 0x00343c48, 0x00333b48, 0x00343c49, 0x00353d4a, 0x00343c48, 0x00343944, 0x00343945, 0x00343b46, 0x00333944, 0x00303742, 0x00303742, 0x00303843, 0x002f3642, 0x002e343f, 0x002d313d, 0x002c303c, 0x002b313b, 0x002c323c, 0x002d333e, 0x002c333e, 0x002c323d, 0x002b313c, 0x00282f3a, 0x00282d38, 0x00282e39, 0x00282f38, 0x00282f38, 0x00293039, 0x002b313c, 0x002b313c, 0x002a323d, 0x002b333e, 0x002c3440, 0x002e3641, 0x00303843, 0x002e3641, 0x002c343e, 0x0028303b, 0x00262e39, 0x00252e38, 0x00242d38, 0x00242d38, 0x0024303b, 0x0028323d, 0x0029313c, 0x0028303b, 0x00232b36, 0x001e2832, 0x001c2630, 0x001c2530, 0x001b232e, 0x00161f29, 0x00121c24, 0x00121c23, 0x00152028, 0x001c252e, 0x00212c36, 0x00202b35, 0x00182530, 0x001e2a34, 0x00232f38, 0x001e2933, 0x00142029, 0x00152128, 0x0018242b, 0x001c2832, 0x001f2a38, 0x00202c39, 0x00222d39, 0x00232e3a, 0x00202d38, 0x001d2c38, 0x001d2c38, 0x001c2b36, 0x00182833, 0x00182530, 0x001a262f, 0x001b272f, 0x001e2a33, 0x00222e36, 0x00202c37, 0x001d2c38, 0x001c2c37, 0x001c2934, 0x001a2833, 0x001a2733, 0x00182531, 0x00172430, 0x00172430, 0x0016242f, 0x00172430, 0x00182530, 0x00182530, 0x0014242d, 0x0013232c, 0x0013232c, 0x0013232c, 0x0014222c, 0x00142029, 0x00142028, 0x00131f28, 0x00111d25, 0x000f1b23, 0x000d1820, 0x000d1720, 0x000c1620, 0x000c1420, 0x000c1420, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c161e, 0x000c161f, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d171f, 0x000d171f, 0x000e1820, 0x000f1921, 0x00101821, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x00101820, 0x00101820, 0x000f1720, 0x000e1720, 0x000d161f, 0x000d161f, 0x000d1720, 0x000d1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1721, 0x000d1721, 0x000c1821, 0x000b1720, 0x0009171f, 0x0009171f, 0x000a1820, 0x000a1820, 0x000c1822, 0x000d1924, 0x000d1924, 0x000d1921, 0x000d1921, 0x000d1923, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x00101b25, 0x00101c26, 0x00101c26, 0x00101b25, 0x00101b25, 0x000f1b25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b26, 0x000e1a26, 0x000e1a26, 0x00101b27, 0x00111c28, 0x000f1c26, 0x000c1c25, 0x000c1c25, 0x000e1c25, 0x000e1c25, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101c26, 0x00101b25, 0x00101b25, 0x00131d28, 0x0014202c, 0x0017222e, 0x0015202c, 0x00111d26, 0x00101c24, 0x00141e27, 0x00172029, 0x0018222c, 0x0018242d, 0x00192530, 0x00192530, 0x00192530, 0x00192530, 0x001b2630, 0x001b2731, 0x001e2a34, 0x00202c36, 0x00202c35, 0x001f2b34, 0x001c2931, 0x001c2830, 0x001c262f, 0x001a242d, 0x001a242b, 0x001a242d, 0x001e2831, 0x00232c36, 0x0024303a, 0x0025303c, 0x0024303b, 0x00242f3a, 0x00242d38, 0x00212c34, 0x00222b34, 0x00222a34, 0x00232c34, 0x00242c35, 0x00242d36, 0x0028313c, 0x002c3640, 0x002e3742, 0x002d3641, 0x002d343f, 0x002c333e, 0x002e343e, 0x002e343e, 0x002f353f, 0x00303740, 0x00303740, 0x002d343d, 0x002c323c, 0x002c333c, 0x002c323c, 0x002c323c, 0x002d343d, 0x002e343d, 0x002c333c, 0x002c323c, 0x002c323c, 0x002d343c, 0x002e333e, 0x002f3440, 0x002f343f, 0x002c303c, 0x002a2f38, 0x002c303a, 0x0030343e, 0x00333841, 0x00343943, 0x00343944, 0x00373d48, 0x00373e49, 0x00363c48, 0x00353c47, 0x00363c48, 0x00343b47, 0x00353c48, 0x00363c49, 0x00353c4a, 0x00343c48, 0x00333b48, 0x00333a47, 0x00343947, 0x00343947, 0x00343947, 0x00333847, 0x00333847, 0x00343848, 0x00343946, 0x00343846, 0x00333845, 0x00333845, 0x00323844, 0x00333844, 0x00333a45, 0x00343b47, 0x00383f4c, 0x003b424f, 0x003c434f, 0x003c4550, 0x003c4653, 0x003d4854, 0x00404957, 0x00414b58, 0x00404a57, 0x00404956, 0x00404956, 0x003c4653, 0x003b4452, 0x003d4754, 0x003d4854, 0x003f4854, 0x00404754, 0x003e4653, 0x003d4453, 0x003b4351, 0x00394150, 0x003b4452, 0x003d4654, 0x003c4650, 0x003d4650, 0x003e4651, 0x00404752, 0x00404652, 0x003f4453, 0x003d4550, 0x003b444e, 0x0038414c, 0x0039404c, 0x00383f4b, 0x00373f4c, 0x00373f4c, 0x00383f4c, 0x00353d4a, 0x00343944, 0x00323843, 0x00323844, 0x00323844, 0x00323844, 0x00313843, 0x00303742, 0x002f3642, 0x002e3440, 0x002d313d, 0x002c313d, 0x002a303b, 0x00282f38, 0x002a303c, 0x002b313d, 0x002b313c, 0x002a303b, 0x0029303a, 0x00282f38, 0x00252c35, 0x00262c36, 0x00293039, 0x002a303a, 0x00282e39, 0x00272e39, 0x00272e39, 0x00272e39, 0x00272f3a, 0x002a323d, 0x002d3640, 0x002f3742, 0x002f3742, 0x002b333e, 0x0028303b, 0x00272f3a, 0x00242e38, 0x00242e38, 0x0025303b, 0x0028323c, 0x002c343e, 0x002c343f, 0x0028303c, 0x00202934, 0x001b2430, 0x001c242f, 0x001b232d, 0x0019232d, 0x0018212b, 0x00141e27, 0x00121c25, 0x0019222b, 0x00222b35, 0x00212c37, 0x00192630, 0x001c2833, 0x00243039, 0x00202c35, 0x0018242c, 0x00142028, 0x0017232a, 0x001b2731, 0x001f2a38, 0x00202c39, 0x00212d39, 0x00232f3a, 0x00212e39, 0x001e2c38, 0x001d2c38, 0x001c2c37, 0x00192934, 0x001a2731, 0x001a2630, 0x001b272f, 0x001c2830, 0x001c2830, 0x001f2c36, 0x001f2d39, 0x001e2d39, 0x001f2c38, 0x001e2c37, 0x001d2a36, 0x001a2833, 0x00192732, 0x00192732, 0x00182631, 0x00192731, 0x001a2832, 0x001a2832, 0x00182730, 0x00172630, 0x0016252f, 0x0016252f, 0x0016242e, 0x0015222b, 0x00142029, 0x00131f28, 0x00111d25, 0x000f1b23, 0x000d1820, 0x000e1820, 0x000d1620, 0x000c1420, 0x000c1420, 0x000c141f, 0x000c141e, 0x000c141e, 0x000c161e, 0x000c161d, 0x000c161f, 0x000c161f, 0x000c161f, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000e1820, 0x000f1921, 0x000f1921, 0x00101821, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x00101820, 0x00101820, 0x000e1720, 0x000d161f, 0x000d161f, 0x000d1720, 0x000d1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1821, 0x000e1823, 0x000d1823, 0x000c1820, 0x000a1820, 0x000a1820, 0x000b1920, 0x000b1821, 0x000b1823, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000f1b25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b26, 0x000e1b27, 0x000e1c27, 0x00101c27, 0x00101c28, 0x000f1c26, 0x000c1c25, 0x000c1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x00101b25, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c27, 0x00131f2a, 0x0017222e, 0x0016222d, 0x00142028, 0x00121e27, 0x00152028, 0x0019232c, 0x001b262f, 0x001a2630, 0x001b2631, 0x001b2630, 0x001b2630, 0x001c2731, 0x001c2831, 0x001e2a34, 0x00202c36, 0x00212d37, 0x00202c36, 0x001e2a34, 0x001c2831, 0x001c2830, 0x001b2830, 0x001b272f, 0x001b272e, 0x001c2730, 0x00212c35, 0x00242d38, 0x00222d38, 0x00222e38, 0x00212d38, 0x00202b35, 0x00202933, 0x00202a33, 0x00232c34, 0x00242c35, 0x00242d36, 0x00262e38, 0x00272f38, 0x0029323d, 0x002b343f, 0x002d3540, 0x002e3641, 0x002e3440, 0x002e3440, 0x002f3440, 0x00303640, 0x00303640, 0x00303640, 0x002c323c, 0x00282e38, 0x00282e38, 0x00282f38, 0x0029303a, 0x002a303b, 0x002c333c, 0x002e343d, 0x002d343c, 0x002c323c, 0x002c323c, 0x002e343d, 0x00303440, 0x00303440, 0x002f3440, 0x002c303c, 0x00282c36, 0x00282d37, 0x002d313c, 0x00313640, 0x00313540, 0x00303541, 0x00333844, 0x00343a45, 0x00333944, 0x00323844, 0x00333944, 0x00343a45, 0x00343a46, 0x00333947, 0x00333947, 0x00333947, 0x00333947, 0x00343a48, 0x00343a48, 0x00363b48, 0x00373c49, 0x00353c49, 0x00343c49, 0x00343c48, 0x00343c47, 0x00333a45, 0x00323944, 0x00323944, 0x00323844, 0x00323844, 0x00313843, 0x00303842, 0x00303844, 0x00303844, 0x00303845, 0x00313944, 0x00323b48, 0x00343d4a, 0x0037404e, 0x00394250, 0x003b4451, 0x003a4350, 0x003a4450, 0x003a434f, 0x00384150, 0x0038404f, 0x00353e4b, 0x00343c49, 0x00353d4a, 0x00373e4c, 0x00343d4b, 0x00323c4a, 0x00313b49, 0x00333c4b, 0x00363e4c, 0x00363e48, 0x00363d48, 0x00363e49, 0x00373f4a, 0x0038404c, 0x00383f4d, 0x0038404b, 0x00363e49, 0x00343c47, 0x00383f4a, 0x0039404c, 0x0038404c, 0x0038404c, 0x0038404c, 0x00363d4a, 0x00353b46, 0x00333944, 0x00313843, 0x00343945, 0x00343a46, 0x00313944, 0x00303843, 0x002e3641, 0x00303641, 0x00303440, 0x002e333f, 0x002c313c, 0x00282f38, 0x00282f38, 0x0029303a, 0x00293039, 0x002a3039, 0x0029303a, 0x00293039, 0x00282e37, 0x00282e36, 0x00282f38, 0x00282f38, 0x00282d38, 0x00282d39, 0x00282d39, 0x00282e39, 0x0029313c, 0x002c343f, 0x002d3540, 0x002e3641, 0x00303843, 0x002f3742, 0x002a313c, 0x0028303b, 0x0026303a, 0x00252f39, 0x00252f39, 0x0025303a, 0x0028303b, 0x0029313c, 0x0029313c, 0x0027303b, 0x00232c38, 0x00212a35, 0x001c2630, 0x001b2530, 0x001c2731, 0x001e2832, 0x001b252f, 0x0019242e, 0x00212b36, 0x00232e38, 0x001c2933, 0x001c2831, 0x0024303a, 0x00202d37, 0x0018252f, 0x0016222b, 0x0017232b, 0x00182430, 0x001c2734, 0x001e2937, 0x00202c38, 0x00222e3a, 0x00222f3a, 0x001f2e39, 0x001e2d38, 0x001c2c37, 0x001c2b36, 0x001c2934, 0x001c2831, 0x001c2830, 0x001c2830, 0x001b2730, 0x001d2a34, 0x001f2e39, 0x001f2f3a, 0x00202e3a, 0x00202e3a, 0x001f2c38, 0x001c2a36, 0x001c2934, 0x001b2834, 0x001b2834, 0x001b2834, 0x001c2934, 0x001c2934, 0x001b2834, 0x001b2834, 0x001b2834, 0x00192732, 0x00182531, 0x0018242f, 0x0016222c, 0x00141f29, 0x00111d27, 0x000f1a24, 0x000e1924, 0x000f1924, 0x000e1823, 0x000c1620, 0x000c1620, 0x000c1520, 0x000d1520, 0x000d1520, 0x000c161e, 0x000c161d, 0x000c161e, 0x000c161f, 0x000c161f, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000e1820, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x00101821, 0x00101821, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x000f1720, 0x000f1720, 0x000e1720, 0x000e1720, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1821, 0x000e1823, 0x000e1823, 0x000c1821, 0x000b1821, 0x000b1921, 0x000b1921, 0x000b1821, 0x000b1823, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000f1b25, 0x000d1c25, 0x000d1c25, 0x000d1c25, 0x000d1c25, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b26, 0x000e1b27, 0x000e1c27, 0x00101c27, 0x00101c28, 0x000f1c26, 0x000d1c25, 0x000d1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x00101b25, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00131f2a, 0x0017222e, 0x0018242e, 0x0017222b, 0x0016222a, 0x0017212a, 0x0019242c, 0x001b262f, 0x001a2630, 0x001a2630, 0x001b2631, 0x001c2731, 0x001c2831, 0x001e2a34, 0x00202c37, 0x00212d37, 0x00222e38, 0x00202c36, 0x001f2b35, 0x001c2831, 0x001c2730, 0x001c2830, 0x001b2730, 0x001b2730, 0x001e2832, 0x00202a34, 0x00202934, 0x001f2934, 0x001f2934, 0x001c2832, 0x001c2630, 0x001c2730, 0x00202b33, 0x00242c35, 0x00252e37, 0x00262e37, 0x00283038, 0x0028303a, 0x002a333d, 0x002a343e, 0x002b333e, 0x002c3440, 0x002d3440, 0x002f3440, 0x00303640, 0x00303640, 0x00303640, 0x002e343e, 0x002a303a, 0x00272d37, 0x0029303a, 0x002b313c, 0x002c323c, 0x002c323d, 0x002c333e, 0x002e343f, 0x002e343f, 0x002c333e, 0x002c333d, 0x002e343d, 0x002f343f, 0x00303440, 0x002f3440, 0x002d323e, 0x002b3038, 0x00292e38, 0x002d323c, 0x00323740, 0x00313540, 0x00313541, 0x00333844, 0x00343a46, 0x00353b47, 0x00343b46, 0x00343b46, 0x00343a46, 0x00343a45, 0x00333944, 0x00323945, 0x00343a48, 0x00353c49, 0x00353b48, 0x00343a48, 0x00353b48, 0x00363c4a, 0x00353d4a, 0x00363d4b, 0x00373f4b, 0x00363e49, 0x00343c48, 0x00343c47, 0x00333b46, 0x00343b47, 0x00343b48, 0x00343a47, 0x00343b45, 0x00333b46, 0x00333a48, 0x00333946, 0x00303844, 0x002f3744, 0x00303844, 0x00303846, 0x00303846, 0x00303845, 0x00303744, 0x002f3744, 0x00303844, 0x00303846, 0x00303846, 0x002e3643, 0x002d3542, 0x002e3644, 0x00333a48, 0x00363d4b, 0x00363f4c, 0x00363f4d, 0x00363e4c, 0x00343c4a, 0x00333b46, 0x00323844, 0x00303843, 0x00313944, 0x00323945, 0x00333947, 0x00323a45, 0x00313844, 0x00303843, 0x00333944, 0x00333a46, 0x00313946, 0x00323a47, 0x00333b48, 0x00333b48, 0x00343a45, 0x00343a46, 0x00333944, 0x00333944, 0x00343b47, 0x00333b46, 0x00323944, 0x00303742, 0x00303742, 0x00313542, 0x002f3440, 0x002c323c, 0x002a3039, 0x00282f38, 0x00282d37, 0x00272d37, 0x00282e37, 0x00282f38, 0x0029303a, 0x002a303a, 0x002a303a, 0x002a303a, 0x00293038, 0x00282e39, 0x00282e39, 0x00282e39, 0x00282f3a, 0x002a323d, 0x002d3540, 0x002d3540, 0x002c343f, 0x002b333e, 0x002e3540, 0x002e3440, 0x002c333e, 0x002b323d, 0x0027303a, 0x00242d38, 0x00232c37, 0x00242c37, 0x00242c38, 0x00262e38, 0x00242d38, 0x00212b35, 0x00212c36, 0x001f2934, 0x0019242e, 0x0018212c, 0x001a242e, 0x001e2833, 0x001d2834, 0x0024303b, 0x0026333e, 0x00212e39, 0x001c2833, 0x0024323c, 0x00223039, 0x001b2832, 0x0017242c, 0x0017232b, 0x0018242f, 0x00182432, 0x00192532, 0x001b2733, 0x001f2b37, 0x00202d38, 0x001f2e39, 0x001f2e39, 0x001d2c38, 0x001c2c37, 0x001f2b36, 0x001f2b34, 0x001f2b34, 0x001e2a33, 0x001f2a33, 0x00202c37, 0x00202f3a, 0x0020303a, 0x00202f3a, 0x00212f3a, 0x00202e39, 0x001f2c38, 0x001f2c38, 0x001e2c37, 0x001e2c37, 0x001e2c37, 0x001e2c37, 0x001e2c37, 0x001e2c37, 0x001e2c37, 0x001e2b37, 0x001c2934, 0x00192632, 0x00182530, 0x0017222c, 0x00141f29, 0x00111d27, 0x000f1a24, 0x000f1a24, 0x00101a24, 0x000f1824, 0x000d1721, 0x000c1620, 0x000d1620, 0x000d1620, 0x000d1620, 0x000c171f, 0x000c171f, 0x000c171f, 0x000c1720, 0x000c1720, 0x000e1820, 0x000e1820, 0x000e1820, 0x000e1820, 0x000e1820, 0x000e1820, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1922, 0x000f1922, 0x00101922, 0x00101822, 0x00101822, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x00101820, 0x000e1720, 0x000e1720, 0x000e1720, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1720, 0x000d1720, 0x000c1720, 0x000c1822, 0x000c1823, 0x000c1823, 0x000b1823, 0x000b1823, 0x000b1824, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1b24, 0x000e1b24, 0x000e1b24, 0x000e1b24, 0x000e1b24, 0x000e1b25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x000f1c27, 0x00101c27, 0x00101b27, 0x00101b27, 0x00101c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x00101c28, 0x000f1c27, 0x000e1c27, 0x000e1c27, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x00101c25, 0x00101c25, 0x00101b25, 0x00101c26, 0x00111d27, 0x00101c26, 0x00101c26, 0x00121d29, 0x0015212d, 0x0018232e, 0x0018242c, 0x0017232b, 0x0018222b, 0x0018222b, 0x0019242c, 0x0018242c, 0x0018242c, 0x0019242d, 0x001a262f, 0x001c2831, 0x001d2b34, 0x001f2c36, 0x00202d37, 0x00202e38, 0x00202c36, 0x001c2933, 0x001b2830, 0x001a262f, 0x001a262f, 0x0019252f, 0x001a252e, 0x001c2630, 0x001d2731, 0x001c2731, 0x001c2731, 0x001c2631, 0x001b2630, 0x001b2630, 0x001e2831, 0x00202b34, 0x00242d36, 0x00262e37, 0x00272f38, 0x0028313a, 0x002b333d, 0x002c343f, 0x002c343e, 0x002b333c, 0x002c343d, 0x002c343e, 0x002e3540, 0x00303740, 0x00303740, 0x002f353f, 0x002e343e, 0x002b323c, 0x002a323c, 0x002c333d, 0x002d343e, 0x002e343f, 0x002e3440, 0x002e343f, 0x002f3540, 0x00303540, 0x002f343f, 0x002e343d, 0x0030333d, 0x0030343e, 0x00313440, 0x00303440, 0x0030343e, 0x002d323b, 0x002c303a, 0x002e333c, 0x00323640, 0x00333742, 0x00333844, 0x00353a46, 0x00343b46, 0x00353b47, 0x00363c48, 0x00353c47, 0x00343b46, 0x00343945, 0x00333944, 0x00333944, 0x00343945, 0x00343a47, 0x00343a46, 0x00323844, 0x00343a46, 0x00343b47, 0x00343c47, 0x00343c48, 0x00373f4a, 0x0037404b, 0x00373f4a, 0x00363e49, 0x00353d48, 0x00353d48, 0x00353d49, 0x00353d4a, 0x00363e49, 0x00353d48, 0x00353c48, 0x00343b47, 0x00333945, 0x00313844, 0x00313844, 0x00313844, 0x00323844, 0x00313744, 0x00303642, 0x00303642, 0x00303644, 0x00303744, 0x00313844, 0x00313844, 0x00313844, 0x00313844, 0x00313844, 0x00313845, 0x00313845, 0x00323946, 0x00333a48, 0x00323946, 0x00313844, 0x00313844, 0x00313944, 0x00333a45, 0x00343b47, 0x00353b48, 0x00343a46, 0x00333a45, 0x00343a47, 0x00343a47, 0x00333946, 0x00313845, 0x00313845, 0x00313845, 0x00313844, 0x00303743, 0x00323844, 0x00313844, 0x00303642, 0x00303742, 0x00303843, 0x00303641, 0x002f3540, 0x00303641, 0x00303540, 0x002d333f, 0x002c333d, 0x002c303b, 0x00282e38, 0x00272c36, 0x00272b35, 0x00272c36, 0x00272d37, 0x002a303b, 0x002b313d, 0x002c323d, 0x002c323c, 0x002c323c, 0x002b313c, 0x002a303c, 0x0029303b, 0x0028303a, 0x0028303c, 0x0029333d, 0x0028303a, 0x00262e39, 0x00282f3a, 0x002a313c, 0x002c333e, 0x002c343f, 0x002b333e, 0x0028303c, 0x00252e38, 0x00242c38, 0x00232c37, 0x00222b35, 0x00242d38, 0x00242e38, 0x00202934, 0x001e2832, 0x001e2832, 0x001d2830, 0x0019242d, 0x001b262e, 0x001c2730, 0x001a2630, 0x00202c38, 0x0024313c, 0x0023303c, 0x001f2c37, 0x0024323c, 0x0026333e, 0x001d2934, 0x0019242e, 0x0018242d, 0x0018232d, 0x0018222d, 0x0018222d, 0x0018242e, 0x001a2630, 0x001d2a35, 0x001f2c38, 0x0021303b, 0x00202f3a, 0x001d2c38, 0x001d2b36, 0x00202d36, 0x00202e36, 0x00202d35, 0x00212d35, 0x00212e38, 0x00202f3a, 0x0020303a, 0x00202f3a, 0x00212f3a, 0x00212f3a, 0x00202e3a, 0x00202e3a, 0x00202e39, 0x00202d39, 0x00202d39, 0x001e2d39, 0x001e2c38, 0x001f2d39, 0x00202c39, 0x001f2c38, 0x001c2a37, 0x001a2734, 0x00182430, 0x0016212c, 0x00121e28, 0x00101c25, 0x000f1a24, 0x00101a24, 0x000f1924, 0x000e1823, 0x000d1822, 0x000d1721, 0x000e1822, 0x000e1823, 0x000e1823, 0x000e1822, 0x000e1822, 0x000e1821, 0x000e1820, 0x000e1820, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1922, 0x00101a23, 0x00101a23, 0x00101923, 0x00111923, 0x00111923, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x000f1820, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1823, 0x000c1824, 0x000c1824, 0x000b1824, 0x000b1824, 0x000b1824, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d27, 0x00101e28, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00111d27, 0x00101c26, 0x00101c26, 0x00111d28, 0x0015202c, 0x0016222d, 0x0017222b, 0x0016222a, 0x0017212a, 0x0017212a, 0x0017212a, 0x00162228, 0x00162228, 0x00162229, 0x0017242a, 0x001a272f, 0x001c2a34, 0x001d2c35, 0x001d2c36, 0x001f2f38, 0x001e2c36, 0x001a2830, 0x001b2830, 0x001b272f, 0x0019252e, 0x0018232c, 0x00162029, 0x0018222b, 0x0019242d, 0x001a242f, 0x001c2630, 0x001c2731, 0x001e2833, 0x001d2933, 0x001f2831, 0x00212c34, 0x00242d36, 0x00262f38, 0x00283039, 0x002b343d, 0x002f3740, 0x00303841, 0x00303841, 0x002c343d, 0x002c343c, 0x002c343c, 0x002d353f, 0x002f3640, 0x00303640, 0x00303640, 0x00313841, 0x00313942, 0x00303842, 0x002f3840, 0x00303740, 0x00303741, 0x00313843, 0x00303640, 0x002f353f, 0x0030343e, 0x002f343d, 0x002f333d, 0x0030333d, 0x0031343f, 0x00323540, 0x0031343f, 0x0030343d, 0x002e333b, 0x002c303a, 0x002e323c, 0x00313540, 0x00333743, 0x00353945, 0x00373b47, 0x00353b47, 0x00353b46, 0x00363c48, 0x00363c48, 0x00343b46, 0x00343b46, 0x00343b46, 0x00343945, 0x00333944, 0x00333944, 0x00323844, 0x00313843, 0x00333944, 0x00343b46, 0x00343b46, 0x00343c48, 0x00353e49, 0x00373f4c, 0x00373f4a, 0x00373f49, 0x00363e49, 0x00373f49, 0x0038404a, 0x0038404a, 0x0038404a, 0x00373f49, 0x00353d48, 0x00343c47, 0x00343b47, 0x00343a45, 0x00333944, 0x00333944, 0x00333844, 0x00323743, 0x00313843, 0x00303743, 0x00303644, 0x00303744, 0x00303844, 0x00313844, 0x00323844, 0x00323844, 0x00323844, 0x00313844, 0x00303743, 0x00303742, 0x00323844, 0x00323844, 0x00313844, 0x00303844, 0x00303844, 0x00343a46, 0x00353b47, 0x00343a46, 0x00333944, 0x00333944, 0x00333945, 0x00333844, 0x00303542, 0x00303542, 0x00303643, 0x00303743, 0x00303742, 0x00303742, 0x00303742, 0x00303641, 0x002f3440, 0x002d333f, 0x002c323d, 0x002c323d, 0x002d333e, 0x002e343f, 0x002e3440, 0x002d333e, 0x002c333e, 0x002c313c, 0x00282d37, 0x00262b34, 0x00282c37, 0x002c303b, 0x002b313b, 0x002c323c, 0x002c343e, 0x002c343f, 0x002c343f, 0x002d3540, 0x00303641, 0x002f3540, 0x002c343f, 0x002b333e, 0x0028313c, 0x0025303a, 0x00222b35, 0x00212a34, 0x00242d38, 0x0028303a, 0x0028303b, 0x0029313c, 0x0029313c, 0x0028303c, 0x00272f3a, 0x00272f3a, 0x0028303c, 0x0028303b, 0x00242c38, 0x00202b35, 0x001c2630, 0x0018232d, 0x0018232c, 0x0019242c, 0x001c282f, 0x001c2830, 0x001f2b34, 0x001e2a34, 0x00202c36, 0x00203039, 0x00203039, 0x0023313c, 0x00273540, 0x00283440, 0x001e2a34, 0x001b2530, 0x0018222c, 0x0017212b, 0x00162029, 0x0016202a, 0x0016222a, 0x0018242c, 0x001b2732, 0x001e2c37, 0x00212f3a, 0x0023323d, 0x0020303b, 0x001d2c36, 0x001d2b34, 0x00202d37, 0x00212d35, 0x00212d35, 0x00212e38, 0x00202f3a, 0x0020303a, 0x00202f3a, 0x00212f3a, 0x00212f3a, 0x00212f3a, 0x00212f3a, 0x00212f3a, 0x00212f3a, 0x00202f3b, 0x00202f3c, 0x001f2f3c, 0x00202f3c, 0x00202d3a, 0x001e2c39, 0x001c2937, 0x00192633, 0x0017232f, 0x0014202b, 0x00111d28, 0x00101c25, 0x00101a24, 0x00101a24, 0x000f1924, 0x000e1823, 0x000e1822, 0x000e1822, 0x000e1823, 0x000f1824, 0x000f1824, 0x000f1824, 0x000f1824, 0x000f1822, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1922, 0x00101a23, 0x00101a23, 0x00101923, 0x00111923, 0x00111923, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x000f1820, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a1820, 0x000b1820, 0x000c1820, 0x000c1823, 0x000c1824, 0x000c1824, 0x000b1824, 0x000b1824, 0x000c1824, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000e1a24, 0x000e1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1d27, 0x00101d27, 0x00101c27, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c27, 0x00101c26, 0x00101c26, 0x00111d28, 0x0015202c, 0x0016212c, 0x00142029, 0x00131f27, 0x00141f28, 0x00152028, 0x00152028, 0x00142027, 0x00152128, 0x00162228, 0x00152128, 0x0018242c, 0x001b2933, 0x001c2c35, 0x001d2c36, 0x001e2d37, 0x001d2b34, 0x001b2830, 0x001c2830, 0x001c2830, 0x0018232b, 0x00141e25, 0x00131c25, 0x00161f28, 0x0017212b, 0x001a242f, 0x001d2832, 0x00202a34, 0x00202b35, 0x001e2a34, 0x00202a33, 0x00232c36, 0x00262f38, 0x00263039, 0x0028323b, 0x002c353e, 0x00303841, 0x00303841, 0x002e3740, 0x002c343d, 0x002c343d, 0x002c343e, 0x002e3640, 0x002f3740, 0x00303740, 0x00323842, 0x00353c45, 0x00343c45, 0x00333c44, 0x00303841, 0x002f3740, 0x00303741, 0x00303641, 0x002f343f, 0x002d343c, 0x002d333c, 0x002c313b, 0x002c303b, 0x002d303b, 0x0030323c, 0x0030333d, 0x0030343e, 0x0030333c, 0x002d323b, 0x002c303b, 0x002e333c, 0x00313540, 0x00323642, 0x00343844, 0x00353945, 0x00353945, 0x00353a46, 0x00373c48, 0x00363c48, 0x00353b47, 0x00353c47, 0x00353c47, 0x00343a46, 0x00333844, 0x00323844, 0x00323844, 0x00333944, 0x00343a46, 0x00363c48, 0x00363d48, 0x00343c48, 0x00343c48, 0x00353d4a, 0x00353d48, 0x00353d48, 0x00363e49, 0x00373f49, 0x0038404a, 0x0038404a, 0x00373f49, 0x00363f49, 0x00353d48, 0x00353c48, 0x00363c48, 0x00343b47, 0x00343944, 0x00343944, 0x00343844, 0x00333743, 0x00313843, 0x00313843, 0x00303644, 0x00303744, 0x00303844, 0x00323844, 0x00323844, 0x00323844, 0x00323844, 0x00313844, 0x00303742, 0x00303742, 0x00313843, 0x00323844, 0x00313843, 0x002f3742, 0x00303842, 0x00333a44, 0x00343a45, 0x00333944, 0x00303742, 0x00303642, 0x00313642, 0x00303541, 0x00303440, 0x002f343f, 0x00303441, 0x00313642, 0x00303742, 0x00303742, 0x00303742, 0x00303641, 0x002f3440, 0x002c323d, 0x002b313c, 0x002c323d, 0x002c333e, 0x002d343f, 0x002e343f, 0x002e343f, 0x002f3440, 0x0030343e, 0x002b303a, 0x00282c36, 0x002a2f39, 0x0030343f, 0x00313841, 0x00313842, 0x00303742, 0x002f3742, 0x002e3641, 0x002f3742, 0x00303843, 0x00303843, 0x002f3641, 0x002d3540, 0x002b343e, 0x0027313c, 0x00242d38, 0x00232c36, 0x00252e38, 0x00262e38, 0x0027303a, 0x0028313c, 0x0028303c, 0x0028303c, 0x0028313c, 0x0028303b, 0x0029313c, 0x002d3540, 0x002c3440, 0x00242e39, 0x001d2731, 0x0018232d, 0x0016202b, 0x00141e26, 0x00141f25, 0x00162028, 0x001b252e, 0x001e2934, 0x0024303a, 0x0026343e, 0x0023323c, 0x0023313c, 0x00273440, 0x00283540, 0x001e2934, 0x001b2630, 0x0018242d, 0x0017222b, 0x00162029, 0x00162029, 0x0016222a, 0x0018242c, 0x001a2631, 0x001c2934, 0x001f2c37, 0x0021303b, 0x0023313d, 0x00212f3a, 0x001e2c35, 0x001c2a34, 0x001f2c34, 0x00202c34, 0x00202d38, 0x00202f3a, 0x0020303a, 0x00202f3a, 0x00212f3a, 0x00212f3a, 0x00212f3a, 0x00212f3a, 0x00212f3a, 0x00212f3a, 0x00202e3a, 0x00202f3c, 0x0020303e, 0x001f303c, 0x001c2d3a, 0x001c2b38, 0x001a2835, 0x00182532, 0x0015222e, 0x0013202a, 0x00101d27, 0x00101c25, 0x00101b24, 0x00101a24, 0x000f1924, 0x000e1824, 0x000e1823, 0x000e1823, 0x000e1823, 0x000f1824, 0x000f1824, 0x000f1824, 0x000f1824, 0x000f1822, 0x000f1921, 0x000f1922, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x00101a22, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101923, 0x00111923, 0x00111923, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x000f1820, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a1821, 0x000a1821, 0x000b1821, 0x000d1823, 0x000e1824, 0x000d1824, 0x000c1824, 0x000c1824, 0x000c1824, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000e1a24, 0x000e1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x00101d28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101c28, 0x00101c28, 0x00101c28, 0x00101c28, 0x00101c28, 0x00111d28, 0x0015202c, 0x0017222d, 0x0015212a, 0x00111d25, 0x00131d25, 0x00141f27, 0x00141e26, 0x00131f24, 0x00142027, 0x00152128, 0x00152128, 0x0016222b, 0x00182730, 0x001c2b34, 0x001d2c36, 0x001d2c36, 0x001c2a34, 0x001a252e, 0x001c2730, 0x001a252d, 0x00141f26, 0x00101b21, 0x00131b24, 0x00151e27, 0x0017212b, 0x001c2630, 0x001d2731, 0x00202934, 0x001e2832, 0x001d2932, 0x00222d36, 0x0027313b, 0x0029313c, 0x0027313c, 0x0027313c, 0x002b343f, 0x002e3540, 0x002d3440, 0x002c343d, 0x002c343d, 0x002d353f, 0x002f3740, 0x00303841, 0x00323944, 0x00323844, 0x00313743, 0x00313843, 0x002e3540, 0x002b333c, 0x0029313b, 0x0029313a, 0x002c343e, 0x002d3440, 0x002e343f, 0x002d343c, 0x002c323c, 0x002c303a, 0x002a2f38, 0x002b2f39, 0x002d313c, 0x002e333c, 0x002e333c, 0x002d323c, 0x002c313b, 0x002d323c, 0x0030343f, 0x00313541, 0x00313541, 0x00313541, 0x00323642, 0x00343844, 0x00343844, 0x00353a46, 0x00363b46, 0x00353b47, 0x00353c47, 0x00353c47, 0x00343a45, 0x00303743, 0x00303743, 0x00323844, 0x00323844, 0x00323844, 0x00333a45, 0x00343a45, 0x00343a45, 0x00353c47, 0x00353c49, 0x00353c48, 0x00353c48, 0x00363d48, 0x00363d48, 0x00373f49, 0x00373f49, 0x00363e4a, 0x0038404b, 0x00373f4b, 0x00373e4b, 0x00373d4a, 0x00343b47, 0x00343844, 0x00343844, 0x00343844, 0x00333844, 0x00323844, 0x00323844, 0x00313843, 0x00313843, 0x00303843, 0x00313844, 0x00323844, 0x00323844, 0x00323844, 0x00313844, 0x00303742, 0x00313843, 0x00323844, 0x00323844, 0x00313843, 0x00303742, 0x00303742, 0x00323944, 0x00333944, 0x00323844, 0x00303641, 0x00303541, 0x00303440, 0x002f3440, 0x002e323e, 0x002d323d, 0x00303440, 0x00323743, 0x00323743, 0x00303742, 0x00303641, 0x002f3540, 0x002e3440, 0x002c333e, 0x002b323d, 0x002b313c, 0x002b313c, 0x002b313c, 0x002b313c, 0x002a303c, 0x002b313c, 0x002c313b, 0x002a2f38, 0x00272c35, 0x00282c37, 0x002d333c, 0x00323842, 0x00343b46, 0x00323944, 0x00303844, 0x00313944, 0x00303844, 0x00303843, 0x00303742, 0x00313843, 0x00303843, 0x002e3741, 0x002c3540, 0x0028313c, 0x0028303b, 0x0028303c, 0x00272f3a, 0x00272f3a, 0x002a323d, 0x002a323d, 0x0028323c, 0x002a333d, 0x002b333d, 0x002a323d, 0x002b333e, 0x002a333e, 0x0027313c, 0x00242f39, 0x001f2833, 0x0019232d, 0x00151f27, 0x00131d24, 0x00141f26, 0x0017212b, 0x0017222c, 0x001f2c35, 0x0027353f, 0x00273640, 0x0025343f, 0x0024323d, 0x00283540, 0x001d2a35, 0x001a2630, 0x0018242f, 0x0018222c, 0x00182029, 0x00182029, 0x0017212a, 0x0019232c, 0x001a252e, 0x00192530, 0x001c2832, 0x001f2c38, 0x0024313c, 0x00212f3b, 0x00202e39, 0x001d2a36, 0x001d2a34, 0x001f2b34, 0x001f2b36, 0x001e2c38, 0x001d2c38, 0x001f2c38, 0x001f2c38, 0x001f2c38, 0x001f2c38, 0x001f2c38, 0x001f2c38, 0x001f2c38, 0x001e2c38, 0x001d2c38, 0x001f2d3b, 0x001f2e3c, 0x001c2c39, 0x001a2a37, 0x00182834, 0x00162432, 0x0014212d, 0x00111e2a, 0x000f1c28, 0x00101c25, 0x00101c26, 0x00101b25, 0x00101b25, 0x000e1a24, 0x000e1924, 0x000e1924, 0x000f1a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101a24, 0x00101a24, 0x00101924, 0x00111923, 0x00111923, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x000f1820, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a1821, 0x000a1821, 0x000b1821, 0x000d1823, 0x000e1824, 0x000d1824, 0x000c1824, 0x000c1824, 0x000c1824, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000e1a24, 0x000e1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x00101d28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101c28, 0x00101e29, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101c28, 0x00101c28, 0x00101c28, 0x00101c28, 0x00101c28, 0x00121d29, 0x0015202c, 0x00182430, 0x0019252e, 0x00152129, 0x00142028, 0x00162029, 0x00162028, 0x00162228, 0x00142128, 0x00142128, 0x00152128, 0x0016222b, 0x00182630, 0x001c2b34, 0x001d2c36, 0x001d2c36, 0x001c2a34, 0x0018242d, 0x001c262f, 0x0019242c, 0x00121c24, 0x000f1921, 0x00141d25, 0x0018202a, 0x001a242e, 0x001c2630, 0x001c2730, 0x001e2830, 0x001d2830, 0x00202c34, 0x0026323c, 0x0029343f, 0x002a343e, 0x0028333d, 0x0028313c, 0x002a323d, 0x002c333e, 0x002c323d, 0x002c333d, 0x002f353f, 0x00303740, 0x00303841, 0x00303942, 0x00323a43, 0x00313843, 0x002e3440, 0x002c333e, 0x002b333d, 0x002c343d, 0x002c343d, 0x002b343c, 0x002c343e, 0x002d3440, 0x002f343f, 0x002d343d, 0x002d333c, 0x002d313c, 0x002c303b, 0x002d313c, 0x002f343d, 0x002f343d, 0x002e333c, 0x002c313c, 0x002d323c, 0x002f343d, 0x00303540, 0x00323641, 0x00323642, 0x00323642, 0x00313542, 0x00323642, 0x00323642, 0x00333844, 0x00343844, 0x00333844, 0x00323944, 0x00323844, 0x00313843, 0x002f3541, 0x00303642, 0x00313843, 0x00313843, 0x00313843, 0x00313843, 0x00313843, 0x00323844, 0x00333944, 0x00343a47, 0x00343a46, 0x00343a45, 0x00343b46, 0x00353c47, 0x00363d48, 0x00353d49, 0x00363f4c, 0x0039414e, 0x0038404d, 0x00383f4c, 0x00383e4b, 0x00363c48, 0x00343945, 0x00343844, 0x00343944, 0x00343944, 0x00323844, 0x00313844, 0x00313843, 0x00313843, 0x00303843, 0x00313843, 0x00313843, 0x00313843, 0x00323844, 0x00313843, 0x00313843, 0x00323844, 0x00333944, 0x00333944, 0x00323844, 0x00313843, 0x00323844, 0x00323844, 0x00333844, 0x00323743, 0x00313542, 0x00313541, 0x00303541, 0x002f3440, 0x002d313d, 0x002d323e, 0x00303440, 0x00323642, 0x00323642, 0x00303541, 0x002f3540, 0x002f3440, 0x002f343f, 0x002d333e, 0x002c323d, 0x002a303c, 0x00282f3a, 0x00292f3a, 0x00282f3a, 0x00282f38, 0x00282e38, 0x00282e38, 0x00282f38, 0x00282f39, 0x00292f3a, 0x002b323c, 0x002e343e, 0x00303641, 0x002f3540, 0x002d343f, 0x002c333e, 0x00303641, 0x00343a45, 0x00353b47, 0x00343b46, 0x00323a45, 0x00313944, 0x002f3843, 0x002c3640, 0x002c343f, 0x002c343f, 0x0028303c, 0x0028303c, 0x0028303c, 0x0028303c, 0x0028323c, 0x002a343f, 0x002c3640, 0x002a343f, 0x0027303b, 0x00242e38, 0x00202b35, 0x00202a34, 0x001f2833, 0x001c2630, 0x0018222a, 0x00131d24, 0x00131d24, 0x00152028, 0x0016202a, 0x0018242e, 0x00202d37, 0x0023313b, 0x0026343f, 0x0026343f, 0x00283641, 0x001f2c37, 0x001a2631, 0x001a2530, 0x0019232d, 0x00182029, 0x00182029, 0x0017212a, 0x0018232c, 0x0019242e, 0x001a2530, 0x001a2630, 0x001c2934, 0x00212f3b, 0x00202c38, 0x00202d38, 0x00202d38, 0x001e2b34, 0x001d2933, 0x001c2934, 0x001a2834, 0x00192834, 0x001a2834, 0x001b2834, 0x001b2834, 0x001b2834, 0x001b2834, 0x001a2834, 0x001a2834, 0x001b2834, 0x001b2834, 0x001c2935, 0x001d2b37, 0x001c2b37, 0x001a2935, 0x00182734, 0x00152431, 0x0013202c, 0x00101e29, 0x000f1c27, 0x00101d26, 0x00101c26, 0x00101c26, 0x00101b25, 0x00101b25, 0x000f1a24, 0x000f1a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101924, 0x00111923, 0x00111923, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x000f1820, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1822, 0x000c1822, 0x000c1822, 0x000d1822, 0x000d1722, 0x000d1722, 0x000c1822, 0x000c1822, 0x000c1823, 0x000c1823, 0x000c1923, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000f1c27, 0x000f1c27, 0x000f1c27, 0x000f1c27, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c27, 0x00101c28, 0x00101c28, 0x00101c28, 0x00101c28, 0x00101c28, 0x00111e29, 0x00111e29, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101c28, 0x00101c28, 0x00111c28, 0x00111c28, 0x00111c28, 0x00101c28, 0x00121f29, 0x0015222c, 0x001b2832, 0x001b2730, 0x0018242d, 0x0018222b, 0x0018222b, 0x0019232c, 0x0019242c, 0x0018222a, 0x00162128, 0x00172229, 0x0018232c, 0x00192630, 0x001e2b35, 0x001f2c35, 0x001e2b35, 0x001c2832, 0x001c2730, 0x001d2830, 0x0018232b, 0x00111c24, 0x00121c24, 0x00172028, 0x0019232c, 0x001b242c, 0x001b242d, 0x001c252e, 0x001e2831, 0x00212c34, 0x0026313a, 0x002a3640, 0x002a3640, 0x002a343f, 0x0029333d, 0x0029323d, 0x0029303c, 0x002a303c, 0x002a313c, 0x002b333c, 0x002d363f, 0x002f3642, 0x002f3641, 0x002f3742, 0x002f3842, 0x002f3742, 0x002d3540, 0x002c3440, 0x002e3641, 0x00323a44, 0x00323944, 0x00303843, 0x002f3641, 0x002f3641, 0x00303640, 0x00303640, 0x0030353f, 0x00303640, 0x00303640, 0x00303540, 0x00303540, 0x00303540, 0x002e343e, 0x002e343e, 0x002f343f, 0x00303540, 0x00303540, 0x00313541, 0x00323642, 0x00323642, 0x00313541, 0x00313541, 0x00323642, 0x00333743, 0x00333844, 0x00313843, 0x00303843, 0x00303843, 0x00303742, 0x002f3541, 0x00303641, 0x00303742, 0x00303742, 0x00303742, 0x00303742, 0x00303742, 0x00313843, 0x00323844, 0x00323844, 0x00333946, 0x00343b47, 0x00343b48, 0x00343c48, 0x00343c48, 0x00343c49, 0x00353d4a, 0x0038404c, 0x0038404d, 0x0038404d, 0x0038404c, 0x00363e4a, 0x00343c48, 0x00343a47, 0x00343a47, 0x00343946, 0x00323844, 0x00323743, 0x00323843, 0x00313843, 0x00313843, 0x00313843, 0x00313843, 0x00313843, 0x00313843, 0x00303843, 0x00313843, 0x00323844, 0x00333944, 0x00343945, 0x00333944, 0x00333944, 0x00323844, 0x00333844, 0x00333844, 0x00323642, 0x00313541, 0x00303441, 0x00303440, 0x00303440, 0x002f3440, 0x002f3440, 0x00303440, 0x00303440, 0x00303440, 0x002f343e, 0x002e333d, 0x002e333d, 0x002e333d, 0x002d323c, 0x002b313c, 0x00282f39, 0x00272d38, 0x00282e38, 0x00282e38, 0x00282e37, 0x00272d37, 0x00272d37, 0x00282f39, 0x002a303c, 0x002b313d, 0x002b313c, 0x002b313c, 0x002e3440, 0x002e343f, 0x002c323d, 0x002b303c, 0x002c303c, 0x00303541, 0x00333844, 0x00333844, 0x00323a46, 0x00323b46, 0x00303945, 0x00303945, 0x002f3945, 0x002e3844, 0x002a333f, 0x0028313d, 0x0028303c, 0x0028303c, 0x0029323c, 0x002c3540, 0x002d3842, 0x002d3842, 0x0029333e, 0x00252f39, 0x00202c34, 0x001e2831, 0x001c2630, 0x001b242f, 0x0018222a, 0x00162028, 0x00141e24, 0x00152027, 0x0018232b, 0x0019242e, 0x001f2c35, 0x00212f38, 0x00212f39, 0x0025333e, 0x00293844, 0x0023313d, 0x001c2834, 0x001a2630, 0x0019242e, 0x0018222c, 0x0018212b, 0x00162029, 0x0017212a, 0x0019232c, 0x001b252f, 0x001c252f, 0x001b2731, 0x001e2a34, 0x001d2a35, 0x001e2b37, 0x00202d38, 0x001f2c37, 0x001b2833, 0x00192430, 0x00182430, 0x0018242f, 0x0017232f, 0x00192531, 0x00192631, 0x00182430, 0x0018242f, 0x0018242f, 0x0017242f, 0x0017242f, 0x0016232c, 0x0017232d, 0x0018252f, 0x001a2731, 0x001a2833, 0x00192632, 0x00172330, 0x0013202c, 0x00101e29, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101c27, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00111c26, 0x00111c26, 0x00101c26, 0x00101c26, 0x00111c26, 0x00111c26, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101a24, 0x00101a24, 0x00101924, 0x00111923, 0x00111923, 0x00101922, 0x00101921, 0x000f1821, 0x000f1820, 0x000f1820, 0x000e171f, 0x000e171e, 0x000e171e, 0x000e171e, 0x000e171e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1822, 0x000c1822, 0x000c1822, 0x000c1820, 0x000c1720, 0x000c1820, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1822, 0x000c1822, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c26, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c26, 0x000f1c27, 0x00101d27, 0x00101d27, 0x00101c28, 0x00121e29, 0x00121e29, 0x00101e29, 0x00101e29, 0x00101d28, 0x00101d28, 0x00101d28, 0x00111c28, 0x00111c28, 0x00111c28, 0x00111c28, 0x00101c28, 0x00101e28, 0x0014212b, 0x001c2933, 0x001c2731, 0x0018242e, 0x0018222b, 0x0018222b, 0x0019232c, 0x001b252e, 0x001a242d, 0x0018222b, 0x0019232c, 0x0019242c, 0x00192530, 0x00202b35, 0x001e2a34, 0x001c2831, 0x0019252f, 0x00202a33, 0x001f2a33, 0x0018232c, 0x00121c25, 0x00141e27, 0x0018212a, 0x001a232c, 0x001a232c, 0x001a242c, 0x001c262f, 0x00202a33, 0x00242d36, 0x0028323b, 0x002a3640, 0x0029353f, 0x0029333c, 0x0028333c, 0x0029333c, 0x002a313c, 0x0029303c, 0x0029313c, 0x002b343d, 0x002c3640, 0x002e3641, 0x002d3540, 0x002c333e, 0x002c343f, 0x002d3641, 0x002f3742, 0x002f3742, 0x00303844, 0x00343c48, 0x00353c48, 0x00333947, 0x00323844, 0x00313843, 0x00323842, 0x00323842, 0x00343a44, 0x00343b44, 0x00343c47, 0x00343a45, 0x00333844, 0x00313843, 0x00313843, 0x00303742, 0x00303742, 0x00303740, 0x0030343f, 0x002f343f, 0x00303440, 0x00303440, 0x00313641, 0x00333843, 0x00333743, 0x00333844, 0x00323844, 0x00303843, 0x002f3742, 0x00303742, 0x00303541, 0x00303541, 0x00303742, 0x00303743, 0x00303743, 0x00303743, 0x00303742, 0x00313843, 0x00313843, 0x00323844, 0x00333945, 0x00343b48, 0x00343c49, 0x00343c49, 0x00323c48, 0x00323b48, 0x00323b48, 0x00343c48, 0x00353d4a, 0x0038404c, 0x0038404d, 0x00383f4c, 0x00343c49, 0x00333b48, 0x00333b48, 0x00333b48, 0x00333b47, 0x00323844, 0x00323843, 0x00333944, 0x00333944, 0x00323844, 0x00333844, 0x00323844, 0x00313843, 0x00303742, 0x002f3440, 0x00303641, 0x00323844, 0x00343a46, 0x00343b46, 0x00343b46, 0x00333944, 0x00333844, 0x00333743, 0x00323642, 0x00313541, 0x002f343f, 0x002d323d, 0x002e333e, 0x00303440, 0x00303441, 0x00303440, 0x002f3440, 0x002e333e, 0x002e323e, 0x002d323c, 0x002c3139, 0x002b3038, 0x002b3038, 0x002b3038, 0x002a303a, 0x00272d37, 0x00252c36, 0x00262c36, 0x00262c36, 0x00262d37, 0x00272d37, 0x00272d37, 0x00282e38, 0x0029303b, 0x002a303c, 0x002a303c, 0x002a303c, 0x002d333e, 0x002d333f, 0x002d333f, 0x002c333e, 0x002e3440, 0x00303641, 0x00313743, 0x00323744, 0x00303744, 0x00313946, 0x00303946, 0x00303a47, 0x00313b49, 0x00303a47, 0x002c3441, 0x0028303e, 0x00272f3c, 0x00272f3c, 0x0028303c, 0x0028313c, 0x0029333d, 0x002b3540, 0x002b3540, 0x0028323c, 0x00242d36, 0x001e2830, 0x001c242f, 0x0019212c, 0x0018212c, 0x0018232b, 0x00182329, 0x0019242a, 0x001a242c, 0x001a2530, 0x00202d37, 0x00223039, 0x00202d38, 0x00202f3a, 0x00263640, 0x0023333e, 0x001c2b36, 0x00192631, 0x00192430, 0x0019232d, 0x0018222c, 0x00162029, 0x00152028, 0x0018222a, 0x001c252e, 0x001c262f, 0x001a262f, 0x001a262f, 0x001b2730, 0x001c2833, 0x001e2a34, 0x001d2a35, 0x001a2733, 0x0018232e, 0x0018222c, 0x0016202b, 0x00151f2a, 0x0018222c, 0x0018232e, 0x0015212c, 0x0014202a, 0x0014202a, 0x0014202a, 0x00142029, 0x00131f28, 0x00131f29, 0x0014202a, 0x0017232d, 0x00192530, 0x00192531, 0x0018232f, 0x0014202c, 0x00101e2a, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101c27, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00111c26, 0x00111c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00111c26, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101a24, 0x00101a24, 0x00101924, 0x00111923, 0x00111923, 0x00101922, 0x000f1921, 0x000f1821, 0x000e1820, 0x000e1820, 0x000e171e, 0x000e171e, 0x000e171e, 0x000e171e, 0x000e171e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1822, 0x000c1822, 0x000c1822, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1822, 0x000c1822, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c26, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c27, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101d28, 0x00121e29, 0x00121e29, 0x00101e29, 0x00101e29, 0x00101d28, 0x00101d28, 0x00101d28, 0x00111c28, 0x00111c28, 0x00111c28, 0x00111c28, 0x00101c27, 0x000f1d27, 0x0013202b, 0x001b2832, 0x001b2732, 0x00182430, 0x0018222c, 0x0018222b, 0x0018232c, 0x0019242d, 0x001b262f, 0x001a252e, 0x001a252e, 0x0019242c, 0x00192530, 0x001e2a34, 0x001c2833, 0x0018232d, 0x0016222c, 0x001d2934, 0x001e2a34, 0x001a252e, 0x0017212a, 0x0018212a, 0x0018232c, 0x0018232c, 0x001b242d, 0x001e2830, 0x00202b34, 0x00212c34, 0x00232d36, 0x00273039, 0x0028333c, 0x0028333c, 0x0029333c, 0x0029333c, 0x002a333c, 0x002b323c, 0x002a313c, 0x002a323d, 0x002b343e, 0x002c3540, 0x002d3540, 0x002c343f, 0x002a313d, 0x002b323d, 0x002e3540, 0x00303844, 0x00333b46, 0x00333c46, 0x00333b46, 0x00313845, 0x00313744, 0x00303644, 0x00303642, 0x00303741, 0x00313841, 0x00333943, 0x00343b45, 0x00343b46, 0x00343b46, 0x00333944, 0x00333944, 0x00333944, 0x00313843, 0x00313843, 0x00303740, 0x002f343e, 0x002c303c, 0x002e333e, 0x00303440, 0x00323742, 0x00343844, 0x00343844, 0x00333844, 0x00323844, 0x00313843, 0x00303843, 0x00303743, 0x00303642, 0x00303642, 0x00303742, 0x00313843, 0x00313843, 0x00303843, 0x00303843, 0x00303743, 0x00303742, 0x00323844, 0x00333945, 0x00343c48, 0x00343d49, 0x00343d49, 0x00323c49, 0x00323c48, 0x00333c49, 0x00343c49, 0x00353d4a, 0x00373f4c, 0x0038404c, 0x00363e4b, 0x00343c49, 0x00343c48, 0x00333b48, 0x00333b48, 0x00333b48, 0x00343a48, 0x00343a47, 0x00353b48, 0x00343b47, 0x00343a46, 0x00343a46, 0x00343945, 0x00323844, 0x002f3540, 0x002c333e, 0x002d333f, 0x00323844, 0x00343b46, 0x00343a45, 0x00333944, 0x00313843, 0x00323642, 0x00323642, 0x00323642, 0x00303440, 0x002f333d, 0x002e333e, 0x002e333e, 0x002f343f, 0x00303440, 0x00303440, 0x002e333e, 0x002c303c, 0x002b2f3c, 0x002b3038, 0x002a2f37, 0x002a2f37, 0x002a2f37, 0x002a2f37, 0x00292f38, 0x00262c36, 0x00242b34, 0x00252c35, 0x00262c36, 0x00262c36, 0x00272c36, 0x00272d37, 0x00282d38, 0x0029303b, 0x002b313c, 0x002b313c, 0x002c313d, 0x002c323d, 0x002d343f, 0x002f3440, 0x002f3440, 0x002d333f, 0x002e3440, 0x00303541, 0x00303442, 0x002c3442, 0x002b3441, 0x002c3542, 0x002f3846, 0x00313c4a, 0x00303948, 0x002d3543, 0x0028303d, 0x00272f3c, 0x00262e3b, 0x00262d39, 0x00262f39, 0x0025303a, 0x0028303b, 0x0028303c, 0x0027303a, 0x00252d36, 0x00202831, 0x001f2630, 0x001b232d, 0x00172029, 0x00162028, 0x00172128, 0x0019242b, 0x001d2830, 0x001c2630, 0x00202c37, 0x00202e38, 0x001f2c37, 0x001e2c38, 0x0022323c, 0x0024333e, 0x001d2c37, 0x00192531, 0x00192430, 0x0019232d, 0x0018222c, 0x0017212a, 0x00152029, 0x00162029, 0x001a242d, 0x001c262f, 0x0019242d, 0x0018242c, 0x0018242c, 0x001b252f, 0x001c2630, 0x001a2631, 0x00192531, 0x001a2530, 0x0019232e, 0x0016202b, 0x00141e29, 0x00151f2a, 0x0015202b, 0x00141f29, 0x00101c27, 0x00111d27, 0x00121e28, 0x00111d27, 0x00101c26, 0x00101b25, 0x00121e28, 0x0016212c, 0x0018242f, 0x00182530, 0x0017232e, 0x0014202c, 0x00101e2a, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x00101c27, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00111c26, 0x00111c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00111c26, 0x00101c26, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101a24, 0x00101a24, 0x00101924, 0x00111923, 0x00111923, 0x00101922, 0x000f1921, 0x000f1821, 0x000e1820, 0x000e1820, 0x000e171e, 0x000e171e, 0x000e171e, 0x000e171e, 0x000e171e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1822, 0x000c1822, 0x000c1822, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1822, 0x000c1822, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c26, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00111e29, 0x00121e29, 0x00121e29, 0x00121e29, 0x00111e28, 0x00101f29, 0x0014222d, 0x001a2833, 0x001a2834, 0x00172430, 0x0017222d, 0x0017232c, 0x0017232c, 0x0018242d, 0x00192530, 0x001b2630, 0x00192530, 0x0018242e, 0x00192530, 0x001d2933, 0x001b2731, 0x0016222c, 0x0015212c, 0x001b2731, 0x001c2832, 0x001c2832, 0x001b2530, 0x001a242c, 0x001a252d, 0x001b252d, 0x001e2831, 0x00202b34, 0x00202b34, 0x00212c34, 0x00212c34, 0x00242e37, 0x00252f39, 0x0028323c, 0x002c353f, 0x002d3740, 0x002d343e, 0x002b323c, 0x002c323d, 0x002c333e, 0x002c343e, 0x002c353f, 0x002d3540, 0x002d3440, 0x002c333e, 0x002c333f, 0x00303742, 0x00323a45, 0x00333b46, 0x00303844, 0x002d3641, 0x002e3542, 0x002f3643, 0x002f3643, 0x00303641, 0x002f353f, 0x002e343e, 0x002d343c, 0x002c323c, 0x002a313c, 0x002a303c, 0x002b303c, 0x002c313d, 0x002c323e, 0x002e343f, 0x00313842, 0x00303740, 0x0030343f, 0x002e333c, 0x00303440, 0x00313541, 0x00313541, 0x00323642, 0x00333743, 0x00323843, 0x00313843, 0x00323844, 0x00323844, 0x00323844, 0x00313843, 0x00303642, 0x00303641, 0x00303641, 0x00303641, 0x00303541, 0x00303541, 0x00303541, 0x002f3541, 0x00303641, 0x00303643, 0x00323a47, 0x00343c49, 0x00343c49, 0x00323c49, 0x00323c49, 0x00343c49, 0x00363d4a, 0x00353d4a, 0x00363e4b, 0x00363e4b, 0x00373e4b, 0x00373e4b, 0x00363e4b, 0x00353e4b, 0x00353d4a, 0x00353d4a, 0x00363c4a, 0x00363c49, 0x00353c49, 0x00343b48, 0x00343a46, 0x00343b47, 0x00343b46, 0x00343a46, 0x00313843, 0x00303540, 0x002f3540, 0x00323844, 0x00343c47, 0x00343b46, 0x00313843, 0x00303641, 0x00303440, 0x00303541, 0x00303441, 0x0030343f, 0x002e333c, 0x002d313c, 0x002d313d, 0x002e323e, 0x002e333e, 0x002e333e, 0x002c303c, 0x002a2f3b, 0x00292e39, 0x002a2f38, 0x002a2f37, 0x002a2f37, 0x002a2f37, 0x002a2f37, 0x002b2f39, 0x00282d38, 0x00282c36, 0x00282c36, 0x00282d37, 0x00282c36, 0x00282c36, 0x00282c36, 0x00282d38, 0x002b303a, 0x002c303c, 0x002a303c, 0x002a303b, 0x002b313c, 0x002d343f, 0x002f3641, 0x00303641, 0x002c343e, 0x002c3440, 0x002f3542, 0x002f3442, 0x002c3441, 0x002b3441, 0x0028323e, 0x00293440, 0x00303948, 0x002f3845, 0x002d3542, 0x002a323f, 0x0029313e, 0x0028303c, 0x00262f39, 0x00252d38, 0x00242d38, 0x00252f39, 0x00252d38, 0x00232a34, 0x00222933, 0x00222831, 0x00212832, 0x001e2430, 0x00161e28, 0x00121c24, 0x00141f26, 0x00162028, 0x001c262f, 0x001f2a34, 0x00202d37, 0x00212f38, 0x00212f38, 0x001c2a35, 0x00202d39, 0x0024323e, 0x00202e39, 0x00182631, 0x00192530, 0x0019242f, 0x0018232d, 0x0018222c, 0x0016202b, 0x00152029, 0x00172029, 0x0018232c, 0x0018222b, 0x00162029, 0x00162028, 0x00172129, 0x0019242c, 0x0018232c, 0x0016222c, 0x0018242e, 0x001a242f, 0x0018222c, 0x00141f29, 0x00151f2a, 0x0014202a, 0x00131f28, 0x00101c25, 0x00101b24, 0x00101b25, 0x00101a24, 0x000e1924, 0x000e1924, 0x00111c27, 0x0014202b, 0x0017232d, 0x0016242e, 0x0014222c, 0x0013202c, 0x00101e2a, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x00101c27, 0x00101c28, 0x00101c27, 0x000e1c25, 0x000e1c25, 0x00101c25, 0x00101c26, 0x00101c26, 0x000f1c26, 0x000f1c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101b25, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101924, 0x00111924, 0x00111924, 0x00101923, 0x000f1921, 0x000f1821, 0x000e1820, 0x000e1820, 0x000d181e, 0x000d181e, 0x000d171e, 0x000e171e, 0x000e171e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1822, 0x000c1822, 0x000c1822, 0x000c1822, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1822, 0x000c1822, 0x000c1822, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c26, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101e29, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00121e29, 0x00121e29, 0x00121e2a, 0x00131f2a, 0x0013202c, 0x0014222e, 0x00172633, 0x001b2936, 0x001a2835, 0x00172431, 0x0017232e, 0x0017232c, 0x0017232c, 0x0017232c, 0x00192530, 0x001c2731, 0x001a2530, 0x0018242f, 0x00192530, 0x001c2832, 0x001a2630, 0x0017222c, 0x0018232d, 0x001c2831, 0x001c2832, 0x001b2731, 0x001a2630, 0x001c2730, 0x001f2932, 0x00222d35, 0x00242d36, 0x00222c34, 0x00202b34, 0x00212c34, 0x00222c35, 0x00242d36, 0x00242f38, 0x0028313c, 0x002c343e, 0x00303840, 0x002f353f, 0x002c323c, 0x002c323d, 0x002c333d, 0x002c343d, 0x002c343e, 0x002e3641, 0x002e3641, 0x002f3541, 0x002f3541, 0x00303742, 0x002f3641, 0x002e3440, 0x002d343f, 0x002c343f, 0x002c343f, 0x002c343f, 0x002a323d, 0x0029303b, 0x00282f38, 0x00282f37, 0x002b313a, 0x002b313b, 0x00282f39, 0x00282e39, 0x00282f3b, 0x00292f3a, 0x0029303a, 0x002b313b, 0x002d343d, 0x002d343d, 0x0030353f, 0x00323740, 0x00313641, 0x00313541, 0x00303440, 0x00313541, 0x00323642, 0x00323743, 0x00313843, 0x00333944, 0x00333944, 0x00333944, 0x00323844, 0x00303742, 0x00303541, 0x002d343f, 0x002d343f, 0x002f3440, 0x002f3541, 0x00303641, 0x00303742, 0x00303742, 0x00303743, 0x00333a47, 0x00343c49, 0x00343c48, 0x00333c48, 0x00343d4a, 0x00363e4b, 0x00373f4c, 0x00363d4a, 0x00363e4b, 0x00363e4b, 0x00373f4c, 0x0038404c, 0x0038404d, 0x0039414e, 0x0039414e, 0x0039414e, 0x0039404d, 0x003a404d, 0x00383f4c, 0x00373c4a, 0x00363c48, 0x00353c47, 0x00353c47, 0x00343b46, 0x00343a45, 0x00333944, 0x00323844, 0x00313843, 0x00313844, 0x00323844, 0x00313843, 0x002f3540, 0x002e333e, 0x002e333e, 0x002f3440, 0x002e333d, 0x002d313c, 0x002c303c, 0x002c303c, 0x002c303c, 0x002c303c, 0x002d313d, 0x002d313d, 0x002c303c, 0x002c303c, 0x002a2f38, 0x002a2f37, 0x002a2f37, 0x002a2f37, 0x002a2f37, 0x002c303a, 0x002b2f39, 0x002a2f39, 0x002b303a, 0x002b3039, 0x002a2f39, 0x002b3039, 0x002a3039, 0x002b303a, 0x002c313b, 0x002d323e, 0x002d343f, 0x002e343f, 0x002e3540, 0x002f3743, 0x00303844, 0x00303844, 0x002c3440, 0x002b333f, 0x002d3441, 0x002e3442, 0x002c3542, 0x002c3542, 0x0028323e, 0x0026303c, 0x002c3542, 0x002f3643, 0x002d3440, 0x002e3441, 0x002e3442, 0x002c3340, 0x0028303c, 0x0027303a, 0x00252f39, 0x00252e38, 0x00242c37, 0x00222934, 0x001e242e, 0x001e242e, 0x00202630, 0x001f2530, 0x001a212c, 0x00141c24, 0x00141d24, 0x00172029, 0x001a242c, 0x00242f39, 0x00223039, 0x0022313c, 0x0022313c, 0x001b2834, 0x001c2935, 0x00212f3b, 0x0023303c, 0x001a2832, 0x001a2630, 0x001c2832, 0x001b2730, 0x001a242f, 0x0018222c, 0x0016202a, 0x00141e27, 0x00131c25, 0x00141f28, 0x00162029, 0x00152028, 0x00162028, 0x0018222a, 0x0018232c, 0x0016212c, 0x0016212b, 0x0018222b, 0x0018232c, 0x0018212c, 0x0017212c, 0x0018222c, 0x00162029, 0x00131d25, 0x00101a23, 0x000f1923, 0x000e1823, 0x000e1822, 0x000e1823, 0x00111c26, 0x0014202a, 0x0015212c, 0x0015232d, 0x0014222c, 0x0013202b, 0x00101e2a, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x00101c28, 0x00101c28, 0x00101c27, 0x000e1c25, 0x000e1c25, 0x000f1c25, 0x00101c26, 0x00101c26, 0x000f1c26, 0x000f1c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101b25, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101924, 0x00111924, 0x00111924, 0x00101923, 0x000f1921, 0x000f1821, 0x000e1820, 0x000e1820, 0x000d181e, 0x000d181e, 0x000d171e, 0x000e171e, 0x000e171e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1822, 0x000c1822, 0x000c1822, 0x000c1824, 0x000c1724, 0x000c1724, 0x000c1724, 0x000c1724, 0x000c1723, 0x000c1821, 0x000c1821, 0x000c1822, 0x000c1822, 0x000c1823, 0x000b1823, 0x000b1823, 0x000d1924, 0x000d1924, 0x000d1a25, 0x000d1a25, 0x000d1b25, 0x000d1b25, 0x000d1b25, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c27, 0x000f1c27, 0x000f1c28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00111e2a, 0x00131f2b, 0x00131f2b, 0x0014202c, 0x00162330, 0x001a2836, 0x001e2d3c, 0x001f2e3c, 0x001c2b38, 0x001a2834, 0x00182530, 0x0017232e, 0x0017222d, 0x0017232c, 0x00182430, 0x001a2530, 0x0018242f, 0x0018242f, 0x00192530, 0x001c2731, 0x001b2430, 0x0018222c, 0x001a242f, 0x001c2730, 0x001b2630, 0x0019242e, 0x0019242d, 0x001d2830, 0x00202c34, 0x00243038, 0x00232e36, 0x00212c34, 0x00202c34, 0x00232c35, 0x00242e37, 0x00242e37, 0x00242d38, 0x0026303b, 0x002b343e, 0x002e3640, 0x002f3640, 0x002d343e, 0x002c333d, 0x002e333d, 0x002d323c, 0x002c313c, 0x002f3540, 0x00303640, 0x002f3640, 0x002d343e, 0x002c313c, 0x002a303b, 0x002a303b, 0x002c323c, 0x002c333e, 0x002c333e, 0x002c323d, 0x002b313c, 0x0029303b, 0x00282f39, 0x00293038, 0x002c313a, 0x002c323c, 0x002c313c, 0x002a2f3a, 0x00292e39, 0x00282e38, 0x00272d37, 0x00252c35, 0x00272c36, 0x00272c36, 0x00282d37, 0x002c303a, 0x002d313c, 0x002c303b, 0x002b303b, 0x002c323c, 0x002f343f, 0x00303540, 0x00303742, 0x00303843, 0x00303843, 0x00303844, 0x00303844, 0x00303742, 0x00303642, 0x002e3541, 0x002e3540, 0x002e3540, 0x002f3741, 0x00303842, 0x00323843, 0x00303742, 0x00313844, 0x00343b47, 0x00343c48, 0x00343b47, 0x00343c48, 0x00373f4b, 0x0038404c, 0x00383f4b, 0x00373e4a, 0x00373e4a, 0x00373e4a, 0x00383f4b, 0x00383f4c, 0x0038404c, 0x0039404d, 0x0039404d, 0x0039404d, 0x003b414d, 0x003c414e, 0x003b404c, 0x00383c49, 0x00353b47, 0x00353b47, 0x00363c48, 0x00363c47, 0x00353b47, 0x00343b47, 0x00343c47, 0x00343c47, 0x00343b46, 0x00333944, 0x00303742, 0x002d343f, 0x002c313c, 0x002c313d, 0x002d323d, 0x002e313c, 0x002d303b, 0x002c303b, 0x002c2f3c, 0x002c303c, 0x002d303c, 0x002d333d, 0x002d333d, 0x002c323c, 0x002c303c, 0x002b303a, 0x002a3039, 0x00293038, 0x00292f38, 0x002b3039, 0x002c323c, 0x002c323c, 0x002c323c, 0x002d333c, 0x0030353e, 0x00303540, 0x00323841, 0x00323842, 0x00323841, 0x00333842, 0x00323844, 0x00323844, 0x00323844, 0x00313844, 0x00333b48, 0x00333b48, 0x00333b48, 0x00313946, 0x002f3643, 0x002e3543, 0x002f3643, 0x002d3543, 0x002c3540, 0x002b3440, 0x0029323d, 0x002c3440, 0x002d3440, 0x002c333f, 0x002c3440, 0x002e3441, 0x002d3540, 0x002a333d, 0x0028313c, 0x0027303c, 0x00242e38, 0x00212b35, 0x00202934, 0x001e272f, 0x001c232b, 0x001c232c, 0x001d242c, 0x001c242c, 0x00182128, 0x00151e25, 0x00172028, 0x0019232c, 0x00212c38, 0x0022303b, 0x0024333e, 0x0022303c, 0x001b2834, 0x001b2834, 0x00202d38, 0x0024323d, 0x001b2833, 0x001a2630, 0x001c2830, 0x001c2830, 0x001a242e, 0x0018222c, 0x0017202a, 0x00141d26, 0x00111a24, 0x00141d26, 0x00151f28, 0x00172028, 0x00182029, 0x0018212a, 0x0019242e, 0x0018242f, 0x0016222c, 0x00131d26, 0x00121c25, 0x0016202a, 0x001b2430, 0x001c2630, 0x0018222c, 0x00141f28, 0x00121c24, 0x00101a23, 0x000f1824, 0x000e1822, 0x000f1824, 0x00111c26, 0x00131e28, 0x0014202b, 0x0014222c, 0x0014222c, 0x0013202b, 0x00101e29, 0x00101d28, 0x000f1c28, 0x000e1c27, 0x000f1b27, 0x00101b27, 0x00101b27, 0x000e1c25, 0x000e1c25, 0x000e1b24, 0x000f1a24, 0x000f1a24, 0x000f1c25, 0x000f1c25, 0x00101c25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000f1b25, 0x000f1a24, 0x000f1a24, 0x000f1a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101924, 0x00101924, 0x000f1922, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000e1820, 0x000e181f, 0x000d171e, 0x000d161d, 0x000d161d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1822, 0x000c1822, 0x000c1823, 0x000c1825, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1724, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1821, 0x000b1822, 0x000b1822, 0x000d1924, 0x000d1924, 0x000e1a26, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x00101d28, 0x00101d28, 0x000f1c26, 0x000f1c26, 0x000f1c27, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00111f2b, 0x0013202c, 0x0013202c, 0x00142230, 0x00182735, 0x0020303e, 0x00243443, 0x00253544, 0x00243240, 0x001f2d3a, 0x001c2834, 0x00192531, 0x0018242f, 0x0017232d, 0x0018242d, 0x0018242e, 0x0018242d, 0x0018242f, 0x001b2530, 0x001b2530, 0x001a242f, 0x001a242f, 0x001b2530, 0x001c262e, 0x001b252c, 0x0019242b, 0x0019242a, 0x001c262e, 0x001c2830, 0x001b2830, 0x001b262e, 0x001c272f, 0x001f2b33, 0x00232d36, 0x00242e37, 0x00242e37, 0x00252f38, 0x0028323c, 0x002b3540, 0x002e3742, 0x00303743, 0x002e3440, 0x002d333e, 0x002e343f, 0x002e333d, 0x002d323c, 0x002f343e, 0x0030353f, 0x002c343d, 0x00282e38, 0x00262c36, 0x00282f38, 0x00293039, 0x00293039, 0x002b313c, 0x002c333e, 0x002c333e, 0x002c333e, 0x002b313c, 0x002a303c, 0x00292f39, 0x002a2e38, 0x002b2f39, 0x002b303a, 0x002b2f39, 0x002b2f39, 0x00292e38, 0x00272d37, 0x00272c36, 0x00282d37, 0x00282d38, 0x00282d37, 0x00292e38, 0x00292e38, 0x00282d37, 0x00272d37, 0x00282e38, 0x00282f38, 0x0029303a, 0x0029313c, 0x002b333d, 0x002c343f, 0x002c3440, 0x002d3540, 0x002d3540, 0x002d3541, 0x002d3540, 0x002c343f, 0x002a323d, 0x002b333d, 0x002c343e, 0x002c323c, 0x002a303a, 0x002a303b, 0x002c333e, 0x002d343f, 0x002e3440, 0x002f3540, 0x00313743, 0x00313743, 0x00313743, 0x00313843, 0x00323844, 0x00333844, 0x00323844, 0x00323845, 0x00333946, 0x00343a47, 0x00343b48, 0x00343b48, 0x00363c48, 0x00363c48, 0x00353945, 0x00303540, 0x00303440, 0x00313642, 0x00323742, 0x00343944, 0x00353b47, 0x00343c47, 0x00333c46, 0x00333b46, 0x00343a46, 0x00323844, 0x00303641, 0x002e343f, 0x002c333e, 0x002e343f, 0x002d343f, 0x002d313d, 0x002b303a, 0x002a2f39, 0x002a2f39, 0x002c303a, 0x002c313c, 0x002d343d, 0x002e343d, 0x002e343d, 0x002c333c, 0x002c323c, 0x002b313c, 0x002a303b, 0x002a303a, 0x002c333c, 0x00303640, 0x00303740, 0x00303740, 0x0030363f, 0x002f353e, 0x002c333c, 0x002d353e, 0x002e3740, 0x002f3740, 0x002e363f, 0x002c343f, 0x002d343f, 0x00303742, 0x00303844, 0x00323a48, 0x00323a48, 0x00303a47, 0x00303945, 0x002e3844, 0x002e3643, 0x002f3743, 0x002e3642, 0x002b333e, 0x0028303c, 0x0029313c, 0x0029313c, 0x002a323c, 0x002a323d, 0x002c343e, 0x002c3440, 0x002d3540, 0x002c343f, 0x002a343e, 0x002a343f, 0x0028313c, 0x00212b36, 0x00202b34, 0x00202a32, 0x001b242b, 0x00192028, 0x001b2129, 0x001d252c, 0x001d262d, 0x001a2229, 0x00152028, 0x0019232d, 0x001e2b35, 0x0022303b, 0x0026353f, 0x00202d38, 0x00192732, 0x00192732, 0x001f2d38, 0x0024343f, 0x001d2c37, 0x001a2730, 0x001a272d, 0x001a262c, 0x0019242a, 0x00182329, 0x00182128, 0x00151e25, 0x00131b23, 0x00131c24, 0x00151d27, 0x00182029, 0x0018212a, 0x0018212a, 0x0018222c, 0x0017232d, 0x0017232d, 0x00142029, 0x00101c24, 0x00131f27, 0x001a252e, 0x001d2831, 0x001c262f, 0x0018222b, 0x00141e27, 0x00101b24, 0x000f1923, 0x000f1824, 0x00101a24, 0x00121c26, 0x00121e28, 0x0014202a, 0x0014212b, 0x0014222c, 0x0012202b, 0x00101e29, 0x00101d28, 0x000f1c28, 0x000e1c27, 0x000f1b27, 0x00101b27, 0x000f1b26, 0x000d1b24, 0x000d1b24, 0x000d1a24, 0x000d1924, 0x000e1a24, 0x000f1b25, 0x00101b25, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101b24, 0x00101b24, 0x00101a23, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000d171f, 0x000d161d, 0x000d161d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1822, 0x000c1822, 0x000c1823, 0x000c1825, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1724, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1821, 0x000b1822, 0x000b1822, 0x000d1924, 0x000d1924, 0x000e1a26, 0x000e1c27, 0x000e1c27, 0x000d1b26, 0x000d1b26, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c26, 0x000f1c26, 0x000f1c27, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00111f2b, 0x0013202c, 0x0013202c, 0x00142230, 0x001b2838, 0x00213240, 0x00263846, 0x00283948, 0x00253544, 0x0021303c, 0x001f2c38, 0x001c2935, 0x001b2732, 0x00192530, 0x0017232c, 0x0017232c, 0x0018242d, 0x0018242f, 0x001b2530, 0x001b2530, 0x001a242f, 0x001a242f, 0x001b252f, 0x001b252d, 0x001b252c, 0x0019242a, 0x0019242a, 0x001b252c, 0x0018242b, 0x0017232a, 0x0018232b, 0x001b252d, 0x00202a33, 0x00232d37, 0x00242e37, 0x0028313a, 0x002a343d, 0x002c3540, 0x002c3741, 0x002e3842, 0x002f3641, 0x002d343f, 0x002d333e, 0x002e343f, 0x002e343d, 0x002d333c, 0x002e343d, 0x002d343d, 0x002b313b, 0x00262c36, 0x00252c35, 0x00282e38, 0x002a303a, 0x002a303a, 0x002a303c, 0x002b313c, 0x002c323d, 0x002d333f, 0x002c323e, 0x002c323d, 0x00282f38, 0x00282d37, 0x00282c36, 0x00282d37, 0x00292e38, 0x00292e38, 0x002a2f38, 0x00293039, 0x002a303a, 0x002c303a, 0x002b303a, 0x002b2f39, 0x002c2f39, 0x002b2f39, 0x002a2f39, 0x00293039, 0x00293039, 0x00293039, 0x00282f39, 0x0029303c, 0x002c323d, 0x002c333e, 0x002b333d, 0x002b333d, 0x002b333d, 0x002a323d, 0x002b333d, 0x002b333d, 0x002a323d, 0x002a333c, 0x002b333c, 0x002b313c, 0x002a303a, 0x002a303a, 0x002c323d, 0x002c333e, 0x002d333e, 0x002e343f, 0x002d343f, 0x002d333e, 0x002c323e, 0x002c323d, 0x002c323e, 0x002d333f, 0x002d333f, 0x002d3441, 0x002f3442, 0x00303543, 0x00303644, 0x00303643, 0x00303641, 0x00303540, 0x00303440, 0x00303440, 0x00303440, 0x00323642, 0x00323741, 0x00323742, 0x00333844, 0x00323844, 0x002f3842, 0x002e3641, 0x00303742, 0x00323844, 0x00323844, 0x00313843, 0x00313843, 0x00303742, 0x00303641, 0x002f3440, 0x002c303b, 0x002b303a, 0x002c303a, 0x002d313c, 0x002d333c, 0x002e343d, 0x002e343e, 0x002e343e, 0x002e343e, 0x002d343d, 0x002d343d, 0x002e343e, 0x002e343e, 0x002e343e, 0x002e343e, 0x002d343d, 0x002d343d, 0x002c333c, 0x002c323b, 0x00282f38, 0x00262e38, 0x00262e38, 0x00242c35, 0x00232c34, 0x00252c37, 0x00272c38, 0x00272d38, 0x00282e3a, 0x002b3240, 0x002c3442, 0x002b3441, 0x002c3542, 0x002d3743, 0x002f3744, 0x002f3743, 0x002e3641, 0x002a333d, 0x002a323c, 0x0029313c, 0x0029313c, 0x0028303c, 0x0029313c, 0x002c343e, 0x002d3540, 0x002d3540, 0x002c343f, 0x002c3540, 0x002c3640, 0x002a343f, 0x00242f39, 0x00212c35, 0x00202a33, 0x001c252d, 0x001a202a, 0x00192028, 0x001c232c, 0x001c252c, 0x001d262d, 0x0019232b, 0x0019242d, 0x001c2833, 0x0023313b, 0x00283740, 0x001e2b34, 0x00192531, 0x00182631, 0x00202f3a, 0x0023323d, 0x001e2c38, 0x001b2830, 0x0019262c, 0x0019262c, 0x0019242a, 0x00182329, 0x00182329, 0x00192128, 0x00161f26, 0x00141c24, 0x00141d26, 0x00182029, 0x0018212a, 0x0018212b, 0x0018222c, 0x0018232d, 0x0018242f, 0x0019252e, 0x0018242c, 0x00152129, 0x0017232b, 0x0018232c, 0x0019242d, 0x0019232c, 0x00172029, 0x00121c25, 0x00101923, 0x000f1924, 0x00121c26, 0x00141e28, 0x00131f29, 0x0013202a, 0x0014212b, 0x0014222c, 0x0013202b, 0x00101e2a, 0x00101e29, 0x00101d28, 0x000f1c28, 0x000f1b27, 0x000f1a26, 0x000e1a26, 0x000d1b24, 0x000d1b24, 0x000d1a24, 0x000d1924, 0x000e1924, 0x000e1a24, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101b24, 0x00101b24, 0x00101a23, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000d171f, 0x000d161d, 0x000d161d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1822, 0x000c1822, 0x000c1823, 0x000c1825, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1724, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1821, 0x000b1822, 0x000b1822, 0x000d1924, 0x000d1924, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00111f2b, 0x00111f2b, 0x00121f2c, 0x0014212f, 0x001b2837, 0x0020303f, 0x00243644, 0x00243845, 0x00243644, 0x0022313e, 0x001e2c39, 0x001d2b38, 0x001c2a36, 0x001b2732, 0x0016222c, 0x0016212c, 0x0018242d, 0x00192530, 0x001c2632, 0x001c2630, 0x001b242f, 0x0019232d, 0x001a242e, 0x001a242c, 0x0019242a, 0x0019242a, 0x001a242b, 0x0019242a, 0x00172229, 0x00162228, 0x0017232a, 0x001a242c, 0x001f2831, 0x00222c37, 0x00253039, 0x0028333c, 0x002a343e, 0x002b3540, 0x002b3540, 0x002c3540, 0x002c3440, 0x002c343e, 0x002c323e, 0x002d343f, 0x002d343d, 0x002c333c, 0x002d343c, 0x002d343c, 0x002a313b, 0x00272d37, 0x00262c36, 0x00282e38, 0x002b313b, 0x002b313b, 0x002a303b, 0x002a303b, 0x002c323c, 0x002c333c, 0x002c323c, 0x002b313b, 0x00282e38, 0x00262c36, 0x00252c35, 0x00262c36, 0x00283039, 0x002a303a, 0x002a303a, 0x0029303a, 0x002a303a, 0x002c303a, 0x002b2f3a, 0x002b2e39, 0x002c2f39, 0x002c303a, 0x002c303b, 0x002c313c, 0x002b313b, 0x00293039, 0x00282e39, 0x002a2f3b, 0x002c313d, 0x002c313d, 0x002c313c, 0x002b313c, 0x0029303c, 0x0028303c, 0x002b323d, 0x002c343f, 0x002d3440, 0x002c343e, 0x002c333c, 0x002c313b, 0x002b303a, 0x002c303a, 0x002c303c, 0x002d323e, 0x002e333e, 0x002e343f, 0x002d333e, 0x002d343f, 0x002d333e, 0x002c333e, 0x002d333e, 0x002e343f, 0x002d333e, 0x002d343f, 0x002f3540, 0x00303542, 0x00303643, 0x00303643, 0x00303742, 0x00303541, 0x00313541, 0x00303440, 0x002e333e, 0x002c303c, 0x002c303c, 0x002c303c, 0x002c323d, 0x002c323d, 0x002b313c, 0x002a313d, 0x002d343f, 0x00313843, 0x00323844, 0x00323844, 0x00313843, 0x00313843, 0x00313843, 0x00323742, 0x002f343e, 0x002d323c, 0x002f333c, 0x0030343e, 0x0030343e, 0x002e343d, 0x002c313b, 0x00292f38, 0x00293038, 0x00293039, 0x00283038, 0x00282f38, 0x00262c36, 0x00242b34, 0x00232933, 0x00222832, 0x00232932, 0x00232933, 0x00252c34, 0x00252c35, 0x00242c35, 0x00232c35, 0x00222b34, 0x00242d36, 0x00282e3a, 0x00292e39, 0x00292f3a, 0x00282e3a, 0x00282f3d, 0x00272f3d, 0x0028303d, 0x0028323e, 0x002c3441, 0x002e3744, 0x002e3643, 0x002d3540, 0x002c343f, 0x002b333d, 0x002a323d, 0x0028303c, 0x0028303b, 0x0028303b, 0x002b333d, 0x002d3540, 0x002d3540, 0x002c343f, 0x002b3540, 0x002b3540, 0x002c3540, 0x002b3440, 0x0028313c, 0x00252f39, 0x00202834, 0x001c242f, 0x0019212c, 0x0018202b, 0x00172129, 0x001b242c, 0x001c262f, 0x001a242f, 0x001c2831, 0x0023303a, 0x002c3a44, 0x001d2a34, 0x00182530, 0x001a2834, 0x0023323d, 0x0021303c, 0x001f2c38, 0x001b2830, 0x0018252c, 0x0018242b, 0x0019242a, 0x00182228, 0x00182128, 0x0019222a, 0x00182129, 0x00182028, 0x00182029, 0x0018212c, 0x001a222d, 0x001b242e, 0x001c2530, 0x001c2630, 0x001c2630, 0x001b262f, 0x001a252e, 0x0018232c, 0x00152129, 0x00141f28, 0x00151f27, 0x00161e27, 0x00151d27, 0x00141c25, 0x00111924, 0x00101a24, 0x00131c28, 0x00151f2a, 0x0014202a, 0x0014202a, 0x0014202b, 0x0014212b, 0x0014202c, 0x0013202c, 0x0012202c, 0x0012202c, 0x00111f2a, 0x000f1c27, 0x000d1925, 0x000d1925, 0x000d1b24, 0x000d1b24, 0x000d1a24, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x00101a24, 0x00101a24, 0x00101b24, 0x00101b24, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101a23, 0x000f1922, 0x000f1921, 0x000e1820, 0x000e1820, 0x000e1820, 0x000e1820, 0x000e1720, 0x000e1720, 0x000e1720, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1822, 0x000c1822, 0x000c1823, 0x000c1825, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1724, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1822, 0x000b1822, 0x000b1822, 0x000d1924, 0x000d1924, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00111f2b, 0x00111f2b, 0x00121f2c, 0x0014202e, 0x00182634, 0x001c2c3b, 0x001e303f, 0x00203441, 0x00243544, 0x00253442, 0x0023313f, 0x0022303d, 0x001f2c39, 0x001c2833, 0x0017222c, 0x0016212c, 0x0018242d, 0x001a2530, 0x001c2732, 0x001d2732, 0x001b2530, 0x0019232d, 0x001a242e, 0x001a242c, 0x0019242a, 0x001a242b, 0x001a242b, 0x001a242c, 0x0018242d, 0x0017232b, 0x0018242c, 0x001b252f, 0x001f2934, 0x00222c37, 0x0026303a, 0x0028323c, 0x0029343d, 0x002b343f, 0x002b343f, 0x002c3540, 0x002d3540, 0x002c343f, 0x002a313c, 0x002c323d, 0x002c323c, 0x002a303a, 0x002b313b, 0x002c323c, 0x0029313b, 0x00293039, 0x00293039, 0x002a303a, 0x002c323c, 0x002c333c, 0x002d343d, 0x002d343d, 0x002e343e, 0x002f353f, 0x002f353f, 0x002c333c, 0x002b313b, 0x002b313a, 0x002c323b, 0x002b313b, 0x002a303a, 0x002a303a, 0x002a303a, 0x00293039, 0x0029303a, 0x002c303a, 0x002b2f3a, 0x002b2e39, 0x002c2f39, 0x002c2f39, 0x002c303a, 0x002c323c, 0x002b313b, 0x00293039, 0x00282f39, 0x002b303b, 0x002c313c, 0x002d323d, 0x002d323d, 0x002c313d, 0x002a303c, 0x002a303c, 0x002c323e, 0x002e3440, 0x002f3440, 0x002d343e, 0x002c323c, 0x002c313c, 0x002c303a, 0x002b2f39, 0x002c303c, 0x002d313d, 0x002e333e, 0x002e333e, 0x002c333e, 0x002d343f, 0x002e343f, 0x002e3440, 0x002e343f, 0x002d333e, 0x002c333e, 0x002c323e, 0x002e3440, 0x002f3542, 0x002f3543, 0x00303542, 0x00303641, 0x00303541, 0x00313541, 0x00303540, 0x002e333f, 0x002c303c, 0x002c303c, 0x002c303c, 0x002c303c, 0x002b313c, 0x002b313c, 0x002c323d, 0x002d343f, 0x00303541, 0x00303641, 0x002d343f, 0x002c323d, 0x002c323d, 0x002c323d, 0x002c313d, 0x002c303b, 0x00292d38, 0x00282c36, 0x00282a34, 0x00262933, 0x00242933, 0x00242933, 0x00242832, 0x00232831, 0x00232831, 0x00202730, 0x00202730, 0x00212831, 0x00212831, 0x00202730, 0x00202630, 0x001f252f, 0x001f252f, 0x00202830, 0x00222832, 0x00202832, 0x00202932, 0x00212933, 0x00252d37, 0x00292f3b, 0x002a2f3b, 0x002b303c, 0x00292f3c, 0x00282f3c, 0x00282e3c, 0x0028303c, 0x0029313c, 0x002a333e, 0x002c3440, 0x002d3540, 0x002d3540, 0x002c343f, 0x002c343e, 0x002b323d, 0x0029303c, 0x00282f3a, 0x0028303b, 0x002a323d, 0x002d3440, 0x002c343f, 0x002a333d, 0x002a343e, 0x002b3540, 0x002c3542, 0x002c3643, 0x002b3641, 0x002a343f, 0x0027303b, 0x00222a35, 0x001d2631, 0x001c242f, 0x0018222c, 0x0018232c, 0x001d2830, 0x001e2832, 0x001c2832, 0x0024313b, 0x002d3c45, 0x001e2b35, 0x00162430, 0x001b2934, 0x0024333f, 0x0024313c, 0x0023303c, 0x001e2b34, 0x0018242c, 0x0018242b, 0x001a242b, 0x00182228, 0x00172028, 0x0018212a, 0x0018202a, 0x0019222b, 0x001b232d, 0x001c2430, 0x001c2430, 0x001c2430, 0x001c2630, 0x001c2630, 0x001c2630, 0x001c262f, 0x001b252e, 0x0018212a, 0x00142028, 0x00141e26, 0x00141c25, 0x00111923, 0x00101821, 0x00101821, 0x00101822, 0x00101824, 0x00121a25, 0x00141c27, 0x00141e28, 0x00141f29, 0x0014202a, 0x0014212b, 0x0014212c, 0x0014212c, 0x0014212c, 0x0014212c, 0x0013202c, 0x00101c28, 0x000d1925, 0x000d1924, 0x000d1b24, 0x000d1b24, 0x000d1a24, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x00101a24, 0x00101a24, 0x00101b24, 0x00101b24, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101a23, 0x000f1922, 0x000f1821, 0x000e1820, 0x000e1820, 0x000e1820, 0x000e1820, 0x000e1720, 0x000e1720, 0x000e1720, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1825, 0x000c1825, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1824, 0x000c1823, 0x000c1823, 0x000c1824, 0x000c1824, 0x000b1824, 0x000b1824, 0x000b1824, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000d1b26, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e2a, 0x00101e2a, 0x00121f2b, 0x0014202c, 0x00142430, 0x00172835, 0x00182b38, 0x001c2e3c, 0x00213240, 0x00243442, 0x00243440, 0x0023313f, 0x001f2c38, 0x001b2832, 0x0018222c, 0x0018202c, 0x0019232d, 0x001b2430, 0x001c2531, 0x001d2731, 0x001b2530, 0x001a242f, 0x001a242e, 0x0019242c, 0x0018232b, 0x001a242b, 0x001a242b, 0x001a242c, 0x0019242e, 0x0019242c, 0x001a242d, 0x001c2530, 0x00202a34, 0x00242e38, 0x0028323b, 0x0029333c, 0x0029333c, 0x002b343f, 0x002c3540, 0x002d3540, 0x002d3540, 0x002c343e, 0x002a303c, 0x002b313c, 0x002a313b, 0x00283039, 0x0029303a, 0x002c333c, 0x002a333c, 0x002b323c, 0x002b323c, 0x002c333d, 0x002f343f, 0x002f3540, 0x002f353f, 0x002e343e, 0x002e343e, 0x002f353f, 0x00303640, 0x002f3540, 0x002f353f, 0x002f353f, 0x00303640, 0x002f353e, 0x002b313b, 0x0029303a, 0x002b313b, 0x002c323c, 0x002c323c, 0x002d323c, 0x002d313c, 0x002d303b, 0x002d303b, 0x002c303a, 0x002c303b, 0x002c323c, 0x002c323d, 0x002b313c, 0x002c313c, 0x002d313c, 0x002d323c, 0x002e333d, 0x002f343e, 0x002d343d, 0x002c333e, 0x002c333e, 0x002d333f, 0x002e3440, 0x002e3440, 0x002d333e, 0x002c323d, 0x002c303d, 0x002c303c, 0x002c303c, 0x002c303c, 0x002c303c, 0x002d323d, 0x002d323d, 0x002d323d, 0x002d333e, 0x002e343f, 0x002f3440, 0x002f3440, 0x002e343f, 0x002d343f, 0x002e343e, 0x002f343f, 0x00303540, 0x00303540, 0x00303541, 0x00303641, 0x00303541, 0x00313541, 0x00313541, 0x00303440, 0x002d323d, 0x002c303c, 0x002b303c, 0x002c303c, 0x002c313c, 0x002c323d, 0x002c333e, 0x002e3440, 0x002f3440, 0x002f3440, 0x002e3440, 0x002b313c, 0x00282e39, 0x00272d38, 0x00282d38, 0x00282d37, 0x00282c37, 0x00282c36, 0x00272b35, 0x00262a34, 0x00252a34, 0x00262a34, 0x00242934, 0x00242833, 0x00252934, 0x00252934, 0x00252a34, 0x00252b35, 0x00252c35, 0x00252c35, 0x00242b34, 0x00242a34, 0x00242a33, 0x00232933, 0x00222832, 0x00212832, 0x00232a34, 0x00242c36, 0x00252c37, 0x00282d38, 0x00282e39, 0x00282d39, 0x00272d39, 0x00272d39, 0x00282d3a, 0x00262e38, 0x00262e38, 0x00272f38, 0x0028303b, 0x0029323c, 0x002a323d, 0x002a323d, 0x002c343f, 0x002c343e, 0x002a313c, 0x00282f3a, 0x00282f3b, 0x002a313c, 0x002c343f, 0x002d343f, 0x002a343e, 0x0028313c, 0x0029343f, 0x002b3641, 0x002c3643, 0x002b3743, 0x00293641, 0x002c3743, 0x0028323f, 0x00222c38, 0x001d2833, 0x0019242e, 0x0018222c, 0x001c272f, 0x00212c35, 0x00202c37, 0x0024333d, 0x00293842, 0x001c2a35, 0x00162431, 0x001a2935, 0x0020303b, 0x001f2f39, 0x0020303a, 0x001f2c35, 0x0019262d, 0x0019242c, 0x001a242c, 0x0019242b, 0x0019242c, 0x001a232c, 0x0018222b, 0x0018232c, 0x0019242e, 0x001b2530, 0x001c2530, 0x001c2530, 0x001c2630, 0x001c2731, 0x001c2731, 0x001c2630, 0x001b252d, 0x0018212a, 0x00152028, 0x00141f27, 0x00141d27, 0x00131c25, 0x00121a24, 0x00121a24, 0x00111924, 0x00101823, 0x00101823, 0x00111a25, 0x00141d28, 0x0015202a, 0x0015212c, 0x0015212c, 0x0014212c, 0x0014212c, 0x0014212c, 0x0014222c, 0x0014212b, 0x00101d28, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1824, 0x000f1824, 0x000f1824, 0x000d1824, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000f1a24, 0x000f1a24, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x000f1a24, 0x000f1a24, 0x00101a24, 0x00101a24, 0x00101a23, 0x00101a23, 0x00101922, 0x000f1921, 0x000f1821, 0x000f1821, 0x000e1820, 0x000d1820, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000c1924, 0x000b1925, 0x000b1a25, 0x000b1a27, 0x000b1927, 0x000b1926, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000b1824, 0x000b1824, 0x000c1925, 0x000d1a26, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101d28, 0x00101d28, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00111f2a, 0x0012202c, 0x0012222d, 0x00142430, 0x00142734, 0x00182b38, 0x001f303e, 0x00203240, 0x0021323f, 0x0021313e, 0x001c2c38, 0x00182631, 0x0018212c, 0x0018202b, 0x0018212c, 0x001a222c, 0x001c242e, 0x001c2630, 0x001b2631, 0x001a2630, 0x0019242f, 0x0018232c, 0x0018222b, 0x001a242b, 0x001a242b, 0x001a242c, 0x0019232c, 0x0019242c, 0x001a242e, 0x001b2530, 0x001f2934, 0x00242f38, 0x0028333c, 0x002b343f, 0x002b3540, 0x002c3540, 0x002d3640, 0x002d3640, 0x002d353e, 0x002c333c, 0x002a303a, 0x002b313b, 0x0029303c, 0x0028303a, 0x0029323b, 0x002c343d, 0x002c343f, 0x002c343f, 0x002c343f, 0x002e3540, 0x00303741, 0x00303640, 0x002d343d, 0x002b313b, 0x002a303a, 0x002b313b, 0x002c323c, 0x002c333c, 0x002c333c, 0x002c333c, 0x002c333c, 0x002c323c, 0x002a303b, 0x0029303a, 0x002c323c, 0x00303640, 0x002f353f, 0x002f353f, 0x002f343e, 0x0030333d, 0x002e313c, 0x002c303c, 0x002c313c, 0x002c333e, 0x002c333e, 0x002c323d, 0x002c323c, 0x002d323c, 0x002d323c, 0x002d323c, 0x002f343d, 0x002f343e, 0x002e343f, 0x002c333e, 0x002d333f, 0x002e343f, 0x002e343f, 0x002d333f, 0x002c313e, 0x002c303e, 0x002c303e, 0x002c303e, 0x002c303d, 0x002c303c, 0x002c303c, 0x002c303b, 0x002c313b, 0x002d323d, 0x002e333f, 0x002e343f, 0x002e343f, 0x002f343f, 0x002f343f, 0x002f343c, 0x002f343c, 0x0030343c, 0x0030353d, 0x00303540, 0x00303641, 0x00303541, 0x00313541, 0x00313541, 0x00303440, 0x002d343d, 0x002c323c, 0x002c323d, 0x002c323e, 0x002c323d, 0x002c323d, 0x002c323e, 0x002e3440, 0x002f3440, 0x002f3440, 0x002e3440, 0x002c323e, 0x002c323d, 0x002b313c, 0x002b313c, 0x002b313c, 0x002c303a, 0x00292e38, 0x00282c36, 0x00282c36, 0x00282c36, 0x00282c37, 0x00282c36, 0x00282c36, 0x00272c35, 0x00272b35, 0x00272b35, 0x00272c35, 0x00262c36, 0x00262c36, 0x00282d37, 0x00282e38, 0x00282f38, 0x00272d38, 0x00242b36, 0x00242a35, 0x00262c38, 0x00282d39, 0x00282d39, 0x00282c38, 0x00272c38, 0x00242b36, 0x00242935, 0x00232934, 0x00222934, 0x00232b34, 0x00232b34, 0x00232c34, 0x00242c36, 0x00242d38, 0x00252e38, 0x00272f3a, 0x002c343f, 0x002c343f, 0x002a323c, 0x0028303b, 0x00272f3a, 0x0029313c, 0x002c343f, 0x002c3440, 0x002b343f, 0x0028313c, 0x0028333d, 0x002a3640, 0x002c3744, 0x002c3844, 0x00283641, 0x002b3844, 0x002c3745, 0x0027313e, 0x00202b36, 0x001b2730, 0x0018242d, 0x001a262c, 0x00222d35, 0x00233039, 0x0027343d, 0x0027343e, 0x001a2833, 0x00162530, 0x0020303b, 0x001d2e38, 0x001c2c36, 0x001d2d37, 0x00202e37, 0x001c2830, 0x0018242c, 0x0018222b, 0x0019242c, 0x001b252e, 0x001b272f, 0x001b262e, 0x0018242c, 0x0018242e, 0x001a2530, 0x001b2530, 0x001a2530, 0x001a2530, 0x001c2832, 0x001d2832, 0x001c2730, 0x001a2530, 0x0018232c, 0x0016212b, 0x0017212b, 0x0018222c, 0x0018212c, 0x0017212c, 0x0015202a, 0x00141d28, 0x00131c28, 0x00121c26, 0x00111c26, 0x00141f29, 0x0017212c, 0x0017232c, 0x0017232c, 0x0015232e, 0x0014222d, 0x0014222d, 0x0014232c, 0x0014242d, 0x0012202a, 0x000f1c24, 0x000c1a23, 0x000c1823, 0x000c1822, 0x000e1823, 0x000f1824, 0x000f1824, 0x000e1824, 0x000d1924, 0x000c1823, 0x000c1822, 0x000c1823, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000f1a24, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000f1922, 0x000f1921, 0x000e1821, 0x000e1820, 0x000e1820, 0x000d1720, 0x000d1720, 0x000c1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00111f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000c1924, 0x000b1a25, 0x000b1a25, 0x000b1a27, 0x000b1a27, 0x000b1926, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1924, 0x000b1824, 0x000c1925, 0x000d1a26, 0x000d1b26, 0x000e1b27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101e29, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101f2a, 0x0010202b, 0x0010212c, 0x00122430, 0x00162834, 0x001b2c3b, 0x001d303c, 0x001d303d, 0x001e303c, 0x001b2c37, 0x00172530, 0x0017202a, 0x00171f28, 0x00182029, 0x0018212a, 0x001a222c, 0x001b252f, 0x001b2731, 0x001c2731, 0x0019252f, 0x0018232c, 0x0018222b, 0x0019242b, 0x001a242b, 0x0019242b, 0x0019232b, 0x001a242d, 0x001c2630, 0x001e2833, 0x00202b37, 0x0025303b, 0x002a343e, 0x002d3741, 0x002d3842, 0x002d3842, 0x002e3641, 0x002d363e, 0x002d353c, 0x002d343c, 0x002c323a, 0x002a313b, 0x0029303c, 0x0028303b, 0x002b333c, 0x002c353f, 0x002c3440, 0x002c3440, 0x002c343f, 0x002d3440, 0x002e343f, 0x002c323c, 0x00282f38, 0x00252c36, 0x00242a34, 0x00242a34, 0x00242b34, 0x00252c36, 0x00252c36, 0x00252c36, 0x00252c36, 0x00252c36, 0x00262c36, 0x00272d37, 0x00293039, 0x002c333c, 0x002e343d, 0x002f3440, 0x00303540, 0x00303540, 0x00303440, 0x002e343f, 0x002d333f, 0x002d3440, 0x002d343f, 0x002c333e, 0x002d333e, 0x002d323d, 0x002e333d, 0x002f343f, 0x00303440, 0x0030343f, 0x002f3440, 0x002c333e, 0x002d333f, 0x002e343f, 0x002e343f, 0x002e333f, 0x002d313e, 0x002d313f, 0x002d313f, 0x002e3240, 0x002e323e, 0x002c303c, 0x002c303b, 0x002c303a, 0x002c303a, 0x002c303c, 0x002d323e, 0x002d333e, 0x002f343f, 0x002f343f, 0x002f343f, 0x002f343c, 0x002f343c, 0x0030343c, 0x0030353d, 0x00303540, 0x00303641, 0x00303541, 0x00313541, 0x00313541, 0x00313541, 0x002f353f, 0x002e343e, 0x002d343f, 0x002d343f, 0x002d343f, 0x002c333e, 0x002c323d, 0x002e343f, 0x002e3440, 0x002e343f, 0x002d333f, 0x002c323e, 0x002c333e, 0x002e343f, 0x002e343f, 0x002c333d, 0x002c313c, 0x002a2e39, 0x00282d38, 0x00292e38, 0x002a2f38, 0x002a2f39, 0x00292e38, 0x00282d37, 0x00282c36, 0x00272c35, 0x00272c35, 0x00272c36, 0x00262c36, 0x00272d37, 0x00282e38, 0x002a2f39, 0x002b303a, 0x00292e38, 0x00262c38, 0x00262c38, 0x00272d38, 0x00282e39, 0x00282e3a, 0x00282d3a, 0x00262d38, 0x00252c37, 0x00242a35, 0x00252c36, 0x00242c35, 0x00242c35, 0x00242c34, 0x00232c35, 0x00232b36, 0x00232b36, 0x00242c37, 0x00262f39, 0x002b333e, 0x002c343f, 0x002b333d, 0x0028303b, 0x0028303b, 0x0029313c, 0x002b333e, 0x002c343f, 0x002c3540, 0x002b3540, 0x002b3540, 0x002c3742, 0x002e3844, 0x002f3945, 0x002c3844, 0x00293643, 0x00293644, 0x00283441, 0x0024303b, 0x001e2a34, 0x001c2830, 0x001b262d, 0x00212c34, 0x00243039, 0x0028343d, 0x0024303a, 0x00192630, 0x00182832, 0x001d2f3a, 0x001b2d37, 0x001a2c34, 0x001b2c34, 0x001d2c34, 0x001a272f, 0x0017232b, 0x0017212a, 0x00152029, 0x0016212a, 0x0018242d, 0x001a262f, 0x001a262f, 0x001a2630, 0x00192530, 0x00192530, 0x00192530, 0x00192530, 0x001c2832, 0x001e2833, 0x001c2731, 0x001b2731, 0x001b2731, 0x001b2630, 0x001c2832, 0x001d2934, 0x001d2934, 0x001c2834, 0x001b2631, 0x00192530, 0x00182530, 0x00182430, 0x00172430, 0x00192631, 0x001a2833, 0x001a2833, 0x001a2833, 0x00192732, 0x00172530, 0x00172430, 0x00172630, 0x00172830, 0x0015252e, 0x00101e28, 0x000c1a24, 0x000c1823, 0x000c1822, 0x000d1823, 0x000f1824, 0x000f1824, 0x000e1824, 0x000d1924, 0x000c1823, 0x000c1822, 0x000c1823, 0x000d1924, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000f1922, 0x000f1921, 0x000e1820, 0x000e1820, 0x000e1820, 0x000d1720, 0x000d1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00111f27, 0x00101f27, 0x00112229, 0x00102229, 0x000f2229, 0x000f2229, 0x000f2229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x000f2229, 0x000f2229, 0x000f2229, 0x00102229, 0x00112229, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1a25, 0x000e1a25, 0x000e1a25, 0x000d1a26, 0x000c1a26, 0x000c1b26, 0x000c1b27, 0x000c1b28, 0x000c1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1a26, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x000e1e29, 0x000f1f2a, 0x0010202d, 0x00132430, 0x00172834, 0x001b2c38, 0x001c303b, 0x001d2f3a, 0x001b2c36, 0x0017242f, 0x00182029, 0x00182029, 0x00182029, 0x0018212a, 0x001a222c, 0x001a242f, 0x001b2731, 0x001c2832, 0x001a2630, 0x0018242e, 0x0018242d, 0x0018242c, 0x0019232c, 0x0019242c, 0x001b242d, 0x001c2630, 0x001d2731, 0x001e2834, 0x00212b38, 0x0025303b, 0x002a343f, 0x002d3943, 0x002f3944, 0x002f3844, 0x002f3742, 0x002d3640, 0x002d353f, 0x002f363f, 0x002e343e, 0x002c343e, 0x002b333e, 0x0029323c, 0x002c343e, 0x002c3540, 0x002c3640, 0x002d3641, 0x002c343f, 0x002a323d, 0x0029303b, 0x00272e37, 0x00242b34, 0x00242a34, 0x00242a35, 0x00242b36, 0x00252c36, 0x00252c35, 0x00252c35, 0x00252c35, 0x00252c35, 0x00252c36, 0x00252c37, 0x00262c38, 0x00282d38, 0x002a303c, 0x002c333d, 0x002e3440, 0x00303642, 0x00323844, 0x00313843, 0x00303742, 0x002f3641, 0x002e3641, 0x002e3641, 0x002d3540, 0x002f3440, 0x002f3440, 0x002f343f, 0x00303440, 0x00303440, 0x00303440, 0x00303440, 0x002f3440, 0x002e333f, 0x002f343f, 0x002f343f, 0x002f333f, 0x002f333f, 0x00303440, 0x00303440, 0x00303440, 0x002f3440, 0x002e333f, 0x002c303c, 0x002c303b, 0x002c303a, 0x002c303c, 0x002d303d, 0x002d323e, 0x002e333e, 0x002f343f, 0x002f343f, 0x002f343c, 0x002f343c, 0x0030343c, 0x0031363e, 0x00323740, 0x00313743, 0x00313743, 0x00323642, 0x00313541, 0x00313541, 0x00303640, 0x00303640, 0x002f3540, 0x002f3440, 0x002f3440, 0x002e343f, 0x002d343f, 0x002e343f, 0x002d333e, 0x002c323d, 0x002c333e, 0x002c323d, 0x002c333e, 0x002d343f, 0x002d333f, 0x002c323d, 0x002b303c, 0x00292e3a, 0x00292e39, 0x00292e38, 0x002a2f39, 0x002b303a, 0x002a2f39, 0x00292e38, 0x00282e38, 0x00282d37, 0x00282d37, 0x00292e38, 0x00292e38, 0x002a2f39, 0x002c313c, 0x002e333c, 0x002d323c, 0x002c303b, 0x00292f3a, 0x0029303b, 0x002a303c, 0x002a303c, 0x002a303c, 0x0029303c, 0x00282f3c, 0x00272d38, 0x00262c37, 0x00272d37, 0x00282f38, 0x00262d36, 0x00262c36, 0x00252c36, 0x00242b36, 0x00232934, 0x00232a35, 0x00272f39, 0x002c343e, 0x002c3440, 0x002c343f, 0x0028303c, 0x0028303b, 0x002a323c, 0x002c343f, 0x002d3540, 0x002c3641, 0x002c3741, 0x002c3540, 0x002c3641, 0x002f3844, 0x002f3945, 0x002e3945, 0x002c3845, 0x00283544, 0x00283441, 0x0024303c, 0x00212d37, 0x00202c35, 0x001d2930, 0x00202c33, 0x00243038, 0x0025313b, 0x00232e39, 0x001b2833, 0x001a2935, 0x001a2b36, 0x001c2d36, 0x001b2c35, 0x001a2b34, 0x001b2932, 0x0018242c, 0x00162129, 0x0016222a, 0x0017212a, 0x0016212a, 0x00152129, 0x0018242c, 0x0019252e, 0x001b2630, 0x001c2731, 0x001c2831, 0x001c2832, 0x001c2731, 0x001c2832, 0x001c2832, 0x001d2934, 0x001e2a36, 0x00202c38, 0x00202c38, 0x00202c38, 0x00202c3a, 0x00202d3b, 0x00202c3a, 0x001e2b38, 0x001e2b38, 0x001f2c3b, 0x001e2d3b, 0x001f2d3b, 0x001f2d3b, 0x001f2d3b, 0x001e2c39, 0x001c2a38, 0x001a2836, 0x00192834, 0x00182834, 0x00182832, 0x00192a33, 0x00162830, 0x00102029, 0x000c1a24, 0x000c1821, 0x000c1821, 0x000d1822, 0x000e1822, 0x000e1822, 0x000d1823, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101a23, 0x00101a23, 0x000f1922, 0x000f1921, 0x000e1820, 0x000d1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x000f2229, 0x000f2229, 0x00102229, 0x00102229, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0012242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x00102229, 0x00102229, 0x000f2229, 0x00102229, 0x00112229, 0x00111f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1a26, 0x000e1a26, 0x000e1a26, 0x000d1a26, 0x000c1b26, 0x000c1b26, 0x000c1b28, 0x000c1b28, 0x000c1a27, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000e1c27, 0x000d1b26, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101d28, 0x000e1c28, 0x000e1d28, 0x0010202b, 0x0012212f, 0x00142532, 0x00182a36, 0x001c2f38, 0x001c2f39, 0x001c2c38, 0x00182530, 0x0018212a, 0x0018212a, 0x0018202a, 0x0018212a, 0x001a232c, 0x001a242f, 0x001c2731, 0x001d2933, 0x001a2630, 0x0018242f, 0x0018242f, 0x0019242e, 0x001a242d, 0x001a242d, 0x001b252f, 0x001b252f, 0x001b2530, 0x001d2734, 0x00212c38, 0x0026303c, 0x002a3640, 0x002e3a44, 0x002f3b45, 0x00303945, 0x00303844, 0x002e3640, 0x002e3740, 0x002f3841, 0x002f3740, 0x002e3740, 0x002e3742, 0x002c3640, 0x002c3640, 0x002c3540, 0x002c3540, 0x002c3540, 0x0029313c, 0x00262e38, 0x00242c37, 0x00232b34, 0x00232a34, 0x00242b36, 0x00282d38, 0x00282e39, 0x00282f39, 0x00293039, 0x00293039, 0x00293039, 0x00293039, 0x00293039, 0x00282e39, 0x00282e39, 0x00282f3a, 0x002a303c, 0x002d333e, 0x002f3540, 0x00323844, 0x00343945, 0x00343945, 0x00323944, 0x00303844, 0x00303844, 0x00303844, 0x00303843, 0x00303642, 0x00303441, 0x00303440, 0x00303440, 0x00303441, 0x00313541, 0x00313541, 0x00313541, 0x00303440, 0x002f343f, 0x002f343f, 0x0030333f, 0x00303340, 0x00313441, 0x00313541, 0x00303541, 0x00303440, 0x00303440, 0x002f343f, 0x002e333c, 0x002e333c, 0x002e333e, 0x002e333e, 0x002e333e, 0x002e333f, 0x002f3440, 0x00303440, 0x0030343e, 0x0030343c, 0x0030343d, 0x0032373f, 0x00333841, 0x00323844, 0x00323844, 0x00343844, 0x00323642, 0x00323642, 0x00313741, 0x00313841, 0x00303742, 0x00303642, 0x00303541, 0x002f3440, 0x002f3440, 0x002f3440, 0x002e343f, 0x002e343f, 0x002e3440, 0x002f3440, 0x00303540, 0x002e3440, 0x002c333e, 0x002b313d, 0x002c303c, 0x002a2f3a, 0x00292e3a, 0x002a2f39, 0x002c303a, 0x002c313c, 0x002c313b, 0x002c303b, 0x002c303b, 0x002c303b, 0x002c303b, 0x002d323c, 0x002f333d, 0x0030343e, 0x00313640, 0x00323642, 0x00303440, 0x002e333e, 0x002c323e, 0x002c323e, 0x002b313c, 0x002b303c, 0x002b303c, 0x002a303c, 0x002a303c, 0x00282e38, 0x00262c36, 0x00262c36, 0x00282d37, 0x00282d37, 0x00282d37, 0x00262c36, 0x00242b36, 0x00232834, 0x00242a35, 0x00272f3a, 0x002b333e, 0x002c3540, 0x002d3540, 0x002b343f, 0x002a343e, 0x002c343f, 0x002c343e, 0x002d3540, 0x002d3641, 0x002c3742, 0x002c3540, 0x002c3641, 0x002f3844, 0x002f3945, 0x002e3945, 0x002d3845, 0x00283543, 0x0025323f, 0x0023303b, 0x00232f38, 0x00243038, 0x0025323a, 0x00233038, 0x00243039, 0x00232f38, 0x00202d38, 0x001f2c38, 0x001d2c39, 0x00172833, 0x001b2c36, 0x001b2c35, 0x00192b34, 0x0018262f, 0x00162028, 0x00131c24, 0x00141c25, 0x00182029, 0x0019232c, 0x0018232c, 0x0018242c, 0x001a242d, 0x001c2630, 0x001c2731, 0x001d2832, 0x001f2b34, 0x00202c36, 0x00202c36, 0x00202c36, 0x001d2a36, 0x001d2a36, 0x00202c38, 0x00202d3a, 0x00212f3d, 0x0022303f, 0x00233040, 0x0023303f, 0x00212f3e, 0x0022303f, 0x00243240, 0x00233241, 0x00233241, 0x00243341, 0x00243341, 0x00223140, 0x001f2e3d, 0x001c2c39, 0x001c2b38, 0x001c2c39, 0x001d2c38, 0x001c2d36, 0x00182831, 0x0011202a, 0x000d1a24, 0x000c1821, 0x000c1821, 0x000d1821, 0x000e1822, 0x000e1822, 0x000d1823, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101a23, 0x00101a23, 0x000f1922, 0x000f1921, 0x000e1820, 0x000c1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x000f2229, 0x00102229, 0x0013242c, 0x0013242c, 0x0012242c, 0x0012282e, 0x0012282e, 0x0010282e, 0x0010282e, 0x0010282e, 0x00112a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00112a30, 0x0010282e, 0x0010282e, 0x0010282e, 0x0012282e, 0x0013282e, 0x0012242c, 0x0013242c, 0x0012242c, 0x00102229, 0x000f2229, 0x00112229, 0x00111f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1b26, 0x000e1b26, 0x000e1b26, 0x000d1b25, 0x000c1b25, 0x000c1b26, 0x000c1b27, 0x000c1a27, 0x000c1a26, 0x000c1a26, 0x000c1a26, 0x000c1a26, 0x000c1a26, 0x000c1a25, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000e1b27, 0x000e1c27, 0x000e1c27, 0x000d1a26, 0x000d1a26, 0x000d1b26, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000e1c28, 0x000e1c28, 0x000f1d28, 0x000f1d28, 0x000f1d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x00101e29, 0x0012202d, 0x00142430, 0x00152732, 0x00182a34, 0x001c2d38, 0x001e2c38, 0x001b2630, 0x001a232b, 0x0018222a, 0x00182028, 0x0018212a, 0x001a242d, 0x001a2530, 0x001c2832, 0x001d2933, 0x001c2831, 0x001a2630, 0x001a2630, 0x001b262f, 0x001c262f, 0x001b252e, 0x001a252e, 0x0018232c, 0x0018232e, 0x001c2734, 0x00222c39, 0x0028333e, 0x002b3842, 0x002e3b45, 0x002f3a47, 0x00303947, 0x00303844, 0x002f3743, 0x002f3742, 0x00303842, 0x00303842, 0x002f3842, 0x002f3842, 0x002d3740, 0x002c3540, 0x002c343e, 0x002b323c, 0x002a313c, 0x00262c38, 0x00242b36, 0x00232b35, 0x00232c34, 0x00242c35, 0x00262e38, 0x00282f3b, 0x0029303c, 0x002a313c, 0x002b313c, 0x002b313c, 0x002c323c, 0x002c333c, 0x002c333d, 0x002c333e, 0x002c333e, 0x002c333d, 0x002c333d, 0x002b323e, 0x002c343e, 0x002f3641, 0x00303743, 0x00313844, 0x00323944, 0x00323a45, 0x00323a45, 0x00323945, 0x00313845, 0x00323845, 0x00343845, 0x00343845, 0x00343844, 0x00323643, 0x00313541, 0x00303440, 0x00303440, 0x00303440, 0x002f3440, 0x002f3440, 0x0030343f, 0x00303440, 0x00303440, 0x00303541, 0x00303441, 0x00303440, 0x00303541, 0x00303540, 0x00303440, 0x0030343f, 0x00303440, 0x00303440, 0x002f3440, 0x00303440, 0x00303440, 0x00303440, 0x00303440, 0x00303540, 0x00313540, 0x00323741, 0x00333842, 0x00333844, 0x00333844, 0x00343844, 0x00343844, 0x00333843, 0x00323843, 0x00323843, 0x00313844, 0x00313843, 0x00303742, 0x00313541, 0x00313541, 0x00313541, 0x00303541, 0x00313642, 0x00323743, 0x00313844, 0x00303742, 0x002f3440, 0x002c323d, 0x002c333e, 0x002d333e, 0x002d323e, 0x002d313d, 0x002d323e, 0x002e343e, 0x002f343e, 0x002f343f, 0x002f3440, 0x002f343f, 0x002f343e, 0x002d323d, 0x002f343f, 0x00313741, 0x00323842, 0x00323743, 0x00303541, 0x002d333e, 0x002c323d, 0x002a303b, 0x00282f39, 0x00252c36, 0x00242934, 0x00242a35, 0x00232934, 0x00232934, 0x00232934, 0x00242a34, 0x00232933, 0x00242934, 0x00282c37, 0x00282e38, 0x00282e37, 0x00282d38, 0x00262c38, 0x00242c36, 0x00242d38, 0x0028313c, 0x002b3540, 0x002d3741, 0x002e3641, 0x002f3742, 0x002d3540, 0x002c343e, 0x002c343f, 0x002c3540, 0x002c3741, 0x002c3640, 0x002c3641, 0x002e3844, 0x002f3944, 0x002f3944, 0x002e3844, 0x00293642, 0x0024313c, 0x00222f39, 0x00223038, 0x00233039, 0x0029363e, 0x0029373f, 0x0028353f, 0x0024313c, 0x0021303b, 0x0021303c, 0x001c2c38, 0x00152530, 0x00192932, 0x001a2b34, 0x001b2b34, 0x0017232b, 0x00141c24, 0x00141a23, 0x00121921, 0x00161d25, 0x00172028, 0x001a222b, 0x001a232c, 0x001a222c, 0x001c2430, 0x001e2530, 0x001e2730, 0x00202b34, 0x00232f38, 0x00232f38, 0x00222e38, 0x001f2c38, 0x001d2b37, 0x00202c39, 0x00212f3d, 0x00243140, 0x00253342, 0x00263443, 0x00263443, 0x00263444, 0x00273545, 0x00273848, 0x00283948, 0x00283848, 0x00273848, 0x00273847, 0x00263646, 0x00243443, 0x00213140, 0x00233340, 0x00243441, 0x00233440, 0x001e303c, 0x00172833, 0x00101f2a, 0x000c1a24, 0x000c1823, 0x000c1822, 0x000d1822, 0x000e1822, 0x000e1822, 0x000e1822, 0x000d1923, 0x000d1923, 0x000d1923, 0x000d1923, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x000f1a24, 0x000f1a24, 0x000f1922, 0x000f1921, 0x000e1820, 0x000e1820, 0x000d1720, 0x000c1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f1f27, 0x000f2229, 0x00102229, 0x0013242c, 0x0012242c, 0x0012282e, 0x0010282e, 0x00112a30, 0x00112a30, 0x00132c32, 0x00122c32, 0x00132c32, 0x00132c32, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00132c32, 0x00132c32, 0x00122c32, 0x00112a30, 0x00112a30, 0x00112a30, 0x0011282e, 0x0012282e, 0x0013242c, 0x0013242c, 0x000f2229, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1c27, 0x000e1c27, 0x000e1c27, 0x000e1c25, 0x000d1b24, 0x000d1b24, 0x000d1a26, 0x000d1a26, 0x000c1a26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000c1c28, 0x000c1c28, 0x000c1d28, 0x000c1d28, 0x000e1d28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101e29, 0x0012202c, 0x0013222f, 0x00142431, 0x00182734, 0x001d2d39, 0x0022303a, 0x001c2832, 0x001a242c, 0x00182229, 0x00182026, 0x00182129, 0x0019242e, 0x001b2630, 0x001d2933, 0x001e2a34, 0x001d2933, 0x001c2832, 0x001c2830, 0x001b272f, 0x001a252e, 0x001a242c, 0x0018232b, 0x00172329, 0x0017232a, 0x001b2731, 0x00212c38, 0x00293540, 0x002d3b46, 0x002f3c48, 0x00303b48, 0x002f3948, 0x002f3846, 0x002f3844, 0x002f3844, 0x002f3843, 0x002f3843, 0x002f3843, 0x002e3841, 0x002c3740, 0x002c343e, 0x002c323c, 0x00282e38, 0x00252c36, 0x00242b35, 0x00242a34, 0x00232a34, 0x00232b34, 0x00242d36, 0x00263038, 0x0028303b, 0x0029313c, 0x002b323d, 0x002c333e, 0x002d343f, 0x002e3440, 0x00303641, 0x00303641, 0x002e3641, 0x002e3641, 0x002d3540, 0x002c3440, 0x002c3440, 0x002c3440, 0x002d3540, 0x002d3540, 0x002d3540, 0x00303844, 0x00323a47, 0x00343c49, 0x00353d4a, 0x00363d4a, 0x00383d4b, 0x00393e49, 0x00383c48, 0x00373b47, 0x00343945, 0x00323641, 0x00313540, 0x00303441, 0x00303541, 0x00303440, 0x00303440, 0x00303440, 0x00303440, 0x00303440, 0x002f343f, 0x002f343f, 0x00303440, 0x00303742, 0x00313742, 0x00313742, 0x00323642, 0x00323642, 0x00313642, 0x00303440, 0x00313541, 0x00313541, 0x00313541, 0x00313542, 0x00323642, 0x00323642, 0x00323642, 0x00323741, 0x00333841, 0x00343843, 0x00343844, 0x00343844, 0x00343844, 0x00323843, 0x00313843, 0x00313843, 0x00313843, 0x00313843, 0x00323642, 0x00323642, 0x00323642, 0x00313541, 0x00333642, 0x00333843, 0x00313844, 0x00303744, 0x00303542, 0x002e3440, 0x002f3540, 0x00303641, 0x00313742, 0x00313743, 0x00303843, 0x00303843, 0x00303742, 0x00303742, 0x00303843, 0x00303843, 0x00303742, 0x002c333e, 0x002c333e, 0x00303642, 0x00313843, 0x00303641, 0x002d333e, 0x002b313c, 0x002b313c, 0x00293039, 0x00282f38, 0x00272d37, 0x00242c35, 0x00222934, 0x00212833, 0x00202631, 0x00202631, 0x00202731, 0x00202630, 0x001f252f, 0x00202730, 0x00242a34, 0x00262d37, 0x00293039, 0x0029323c, 0x0026303b, 0x00242f39, 0x0024303a, 0x0028343f, 0x002c3741, 0x002d3842, 0x002f3742, 0x002d3540, 0x002c343e, 0x002c343e, 0x002c3540, 0x002c3741, 0x002c3640, 0x002c3641, 0x002e3842, 0x002f3843, 0x00303944, 0x002f3844, 0x002b3541, 0x0027313e, 0x00242f3a, 0x00202c36, 0x001f2b34, 0x00232f37, 0x0027333c, 0x0028353f, 0x0027353f, 0x0024333e, 0x0023313c, 0x001e2e39, 0x00162530, 0x00182730, 0x001c2b34, 0x001a2832, 0x00152028, 0x00141c21, 0x00141a20, 0x0011181e, 0x00131a20, 0x00141b22, 0x00151c24, 0x00151d24, 0x00161e28, 0x0019202b, 0x001c232c, 0x001c242d, 0x001e2830, 0x00202c34, 0x00222e36, 0x00222f38, 0x00202e38, 0x001f2c37, 0x00202e3a, 0x0023303e, 0x00253341, 0x00263544, 0x00283846, 0x00283847, 0x00293a49, 0x002a3c4c, 0x002c3f4f, 0x002c404f, 0x002c3f4f, 0x002c3f4f, 0x002a3d4d, 0x002a3d4d, 0x002a3d4d, 0x00283a4a, 0x00283b4a, 0x00293c4a, 0x00283b49, 0x00233544, 0x001a2a38, 0x00111f2c, 0x000c1a26, 0x000c1824, 0x000c1824, 0x000c1822, 0x000c1821, 0x000c1822, 0x000c1820, 0x000c181f, 0x000c181f, 0x000c181f, 0x000c1820, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000f1821, 0x000e1820, 0x000d1820, 0x000d1720, 0x000d1720, 0x000c1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x000f2229, 0x0013242c, 0x0012242c, 0x0012282e, 0x00112a30, 0x00112a30, 0x00132c32, 0x00142e34, 0x00142e34, 0x00142e34, 0x00143036, 0x00143036, 0x00143036, 0x00153338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00153338, 0x00153338, 0x00143036, 0x00143036, 0x00143036, 0x00143036, 0x00142e34, 0x00142e34, 0x00132c32, 0x00132c32, 0x00112a30, 0x0010282e, 0x0012282e, 0x0013242c, 0x00102229, 0x000f2229, 0x000f1f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1c28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000d1c26, 0x000d1c26, 0x000c1b27, 0x000c1b27, 0x000c1b27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1b26, 0x000c1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000c1d28, 0x000c1d28, 0x000c1e28, 0x000c1d28, 0x000e1d28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d29, 0x00111f2c, 0x0011202d, 0x00142330, 0x00182734, 0x00202f3c, 0x0026333e, 0x00222e37, 0x001c2830, 0x001a242c, 0x001a2329, 0x001b232b, 0x0019242f, 0x001c2731, 0x001e2a34, 0x001e2a34, 0x001e2a34, 0x001e2a34, 0x001c2831, 0x001a252e, 0x0019232c, 0x0019232c, 0x0019232b, 0x00182329, 0x00182429, 0x001c2831, 0x00243039, 0x002d3844, 0x00303d48, 0x00303d49, 0x00303c48, 0x002e3947, 0x002d3845, 0x002d3844, 0x002f3844, 0x002f3843, 0x002f3843, 0x002f3843, 0x002c3740, 0x002b353d, 0x002b333c, 0x00282f38, 0x00242a34, 0x00222831, 0x00242a34, 0x00242a34, 0x00242a34, 0x00242b34, 0x00242d36, 0x00272f38, 0x00273039, 0x0028313c, 0x002b323d, 0x002c333e, 0x002d333f, 0x002f3440, 0x00303742, 0x00303742, 0x002f3742, 0x002e3540, 0x002d3540, 0x002d3541, 0x002e3641, 0x002e3642, 0x002f3742, 0x002f3742, 0x00303844, 0x00303845, 0x00323a47, 0x00343c48, 0x00353d4a, 0x00373f4c, 0x0039404d, 0x00393f4b, 0x00383c48, 0x00363c48, 0x00363a46, 0x00343944, 0x00333842, 0x00323743, 0x00333743, 0x00323642, 0x00313541, 0x00323642, 0x00323642, 0x00303541, 0x002f3440, 0x002f343f, 0x00303541, 0x00313742, 0x00313843, 0x00323843, 0x00343844, 0x00343844, 0x00333743, 0x00303440, 0x00313541, 0x00323642, 0x00323642, 0x00323642, 0x00323642, 0x00323642, 0x00303440, 0x002f343e, 0x00313540, 0x00333842, 0x00343844, 0x00343844, 0x00343844, 0x00323844, 0x00323844, 0x00333944, 0x00323844, 0x00313843, 0x00323642, 0x00323642, 0x00323642, 0x00323743, 0x00333642, 0x00333743, 0x00323845, 0x00333946, 0x00343a47, 0x00343a45, 0x00333944, 0x00343a45, 0x00353c47, 0x00353c47, 0x00343a46, 0x00313a44, 0x00313944, 0x00313944, 0x00323a44, 0x00333b46, 0x00343b46, 0x00303742, 0x002f3540, 0x00303641, 0x002f3540, 0x002c333e, 0x002b313c, 0x0029303b, 0x00282f39, 0x00272d37, 0x00282e37, 0x00282f38, 0x00252d37, 0x00232b36, 0x00232a34, 0x00212833, 0x00202732, 0x00202730, 0x00202630, 0x001f252f, 0x001e242e, 0x001f252f, 0x00212831, 0x00262c36, 0x0029323b, 0x002a343d, 0x0028333c, 0x0024303b, 0x0026313c, 0x002a343f, 0x002c3640, 0x002c3641, 0x002c343f, 0x002c343e, 0x002c343e, 0x002c3540, 0x002c3741, 0x002c3640, 0x002c3641, 0x002e3842, 0x002e3843, 0x002f3844, 0x002e3844, 0x002a3440, 0x00252f3b, 0x00232d38, 0x00202a34, 0x001d2831, 0x00202b33, 0x00212d37, 0x0024303a, 0x0024323c, 0x0024333d, 0x0025343f, 0x0024333e, 0x00192832, 0x0014242d, 0x00192832, 0x001a2832, 0x0017222a, 0x00151e24, 0x00141b20, 0x0010181d, 0x0012181e, 0x00131920, 0x00121820, 0x00101820, 0x00131b24, 0x00151c28, 0x00171d27, 0x00181f28, 0x0019222b, 0x001b252e, 0x001c2830, 0x00202c36, 0x00212f38, 0x00212f39, 0x0021303c, 0x00243340, 0x00263542, 0x00283846, 0x002a3c4a, 0x002b3c4b, 0x002b3d4c, 0x002c3f4f, 0x002c404f, 0x002a3f4e, 0x002a3e4d, 0x002c4050, 0x002d4251, 0x002f4353, 0x00304453, 0x002d4151, 0x002c4050, 0x002a3f4c, 0x00283c4a, 0x00253847, 0x0021303f, 0x00182533, 0x00111e2a, 0x000c1a26, 0x000c1824, 0x000c1822, 0x000c1821, 0x000c1822, 0x000c1820, 0x000c181f, 0x000c181f, 0x000c181f, 0x000c1820, 0x000d1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1820, 0x000e1820, 0x000d1720, 0x000d1720, 0x000d1720, 0x000c1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0013282e, 0x0010282e, 0x00112a30, 0x00132c32, 0x00142e34, 0x00143036, 0x00153338, 0x00143338, 0x00153439, 0x0015363b, 0x0015363b, 0x0016363b, 0x0016383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0016383c, 0x0016363b, 0x0015363b, 0x0015363b, 0x0015363b, 0x00143439, 0x00153439, 0x00143338, 0x00143036, 0x00143036, 0x00142e34, 0x00132c32, 0x00112a30, 0x0011282e, 0x0012242c, 0x0012242c, 0x000f2229, 0x000f1f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1c28, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000d1c28, 0x000d1c28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1b26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1d28, 0x000d1e28, 0x000c1e28, 0x000d1e28, 0x000e1e28, 0x000e1d28, 0x000e1c25, 0x000d1b25, 0x000e1c26, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000e1c27, 0x000f1c28, 0x00101d29, 0x00101e2c, 0x00101e2c, 0x0012212e, 0x00182734, 0x0022313f, 0x002b3844, 0x00283440, 0x001f2b34, 0x0019242c, 0x0019222a, 0x0019232c, 0x00192430, 0x001c2831, 0x001f2a34, 0x00202c36, 0x001e2a34, 0x001d2933, 0x001c2830, 0x0018242c, 0x0019242c, 0x0019232c, 0x0018222a, 0x00172228, 0x001b272c, 0x00202c34, 0x0027333c, 0x00303b46, 0x00303c48, 0x00303c48, 0x00303c48, 0x002f3a48, 0x002e3946, 0x002e3945, 0x00303946, 0x00303a44, 0x002f3843, 0x002d3842, 0x002a343e, 0x0028323b, 0x00283039, 0x00252c35, 0x00202730, 0x00202730, 0x00232933, 0x00242b34, 0x00242a34, 0x00242b34, 0x00242c35, 0x00252e37, 0x00242d36, 0x00272f39, 0x0028303c, 0x002b313c, 0x002c323d, 0x002d343f, 0x002f3641, 0x002d3540, 0x002d3540, 0x002c3440, 0x002d3540, 0x002e3641, 0x002f3742, 0x00303843, 0x00313944, 0x00323a44, 0x00333b46, 0x00333b47, 0x00343c48, 0x00333b48, 0x00313946, 0x00323a47, 0x00343c48, 0x00343b47, 0x00333844, 0x00323844, 0x00343945, 0x00343a45, 0x00343944, 0x00343844, 0x00343945, 0x00343945, 0x00343945, 0x00343a45, 0x00343a45, 0x00343945, 0x00333844, 0x00323642, 0x00323743, 0x00323843, 0x00333843, 0x00333843, 0x00343844, 0x00343844, 0x00333843, 0x00323642, 0x00323642, 0x00333743, 0x00333743, 0x00333743, 0x00333743, 0x00323642, 0x00313541, 0x0030343f, 0x00313640, 0x00343844, 0x00343945, 0x00343944, 0x00343945, 0x00343945, 0x00333945, 0x00343b46, 0x00343b46, 0x00333944, 0x00333844, 0x00333744, 0x00333744, 0x00333844, 0x00343844, 0x00343945, 0x00363c48, 0x00383c4a, 0x00383d4a, 0x00383d49, 0x00383d48, 0x00373c48, 0x00373d48, 0x00363c48, 0x00333947, 0x00313945, 0x00343c47, 0x00353d48, 0x00343c48, 0x00323c46, 0x00323b45, 0x00303843, 0x002f3742, 0x002e3541, 0x002c3440, 0x002c343e, 0x0029303c, 0x00282e39, 0x00262c36, 0x00242b34, 0x00252c35, 0x00262d36, 0x00262c36, 0x00252c37, 0x00252b37, 0x00232935, 0x00232834, 0x00232933, 0x00222832, 0x00212831, 0x00202730, 0x001f252f, 0x001f252f, 0x00202730, 0x00242c35, 0x0028323a, 0x0029343d, 0x0025313b, 0x0024303b, 0x0027313c, 0x0029343e, 0x002c3440, 0x002c343f, 0x002c343e, 0x002c343e, 0x002c3540, 0x002c3741, 0x002c3640, 0x002c3641, 0x002d3842, 0x002c3741, 0x002c3741, 0x002d3642, 0x002a3340, 0x00242c38, 0x00212a36, 0x00202a34, 0x001c2630, 0x001e2831, 0x00202a32, 0x00202d36, 0x00223039, 0x0023303a, 0x0024313b, 0x0026343f, 0x001e2d37, 0x00182630, 0x00182831, 0x0018252f, 0x0018222b, 0x00182027, 0x00171d23, 0x00131a20, 0x0012181e, 0x00131920, 0x00121921, 0x00111920, 0x00131c24, 0x00161c27, 0x00171d27, 0x00171f28, 0x00172029, 0x0018232c, 0x001a262f, 0x001e2a34, 0x00202d37, 0x00212f39, 0x0023313c, 0x00253441, 0x00283844, 0x002b3a48, 0x002c3d4c, 0x002c3f4c, 0x002c3e4c, 0x002b3e4d, 0x002a3e4d, 0x00293e4d, 0x002a3e4d, 0x002b404f, 0x002e4353, 0x00304557, 0x00304556, 0x002f4454, 0x002c4051, 0x00263c4a, 0x00203745, 0x001f3342, 0x001f3040, 0x001c2a39, 0x00152230, 0x000f1c28, 0x000c1924, 0x000c1823, 0x000c1823, 0x000c1824, 0x000c1822, 0x000c1820, 0x000c1820, 0x000c1820, 0x000d1921, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x000e1a24, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1921, 0x000e1820, 0x000e1820, 0x000d1720, 0x000d1720, 0x000c1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b151e, 0x000b151e, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00132c32, 0x00142e34, 0x00143036, 0x00143338, 0x00143439, 0x0016363b, 0x0017383c, 0x00173a3e, 0x00183c40, 0x00183c40, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183c40, 0x00183c40, 0x00173a3e, 0x00183a3e, 0x0017383c, 0x0015363b, 0x00153439, 0x00153338, 0x00143036, 0x00132c32, 0x00112a30, 0x0010282e, 0x0012242c, 0x0012242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1c28, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000d1c28, 0x000d1c28, 0x000e1d28, 0x000e1d28, 0x000d1c28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1b26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1b26, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1d28, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1d28, 0x000e1c25, 0x000d1b24, 0x000e1c26, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000e1c28, 0x000e1b28, 0x000f1c28, 0x000f1c29, 0x000d1c28, 0x0011202c, 0x00172734, 0x0023313f, 0x002f3a47, 0x002d3944, 0x00212d37, 0x001a242d, 0x0018222b, 0x0019232c, 0x001b2630, 0x001e2a34, 0x00202c36, 0x00222e38, 0x00202c36, 0x001e2a34, 0x0019252e, 0x0018242c, 0x0019242c, 0x001a242c, 0x0019232a, 0x0018242b, 0x001d2930, 0x00212e36, 0x0028343d, 0x002f3b45, 0x002f3b47, 0x00303c48, 0x002f3b48, 0x002f3a48, 0x002f3a48, 0x002f3a47, 0x00303a46, 0x00303a44, 0x002f3944, 0x002c3741, 0x002b343e, 0x0028323b, 0x00272f38, 0x00232933, 0x00202630, 0x00202731, 0x00222833, 0x00232934, 0x00222832, 0x00222832, 0x00232a34, 0x00232c35, 0x00222a34, 0x00242c35, 0x0028303a, 0x002b313c, 0x002c333e, 0x002e3440, 0x002f3641, 0x002d3540, 0x002c3440, 0x002d3540, 0x002d3541, 0x002e3642, 0x002f3742, 0x00303843, 0x00313944, 0x00323a44, 0x00333b46, 0x00333c47, 0x00343c49, 0x00363d4a, 0x00343c49, 0x00343c49, 0x00343c4a, 0x00353c49, 0x00343b48, 0x00333946, 0x00323844, 0x00323844, 0x00333944, 0x00343a46, 0x00353b47, 0x00343b47, 0x00353c47, 0x00363d48, 0x00373d48, 0x00363d48, 0x00363c48, 0x00343a46, 0x00343a46, 0x00353a46, 0x00353a46, 0x00343844, 0x00343944, 0x00343844, 0x00343844, 0x00343944, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00333743, 0x00333841, 0x00343944, 0x00383c46, 0x00383c48, 0x00383c48, 0x00383d48, 0x00383d48, 0x00373d49, 0x00383d4a, 0x00383d4a, 0x00353c48, 0x00353a48, 0x00343846, 0x00343945, 0x00343945, 0x00353945, 0x00363b47, 0x00383c49, 0x00383c4a, 0x00383c4a, 0x00393e4a, 0x00393e4a, 0x00383c48, 0x00353b48, 0x00343b48, 0x00343c49, 0x00343c48, 0x00343c48, 0x00343c47, 0x00333b46, 0x00303944, 0x002f3843, 0x002e3641, 0x002e3641, 0x002e3641, 0x002d3540, 0x002c343f, 0x0028303c, 0x00272d39, 0x00252c36, 0x00242b34, 0x00252c35, 0x00282d37, 0x00282e38, 0x00282c38, 0x00272c37, 0x00252b37, 0x00262c37, 0x00252c35, 0x00242b34, 0x00242b34, 0x00242a33, 0x00202730, 0x0020262e, 0x001f252e, 0x00202830, 0x00232c35, 0x0027313a, 0x0025313a, 0x0025313b, 0x0026313c, 0x0027313c, 0x0028313c, 0x0028303c, 0x0029313c, 0x002a323d, 0x002c343f, 0x002c3741, 0x002c3640, 0x002c3641, 0x002d3842, 0x002c3741, 0x002c3540, 0x002c3440, 0x0029303c, 0x00232b37, 0x00202834, 0x00202832, 0x001c242e, 0x001c252e, 0x00202831, 0x00202b34, 0x00212e37, 0x00212e38, 0x00212e38, 0x0024323c, 0x0023303a, 0x001d2b34, 0x001d2c35, 0x0017242d, 0x00162028, 0x00161e24, 0x00151c23, 0x00141a20, 0x00131920, 0x00141b22, 0x00171e25, 0x00182027, 0x00192129, 0x001b222c, 0x001b222c, 0x001b232c, 0x0019242c, 0x0019252d, 0x001c2832, 0x00202c36, 0x00202e38, 0x00223039, 0x0024323d, 0x00283642, 0x002b3945, 0x002c3b49, 0x002d3e4c, 0x002c3e4c, 0x002c3e4d, 0x002a3d4d, 0x002a3e4e, 0x002a3f4f, 0x002b3f4f, 0x002c4151, 0x00304455, 0x00314658, 0x00304556, 0x002e4454, 0x002b4152, 0x00243a49, 0x001d3140, 0x00182b3b, 0x00182838, 0x00182736, 0x00142230, 0x000f1c28, 0x000c1924, 0x000c1824, 0x000c1824, 0x000c1824, 0x000d1922, 0x000d1921, 0x000d1921, 0x000d1921, 0x000d1922, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000e1820, 0x000c1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b151e, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00122229, 0x000f2229, 0x0013242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00142e34, 0x00153338, 0x00143439, 0x0017383c, 0x00183a3e, 0x00183c40, 0x00183d41, 0x00183f43, 0x00194044, 0x001a4245, 0x001a4245, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4245, 0x001a4245, 0x001a4245, 0x001a4245, 0x001a4245, 0x001a4245, 0x001a4245, 0x001a4245, 0x001a4245, 0x001a4245, 0x00194245, 0x001a4245, 0x00194044, 0x00183f43, 0x00183f43, 0x00183d41, 0x00183c40, 0x0017383c, 0x0016363b, 0x00143338, 0x00143036, 0x00142e34, 0x00112a30, 0x0010282e, 0x0013242c, 0x00102229, 0x00102229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000e1d27, 0x00101d28, 0x00101d28, 0x000f1d28, 0x000e1e28, 0x000e1e28, 0x000f1f29, 0x000f1e29, 0x000d1d28, 0x000c1d28, 0x000c1c28, 0x000d1c28, 0x000d1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c27, 0x000f1c27, 0x000f1c27, 0x000f1c27, 0x000f1d28, 0x000e1f29, 0x000e1f29, 0x000e1e2a, 0x000e1e2a, 0x000f1d28, 0x000f1c27, 0x000f1c26, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000d1c27, 0x000e1c27, 0x000e1c28, 0x000e1c28, 0x000e1c28, 0x000f1c2a, 0x000f1c2a, 0x000f1c2a, 0x000f1c2a, 0x000f1c29, 0x000e1c28, 0x000d1a27, 0x000d1a26, 0x000d1b27, 0x000d1b27, 0x000c1c27, 0x000f1f2a, 0x00142431, 0x0022303d, 0x002f3a48, 0x00303a45, 0x00242e38, 0x001c242d, 0x0019212b, 0x001c242d, 0x001c2731, 0x001d2833, 0x001c2832, 0x001e2a34, 0x001d2933, 0x001c2832, 0x0018252e, 0x0018242c, 0x0018242d, 0x0019242d, 0x0019242c, 0x001a262d, 0x001e2a31, 0x00202d36, 0x0026323c, 0x002d3944, 0x002f3b47, 0x00303c48, 0x00303c48, 0x00303c49, 0x00303c48, 0x00303b47, 0x00303a45, 0x002f3843, 0x002e3842, 0x002c3440, 0x002a343d, 0x0027313a, 0x00262e37, 0x00242a34, 0x00202730, 0x00222833, 0x00232934, 0x00232834, 0x00212831, 0x00212831, 0x00222933, 0x00232a34, 0x00222933, 0x00242b34, 0x00272e38, 0x002c323d, 0x002c333e, 0x002d343f, 0x002e3540, 0x002d3540, 0x002e3641, 0x002e3641, 0x002d3541, 0x002d3541, 0x002e3642, 0x00303844, 0x00313a45, 0x00323b46, 0x00333c48, 0x00343c48, 0x00353e4a, 0x00383f4c, 0x00373f4c, 0x00363e4c, 0x0037404e, 0x00373f4c, 0x00383f4c, 0x00383f4c, 0x00353c48, 0x00333945, 0x00323844, 0x00343a45, 0x00353c47, 0x00353b48, 0x00363c49, 0x00383f4b, 0x00393f4c, 0x00393f4c, 0x00393f4c, 0x00383e4a, 0x00383e4a, 0x00383d49, 0x00383c48, 0x00353a46, 0x00343944, 0x00343945, 0x00353a46, 0x00363b47, 0x00373b48, 0x00363b47, 0x00343a46, 0x00353a46, 0x00343946, 0x00343944, 0x00343844, 0x00343944, 0x00363b44, 0x00373c47, 0x00383c48, 0x003a3f4b, 0x003c404c, 0x003a3f4c, 0x003a404c, 0x003a404d, 0x003a404d, 0x00383f4c, 0x00373d4b, 0x00363c4a, 0x00353b48, 0x00353b49, 0x00373c49, 0x00383e4a, 0x00383e4b, 0x00393e4c, 0x00383e4b, 0x00383e4b, 0x00373d4a, 0x00353c49, 0x00353d4a, 0x00383f4c, 0x00383f4c, 0x00353c49, 0x00343b48, 0x00333a47, 0x00333a46, 0x00313944, 0x002f3742, 0x002d3540, 0x002d3540, 0x002e3642, 0x002d3441, 0x002b333f, 0x0029313e, 0x002a303c, 0x00282e38, 0x00282e38, 0x00282e38, 0x00282f38, 0x00292e38, 0x00282c37, 0x00282c38, 0x00262c37, 0x00252c36, 0x00252c35, 0x00242c35, 0x00242c34, 0x00252c34, 0x00232931, 0x0020272e, 0x0020262e, 0x001f252f, 0x00202831, 0x00242e37, 0x00242e37, 0x0024303b, 0x0026303b, 0x0026303a, 0x00262f38, 0x00252e38, 0x00252e38, 0x0028303b, 0x002a343e, 0x002c3540, 0x002b343f, 0x002c3540, 0x002d3742, 0x002d3741, 0x002c3540, 0x002b333e, 0x0028303c, 0x00242c36, 0x00222932, 0x0020282f, 0x001c222a, 0x001a212a, 0x00202730, 0x00202c34, 0x00202c35, 0x00202c35, 0x00202c35, 0x00212f38, 0x0024333c, 0x00222f39, 0x00202c36, 0x001b2831, 0x0018232c, 0x00161d25, 0x00151c24, 0x00151c24, 0x00161c24, 0x00171d24, 0x00181f26, 0x00182027, 0x00182129, 0x0019222c, 0x001a232d, 0x001b242f, 0x001a242f, 0x00192530, 0x001f2a36, 0x0024303b, 0x0025323c, 0x0026343e, 0x00273440, 0x00293743, 0x002b3845, 0x002b3a48, 0x002c3c4c, 0x002c3c4c, 0x002b3c4d, 0x002b3d4f, 0x002b4050, 0x002c4052, 0x002c4052, 0x002e4354, 0x00304456, 0x00304557, 0x002c4152, 0x00283d4c, 0x00263b4a, 0x00203544, 0x001c2f3d, 0x00152634, 0x00132230, 0x0013212f, 0x00111f2c, 0x000f1c28, 0x000d1a25, 0x000c1924, 0x000c1824, 0x000d1924, 0x000e1923, 0x000e1922, 0x000e1923, 0x000e1923, 0x000e1a24, 0x000f1a24, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000f1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000d1720, 0x000d1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b151e, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x000f2229, 0x0012242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00142e34, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183c40, 0x00183f43, 0x00194044, 0x001a4347, 0x001b4448, 0x001c4649, 0x001c474b, 0x001c474b, 0x001d484c, 0x001d484c, 0x001d484c, 0x001d484c, 0x001d484c, 0x001d484c, 0x001c484c, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c4649, 0x001c4649, 0x001b4448, 0x001a4347, 0x001a4245, 0x00183f43, 0x00183d41, 0x00183a3e, 0x0017383c, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000e1d27, 0x00101e29, 0x00101e29, 0x00101f29, 0x000f1f29, 0x000f1f29, 0x0010202b, 0x0010202b, 0x000f1f29, 0x000e1d28, 0x000e1d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101e28, 0x000f1f29, 0x000f1f29, 0x000f1e2c, 0x000f1e2c, 0x000f1e2a, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000c1c2a, 0x000d1c2b, 0x000d1c2b, 0x000f1c2b, 0x000f1c2b, 0x000f1c2a, 0x000d1a27, 0x000d1a26, 0x000d1a26, 0x000d1b26, 0x000c1a26, 0x000c1b25, 0x000d1e29, 0x00122430, 0x00202f3c, 0x002f3b48, 0x00303945, 0x00242c38, 0x001c232d, 0x001b212b, 0x001b222c, 0x0019222c, 0x0016202b, 0x0015212c, 0x001a2530, 0x0018242e, 0x0018242f, 0x0018242f, 0x0017242f, 0x0018242f, 0x00192530, 0x001a2630, 0x001c2831, 0x001e2a33, 0x00202c37, 0x0026303c, 0x002d3844, 0x002f3b47, 0x002f3b47, 0x00303c48, 0x00303c48, 0x00303c47, 0x00313b46, 0x00303944, 0x002e3842, 0x002e3641, 0x002b333e, 0x0028323c, 0x0027303b, 0x00272e38, 0x00242b36, 0x00242a34, 0x00252c34, 0x00242b35, 0x00232933, 0x00222831, 0x00222831, 0x00232933, 0x00242a34, 0x00242a34, 0x00242a35, 0x00272d38, 0x002b313c, 0x002c323d, 0x002c333e, 0x002c333e, 0x002c343e, 0x002b333e, 0x002c343f, 0x002b333e, 0x002a323e, 0x002c3440, 0x00303844, 0x00303a47, 0x00313c48, 0x00323d49, 0x00333f4b, 0x00343f4b, 0x0037404d, 0x0038414e, 0x0038404d, 0x0038424e, 0x0038424f, 0x003a424f, 0x003a424f, 0x0039404d, 0x00383e4a, 0x00343b44, 0x00343a44, 0x00383f4a, 0x00383e4a, 0x0038404c, 0x0038404c, 0x0039404c, 0x0039414e, 0x003b424f, 0x003b424e, 0x003b424f, 0x003b404d, 0x00383c4a, 0x00353a48, 0x00353a47, 0x00373c48, 0x00383c48, 0x00383d4b, 0x00383d4b, 0x00373c4a, 0x00363c49, 0x00373b48, 0x00373b48, 0x00353a47, 0x00353a45, 0x00353a46, 0x00363c46, 0x00373d48, 0x00353c47, 0x00393e4b, 0x003c404d, 0x003a3f4c, 0x003b404e, 0x00394150, 0x0039404f, 0x0039404f, 0x0038404f, 0x0038404e, 0x00383f4d, 0x0038404f, 0x003a414f, 0x003a424f, 0x0038404c, 0x00373e4b, 0x00383f4c, 0x003a414e, 0x0038404e, 0x00353e4b, 0x00363d4a, 0x00373d4a, 0x00363c49, 0x00353b48, 0x00343947, 0x00323846, 0x00313845, 0x00303844, 0x002d3540, 0x002c3440, 0x002d3440, 0x00303540, 0x002c333e, 0x002b313d, 0x002b313c, 0x002a313d, 0x002a303c, 0x002a303c, 0x002a303b, 0x0029303a, 0x00282e38, 0x00272c36, 0x00252a36, 0x00242935, 0x00222a33, 0x00222a33, 0x00212933, 0x00212931, 0x00242a32, 0x00242a31, 0x00212830, 0x0020272f, 0x001e242e, 0x001f252e, 0x00222932, 0x00212b34, 0x0025303a, 0x0028323c, 0x00263039, 0x00242e36, 0x00212c34, 0x00232c35, 0x00263039, 0x0028333d, 0x002a343e, 0x002b323d, 0x002b333d, 0x002d3540, 0x002e3540, 0x002c343f, 0x0029313d, 0x0028303c, 0x00252c37, 0x00232933, 0x001f252c, 0x001a2027, 0x00181f26, 0x001d242c, 0x00222b35, 0x00222e38, 0x00202c35, 0x001f2c36, 0x001d2b34, 0x0024313b, 0x0024313b, 0x001c2832, 0x0018252f, 0x0018232c, 0x00171f26, 0x00171f26, 0x00181f26, 0x00192026, 0x00181f27, 0x00181f26, 0x00161d24, 0x00141c25, 0x00151d27, 0x00162029, 0x0018212c, 0x0019242f, 0x001c2731, 0x00212d39, 0x0027333f, 0x00283440, 0x00263440, 0x00263440, 0x00283543, 0x00283845, 0x00283947, 0x00283a48, 0x002a3c4b, 0x002c3f4f, 0x002d4152, 0x002d4253, 0x002e4354, 0x002d4354, 0x002e4454, 0x002f4556, 0x002d4455, 0x00273c4c, 0x001f3442, 0x001b303c, 0x001c2f3c, 0x001a2c39, 0x00142431, 0x0010202c, 0x000f1e2a, 0x00101d28, 0x000e1c26, 0x000d1b24, 0x000d1a23, 0x000d1922, 0x000e1923, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101c26, 0x00101b25, 0x000f1a24, 0x000d1924, 0x000d1924, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000d1720, 0x000d1720, 0x000d1720, 0x000c1720, 0x000c161f, 0x000b151e, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00142e34, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183d41, 0x00194044, 0x001a4347, 0x001b4649, 0x001c474b, 0x001c4a4d, 0x001d4b4e, 0x001d4c50, 0x001d4c50, 0x001e4d50, 0x001e4d50, 0x001d4d50, 0x001e4d50, 0x001e4d50, 0x001e4d50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4b4e, 0x001d4b4e, 0x001c4a4d, 0x001d4a4d, 0x001c484c, 0x001b4649, 0x001b4448, 0x001a4245, 0x00183f43, 0x00183c40, 0x0017383c, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0013282e, 0x0012242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000e1d28, 0x00101e29, 0x00101e29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x0010202b, 0x0010202b, 0x000f1f29, 0x000e1e28, 0x000e1e28, 0x000f1d28, 0x000f1d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101f2a, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010202c, 0x00101e2b, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000c1c2a, 0x000d1c2b, 0x000d1c2b, 0x000e1c2b, 0x000f1c2b, 0x000f1c2a, 0x000d1a27, 0x000d1a26, 0x000d1a26, 0x000d1b26, 0x000c1a26, 0x000b1a25, 0x000d1d28, 0x0011222f, 0x001e2d3a, 0x002d3a48, 0x00303944, 0x00242c38, 0x001c232d, 0x001a202a, 0x0019202a, 0x00171f2a, 0x00131c27, 0x00121e28, 0x0017222c, 0x0017232c, 0x0018242e, 0x0018242f, 0x00182630, 0x001b2831, 0x001c2832, 0x001b2831, 0x001b2832, 0x001d2932, 0x00212c35, 0x0026303a, 0x002d3843, 0x002f3a46, 0x002f3b47, 0x00303c48, 0x00303c48, 0x00303c47, 0x00303a45, 0x002e3843, 0x002c3640, 0x002a323d, 0x0029313c, 0x0027303c, 0x0026303a, 0x00272d38, 0x00242b36, 0x00242b36, 0x00272d37, 0x00262c36, 0x00232933, 0x00222831, 0x00222831, 0x00222832, 0x00242a34, 0x00242b34, 0x00252c36, 0x00282e3a, 0x002c323d, 0x002c323d, 0x002a313c, 0x0028303b, 0x0028303c, 0x0028303c, 0x002b333e, 0x002c333e, 0x002a323c, 0x002c333e, 0x00303844, 0x00303a47, 0x00313b48, 0x00303c48, 0x00333e4a, 0x00343f4b, 0x0037404c, 0x0038414e, 0x0037414e, 0x0038424f, 0x0039434f, 0x003c4450, 0x003c4451, 0x003c4350, 0x003b414f, 0x0039404c, 0x00383e49, 0x003a404c, 0x003b414d, 0x003c434f, 0x003a424d, 0x0039414d, 0x003a424f, 0x003c4451, 0x003c4451, 0x003c4450, 0x003c4250, 0x003a404d, 0x00373c4a, 0x00363b48, 0x00373b48, 0x00383d49, 0x0039404c, 0x003a404d, 0x00393f4c, 0x00383e4b, 0x00393d4b, 0x00393d4b, 0x00383c48, 0x00383c48, 0x00383c48, 0x00373d48, 0x00383e48, 0x00363c48, 0x00393e4c, 0x003b404d, 0x003c404d, 0x003d4350, 0x003b4351, 0x003a4250, 0x003a4250, 0x003a4250, 0x003a4250, 0x00394250, 0x003a4250, 0x0039414f, 0x0038404c, 0x00373f4c, 0x00383f4c, 0x003a404d, 0x003b424f, 0x0038414e, 0x00353f4c, 0x00343c49, 0x00363c49, 0x00353b48, 0x00353b48, 0x00343a48, 0x00343947, 0x00333947, 0x00313844, 0x002e3641, 0x002c3440, 0x002c343f, 0x002e343f, 0x002d343f, 0x002e343f, 0x002c323d, 0x0028303b, 0x00282f3b, 0x002a303c, 0x002a303c, 0x002a303b, 0x00282e38, 0x00252c36, 0x00242934, 0x00222834, 0x00212831, 0x00202830, 0x001e2730, 0x001e2730, 0x00202830, 0x00212830, 0x0020282f, 0x0020262e, 0x001e242d, 0x001d242c, 0x00202630, 0x00212933, 0x00242f39, 0x0025303a, 0x00242d37, 0x00212c34, 0x00222c34, 0x00242d36, 0x00263039, 0x0028323c, 0x0029333d, 0x0029313c, 0x0029313c, 0x002c343f, 0x002c343f, 0x002a323d, 0x0029313d, 0x0028303c, 0x00252c37, 0x00242a33, 0x001f252c, 0x00192027, 0x00151c24, 0x00181f27, 0x00212a34, 0x0024303a, 0x00212d37, 0x001e2a34, 0x001c2933, 0x001e2c35, 0x00202d37, 0x0017242e, 0x00101e28, 0x00141f28, 0x00141e26, 0x00141c24, 0x00161c23, 0x00161c23, 0x00161c24, 0x00151c23, 0x00141c23, 0x00101822, 0x00111922, 0x00131c25, 0x00152029, 0x001b2530, 0x001f2b34, 0x0025313d, 0x00283440, 0x0025323e, 0x0023303c, 0x0024333e, 0x00283643, 0x00293947, 0x00283a47, 0x00283c4a, 0x002c404d, 0x00304454, 0x00314555, 0x00304455, 0x002f4455, 0x002f4455, 0x002e4455, 0x002d4555, 0x002c4353, 0x00253b4a, 0x001b2f3d, 0x00152935, 0x00162936, 0x00152834, 0x0012222f, 0x000f1f2b, 0x000e1d28, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000d1a23, 0x000d1921, 0x000e1a23, 0x00101b25, 0x00111c26, 0x00111c26, 0x00111c26, 0x00111c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x000f1a24, 0x000d1924, 0x000d1924, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000d1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b151e, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00143036, 0x00143439, 0x00183a3e, 0x00183d41, 0x001a4245, 0x001b4448, 0x001c474b, 0x001d4b4e, 0x001d4c50, 0x001e4f51, 0x001f5053, 0x00205154, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x001f5154, 0x001f5154, 0x00205154, 0x001f5053, 0x001e5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001e5053, 0x001e4f51, 0x001e4f51, 0x001d4d50, 0x001d4c50, 0x001c4a4d, 0x001c474b, 0x001b4649, 0x001a4245, 0x00183f43, 0x00183c40, 0x0016363b, 0x00143338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x000f1f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x00101f2a, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101f2b, 0x00101f2b, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x0011202b, 0x0011202c, 0x0011202c, 0x0011202d, 0x0011202d, 0x0010202c, 0x00101e2c, 0x00101e2b, 0x00101d28, 0x00101d28, 0x000f1d28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e2b, 0x000c1e2c, 0x000c1d2c, 0x000e1d2c, 0x000e1d2c, 0x000e1c2a, 0x000d1a27, 0x000d1a26, 0x000d1a26, 0x000d1b26, 0x000c1a26, 0x000b1a25, 0x000c1d28, 0x0011212e, 0x001b2a37, 0x002a3644, 0x002f3843, 0x00252d38, 0x001c232d, 0x00192029, 0x0019202a, 0x0018202c, 0x0016202b, 0x0014202a, 0x0015212b, 0x0018242d, 0x001b2731, 0x001b2831, 0x001b2832, 0x001d2a34, 0x001c2832, 0x001b2630, 0x001b2730, 0x001c2730, 0x00202b34, 0x00252e38, 0x002c3641, 0x002e3844, 0x002e3945, 0x002f3b47, 0x002f3c48, 0x00303b47, 0x00303944, 0x002d3842, 0x002b3540, 0x0028303b, 0x0028303c, 0x0027303b, 0x0026303a, 0x00272c38, 0x00222834, 0x00232934, 0x00242b34, 0x00242b34, 0x00232932, 0x00212831, 0x00212831, 0x00232933, 0x00252c35, 0x00272c37, 0x00282e39, 0x002a303c, 0x002d333e, 0x002e343f, 0x002d343f, 0x002b333e, 0x002a323d, 0x002c343e, 0x002c3440, 0x002d343f, 0x002d343c, 0x002e343f, 0x00313844, 0x00313a46, 0x00303a47, 0x00313c48, 0x00333d49, 0x00343f4b, 0x0036404c, 0x0038414e, 0x0038434f, 0x0038434f, 0x00394350, 0x003c4452, 0x003c4453, 0x003c4452, 0x003c4251, 0x003c424f, 0x003b414e, 0x003a404d, 0x003b414f, 0x003d4452, 0x003c4451, 0x003a4250, 0x003c4450, 0x003d4552, 0x003d4553, 0x003e4454, 0x003e4454, 0x003b4150, 0x00393f4d, 0x00383d4b, 0x00363c49, 0x00373d49, 0x00383f4b, 0x00393f4c, 0x003a404d, 0x0039404d, 0x00393f4c, 0x00393f4c, 0x003a3f4c, 0x003a3f4a, 0x003a3f4b, 0x0039404b, 0x003a414c, 0x0039404c, 0x003d4250, 0x003f4351, 0x00404452, 0x003f4554, 0x003b4351, 0x00394050, 0x00394150, 0x003a4250, 0x003a4250, 0x003a4250, 0x003a4250, 0x003b4351, 0x003b4351, 0x003a4250, 0x003b424f, 0x00393f4c, 0x00373e4b, 0x0037404c, 0x0036404c, 0x00363e4b, 0x00363c49, 0x00353b48, 0x00343a48, 0x00353b48, 0x00343a48, 0x00343a48, 0x00323a45, 0x00303843, 0x002d3540, 0x002c343f, 0x002c333e, 0x002f3540, 0x00303742, 0x002f3440, 0x002a303c, 0x00292f3c, 0x002a303d, 0x002b313d, 0x002c323d, 0x00292f3b, 0x00262c38, 0x00242935, 0x00232934, 0x00222832, 0x001f2730, 0x001c242f, 0x001c242f, 0x001e252f, 0x0020262f, 0x001f252e, 0x001f252e, 0x001e242d, 0x001c232c, 0x001f252e, 0x00222a33, 0x00222c36, 0x00212b35, 0x00202a34, 0x00202c34, 0x00222c35, 0x00232d36, 0x00242e37, 0x0027303b, 0x0029333d, 0x002a343e, 0x002b333e, 0x002a323e, 0x0029313e, 0x0029323e, 0x002a323e, 0x0028303c, 0x00252c37, 0x00242a33, 0x001f262d, 0x00192028, 0x00141b23, 0x00161c24, 0x00212a33, 0x00243039, 0x00222e38, 0x001e2b35, 0x001c2934, 0x001a2831, 0x001a2832, 0x0018242e, 0x00131e28, 0x00141f28, 0x00172029, 0x00141c24, 0x000f161c, 0x000c1319, 0x000d141c, 0x000f171c, 0x00111920, 0x00101821, 0x00101821, 0x00131c25, 0x0017212b, 0x001d2933, 0x00222e38, 0x0024303c, 0x0024303c, 0x00212e3a, 0x00202e39, 0x00253440, 0x002b3a47, 0x002c3c4a, 0x002b3e4b, 0x002c404e, 0x002e4250, 0x00304554, 0x00314556, 0x002f4454, 0x002d4454, 0x002c4354, 0x002c4354, 0x002c4354, 0x002c4251, 0x00243a48, 0x00192d3b, 0x00132734, 0x00142534, 0x00142432, 0x0011202d, 0x000e1d29, 0x000d1c27, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1b24, 0x000e1a24, 0x00101b25, 0x00111c26, 0x00111c26, 0x00111c26, 0x00111c26, 0x00111c27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00101c26, 0x00101b25, 0x000f1a24, 0x000e1a24, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000c161f, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000a141d, 0x0009141c, 0x0009141c, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x00102229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x00143439, 0x0017383c, 0x00183d41, 0x00194044, 0x001b4649, 0x001c484c, 0x001d4c50, 0x001e4f51, 0x001f5154, 0x00205356, 0x00205457, 0x00205558, 0x00205558, 0x00215659, 0x00215659, 0x00215659, 0x00215659, 0x00205558, 0x00205558, 0x00205558, 0x00205457, 0x00205457, 0x00205457, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205254, 0x00205154, 0x001e5053, 0x001d4d50, 0x001d4b4e, 0x001c484c, 0x001b4649, 0x001a4245, 0x00183d41, 0x00183a3e, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x00101f2a, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x00101f2a, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x00101e29, 0x00101e29, 0x00101f2a, 0x0010202b, 0x0010202b, 0x0011202c, 0x0011202c, 0x0012202c, 0x0013202c, 0x0013202c, 0x0013202c, 0x0013202c, 0x0012202c, 0x0012212c, 0x0012212c, 0x0012212d, 0x0012212e, 0x0011202d, 0x0010202c, 0x0010202c, 0x00101e29, 0x00101e29, 0x00101d28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e2b, 0x000c1e2c, 0x000c1e2c, 0x000e1d2c, 0x000e1d2c, 0x000e1c2a, 0x000d1a27, 0x000d1a26, 0x000d1a26, 0x000d1b26, 0x000c1a26, 0x000b1a25, 0x000c1c27, 0x0010202c, 0x00182633, 0x0026323f, 0x002e3743, 0x00262e39, 0x001c232d, 0x00192029, 0x0019202a, 0x001b242e, 0x001c2530, 0x001a2630, 0x0019242f, 0x001b2731, 0x001d2933, 0x001c2a34, 0x001e2c35, 0x001f2b35, 0x001b2731, 0x0019252f, 0x001c2830, 0x001c2730, 0x001e2832, 0x00232c36, 0x002b343f, 0x002d3844, 0x002d3945, 0x002e3a46, 0x002f3b47, 0x00303b46, 0x00303944, 0x002d3842, 0x002c3540, 0x0028303b, 0x0028303b, 0x0029323c, 0x0027303a, 0x00242b36, 0x00202732, 0x00222832, 0x00222831, 0x00222830, 0x00232931, 0x00242a33, 0x00242a34, 0x00252c35, 0x00272d37, 0x00282f3a, 0x002a303c, 0x002a303c, 0x002d3440, 0x002f3441, 0x002f3743, 0x002d3541, 0x002c343f, 0x002b333e, 0x002b323c, 0x002b313d, 0x002c333c, 0x002e343e, 0x00303742, 0x00303844, 0x00303845, 0x00303a47, 0x00323c48, 0x00353e4b, 0x0037404c, 0x0038414e, 0x00394450, 0x0038434f, 0x003b4450, 0x003c4452, 0x003c4454, 0x003c4453, 0x003c4352, 0x003c4350, 0x003c424f, 0x003b404e, 0x003b414e, 0x003c4350, 0x003c4451, 0x003d4553, 0x003e4554, 0x003e4654, 0x003d4454, 0x00404556, 0x00404556, 0x003e4454, 0x003c4252, 0x003b404f, 0x00393f4d, 0x00373d4b, 0x00383f4c, 0x003b404e, 0x003c414f, 0x003c424f, 0x003c4350, 0x003c4350, 0x003d424e, 0x003e424e, 0x003d424e, 0x003c434e, 0x003c444f, 0x003c4450, 0x00404554, 0x00414655, 0x00404655, 0x003f4554, 0x003c4454, 0x003c4454, 0x003c4454, 0x003c4455, 0x003c4455, 0x003c4455, 0x003c4454, 0x003c4454, 0x003d4454, 0x003c4452, 0x003b424f, 0x00383f4c, 0x00373d4a, 0x0037404c, 0x0037404d, 0x0038404c, 0x00363c49, 0x00343a48, 0x00333945, 0x00343a47, 0x00353b48, 0x00343a48, 0x00333a46, 0x00303843, 0x002e3641, 0x002d3540, 0x002d343f, 0x002e3440, 0x00303641, 0x00303742, 0x002c323e, 0x002a303d, 0x002b313f, 0x002d3440, 0x002e3440, 0x002c323d, 0x00292f3a, 0x00272c38, 0x00252b34, 0x00232933, 0x00202830, 0x001d2530, 0x001c242f, 0x001d2430, 0x001e2430, 0x001f252f, 0x001f252f, 0x0020242e, 0x001e242c, 0x001f252d, 0x00212831, 0x00202932, 0x001d2730, 0x001e2831, 0x00202c34, 0x00212c36, 0x00222c36, 0x00232d37, 0x0026303c, 0x0028313d, 0x0028323d, 0x002a323e, 0x0029313d, 0x0028303d, 0x0029313e, 0x002a323f, 0x0028303c, 0x00252c37, 0x00242a33, 0x0020272e, 0x001b2128, 0x00181c24, 0x00161b23, 0x00202830, 0x00242f38, 0x00212e37, 0x00202d37, 0x001d2b35, 0x001b2832, 0x00182630, 0x0018242e, 0x00151f2a, 0x00131c27, 0x00162029, 0x00151e26, 0x0010181f, 0x000c131a, 0x000d151c, 0x0010181e, 0x0010181f, 0x00101822, 0x00131b24, 0x0018212b, 0x001f2833, 0x00242f39, 0x00232e38, 0x00202a37, 0x001f2935, 0x001f2a36, 0x00212e3a, 0x00273541, 0x002c3a47, 0x002e3d4c, 0x002d3f4d, 0x002e404f, 0x002d4250, 0x002f4453, 0x00304454, 0x002e4253, 0x002c4252, 0x002c4252, 0x002c4252, 0x002c4353, 0x002b4151, 0x00243a48, 0x00182c3a, 0x00122433, 0x00112331, 0x00112230, 0x0010202c, 0x000d1c28, 0x000d1c27, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000f1b25, 0x00101b25, 0x00101c25, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00111d27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00101c26, 0x00101b25, 0x000f1a24, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000c161f, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000a141c, 0x0009141c, 0x0009141c, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0013282e, 0x00112a30, 0x00142e34, 0x00153338, 0x0015363b, 0x00183c40, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4c50, 0x00216371, 0x00267f9a, 0x0027819b, 0x0028819c, 0x0028829c, 0x0028829c, 0x0028839c, 0x0028839c, 0x0028839c, 0x0028839c, 0x0028839c, 0x0028839c, 0x0028839c, 0x0028829c, 0x0028829c, 0x0028829c, 0x0028829c, 0x0028829c, 0x0028819c, 0x0028819c, 0x0028819c, 0x0028819c, 0x0028819c, 0x0028819c, 0x0028829c, 0x0028819c, 0x0028819c, 0x0027819c, 0x0027819b, 0x0027809b, 0x0026809b, 0x00257e99, 0x001f5d6b, 0x001c484c, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010202e, 0x0010202d, 0x0010202d, 0x0010202d, 0x0010202c, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202c, 0x0011202c, 0x0011202c, 0x0012212c, 0x0012212c, 0x0013212c, 0x0014212c, 0x0014212c, 0x0014212c, 0x0014212c, 0x0013212e, 0x0012212f, 0x0012212f, 0x0012212f, 0x0012212f, 0x0011212e, 0x0010202e, 0x0010202d, 0x00101f2c, 0x00101f2b, 0x00101f2a, 0x00101e29, 0x00101e29, 0x000f1d28, 0x000f1d28, 0x000f1d2a, 0x000e1d2c, 0x000e1c2c, 0x000e1c2c, 0x000e1c2c, 0x000e1c29, 0x000d1a27, 0x000d1a26, 0x000d1a26, 0x000d1b26, 0x000d1a26, 0x000c1a24, 0x000c1b26, 0x000f1d29, 0x0014222f, 0x00222d3a, 0x002c3541, 0x00252e39, 0x001d242f, 0x001a202b, 0x001b212c, 0x001f2530, 0x00202834, 0x001f2934, 0x001c2831, 0x001c2730, 0x001c2831, 0x001e2a34, 0x001e2c34, 0x001d2933, 0x001a252f, 0x001a252f, 0x001c2830, 0x001c262f, 0x001b2530, 0x00202934, 0x002a323e, 0x002e3844, 0x002e3945, 0x002e3a46, 0x002f3b47, 0x002f3b46, 0x002e3a44, 0x002c3842, 0x002b3540, 0x0027303a, 0x00262f38, 0x00272f39, 0x00232b36, 0x00212833, 0x00212833, 0x00212831, 0x00202730, 0x0020262f, 0x00222830, 0x00242b34, 0x00252c36, 0x00262d38, 0x00283039, 0x0029303c, 0x002a303c, 0x0029303c, 0x002c323f, 0x002f3542, 0x00303844, 0x002d3541, 0x002b333d, 0x0028303b, 0x00282f3a, 0x00282f3b, 0x0029303a, 0x002b313b, 0x002c343f, 0x002e3642, 0x002f3744, 0x00303844, 0x00313a47, 0x00343c49, 0x0038404c, 0x0038424f, 0x0038434f, 0x0038424e, 0x00394450, 0x003b4553, 0x003c4654, 0x003c4755, 0x003c4554, 0x003c4451, 0x003a424f, 0x003a4250, 0x003c4451, 0x003c4553, 0x003d4754, 0x003f4857, 0x003f4858, 0x00404858, 0x00404858, 0x00404858, 0x003f4756, 0x003d4454, 0x003e4454, 0x003d4453, 0x003c4351, 0x003c4250, 0x003c4350, 0x003e4451, 0x003d4451, 0x003d4451, 0x003e4552, 0x003d4452, 0x003e4450, 0x003f4450, 0x003e4450, 0x003d4450, 0x003c4450, 0x003c4451, 0x00424858, 0x00444b59, 0x00414857, 0x00404857, 0x003f4757, 0x003f4758, 0x00404858, 0x00404858, 0x00404858, 0x00404858, 0x00404757, 0x003e4454, 0x003d4454, 0x003d4454, 0x003c4452, 0x003a404f, 0x0039404d, 0x0039404d, 0x0038414e, 0x0038404c, 0x00353c49, 0x00323945, 0x00313944, 0x00333a45, 0x00353b48, 0x00363c49, 0x00353b48, 0x00333b46, 0x00303844, 0x002f3742, 0x002f3441, 0x002e3440, 0x002f3440, 0x00303742, 0x002f3540, 0x002c333f, 0x002c333f, 0x002c333f, 0x002c3440, 0x002b333e, 0x0029303c, 0x00282f3b, 0x00282e38, 0x00242c34, 0x00212933, 0x00202a34, 0x00202934, 0x00212834, 0x00202833, 0x00212832, 0x00212832, 0x00202730, 0x001f262f, 0x0020262f, 0x00202730, 0x001f2730, 0x001e2730, 0x00212b34, 0x00242e38, 0x00242e38, 0x00222c36, 0x00232d38, 0x00252f3b, 0x00252f3c, 0x0027303d, 0x0028313e, 0x0028303d, 0x0028303d, 0x0029323e, 0x002a323e, 0x0028303b, 0x00252c37, 0x00242a33, 0x0021282f, 0x001d242c, 0x00191f27, 0x00141b22, 0x001c242c, 0x00253239, 0x00202f37, 0x001e2c35, 0x001f2d38, 0x001e2c35, 0x001b2832, 0x001c2832, 0x00141e28, 0x000c1620, 0x000d1820, 0x00111b22, 0x00141c24, 0x00141c23, 0x00151d24, 0x00151e24, 0x00141d24, 0x00161e27, 0x0019222b, 0x001f2831, 0x00242d38, 0x00242f39, 0x00202b35, 0x001e2833, 0x001d2833, 0x00202b37, 0x0024303c, 0x00283542, 0x002b3846, 0x002c3a4a, 0x002c3c4c, 0x002c3d4c, 0x002c3e4c, 0x002c3f4e, 0x00304252, 0x00304454, 0x002f4454, 0x002f4555, 0x00304655, 0x00304556, 0x002d4252, 0x00243848, 0x00182b39, 0x00122331, 0x00122130, 0x0011202c, 0x000f1d2a, 0x000d1c28, 0x000e1b27, 0x000e1b25, 0x000e1c25, 0x000d1c25, 0x000f1c25, 0x00101c26, 0x00101c26, 0x00101d27, 0x00101d27, 0x00111d27, 0x00111d27, 0x00121e28, 0x00131f28, 0x00131f28, 0x00131f28, 0x00131f28, 0x00121e28, 0x00121e28, 0x00121e28, 0x00111c27, 0x00101c26, 0x00101b25, 0x000f1a23, 0x000e1922, 0x000e1822, 0x000d1821, 0x000c1720, 0x000b151e, 0x000b151e, 0x000b151e, 0x000a141d, 0x000a141d, 0x000b151e, 0x000b151e, 0x000a141d, 0x0009141c, 0x0009141c, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4245, 0x001b4649, 0x001d4b4e, 0x0020616f, 0x002c9bc0, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002fa3ca, 0x0030a3ca, 0x0030a4ca, 0x0030a4ca, 0x0030a4ca, 0x0030a4ca, 0x0030a4ca, 0x0030a3ca, 0x0030a3ca, 0x0030a3ca, 0x002fa3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002da2ca, 0x002da2ca, 0x002ca1ca, 0x002ca2cb, 0x002994b8, 0x001d4c50, 0x001b4649, 0x001a4245, 0x00183d41, 0x0017383c, 0x00153439, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010212c, 0x0010202c, 0x0010202f, 0x00102130, 0x0010202f, 0x0010202f, 0x0010202f, 0x0010202d, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x000f202b, 0x000e202b, 0x000e202b, 0x000e202b, 0x000e202b, 0x0011212c, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0014222d, 0x0014222d, 0x0014222d, 0x0014222d, 0x0014222d, 0x00142230, 0x00132231, 0x00132231, 0x00132231, 0x00132231, 0x00122230, 0x00102130, 0x0010212f, 0x0010202c, 0x0010202c, 0x0010202b, 0x00111f2b, 0x00111f2b, 0x00101e29, 0x00101e29, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a25, 0x000d1b24, 0x000d1b24, 0x000e1c26, 0x0012202b, 0x001c2835, 0x0028333f, 0x00242f39, 0x001c2630, 0x0019212c, 0x001c232e, 0x00212833, 0x00212934, 0x00202934, 0x001c2630, 0x0019232e, 0x001a242f, 0x001e2a33, 0x001e2a33, 0x001c272f, 0x001b252e, 0x001c2730, 0x001c2730, 0x001a242d, 0x0019222c, 0x00202833, 0x0028323d, 0x002e3844, 0x00303945, 0x002f3b47, 0x00303c48, 0x002f3b47, 0x002c3a44, 0x002c3842, 0x002a3540, 0x0025303a, 0x00263038, 0x00262e38, 0x00202832, 0x00202730, 0x00212832, 0x00222832, 0x00202830, 0x001f2730, 0x00202830, 0x00222a33, 0x00242c35, 0x00242c37, 0x00272f3a, 0x0028303c, 0x00292f3b, 0x00272d39, 0x00272d39, 0x002c313d, 0x002f3641, 0x002f3741, 0x002c343e, 0x00272f3a, 0x00252d38, 0x00252d38, 0x00252d36, 0x00282f38, 0x002b313c, 0x002e3440, 0x00303543, 0x00303644, 0x00313845, 0x00343c48, 0x00373f4c, 0x0038404c, 0x0037404d, 0x0038414e, 0x00394350, 0x003c4553, 0x003e4856, 0x003f4957, 0x003f4957, 0x003d4654, 0x003c4453, 0x003c4553, 0x003d4755, 0x003e4856, 0x003e4957, 0x00404b5a, 0x00424c5d, 0x00444c5e, 0x00434c5d, 0x00424b5b, 0x003e4754, 0x003d4553, 0x003d4552, 0x003d4551, 0x003d4551, 0x003f4753, 0x003f4654, 0x00404754, 0x00404755, 0x003f4754, 0x003e4653, 0x003d4552, 0x003d4451, 0x003e4452, 0x00404654, 0x00404854, 0x003f4654, 0x003c4452, 0x00444c5a, 0x00464e5c, 0x00414a58, 0x00404a58, 0x00404958, 0x00404858, 0x0041495a, 0x00424a58, 0x00424b59, 0x00404857, 0x00404756, 0x003f4454, 0x003e4654, 0x00404755, 0x003f4554, 0x003c4251, 0x003c4250, 0x003c424f, 0x003a424f, 0x0038404d, 0x00353d4a, 0x00333b47, 0x00323a45, 0x00333b46, 0x00363c49, 0x00363c49, 0x00363c49, 0x00343c47, 0x00313a44, 0x00303843, 0x00303643, 0x002f3440, 0x002e3440, 0x00303541, 0x00303540, 0x002d333e, 0x002b333e, 0x0028333d, 0x0027323c, 0x0028323c, 0x0027313c, 0x0028313c, 0x0028313a, 0x00252f37, 0x00222c35, 0x00222c37, 0x00242d38, 0x00242e39, 0x00252e39, 0x00252d38, 0x00242c37, 0x00212a33, 0x00202830, 0x0020262f, 0x001e242e, 0x001d242e, 0x00202831, 0x00242d36, 0x00242d36, 0x0027303a, 0x00242e38, 0x00242e39, 0x00252f3c, 0x00242e3b, 0x0027303c, 0x0028323f, 0x0027303c, 0x0025303c, 0x0028323c, 0x0029313c, 0x00272f3a, 0x00242b36, 0x00242a33, 0x00222930, 0x0020262e, 0x001a2128, 0x00131c21, 0x00152025, 0x00233137, 0x0024343b, 0x001a2c33, 0x001d2c36, 0x00202e38, 0x001f2b34, 0x001f2a34, 0x0016202a, 0x000d1720, 0x000a141d, 0x000c161e, 0x00101a21, 0x00151f26, 0x00182229, 0x00182229, 0x0018222a, 0x001a242d, 0x001e2831, 0x00202a34, 0x00202b34, 0x001e2833, 0x001d2733, 0x001f2834, 0x00202a36, 0x00242d3a, 0x00283240, 0x00283544, 0x002b3846, 0x002b3848, 0x002b3a48, 0x002b3a48, 0x002b3a49, 0x002c3d4c, 0x00304152, 0x00304455, 0x00304758, 0x00324a5a, 0x00324a5a, 0x00314858, 0x002c4150, 0x00243746, 0x00172837, 0x0012212f, 0x0011202c, 0x00101e2a, 0x000f1c28, 0x000e1b27, 0x000e1a26, 0x000d1a25, 0x000c1b24, 0x000c1b24, 0x000d1c25, 0x000f1c26, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101e28, 0x00121e28, 0x00121e28, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f28, 0x00121e28, 0x00111d27, 0x00101c26, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000c1822, 0x000c1821, 0x000c161f, 0x000b151e, 0x000b151e, 0x0009141c, 0x0009141d, 0x000a141d, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00132c32, 0x00143036, 0x00153439, 0x00183a3e, 0x00183f43, 0x001a4347, 0x001c484c, 0x001e4d50, 0x00237085, 0x002da3cb, 0x0028819c, 0x00267081, 0x00277282, 0x00277383, 0x00277484, 0x00277484, 0x00287484, 0x00287484, 0x00277484, 0x00277484, 0x00287484, 0x00277484, 0x00267383, 0x00277383, 0x00277282, 0x00267181, 0x00257181, 0x00267081, 0x00267081, 0x00267081, 0x00267081, 0x00267081, 0x00267081, 0x00267081, 0x00267181, 0x00267081, 0x00257081, 0x00257080, 0x00256e80, 0x00246d7f, 0x002991b2, 0x002a9ac0, 0x001d4d51, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00143439, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010212c, 0x0010212c, 0x0010212f, 0x00102130, 0x00102030, 0x0010202f, 0x0010202f, 0x0010202d, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x000f202b, 0x000d202b, 0x000d202b, 0x000d202b, 0x000e202b, 0x0011212c, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0014232e, 0x0014232e, 0x0015232e, 0x0015232e, 0x00142331, 0x00142433, 0x00142433, 0x00142433, 0x00142333, 0x00132331, 0x000f2230, 0x000f222f, 0x0010202c, 0x0010202c, 0x0011202b, 0x00111f2b, 0x00111f2b, 0x00101e29, 0x00101e29, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000d1a26, 0x000d1a26, 0x000c1a26, 0x000c1925, 0x000d1a25, 0x000d1b24, 0x000d1b24, 0x000e1c26, 0x00111f2a, 0x00182532, 0x0025303c, 0x0028303a, 0x001f2731, 0x001c212d, 0x001e2430, 0x00212833, 0x00212833, 0x001c262f, 0x001b242d, 0x0018222c, 0x0018222c, 0x001c2730, 0x001c2830, 0x001a252d, 0x001c262f, 0x001d2830, 0x001f2831, 0x001b252e, 0x0019232c, 0x00202830, 0x0029323c, 0x002e3844, 0x002f3a46, 0x002f3b48, 0x00303c48, 0x002f3c48, 0x002c3a45, 0x002b3944, 0x002a3641, 0x0025313c, 0x0028333c, 0x00273038, 0x00202832, 0x00202932, 0x00202830, 0x0020282f, 0x00202831, 0x00222c34, 0x00242e37, 0x00252d37, 0x00262e38, 0x00262f38, 0x0028313c, 0x002a333d, 0x0029313c, 0x00262f39, 0x00252e38, 0x00272f38, 0x002a323b, 0x002c353e, 0x002c343e, 0x0028303b, 0x00262e38, 0x00252e38, 0x00252d36, 0x00282d38, 0x002a303a, 0x002d333e, 0x002e3440, 0x002f3442, 0x00313845, 0x00343c48, 0x00343c49, 0x00353d4a, 0x00363e4b, 0x0036404c, 0x00384250, 0x003c4654, 0x003f4958, 0x003f4a58, 0x00404b59, 0x00404958, 0x003f4858, 0x003e4857, 0x00404958, 0x00404a59, 0x00404c5a, 0x00414e5d, 0x00445061, 0x00465062, 0x00485163, 0x00444d5d, 0x003d4754, 0x003e4754, 0x003e4652, 0x003c4550, 0x003d4652, 0x00414a57, 0x00414957, 0x00404857, 0x00414958, 0x00414958, 0x00404854, 0x003f4754, 0x00404754, 0x00404754, 0x00414855, 0x00444b59, 0x00434b59, 0x003d4554, 0x00434b59, 0x00454c5c, 0x00414b59, 0x00434c5b, 0x00424b5b, 0x00404858, 0x00424a5b, 0x00444c5b, 0x00424c5a, 0x00404a58, 0x00414958, 0x00414857, 0x00404856, 0x00404856, 0x003f4655, 0x003c4251, 0x003c4250, 0x003c4350, 0x003b4350, 0x003a424f, 0x0038404c, 0x00353d49, 0x00343c47, 0x00343c48, 0x00363c49, 0x00353c48, 0x00353c48, 0x00333a46, 0x00303844, 0x00303742, 0x00303643, 0x002f3441, 0x002e343f, 0x002f3540, 0x002f3540, 0x002c333e, 0x002b343e, 0x0028343d, 0x0024303b, 0x0024303a, 0x0027323c, 0x0028323c, 0x0027313b, 0x0027313a, 0x0028333c, 0x002a3440, 0x002a3440, 0x00293440, 0x00293340, 0x0027313c, 0x0026303a, 0x00232c36, 0x00212834, 0x00212832, 0x00202831, 0x001e2630, 0x00232b34, 0x0028303a, 0x00263039, 0x0028323d, 0x0026303a, 0x0026303b, 0x0028313e, 0x0027303d, 0x0028323e, 0x0029333f, 0x0026303c, 0x00242e39, 0x0026303b, 0x0028303b, 0x00262e38, 0x00242a35, 0x00232932, 0x00222830, 0x0020272e, 0x001a2028, 0x00141c22, 0x00121d23, 0x00202d34, 0x00283940, 0x001b2c34, 0x001a2933, 0x00202d37, 0x00202c36, 0x001e2833, 0x001b242f, 0x00151f28, 0x00121c24, 0x00111c22, 0x00111c23, 0x00141f27, 0x0019232c, 0x001b252f, 0x001b2530, 0x001b2530, 0x001e2833, 0x001e2833, 0x001b2630, 0x001b2530, 0x001d2833, 0x00202a37, 0x00242d39, 0x0026303c, 0x002b3542, 0x002d3947, 0x002d3b49, 0x002c3948, 0x002a3846, 0x00293845, 0x00293946, 0x002c3c4c, 0x002f4051, 0x002f4354, 0x002f4858, 0x00304a5a, 0x00344b5c, 0x00304656, 0x00293c4c, 0x001f313f, 0x00152533, 0x0010202c, 0x00101f2a, 0x000f1c28, 0x000e1c27, 0x000e1b26, 0x000d1925, 0x000d1925, 0x000c1b24, 0x000c1b24, 0x000d1c25, 0x000f1c26, 0x00101d27, 0x00101e28, 0x00101e28, 0x00111e28, 0x00121e28, 0x00121e28, 0x0014202a, 0x0014202a, 0x0014202a, 0x0014202a, 0x0014202a, 0x00131f29, 0x00131f29, 0x00121e28, 0x00111d27, 0x00111c27, 0x00101b25, 0x000e1a24, 0x000e1a24, 0x000c1823, 0x000c1822, 0x000c1720, 0x000b161f, 0x000b151e, 0x0009141c, 0x0009141d, 0x000a141d, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00122c32, 0x00143036, 0x0015363b, 0x00173a3e, 0x00194044, 0x001b4448, 0x001c4a4d, 0x001e4f51, 0x00247286, 0x002ea3ca, 0x0026768a, 0x00245c5f, 0x00245e60, 0x00245f61, 0x00256163, 0x00256163, 0x00266264, 0x00266264, 0x00256163, 0x00256163, 0x00256163, 0x00246062, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x00235a5c, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0022585b, 0x00215659, 0x00288baa, 0x002a9ac0, 0x001d4f53, 0x001c484c, 0x001b4448, 0x00183f43, 0x00183a3e, 0x0015363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010202c, 0x0010202c, 0x0010202f, 0x0010202f, 0x0010202f, 0x00102130, 0x00102130, 0x0010202e, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202c, 0x000e212c, 0x000e212c, 0x000f222c, 0x000f222c, 0x0011222c, 0x0011232d, 0x0012232d, 0x0014232e, 0x0014232e, 0x0014232e, 0x0014232e, 0x0014232e, 0x0015232e, 0x0015232e, 0x00142331, 0x00142433, 0x00142433, 0x00142433, 0x00142433, 0x00132332, 0x00102330, 0x00102330, 0x0010212e, 0x0010212e, 0x0012202d, 0x0013202d, 0x0013202c, 0x00111f2c, 0x00111f2c, 0x00101e2a, 0x000e1d28, 0x000e1d28, 0x000f1d28, 0x000f1c28, 0x000e1c28, 0x000c1b26, 0x000c1a26, 0x000c1924, 0x000b1824, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1b25, 0x00101e28, 0x00182430, 0x00242f3b, 0x002a313c, 0x00242a34, 0x00202630, 0x00202732, 0x00222833, 0x00222832, 0x001e2830, 0x001c242f, 0x001a232d, 0x0019232c, 0x001b252e, 0x001b262f, 0x0019242c, 0x001c262f, 0x001e2830, 0x00202a33, 0x001d2730, 0x001a232c, 0x00202932, 0x0028333d, 0x002d3844, 0x002f3b47, 0x00303c48, 0x00313c48, 0x00303c48, 0x002c3a46, 0x002b3844, 0x00283440, 0x0025313c, 0x0026313b, 0x00252e37, 0x00202831, 0x00232c34, 0x001e2630, 0x001d252e, 0x001d2730, 0x00232c35, 0x0028323b, 0x0029343c, 0x0029333c, 0x0028323b, 0x0029343c, 0x002b343e, 0x002b333d, 0x0028313c, 0x00272f39, 0x00272f38, 0x00283039, 0x0028303a, 0x002a323c, 0x0029313c, 0x0028303b, 0x0028303a, 0x00272f38, 0x00282e39, 0x00293039, 0x002c323c, 0x002c323d, 0x002c333f, 0x002d3540, 0x002f3844, 0x00323a47, 0x00343c49, 0x00353d4a, 0x0037404c, 0x00394351, 0x003c4655, 0x003e4858, 0x00404a5a, 0x00414c5c, 0x00434c5d, 0x00454f5f, 0x00434c5d, 0x00444d5f, 0x00455060, 0x00445060, 0x00445162, 0x00485364, 0x00485365, 0x00495364, 0x00444e5e, 0x00404957, 0x00404855, 0x00404854, 0x003e4653, 0x003f4854, 0x00434c59, 0x00444c5b, 0x00434b5a, 0x00444c5b, 0x00434a59, 0x00404857, 0x00414857, 0x00434958, 0x00404857, 0x00424a58, 0x00444c5b, 0x00474f5d, 0x00414958, 0x00424a5a, 0x00444c5c, 0x00424c5c, 0x00444d5c, 0x00444c5c, 0x00444c5c, 0x00454d5e, 0x00475060, 0x00444e5d, 0x00444d5c, 0x0048505f, 0x00495160, 0x00444d5c, 0x00404958, 0x00404755, 0x003c4351, 0x003c4251, 0x003c4250, 0x003b4350, 0x003b4350, 0x003b4350, 0x0039414e, 0x00373f4b, 0x00343c48, 0x00343b48, 0x00333947, 0x00313844, 0x00303742, 0x002e3641, 0x002e3641, 0x00303542, 0x002f3441, 0x002d343f, 0x002f3440, 0x002f3540, 0x002c333e, 0x002c3440, 0x002b3640, 0x00293540, 0x0026323c, 0x0028343d, 0x0028343d, 0x002a353f, 0x002c3841, 0x002b3641, 0x002c3844, 0x002c3844, 0x002c3844, 0x002c3743, 0x00293440, 0x0026303b, 0x00242d38, 0x00232c37, 0x00272e39, 0x0028303b, 0x00242c37, 0x00242c37, 0x00262e3a, 0x0027303c, 0x00293440, 0x0028323d, 0x0028333d, 0x002b3441, 0x002b3441, 0x002b3441, 0x002a3440, 0x0026303c, 0x00222c38, 0x00242e38, 0x00272f39, 0x00262e38, 0x00242b35, 0x00232933, 0x00222831, 0x001f262e, 0x00192028, 0x00141c23, 0x00121d23, 0x001f2c33, 0x00293a40, 0x001e2f36, 0x00182730, 0x001a2731, 0x001e2a34, 0x001e2833, 0x001e2731, 0x001c242f, 0x0019222b, 0x00182228, 0x00162028, 0x00162028, 0x0018212c, 0x001a242e, 0x0018242e, 0x0018232d, 0x001c2731, 0x001c2831, 0x001b2630, 0x001d2833, 0x00202936, 0x00232c38, 0x0026303c, 0x0029323f, 0x002d3844, 0x00303c4a, 0x00303d4c, 0x002e3b4a, 0x002b3846, 0x00293845, 0x00293846, 0x002b3c4b, 0x002e4050, 0x002d4354, 0x002e4758, 0x00304858, 0x00324a5a, 0x002f4454, 0x00233745, 0x00182a38, 0x0011212e, 0x000f1f2a, 0x000e1d28, 0x000f1c28, 0x000e1c27, 0x000d1a26, 0x000d1925, 0x000d1a25, 0x000c1b24, 0x000c1c25, 0x000e1c26, 0x00101d27, 0x00101e28, 0x00101e28, 0x00111f28, 0x00111f29, 0x00111f29, 0x00122029, 0x0014202c, 0x0014202c, 0x0014202c, 0x0015202c, 0x0015202c, 0x0014202c, 0x0014202b, 0x00131f2a, 0x00121e29, 0x00111d28, 0x00101c27, 0x00101b27, 0x000f1a26, 0x000e1a25, 0x000d1924, 0x000c1821, 0x000c1720, 0x000b161f, 0x000b151e, 0x000b151e, 0x000a151f, 0x000a161e, 0x000a151d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00122c32, 0x00153036, 0x0016363b, 0x00173c40, 0x00194044, 0x001b4649, 0x001d4b4e, 0x001e4f51, 0x00247286, 0x002ea3ca, 0x0027778a, 0x00245d60, 0x00245f61, 0x00256163, 0x00256264, 0x00256364, 0x00256364, 0x00256364, 0x00256364, 0x00256364, 0x00256264, 0x00256163, 0x00246062, 0x00245f61, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00245c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x0021585b, 0x0021575a, 0x00298dac, 0x002a9ac0, 0x001d4f53, 0x001c484c, 0x001b4448, 0x00183f43, 0x00183a3e, 0x0015363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010202c, 0x0010202c, 0x0010202e, 0x0010202f, 0x0010202f, 0x00102130, 0x00102130, 0x0010202e, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010212c, 0x000f222c, 0x000f222c, 0x0010232d, 0x0010232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0014242e, 0x0014242f, 0x0014242e, 0x0014232e, 0x0013232e, 0x0014232e, 0x0014232e, 0x00142331, 0x00142433, 0x00142433, 0x00142433, 0x00142433, 0x00142433, 0x00112432, 0x00112432, 0x0011232f, 0x0011232f, 0x0013212e, 0x0014202e, 0x0014202e, 0x0013202d, 0x0013202d, 0x00101f2b, 0x000e1e28, 0x000e1d28, 0x00101d28, 0x00101d28, 0x000e1c28, 0x000c1b26, 0x000c1b26, 0x000b1824, 0x000b1824, 0x000b1824, 0x000c1924, 0x000c1924, 0x000d1b24, 0x00111e28, 0x00182530, 0x0025303c, 0x002c3541, 0x002b323d, 0x00272c38, 0x00242a35, 0x00242a34, 0x00242c34, 0x00222a34, 0x001d2530, 0x001b2430, 0x0019232f, 0x001b252f, 0x001b252e, 0x0019242c, 0x001e2830, 0x001f2831, 0x00202a32, 0x001c262e, 0x0018232c, 0x00212c34, 0x0029343f, 0x002d3844, 0x002f3c48, 0x00313d49, 0x00323d49, 0x00303d48, 0x002e3c47, 0x002c3945, 0x00283440, 0x0025313c, 0x00243039, 0x00222c34, 0x00212a33, 0x00232c34, 0x001f2730, 0x001d252f, 0x001b242d, 0x001f2831, 0x00212c34, 0x00242d37, 0x0027313a, 0x0028323b, 0x0029333c, 0x0028333c, 0x0029323c, 0x0029323c, 0x0029323c, 0x0028303a, 0x00283038, 0x00273038, 0x00283039, 0x0028313c, 0x00262f39, 0x00242d38, 0x00272e38, 0x00292f3a, 0x00282f39, 0x0029303b, 0x00282e3a, 0x0028303b, 0x002a323c, 0x002c3440, 0x00303845, 0x00343c49, 0x00353d4a, 0x00353e4b, 0x0036404e, 0x003a4453, 0x003c4757, 0x00404a5a, 0x00424d5d, 0x00445060, 0x00465061, 0x00445061, 0x00465062, 0x00455163, 0x00455263, 0x00475465, 0x004a5468, 0x004a5568, 0x004a5568, 0x00455060, 0x00424d5c, 0x00434c59, 0x00424b58, 0x00404a58, 0x00424c5a, 0x00475060, 0x00485261, 0x00464f5f, 0x00485060, 0x00424a5a, 0x00404859, 0x00444b5c, 0x00454c5c, 0x00434a5b, 0x00434b5b, 0x00454d5c, 0x00485060, 0x00485060, 0x00444c5e, 0x00464e5f, 0x00444e5f, 0x00454e5f, 0x00454e5f, 0x00485061, 0x00485263, 0x00485262, 0x00465060, 0x00444e5e, 0x00485060, 0x00495261, 0x00485160, 0x00454f5e, 0x00444c5b, 0x00414757, 0x00404654, 0x003e4554, 0x003c4451, 0x003c4450, 0x003c4451, 0x0039414e, 0x00373f4c, 0x00343c48, 0x00343b48, 0x00323846, 0x00313844, 0x002f3742, 0x002e3641, 0x002f3641, 0x00303542, 0x00303542, 0x002f3540, 0x002f3540, 0x002e3440, 0x002c333e, 0x002c333e, 0x002a343f, 0x002a343f, 0x0027313c, 0x0026303b, 0x0027313c, 0x0028353f, 0x002c3842, 0x002b3843, 0x002a3844, 0x002a3844, 0x002c3844, 0x002b3843, 0x0026313c, 0x00242f39, 0x00222d38, 0x00212b35, 0x00232c36, 0x00262e39, 0x0028303c, 0x0029313d, 0x002a313f, 0x002b3441, 0x002b3441, 0x0028323e, 0x002a343e, 0x002c3542, 0x002c3542, 0x002c3542, 0x002b3441, 0x002a3440, 0x0026303c, 0x00232e38, 0x00242d38, 0x00242d38, 0x00242b36, 0x00232933, 0x00232933, 0x00202730, 0x001c222a, 0x00141d23, 0x00141f24, 0x001e292f, 0x002c383f, 0x0024333a, 0x001a2831, 0x0016222c, 0x0019252f, 0x001c2731, 0x001f2832, 0x001f2730, 0x001c252d, 0x001a232a, 0x00182028, 0x00162028, 0x00172029, 0x0018202c, 0x0018212c, 0x0018242e, 0x001c2831, 0x001c2832, 0x00202a34, 0x00202a36, 0x00222c38, 0x00252f3c, 0x0029323f, 0x002e3643, 0x00313c48, 0x0034404d, 0x0033404e, 0x00303d4c, 0x002c3947, 0x00293845, 0x00293947, 0x002b3c4c, 0x002d4050, 0x002c4253, 0x002c4454, 0x002d4656, 0x002f4657, 0x002b4050, 0x001e3140, 0x00132432, 0x000e1f2c, 0x000d1d29, 0x000e1c28, 0x000f1c28, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1a25, 0x000c1c25, 0x000d1c26, 0x000f1d27, 0x00101d27, 0x00101e28, 0x00111f29, 0x00111f29, 0x00111f29, 0x00122029, 0x0013202a, 0x0014212c, 0x0014222d, 0x0015212d, 0x0016212d, 0x0016212d, 0x0015202c, 0x0015202c, 0x0014202c, 0x00131f2b, 0x00121e2a, 0x00111c28, 0x00101c28, 0x00101b27, 0x000e1a26, 0x000d1925, 0x000c1822, 0x000c1820, 0x000c1720, 0x000c161f, 0x000c161f, 0x000a151f, 0x000a161e, 0x000a151d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x000f2229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00153036, 0x0016363b, 0x00183c40, 0x001a4044, 0x001b4649, 0x001d4b4e, 0x001f5053, 0x00247286, 0x002ea3ca, 0x0027778a, 0x00245d60, 0x00245f61, 0x00266163, 0x00256264, 0x00256364, 0x00276466, 0x00276466, 0x00276466, 0x00266466, 0x00256364, 0x00256264, 0x00256163, 0x00246062, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0022595c, 0x00277c94, 0x002ca0c8, 0x00288eaf, 0x001d4c50, 0x001c484c, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00143439, 0x00143036, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010202c, 0x0010202c, 0x0010202e, 0x0010202f, 0x0010212f, 0x00112130, 0x00112130, 0x0011202d, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010212c, 0x0010232d, 0x0010232d, 0x0011232d, 0x0011232d, 0x0012232d, 0x0012232d, 0x0012232e, 0x0014242e, 0x0014242f, 0x0014242f, 0x0014242f, 0x0014242f, 0x00142430, 0x00142430, 0x00142433, 0x00152434, 0x00152434, 0x00152434, 0x00152434, 0x00142433, 0x00112432, 0x00112432, 0x00122430, 0x00122430, 0x0013222f, 0x0014212e, 0x0014212e, 0x0013202e, 0x0013202d, 0x00101f2c, 0x000e1e29, 0x000e1d29, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000c1b27, 0x000c1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1924, 0x000c1924, 0x000d1b25, 0x00101e28, 0x00182530, 0x00263340, 0x00303a48, 0x00303946, 0x002c333f, 0x00262c38, 0x00252c35, 0x00262c36, 0x00242c34, 0x001e2631, 0x001c2430, 0x001b2431, 0x001c2630, 0x001c2630, 0x001c2630, 0x00202b34, 0x00202b34, 0x001f2931, 0x001a242c, 0x0019242c, 0x00222c37, 0x002a3441, 0x002e3945, 0x00303c48, 0x00333e4a, 0x00343f4b, 0x00323f4a, 0x00303e49, 0x002f3c48, 0x002a3743, 0x0025323d, 0x00222e39, 0x00202b34, 0x00242d36, 0x00242d36, 0x00222a33, 0x00202932, 0x00202a32, 0x00232c34, 0x00242d36, 0x00242d36, 0x00263038, 0x00263039, 0x00263038, 0x00263038, 0x00263039, 0x0029333c, 0x0029333c, 0x0028323b, 0x00283039, 0x00283038, 0x00283039, 0x00273039, 0x00242c37, 0x00232c36, 0x00232c34, 0x00242c36, 0x00242c35, 0x00252d38, 0x00242c37, 0x00252d38, 0x0028303b, 0x002c343f, 0x00303643, 0x00333a46, 0x00343c48, 0x00353e4b, 0x0038414f, 0x003b4453, 0x003e4858, 0x00404b5a, 0x00424d5c, 0x0044505f, 0x00445060, 0x00445061, 0x00465264, 0x00485466, 0x00485667, 0x00485567, 0x004b586a, 0x004c596c, 0x004c5869, 0x00455060, 0x00444f5c, 0x0044505c, 0x00444f5c, 0x00434e5d, 0x00444f5f, 0x00485364, 0x004a5566, 0x004a5465, 0x00485062, 0x0041495a, 0x00464e5e, 0x00495061, 0x00495061, 0x00474e5f, 0x00464d5e, 0x00475060, 0x00495161, 0x004b5464, 0x00495264, 0x00495264, 0x00485264, 0x00475163, 0x00465062, 0x00485364, 0x00495364, 0x00485262, 0x00454f5f, 0x00434d5c, 0x00465060, 0x00485363, 0x00485464, 0x00475261, 0x00454f5f, 0x00444c5b, 0x00424b5a, 0x00414a58, 0x003f4755, 0x003c4452, 0x003a414e, 0x00373e4b, 0x00343c48, 0x00313946, 0x00303844, 0x00313845, 0x00313845, 0x00303844, 0x002f3843, 0x002f3743, 0x00303642, 0x00303743, 0x00303743, 0x00303742, 0x002e3541, 0x002d3440, 0x002a313c, 0x0027303c, 0x0025303a, 0x00242f38, 0x0026303a, 0x0027323c, 0x002b3740, 0x002f3c46, 0x002f3c47, 0x002b3a44, 0x00293843, 0x002b3a44, 0x002a3842, 0x0027343e, 0x0027343f, 0x00232e3a, 0x00222c38, 0x00262f39, 0x002c343f, 0x00303844, 0x00313b47, 0x00303a46, 0x002e3844, 0x002a3441, 0x0028313d, 0x0029333e, 0x002b3441, 0x002c3542, 0x002c3543, 0x002c3643, 0x002c3542, 0x00293440, 0x0024303a, 0x00242d38, 0x00242c38, 0x00242a35, 0x00242934, 0x00242934, 0x00232833, 0x001f252e, 0x00171f26, 0x00141e24, 0x0019232b, 0x0028333b, 0x0029363f, 0x001e2a34, 0x0016222c, 0x0014202a, 0x001a242e, 0x0019222c, 0x001a232c, 0x001a232a, 0x00182027, 0x00141c24, 0x00141c24, 0x00161d26, 0x00181f29, 0x001b232d, 0x001c2630, 0x001d2831, 0x001f2934, 0x00212b35, 0x00232b37, 0x00242c38, 0x00262e39, 0x002b323e, 0x00303644, 0x00333c49, 0x00364250, 0x00344250, 0x00303e4e, 0x002c3a48, 0x00293847, 0x002a3a48, 0x002c3c4c, 0x002c4050, 0x002a4051, 0x002a4252, 0x002c4454, 0x002d4454, 0x00283c4c, 0x001b2c3b, 0x00122330, 0x000d1e2a, 0x000d1d28, 0x000d1c27, 0x000e1c27, 0x000c1a26, 0x000c1925, 0x000c1925, 0x000c1a25, 0x000c1c26, 0x000d1d27, 0x000f1d27, 0x00101e28, 0x00111f29, 0x0012202a, 0x0012202a, 0x0013212b, 0x0013212b, 0x0014212b, 0x0014222d, 0x0014222d, 0x0015222d, 0x0016212d, 0x0016212d, 0x0015212c, 0x0014202c, 0x0014202b, 0x00131f2b, 0x00131f2a, 0x00111d28, 0x00101c28, 0x00101b26, 0x000e1a25, 0x000d1924, 0x000c1822, 0x000c1820, 0x000c1720, 0x000c1620, 0x000c161f, 0x000b151f, 0x000a151e, 0x000a141e, 0x000a141e, 0x000a141e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00122c32, 0x00143036, 0x0015363b, 0x00183c40, 0x00194044, 0x001b4649, 0x001d4b4e, 0x001e4f51, 0x00247286, 0x002ea3ca, 0x0027778a, 0x00245c5f, 0x00245f61, 0x00256163, 0x00256264, 0x00256364, 0x00276466, 0x00276466, 0x00276466, 0x00276466, 0x00266466, 0x00256364, 0x00256264, 0x00266163, 0x00246062, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x00235a5c, 0x00225b60, 0x0028839c, 0x002da0c8, 0x00288cab, 0x001f575f, 0x001d4b4e, 0x001c474b, 0x001a4245, 0x00183d41, 0x0017383c, 0x00153439, 0x00142e34, 0x00122c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010212c, 0x0010212c, 0x0010212c, 0x0010212d, 0x0010212d, 0x0012212d, 0x0012212c, 0x0011202c, 0x0010202b, 0x0010202b, 0x0010202b, 0x0011202c, 0x0011222c, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0013232e, 0x0014232e, 0x0014232e, 0x0014242e, 0x0014242f, 0x00142430, 0x00142431, 0x00142431, 0x00142532, 0x00152633, 0x00142634, 0x00142634, 0x00142634, 0x00142634, 0x00142634, 0x00132534, 0x00122433, 0x00122433, 0x00132431, 0x00132430, 0x00132430, 0x0012222f, 0x0012222f, 0x0011222f, 0x0010212e, 0x0010202c, 0x00101f2c, 0x000f1e2c, 0x00101e29, 0x00101e29, 0x00101d28, 0x000e1c28, 0x000e1b28, 0x000d1a28, 0x000c1a28, 0x000c1a28, 0x000c1926, 0x000c1925, 0x000c1a25, 0x00101e29, 0x00182531, 0x00273442, 0x00313e4c, 0x00343e4c, 0x00303644, 0x00282d3a, 0x00262a35, 0x00282c35, 0x00262c34, 0x001f2831, 0x001d2732, 0x001f2834, 0x001e2833, 0x001c2731, 0x001d2833, 0x00212c37, 0x00212c35, 0x001e2831, 0x0018232a, 0x0018232c, 0x00222c38, 0x002b3441, 0x00303a46, 0x00323d49, 0x0034404c, 0x0034404c, 0x0033404b, 0x00303e49, 0x00303c48, 0x002e3945, 0x00283440, 0x00222d38, 0x00222c36, 0x00242e37, 0x00252f38, 0x00202b34, 0x00242d36, 0x00242c34, 0x00262e37, 0x002b313b, 0x00283039, 0x00262d36, 0x00242c35, 0x00242c36, 0x00272f38, 0x0028313a, 0x0028333c, 0x0028343c, 0x0028333b, 0x00273139, 0x0027313a, 0x00263038, 0x00242d36, 0x00272f38, 0x0028303a, 0x0029313b, 0x00242c36, 0x00212a33, 0x00262e38, 0x00262d38, 0x00242c38, 0x00272f3a, 0x002a323d, 0x002f3641, 0x00303844, 0x00323a46, 0x0037404c, 0x003a4450, 0x003b4451, 0x003c4755, 0x003c4856, 0x003e4b58, 0x0044505e, 0x0044505f, 0x00455061, 0x00465364, 0x00495868, 0x004a5a6a, 0x00495868, 0x004c5b6c, 0x004e5c6d, 0x00495666, 0x00434f5d, 0x00424d5b, 0x0044505f, 0x00465060, 0x00485163, 0x00495566, 0x00495667, 0x004a5567, 0x00495465, 0x00495264, 0x00485063, 0x004b5464, 0x004d5667, 0x004c5667, 0x004b5466, 0x00485363, 0x004b5565, 0x004b5565, 0x00495464, 0x004d586a, 0x004e586c, 0x004c5868, 0x004a5768, 0x00475566, 0x00485466, 0x00485364, 0x00445060, 0x00455261, 0x00465260, 0x00485161, 0x00485362, 0x00485563, 0x00465460, 0x0043505d, 0x00414e5c, 0x00414c5c, 0x003e4856, 0x003c4554, 0x003a4350, 0x0038404c, 0x00383e4a, 0x00343c49, 0x00323a47, 0x00303844, 0x00303844, 0x00303844, 0x002f3744, 0x002f3744, 0x002f3744, 0x002f3743, 0x00303844, 0x00323a47, 0x00333b48, 0x002f3845, 0x002b3541, 0x0029323d, 0x0026313c, 0x0025303a, 0x00263039, 0x0028343c, 0x00293540, 0x002a3740, 0x002b3842, 0x002a3842, 0x00283640, 0x0025333c, 0x0025333c, 0x00283640, 0x002c3a44, 0x00303d48, 0x002f3a47, 0x002d3844, 0x002f3844, 0x002e3843, 0x00303b47, 0x00323d49, 0x00323d49, 0x002f3a46, 0x002a3440, 0x0027313c, 0x0029333d, 0x002b3440, 0x002c3543, 0x002c3643, 0x002d3844, 0x002c3644, 0x002b3441, 0x0027313c, 0x00262f39, 0x00252d38, 0x00242c37, 0x00242b36, 0x00242b36, 0x00242a34, 0x00202730, 0x001b212b, 0x00161e26, 0x00171e28, 0x00212b34, 0x002b3440, 0x00202a35, 0x0018232c, 0x00152028, 0x00182128, 0x00171f28, 0x00161e27, 0x00151f25, 0x00131c24, 0x00111a21, 0x00141a23, 0x00161c26, 0x001a212b, 0x001d262f, 0x001d2830, 0x001e2830, 0x00212934, 0x00242b36, 0x00272c37, 0x00262b35, 0x00262b34, 0x002a2f3a, 0x00303643, 0x00353e4b, 0x00364250, 0x00324250, 0x002f3f4f, 0x002a3b49, 0x00283a49, 0x002b3d4d, 0x002d4051, 0x002c4051, 0x00283e4e, 0x0029404e, 0x002a4150, 0x002b4150, 0x00263947, 0x00182a37, 0x0011222f, 0x000d1e29, 0x000e1d28, 0x000e1c27, 0x000e1c27, 0x000d1b26, 0x000d1b26, 0x000c1a26, 0x000c1a26, 0x000c1c27, 0x000d1c28, 0x000e1d28, 0x000f1f28, 0x00102029, 0x0011202a, 0x0011202a, 0x0012212b, 0x0012212b, 0x0012212b, 0x0014222d, 0x0014222d, 0x0014222d, 0x0015212d, 0x0014212d, 0x0014222c, 0x0014212b, 0x0014202b, 0x0014202a, 0x00131f28, 0x00111d27, 0x00101c26, 0x00101b25, 0x000e1a24, 0x000d1924, 0x000c1822, 0x000c1820, 0x000c1720, 0x000c1620, 0x000b151f, 0x000a141f, 0x000a141f, 0x000a141f, 0x000a141f, 0x000a141f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00132c32, 0x00143036, 0x0015363b, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001c484c, 0x001d4d50, 0x00247186, 0x002ea3ca, 0x0026778b, 0x00245c60, 0x00246063, 0x00246164, 0x00256366, 0x00266468, 0x00266568, 0x00276568, 0x00276669, 0x00276669, 0x00276569, 0x00266468, 0x00256468, 0x00266467, 0x00256163, 0x00246062, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00245c5e, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x00235a5c, 0x0022595c, 0x00225d62, 0x002988a6, 0x002da1c8, 0x002785a1, 0x001f555b, 0x001d4d50, 0x001c4a4d, 0x001b4649, 0x00194044, 0x00183c40, 0x0016363b, 0x00143338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010212c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0012212c, 0x0012212c, 0x0011202c, 0x0010202b, 0x0010202b, 0x0010202b, 0x0011202c, 0x0011222c, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0013232e, 0x0014232e, 0x0014232e, 0x0014242e, 0x0014242f, 0x00142430, 0x00142431, 0x00142431, 0x00142532, 0x00152633, 0x00142634, 0x00142734, 0x00142734, 0x00142734, 0x00142734, 0x00132534, 0x00122433, 0x00122433, 0x00132431, 0x00142431, 0x00132430, 0x0011232f, 0x0011232f, 0x0011232f, 0x0010222e, 0x0010202c, 0x00101f2c, 0x000f1e2c, 0x00101e29, 0x00101e29, 0x00101d29, 0x000e1c28, 0x000e1b28, 0x000d1a28, 0x000d1a28, 0x000d1a28, 0x000c1926, 0x000c1925, 0x000c1a25, 0x00101e29, 0x00182531, 0x00283542, 0x00344050, 0x00384252, 0x00343c4b, 0x002c303e, 0x00242733, 0x00272833, 0x00282c34, 0x00222a34, 0x00212c35, 0x00242c38, 0x00232c37, 0x001d2a34, 0x001e2b34, 0x00222d38, 0x00212c35, 0x001c272f, 0x00162028, 0x0018232c, 0x00222c38, 0x002b3440, 0x002f3945, 0x00323c49, 0x0034404c, 0x0034404c, 0x0032404b, 0x00303e49, 0x00303d48, 0x00303c48, 0x002d3844, 0x0026323d, 0x0028323d, 0x002b3640, 0x002b353f, 0x00242f38, 0x002c343e, 0x00262e38, 0x00272f39, 0x002a303a, 0x00272d37, 0x00242b34, 0x00232b34, 0x00242c35, 0x00272f38, 0x0028313a, 0x00263039, 0x00253139, 0x00253139, 0x00243038, 0x0028333c, 0x0028333c, 0x002a333c, 0x0029333c, 0x0029343c, 0x0029343c, 0x0028323b, 0x00242f38, 0x002a343d, 0x002e3741, 0x002e3641, 0x002d3540, 0x002e3640, 0x00313944, 0x00343c49, 0x00323c48, 0x00323c49, 0x003a4450, 0x003b4453, 0x003e4857, 0x003e4b58, 0x00414e5b, 0x00455260, 0x00475261, 0x00465162, 0x00485465, 0x00485768, 0x00485869, 0x00485868, 0x004c5b6c, 0x004a586a, 0x00465364, 0x00465161, 0x00455060, 0x00475262, 0x004a5565, 0x004d586a, 0x00505c6e, 0x004e5b6c, 0x004a5568, 0x00495467, 0x004c5869, 0x004c5768, 0x004c5666, 0x004e5868, 0x004c5768, 0x004b5667, 0x004a5767, 0x004d5969, 0x004d5868, 0x00495565, 0x004f5c6d, 0x00505c70, 0x004e5c6d, 0x004c5b6c, 0x004b5a6b, 0x004c5a6b, 0x004a5668, 0x00465364, 0x00485667, 0x00495465, 0x004a5464, 0x00485363, 0x00465361, 0x00414f5c, 0x003c4b58, 0x003d4b59, 0x003c4857, 0x00384250, 0x003a4452, 0x003b4451, 0x0038404b, 0x0038404b, 0x00343d4a, 0x00323b48, 0x00313a47, 0x00313a46, 0x00303946, 0x00323a47, 0x00313a46, 0x00303844, 0x00303845, 0x00303945, 0x00303946, 0x00303a46, 0x002e3945, 0x002b3642, 0x002a3440, 0x0029343e, 0x002a343f, 0x002a3640, 0x002b3740, 0x00293640, 0x0028353f, 0x00293741, 0x002b3844, 0x002f3c48, 0x00303e49, 0x0032404a, 0x00313f4b, 0x00303e49, 0x0032404c, 0x00303c49, 0x002e3947, 0x002f3b47, 0x00303c48, 0x00323e4b, 0x00323f4b, 0x00343f4c, 0x00303c48, 0x002b3643, 0x0029343f, 0x002b3440, 0x002c3541, 0x002c3743, 0x002d3844, 0x002d3844, 0x002c3644, 0x002b3442, 0x0028313c, 0x0028303c, 0x00272f3a, 0x00262d38, 0x00262d38, 0x00262c38, 0x00252c36, 0x00232932, 0x001e252e, 0x00182029, 0x00161e27, 0x001c242e, 0x0028303c, 0x00212c35, 0x001b252d, 0x00152027, 0x00141d24, 0x00151d24, 0x00141c24, 0x00121c23, 0x00101a21, 0x00111920, 0x00141a23, 0x00181e28, 0x001d2630, 0x00202a34, 0x00202a33, 0x00202933, 0x00242c37, 0x00293039, 0x002b303a, 0x00272c35, 0x00242831, 0x00282d37, 0x00303742, 0x00363e4b, 0x00354250, 0x00314250, 0x002d404f, 0x002a3d4c, 0x00293d4c, 0x002b404f, 0x002c4152, 0x00293f50, 0x00273d4c, 0x00263c4b, 0x00283e4b, 0x00273c4a, 0x00203340, 0x00162733, 0x0010202d, 0x000c1e29, 0x000e1d28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000d1b26, 0x000d1a26, 0x000d1a26, 0x000c1c27, 0x000d1c28, 0x000e1d28, 0x000f1f28, 0x00102029, 0x0011202a, 0x0011202a, 0x0012212b, 0x0012212b, 0x0012212b, 0x0013222d, 0x0013222d, 0x0014222d, 0x0014222d, 0x0014222d, 0x0014222c, 0x0014212b, 0x0014202b, 0x0014202a, 0x00131f28, 0x00111d27, 0x00101c26, 0x00101b25, 0x000e1a24, 0x000d1924, 0x000c1821, 0x000c1820, 0x000c1720, 0x000c161f, 0x000b161f, 0x000a141f, 0x000a141f, 0x000a141f, 0x000a141f, 0x000a141f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00153439, 0x0017383c, 0x00183d41, 0x001a4347, 0x001c474b, 0x001d4c50, 0x00226b7d, 0x002da0c8, 0x002c99bd, 0x002c95b7, 0x002c96b7, 0x002d97b8, 0x002e98b8, 0x002f98b8, 0x002f99b9, 0x002f99b9, 0x003099ba, 0x003099ba, 0x002f9aba, 0x002f9aba, 0x002f9abb, 0x002f97b7, 0x0026666c, 0x00256163, 0x00246062, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x00235a5c, 0x0022595c, 0x00236068, 0x002a8eae, 0x002da0c8, 0x00267e98, 0x00205458, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x0016363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010202c, 0x0010202c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0012212c, 0x0012212c, 0x0011202c, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0011222c, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0013232e, 0x0014232e, 0x0014232f, 0x00142430, 0x00142430, 0x00142532, 0x00132533, 0x00142534, 0x00152634, 0x00152634, 0x00142634, 0x00132734, 0x00122734, 0x00142734, 0x00142734, 0x00132534, 0x00122433, 0x00122433, 0x00132432, 0x00142432, 0x00132432, 0x00112230, 0x00112230, 0x00112230, 0x00102230, 0x0010202d, 0x000e1f2a, 0x000e1e29, 0x000f1e29, 0x000f1e29, 0x000e1d29, 0x000d1c28, 0x000d1b28, 0x000d1a28, 0x000d1a28, 0x000d1a28, 0x000c1926, 0x000c1925, 0x000d1a26, 0x00101e29, 0x00182632, 0x00263442, 0x00344150, 0x003a4555, 0x00384050, 0x00313544, 0x00272936, 0x00242530, 0x00282a34, 0x00252c35, 0x00242c36, 0x00272f39, 0x00242e38, 0x00202c36, 0x001f2b35, 0x00232e38, 0x00232c36, 0x001b252d, 0x00172028, 0x001b232c, 0x00242c38, 0x002b3340, 0x00303844, 0x00333c48, 0x0035404c, 0x0035404c, 0x00343f4c, 0x00303d4a, 0x00303c49, 0x00313d4a, 0x00303c48, 0x002c3844, 0x002d3945, 0x00303c48, 0x002f3b45, 0x002a333f, 0x002b333f, 0x00272f3b, 0x00262e39, 0x00282e39, 0x00242b34, 0x00242a32, 0x00232b34, 0x00232b34, 0x00242c35, 0x0027303a, 0x00253039, 0x00233038, 0x00243139, 0x0024323b, 0x0025333c, 0x0026333c, 0x0028333c, 0x0028343c, 0x0029353e, 0x0029373f, 0x0029373f, 0x002a363f, 0x002c3841, 0x00303843, 0x00323a44, 0x00343c47, 0x00343c48, 0x00333c47, 0x00343d4a, 0x00394350, 0x0036404e, 0x00384250, 0x003e4857, 0x00404b5b, 0x00404c5b, 0x0044525e, 0x00485564, 0x00485465, 0x00485466, 0x00485568, 0x0049576a, 0x0049596c, 0x004a5a6e, 0x004c5b6f, 0x0048576c, 0x00485669, 0x00495668, 0x00495567, 0x00495567, 0x004c596a, 0x00525e70, 0x00556275, 0x00546074, 0x004b576a, 0x004c566a, 0x004d596c, 0x004c5869, 0x004c5768, 0x004c5868, 0x004b5768, 0x004a5768, 0x004a5769, 0x004b586a, 0x004c586a, 0x00485566, 0x004c596b, 0x00505d70, 0x004f5d70, 0x004e5d70, 0x004e5e70, 0x004d5c6e, 0x004a586a, 0x00485568, 0x004b586a, 0x004c586b, 0x004c576a, 0x004a5568, 0x00455263, 0x003e4c5b, 0x003a4957, 0x003b4958, 0x003a4557, 0x003a4454, 0x003b4453, 0x003a4450, 0x0038424c, 0x0037404c, 0x00343f49, 0x00323d48, 0x00333e48, 0x00323d49, 0x00303c48, 0x002f3b47, 0x00303b47, 0x00303c48, 0x00303c48, 0x002c3844, 0x0026333f, 0x0025313d, 0x0026333f, 0x002a3541, 0x002c3844, 0x002f3b45, 0x00303c46, 0x002d3944, 0x002a3842, 0x00283641, 0x002c3944, 0x00303e49, 0x00313f4b, 0x00313f4a, 0x002e3c48, 0x00303d48, 0x0033404d, 0x0033424f, 0x00303e4c, 0x00313c4c, 0x00374250, 0x00384452, 0x00384453, 0x00313e4c, 0x002f3c4a, 0x002f3c49, 0x002e3a48, 0x002c3846, 0x002d3844, 0x002e3944, 0x002f3a45, 0x002e3945, 0x002e3844, 0x002c3844, 0x002c3644, 0x002b3442, 0x0028323d, 0x0029333d, 0x0028323c, 0x0027303b, 0x00272f3a, 0x00262e39, 0x00262d38, 0x00232b34, 0x00202830, 0x001b242c, 0x00171f28, 0x0018202a, 0x00242c38, 0x00222c35, 0x001c262d, 0x00162027, 0x00141c23, 0x00141b22, 0x00141c24, 0x00111b22, 0x00111b22, 0x00141c23, 0x00181f26, 0x001d242e, 0x00202934, 0x00212c36, 0x00202b35, 0x00232c36, 0x00282f3a, 0x002c333c, 0x002c313c, 0x00262b34, 0x0022272f, 0x00262b34, 0x00303641, 0x00373f4c, 0x0034414f, 0x00304050, 0x002d4050, 0x002b404e, 0x0029404e, 0x0029404e, 0x00283f4f, 0x00273d4e, 0x00253c4a, 0x00243a48, 0x00223845, 0x00203441, 0x001a2c3a, 0x00122430, 0x000e1f2b, 0x000c1d28, 0x000e1d28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000d1b26, 0x000d1b27, 0x000d1c27, 0x000d1c28, 0x000e1d28, 0x000f1e28, 0x0010202b, 0x0011202b, 0x0011202b, 0x0012212c, 0x0012212c, 0x0012212c, 0x0013222d, 0x0013222d, 0x0014222d, 0x0014222d, 0x0014222d, 0x0013222c, 0x0013212b, 0x0013212b, 0x0013202a, 0x00111f28, 0x00101d27, 0x000f1c26, 0x000e1c25, 0x000d1a24, 0x000c1924, 0x000b1821, 0x000a1820, 0x000b1720, 0x000b161f, 0x000b161f, 0x0009141f, 0x0008141f, 0x0009141f, 0x000a141f, 0x000a141f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0013282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0016363b, 0x00183c40, 0x00194044, 0x001c4649, 0x001c4a4d, 0x001e4f53, 0x0024768d, 0x002c9abe, 0x002c9cc0, 0x002d9dc0, 0x002f9dc1, 0x00309ec1, 0x00309fc2, 0x00309fc2, 0x00309fc3, 0x0031a0c3, 0x0030a0c3, 0x0031a1c4, 0x0031a1c4, 0x0031a3c6, 0x0031a4ca, 0x00276970, 0x00256163, 0x00256062, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0023646e, 0x002b94b5, 0x002da0c6, 0x0025768c, 0x00205457, 0x001e4f51, 0x001d4c50, 0x001c484c, 0x001b4448, 0x00194044, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00122c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010202c, 0x0010202c, 0x0010212c, 0x0010222c, 0x0010222c, 0x0012212c, 0x0012212c, 0x0011202c, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0011222c, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0013232e, 0x0014232e, 0x00142330, 0x00142430, 0x00142431, 0x00142533, 0x00142734, 0x00142734, 0x00152634, 0x00152634, 0x00142634, 0x00122734, 0x00122734, 0x00142734, 0x00142734, 0x00132534, 0x00122433, 0x00122433, 0x00132433, 0x00142433, 0x00132432, 0x00112331, 0x00112230, 0x00112230, 0x00112230, 0x0010202e, 0x000e1f2a, 0x000e1f29, 0x000f1f29, 0x000f1f29, 0x000e1d29, 0x000c1c28, 0x000c1b28, 0x000d1a28, 0x000d1a28, 0x000d1a28, 0x000d1a27, 0x000d1a26, 0x000d1a26, 0x00101d29, 0x00182734, 0x00253544, 0x00324150, 0x003c4857, 0x003d4454, 0x00373b49, 0x002b2c39, 0x00242530, 0x00282a34, 0x00282c36, 0x00232b34, 0x00242d38, 0x00242c38, 0x00212c38, 0x001e2a36, 0x00212c38, 0x00232d37, 0x001e2830, 0x00182129, 0x001c252e, 0x00262d39, 0x002b3340, 0x002f3744, 0x00333c48, 0x0036404c, 0x0036404d, 0x00343f4d, 0x00303c4a, 0x00303c49, 0x00323e4c, 0x00323d49, 0x002f3a48, 0x0034404c, 0x003a4551, 0x0034404c, 0x002d3643, 0x0029313e, 0x00262e3b, 0x0028303b, 0x0029303a, 0x00272e36, 0x00272d34, 0x00252d35, 0x00242c35, 0x00242c35, 0x00273039, 0x0028333c, 0x0028343e, 0x002b3841, 0x002a3842, 0x002a3842, 0x002a3842, 0x002c3842, 0x002c3842, 0x002c3842, 0x002a3842, 0x002c3b44, 0x002d3b44, 0x002a3641, 0x00303844, 0x002d3741, 0x00303944, 0x00323c46, 0x00343e49, 0x00323c48, 0x0038424e, 0x003f4856, 0x003e4856, 0x003e4858, 0x00404c5d, 0x00414e5e, 0x00455260, 0x00495767, 0x00495669, 0x00495669, 0x004a576c, 0x004c5a6f, 0x004f5e74, 0x004f5f75, 0x004c5c71, 0x0049586d, 0x004a586d, 0x004c596c, 0x004b586b, 0x004c5a6c, 0x00505f70, 0x00566376, 0x00586578, 0x00546275, 0x004b586b, 0x004a5769, 0x004c586b, 0x004b586b, 0x004e5b6c, 0x004f5c6e, 0x004e5b6e, 0x004d5b6e, 0x004c5a6d, 0x004b586b, 0x004a576a, 0x00475465, 0x004a5768, 0x00505e70, 0x00526074, 0x00526275, 0x00506274, 0x00506074, 0x004c5a6e, 0x004c5a6f, 0x004b596e, 0x004c596c, 0x004c596c, 0x004b586b, 0x00465466, 0x003e4d5c, 0x003d4c5c, 0x003c4b5b, 0x003e4a5c, 0x00404859, 0x003e4757, 0x003b4452, 0x0038424e, 0x00343f4a, 0x0035414d, 0x00384450, 0x00384450, 0x0036434e, 0x00323f4b, 0x0032404c, 0x0034414c, 0x0034414d, 0x00313f4b, 0x002e3a46, 0x002f3a46, 0x00303c48, 0x002e3a46, 0x002c3844, 0x00303c48, 0x0033404b, 0x0034414c, 0x00313f4b, 0x00303d4a, 0x002e3c49, 0x00303e4b, 0x0035434f, 0x0034424e, 0x00374450, 0x00384552, 0x00384654, 0x00364452, 0x00334150, 0x00334251, 0x00364254, 0x00434f5f, 0x0043505f, 0x00414e5d, 0x00394755, 0x00334150, 0x002e3c4b, 0x00303c4b, 0x00303c4a, 0x00303c4b, 0x00323e4b, 0x00323d49, 0x002f3a46, 0x002c3844, 0x002c3643, 0x002c3544, 0x002b3442, 0x0029333e, 0x002a343e, 0x0029333e, 0x0028323c, 0x0027313c, 0x0027303b, 0x00272f39, 0x00242c35, 0x00222933, 0x001d242f, 0x00181f28, 0x00171f28, 0x00202934, 0x00212c34, 0x0019242b, 0x00141f25, 0x00131b22, 0x00131a22, 0x00141c25, 0x00141e25, 0x00161f26, 0x00182028, 0x001e242c, 0x00222934, 0x00222c36, 0x00232c37, 0x00232d38, 0x00262f39, 0x0029313c, 0x002c333c, 0x002c303b, 0x00262b34, 0x0022262f, 0x00262a34, 0x00303641, 0x00363e4c, 0x0032404d, 0x0030404f, 0x002e4150, 0x002c414f, 0x002a404f, 0x00283f4c, 0x00263d4c, 0x00253b4a, 0x00243947, 0x00233644, 0x001f3340, 0x001b2e3c, 0x00152835, 0x0010212c, 0x000c1e28, 0x000c1d28, 0x000f1d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000d1c28, 0x000d1c28, 0x000e1d28, 0x000f1e29, 0x0010202b, 0x0011202c, 0x0011202c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0013222d, 0x0013222d, 0x0014222d, 0x0014222d, 0x0014222d, 0x0013222c, 0x0012212b, 0x0012212b, 0x0013202a, 0x00111f28, 0x00101d27, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000c1924, 0x000b1822, 0x000a1820, 0x000a1820, 0x000b171f, 0x000b161f, 0x0009141f, 0x0008141f, 0x0009141f, 0x000a141f, 0x000a141f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00143036, 0x00143439, 0x00173a3e, 0x00183d41, 0x001a4347, 0x001c474b, 0x001c4a4d, 0x001e4f51, 0x00205357, 0x0020565a, 0x0022595c, 0x00235b5f, 0x00245d60, 0x00245f62, 0x00246064, 0x00256164, 0x00266366, 0x00256468, 0x00276568, 0x00276568, 0x002a7f92, 0x0031a4c9, 0x00276970, 0x00256364, 0x00266264, 0x00256062, 0x00245f61, 0x00245e60, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x00246876, 0x002c98bc, 0x002c9cc2, 0x00246f81, 0x00205254, 0x001e4f51, 0x001d4c50, 0x001c4a4d, 0x001b4649, 0x001a4245, 0x00183d41, 0x00183a3e, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0013282e, 0x0013242c, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000e1f2a, 0x000e1f2a, 0x000f202b, 0x0010212c, 0x0010212c, 0x0010212c, 0x0011202c, 0x0011202c, 0x0011202c, 0x0010202b, 0x0010202b, 0x0010202b, 0x0011202c, 0x0011222d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0013232e, 0x0013232e, 0x0013232f, 0x00142330, 0x00142430, 0x00142532, 0x00142634, 0x00142634, 0x00142534, 0x00142534, 0x00142634, 0x00122634, 0x00122634, 0x00132634, 0x00132634, 0x00132533, 0x00122432, 0x00122432, 0x00132432, 0x00132432, 0x00132432, 0x00112331, 0x00112230, 0x00102230, 0x00102130, 0x0010202e, 0x000f202c, 0x000e1f2c, 0x000e1e2b, 0x000e1e2b, 0x000e1d2a, 0x000d1c28, 0x000d1c28, 0x000d1b28, 0x000d1a28, 0x000d1a28, 0x000d1a28, 0x000d1a27, 0x000d1a28, 0x00101d2b, 0x00182634, 0x00223241, 0x002c3c4c, 0x00354454, 0x003c4656, 0x00393e4d, 0x00303340, 0x002a2b37, 0x002a2d38, 0x002a2d38, 0x00242934, 0x00212934, 0x00232c37, 0x00212c37, 0x001c2733, 0x001d2834, 0x00212c35, 0x001f2831, 0x001a222a, 0x001e2630, 0x0028303a, 0x002b3340, 0x002f3844, 0x00313c48, 0x00343f4b, 0x0036404d, 0x0034404d, 0x00303c4a, 0x002f3c4a, 0x00313f4c, 0x00313e4c, 0x00303d4c, 0x00343f4d, 0x003a4653, 0x00384450, 0x00343d4a, 0x002e3744, 0x002a323f, 0x002b323e, 0x002b313d, 0x002a313a, 0x002b333a, 0x002c343c, 0x002c343d, 0x002f3740, 0x00313942, 0x00313c45, 0x00343e48, 0x00333f4a, 0x00303d48, 0x00303d49, 0x00303d49, 0x00303c48, 0x00303c48, 0x00303d49, 0x00303e48, 0x002e3c45, 0x002e3b46, 0x002c3744, 0x00293340, 0x0029323f, 0x002b3440, 0x002c3742, 0x002f3a44, 0x00323e4a, 0x0037434f, 0x003b4652, 0x003c4856, 0x003d4958, 0x003e4b5c, 0x00404e60, 0x00465464, 0x00485668, 0x00485669, 0x0049576b, 0x004c596e, 0x004d5c71, 0x00506075, 0x004d5d74, 0x004d5d73, 0x004c5c72, 0x004d5c72, 0x004f5d72, 0x00505e73, 0x00526075, 0x0056657a, 0x0058667b, 0x00586579, 0x00536174, 0x004b586b, 0x004a576a, 0x004c596c, 0x004c5a6d, 0x00505d70, 0x00505e70, 0x00505d70, 0x004e5c70, 0x004b596c, 0x004a586b, 0x004b586a, 0x00475465, 0x00485568, 0x00536074, 0x00546276, 0x00536377, 0x00516478, 0x00526478, 0x00516177, 0x00506076, 0x004d5c72, 0x004b5a6e, 0x004c5a6d, 0x004a586c, 0x00485669, 0x00425162, 0x00425162, 0x00425061, 0x00414e5f, 0x00404b5c, 0x003f485a, 0x003c4655, 0x003b4453, 0x00364250, 0x00374450, 0x00394753, 0x003b4854, 0x00364450, 0x0033404c, 0x00394753, 0x00384550, 0x0034414c, 0x00313e4a, 0x00303c48, 0x00303c48, 0x00313d48, 0x00323f4a, 0x0034404c, 0x0035424e, 0x0036434f, 0x00384450, 0x00384552, 0x00384653, 0x00354350, 0x0032404d, 0x00344251, 0x00334050, 0x00344351, 0x00384655, 0x00384856, 0x00374656, 0x00374657, 0x003b4a5b, 0x003f4d5e, 0x00425060, 0x00404f5e, 0x0041505f, 0x00415060, 0x003f4e5d, 0x003c4959, 0x00384454, 0x00333f4e, 0x00344050, 0x00364150, 0x00343f4b, 0x002f3a46, 0x002c3843, 0x002c3643, 0x002c3643, 0x002c3542, 0x002a343f, 0x002b343f, 0x002a3440, 0x0029333e, 0x0028323c, 0x0028323c, 0x0028303a, 0x00242c35, 0x00242934, 0x00212530, 0x00191f28, 0x00161d25, 0x001e262e, 0x00242d34, 0x0018232a, 0x00141d24, 0x00131c23, 0x00131b24, 0x00171e27, 0x00182129, 0x001c252c, 0x00212830, 0x00242b34, 0x00242b35, 0x00242c37, 0x00252f39, 0x0028313c, 0x0028313c, 0x0028313c, 0x002b313c, 0x002c303a, 0x00282c36, 0x00242731, 0x00262a34, 0x002e3440, 0x00343c49, 0x00303e4b, 0x002e404d, 0x002d4150, 0x002c4250, 0x002a404e, 0x00273d4b, 0x00243a48, 0x00233745, 0x00223542, 0x001e313f, 0x001b2e3c, 0x00172937, 0x00132431, 0x000f202b, 0x000d1e29, 0x000d1e29, 0x000f1e29, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000e1c28, 0x000d1c28, 0x000d1c28, 0x000e1d28, 0x000e1e28, 0x00101f2a, 0x0011202c, 0x0011202c, 0x0012212c, 0x0012212c, 0x0013212c, 0x0013222d, 0x0013222d, 0x0014222d, 0x0014222d, 0x0014222d, 0x0013222c, 0x0012212b, 0x0012202b, 0x00122029, 0x00101e28, 0x00101d27, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000c1924, 0x000b1822, 0x000a1820, 0x000b181f, 0x000b171e, 0x000b161e, 0x0009151f, 0x0008141e, 0x0009141e, 0x000a141e, 0x000a141e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0016363b, 0x00183c40, 0x00183f43, 0x001a4347, 0x001c474b, 0x001d4b4e, 0x001e4f51, 0x001f5154, 0x00205457, 0x00215659, 0x0022595c, 0x00235c5e, 0x00245d60, 0x00245f61, 0x00246062, 0x00256264, 0x00256364, 0x00276466, 0x002a7f91, 0x0032a4c9, 0x00276a70, 0x00266466, 0x00256364, 0x00266264, 0x00246062, 0x00245e60, 0x00245d60, 0x00235c5e, 0x00256e7d, 0x002c9cc0, 0x002c99bd, 0x00236877, 0x00205254, 0x001e5053, 0x001d4c50, 0x001c4a4d, 0x001c4649, 0x001a4347, 0x00183f43, 0x00183c40, 0x0016363b, 0x00143338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1d28, 0x000d1e28, 0x000e2028, 0x000f2029, 0x0010202a, 0x0010202a, 0x0010202a, 0x0010202b, 0x0011202c, 0x0012212c, 0x0012212c, 0x0013222d, 0x0013222d, 0x0012222d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0012242e, 0x0012242e, 0x0012242e, 0x0013242f, 0x00142430, 0x00142532, 0x00142532, 0x00142534, 0x00142534, 0x00142533, 0x00132632, 0x00132632, 0x00132632, 0x00132632, 0x00132532, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x0011232f, 0x0011232f, 0x0010222e, 0x0010212e, 0x0010202d, 0x0010202d, 0x000f202e, 0x000e1f2d, 0x000e1f2d, 0x000d1e2c, 0x000d1c28, 0x000d1c28, 0x000d1c26, 0x000e1c26, 0x000e1b27, 0x000e1b28, 0x000e1b28, 0x000e1b28, 0x00101e2b, 0x00142431, 0x001c2f3c, 0x00243846, 0x002d404e, 0x00384554, 0x00374050, 0x00333948, 0x002d313e, 0x002d303b, 0x002d313c, 0x00262c38, 0x00212934, 0x00232c37, 0x00212c35, 0x001b252e, 0x001b262f, 0x001f2b34, 0x001e2932, 0x001b242d, 0x001f2833, 0x0027303b, 0x002a343f, 0x002d3843, 0x00303c45, 0x00323d4a, 0x0034404d, 0x0034404e, 0x00303e4b, 0x00303f4c, 0x0033414f, 0x00344351, 0x00374554, 0x00384655, 0x003a4958, 0x00364552, 0x0034414f, 0x00364150, 0x0034404e, 0x00323c49, 0x00303946, 0x00303844, 0x00303841, 0x00303941, 0x00303842, 0x00333c44, 0x00353f48, 0x0036404a, 0x0038414c, 0x0037424c, 0x0034404c, 0x0033404c, 0x00303f4c, 0x002f3c4b, 0x002f3d4a, 0x00313f4c, 0x0031414c, 0x00314049, 0x00313e48, 0x00313c48, 0x00303844, 0x002d3543, 0x002d3643, 0x002c3743, 0x002c3842, 0x002f3c47, 0x00323f4a, 0x0036434f, 0x003b4755, 0x003d4a5b, 0x00414f60, 0x00445364, 0x00465568, 0x0049586b, 0x004a586c, 0x004a586d, 0x004c5b70, 0x004d5d71, 0x004e5f74, 0x004c5c73, 0x004d5e74, 0x004f5f75, 0x00506076, 0x00526278, 0x00536378, 0x00546479, 0x0057677c, 0x0056667c, 0x00546579, 0x004f5f71, 0x004c5a6c, 0x004a586c, 0x004d5c6e, 0x004d5c70, 0x004c5c6e, 0x004f5d70, 0x00526074, 0x00505f71, 0x004d5c6e, 0x004c5c6e, 0x004c5b6e, 0x0049586a, 0x00495768, 0x00546175, 0x00556478, 0x00546478, 0x00536578, 0x0054667a, 0x00546479, 0x00546479, 0x00506076, 0x004f5d73, 0x004c5b70, 0x0048586c, 0x0048586c, 0x00475769, 0x00475868, 0x00455466, 0x00435063, 0x003e4b5c, 0x003c4859, 0x003c4857, 0x003a4553, 0x00374350, 0x00364350, 0x003a4754, 0x003c4a57, 0x0033404c, 0x00313f4a, 0x0034424d, 0x0033404c, 0x0034404c, 0x0032404b, 0x002e3c47, 0x002c3944, 0x00303d48, 0x00364450, 0x00384551, 0x00384551, 0x003a4853, 0x003b4955, 0x003a4956, 0x00394856, 0x00394856, 0x003a4856, 0x003e4c5c, 0x003b495b, 0x00394859, 0x003e4d5e, 0x00415261, 0x00435565, 0x00415464, 0x00405261, 0x00435464, 0x00425363, 0x00405060, 0x00405061, 0x00435361, 0x00425261, 0x00425162, 0x003e4c5c, 0x00394555, 0x00394454, 0x00384452, 0x00313d4a, 0x002c3844, 0x002b3742, 0x002b3741, 0x002c3643, 0x002c3542, 0x002b3441, 0x002b3541, 0x002b343f, 0x002a343e, 0x0029333c, 0x0029333c, 0x00272f38, 0x00232933, 0x00232832, 0x00212730, 0x001a2028, 0x00151c24, 0x001b232a, 0x00242e35, 0x001f2831, 0x00141e27, 0x00131c24, 0x00111a23, 0x00151e27, 0x001a232c, 0x00202831, 0x00242c34, 0x00262c34, 0x00242b35, 0x00222c36, 0x0026303b, 0x0029343e, 0x0028333d, 0x0028303c, 0x0029313c, 0x002c303b, 0x00282d38, 0x00252934, 0x00262c36, 0x002d3440, 0x00313c48, 0x002e3c49, 0x002c404c, 0x002c414f, 0x002c414f, 0x002a3f4c, 0x00263b48, 0x00233845, 0x00213442, 0x001f313f, 0x001b2e3b, 0x00182a38, 0x00142533, 0x00122430, 0x0010212d, 0x000f202c, 0x000e1f2c, 0x000f1f2c, 0x000f1e2b, 0x000f1d28, 0x000f1d28, 0x000e1c28, 0x000e1c28, 0x000e1c28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000f1f29, 0x0010202b, 0x0010202b, 0x0012202c, 0x0014212c, 0x0014212c, 0x0013222e, 0x0012212e, 0x0013222f, 0x0013222f, 0x0013222f, 0x0014212d, 0x0013202c, 0x00121f2a, 0x00121e28, 0x00121e28, 0x00101d27, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000c1924, 0x000c1a21, 0x000b1820, 0x000b181e, 0x000b171d, 0x000b171c, 0x000a161d, 0x000a161e, 0x000a151e, 0x000b151e, 0x000b151e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00112a30, 0x00132c32, 0x00143036, 0x00143439, 0x0017383c, 0x00173c40, 0x00194044, 0x001a4347, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205356, 0x00215659, 0x0022585b, 0x00235a5c, 0x00245d60, 0x00245f61, 0x00256163, 0x00256364, 0x00276466, 0x002b7f91, 0x0032a4c9, 0x00276c72, 0x00266467, 0x00266466, 0x00266364, 0x00256163, 0x00245f61, 0x00245e60, 0x00277486, 0x002d9ec3, 0x002c95b8, 0x0022646f, 0x00205254, 0x001f5053, 0x001d4d50, 0x001c4a4d, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0017383c, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0011242c, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1d28, 0x000c1e28, 0x000d1f27, 0x000e1f27, 0x000f1f28, 0x00102029, 0x00102029, 0x0010202a, 0x0011202c, 0x0011202c, 0x0011212c, 0x0013222d, 0x0013222d, 0x0012222d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0012242e, 0x0012242e, 0x00132430, 0x00142431, 0x00142532, 0x00142534, 0x00142534, 0x00142533, 0x00132632, 0x00132632, 0x00132632, 0x00132632, 0x00122532, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x0011232f, 0x0011232f, 0x0010212e, 0x0010202d, 0x0010202d, 0x0010202d, 0x000f202e, 0x000e1f2d, 0x000e1f2d, 0x000d1e2c, 0x000d1c28, 0x000d1c28, 0x000d1c25, 0x000e1c25, 0x000e1b27, 0x000e1b28, 0x000e1b28, 0x000e1b28, 0x00101d2a, 0x00142330, 0x001c2d3a, 0x00243745, 0x002b3d4c, 0x00344351, 0x0035404f, 0x00343c4b, 0x00313644, 0x00313440, 0x00303541, 0x002a313c, 0x00232c37, 0x00232c37, 0x00212b34, 0x001a242b, 0x001b262d, 0x001f2b34, 0x001e2932, 0x001d2730, 0x00212c36, 0x0028323c, 0x002b3540, 0x002d3943, 0x00303c46, 0x00313c48, 0x0034404d, 0x0034404d, 0x002f3d4a, 0x0030404d, 0x00344552, 0x00374756, 0x003b4c5a, 0x003c4e5d, 0x00405160, 0x00405160, 0x003a4a58, 0x00394858, 0x003d4b5a, 0x003e4958, 0x00394553, 0x0037404e, 0x00363f4a, 0x00363f49, 0x0037404a, 0x00323c47, 0x00303b45, 0x00343f49, 0x0038434d, 0x003b4651, 0x00394652, 0x00394753, 0x00394855, 0x00394857, 0x00394857, 0x00384855, 0x00364551, 0x0034434d, 0x0034424c, 0x0035424d, 0x0036404c, 0x00343d4a, 0x00343e4c, 0x0034404c, 0x0034404b, 0x0034424c, 0x0036444f, 0x003a4754, 0x003e4b58, 0x00404d5c, 0x00424f60, 0x00425062, 0x00455667, 0x004c5c6e, 0x004e5d70, 0x004d5c70, 0x004c5c70, 0x004e5f72, 0x004f6074, 0x004d5e72, 0x004e5f74, 0x00516177, 0x00546478, 0x00546478, 0x00546478, 0x00546479, 0x0056667c, 0x0055657b, 0x00546478, 0x00506072, 0x004e5c70, 0x004c5a6d, 0x004d5c70, 0x004c5c70, 0x004c5a6e, 0x00505e72, 0x00546377, 0x00546376, 0x00505f71, 0x00505e71, 0x004e5c6f, 0x004c596c, 0x004a5769, 0x00525f74, 0x0058667b, 0x0058677c, 0x0055687b, 0x0055677c, 0x0054647a, 0x0054657b, 0x0054647a, 0x00506076, 0x004c5c72, 0x0048596e, 0x004b5c70, 0x004c5c70, 0x004c5c70, 0x004b5b6d, 0x00485668, 0x00414f61, 0x003f4b5c, 0x003f4a5a, 0x003e4958, 0x003d4857, 0x003a4754, 0x00354350, 0x00303e4b, 0x00303e4b, 0x00313f4b, 0x0034404c, 0x00313e4a, 0x00303d48, 0x00303d48, 0x00303d48, 0x0032404c, 0x0032404b, 0x00303e49, 0x0033404c, 0x00384652, 0x003e4d58, 0x003d4c59, 0x003a4b58, 0x00364754, 0x00334350, 0x003b4a58, 0x00445363, 0x00445464, 0x00435364, 0x00435464, 0x00455866, 0x00445666, 0x00415464, 0x003e5060, 0x00405262, 0x00415363, 0x00415263, 0x00425363, 0x00435463, 0x00445463, 0x00435464, 0x00425161, 0x003f4c5c, 0x003c4857, 0x00384454, 0x00323e4c, 0x002d3845, 0x002b3742, 0x002a3641, 0x002b3541, 0x002c3542, 0x002b3442, 0x002c3542, 0x002c3540, 0x002a343e, 0x0029333c, 0x0029333c, 0x00252d36, 0x00202730, 0x00232831, 0x00222830, 0x001c2229, 0x00141d24, 0x00161f24, 0x00202b31, 0x00242f37, 0x0019242c, 0x00131d25, 0x00111a24, 0x00151d26, 0x0018202a, 0x001c242e, 0x00202730, 0x00212831, 0x001e2530, 0x001e2833, 0x00232e38, 0x0026323c, 0x0025313c, 0x0028303d, 0x002a313c, 0x002c313c, 0x002a2f39, 0x00272b37, 0x00262c37, 0x002c3440, 0x00303c47, 0x002c3c48, 0x002b3f4c, 0x002c414f, 0x002b404d, 0x00283d4b, 0x00243846, 0x00213643, 0x001f3240, 0x001c2f3c, 0x00182c38, 0x00152834, 0x00132430, 0x00112330, 0x0010212e, 0x0010202d, 0x000f202c, 0x0010202c, 0x00101f2c, 0x000e1e28, 0x000e1d28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1e28, 0x0010202a, 0x0010202b, 0x0011202c, 0x0014212c, 0x0013212c, 0x0013212e, 0x0012212e, 0x0012212e, 0x0012212e, 0x0012212e, 0x0013212c, 0x0013202c, 0x00111e29, 0x00121e28, 0x00121e28, 0x00101d27, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000c1924, 0x000c1a21, 0x000b1920, 0x000b181e, 0x000b171d, 0x000b171c, 0x000a161d, 0x000a161e, 0x000a151e, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00143036, 0x00153439, 0x0017383c, 0x00183d41, 0x001a4044, 0x001a4347, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205356, 0x00215659, 0x0022595c, 0x00245c5e, 0x00245e60, 0x00256062, 0x00256264, 0x00266466, 0x002b7f91, 0x0032a4c9, 0x00286c73, 0x00276668, 0x00266568, 0x00266466, 0x00256264, 0x00256164, 0x00287c91, 0x002fa0c5, 0x002b90b0, 0x00226068, 0x00205457, 0x001f5154, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00183d41, 0x00183a3e, 0x0015363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1d28, 0x000c1d28, 0x000c1e26, 0x000d1e27, 0x000e1f28, 0x00101f28, 0x00101f28, 0x00101f28, 0x0010202b, 0x0010202b, 0x0010202c, 0x0011212c, 0x0012212c, 0x0011222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0012242e, 0x0013242f, 0x00142430, 0x00142430, 0x00142432, 0x00142432, 0x00132531, 0x00132631, 0x00132631, 0x00132632, 0x00132632, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x0010232f, 0x0010232f, 0x0010212e, 0x0010202d, 0x0010202d, 0x0010202d, 0x000f202c, 0x000e1f2c, 0x000e1f2c, 0x000d1e2a, 0x000c1d27, 0x000c1c26, 0x000c1c25, 0x000d1c25, 0x000d1c27, 0x000d1c29, 0x000d1c29, 0x000d1c28, 0x000f1d2a, 0x00132330, 0x001b2c38, 0x00233543, 0x00283b49, 0x0030404f, 0x0034404e, 0x00343e4c, 0x00333a47, 0x00323844, 0x00303845, 0x002c3541, 0x00242e39, 0x00212c36, 0x001e2831, 0x001a242c, 0x001d2830, 0x00202b33, 0x001c2830, 0x001d2830, 0x00242e37, 0x0028323c, 0x002b3640, 0x002e3a44, 0x00303c46, 0x00303c48, 0x00333e4c, 0x00323e4b, 0x002f3c4a, 0x0031404e, 0x00354452, 0x00374755, 0x003a4c5b, 0x003b4e5e, 0x003d5160, 0x003f5160, 0x003c4e5c, 0x003c4c5b, 0x00404d5d, 0x00404c5c, 0x003f4a59, 0x003d4856, 0x003c4654, 0x003c4653, 0x003c4754, 0x00394452, 0x0038434f, 0x0036414d, 0x003b4753, 0x003f4c58, 0x00414f5c, 0x00445160, 0x00455261, 0x00445363, 0x00445261, 0x00445362, 0x00435360, 0x0040505c, 0x00404f5b, 0x00404d5a, 0x00414e5b, 0x003f4c59, 0x003b4856, 0x00374451, 0x0035444f, 0x0034434e, 0x0036424e, 0x00394654, 0x003c4958, 0x00414e5f, 0x00445263, 0x00445465, 0x00475868, 0x004c5c6e, 0x00505f71, 0x004e5c70, 0x004c5c70, 0x004d5e71, 0x004f5f73, 0x004f5f73, 0x00516175, 0x00536378, 0x00546478, 0x00546478, 0x00546478, 0x00546478, 0x00546478, 0x00546478, 0x00536476, 0x00516074, 0x004f5e71, 0x004d5c70, 0x004f5d71, 0x00505f74, 0x00516074, 0x00546276, 0x00546377, 0x00546377, 0x00536275, 0x004f5e71, 0x004d5c6f, 0x004c586c, 0x004a576b, 0x00505c71, 0x00586479, 0x0058687c, 0x0055677b, 0x0054667a, 0x00546478, 0x00526278, 0x00536378, 0x00516277, 0x004e5f74, 0x004d5d73, 0x004c5d72, 0x004d5e71, 0x004d5d70, 0x004d5d70, 0x004c586c, 0x00475467, 0x00455264, 0x00434e60, 0x00424d5e, 0x003d4959, 0x00384453, 0x00364451, 0x00374551, 0x00374651, 0x0034434e, 0x00303e49, 0x002c3a45, 0x002d3b46, 0x00303d49, 0x0036424e, 0x0036414d, 0x00323e4a, 0x00303c48, 0x0034404d, 0x003b4855, 0x003d4c59, 0x003a4857, 0x00384856, 0x00374654, 0x00384857, 0x0041505f, 0x00465565, 0x00445564, 0x00435463, 0x00425363, 0x003f5161, 0x00405262, 0x00445565, 0x00445464, 0x00455668, 0x00455668, 0x00445667, 0x00445668, 0x00445565, 0x00445565, 0x00425364, 0x00405062, 0x003e4d5e, 0x003d4a5b, 0x00394556, 0x0034404f, 0x00303c49, 0x002d3844, 0x002a3641, 0x00293541, 0x00293441, 0x00283440, 0x002a3440, 0x002b3540, 0x002a343e, 0x0028323b, 0x0028333c, 0x00263038, 0x00232b34, 0x00232933, 0x00232931, 0x001e252c, 0x00171f26, 0x00141d23, 0x001c262c, 0x00252f38, 0x001c2730, 0x00121c25, 0x00111b24, 0x00131c25, 0x00151f28, 0x00172029, 0x00182029, 0x0018212a, 0x0019222c, 0x001a2630, 0x00202c36, 0x0024303b, 0x0025313c, 0x002a333f, 0x002c343f, 0x002e343e, 0x002c313c, 0x00292d39, 0x00282e39, 0x0029333e, 0x002c3945, 0x002a3b48, 0x002a3e4c, 0x002b404d, 0x00283d4b, 0x00243947, 0x00203643, 0x001d3240, 0x001c303e, 0x001a2c3a, 0x00152834, 0x00132632, 0x00122430, 0x00122430, 0x0010222e, 0x0010202d, 0x000f202c, 0x0010202c, 0x00101f2c, 0x000e1d28, 0x000e1d28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1e28, 0x000f1f29, 0x00101f2a, 0x00101f2a, 0x0013202c, 0x0013212c, 0x0012212e, 0x0012212e, 0x0012212e, 0x0011202d, 0x0012202d, 0x0013202d, 0x0013202c, 0x00121f2b, 0x00131f2a, 0x00121e29, 0x00101d27, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000c1924, 0x000c1a21, 0x000b1920, 0x000b181f, 0x000b171e, 0x000b171d, 0x0009161d, 0x000a161e, 0x0009141d, 0x0009141c, 0x0009141c, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0012242c, 0x0010282e, 0x00132c32, 0x00142e34, 0x00153338, 0x0015363b, 0x00183a3e, 0x00183d41, 0x001a4044, 0x001a4347, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205457, 0x0021585a, 0x00235a5c, 0x00245d60, 0x00246062, 0x00256264, 0x00266466, 0x002b7f91, 0x0033a4c9, 0x00286d74, 0x00286769, 0x00276668, 0x00266467, 0x00266568, 0x002b849b, 0x0030a2c7, 0x002b8ca8, 0x00235f64, 0x00215659, 0x00205356, 0x001e5053, 0x001d4c50, 0x001c484c, 0x001b4649, 0x001a4245, 0x00183f43, 0x00183a3e, 0x0016363b, 0x00143338, 0x00142e34, 0x00132c32, 0x00112a30, 0x0011242c, 0x0012242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1d28, 0x000c1d28, 0x000c1d26, 0x000c1e26, 0x000d1e27, 0x000f1f28, 0x000f1f28, 0x000f1f28, 0x00101f2a, 0x0010202b, 0x0010202b, 0x0011202c, 0x0012212c, 0x0011212c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0011232d, 0x0011232d, 0x0011232d, 0x0012242e, 0x0013242e, 0x0014242f, 0x0014242f, 0x00142431, 0x00142431, 0x00132430, 0x00132630, 0x00132630, 0x00132632, 0x00132632, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x0010232f, 0x0010232f, 0x0010212e, 0x0010202d, 0x0010202d, 0x0010202d, 0x000f202c, 0x000e1f2c, 0x000e1f2c, 0x000c1e2a, 0x000c1d27, 0x000c1d26, 0x000c1c25, 0x000c1c25, 0x000c1c27, 0x000d1c29, 0x000d1c29, 0x000c1c28, 0x000e1d2a, 0x0012222f, 0x00192b37, 0x00223341, 0x00263846, 0x002c3c4c, 0x00303f4c, 0x00333d4b, 0x00323b48, 0x00323a46, 0x00313a48, 0x002d3744, 0x0027303c, 0x00212c36, 0x001c2630, 0x0019242c, 0x001e2831, 0x001e2931, 0x001b252e, 0x001c272f, 0x00242e37, 0x0028333d, 0x002c3741, 0x002e3a44, 0x002f3b45, 0x00303c47, 0x00313d49, 0x00313d49, 0x00313e4b, 0x00354350, 0x00354452, 0x00374856, 0x003c4d5c, 0x003b4f5f, 0x003d5261, 0x00405363, 0x00405262, 0x00405162, 0x00415062, 0x00424f60, 0x00445061, 0x00424e5e, 0x00404c5c, 0x00404c5c, 0x00424e5e, 0x00455060, 0x00475260, 0x00485360, 0x004a5564, 0x004a5764, 0x004a5867, 0x004a5867, 0x004c5868, 0x004c5868, 0x004c5868, 0x004a5868, 0x00485866, 0x00455562, 0x0044515f, 0x00404f5d, 0x003e4d5c, 0x003e4c5a, 0x003d4a59, 0x003a4855, 0x0034444f, 0x003c4955, 0x00444f5c, 0x0044505e, 0x00435060, 0x00445163, 0x00445263, 0x00435365, 0x00445567, 0x00485869, 0x0049586b, 0x004a596c, 0x004c5c6e, 0x004c5d70, 0x004e5f71, 0x00506074, 0x00516074, 0x00516074, 0x00526175, 0x00536275, 0x00536376, 0x00536276, 0x00526175, 0x00536276, 0x00546476, 0x00516073, 0x004e5c70, 0x004d5c6f, 0x004c5b6d, 0x00516074, 0x00536276, 0x00546378, 0x00556478, 0x00546478, 0x00516074, 0x004c5c70, 0x004c5b70, 0x004c5b70, 0x004b596e, 0x004e5c70, 0x00556276, 0x0057657a, 0x0054667a, 0x0054667a, 0x00546478, 0x00526276, 0x00506074, 0x00506075, 0x00516177, 0x00506177, 0x00506074, 0x004f6073, 0x004c5c6e, 0x004b586c, 0x00485468, 0x00465266, 0x00445265, 0x00425063, 0x003f4c5d, 0x003c4859, 0x00404f5e, 0x00445361, 0x00455461, 0x0043525e, 0x00404d59, 0x003c4854, 0x003a4652, 0x00394551, 0x00384551, 0x003d4955, 0x003e4a56, 0x003f4b57, 0x00404c58, 0x003e4a57, 0x003a4755, 0x00384554, 0x003c4b5b, 0x00415061, 0x00404f60, 0x00445364, 0x00485768, 0x00475768, 0x00465768, 0x00485869, 0x0049586a, 0x00475868, 0x00455667, 0x00475868, 0x00485869, 0x0048596b, 0x0048596b, 0x0047596b, 0x00485a6c, 0x00485969, 0x00455666, 0x00425364, 0x003f5061, 0x003c4d5d, 0x003e4c5d, 0x003b4858, 0x00364251, 0x00323e4c, 0x002c3945, 0x002a3742, 0x00283440, 0x00283440, 0x0028333f, 0x002a3440, 0x002b3540, 0x002a343f, 0x0028313b, 0x00273039, 0x00262f38, 0x00242c35, 0x00242b34, 0x00222a31, 0x001e262d, 0x00192228, 0x00151d24, 0x00192228, 0x00222c34, 0x001e2831, 0x00151f28, 0x00121c24, 0x00101a23, 0x00111c24, 0x00131c24, 0x00141c25, 0x00171f28, 0x0019212c, 0x001a2530, 0x00202b35, 0x0024303a, 0x0029343f, 0x002f3843, 0x00303842, 0x00303741, 0x002e343d, 0x002c303b, 0x002a303c, 0x00293440, 0x002b3a46, 0x002a3c49, 0x002a3e4c, 0x00283e4c, 0x00243a48, 0x00213644, 0x001e3340, 0x001c303e, 0x001c2e3c, 0x00182b38, 0x00142834, 0x00132531, 0x00122430, 0x00122430, 0x0010222e, 0x0010202d, 0x000f202c, 0x0010202c, 0x000f1e2b, 0x000e1d28, 0x000e1d28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000f1f29, 0x000f1f29, 0x00101e29, 0x00111f2a, 0x0013202c, 0x0012212e, 0x0012212e, 0x0011202d, 0x0011202d, 0x0011202d, 0x0013202d, 0x0013202d, 0x00131f2c, 0x00131f2b, 0x00131f2a, 0x00101d27, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000c1924, 0x000c1a21, 0x000b1920, 0x000b1820, 0x000b171f, 0x000b171e, 0x0009161d, 0x000a161e, 0x0008141c, 0x0009141c, 0x0009141c, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00142e34, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183d41, 0x00194044, 0x001b4448, 0x001c474b, 0x001d4b4e, 0x001e4f51, 0x00205254, 0x00205558, 0x0022595c, 0x00245c5f, 0x00245f61, 0x00256264, 0x00266467, 0x002b7f91, 0x0033a5c9, 0x0029717a, 0x00286c70, 0x00286b70, 0x00276b70, 0x002c8ca6, 0x0031a3c8, 0x002b869f, 0x00245f63, 0x0022595c, 0x00215659, 0x001f5254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00183d41, 0x0017383c, 0x00143439, 0x00143036, 0x00142e34, 0x00112a30, 0x0010282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1c27, 0x000b1c27, 0x000b1d26, 0x000c1d26, 0x000d1e27, 0x000e1e27, 0x000e1e27, 0x000e1f28, 0x000f1f29, 0x0010202b, 0x0010202b, 0x0010202b, 0x0011202c, 0x0010202c, 0x0010212c, 0x0010212c, 0x0010212c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0011232d, 0x0013242e, 0x0014242f, 0x0014242f, 0x00142430, 0x00142431, 0x00122430, 0x00112530, 0x00112630, 0x00112631, 0x00112531, 0x00112431, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x0010232f, 0x0010232f, 0x0010212e, 0x0010202d, 0x000f202c, 0x000f202c, 0x000e1f2c, 0x000e1f2c, 0x000d1e2c, 0x000c1e2a, 0x000c1d28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c28, 0x000d1c29, 0x000d1c29, 0x000c1c28, 0x000f1e2b, 0x0012222f, 0x00182935, 0x0020313e, 0x00233443, 0x00283847, 0x002d3c49, 0x00303c49, 0x00303946, 0x00303a47, 0x00313b49, 0x002e3846, 0x00283140, 0x00212b38, 0x001a2430, 0x0019242e, 0x001f2932, 0x001e2830, 0x001a242d, 0x001c262f, 0x00232d38, 0x002a343f, 0x002d3842, 0x002e3944, 0x002f3a46, 0x00303c48, 0x00303c48, 0x00313d49, 0x00303d4b, 0x00354350, 0x00384754, 0x00394958, 0x003d4f5e, 0x003e5262, 0x00405464, 0x00435767, 0x00445869, 0x0044576a, 0x00445568, 0x00445468, 0x00465568, 0x00485668, 0x00475666, 0x00495867, 0x004c5868, 0x004b5764, 0x00495460, 0x004a5461, 0x0044515e, 0x00404f5c, 0x003c4d5b, 0x003b4a58, 0x00384654, 0x00384452, 0x00384452, 0x00354450, 0x0032404c, 0x00283440, 0x001d2834, 0x001a2630, 0x0018232e, 0x001c2833, 0x001e2936, 0x001c2935, 0x001c2934, 0x0025333e, 0x0036434e, 0x003f4c58, 0x0044505e, 0x00475361, 0x00485362, 0x00465363, 0x00455364, 0x00445465, 0x00445364, 0x00445364, 0x00465567, 0x0049586a, 0x004b5a6c, 0x004b5c6c, 0x004c5c6e, 0x004e5e70, 0x00506072, 0x00516173, 0x00526274, 0x00516073, 0x004f5f70, 0x00505f71, 0x00516070, 0x004e5c6d, 0x004b596b, 0x004a5869, 0x004a586a, 0x004e5c70, 0x00516074, 0x00556478, 0x00546478, 0x00546378, 0x00546276, 0x00506074, 0x004e5c70, 0x004c5b70, 0x004c5b70, 0x004f5c71, 0x00536074, 0x00546477, 0x00546579, 0x00546578, 0x00536477, 0x00516274, 0x00506174, 0x00506175, 0x00506076, 0x00506076, 0x004e5e73, 0x004c5c6f, 0x004a596b, 0x00485668, 0x00455365, 0x00455365, 0x00445466, 0x00465466, 0x00465565, 0x00435161, 0x003e4d5c, 0x003f4e5c, 0x0040505d, 0x0043525e, 0x0045535e, 0x0045525e, 0x0046525f, 0x0044515d, 0x0044525d, 0x0046535e, 0x0045535e, 0x0047545f, 0x00475460, 0x00465461, 0x00445361, 0x00425160, 0x00465666, 0x00475868, 0x0048586a, 0x00495b6c, 0x004a5c6e, 0x00495a6c, 0x00485a6c, 0x004a5a6c, 0x0048586b, 0x0047586a, 0x0047586a, 0x0048596c, 0x00485b6c, 0x00485a6d, 0x00485a6c, 0x00485b6d, 0x00495b6d, 0x00495b6d, 0x0047586a, 0x00425365, 0x00405162, 0x003e4f5f, 0x003f4c5d, 0x003b4858, 0x00364453, 0x00323f4e, 0x002c3a48, 0x002a3843, 0x00283440, 0x0028333f, 0x0028333f, 0x002a3440, 0x002c3540, 0x002c343f, 0x0029313c, 0x0028303a, 0x00272f38, 0x00262e38, 0x00262c36, 0x00232b33, 0x001f272e, 0x001c242c, 0x00182027, 0x001a2129, 0x001f2830, 0x00202a33, 0x0018232c, 0x00131d26, 0x00101b24, 0x00111c24, 0x00141c25, 0x00151d26, 0x00181f28, 0x001a222c, 0x001d2530, 0x00212934, 0x00262f39, 0x002c343f, 0x00303944, 0x00323a44, 0x00323944, 0x00303842, 0x002e3440, 0x002b323f, 0x00293440, 0x002a3844, 0x002a3b48, 0x00283d4b, 0x00263c49, 0x00223744, 0x001f3340, 0x001c3140, 0x001c2f3e, 0x001b2c3b, 0x00182937, 0x00162734, 0x00142533, 0x00132430, 0x00122430, 0x0010222e, 0x0010202d, 0x0010202d, 0x0010202c, 0x00101f2c, 0x000e1e28, 0x000e1d28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000e1c28, 0x000e1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000f1e28, 0x000f1e28, 0x00101e29, 0x00101e29, 0x00111f2b, 0x0011202d, 0x0012212d, 0x0011202d, 0x0011202d, 0x0011202d, 0x0012202c, 0x00121f2c, 0x00121f2c, 0x00121f2a, 0x00111e28, 0x00101d27, 0x000f1c26, 0x000e1b24, 0x000d1a24, 0x000c1923, 0x000b1822, 0x000b1821, 0x000b1720, 0x000a1620, 0x000a161e, 0x0009151e, 0x0009151e, 0x0008141d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00132c32, 0x00153036, 0x00143439, 0x0016383c, 0x00183c40, 0x00183f43, 0x001a4245, 0x001b4649, 0x001d4a4d, 0x001d4d50, 0x001f5154, 0x00205457, 0x0022585b, 0x00245c5e, 0x00245f61, 0x00256264, 0x00266467, 0x002b7f91, 0x0034a6cb, 0x0032a0c2, 0x0031a0c1, 0x00319fc0, 0x0031a0c1, 0x0031a3c7, 0x002b8297, 0x00256164, 0x00245d60, 0x0022595c, 0x00215659, 0x001f5254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0017383c, 0x00153439, 0x00143036, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a1c24, 0x00091c25, 0x00091c25, 0x000b1d26, 0x000c1e27, 0x000e1e27, 0x000e1e27, 0x000e1e28, 0x000f1e29, 0x000f1f29, 0x000f1f29, 0x00101f2a, 0x00101f2a, 0x0010202a, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010212c, 0x0010212c, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232f, 0x0011232f, 0x0010242f, 0x0010252f, 0x00102630, 0x00102631, 0x00102631, 0x00102431, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010212e, 0x0010202d, 0x000f202c, 0x000d1e2b, 0x000c1e2a, 0x000c1e2c, 0x000c1e2c, 0x000c1d2b, 0x000c1c28, 0x000c1c28, 0x000d1b28, 0x000e1b28, 0x000e1b28, 0x000f1c29, 0x000e1c28, 0x000c1c28, 0x000f1e2b, 0x0012212e, 0x00152632, 0x001d2f3c, 0x0020323f, 0x00243643, 0x002a3947, 0x002c3a47, 0x002e3844, 0x002f3945, 0x00303947, 0x002d3745, 0x00283240, 0x00202a38, 0x001a2531, 0x001c2832, 0x00222c36, 0x001f2932, 0x001b252e, 0x001e2831, 0x00252f39, 0x002b3540, 0x002e3842, 0x002f3944, 0x00303945, 0x00313b48, 0x00313b48, 0x00303c48, 0x002f3b48, 0x0033404d, 0x003a4856, 0x003c4c5a, 0x003d5060, 0x00405463, 0x00415567, 0x00435768, 0x0044586a, 0x0044586b, 0x00475a6c, 0x00485a6c, 0x00485969, 0x00495868, 0x00485965, 0x00495864, 0x0045515c, 0x003d4750, 0x00333d45, 0x00333c48, 0x002c3a46, 0x002c3e4a, 0x002b3f4c, 0x00253746, 0x00172734, 0x0014242f, 0x00172630, 0x0013222b, 0x00091720, 0x00020c15, 0x00040d17, 0x00040f16, 0x00040e14, 0x000e1820, 0x0014202b, 0x00182631, 0x00182731, 0x00192834, 0x00283642, 0x002d3c47, 0x0035404c, 0x003b4653, 0x003d4855, 0x00414d5b, 0x00445161, 0x00445464, 0x00465465, 0x00455464, 0x00445163, 0x00445263, 0x00445362, 0x00455563, 0x00485967, 0x004c5c6c, 0x004d5f6f, 0x00506071, 0x00506071, 0x004f6070, 0x004f5e6f, 0x00505d6e, 0x004e5b6a, 0x004c5968, 0x004a5868, 0x00485566, 0x00485568, 0x004c5a6c, 0x00505f71, 0x00526074, 0x00516175, 0x00506175, 0x00516074, 0x004e5d70, 0x004a586b, 0x004b596c, 0x004d5b6d, 0x00505d70, 0x00515f72, 0x00526175, 0x00526476, 0x00516475, 0x00506374, 0x00506374, 0x00506274, 0x004e6073, 0x004c5e71, 0x00485b70, 0x0047586d, 0x00465769, 0x00455568, 0x00455466, 0x00465465, 0x00465464, 0x00465464, 0x00455464, 0x00435060, 0x00394858, 0x0031404e, 0x002e3c4a, 0x002b3b48, 0x0024323f, 0x0025323d, 0x002b3742, 0x0027333e, 0x0024303b, 0x002c3742, 0x00313e47, 0x0038454f, 0x003e4c56, 0x0041505a, 0x00445460, 0x00455663, 0x00415361, 0x00435464, 0x00445868, 0x00465969, 0x00485b6c, 0x004a5c6d, 0x004c5c6e, 0x004c5c6e, 0x004a5b6c, 0x0048586b, 0x0048596c, 0x00485a6d, 0x00485b6f, 0x00495c70, 0x00495b6f, 0x004b5c70, 0x004b5c70, 0x004a5c70, 0x00485b6f, 0x0047596c, 0x00425466, 0x00405263, 0x003e4f60, 0x003e4c5d, 0x003a4757, 0x00364452, 0x0032404d, 0x002e3b48, 0x002d3947, 0x002c3843, 0x002a3641, 0x002b3640, 0x002c3640, 0x002c3640, 0x002c343f, 0x0029313c, 0x0028303b, 0x0028303b, 0x0027303a, 0x00262e38, 0x00232b34, 0x001f2830, 0x001d252e, 0x001a232b, 0x0019212a, 0x001c242d, 0x001d2830, 0x0019242d, 0x00131e26, 0x00111c24, 0x00141d25, 0x00161f26, 0x00171f27, 0x00182029, 0x001c222c, 0x00202430, 0x00232834, 0x00272c38, 0x002b323d, 0x00303843, 0x00313a46, 0x00313a46, 0x00303844, 0x002e3644, 0x002c3341, 0x00293340, 0x002a3744, 0x002a3b48, 0x00283c4b, 0x00253a47, 0x001f3340, 0x001d303d, 0x001b2f3d, 0x001b2c3c, 0x00192a39, 0x00182837, 0x00162734, 0x00142633, 0x00132431, 0x00122430, 0x0011232f, 0x0010222e, 0x0010202d, 0x0010202d, 0x00101f2c, 0x000e1e29, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000d1c28, 0x000e1c27, 0x000e1c27, 0x000d1b26, 0x000d1b26, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101e2a, 0x00111f2b, 0x0010202a, 0x0010202a, 0x0010202a, 0x00101f2a, 0x00101f2a, 0x00101f2a, 0x00101f2a, 0x00101e29, 0x00101d28, 0x000f1c26, 0x000f1c26, 0x000f1b25, 0x000d1924, 0x000c1922, 0x000b1821, 0x000b1821, 0x00091821, 0x00091620, 0x0009141f, 0x0008141f, 0x0009141e, 0x0009141e, 0x0009141e, 0x000a141f, 0x000b1520, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00142e34, 0x00153338, 0x0015363b, 0x00183a3e, 0x00183d41, 0x001a4044, 0x001b4448, 0x001c484c, 0x001d4c50, 0x001f5053, 0x00205457, 0x0021585a, 0x00245c5e, 0x00245e60, 0x00256163, 0x00266467, 0x0028737e, 0x002f90aa, 0x002f91ac, 0x002f92ac, 0x002f92ad, 0x002f92ad, 0x002a7c8c, 0x00266466, 0x00256062, 0x00245d60, 0x0022595c, 0x00215659, 0x001f5254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183c40, 0x0017383c, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081b24, 0x00081c24, 0x00091c24, 0x000b1c25, 0x000c1d26, 0x000c1d26, 0x000d1d26, 0x000d1d27, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1e28, 0x000f1e29, 0x000f1e29, 0x000f1e29, 0x000f1e29, 0x000f1f28, 0x00101f28, 0x0010202a, 0x0010202b, 0x0011202c, 0x0010212c, 0x0010222c, 0x0010222c, 0x0010222e, 0x0010222e, 0x0010242f, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222e, 0x0010212e, 0x0010202d, 0x000e1f2c, 0x000d1e2b, 0x000c1e2a, 0x000c1e2c, 0x000c1e2c, 0x000c1d2c, 0x000c1c28, 0x000c1c28, 0x000d1b28, 0x000e1b28, 0x000e1b28, 0x000f1c29, 0x000e1c28, 0x000c1c28, 0x000f1e2b, 0x0012212e, 0x00142531, 0x001c2e3b, 0x0020303e, 0x00233440, 0x00283844, 0x002b3946, 0x002d3844, 0x002e3844, 0x002f3846, 0x002d3745, 0x00283341, 0x00202b38, 0x001a2633, 0x001d2834, 0x00202c36, 0x001c2831, 0x0019252e, 0x001f2a33, 0x0026313a, 0x002b3540, 0x002e3842, 0x00303944, 0x00303946, 0x00303b48, 0x00303b48, 0x00313b48, 0x00313c4a, 0x00333f4c, 0x00394654, 0x003c4c5a, 0x003e505f, 0x00405363, 0x00425668, 0x00435768, 0x00435769, 0x0044586b, 0x00485c6d, 0x004a5c6d, 0x0048596b, 0x00485867, 0x00455660, 0x00414e56, 0x00313c43, 0x0022282f, 0x001c2228, 0x00222831, 0x002c3841, 0x0031424c, 0x00304450, 0x00283c49, 0x00172834, 0x0014242d, 0x0017262e, 0x00112129, 0x0007171f, 0x0007141d, 0x00101c24, 0x00121e25, 0x00101a21, 0x00111c23, 0x0014202b, 0x001a2b34, 0x00182832, 0x001c2b35, 0x002b3a45, 0x002c3b45, 0x002f3b45, 0x00303a44, 0x002f3944, 0x00323c49, 0x003a4454, 0x003c4958, 0x003e4c5c, 0x003f4c5c, 0x00404d5d, 0x00404e5d, 0x003f4d5b, 0x003d4c58, 0x0040505c, 0x00445463, 0x00475868, 0x004c5c6d, 0x004d5d6e, 0x004d5e6e, 0x004e5c6d, 0x004f5b6c, 0x004d5868, 0x004c5866, 0x004b5666, 0x004a5566, 0x004a5668, 0x004c586b, 0x004f5d70, 0x00536174, 0x00546476, 0x00536476, 0x00526074, 0x00505e70, 0x004c5a6c, 0x004c586b, 0x004c586c, 0x004c596c, 0x00505d70, 0x00526074, 0x00516375, 0x00506274, 0x004e6072, 0x004f6073, 0x004d5f71, 0x004a5c6f, 0x0046586b, 0x00445568, 0x00445466, 0x00435364, 0x00435263, 0x00445263, 0x00445060, 0x00414c5c, 0x003c4855, 0x00384350, 0x00303c4a, 0x002a3746, 0x002a3947, 0x002c3b48, 0x00293a46, 0x001c2c38, 0x001a2732, 0x001a2832, 0x0013212c, 0x000c1a25, 0x000c1824, 0x00101e29, 0x0010202a, 0x00102029, 0x0013232c, 0x00182935, 0x001d2f3c, 0x001d303d, 0x00243845, 0x002f4450, 0x00354957, 0x00374856, 0x003b4856, 0x00404b59, 0x00485261, 0x004c5868, 0x004c5c6d, 0x004b5d70, 0x004a5e70, 0x00495d70, 0x00485c6f, 0x00485a6e, 0x004a5c70, 0x004c5e71, 0x004c5e71, 0x004a5c70, 0x00485b6e, 0x0047596b, 0x00415466, 0x00405164, 0x00414f62, 0x003d4b5c, 0x00394757, 0x00344250, 0x00303d4b, 0x00303c4a, 0x002f3b48, 0x002e3a45, 0x002e3843, 0x002c3741, 0x002b3540, 0x002b333e, 0x0028303c, 0x0028303a, 0x0028303b, 0x0028303b, 0x00272f38, 0x00232c34, 0x00202831, 0x001e2630, 0x001a232c, 0x00172028, 0x0018202a, 0x0018242c, 0x0019252d, 0x00142028, 0x00141e27, 0x00162028, 0x00182329, 0x00192329, 0x001b232b, 0x001d242d, 0x00212630, 0x00242834, 0x00272c37, 0x00282e3a, 0x002c3440, 0x00303845, 0x00303945, 0x002e3945, 0x002d3745, 0x002b3342, 0x00283240, 0x00273441, 0x00293946, 0x00283c49, 0x00243845, 0x001c303c, 0x001c2f3b, 0x00192c3b, 0x00182a38, 0x00182837, 0x00162735, 0x00142534, 0x00132432, 0x00122431, 0x00122430, 0x0011232f, 0x0010212e, 0x0010202d, 0x0010202c, 0x00101f2c, 0x000e1e28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000d1c28, 0x000d1c27, 0x000d1b26, 0x000d1a26, 0x000d1a26, 0x000e1b26, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101e2a, 0x00101e2a, 0x000f1e29, 0x000e1e28, 0x000e1e28, 0x000e1e28, 0x000e1e28, 0x000e1d28, 0x000e1d28, 0x000e1c28, 0x000f1c26, 0x000e1c25, 0x000e1b24, 0x000e1a24, 0x000d1924, 0x000b1921, 0x000a1820, 0x00091820, 0x00091720, 0x00081520, 0x0008141f, 0x0008141f, 0x0008131e, 0x0009131e, 0x0009141e, 0x000b1520, 0x000b1520, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f2229, 0x0012242c, 0x0012242c, 0x0010282e, 0x00132c32, 0x00132e34, 0x00153338, 0x00153439, 0x0016383c, 0x00183d41, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4c50, 0x001e5053, 0x00205356, 0x0022585a, 0x00235c5e, 0x00245e60, 0x00256163, 0x00276970, 0x002d8ca5, 0x002f92ac, 0x002f91ac, 0x003091ab, 0x002f90aa, 0x002e8fa8, 0x00286f78, 0x00266364, 0x00246062, 0x00245d60, 0x00235a5c, 0x00215659, 0x00205356, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00173c40, 0x0017383c, 0x00143439, 0x00153338, 0x00132e34, 0x00112a30, 0x0010282e, 0x0012242c, 0x00102229, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081a22, 0x00081b24, 0x00081c24, 0x000a1c24, 0x000b1c25, 0x000c1c25, 0x000c1c26, 0x000d1d26, 0x000d1c27, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1d27, 0x000e1e27, 0x000f1f28, 0x00101f2a, 0x0010202b, 0x0010202c, 0x0010212c, 0x0010212c, 0x0010212e, 0x0010212e, 0x0010222e, 0x000f242f, 0x000f242f, 0x000f242f, 0x000f242f, 0x000f232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222e, 0x000f222e, 0x000f222e, 0x0010202d, 0x000f202d, 0x000e1f2c, 0x000c1e2a, 0x000c1e2a, 0x000c1e2c, 0x000c1e2c, 0x000c1d2c, 0x000c1c28, 0x000c1c28, 0x000d1c28, 0x000d1c28, 0x000d1c29, 0x000e1c29, 0x000d1c28, 0x000c1c28, 0x000f1e2b, 0x0012212e, 0x00142431, 0x001c2d39, 0x0020303e, 0x0022333f, 0x00263542, 0x00293845, 0x002c3844, 0x002e3844, 0x002f3846, 0x002d3744, 0x00283341, 0x00202b38, 0x001a2634, 0x001c2834, 0x001f2a34, 0x001c2832, 0x001b272f, 0x001f2b33, 0x0027323c, 0x002c3640, 0x002d3842, 0x002f3843, 0x00303946, 0x00303a47, 0x00303a46, 0x00303a47, 0x00333e4c, 0x00364250, 0x00374552, 0x00394857, 0x003d4e5e, 0x00405364, 0x00425668, 0x00435768, 0x00435769, 0x0043586a, 0x00465a6b, 0x00485a6c, 0x00485869, 0x00455462, 0x00414f58, 0x00344046, 0x00252c33, 0x001c2024, 0x0017191d, 0x001a1c24, 0x00283038, 0x0031404a, 0x00334550, 0x002e424f, 0x001c2e39, 0x0015252e, 0x0017272e, 0x0014242c, 0x000e1f28, 0x00102029, 0x001a2a33, 0x0020313a, 0x00192830, 0x00132028, 0x0015242c, 0x001a2b34, 0x00192932, 0x0022323b, 0x002f3f48, 0x002c3c45, 0x002b3841, 0x0029343e, 0x0027303b, 0x002d3742, 0x002e3744, 0x00333e4b, 0x00364250, 0x00384451, 0x00384654, 0x003a4958, 0x003a4a58, 0x00394855, 0x003a4956, 0x003d4d5c, 0x00404e5e, 0x00435264, 0x00485868, 0x004a5a6a, 0x004c596a, 0x004c5868, 0x004a5565, 0x004a5563, 0x004a5564, 0x004a5565, 0x004a5566, 0x004c5769, 0x004e5b6d, 0x00505f71, 0x00516174, 0x00516274, 0x004f5e70, 0x004d5c6f, 0x004c5b6d, 0x004a576a, 0x00485467, 0x00485468, 0x00495669, 0x004d5c6e, 0x004e6071, 0x004c5e70, 0x004b5c6d, 0x00495a6c, 0x0048586b, 0x00455467, 0x00405062, 0x003d4d5f, 0x003d4d5c, 0x003d4c5c, 0x003c4a5a, 0x003c4858, 0x003b4554, 0x00363f4c, 0x00333c48, 0x00313a46, 0x00293240, 0x00293544, 0x002d3c49, 0x0031404d, 0x002f404c, 0x0023333e, 0x00162530, 0x00182831, 0x0014242f, 0x0011202b, 0x00172430, 0x00202f3a, 0x00182832, 0x0010222a, 0x000e212c, 0x00122431, 0x00142734, 0x00142835, 0x001b2f3c, 0x002c414d, 0x00314450, 0x00303d49, 0x0028303b, 0x001f242f, 0x00232833, 0x002f3642, 0x003a4654, 0x00475868, 0x004b5e70, 0x004a5e70, 0x00485c70, 0x0046596c, 0x0046586c, 0x0046586c, 0x00485a6e, 0x00485a6e, 0x00485b6e, 0x00485c6d, 0x0046586a, 0x00465769, 0x00465467, 0x00414e60, 0x003b4858, 0x00364453, 0x00323e4d, 0x00303c4b, 0x00303c49, 0x00303c48, 0x00303a44, 0x002d3842, 0x002b3540, 0x002a333e, 0x0028303c, 0x0028303b, 0x0028303b, 0x0028303b, 0x00272f38, 0x00242c35, 0x00222a34, 0x00202831, 0x001c242d, 0x00171f28, 0x00161f28, 0x0016212a, 0x0018242c, 0x00162029, 0x00152028, 0x0018232c, 0x001b252c, 0x001c262d, 0x001c242c, 0x001c242c, 0x001f242d, 0x00212632, 0x00242934, 0x00252c37, 0x0029303c, 0x002f3743, 0x00303a46, 0x00303a47, 0x002e3846, 0x002b3341, 0x0028313e, 0x0024303d, 0x00243441, 0x00253844, 0x00213541, 0x001d303c, 0x001c2d3a, 0x00182c39, 0x00172837, 0x00162735, 0x00142534, 0x00142433, 0x00122430, 0x00112430, 0x00112330, 0x0010212e, 0x0010202d, 0x000f202c, 0x000f1f2c, 0x000e1e2b, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000c1c27, 0x000c1a26, 0x000c1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1d28, 0x000f1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000e1d28, 0x000e1c28, 0x000d1c28, 0x000d1c28, 0x000d1c27, 0x000e1c25, 0x000d1b24, 0x000d1a24, 0x000d1924, 0x000c1823, 0x000b1820, 0x0009171f, 0x0008161f, 0x0008151e, 0x0008151e, 0x0008141e, 0x0009141e, 0x000a141e, 0x000b131e, 0x000b141f, 0x000c1420, 0x000c1420, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f2229, 0x0012242c, 0x0012242c, 0x0010282e, 0x00112a30, 0x00142e34, 0x00153338, 0x00143439, 0x00183a3e, 0x00183d41, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4c50, 0x001f5053, 0x00205457, 0x0021585a, 0x00235a5c, 0x00245e60, 0x00276b74, 0x002f98b6, 0x0031a4c7, 0x003099b8, 0x003099b8, 0x00309ab8, 0x00319cbd, 0x0034a6cb, 0x00297886, 0x00266466, 0x00256163, 0x00245e60, 0x00245c5e, 0x0021585a, 0x00205457, 0x001f5053, 0x001d4c50, 0x001c484c, 0x001b4649, 0x001a4245, 0x00183d41, 0x00183a3e, 0x0016363b, 0x00143338, 0x00143036, 0x00132c32, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091921, 0x00091b24, 0x00091b24, 0x000a1c24, 0x000a1c24, 0x000b1c25, 0x000c1c25, 0x000c1c25, 0x000c1c26, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c26, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c26, 0x000d1d26, 0x000e1d28, 0x000f1e28, 0x00101f29, 0x0010202b, 0x0010202c, 0x0010202c, 0x0010202d, 0x0010202d, 0x000f212d, 0x000e222e, 0x000e222e, 0x000e222e, 0x000e222e, 0x000e222e, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000f202d, 0x000f202c, 0x000e1f2c, 0x000c1e2a, 0x000c1e2a, 0x000c1e2c, 0x000c1e2c, 0x000c1e2c, 0x000c1d28, 0x000c1d28, 0x000c1c28, 0x000d1c29, 0x000d1c29, 0x000d1c29, 0x000c1c28, 0x000c1c28, 0x000f1e2b, 0x0012212e, 0x00152431, 0x001c2c39, 0x0021303e, 0x00223340, 0x00253541, 0x00293744, 0x002c3844, 0x002e3844, 0x002f3846, 0x002c3644, 0x00293340, 0x00232d3c, 0x001e2836, 0x001d2833, 0x001e2934, 0x001f2b35, 0x001d2933, 0x00202c35, 0x0028343e, 0x002a3640, 0x002b3741, 0x002d3842, 0x002f3843, 0x00303944, 0x002f3844, 0x00303946, 0x00333d4c, 0x00374452, 0x00394755, 0x003c4b59, 0x003c4e5e, 0x00405264, 0x00425668, 0x00425668, 0x00425668, 0x0044586b, 0x0047596b, 0x00485869, 0x00455464, 0x00404d5b, 0x003a4750, 0x002b343c, 0x0021272d, 0x001d2026, 0x001a1c1f, 0x001a181f, 0x001e222a, 0x002b3740, 0x0032444f, 0x00344954, 0x00263944, 0x00172831, 0x00182931, 0x0020333b, 0x00223740, 0x001f333c, 0x00223742, 0x002b414c, 0x0020353e, 0x001c2e38, 0x001c2e37, 0x00182830, 0x001b2b34, 0x002d3c46, 0x0033434c, 0x00303f46, 0x002c3840, 0x00283039, 0x00242a34, 0x00242a34, 0x00222832, 0x00283039, 0x00343c48, 0x0038414d, 0x00384350, 0x00374451, 0x00364451, 0x00354450, 0x00354350, 0x00384654, 0x003b4857, 0x003c4959, 0x00414f5d, 0x00445361, 0x00475464, 0x00485463, 0x00485461, 0x00485361, 0x00485363, 0x00485464, 0x00495465, 0x004c5869, 0x00505c6f, 0x00516073, 0x00506073, 0x00506072, 0x0049586b, 0x00475668, 0x00485769, 0x00485467, 0x00455364, 0x00445164, 0x00465365, 0x00455465, 0x00475768, 0x00475768, 0x00475768, 0x00475668, 0x00425063, 0x003c4859, 0x003c4858, 0x003a4858, 0x00394655, 0x00394655, 0x00394353, 0x0038404d, 0x00343944, 0x002a2f39, 0x002a2f39, 0x002c313c, 0x00252c38, 0x002a3440, 0x00303c49, 0x0034434f, 0x00344550, 0x002c3c47, 0x00182732, 0x00192833, 0x0020313c, 0x0020303c, 0x0022333d, 0x002a3c46, 0x0020343d, 0x00192f38, 0x001c323c, 0x00182c38, 0x00142734, 0x00142634, 0x00233642, 0x0031444f, 0x00303e4a, 0x0028303b, 0x001e2029, 0x001b1a21, 0x001c1c22, 0x0021222a, 0x00232934, 0x0032404d, 0x00425262, 0x0048596b, 0x004c5f71, 0x004c5f73, 0x004a5d70, 0x00485b6e, 0x00485a6e, 0x00485b6f, 0x00485b6e, 0x00475a6c, 0x0047596b, 0x00465769, 0x00435264, 0x00404c5e, 0x003c4959, 0x00394655, 0x00354150, 0x00343e4e, 0x00313b4a, 0x00303a47, 0x002e3844, 0x002c3640, 0x0029333e, 0x0029323e, 0x0029313e, 0x0028303d, 0x0028303b, 0x0028303b, 0x00272f38, 0x00252e37, 0x00242c34, 0x00212a33, 0x001d262f, 0x00171f28, 0x00161e28, 0x00162029, 0x0018222b, 0x00172029, 0x00162029, 0x001a242c, 0x001c272f, 0x001c262f, 0x001c242c, 0x001c242c, 0x001c232c, 0x001d242d, 0x00202730, 0x00242a35, 0x0028303b, 0x002e3641, 0x00313a47, 0x00303a47, 0x002f3948, 0x002c3444, 0x00283240, 0x00212d3b, 0x00202e3c, 0x00213240, 0x0020323f, 0x001c2f3a, 0x001c2c38, 0x00192c38, 0x00162834, 0x00142534, 0x00142433, 0x00132432, 0x00112330, 0x0010222e, 0x0010212e, 0x0010202d, 0x000f202c, 0x000e1f2c, 0x000e1e2c, 0x000e1d2a, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000c1c27, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000d1a26, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000d1c27, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1c27, 0x000d1c28, 0x000c1c27, 0x000c1a26, 0x000c1a26, 0x000d1a24, 0x000c1a24, 0x000c1924, 0x000c1823, 0x000c1822, 0x000a1820, 0x0009171f, 0x0008161e, 0x0008151d, 0x0008141d, 0x0008141d, 0x0009141d, 0x000b141e, 0x000c141f, 0x000c141f, 0x000c1420, 0x000c1420, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00143036, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183f43, 0x001a4245, 0x001b4649, 0x001c4a4d, 0x001d4d50, 0x00205154, 0x00205457, 0x0021585a, 0x00245c5e, 0x00266c78, 0x002f9bbc, 0x0030a0c4, 0x00297b8b, 0x0027686b, 0x0028686c, 0x0028696c, 0x002b7886, 0x0033a4c8, 0x00297886, 0x00266466, 0x00256163, 0x00245f61, 0x00245c5e, 0x0022585b, 0x00205558, 0x00205254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4448, 0x001a4044, 0x00183d41, 0x00183a3e, 0x0015363b, 0x00153338, 0x00142e34, 0x00132c32, 0x00112a30, 0x0011242c, 0x0012242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091921, 0x00091a23, 0x00091a23, 0x00091b24, 0x000a1c24, 0x000b1c24, 0x000c1b24, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c27, 0x000c1c27, 0x000c1b25, 0x000c1b24, 0x000c1b24, 0x000c1b26, 0x000c1b26, 0x000c1c25, 0x000c1c25, 0x000f1d26, 0x00101d27, 0x00101d27, 0x000f1f29, 0x000f202b, 0x000f202b, 0x000f202c, 0x000f202c, 0x000f202c, 0x000f202c, 0x000f202c, 0x000f202d, 0x000f202d, 0x000f202d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000d202c, 0x0010202d, 0x000f202c, 0x000e1f2c, 0x000c1e2a, 0x000c1e2a, 0x000c1e2c, 0x000c1e2c, 0x000c1e2b, 0x000c1d28, 0x000c1d28, 0x000c1c29, 0x000d1c29, 0x000d1c29, 0x000d1c29, 0x000c1c28, 0x000c1c28, 0x000e1d2a, 0x0011202d, 0x00142430, 0x001c2c38, 0x0022313e, 0x00233440, 0x00253542, 0x00293744, 0x002c3844, 0x002d3844, 0x002e3745, 0x002c3544, 0x0027303e, 0x00232c39, 0x00202935, 0x001e2833, 0x00212b35, 0x00212c36, 0x001e2a34, 0x00212d37, 0x0028343e, 0x00293540, 0x002a3640, 0x002c3842, 0x002f3843, 0x002f3844, 0x00303a48, 0x00313b49, 0x00323d4c, 0x00344150, 0x00384655, 0x003e4d5c, 0x003f5060, 0x00405465, 0x00425668, 0x00435668, 0x00435568, 0x00445668, 0x00455567, 0x00445363, 0x00404d5c, 0x003b4654, 0x00344048, 0x00262f37, 0x0022282e, 0x00202429, 0x001f2024, 0x001d1c22, 0x001b1e24, 0x00202931, 0x002d3b45, 0x00384954, 0x00344752, 0x0020343d, 0x00283d47, 0x002e454f, 0x00253e48, 0x00203943, 0x0027424e, 0x003c5864, 0x002e4652, 0x001d323d, 0x00192b34, 0x00192a34, 0x00283842, 0x0034444d, 0x0034424c, 0x00303c44, 0x00283138, 0x0022262f, 0x001e2129, 0x001b1d27, 0x001c1f28, 0x0020252e, 0x00282c37, 0x002d333e, 0x00333a46, 0x00394350, 0x00374350, 0x0032404d, 0x00303c4a, 0x00303c4b, 0x00374350, 0x00384452, 0x00384451, 0x003c4855, 0x00404c58, 0x00404c59, 0x00404c58, 0x00434c5a, 0x00434d5c, 0x00444e5f, 0x00465263, 0x004b5668, 0x004e5b6c, 0x00536073, 0x00526073, 0x004f5e70, 0x004a596b, 0x00485768, 0x00485668, 0x00455264, 0x00435060, 0x00435060, 0x00435060, 0x00425060, 0x00415060, 0x00404f5e, 0x00404e5e, 0x003f4c5c, 0x00374353, 0x0034404e, 0x00384351, 0x00384453, 0x00394453, 0x00384250, 0x00333948, 0x002d313d, 0x00262933, 0x0021232c, 0x001f2029, 0x001f202a, 0x0021242f, 0x00272e39, 0x002d3843, 0x0034414c, 0x00364650, 0x0034444f, 0x0022313c, 0x00162732, 0x001e2f3b, 0x00243540, 0x00273a44, 0x00394f59, 0x0029404b, 0x001b343f, 0x00203844, 0x00253b48, 0x001d303d, 0x001e303c, 0x0030404b, 0x0032404a, 0x0028323c, 0x001e232c, 0x001b1c25, 0x001e1d24, 0x00212128, 0x00222229, 0x0020242d, 0x0027323e, 0x00364351, 0x003f4e5d, 0x00465768, 0x00475a6c, 0x0045596c, 0x0044586c, 0x0045596c, 0x00465a6d, 0x00465a6c, 0x00475b6c, 0x00485a6c, 0x00455769, 0x00445465, 0x00404f60, 0x003c4c5a, 0x003c4a58, 0x003a4654, 0x0036404e, 0x00303a48, 0x002d3844, 0x002b3540, 0x002b343f, 0x0029333d, 0x002a323e, 0x0029313e, 0x0029313e, 0x0028303c, 0x0028303b, 0x00272f39, 0x00272f38, 0x00262e37, 0x00242c35, 0x00202831, 0x0018202a, 0x00171f28, 0x00172029, 0x0018212a, 0x0018212a, 0x0018222b, 0x001a262e, 0x001c2830, 0x001d2730, 0x001c242e, 0x001c242e, 0x001c242c, 0x001d242d, 0x001f2530, 0x00222834, 0x00272e39, 0x002d3440, 0x00313945, 0x00303a47, 0x00303948, 0x002c3544, 0x00283140, 0x00222c3b, 0x001e2b38, 0x001e2d3b, 0x001d2f3c, 0x001c2e38, 0x001b2c38, 0x00182b37, 0x00162733, 0x00142433, 0x00142433, 0x00132432, 0x00112330, 0x0010212e, 0x0010212e, 0x0010202d, 0x000f202c, 0x000e1f2c, 0x000d1d2a, 0x000d1c29, 0x000d1c28, 0x000d1c28, 0x000c1c27, 0x000c1c27, 0x000c1b26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000d1a26, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000d1b27, 0x000c1b26, 0x000c1a26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000b1823, 0x000b1822, 0x000c1822, 0x000c1821, 0x000c1821, 0x000c1820, 0x000a161f, 0x0008161e, 0x0009151e, 0x0008141d, 0x0008141d, 0x0009141d, 0x000b141f, 0x000c141f, 0x000c141f, 0x000c1420, 0x000c1420, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x000f2229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00153338, 0x00143439, 0x00183a3e, 0x00183d41, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4b4e, 0x001e4f51, 0x00205254, 0x00205558, 0x0022595c, 0x00267080, 0x002f9ec0, 0x00309dc0, 0x00287482, 0x00266467, 0x00276668, 0x00276769, 0x00286769, 0x002a7784, 0x0033a4c8, 0x00297886, 0x00266466, 0x00256264, 0x00246062, 0x00245d60, 0x00235a5c, 0x0021585a, 0x00205457, 0x001f5154, 0x001d4d50, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183d41, 0x00173a3e, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0012242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091820, 0x00081821, 0x00081821, 0x00081a23, 0x00091b24, 0x000a1b24, 0x000b1a24, 0x000b1a24, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b26, 0x000c1b26, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000c1b26, 0x000c1b26, 0x000c1b25, 0x000c1b24, 0x000e1c25, 0x000f1c26, 0x000f1c26, 0x000e1e28, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f2b, 0x000f202b, 0x000f202b, 0x000f202c, 0x000f202c, 0x000f202c, 0x000f202c, 0x000e202c, 0x000d202c, 0x000d202c, 0x000c202c, 0x000c202c, 0x000c1f2c, 0x000e1f2c, 0x000e1f2c, 0x000d1e2a, 0x000c1e28, 0x000c1e28, 0x000c1e29, 0x000c1e29, 0x000d1e29, 0x000c1d28, 0x000c1e28, 0x000c1e29, 0x000c1e2a, 0x000c1d29, 0x000d1c29, 0x000d1c29, 0x000d1c29, 0x000e1d2a, 0x0010202c, 0x00142331, 0x001c2c3a, 0x00223241, 0x00243444, 0x00273645, 0x00293644, 0x002b3644, 0x002c3544, 0x002d3544, 0x002c3442, 0x00252d3a, 0x00202934, 0x001e2831, 0x001f2831, 0x00232d36, 0x00242d38, 0x00202a34, 0x00222c37, 0x0028323d, 0x002a343e, 0x002b343f, 0x002c3741, 0x002d3842, 0x002f3944, 0x00323c48, 0x00343e4b, 0x00313c4a, 0x00333f4c, 0x00384553, 0x00404e5c, 0x00415162, 0x00425564, 0x00415565, 0x00415465, 0x00425466, 0x00445667, 0x00445464, 0x00404e5d, 0x003b4755, 0x00343e4b, 0x002e3440, 0x00282c37, 0x00272b33, 0x00272830, 0x0026262d, 0x00242329, 0x00202027, 0x001d2028, 0x00222832, 0x002e3945, 0x00384854, 0x003c4f5c, 0x00384d5a, 0x00263d49, 0x00243c48, 0x001c3541, 0x0027434f, 0x003a5662, 0x00344c58, 0x00182c39, 0x00182a35, 0x00283844, 0x0033434e, 0x0032404c, 0x002e3a44, 0x00283038, 0x0022262e, 0x001e1f27, 0x001b1b23, 0x001a1b23, 0x0020212a, 0x0023252e, 0x0024252d, 0x0021222c, 0x00252832, 0x002d333f, 0x00353f4b, 0x00323d49, 0x002a3542, 0x00283140, 0x00333c4a, 0x00343d4b, 0x00313c49, 0x0035414e, 0x00394451, 0x003b4653, 0x003c4854, 0x003d4855, 0x003d4857, 0x003c4856, 0x003e4958, 0x00404c5b, 0x00455060, 0x004d5968, 0x00505e6e, 0x004d5c6c, 0x004b596b, 0x004a5868, 0x00485565, 0x00465261, 0x00424d5c, 0x003f4a58, 0x003b4854, 0x003a4754, 0x00394654, 0x00394554, 0x00384454, 0x0034404f, 0x002a3444, 0x002a3441, 0x00343d4b, 0x003a4451, 0x00343e4c, 0x00282f3c, 0x00202430, 0x0021232c, 0x0024242b, 0x00212027, 0x001d1c20, 0x001c1b21, 0x001e1f27, 0x00242831, 0x0029303a, 0x002f3843, 0x00333f4a, 0x0035434d, 0x0030404a, 0x001e2e38, 0x00152730, 0x00192d37, 0x00294048, 0x0039515b, 0x002e4853, 0x001b3440, 0x00203844, 0x00233844, 0x002a3b47, 0x00303e48, 0x00313c46, 0x00262e38, 0x001d232e, 0x001c2029, 0x00202029, 0x0022212b, 0x0024242c, 0x0023242e, 0x0020242e, 0x00232b35, 0x002d3743, 0x003a4551, 0x00455260, 0x00485867, 0x00445768, 0x00405467, 0x00405467, 0x0044566a, 0x0046586c, 0x00485b6e, 0x00485a6c, 0x00425466, 0x00405163, 0x00404f60, 0x003c4c58, 0x003b4b56, 0x003a4854, 0x0034404c, 0x002f3845, 0x002c3744, 0x002b3642, 0x002b3540, 0x0029333d, 0x002a343e, 0x002a343f, 0x002a343f, 0x0029333e, 0x0028323c, 0x0028303c, 0x0028303c, 0x0028303a, 0x00262e38, 0x00242a35, 0x001c222e, 0x00171f29, 0x00162029, 0x0019232c, 0x001a242c, 0x0019252d, 0x001b272f, 0x001c2830, 0x001d2730, 0x001d2630, 0x001c242e, 0x001c242c, 0x001c242d, 0x001e252f, 0x00202831, 0x00242b36, 0x002a323d, 0x00303843, 0x00313945, 0x00303845, 0x002c3542, 0x0028303d, 0x00222c39, 0x001d2836, 0x001c2b37, 0x001c2c38, 0x001a2c38, 0x00192b38, 0x00162834, 0x00152633, 0x00142431, 0x00122430, 0x00112330, 0x0012212f, 0x0011202d, 0x0011202c, 0x0010202c, 0x00101f2b, 0x000f1e2a, 0x000e1d29, 0x000d1c28, 0x000e1b27, 0x000d1b26, 0x000c1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000d1a26, 0x000c1a27, 0x000c1b28, 0x000c1a27, 0x000b1824, 0x000b1824, 0x000b1924, 0x000b1a24, 0x000b1a24, 0x000b1823, 0x000a1821, 0x000a1821, 0x00091720, 0x000a1720, 0x000c1821, 0x000c1620, 0x000c1620, 0x000c1620, 0x000d1520, 0x000b1620, 0x000b1520, 0x000b151e, 0x000b151e, 0x000b1520, 0x000a1520, 0x000a1520, 0x000a1520, 0x000a1520, 0x000a1520, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x000f2229, 0x0012242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00153036, 0x00143439, 0x0017383c, 0x00183c40, 0x00194044, 0x001b4448, 0x001c474b, 0x001d4b4e, 0x001e4f51, 0x001f5154, 0x00205457, 0x0021575a, 0x00267588, 0x00309fc4, 0x002e99bb, 0x00276e79, 0x00256264, 0x00266466, 0x00266568, 0x00276668, 0x00286769, 0x002a7784, 0x0032a4c8, 0x00297886, 0x00266467, 0x00266364, 0x00256163, 0x00245e60, 0x00245c5f, 0x0022595c, 0x00215659, 0x00205457, 0x001f5154, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x001a4245, 0x00183d41, 0x0017383c, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081820, 0x00081821, 0x00071821, 0x00081922, 0x00091922, 0x00091922, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1823, 0x000c1924, 0x000c1924, 0x000b1924, 0x000b1a24, 0x000b1a24, 0x000c1b26, 0x000c1b26, 0x000c1a24, 0x000c1a24, 0x000d1b24, 0x000e1c25, 0x000f1c26, 0x000e1d28, 0x000d1e28, 0x000d1e28, 0x000e1f29, 0x000e1f29, 0x000e1f2a, 0x000f1f29, 0x000f1f29, 0x000f1e2b, 0x000f1e2c, 0x000e1e2c, 0x000e1f2c, 0x000e1f2c, 0x000c1f2c, 0x000c1f2c, 0x000c1e2a, 0x000a1e28, 0x000b1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000d1e28, 0x000c1d28, 0x000c1e28, 0x000c1e29, 0x000c1e2a, 0x000c1d29, 0x000d1c29, 0x000d1c29, 0x000e1d2a, 0x000e1d2a, 0x00101f2c, 0x00132230, 0x001c2b39, 0x00233342, 0x00243544, 0x00283645, 0x00293644, 0x002b3644, 0x002c3544, 0x002d3544, 0x002c3442, 0x00242c38, 0x001f2831, 0x001c2730, 0x001f2932, 0x00232d36, 0x00232d38, 0x00202934, 0x00222c37, 0x0028323c, 0x0029333e, 0x002b343f, 0x002c3741, 0x002d3842, 0x002f3843, 0x00303a46, 0x00333c48, 0x00343d4b, 0x00343f4d, 0x00384553, 0x003d4a59, 0x00404f5f, 0x00405362, 0x00405363, 0x00405363, 0x00425464, 0x00455767, 0x00445362, 0x003d4958, 0x0035404c, 0x002c343f, 0x00272c37, 0x00292c35, 0x002b2f35, 0x002a2c33, 0x002b2b32, 0x002a2830, 0x0027262c, 0x0024242a, 0x0020232b, 0x00222832, 0x00283340, 0x00374452, 0x00374653, 0x002a3c48, 0x00223540, 0x00192d38, 0x00243a45, 0x002f4651, 0x002e434f, 0x0022323e, 0x0025343f, 0x002e3c48, 0x002c3944, 0x0025313c, 0x001f2832, 0x001c2029, 0x001c1d24, 0x001a1820, 0x0019171e, 0x0019181f, 0x001b1a22, 0x00191920, 0x0019181f, 0x001a1921, 0x001e1d27, 0x001f212c, 0x00282e39, 0x002f3844, 0x0028323e, 0x00252d39, 0x002d3541, 0x002e3642, 0x002d3744, 0x00333d49, 0x0037404d, 0x0039424f, 0x003a4450, 0x003b4451, 0x003b4453, 0x00394351, 0x003c4554, 0x00404856, 0x00404a59, 0x00404959, 0x00404c5c, 0x00414e5f, 0x00414e5f, 0x00404d5d, 0x00414c5c, 0x003f4958, 0x003d4755, 0x003b4552, 0x0038434f, 0x0035414d, 0x0035404d, 0x0035404d, 0x00343e4c, 0x00303947, 0x0028303d, 0x00252d3a, 0x00303844, 0x002f3641, 0x001f2430, 0x00171a26, 0x00181823, 0x001b1a22, 0x001d1b22, 0x001c191f, 0x001b171b, 0x001c181c, 0x001c1a22, 0x001e1e27, 0x001f212c, 0x00202430, 0x00242c37, 0x002a3440, 0x00313d48, 0x002c3a43, 0x001d2c33, 0x00182830, 0x00243840, 0x002d414a, 0x00263a45, 0x001b2e3a, 0x00213440, 0x0023323e, 0x00293540, 0x002d353f, 0x00232831, 0x001c202a, 0x001f202b, 0x0022242c, 0x0026262f, 0x0027272f, 0x00252630, 0x00262732, 0x00252731, 0x00242831, 0x00272c36, 0x00313842, 0x00404a56, 0x00485764, 0x00465869, 0x0043576a, 0x00405468, 0x00415468, 0x00435569, 0x0044576a, 0x00445768, 0x00405365, 0x00405164, 0x003e4e5f, 0x003b4a58, 0x00384753, 0x0034424d, 0x00303b47, 0x002d3744, 0x002c3644, 0x002b3642, 0x002c3640, 0x002a343e, 0x002a343f, 0x002c3640, 0x002c3741, 0x002b3540, 0x002a343e, 0x002a333d, 0x0029313c, 0x0028313c, 0x0028303c, 0x00252c37, 0x001c222e, 0x00171f29, 0x00172029, 0x001a242c, 0x001c2730, 0x001d2830, 0x001b272f, 0x001c272f, 0x001d2730, 0x001d2730, 0x001d252f, 0x001c242e, 0x001c242e, 0x001d252f, 0x00202831, 0x00252b37, 0x002a313c, 0x002e3641, 0x002e3642, 0x002d3542, 0x002a323e, 0x00262f3a, 0x00212c38, 0x001c2834, 0x001c2a35, 0x001b2b37, 0x00192c38, 0x00172936, 0x00142733, 0x00142632, 0x00132430, 0x0011222e, 0x0010212e, 0x0011202d, 0x0010202c, 0x0010202b, 0x000f1f29, 0x000e1e28, 0x000e1d28, 0x000e1d28, 0x000d1c27, 0x000d1b26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000b1926, 0x000b1a27, 0x000b1826, 0x000a1824, 0x000a1823, 0x00091822, 0x00081821, 0x00091822, 0x000a1822, 0x000a1821, 0x000a1821, 0x00091720, 0x000a1620, 0x000c1721, 0x000c1620, 0x000c1620, 0x000c1620, 0x000d1520, 0x000b1620, 0x000b1520, 0x000b151e, 0x000b151e, 0x000b1520, 0x000a1520, 0x000a1520, 0x000a1520, 0x000a1520, 0x000a1520, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00142e34, 0x00143338, 0x0016363b, 0x00183c40, 0x00183f43, 0x001a4347, 0x001c474b, 0x001d4b4e, 0x001e4f51, 0x001f5154, 0x00205356, 0x0021585b, 0x00277c92, 0x002ea0c7, 0x002c95b5, 0x00256870, 0x00256062, 0x00256264, 0x00266466, 0x00266467, 0x00266568, 0x00286668, 0x00297684, 0x0032a4c8, 0x00297886, 0x00266568, 0x00266466, 0x00256264, 0x00256163, 0x00245e60, 0x00245c5f, 0x00235a5c, 0x0021585a, 0x00205558, 0x00205254, 0x001e4f51, 0x001d4c50, 0x001c484c, 0x001b4448, 0x001a4245, 0x00183d41, 0x0017383c, 0x00153439, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091820, 0x00081821, 0x00081821, 0x00081821, 0x00081821, 0x00091821, 0x000a1821, 0x000a1821, 0x000a1820, 0x000b1820, 0x000b1820, 0x000b1820, 0x000b1820, 0x000b1820, 0x000b1921, 0x000b1922, 0x000c1a24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000e1c25, 0x000d1c27, 0x000c1c28, 0x000c1c28, 0x000c1c28, 0x000c1d28, 0x000c1e28, 0x000d1e28, 0x000d1e28, 0x000e1e2b, 0x000e1e2b, 0x000d1e2b, 0x000c1e2a, 0x000c1e2a, 0x000c1e2a, 0x000c1e2a, 0x000b1d28, 0x000a1d26, 0x000a1e26, 0x000c1e27, 0x000c1e27, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000d1e28, 0x000c1d28, 0x000c1e28, 0x000c1e29, 0x000c1e2a, 0x000c1e2a, 0x000c1d29, 0x000c1d29, 0x000e1d2a, 0x000e1d2a, 0x00101f2c, 0x00132230, 0x001b2a38, 0x00223240, 0x00253444, 0x00283645, 0x002a3544, 0x002a3544, 0x002b3544, 0x002c3544, 0x002b3442, 0x00252f3b, 0x00202832, 0x001c262f, 0x001f2931, 0x00212c35, 0x00202a34, 0x001d2832, 0x00232c38, 0x0028333d, 0x002a343f, 0x002c3540, 0x002c3741, 0x002d3842, 0x002d3842, 0x002c3642, 0x002d3744, 0x00333c49, 0x0036414f, 0x00354350, 0x00364452, 0x003a4959, 0x003d4d5e, 0x003f5060, 0x00425363, 0x00425464, 0x00425261, 0x003e4c5a, 0x00384150, 0x002f3644, 0x00282c38, 0x00272b35, 0x002a2f36, 0x002f333b, 0x002d3038, 0x002d2e37, 0x002e2f36, 0x002d2d33, 0x002c2c32, 0x00282830, 0x0024262f, 0x00242630, 0x00262934, 0x00282c37, 0x00282c36, 0x00232933, 0x001f252e, 0x00202831, 0x00212b35, 0x00212b36, 0x00222a35, 0x00242a35, 0x00212834, 0x001f2730, 0x001e242f, 0x001f232c, 0x001f2028, 0x001f1c22, 0x001e1a20, 0x001c181f, 0x001a171d, 0x0018171d, 0x0019181e, 0x001b1b20, 0x001e1e24, 0x00202028, 0x0020212b, 0x00202430, 0x00282e3a, 0x0029303c, 0x00262d38, 0x0029303c, 0x002a323d, 0x002c343f, 0x00303a46, 0x00343d49, 0x00353d49, 0x00353d48, 0x00353d4a, 0x00363e4c, 0x0039404e, 0x003d4553, 0x003f4754, 0x003f4855, 0x003f4856, 0x003d4756, 0x00394454, 0x00394354, 0x00394353, 0x00394351, 0x00394350, 0x00384250, 0x0038414e, 0x0038414e, 0x0036404c, 0x00343d4a, 0x00333a47, 0x00303844, 0x002e3642, 0x002a313c, 0x00272d38, 0x00282d38, 0x0021252f, 0x001a1d26, 0x001c1c24, 0x001c1c24, 0x001b1a22, 0x001c1920, 0x001c181e, 0x001b171c, 0x001d191e, 0x00201c22, 0x00201e26, 0x0020202a, 0x0020212b, 0x001f222d, 0x0020242f, 0x00212830, 0x00232b32, 0x00212a30, 0x001b242c, 0x001b252c, 0x001c272f, 0x001a242e, 0x0019202c, 0x001d242f, 0x00202730, 0x0020272f, 0x0020242c, 0x0020232a, 0x0020222b, 0x0024262f, 0x00272830, 0x0027282f, 0x0026272f, 0x00272830, 0x00292a35, 0x002a2b35, 0x00282a34, 0x00262933, 0x00282d38, 0x00343c48, 0x0043505c, 0x00465667, 0x00445869, 0x00445769, 0x00445568, 0x00425468, 0x00415466, 0x00415465, 0x00425467, 0x00425465, 0x003d4c5d, 0x00384654, 0x0034404c, 0x002f3c47, 0x002d3844, 0x002c3644, 0x002c3643, 0x002a3641, 0x002c3640, 0x002a343f, 0x002b343f, 0x002c3640, 0x002c3640, 0x002b343f, 0x002a343f, 0x002b343e, 0x002a323d, 0x002a323d, 0x0029313c, 0x00272e39, 0x001c242f, 0x0016202a, 0x0017222a, 0x0019242d, 0x001c2830, 0x001e2931, 0x001b272f, 0x0019242c, 0x0019232c, 0x001b242d, 0x001d252f, 0x001e2630, 0x001e2730, 0x00202832, 0x00242c35, 0x0029303b, 0x002b323d, 0x002b323d, 0x00272e39, 0x00262c38, 0x00262d38, 0x00242d38, 0x00212c37, 0x001c2a35, 0x001b2a35, 0x001a2a36, 0x00182a37, 0x00162834, 0x00112531, 0x00122430, 0x0012232f, 0x0010222d, 0x0010212c, 0x0010202b, 0x00101f2b, 0x000e1e29, 0x000e1d28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000c1b26, 0x000c1925, 0x000c1924, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1924, 0x000b1823, 0x000a1824, 0x000a1824, 0x000a1824, 0x000a1822, 0x000a1821, 0x00091821, 0x00091821, 0x00091821, 0x000a1821, 0x00091720, 0x00091720, 0x00091720, 0x000a1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1520, 0x000a1620, 0x000a1520, 0x000a151f, 0x000a151f, 0x000b1520, 0x000a1520, 0x000a1520, 0x000a1520, 0x000b1620, 0x000b1620, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153338, 0x0015363b, 0x00183a3e, 0x00183f43, 0x001a4347, 0x001b4649, 0x001d4b4e, 0x001e4f51, 0x001f5154, 0x00205457, 0x0021585c, 0x0028829c, 0x002fa1c8, 0x002c8fad, 0x0024646b, 0x00245f61, 0x00246062, 0x00266264, 0x00266364, 0x00276467, 0x00266568, 0x00276668, 0x00297684, 0x0032a4c8, 0x002a7887, 0x00276668, 0x00266568, 0x00266466, 0x00266364, 0x00256163, 0x00245f61, 0x00245d60, 0x00245c5e, 0x0022585b, 0x00215659, 0x00205356, 0x001f5053, 0x001d4c50, 0x001c484c, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00143338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1820, 0x00091821, 0x00091821, 0x00081821, 0x00081821, 0x00081821, 0x00091821, 0x000a1821, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1923, 0x000c1923, 0x000c1924, 0x000c1a24, 0x000d1b25, 0x000d1a26, 0x000c1b26, 0x000c1b26, 0x000c1c26, 0x000b1c26, 0x000c1d28, 0x000d1c28, 0x000e1c28, 0x000d1c28, 0x000c1c29, 0x000d1c29, 0x000c1c29, 0x000c1d29, 0x000b1d29, 0x000b1d28, 0x000c1d26, 0x000c1d26, 0x000c1e27, 0x000c1e27, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000d1e28, 0x000c1d28, 0x000c1e28, 0x000c1e29, 0x000c1e2a, 0x000c1e2a, 0x000c1e2a, 0x000c1e2a, 0x000e1d2a, 0x000e1d2a, 0x00101f2c, 0x00132230, 0x00192838, 0x0020303e, 0x00253443, 0x00283545, 0x002a3545, 0x002a3545, 0x002b3544, 0x002c3544, 0x002a3442, 0x0026303c, 0x001f2932, 0x001c262f, 0x00202932, 0x00202a33, 0x001c2630, 0x001c2630, 0x00242e38, 0x002b343f, 0x002c3640, 0x002c3640, 0x002c3741, 0x002d3842, 0x002d3842, 0x002c3642, 0x002b3441, 0x002d3744, 0x00343e4b, 0x0034404e, 0x00354250, 0x003a4857, 0x003c4c5c, 0x003f5060, 0x00425363, 0x00415161, 0x003c4b5a, 0x00384451, 0x00303a48, 0x0028303d, 0x00282d39, 0x002a2e38, 0x002c3139, 0x0032373f, 0x00323740, 0x0031343d, 0x0030333c, 0x00303239, 0x0030313a, 0x002e2f38, 0x002f2f3a, 0x002c2c38, 0x002a2a37, 0x00272733, 0x00272633, 0x00262531, 0x0024232d, 0x0022232b, 0x0022242d, 0x0021242e, 0x0021232f, 0x00222430, 0x00222430, 0x00222530, 0x00232630, 0x0022242d, 0x00232229, 0x00201e24, 0x00211d24, 0x00211d24, 0x00201d23, 0x001e1d23, 0x00202026, 0x00222328, 0x0024272f, 0x00262830, 0x00252831, 0x00242831, 0x00242b34, 0x00272d37, 0x00272c37, 0x00292f39, 0x0028303b, 0x0028303c, 0x002e3741, 0x00313944, 0x00333a45, 0x00343b45, 0x00343c48, 0x00343c48, 0x00353c49, 0x0038404d, 0x0039414d, 0x0038424e, 0x003b4451, 0x003c4554, 0x00394352, 0x00384152, 0x00384050, 0x00373f4d, 0x00353e4c, 0x00343d4a, 0x00343e4b, 0x0035404c, 0x00343c49, 0x00333a48, 0x002f3543, 0x002d3440, 0x002d3541, 0x002c323e, 0x00272c37, 0x00242833, 0x0022242e, 0x0022252d, 0x0025272e, 0x0025252c, 0x0024232b, 0x00232028, 0x00211d24, 0x00201d23, 0x00211d24, 0x00201d23, 0x00202026, 0x00232229, 0x0024242d, 0x0025252f, 0x0024252e, 0x0020242c, 0x001f2329, 0x001e2328, 0x001e242a, 0x001d222a, 0x001c2029, 0x001c2029, 0x001f212c, 0x0021232d, 0x0020242c, 0x0021262d, 0x00242830, 0x00282b33, 0x00282b34, 0x00292b34, 0x00292b34, 0x00272931, 0x00272932, 0x00282b34, 0x002a2c37, 0x002b2d38, 0x00292c35, 0x00282b34, 0x00282c37, 0x0029303c, 0x00343d4a, 0x003d4a5a, 0x003e4f5f, 0x00405061, 0x00415364, 0x00425366, 0x003f5062, 0x003c4e5f, 0x003d4f60, 0x003e4f60, 0x003c4a5a, 0x00374452, 0x00333f4b, 0x002f3a46, 0x002d3843, 0x002c3742, 0x002b3641, 0x002a3640, 0x002c3640, 0x002c3640, 0x002c3640, 0x002c3741, 0x002c3540, 0x002a343e, 0x0029333e, 0x002a333d, 0x002a323d, 0x002a323d, 0x002a323d, 0x00272f3a, 0x001d2530, 0x0015202a, 0x0017232b, 0x0019252e, 0x001c2830, 0x001f2b34, 0x001d2933, 0x001a242e, 0x001a232d, 0x001c242f, 0x001f2731, 0x00212932, 0x00232b34, 0x00272f38, 0x0029313b, 0x002b313c, 0x002b303c, 0x00272c38, 0x00232834, 0x00242834, 0x00242c36, 0x00242d37, 0x00222c37, 0x001c2a36, 0x001b2a35, 0x00192a35, 0x00182a37, 0x00152834, 0x00102430, 0x0010232f, 0x0011222e, 0x0010212c, 0x0010202c, 0x0010202a, 0x000e1e29, 0x000d1c28, 0x000c1c27, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000c1b26, 0x000b1824, 0x000b1824, 0x000c1924, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000b1823, 0x000b1822, 0x000a1822, 0x000a1823, 0x00091722, 0x00091720, 0x00091720, 0x00091720, 0x00091720, 0x00091720, 0x00091821, 0x00091720, 0x00091720, 0x00091720, 0x000a1620, 0x000b1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x00091720, 0x000a1620, 0x000a1520, 0x000a1520, 0x000b1620, 0x000b1620, 0x000a1520, 0x000a1520, 0x000b1720, 0x000c1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00143036, 0x00153439, 0x00183a3e, 0x00183d41, 0x001a4347, 0x001b4649, 0x001d4b4e, 0x001e4f51, 0x001f5154, 0x00205457, 0x00225c61, 0x002a88a5, 0x002fa2c9, 0x002b8ba6, 0x00246167, 0x00245f61, 0x00246062, 0x00266163, 0x00256264, 0x00256364, 0x00276467, 0x00266568, 0x00276668, 0x00297684, 0x0033a4c8, 0x002b8194, 0x0028727c, 0x0028727c, 0x0028717b, 0x0028707a, 0x00287079, 0x00286d78, 0x00276c76, 0x00266b75, 0x00256873, 0x00246670, 0x0023646f, 0x00215e68, 0x001f5054, 0x001d4c50, 0x001c484c, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00143036, 0x00132c32, 0x0010282e, 0x0012242c, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a171f, 0x00091720, 0x00091720, 0x00081821, 0x00081821, 0x00081821, 0x00081821, 0x00091821, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1823, 0x000c1823, 0x000c1822, 0x000c1822, 0x000c1822, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1925, 0x000c1a25, 0x000c1a24, 0x000c1b24, 0x000c1c25, 0x000c1c26, 0x000e1c27, 0x000e1c27, 0x000d1c28, 0x000d1c28, 0x000e1c28, 0x000d1c28, 0x000c1c28, 0x000b1c28, 0x000c1d28, 0x000c1d26, 0x000c1d26, 0x000c1e27, 0x000c1e27, 0x000c1e28, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000d1d28, 0x000d1c28, 0x000d1c28, 0x000d1c29, 0x000d1c29, 0x000d1d29, 0x000c1d29, 0x000c1d2a, 0x000e1d2a, 0x000e1d2b, 0x00101f2c, 0x00122130, 0x00182836, 0x001f2e3d, 0x00243341, 0x00273544, 0x00293545, 0x002a3545, 0x002b3544, 0x002b3443, 0x002a3442, 0x0028323d, 0x00212c35, 0x001f2831, 0x001f2932, 0x001d2830, 0x001a2430, 0x001b242f, 0x00242e38, 0x002c3640, 0x002c3741, 0x002c3640, 0x002c3741, 0x002d3842, 0x002c3842, 0x002c3642, 0x002c3542, 0x002c3643, 0x002f3a46, 0x0034404c, 0x00374451, 0x003b4856, 0x003c4b5a, 0x003e4d5c, 0x00404e5d, 0x003c4b59, 0x00384754, 0x0033404e, 0x00303949, 0x002c3442, 0x002c333f, 0x002c323d, 0x002c333c, 0x00303842, 0x00303843, 0x00323944, 0x00303742, 0x00303640, 0x00303540, 0x00313541, 0x00343846, 0x00383c4b, 0x00363a49, 0x00313544, 0x00313444, 0x00303340, 0x002e313c, 0x002c2f39, 0x002c2e38, 0x002c2f39, 0x002a2d38, 0x002a2d39, 0x00282c38, 0x00242a35, 0x00232831, 0x0022262e, 0x0023242c, 0x0022222a, 0x00242129, 0x00242128, 0x00222128, 0x00202229, 0x0022242c, 0x0024272e, 0x00252831, 0x00262931, 0x00262932, 0x00242932, 0x00232932, 0x00232933, 0x00252b34, 0x00282c37, 0x00282d38, 0x00272d38, 0x002c343e, 0x00303842, 0x00313842, 0x00323843, 0x00333944, 0x00333845, 0x00333946, 0x00343c48, 0x00353d49, 0x0037404c, 0x0038404d, 0x00363e4c, 0x00343c4b, 0x00343b4b, 0x00333a48, 0x00323947, 0x00313946, 0x00313845, 0x00313946, 0x00323a47, 0x00323946, 0x00323845, 0x002d323f, 0x002b303c, 0x002b313c, 0x002a303b, 0x00282d38, 0x00262b34, 0x00242831, 0x00242830, 0x00262830, 0x0026282f, 0x0025262f, 0x0024242c, 0x00232129, 0x00232128, 0x00222028, 0x00212026, 0x00212028, 0x00222129, 0x0023232c, 0x0024252e, 0x00262730, 0x00272932, 0x00282c34, 0x00292d36, 0x002b3038, 0x002a303a, 0x00292e39, 0x00282d38, 0x00282d39, 0x00282d38, 0x00282e38, 0x00293038, 0x002c313b, 0x002e333d, 0x002c303c, 0x002c303b, 0x002c303b, 0x002c303a, 0x002c303b, 0x002d313c, 0x002c303c, 0x002c303b, 0x002c2f39, 0x002c2f39, 0x002c303b, 0x00272e39, 0x00272f3c, 0x00303c4b, 0x00354251, 0x00364454, 0x00384656, 0x00394859, 0x00394959, 0x00394858, 0x003c4c5c, 0x003d4d5d, 0x003c4a5a, 0x00384451, 0x00333f4a, 0x00303a45, 0x002d3841, 0x002c3640, 0x002b3640, 0x0029353f, 0x002b3540, 0x002c3640, 0x002c3540, 0x002c3540, 0x002c3540, 0x002a343f, 0x0029333d, 0x0029323d, 0x0029323d, 0x0029323d, 0x0029313c, 0x00262e39, 0x001f2530, 0x00161f29, 0x0018222a, 0x001c272f, 0x001e2831, 0x001f2b34, 0x00202d37, 0x001f2b34, 0x001d2832, 0x001f2833, 0x00222b36, 0x00242d37, 0x00252e37, 0x0029313a, 0x002b313b, 0x00282d38, 0x00252a34, 0x00232630, 0x00212530, 0x00232833, 0x00262b36, 0x00252d38, 0x00232d38, 0x001d2b37, 0x001b2b36, 0x00182a35, 0x00172936, 0x00152834, 0x00112430, 0x0010222e, 0x0010202d, 0x0010202b, 0x000f1f2a, 0x000e1d28, 0x000d1c28, 0x000c1c28, 0x000c1c27, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1a25, 0x000c1925, 0x000b1824, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1924, 0x000c1924, 0x000b1823, 0x000b1822, 0x000a1822, 0x000a1822, 0x000a1822, 0x00091720, 0x00091720, 0x00091720, 0x00091720, 0x000a1821, 0x000a1821, 0x000a1620, 0x000a1620, 0x000a1620, 0x000b1620, 0x000b1620, 0x000b1520, 0x000c1520, 0x000c1520, 0x000c1520, 0x00091620, 0x000a1620, 0x000a1520, 0x000a1520, 0x000b1620, 0x000b1620, 0x000a1520, 0x000b1620, 0x000c1821, 0x000c1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4245, 0x001c4649, 0x001d4b4e, 0x001e4f51, 0x00205254, 0x00205558, 0x00235f67, 0x002b8fae, 0x0030a2c8, 0x0029859d, 0x00246164, 0x00246062, 0x00256163, 0x00256163, 0x00256264, 0x00256364, 0x00266466, 0x00266467, 0x00266568, 0x00276668, 0x002a7784, 0x0033a4c9, 0x0033a4c8, 0x0032a4c7, 0x0032a4c7, 0x0032a4c7, 0x0032a4c7, 0x0032a4c7, 0x0031a3c7, 0x0031a3c6, 0x0030a3c6, 0x0030a2c6, 0x0030a0c6, 0x002fa0c6, 0x002d9ec3, 0x0025788e, 0x001f5054, 0x001d4c50, 0x001c474b, 0x00194245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0013282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0009171f, 0x00091720, 0x00091720, 0x00091820, 0x00091821, 0x00091821, 0x00091821, 0x00091821, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1821, 0x000c1822, 0x000c1822, 0x000c1823, 0x000c1923, 0x000c1823, 0x000b1824, 0x000c1824, 0x000c1923, 0x000c1923, 0x000c1924, 0x000c1a24, 0x000d1a25, 0x000c1a25, 0x000c1b25, 0x000c1b27, 0x000e1c27, 0x000c1c27, 0x000c1c28, 0x000b1c28, 0x000b1c28, 0x000c1d27, 0x000c1d27, 0x000c1e28, 0x000c1e28, 0x000c1d28, 0x000d1c28, 0x000d1c28, 0x000e1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000d1c29, 0x000d1c29, 0x000f1e2b, 0x00101f2c, 0x0010202c, 0x0010202d, 0x00142432, 0x001b2c3a, 0x00203140, 0x00243442, 0x00283544, 0x00283644, 0x002a3443, 0x002b3340, 0x002a323f, 0x0028303c, 0x00232c38, 0x00202a34, 0x001e2832, 0x001c2630, 0x001a242f, 0x001b242f, 0x00232d37, 0x002c3640, 0x002c3741, 0x002c3741, 0x002c3741, 0x002d3842, 0x002c3741, 0x002c3640, 0x002c3641, 0x002c3742, 0x002d3844, 0x00303c47, 0x0034414d, 0x00394654, 0x003c4854, 0x003c4855, 0x00394653, 0x0034414f, 0x0032404c, 0x00303d4a, 0x00303c49, 0x00303948, 0x00303844, 0x002e3641, 0x002e3640, 0x002f3843, 0x00303945, 0x00343c48, 0x00343c4a, 0x00323b49, 0x00313948, 0x00303845, 0x00313a48, 0x0038404f, 0x003b4454, 0x00394454, 0x00394453, 0x00394250, 0x0038414e, 0x0038404d, 0x0037404c, 0x00363d49, 0x00323844, 0x002d343f, 0x0029303c, 0x00262d38, 0x00242934, 0x00232831, 0x0024262f, 0x0024252f, 0x0024252f, 0x0023242e, 0x0021242c, 0x0021242d, 0x0023242d, 0x0024262e, 0x0024262f, 0x0023252e, 0x0023272f, 0x00232730, 0x0021262e, 0x0020262f, 0x00222730, 0x00242934, 0x00252a34, 0x00252c35, 0x002b313b, 0x00303740, 0x00303741, 0x00303841, 0x00303843, 0x00303742, 0x00303742, 0x00303843, 0x00303844, 0x00313946, 0x00303846, 0x00313848, 0x00303847, 0x00303847, 0x00303844, 0x002f3744, 0x002f3744, 0x00303744, 0x00313844, 0x00313844, 0x00323844, 0x00313743, 0x002c323c, 0x00282d37, 0x00252c36, 0x00252c36, 0x00242c34, 0x00242c34, 0x00242830, 0x00232830, 0x00242830, 0x00242730, 0x00252730, 0x0025262f, 0x0024242d, 0x0024242d, 0x0023232c, 0x0022222a, 0x0022232b, 0x0022242c, 0x0022242d, 0x0024272f, 0x00252830, 0x00282c35, 0x002c313b, 0x00333843, 0x003a3f4b, 0x003a404e, 0x00383e4c, 0x00343c49, 0x00333a48, 0x00303845, 0x002f3643, 0x002e3541, 0x00303641, 0x00313843, 0x00303641, 0x002f3540, 0x00303643, 0x00303743, 0x00303643, 0x00303541, 0x002c3340, 0x002c333e, 0x002d343f, 0x002d333e, 0x002e343f, 0x002c333f, 0x0028303c, 0x002b3542, 0x00313d4b, 0x00323f4c, 0x00303d4a, 0x00344250, 0x00384654, 0x00384755, 0x00394857, 0x003a4857, 0x00384554, 0x00374350, 0x0034404c, 0x00303b46, 0x002d3842, 0x002c3640, 0x002b343f, 0x0028323c, 0x0029333d, 0x002b343f, 0x002b343f, 0x002a343e, 0x002a343f, 0x002b343f, 0x002a343e, 0x0029333e, 0x0029333d, 0x0029333d, 0x0029313c, 0x00272f3a, 0x001e2631, 0x00161e27, 0x00182028, 0x001d282f, 0x00202b32, 0x001f2c34, 0x00202f38, 0x00212f38, 0x001f2c35, 0x001e2a34, 0x00222e38, 0x00232f39, 0x00242e38, 0x00272e38, 0x00252b34, 0x00222630, 0x0020232b, 0x001e2129, 0x0020232b, 0x00242731, 0x00272c37, 0x00262e3b, 0x00232e3c, 0x001d2c39, 0x001a2b38, 0x00182936, 0x00162834, 0x00142734, 0x00132430, 0x0011212e, 0x0010202c, 0x00101e2c, 0x000f1d2a, 0x000e1c28, 0x000d1b27, 0x000d1b26, 0x000d1a26, 0x000c1a25, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1925, 0x000d1925, 0x000d1a26, 0x000e1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1924, 0x000c1924, 0x000c1924, 0x000b1823, 0x000b1823, 0x000b1822, 0x000a1822, 0x000a1822, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1720, 0x000b1620, 0x000b1720, 0x000c1821, 0x000c1721, 0x000b151e, 0x000b151d, 0x000c151d, 0x000d161e, 0x000c161f, 0x000c1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000c1821, 0x000c1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0016363b, 0x00173a3e, 0x00194044, 0x001b4448, 0x001c4a4d, 0x001e4f51, 0x00205254, 0x00215659, 0x0024646e, 0x002c95b5, 0x0030a1c7, 0x00298095, 0x00256164, 0x00256264, 0x00256264, 0x00266364, 0x00266364, 0x00266466, 0x00276467, 0x00266568, 0x00276568, 0x00276668, 0x00286769, 0x0029717b, 0x002f90a9, 0x003091ab, 0x003091ab, 0x003091ab, 0x003091ab, 0x003091ab, 0x003091ab, 0x002f90ab, 0x002f90aa, 0x002e90aa, 0x002e90aa, 0x002d8ea9, 0x002c8da9, 0x002f9dc1, 0x002c9cc0, 0x00205559, 0x001f5053, 0x001d4a4d, 0x001b4448, 0x00194044, 0x00173a3e, 0x00153439, 0x00143036, 0x00122c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0009151e, 0x0009151f, 0x0009151f, 0x000a161f, 0x000a161f, 0x000a171f, 0x000a171f, 0x000a171f, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1720, 0x000c1620, 0x000c1720, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1721, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1821, 0x000b1921, 0x000b1923, 0x000b1a23, 0x00091a23, 0x000b1b24, 0x000c1a24, 0x000c1b25, 0x000b1b27, 0x000a1b28, 0x000a1c28, 0x000b1c27, 0x000c1d28, 0x000c1d28, 0x000c1e28, 0x000c1c28, 0x000c1c27, 0x000c1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000d1c28, 0x000d1c29, 0x000d1c29, 0x000f1e2c, 0x00101f2c, 0x00101f2c, 0x0010202c, 0x00142430, 0x00182a38, 0x001e313f, 0x00223442, 0x00273544, 0x00283544, 0x00283341, 0x0028303d, 0x0028303c, 0x0027303c, 0x00232c37, 0x00202b35, 0x001e2833, 0x001b2530, 0x0019232d, 0x001a242c, 0x00232c36, 0x002c3640, 0x002c3741, 0x002c3741, 0x002c3741, 0x002d3842, 0x002c3741, 0x002c3640, 0x002c3640, 0x002c3842, 0x002e3a44, 0x00303c46, 0x00303d48, 0x00323f49, 0x00343f4a, 0x00313c47, 0x002c3844, 0x002e3a44, 0x00303c48, 0x00303d49, 0x00303d4a, 0x00323e4b, 0x00323c49, 0x00313a45, 0x00303944, 0x00303a45, 0x00323c48, 0x0038414f, 0x00394252, 0x00384252, 0x00374050, 0x00354050, 0x00374050, 0x00374252, 0x00374453, 0x00364353, 0x00354151, 0x00374352, 0x00384350, 0x0035404d, 0x00323d4a, 0x00313a47, 0x002e3642, 0x002c343f, 0x002c343f, 0x002b333e, 0x002a2f3a, 0x00282c36, 0x00262934, 0x00242732, 0x00242630, 0x00242630, 0x00232530, 0x00232530, 0x00242530, 0x00242630, 0x0022252e, 0x0021242d, 0x0020252e, 0x0020262e, 0x0020252d, 0x0020242d, 0x0020252f, 0x0020252f, 0x00232731, 0x00252b34, 0x002b313b, 0x00303640, 0x00303740, 0x00303740, 0x002f3742, 0x002e3642, 0x002f3742, 0x002f3742, 0x002f3743, 0x002f3743, 0x002f3744, 0x002f3745, 0x002f3745, 0x002f3745, 0x002e3643, 0x002e3642, 0x002d3542, 0x00303643, 0x00303744, 0x00313843, 0x00323743, 0x00303440, 0x002c313b, 0x00262c35, 0x00222a34, 0x00212932, 0x00222a33, 0x00232a34, 0x00242832, 0x00232831, 0x00232830, 0x00242830, 0x00252830, 0x00272932, 0x00282a33, 0x00282a32, 0x00262831, 0x00242830, 0x00262831, 0x00282b34, 0x00282c36, 0x00292d37, 0x00292e38, 0x00292f39, 0x002b303d, 0x002c323f, 0x002e3544, 0x00323948, 0x00323b49, 0x00343d4b, 0x00333c4a, 0x00313a48, 0x002f3846, 0x002f3745, 0x00303844, 0x00313945, 0x00333b47, 0x00343d49, 0x0038404d, 0x00373f4c, 0x00363e4b, 0x00323a47, 0x002d3543, 0x002d3542, 0x002f3743, 0x002f3742, 0x00303743, 0x00313844, 0x00303944, 0x002c3642, 0x002a3642, 0x002c3944, 0x002b3844, 0x002c3945, 0x002f3c48, 0x0033404d, 0x00354350, 0x00364250, 0x0035414e, 0x0035414d, 0x0034404c, 0x00333d48, 0x00313c46, 0x002f3844, 0x002c3640, 0x0028333d, 0x0028333d, 0x002b3540, 0x002b3540, 0x0029343e, 0x0029333e, 0x002b3540, 0x002b3540, 0x002a343f, 0x002a343e, 0x002a343e, 0x002a333e, 0x0028303c, 0x001f2832, 0x00151e27, 0x00151e25, 0x001a242a, 0x001f2a30, 0x001f2c34, 0x00202f38, 0x00203038, 0x001e2c35, 0x001c2731, 0x001f2a34, 0x00212c36, 0x00212a34, 0x001f2730, 0x001c222b, 0x001c1f28, 0x001a1d24, 0x001c2026, 0x0020232a, 0x00242831, 0x00282c38, 0x00272f3c, 0x00242f3d, 0x001e2d3a, 0x00192b38, 0x00172935, 0x00152834, 0x00142733, 0x00122330, 0x0011202d, 0x00101f2c, 0x000f1c2a, 0x000e1c28, 0x000d1b27, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1925, 0x000d1925, 0x000e1a26, 0x000e1a26, 0x000e1a26, 0x000c1925, 0x000c1925, 0x000c1924, 0x000c1924, 0x000c1924, 0x000b1822, 0x000b1822, 0x000a1821, 0x000a1821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1720, 0x000b1620, 0x000b1720, 0x000c1821, 0x000c1721, 0x000b151e, 0x000b151c, 0x000c151c, 0x000d161d, 0x000d161e, 0x000c1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1720, 0x000c1821, 0x000c1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0013282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4347, 0x001c484c, 0x001d4d50, 0x00205254, 0x00215659, 0x00246976, 0x002e99bc, 0x0030a0c4, 0x00297b8d, 0x00266466, 0x00266466, 0x00276467, 0x00276568, 0x00276568, 0x00266568, 0x00276668, 0x00276668, 0x00286769, 0x00286769, 0x0028686a, 0x0028686b, 0x0028696c, 0x00286a6c, 0x00296b6d, 0x00296c6e, 0x00296c6e, 0x00296c6e, 0x00296c6e, 0x00296c6e, 0x00296b6d, 0x00286a6c, 0x0028696c, 0x00286769, 0x00276568, 0x00266467, 0x002e94b4, 0x002e9dc0, 0x0021585c, 0x001f5254, 0x001d4d50, 0x001c474b, 0x001a4245, 0x00183c40, 0x0016363b, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a161e, 0x000a161e, 0x0009151e, 0x0009151d, 0x0008141d, 0x000a161e, 0x000a161e, 0x000b171f, 0x000b171f, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c171f, 0x000c161f, 0x000c161f, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1820, 0x000b1920, 0x000a1920, 0x00091920, 0x000a1a21, 0x000b1b23, 0x000c1b24, 0x000c1b25, 0x000a1b26, 0x000a1b28, 0x000a1b27, 0x000a1c27, 0x000b1c27, 0x000b1c27, 0x000c1d28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000d1c27, 0x000d1c27, 0x000d1c27, 0x000d1c27, 0x000d1c27, 0x000d1c27, 0x000d1c27, 0x000d1c27, 0x000d1c28, 0x000d1c28, 0x000e1d2b, 0x000f1e2b, 0x000f1e2c, 0x00101f2c, 0x00132330, 0x00182937, 0x001d303e, 0x00213442, 0x00273444, 0x00283543, 0x00283240, 0x00262e3b, 0x00262e3b, 0x00262f3a, 0x00232c37, 0x00202b35, 0x001e2833, 0x001b2530, 0x0019232e, 0x001a242d, 0x00232d35, 0x002c3640, 0x002c3741, 0x002c3741, 0x002c3741, 0x002c3742, 0x002c3741, 0x002c3640, 0x002c3540, 0x002c3744, 0x002e3a45, 0x00303c47, 0x00303d47, 0x00313c48, 0x00303b47, 0x00303945, 0x002c3843, 0x002d3844, 0x00303b47, 0x00323e4a, 0x0034424d, 0x0035434e, 0x0037414d, 0x00353e4b, 0x00343d49, 0x00343e4a, 0x0036404d, 0x00394352, 0x00384353, 0x00384554, 0x003c4958, 0x003e4b5a, 0x003e4b5a, 0x003d4b5b, 0x003d4b5c, 0x003a4858, 0x00384655, 0x00364453, 0x0034414f, 0x00323f4b, 0x00313d49, 0x00303a47, 0x002e3744, 0x00303844, 0x00313844, 0x00303843, 0x002e3440, 0x002b303b, 0x00282d37, 0x00262a34, 0x00242832, 0x00242731, 0x00242831, 0x00252934, 0x00272a34, 0x00272a34, 0x00242832, 0x00242831, 0x00232832, 0x00212830, 0x0020262e, 0x001f242c, 0x001e232b, 0x001d212a, 0x0020232d, 0x00252a34, 0x002c313b, 0x00313540, 0x00313641, 0x00303640, 0x00303641, 0x002f3641, 0x00303741, 0x00303741, 0x002f3742, 0x002e3641, 0x002e3642, 0x002e3644, 0x002e3644, 0x002e3644, 0x002e3641, 0x002c3440, 0x002d3440, 0x002f3440, 0x00303641, 0x00313742, 0x00303541, 0x002e323e, 0x002c303a, 0x00262c35, 0x00212831, 0x00202730, 0x00222833, 0x00242b35, 0x00262c36, 0x00262b36, 0x00262b35, 0x00272c35, 0x00282c36, 0x002a2e37, 0x002c2f38, 0x002b2f38, 0x002b2e38, 0x00292d36, 0x00292d37, 0x002a2f38, 0x002c3139, 0x002e333c, 0x00303440, 0x00303643, 0x002f3644, 0x002e3644, 0x00303846, 0x00313a48, 0x00333d4c, 0x0035404e, 0x00343f4c, 0x00323c4b, 0x00323c4b, 0x00303b4a, 0x00313c4b, 0x00313c4b, 0x00323d4a, 0x00374350, 0x003c4854, 0x003e4856, 0x003d4754, 0x00394250, 0x00343d4c, 0x00313a47, 0x002f3845, 0x00303845, 0x00303946, 0x00323b48, 0x00323c48, 0x00303c46, 0x002a3843, 0x00283440, 0x0026333e, 0x0027313c, 0x0028333e, 0x00293440, 0x002d3843, 0x002f3844, 0x00303845, 0x00303844, 0x002f3844, 0x002e3843, 0x002e3843, 0x002c3640, 0x0029343e, 0x0028323c, 0x0029333d, 0x002a343f, 0x0029333d, 0x0028313c, 0x0028323c, 0x002b3540, 0x002c3741, 0x002c3741, 0x002c3641, 0x002c3641, 0x002c3540, 0x0028313c, 0x001f2832, 0x00161f27, 0x00141c24, 0x00151f25, 0x0019242b, 0x001d2a33, 0x00202e38, 0x00203038, 0x001e2c35, 0x001c2630, 0x00202934, 0x00202833, 0x001d242d, 0x00181d27, 0x00171b24, 0x00181a24, 0x00181c23, 0x001c1f25, 0x0020242b, 0x00262933, 0x002a2d39, 0x0028303c, 0x0024303d, 0x001f2e3b, 0x001b2c38, 0x00172936, 0x00152834, 0x00122531, 0x0011222f, 0x0010202c, 0x000e1c29, 0x000e1c28, 0x000d1a28, 0x000c1a27, 0x000c1926, 0x000c1926, 0x000c1926, 0x000c1926, 0x000c1926, 0x000c1926, 0x000c1926, 0x000d1925, 0x000d1925, 0x000e1a26, 0x000e1a26, 0x000e1a26, 0x000c1a26, 0x000b1926, 0x000c1925, 0x000c1924, 0x000c1924, 0x000c1923, 0x000c1923, 0x000b1822, 0x000b1822, 0x000b1822, 0x000c1822, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1822, 0x000c1722, 0x000c1722, 0x000c1722, 0x000c1722, 0x000c1722, 0x000b161f, 0x000b161e, 0x000c161e, 0x000c161e, 0x000c161f, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1720, 0x000c1721, 0x000c1721, 0x000c1721, 0x000c1821, 0x000c1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00132c32, 0x00143036, 0x0015363b, 0x00183c40, 0x001a4044, 0x001c4649, 0x001d4b4e, 0x001f5154, 0x00205558, 0x00256e7e, 0x002f9dc0, 0x00309fc2, 0x00287786, 0x00276568, 0x00276668, 0x00286769, 0x0028686a, 0x0028686a, 0x0028686a, 0x0028686a, 0x0028686a, 0x0028686a, 0x0028686b, 0x0028696c, 0x00286a6c, 0x00286a6c, 0x00296b6d, 0x00296c6f, 0x00296c6f, 0x002a6d6f, 0x002a6e70, 0x002a6e70, 0x002a6e70, 0x002a6e70, 0x002a6e70, 0x002a6d6f, 0x002a6c6e, 0x00286a6c, 0x0028686a, 0x00276669, 0x002f95b4, 0x002f9ec0, 0x00235c5f, 0x00205558, 0x001e5053, 0x001c4a4d, 0x001b4448, 0x00183f43, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0012242c, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a161e, 0x000a161e, 0x0009151e, 0x0008141d, 0x0008141c, 0x0008141d, 0x000a161e, 0x000b171f, 0x000b171f, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c171f, 0x000c161f, 0x000c161f, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1820, 0x000c1820, 0x000b1820, 0x000a1920, 0x000a1920, 0x000b1a22, 0x000c1a23, 0x000c1a24, 0x000c1b26, 0x000b1b27, 0x000b1b27, 0x000a1b26, 0x000b1c26, 0x000a1c26, 0x000b1c27, 0x000b1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000d1c28, 0x000d1c28, 0x000e1d29, 0x000e1d2a, 0x000e1d2b, 0x000f1e2c, 0x0012222f, 0x00152735, 0x001c2f3d, 0x00213341, 0x00263444, 0x00283443, 0x00283240, 0x00272e3c, 0x00272e3b, 0x00262f3b, 0x00232c37, 0x00202b35, 0x001d2731, 0x001a242f, 0x0019232d, 0x001b252e, 0x00232d35, 0x002c3640, 0x002c3741, 0x002c3741, 0x002c3741, 0x002c3741, 0x002c3741, 0x002c3640, 0x002c3641, 0x002d3844, 0x002f3b47, 0x002f3b44, 0x002f3b45, 0x00303c46, 0x00303b46, 0x00303944, 0x002c3540, 0x002c3540, 0x002e3945, 0x0034404c, 0x00384552, 0x00384552, 0x00394451, 0x0038404e, 0x0037404d, 0x00384250, 0x00394351, 0x00394454, 0x00384454, 0x00384856, 0x003d4c5b, 0x00404f5d, 0x00404f5d, 0x003f4d5d, 0x003e4c5c, 0x003e4c5c, 0x003f4c5c, 0x003d4a59, 0x003b4856, 0x00394754, 0x00374450, 0x0038424f, 0x0037404d, 0x00353f4a, 0x00343d48, 0x00323a44, 0x002e3540, 0x002c323c, 0x002a2f39, 0x00282d38, 0x00282c36, 0x00262b34, 0x00272b35, 0x00282d37, 0x002a2e38, 0x002b2f39, 0x00282d38, 0x00282c36, 0x00262b34, 0x00242932, 0x0020252d, 0x001e222a, 0x001c1f27, 0x001b1e26, 0x001e212b, 0x00242833, 0x002c313c, 0x00303541, 0x00303441, 0x00303440, 0x00303540, 0x00303640, 0x00303740, 0x00303740, 0x00303740, 0x002e3640, 0x002e3641, 0x002e3642, 0x002e3643, 0x002e3642, 0x002c3540, 0x002c343f, 0x002d3440, 0x00303440, 0x00303440, 0x00303440, 0x002e323e, 0x002c303c, 0x002c303b, 0x00282c36, 0x00232831, 0x0020252f, 0x00222631, 0x00262b36, 0x00282d39, 0x00282d38, 0x00282d38, 0x00282d38, 0x00293039, 0x002a303a, 0x002b303a, 0x002a2f39, 0x002a3039, 0x00292f38, 0x00292f38, 0x002b303a, 0x002d323c, 0x0030343f, 0x00323844, 0x00343c49, 0x00343e4c, 0x00353f4d, 0x00384150, 0x00394452, 0x00394553, 0x003b4754, 0x003b4754, 0x003a4654, 0x003c4756, 0x003c4958, 0x003d4b5a, 0x003c4b5a, 0x003a4858, 0x003c4a58, 0x003b4957, 0x00394855, 0x003c4855, 0x003a4654, 0x00384453, 0x0034404f, 0x00313c4b, 0x002f3b48, 0x00303c49, 0x00323d4c, 0x00303d4b, 0x002e3d48, 0x002c3943, 0x0029353f, 0x0026313c, 0x00253039, 0x00262f38, 0x00272f39, 0x00282f3a, 0x0028303c, 0x0028303d, 0x0028313c, 0x0028313c, 0x0028323c, 0x0028323c, 0x0028323c, 0x0027313c, 0x0028323c, 0x0029333d, 0x002a343e, 0x0028323c, 0x0026303c, 0x0028323c, 0x002c3640, 0x002d3842, 0x002d3842, 0x002d3842, 0x002d3742, 0x002b3540, 0x0026303a, 0x001d2730, 0x00182028, 0x00141d24, 0x00141d24, 0x00162028, 0x001b2830, 0x001f2c36, 0x00202f38, 0x00202c37, 0x00202934, 0x00202832, 0x001e242d, 0x00181c26, 0x00141720, 0x00151822, 0x00191c24, 0x001c1e26, 0x001f2229, 0x0023252e, 0x00272a35, 0x002a2e3c, 0x0028303d, 0x0025303e, 0x001f2e3b, 0x001a2b38, 0x00172835, 0x00142632, 0x00112330, 0x0010212d, 0x000d1e2b, 0x000c1c29, 0x000c1b28, 0x000c1a28, 0x000b1927, 0x000b1826, 0x000b1826, 0x000c1927, 0x000c1927, 0x000c1927, 0x000c1927, 0x000c1926, 0x000d1925, 0x000d1925, 0x000e1a26, 0x000e1a26, 0x000e1a26, 0x000c1a27, 0x000b1a27, 0x000b1926, 0x000c1925, 0x000c1925, 0x000c1924, 0x000c1924, 0x000b1823, 0x000b1822, 0x000b1822, 0x000c1824, 0x000c1824, 0x000c1824, 0x000c1824, 0x000c1824, 0x000c1723, 0x000c1723, 0x000c1723, 0x000c1723, 0x000c1723, 0x000b1620, 0x000b171f, 0x000b161f, 0x000c161f, 0x000c161f, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1721, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00153338, 0x0016383c, 0x00183d41, 0x001a4347, 0x001c484c, 0x001e4f51, 0x00205457, 0x00236068, 0x00309ec2, 0x002f9cbe, 0x0028737e, 0x00276668, 0x0028686a, 0x0028696c, 0x00286a6c, 0x00296b6d, 0x00286b6d, 0x00296b6d, 0x00296b6d, 0x00296b6d, 0x00296b6d, 0x00296b6d, 0x002a6c6e, 0x00296c6e, 0x00296c6f, 0x002a6d6f, 0x002a6e70, 0x002b6f70, 0x002b7071, 0x002b7072, 0x002b7072, 0x002b7072, 0x002b7072, 0x002b7072, 0x002c7071, 0x002a6e70, 0x00296c6f, 0x00286a6c, 0x0028686c, 0x003096b4, 0x00309ec0, 0x00245d60, 0x0021585a, 0x00205254, 0x001d4b4e, 0x001c4649, 0x00194044, 0x00183a3e, 0x00153439, 0x00142e34, 0x00112a30, 0x0011242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a1620, 0x000a1620, 0x000a1620, 0x0009151e, 0x0008141d, 0x0009151e, 0x000a161e, 0x000a171f, 0x000b1720, 0x000c1820, 0x000c1820, 0x000c1821, 0x000c1821, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c171f, 0x000c161f, 0x000c161f, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1720, 0x000c1820, 0x000c1820, 0x000b1820, 0x000b1920, 0x000b1920, 0x000c1a21, 0x000c1a23, 0x000c1a24, 0x000c1b26, 0x000b1a25, 0x000b1a25, 0x000b1a25, 0x000b1b26, 0x000c1c26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000d1c27, 0x000d1c27, 0x000d1c28, 0x000d1c29, 0x000d1c29, 0x000f1e2b, 0x0010202d, 0x00142433, 0x001c2c3a, 0x00223140, 0x00263443, 0x00283543, 0x00293442, 0x0028303e, 0x0028303c, 0x0027303c, 0x00232d38, 0x00202934, 0x001c2530, 0x0019232d, 0x0019232d, 0x001b252e, 0x00232d35, 0x002c3640, 0x002e3843, 0x002e3843, 0x002d3842, 0x002c3741, 0x002c3641, 0x002c3741, 0x002d3843, 0x002e3a45, 0x002f3a46, 0x002e3a44, 0x002f3944, 0x00303b45, 0x00313a44, 0x002e3641, 0x002c343e, 0x002c343e, 0x002e3844, 0x0034404c, 0x00384553, 0x00384654, 0x003b4654, 0x003c4454, 0x00394451, 0x00394452, 0x003a4754, 0x003b4857, 0x003b4958, 0x003c4b59, 0x003e4c5a, 0x00404e5c, 0x00404e5c, 0x003e4c5b, 0x003e4c5b, 0x00404d5c, 0x00404d5c, 0x003e4b5a, 0x003c4958, 0x003c4855, 0x00394652, 0x00394450, 0x0038424e, 0x00363e4a, 0x00353c48, 0x00313843, 0x002c323e, 0x002c303c, 0x002c303b, 0x002c303a, 0x002a2f39, 0x00292e38, 0x00292e38, 0x002a2f39, 0x002b303a, 0x002c303b, 0x002b303a, 0x00282e37, 0x00272b34, 0x00242830, 0x0020232b, 0x001c1f26, 0x00191c24, 0x001b1f27, 0x0020242d, 0x00282c36, 0x002c323c, 0x002f343f, 0x002f343f, 0x002f343f, 0x0030343f, 0x00303540, 0x00303740, 0x00303740, 0x00303740, 0x002f3740, 0x002f3741, 0x002e3642, 0x002e3643, 0x002e3441, 0x002d343f, 0x002c333d, 0x002c313c, 0x002c303c, 0x002b303c, 0x002c303c, 0x002c303c, 0x002d303c, 0x002c303c, 0x00292d38, 0x00242832, 0x0020242e, 0x00222530, 0x00252934, 0x00282c38, 0x00282e39, 0x00282e3a, 0x0029303c, 0x002c323c, 0x002c323c, 0x002c323c, 0x002b313b, 0x002b313b, 0x002a303b, 0x002b303b, 0x002c313c, 0x002e343f, 0x00303641, 0x00333a47, 0x00363f4d, 0x00384350, 0x003b4553, 0x003c4854, 0x003c4856, 0x003c4958, 0x003c4a58, 0x00404c5a, 0x00404c5a, 0x003f4b5b, 0x00404d5c, 0x0041505f, 0x00445362, 0x00445260, 0x0041505e, 0x003b4a58, 0x00374654, 0x00374454, 0x00364453, 0x00374454, 0x00354452, 0x0031404f, 0x00303f4e, 0x0031404f, 0x00334150, 0x00303f4c, 0x002e3c47, 0x002c3842, 0x0029343e, 0x0026303b, 0x00262e38, 0x00262e37, 0x00282f38, 0x00282f38, 0x0028303b, 0x0028303c, 0x0028303c, 0x0029313c, 0x0029323d, 0x0029323d, 0x0028323c, 0x0028323c, 0x0028323c, 0x0028323d, 0x0029333d, 0x0028323d, 0x0027313c, 0x0029343e, 0x002c3741, 0x002f3843, 0x002f3843, 0x002f3843, 0x002f3843, 0x002c3640, 0x0027303a, 0x001e2630, 0x00182028, 0x00151d24, 0x00141d24, 0x00172128, 0x001c2730, 0x001f2c35, 0x001e2a34, 0x001e2833, 0x001f2630, 0x001c212c, 0x00181d25, 0x00141820, 0x0013151e, 0x00171a22, 0x001c1e27, 0x0020232b, 0x00242830, 0x00282c35, 0x002b2f3b, 0x002c313f, 0x002b3340, 0x00263140, 0x001f2e3c, 0x00192a38, 0x00172834, 0x00142532, 0x0011232f, 0x0010202d, 0x000e1e2b, 0x000c1c28, 0x000d1b28, 0x000c1a27, 0x000c1927, 0x000c1926, 0x000c1926, 0x000c1927, 0x000c1927, 0x000c1927, 0x000c1927, 0x000c1926, 0x000d1925, 0x000d1925, 0x000d1925, 0x000d1925, 0x000d1a26, 0x000c1a27, 0x000c1a27, 0x000c1926, 0x000c1925, 0x000c1925, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1923, 0x000c1923, 0x000c1824, 0x000c1824, 0x000c1824, 0x000c1824, 0x000c1824, 0x000c1823, 0x000c1823, 0x000c1723, 0x000c1723, 0x000c1723, 0x000b1720, 0x000b1720, 0x000b171f, 0x000c161f, 0x000c161f, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1721, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012242c, 0x00112a30, 0x00142e34, 0x00153439, 0x00173a3e, 0x00193f43, 0x001b4448, 0x001d4b4e, 0x001f5154, 0x00215659, 0x0024646d, 0x0031a3c8, 0x002c879e, 0x00286769, 0x0028696c, 0x00296b6d, 0x00296c6f, 0x00296d6f, 0x002a6d6f, 0x002a6e70, 0x002a6d6f, 0x002a6d6f, 0x002a6d6f, 0x002a6d6f, 0x002a6e70, 0x002a6e70, 0x002b6e70, 0x002b6f70, 0x002b7071, 0x002b7072, 0x002c7173, 0x002b7173, 0x002c7274, 0x002c7374, 0x002c7374, 0x002c7374, 0x002c7374, 0x002c7274, 0x002b7072, 0x002b6f70, 0x00296c6f, 0x00296b6e, 0x003097b4, 0x00309fc1, 0x00246062, 0x0022595c, 0x00205356, 0x001d4d50, 0x001c474b, 0x00194044, 0x00173a3e, 0x00153439, 0x00143036, 0x00112a30, 0x0012282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091722, 0x00081721, 0x00081721, 0x000a1520, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a151f, 0x00091620, 0x00081722, 0x00081722, 0x00091823, 0x00091823, 0x00091821, 0x00091820, 0x00091820, 0x00091820, 0x00091820, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000b1720, 0x000b1720, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b171f, 0x000b171f, 0x000a1820, 0x000a1820, 0x000b1920, 0x000c1a21, 0x000c1a23, 0x000c1a24, 0x000c1a25, 0x000b1924, 0x000b1923, 0x000b1924, 0x000b1a24, 0x000b1a25, 0x000b1a25, 0x000b1a25, 0x000b1a25, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1c26, 0x000c1c25, 0x000c1c25, 0x000c1c27, 0x000c1c27, 0x000d1c28, 0x000e1d28, 0x000f1f2a, 0x00122330, 0x00172836, 0x001e2f3d, 0x00243442, 0x00283644, 0x002b3644, 0x002a3240, 0x0028303e, 0x0028303c, 0x00242d38, 0x001e2832, 0x001a242e, 0x0018222b, 0x0019232c, 0x001c252e, 0x00242d37, 0x002d3741, 0x00303944, 0x00303a44, 0x002d3843, 0x002b3741, 0x002b3541, 0x002c3642, 0x002e3844, 0x002f3a46, 0x002f3b45, 0x00303a44, 0x00303843, 0x00303843, 0x00303843, 0x002e3641, 0x002b333e, 0x002c343e, 0x002d3742, 0x00323d49, 0x00364350, 0x00384754, 0x003b4858, 0x003c4958, 0x003b4858, 0x00394858, 0x003b4958, 0x003c4a5a, 0x003c4a59, 0x003d4a58, 0x003d4a57, 0x003d4957, 0x00404c59, 0x00414d5b, 0x00424e5c, 0x00414d5b, 0x00404c59, 0x003d4857, 0x003c4856, 0x003c4755, 0x003a4451, 0x0038414e, 0x00363d4b, 0x00343a47, 0x00333843, 0x002f333e, 0x002a2e3a, 0x002b2f3b, 0x002c303c, 0x002c303c, 0x002c303c, 0x002c303c, 0x002c303c, 0x002b2f3b, 0x002a2f3b, 0x002b303a, 0x002b303a, 0x00292e38, 0x00272b34, 0x0022252d, 0x001d2027, 0x001a1d23, 0x001a1d24, 0x001e2129, 0x00242a32, 0x00283038, 0x002a323a, 0x002c323b, 0x002c323b, 0x002e333c, 0x002f343e, 0x0030343f, 0x00303540, 0x00303640, 0x00303741, 0x002e3842, 0x002e3843, 0x002e3842, 0x002d3641, 0x002c333e, 0x002b313b, 0x002a303a, 0x00292e38, 0x00292e38, 0x00282e39, 0x002a303b, 0x002c303c, 0x002c313d, 0x002c303c, 0x00292e39, 0x00242832, 0x0020242c, 0x0020242c, 0x00232831, 0x00282c37, 0x002a2f3b, 0x002b303c, 0x002c323f, 0x002f3441, 0x00303540, 0x002f3540, 0x002e3440, 0x002d343f, 0x002c333e, 0x002c323d, 0x002e3440, 0x00303541, 0x00303643, 0x00333846, 0x00343d4c, 0x00384250, 0x003c4754, 0x003e4a56, 0x003d4b57, 0x003e4c5a, 0x003f4c5c, 0x00414f5e, 0x00445260, 0x00435160, 0x00445060, 0x00445160, 0x00435060, 0x00404d5c, 0x003f4c5a, 0x003b4b58, 0x00384855, 0x00384755, 0x00374453, 0x00374453, 0x00344452, 0x00344351, 0x00344553, 0x00344552, 0x00354350, 0x00333e4b, 0x002f3944, 0x002b343f, 0x0028313b, 0x00252d37, 0x00252d36, 0x00252d36, 0x00272e37, 0x00272f38, 0x00273039, 0x0028303b, 0x0028303d, 0x002a323e, 0x002c333f, 0x002b333f, 0x002a333e, 0x0029333e, 0x0029333d, 0x0028323c, 0x0028323c, 0x0028323c, 0x0028333d, 0x00293540, 0x002c3843, 0x00303945, 0x00303944, 0x002f3944, 0x002f3844, 0x002c3440, 0x00272e38, 0x001e242e, 0x00192027, 0x00151e24, 0x00141c24, 0x00162029, 0x001c2731, 0x00222c36, 0x00202832, 0x001c242c, 0x001b2029, 0x00141921, 0x0013171f, 0x0012141c, 0x0014161f, 0x001a1c24, 0x001d202a, 0x0020242e, 0x00262a35, 0x002b303c, 0x002c3340, 0x002c3442, 0x002b3444, 0x00273341, 0x001e2d3c, 0x00182937, 0x00152634, 0x00142431, 0x0011232f, 0x0010202d, 0x000e1d2a, 0x000c1b28, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1925, 0x000d1925, 0x000c1924, 0x000b1824, 0x000b1824, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000c1a24, 0x000c1924, 0x000b1823, 0x000b1824, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1a25, 0x000d1a25, 0x000c1924, 0x000c1924, 0x000b1823, 0x000b1822, 0x000b1821, 0x000b1821, 0x000a1821, 0x000b1821, 0x000c1822, 0x000c1822, 0x000c1721, 0x000b1622, 0x000c1723, 0x000b1821, 0x000b1821, 0x000b1820, 0x000b1820, 0x000b1820, 0x000b1821, 0x000b1820, 0x000c1820, 0x000c1720, 0x000a1720, 0x00091720, 0x00091720, 0x00091720, 0x000a1821, 0x000a1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012282e, 0x00112a30, 0x00142e34, 0x00143439, 0x00183c40, 0x00194044, 0x001c474b, 0x001e4d50, 0x00205356, 0x0022585b, 0x0025666f, 0x0031a4c8, 0x002c889e, 0x0028696c, 0x00296c6f, 0x002a6e70, 0x002b7071, 0x002b7072, 0x002b7072, 0x002b7072, 0x002b7072, 0x002b7072, 0x002c7072, 0x002b7072, 0x002b7072, 0x002b7072, 0x002b7173, 0x002b7173, 0x002c7274, 0x002c7274, 0x002c7374, 0x002c7475, 0x002c7476, 0x002c7476, 0x002c7476, 0x002c7476, 0x002c7476, 0x002c7475, 0x002c7374, 0x002c7173, 0x002b6f70, 0x00296c6f, 0x003098b4, 0x00309fc1, 0x00256164, 0x00235a5c, 0x00205457, 0x001e4f51, 0x001c484c, 0x00194245, 0x00183c40, 0x00153439, 0x00143036, 0x00132c32, 0x0012282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081722, 0x00081722, 0x00081722, 0x000a1620, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a151f, 0x00091621, 0x00081722, 0x00081722, 0x00081823, 0x00081823, 0x00081821, 0x00081820, 0x00081820, 0x00081820, 0x00081820, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1821, 0x000c1821, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b171f, 0x000b171f, 0x000b171f, 0x0009171f, 0x000a1820, 0x000a1820, 0x000c1a21, 0x000c1a21, 0x000b1922, 0x000b1823, 0x000b1822, 0x000b1822, 0x000b1822, 0x00091924, 0x000a1924, 0x000a1a24, 0x000b1a25, 0x000b1a25, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1c25, 0x000c1c25, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000d1d27, 0x000e1f28, 0x0011222f, 0x00152634, 0x001c2d3c, 0x00233442, 0x00283745, 0x002c3847, 0x002c3444, 0x0029313f, 0x0028303c, 0x00242c38, 0x001c2530, 0x0018222c, 0x0017212a, 0x0019232c, 0x001c252e, 0x00232d36, 0x002e3843, 0x00323c48, 0x00333d48, 0x00303c45, 0x002d3943, 0x002c3643, 0x002c3542, 0x002c3844, 0x002e3a44, 0x002e3a44, 0x002e3843, 0x002c3540, 0x002d3540, 0x002d3540, 0x002c3440, 0x002b333d, 0x002b333e, 0x002b343f, 0x002d3843, 0x00323e4a, 0x00364551, 0x003a4957, 0x003c4c5b, 0x003c4c5a, 0x003c4b5b, 0x003c4a5b, 0x003c4959, 0x003a4856, 0x003c4755, 0x003b4654, 0x00394453, 0x003d4856, 0x003d4857, 0x003d4857, 0x003e4a58, 0x003d4957, 0x003c4855, 0x003c4755, 0x003c4554, 0x003b4350, 0x00383f4c, 0x00353a48, 0x00323642, 0x0030343e, 0x002e313c, 0x002c2f3b, 0x002c313d, 0x002e343f, 0x002f3440, 0x002f3440, 0x00303541, 0x00303641, 0x002e343f, 0x002c323e, 0x002b313c, 0x002a303a, 0x00282d37, 0x00252832, 0x0020242c, 0x001c1f25, 0x001c1f25, 0x001c2027, 0x0021252d, 0x00282d35, 0x00293139, 0x00293239, 0x00293038, 0x002b3039, 0x002c313b, 0x002e333c, 0x002f343d, 0x0030353f, 0x00303640, 0x00303641, 0x002f3843, 0x002f3843, 0x002e3842, 0x002c3540, 0x002c333d, 0x002a303a, 0x00292f38, 0x00282e38, 0x00282d38, 0x00282d38, 0x00292f39, 0x002a303b, 0x002a303c, 0x002b313c, 0x002a303b, 0x00262b34, 0x0021262f, 0x001d222a, 0x0020242c, 0x00252a34, 0x002a2f3a, 0x002c303c, 0x002d3340, 0x002f3542, 0x00303742, 0x00303843, 0x00303843, 0x00303843, 0x00303742, 0x00303642, 0x00303744, 0x00313845, 0x00333947, 0x00343b49, 0x00353d4d, 0x00374250, 0x003a4553, 0x003b4854, 0x003b4857, 0x003b4a59, 0x003d4c5c, 0x00404f5e, 0x0041505f, 0x00425060, 0x00435060, 0x00404e5d, 0x003c4958, 0x003b4857, 0x00394756, 0x00384755, 0x00364854, 0x00374854, 0x00384854, 0x00384655, 0x00354453, 0x00364454, 0x00384857, 0x00384856, 0x00364451, 0x00333e4c, 0x002d3844, 0x0029313c, 0x00262e38, 0x00242d36, 0x00262e37, 0x00262e37, 0x00262e37, 0x00262e37, 0x00272f38, 0x00272f39, 0x0028303c, 0x002b3240, 0x002c3340, 0x002c3340, 0x002c3340, 0x002b3440, 0x002b343f, 0x002a343e, 0x0028323c, 0x0028323c, 0x0029343e, 0x002a3641, 0x002d3844, 0x00303a46, 0x00303a46, 0x00303945, 0x002f3844, 0x002c3440, 0x00262c38, 0x001d242c, 0x00192026, 0x00161e24, 0x00141c24, 0x0017202a, 0x001c2730, 0x00232c37, 0x00222a34, 0x001c232b, 0x00171c24, 0x0010151c, 0x000f141a, 0x0011151c, 0x00171a22, 0x001d1f28, 0x001f222c, 0x00212530, 0x00262c36, 0x002b313d, 0x002c3441, 0x002c3443, 0x002c3544, 0x00273341, 0x001e2d3c, 0x00172836, 0x00152534, 0x00132430, 0x0010212e, 0x000f1f2c, 0x000d1c29, 0x000c1a27, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1925, 0x000d1925, 0x000c1923, 0x000b1822, 0x000b1823, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000c1a24, 0x000b1923, 0x000b1822, 0x000b1823, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000d1a26, 0x000c1924, 0x000c1924, 0x000b1823, 0x000b1920, 0x000b1920, 0x000a1820, 0x000a1820, 0x000b1820, 0x000c1821, 0x000c1822, 0x000c1721, 0x000b1622, 0x000b1622, 0x000b1822, 0x000b1822, 0x000a1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000b1820, 0x000c1820, 0x000c1820, 0x000a1720, 0x00091720, 0x00091720, 0x00091720, 0x000a1821, 0x000a1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00122c32, 0x00143036, 0x0016363b, 0x00183c40, 0x001a4245, 0x001c484c, 0x001e4f51, 0x00205558, 0x00235a5c, 0x00266870, 0x0032a4c8, 0x003096b4, 0x002f899e, 0x002f8b9f, 0x00308ca0, 0x00308da0, 0x00308da0, 0x00318da0, 0x00318da0, 0x00318da0, 0x00318da0, 0x00308da0, 0x00308da0, 0x00308da0, 0x00308da0, 0x00308da0, 0x00318da0, 0x00318ea1, 0x00318ea1, 0x00318fa1, 0x00318fa1, 0x00318fa1, 0x003190a2, 0x003190a2, 0x003190a2, 0x003190a2, 0x00318fa1, 0x00318ea1, 0x00308da0, 0x00308ca0, 0x002f8b9f, 0x00329ebf, 0x0031a0c1, 0x00256264, 0x00235c5e, 0x00205558, 0x001f5053, 0x001c484c, 0x001a4245, 0x00183c40, 0x0015363b, 0x00143036, 0x00132c32, 0x0012282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081722, 0x00081722, 0x00081722, 0x000a1620, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a151f, 0x00091621, 0x00081722, 0x00081722, 0x00081823, 0x00081823, 0x00081821, 0x00081820, 0x00081820, 0x00081820, 0x00081820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000b1821, 0x000b1821, 0x000b1720, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x0009171f, 0x0009171f, 0x000a1820, 0x000b1920, 0x000c1a21, 0x000b1920, 0x000b1920, 0x000b1821, 0x000b1822, 0x000b1822, 0x00091924, 0x00091924, 0x000a1924, 0x000b1924, 0x000b1924, 0x000c1a25, 0x000c1a26, 0x000c1a26, 0x000c1a26, 0x000c1a26, 0x000c1a26, 0x000c1a26, 0x000c1b26, 0x000c1c25, 0x000c1c25, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000d1c26, 0x000e1d27, 0x0010202d, 0x00142433, 0x001a2b39, 0x00203140, 0x00263644, 0x002c3a49, 0x002f3847, 0x002b3340, 0x0028303c, 0x00202a35, 0x0019242e, 0x0017212b, 0x0018212a, 0x001a242c, 0x001c262f, 0x00232d37, 0x002f3844, 0x00343e4a, 0x00353f49, 0x00333e48, 0x00303b45, 0x002d3844, 0x002c3542, 0x002c3643, 0x002a3641, 0x002a3640, 0x002b3540, 0x002b343f, 0x002c333e, 0x002c343f, 0x002c343f, 0x002b333e, 0x002c343e, 0x002b343f, 0x002b3640, 0x002e3b46, 0x0034424e, 0x003a4855, 0x003c4b58, 0x003c4a58, 0x003b4958, 0x003d4c5b, 0x003e4c5b, 0x003d4a58, 0x003c4856, 0x003b4754, 0x00394452, 0x00394453, 0x00394452, 0x00384451, 0x00394452, 0x003a4654, 0x003a4654, 0x003a4554, 0x003b4453, 0x0039404f, 0x00363d4a, 0x00333946, 0x00313542, 0x0030353f, 0x00323640, 0x00323642, 0x00333844, 0x00323844, 0x00323844, 0x00313843, 0x00323844, 0x00313844, 0x00303742, 0x002f3440, 0x002c323c, 0x00282f38, 0x00252934, 0x0022242f, 0x001f222a, 0x001e2128, 0x00202328, 0x0020242a, 0x00242830, 0x002a2f37, 0x002a3139, 0x00293139, 0x00293038, 0x00292f38, 0x002c303a, 0x002c313c, 0x002e333c, 0x002f343d, 0x002f353e, 0x00303640, 0x002f3843, 0x00303a44, 0x00303944, 0x002f3742, 0x002e3440, 0x002a303b, 0x002b303a, 0x002a2f39, 0x00292e39, 0x00282d38, 0x00272c37, 0x00282d38, 0x00282e3a, 0x002a303c, 0x002b303c, 0x00282d37, 0x00232830, 0x001f232b, 0x001d212a, 0x00202530, 0x00282c38, 0x002c303d, 0x002c323f, 0x002d3440, 0x00303642, 0x00303843, 0x00303843, 0x00323a45, 0x00343c48, 0x00343c48, 0x00363c4a, 0x00373c4b, 0x00383e4c, 0x00383f4e, 0x00384051, 0x00384352, 0x003a4554, 0x003b4755, 0x003a4858, 0x003c4b5c, 0x003c4c5d, 0x003e4f5e, 0x003f4e5e, 0x003d4c5c, 0x003d4a5b, 0x003c4959, 0x003c4858, 0x003c4858, 0x00394757, 0x00394756, 0x00374755, 0x00384855, 0x00394857, 0x00394858, 0x00394857, 0x00394857, 0x00394958, 0x00374856, 0x0034424f, 0x00303b48, 0x002b3441, 0x0028313c, 0x00262e38, 0x00252d38, 0x00262f38, 0x00272f38, 0x00273038, 0x00283038, 0x00272f38, 0x0028303a, 0x0029313d, 0x002b333f, 0x002c333f, 0x002c333f, 0x002c333f, 0x002c3540, 0x002c3641, 0x002b3540, 0x002a343e, 0x0029333d, 0x002a343f, 0x002c3843, 0x002e3a45, 0x002f3b47, 0x002f3946, 0x002f3945, 0x002f3844, 0x002c3440, 0x00262c38, 0x001c222c, 0x00181f25, 0x00151d23, 0x00131c24, 0x0017202a, 0x001c2630, 0x00212b35, 0x00202832, 0x001c222a, 0x00161c23, 0x0013181e, 0x0012171d, 0x00151a20, 0x00181c24, 0x001c1f28, 0x001e202c, 0x0020252f, 0x00252b35, 0x0029303c, 0x002c3440, 0x002c3443, 0x002c3544, 0x00263241, 0x001c2c3a, 0x00162635, 0x00142433, 0x0011232f, 0x0010202d, 0x000e1e2b, 0x000c1c28, 0x000b1a27, 0x000b1925, 0x000b1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1924, 0x000b1823, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1b24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1923, 0x000b1920, 0x000b1920, 0x000b1820, 0x000a1820, 0x000b1820, 0x000c1821, 0x000c1821, 0x000b1821, 0x000b1721, 0x000c1722, 0x000b1822, 0x000b1822, 0x000a1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000b1821, 0x000c1820, 0x000c1820, 0x000b1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0016363b, 0x00183d41, 0x001a4347, 0x001c4a4d, 0x001e5053, 0x00215659, 0x00245c5f, 0x0026676d, 0x00319ebf, 0x0034a8cc, 0x0035a8cc, 0x0036a9cc, 0x0037aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038abcc, 0x0038abcc, 0x0038abcc, 0x0038abcc, 0x0038abcc, 0x0038abcc, 0x0038aacc, 0x0037aacc, 0x0037a9cc, 0x0036a8cc, 0x0034a8cc, 0x003096b3, 0x00256264, 0x00235c5e, 0x00215659, 0x001f5053, 0x001c484c, 0x001b4347, 0x00183c40, 0x0015363b, 0x00143036, 0x00132c32, 0x0012282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081722, 0x00081722, 0x00081722, 0x000a1620, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a151f, 0x00091621, 0x00081722, 0x00081722, 0x00081823, 0x00081823, 0x00081821, 0x00081820, 0x00081820, 0x00081820, 0x00081820, 0x00081820, 0x00081820, 0x00091820, 0x000a1821, 0x000a1821, 0x000a1720, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b1820, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1820, 0x000b1821, 0x000b1821, 0x000b1823, 0x000b1823, 0x000b1824, 0x000c1924, 0x000c1924, 0x000c1a25, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000c1a25, 0x000c1c25, 0x000c1c25, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000d1b25, 0x000e1c26, 0x000f1e2a, 0x00102030, 0x00172836, 0x001d2e3c, 0x00253544, 0x002e3b4a, 0x00303a49, 0x002c3340, 0x00262e3b, 0x001e2832, 0x0019232d, 0x0018222c, 0x0018222b, 0x001b252d, 0x001e2830, 0x00232d37, 0x002f3845, 0x00343e4b, 0x00353f4b, 0x00343f4a, 0x00313c48, 0x002f3945, 0x002c3643, 0x002c3744, 0x002c3844, 0x002c3844, 0x002c3542, 0x002b3440, 0x002c3340, 0x002c343f, 0x002c343f, 0x002b333e, 0x002c343e, 0x002c343f, 0x002b3540, 0x002c3842, 0x00313d48, 0x00384450, 0x003c4753, 0x003b4754, 0x003d4857, 0x003f4c59, 0x00404c5a, 0x003f4c5a, 0x00404c59, 0x00404b59, 0x003d4957, 0x003c4755, 0x00394554, 0x00384452, 0x00384452, 0x00384352, 0x00384352, 0x00374252, 0x00384150, 0x00373e4e, 0x00363c4b, 0x00343a48, 0x00343a46, 0x00363c48, 0x00383d48, 0x00373d48, 0x00373d48, 0x00363e48, 0x00363d48, 0x00353d48, 0x00353d48, 0x00343c47, 0x00313944, 0x00303641, 0x002c323c, 0x00272d36, 0x00222731, 0x0020242e, 0x0020222b, 0x0020232a, 0x0021242b, 0x0024272d, 0x00272b33, 0x00292f37, 0x00293037, 0x00293038, 0x00293037, 0x002a3038, 0x002c303b, 0x002d323c, 0x002e333c, 0x002e343c, 0x002e343d, 0x002e3440, 0x002f3842, 0x002f3944, 0x002f3843, 0x002f3742, 0x002d3440, 0x002a303a, 0x002a303a, 0x002c303a, 0x002a2f39, 0x00282d38, 0x00272b35, 0x00272b35, 0x00282c36, 0x002a2f39, 0x00293039, 0x00282d35, 0x00242831, 0x0021242d, 0x001f222b, 0x0020232e, 0x00272936, 0x002c303d, 0x002e3440, 0x00303643, 0x00313844, 0x00323a45, 0x00323a46, 0x00333b48, 0x00343c49, 0x00383e4c, 0x003a4050, 0x003b4150, 0x003c4151, 0x003d4454, 0x003c4556, 0x003b4656, 0x003c4757, 0x003d4858, 0x003d4c5c, 0x003e4c5e, 0x003d4c5f, 0x003e4f5f, 0x003f4f5f, 0x003f4c5d, 0x003f4c5d, 0x003d4b5c, 0x003d4a5c, 0x003d4a5c, 0x003c495b, 0x003b4859, 0x00394959, 0x003b4b5a, 0x003c4c5b, 0x003c4c5b, 0x003d4c5c, 0x003c4b5a, 0x00394856, 0x00344250, 0x002e3a48, 0x002a3440, 0x0028303c, 0x0028303a, 0x00262e38, 0x00252d38, 0x00262e37, 0x00272f38, 0x0029323b, 0x0029323b, 0x0029313a, 0x002a333c, 0x002b333e, 0x002c343e, 0x002c343e, 0x002c343f, 0x002d3540, 0x002d3641, 0x002d3842, 0x002c3741, 0x002b3540, 0x002a343e, 0x002a343f, 0x002d3944, 0x002e3a46, 0x002f3b47, 0x002e3a46, 0x002f3945, 0x002f3844, 0x002b3440, 0x00252c38, 0x001c232c, 0x00181e24, 0x00141c22, 0x00121b22, 0x00162029, 0x001c2630, 0x00202934, 0x00202832, 0x001c232c, 0x00181c25, 0x00161b23, 0x00181c24, 0x001a1f27, 0x001b2028, 0x001c2028, 0x001e212c, 0x00202430, 0x00242a35, 0x00282f3b, 0x002c3340, 0x002c3443, 0x002b3544, 0x00243040, 0x001a2938, 0x00152434, 0x00142432, 0x0010222e, 0x000f202c, 0x000d1d2a, 0x000c1b28, 0x000b1a26, 0x000b1a25, 0x000b1a25, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000c1924, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000d1b24, 0x000d1b24, 0x000d1a25, 0x000d1a26, 0x000d1a26, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000c1a21, 0x000c1a21, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1820, 0x000c1821, 0x000c1821, 0x000b1822, 0x000b1822, 0x000a1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000b1821, 0x000c1821, 0x000c1821, 0x000c1822, 0x000b1823, 0x000c1924, 0x000b1823, 0x000b1822, 0x000b1822, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0016383c, 0x00183d41, 0x001b4448, 0x001d4b4e, 0x00205154, 0x0021585a, 0x00245d60, 0x00256264, 0x0029737e, 0x002d8496, 0x002e8698, 0x002f8898, 0x0030899a, 0x00308a9a, 0x00318a9b, 0x00318b9b, 0x00318b9b, 0x00318b9b, 0x00318b9b, 0x00318a9b, 0x00308a9b, 0x00308a9b, 0x00308a9a, 0x00308a9a, 0x00308a9a, 0x00308a9a, 0x00308a9b, 0x00308a9b, 0x00318b9b, 0x00318b9b, 0x00318b9b, 0x00318b9b, 0x00318b9b, 0x00318b9b, 0x00318b9b, 0x00308a9a, 0x0030899a, 0x002f8898, 0x002e8697, 0x002c8394, 0x00286c72, 0x00256163, 0x00235c5e, 0x00205558, 0x001f5053, 0x001c484c, 0x001a4245, 0x00183c40, 0x0015363b, 0x00143036, 0x00132c32, 0x0012282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081720, 0x00081721, 0x00081721, 0x000a1620, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a151f, 0x00091621, 0x00081722, 0x00081722, 0x00091823, 0x00091823, 0x00081821, 0x00081820, 0x00081820, 0x00081820, 0x00081820, 0x00081820, 0x00081820, 0x00091820, 0x00091820, 0x000a1821, 0x000a1720, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b161f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b181f, 0x000a1820, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1823, 0x000b1823, 0x000c1924, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1a25, 0x000c1c25, 0x000c1c25, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000d1b25, 0x000d1c25, 0x000d1c28, 0x000e1e2c, 0x00142433, 0x001b2c3a, 0x00233442, 0x002c3949, 0x002e3948, 0x00283240, 0x00242c39, 0x001d2733, 0x0019232e, 0x0019222c, 0x0019222b, 0x001c242d, 0x001e2830, 0x00242c38, 0x002e3844, 0x00343e4b, 0x00343f4b, 0x00333e4a, 0x00313d49, 0x00303c48, 0x002e3946, 0x002d3845, 0x002d3844, 0x002d3844, 0x002c3542, 0x002b3440, 0x002c3340, 0x002c333f, 0x002c343f, 0x002c343e, 0x002c343e, 0x002c343e, 0x002a323d, 0x002a343e, 0x00303844, 0x00363f4b, 0x003a4450, 0x003b4451, 0x003c4754, 0x003e4956, 0x003f4a58, 0x003e4a58, 0x003d4856, 0x003c4855, 0x003c4856, 0x003c4957, 0x003a4656, 0x00384454, 0x00384352, 0x00374251, 0x00364251, 0x00374252, 0x00384151, 0x0037404f, 0x00353e4c, 0x00353d4c, 0x00383e4c, 0x0039404d, 0x003b404d, 0x003b404d, 0x003a404d, 0x0038404c, 0x0038404c, 0x0038404c, 0x0038404c, 0x0038404b, 0x00363e48, 0x00333945, 0x002d343f, 0x00282e38, 0x00222831, 0x0020252f, 0x0020242e, 0x0022252c, 0x0024272e, 0x00272931, 0x00282c35, 0x00282e36, 0x00282f36, 0x00293037, 0x002a3038, 0x002b3039, 0x002d313c, 0x002d323c, 0x002e333c, 0x002e343d, 0x002e343d, 0x002f3440, 0x002c3641, 0x002c3741, 0x002c3640, 0x002c3440, 0x002c333e, 0x0029303a, 0x00292f38, 0x002a2e38, 0x00292e38, 0x00282c37, 0x00262a34, 0x00252a34, 0x00272c35, 0x00292e38, 0x00292f38, 0x00282d35, 0x00262b33, 0x0024272f, 0x0020242c, 0x001f222d, 0x00232632, 0x00292c3a, 0x002e3341, 0x00303644, 0x00323946, 0x00353d4a, 0x00353e4b, 0x00353e4c, 0x0037404e, 0x00384050, 0x00384051, 0x00384152, 0x00394253, 0x003c4455, 0x003d4556, 0x003a4454, 0x00394454, 0x003b4757, 0x003c495b, 0x003d4b5c, 0x003c4a5c, 0x003c4b5c, 0x003d4b5c, 0x003e4c5c, 0x003e4c5d, 0x003d4c5c, 0x003c4a5c, 0x003c4a5c, 0x003d4c5c, 0x003f4d5e, 0x003e4e5e, 0x003e4e5d, 0x003f4e5c, 0x003e4c5c, 0x003c4b59, 0x00394654, 0x0034404d, 0x002d3a48, 0x002b3643, 0x0027303c, 0x00262e39, 0x00262e38, 0x00272e38, 0x00262e37, 0x00262e37, 0x00272f38, 0x00283038, 0x0028313a, 0x0029323b, 0x002b343c, 0x002c343f, 0x002c343f, 0x002c3440, 0x002c3440, 0x002d3541, 0x002e3842, 0x00303944, 0x002f3843, 0x002e3843, 0x002c3741, 0x002a3640, 0x002e3a44, 0x002e3b46, 0x002f3b47, 0x002e3a46, 0x002e3945, 0x002e3844, 0x002c3441, 0x00262c39, 0x001c232c, 0x00181f24, 0x00161e24, 0x00121b23, 0x00141d27, 0x001c2630, 0x00202833, 0x00202832, 0x001d252e, 0x001b2029, 0x00191d27, 0x001c2029, 0x001e232c, 0x001f232d, 0x001e232d, 0x001f232f, 0x00202632, 0x00242a37, 0x00282e3c, 0x002b3341, 0x002c3444, 0x002b3443, 0x00212c3c, 0x00182836, 0x00142432, 0x00132330, 0x0011212d, 0x000f1f2c, 0x000d1c29, 0x000c1a27, 0x000a1926, 0x000b1a25, 0x000b1a25, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1a25, 0x000d1a26, 0x000d1a26, 0x000d1b24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1923, 0x000c1922, 0x000c1921, 0x000b1920, 0x000c1a21, 0x000b1920, 0x000b1920, 0x000b1820, 0x000c1821, 0x000c1821, 0x000b1822, 0x000b1822, 0x000a1821, 0x000a1821, 0x000b1822, 0x000b1822, 0x000c1822, 0x000c1822, 0x000c1822, 0x000c1822, 0x000b1923, 0x000c1924, 0x000b1823, 0x000b1822, 0x000b1822, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0017383c, 0x00183f43, 0x001c4448, 0x001d4b4e, 0x00205154, 0x0021585a, 0x00245d60, 0x00266466, 0x002c8093, 0x003198b5, 0x00339ab6, 0x00349bb7, 0x00349cb7, 0x00349cb8, 0x00359db8, 0x00359db8, 0x00359db8, 0x00359db8, 0x00359db8, 0x00359db8, 0x00359cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00359cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb7, 0x00339bb7, 0x00329ab6, 0x003198b5, 0x002a7c8d, 0x00256163, 0x00245c5e, 0x00205558, 0x001e4f51, 0x001c484c, 0x00194245, 0x00183c40, 0x00153439, 0x00143036, 0x00112a30, 0x0012282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0009151d, 0x000a161d, 0x000a161d, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a151f, 0x000a151f, 0x000b1620, 0x000b1620, 0x000a1620, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161f, 0x000b1621, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1620, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b1820, 0x000b1820, 0x000b1820, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000b1823, 0x000b1824, 0x000b1824, 0x000b1822, 0x000b1822, 0x000b1924, 0x000b1a25, 0x000b1925, 0x000c1925, 0x000c1a26, 0x000d1b26, 0x000e1b27, 0x000d1b26, 0x000c1a26, 0x000d1b26, 0x000c1c27, 0x000c1c29, 0x0010212e, 0x00152735, 0x001e2f3f, 0x00273747, 0x002a3947, 0x0025313f, 0x00202a38, 0x001d2734, 0x001c2431, 0x001b222e, 0x001b232e, 0x001c2530, 0x00202834, 0x00242c39, 0x002c3644, 0x00343e4c, 0x00333f4c, 0x00313f4c, 0x00303d4b, 0x00303d4b, 0x00303c4a, 0x002e3a48, 0x002d3844, 0x002e3844, 0x002d3643, 0x002c3441, 0x002c3440, 0x002c343f, 0x002c343f, 0x002c343f, 0x002c343f, 0x002c343f, 0x002c323c, 0x002c323c, 0x002e343e, 0x00333a44, 0x0038404c, 0x00394450, 0x00394652, 0x003c4854, 0x003e4a57, 0x003c4855, 0x003a4653, 0x003b4754, 0x003b4855, 0x003b4855, 0x00394855, 0x00384755, 0x00384655, 0x00384655, 0x00384655, 0x00384655, 0x00394454, 0x00374351, 0x00364050, 0x00384251, 0x00384353, 0x00384352, 0x00394351, 0x003b4451, 0x003b4554, 0x00394654, 0x00384553, 0x00394452, 0x00384451, 0x0038414f, 0x00343d49, 0x00303641, 0x002b313a, 0x00262d34, 0x00222931, 0x0022272f, 0x0022262f, 0x00242830, 0x00272a31, 0x00282b34, 0x002a2c35, 0x00292e37, 0x00292e37, 0x002a2f38, 0x002c313a, 0x002e333c, 0x002e333c, 0x002e333c, 0x002e333c, 0x002e343d, 0x002f353e, 0x00303640, 0x002e3641, 0x002e3742, 0x002f3742, 0x002e3540, 0x002c343e, 0x0028303b, 0x00282e39, 0x002a2f3a, 0x002a2f3b, 0x00292d39, 0x00262b36, 0x00262a34, 0x00272c35, 0x00282d37, 0x00282d37, 0x00282e37, 0x00272c36, 0x00242b34, 0x00212730, 0x001f242f, 0x0020242d, 0x00242933, 0x002a303c, 0x002f3542, 0x00353e4b, 0x00384250, 0x00374350, 0x00374352, 0x00394454, 0x003a4454, 0x003a4454, 0x003b4656, 0x003b4656, 0x003c4656, 0x003c4456, 0x003b4454, 0x00394454, 0x00394457, 0x00384558, 0x00394757, 0x003a4858, 0x003c4959, 0x003e4c5b, 0x003e4b5b, 0x003d4c5b, 0x003c4c5c, 0x003b4b5a, 0x003b4b5a, 0x003e4c5d, 0x003f4d5e, 0x003e4d5e, 0x003c4c5b, 0x003c4c59, 0x003c4a58, 0x003a4554, 0x00343e4c, 0x002f3846, 0x002b3442, 0x0029343f, 0x0026303c, 0x00262f3a, 0x00272f3a, 0x00272f39, 0x00272f39, 0x00272f3a, 0x00272f39, 0x00262e38, 0x00272f39, 0x0028303b, 0x0029323c, 0x002b343e, 0x002b3540, 0x002c3640, 0x002c3640, 0x002d3642, 0x00303844, 0x00303a45, 0x00303a45, 0x00303a45, 0x002c3844, 0x002c3744, 0x002e3945, 0x002e3b47, 0x002f3b47, 0x002f3b47, 0x002e3945, 0x002f3844, 0x002e3540, 0x00262c38, 0x001d232c, 0x00181d25, 0x00181e25, 0x00151c24, 0x00141c25, 0x001c242d, 0x00202831, 0x00202831, 0x001d252e, 0x001c212b, 0x001b2028, 0x001e242c, 0x00222830, 0x00222831, 0x00222630, 0x00212530, 0x00222734, 0x00252a38, 0x00282e3c, 0x002c3341, 0x002c3543, 0x00283440, 0x001f2c39, 0x00182733, 0x0014242e, 0x0014212c, 0x0014202c, 0x00121f2b, 0x00101c28, 0x000d1925, 0x000d1a24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000b1823, 0x000c1924, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000d1a25, 0x000d1b25, 0x000d1b24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000d1a25, 0x000d1a26, 0x000d1a26, 0x000d1b24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1925, 0x000d1a26, 0x000d1a26, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000b1824, 0x000b1824, 0x000b1824, 0x000c1924, 0x000c1a23, 0x000c1a23, 0x000c1a23, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00142e34, 0x00143036, 0x0017383c, 0x00183f43, 0x001c4448, 0x001d4b4e, 0x00205154, 0x0021585a, 0x00245d60, 0x00287584, 0x0033a4c8, 0x0034a4c6, 0x0034a3c3, 0x0035a4c3, 0x0036a4c4, 0x0037a4c4, 0x0037a5c4, 0x0037a5c4, 0x0037a5c4, 0x0037a5c4, 0x0037a5c4, 0x0037a5c4, 0x0037a4c4, 0x0037a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c3, 0x0035a4c3, 0x0034a3c3, 0x0034a2c3, 0x0034a4c8, 0x00319ebf, 0x00246063, 0x00235a5c, 0x00205457, 0x001e4f51, 0x001c474b, 0x001a4245, 0x00173c40, 0x00153439, 0x00143036, 0x00112a30, 0x0012282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0008141a, 0x0008151b, 0x0008151b, 0x000a161d, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000b171f, 0x000b171f, 0x000a171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a1520, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1620, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b1820, 0x000c1820, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000b1823, 0x000b1824, 0x000b1823, 0x000b1822, 0x000b1822, 0x000b1924, 0x000b1a25, 0x000b1925, 0x000b1824, 0x000b1824, 0x000c1924, 0x000c1925, 0x000c1924, 0x000b1924, 0x000c1925, 0x000c1a26, 0x000a1a28, 0x000c1e2b, 0x00102230, 0x00192b3a, 0x00243444, 0x00283745, 0x0022303c, 0x001e2938, 0x001e2837, 0x001d2634, 0x001c2430, 0x001d2530, 0x001d2630, 0x00202934, 0x00242e3a, 0x002c3643, 0x00343f4c, 0x0032404c, 0x00313f4c, 0x002f3e4b, 0x002f3d4b, 0x00313e4c, 0x00303c49, 0x002d3845, 0x002f3844, 0x002f3744, 0x002d3542, 0x002d3541, 0x002c343f, 0x002c343f, 0x002c343f, 0x002c343f, 0x002d343f, 0x002c333d, 0x002c333c, 0x002c333c, 0x002f353e, 0x00343c45, 0x0038434f, 0x00384652, 0x003a4753, 0x003d4856, 0x003c4755, 0x003a4553, 0x003b4753, 0x003c4856, 0x003c4856, 0x003a4956, 0x00394857, 0x003c4858, 0x003c4858, 0x003c4858, 0x003b4857, 0x003a4655, 0x00384453, 0x00384453, 0x00394454, 0x003b4656, 0x003a4656, 0x003c4654, 0x003d4855, 0x003d4958, 0x003c4b59, 0x003b4a58, 0x003b4855, 0x00384452, 0x0036404e, 0x00333c48, 0x002f3540, 0x002b3139, 0x00282f36, 0x00252c34, 0x00242830, 0x00242831, 0x00282b34, 0x002a2d35, 0x002a2d34, 0x002a2d35, 0x00292e34, 0x00282d35, 0x00292e36, 0x002c3139, 0x002e333c, 0x002e343d, 0x002e343d, 0x002e343d, 0x002f353f, 0x00303640, 0x00303640, 0x002e3641, 0x002e3642, 0x002e3641, 0x002d3540, 0x002c343f, 0x0028303c, 0x00292f3b, 0x002c303c, 0x002c303c, 0x002b303c, 0x00282c37, 0x00272c35, 0x00282c36, 0x00282c36, 0x00272c36, 0x00282e37, 0x00282f38, 0x00282e37, 0x00242b34, 0x00222830, 0x0020272f, 0x00212831, 0x00262c38, 0x002b313e, 0x00313a47, 0x0034404e, 0x00354250, 0x00374453, 0x003c4757, 0x003d4758, 0x003c4755, 0x003c4755, 0x003b4755, 0x003b4655, 0x003c4557, 0x003c4455, 0x003a4455, 0x00394456, 0x00384457, 0x00384454, 0x00384656, 0x003c4959, 0x00404d5c, 0x00414f5e, 0x0041505f, 0x0040505f, 0x003e505f, 0x0040505f, 0x00425162, 0x00404f60, 0x003d4c5d, 0x003a4958, 0x00384754, 0x00374553, 0x0035414f, 0x00313b49, 0x002c3644, 0x00293340, 0x0028323d, 0x0027313c, 0x0028303b, 0x0028303a, 0x0028303a, 0x0028303b, 0x0028303c, 0x0028303c, 0x0028303c, 0x0027303a, 0x00272f39, 0x0028303b, 0x0028313c, 0x002b343f, 0x002d3842, 0x002f3843, 0x002f3844, 0x00303844, 0x00313b48, 0x00303b48, 0x00303b47, 0x002e3945, 0x002d3844, 0x002e3945, 0x002f3b47, 0x002f3b47, 0x002f3b47, 0x002e3945, 0x002d3844, 0x002e3440, 0x00272c38, 0x001c212c, 0x00181d25, 0x00181e25, 0x00161c24, 0x00141c24, 0x001a232c, 0x001f2831, 0x00202830, 0x001d252e, 0x001c232c, 0x001c232c, 0x0020272f, 0x00242c35, 0x00282d37, 0x00262b35, 0x00232833, 0x00222733, 0x00252937, 0x00282d3a, 0x002c3340, 0x002c3441, 0x0025313d, 0x001c2b36, 0x00162630, 0x0013222d, 0x0014202c, 0x0014202c, 0x0014202b, 0x00111c28, 0x000d1924, 0x000d1a24, 0x000c1a24, 0x000c1924, 0x000b1823, 0x000b1822, 0x000c1924, 0x000c1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000e1c25, 0x000d1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000d1b24, 0x000d1a25, 0x000d1a26, 0x000d1a26, 0x000d1b24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1925, 0x000d1a26, 0x000d1a26, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000d1b24, 0x000c1924, 0x000b1824, 0x000b1824, 0x000c1a24, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1b24, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0017383c, 0x00183d41, 0x001c4448, 0x001d4b4e, 0x00205154, 0x00205659, 0x00245c5f, 0x00297b8c, 0x0033a6ca, 0x002c8496, 0x002b7378, 0x002c747b, 0x002c787c, 0x002d787d, 0x002d797e, 0x002d7a7e, 0x002e7a7f, 0x002d7a7e, 0x002d7a7e, 0x002d797e, 0x002e787e, 0x002d787d, 0x002d787d, 0x002c787c, 0x002c777c, 0x002c777c, 0x002c757b, 0x002c757b, 0x002c757b, 0x002c777c, 0x002c777c, 0x002c777c, 0x002c777c, 0x002c777c, 0x002c757b, 0x002c747b, 0x002b747a, 0x002a7278, 0x00297076, 0x003094b0, 0x00309fc0, 0x00245e61, 0x0022585b, 0x00205356, 0x001d4c50, 0x001c4649, 0x00194044, 0x00173a3e, 0x00153439, 0x00142e34, 0x00112a30, 0x0011242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0008141a, 0x0008151b, 0x0008151b, 0x000a151c, 0x000a151c, 0x000a151c, 0x0009151d, 0x0009151d, 0x000a161e, 0x000a161e, 0x000b171f, 0x000b171f, 0x000b171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161f, 0x000a1620, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1620, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b1720, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x00091720, 0x00091720, 0x00091720, 0x000b1821, 0x000b1821, 0x000b1823, 0x000c1824, 0x000b1823, 0x000a1821, 0x000a1820, 0x00091822, 0x00091822, 0x00091822, 0x000a1821, 0x000a1821, 0x00091821, 0x000c1822, 0x000c1822, 0x00091821, 0x000b1822, 0x000c1823, 0x000b1924, 0x000c1c28, 0x000f202c, 0x00172835, 0x00213240, 0x00263542, 0x00222e3c, 0x001f2b39, 0x00212b39, 0x00202936, 0x001f2733, 0x001e2731, 0x001d2530, 0x001f2834, 0x00222c38, 0x002b3542, 0x00333e4c, 0x0033404d, 0x0032404c, 0x00303f4b, 0x00303e4a, 0x00303e4a, 0x00303c48, 0x002e3946, 0x002f3844, 0x002f3744, 0x002e3643, 0x002d3542, 0x002d3540, 0x002d3540, 0x002d3540, 0x002c3440, 0x002d3440, 0x002e343e, 0x002e343d, 0x002c333c, 0x002c323c, 0x00303640, 0x00333c48, 0x0036424e, 0x00374450, 0x003a4654, 0x003c4855, 0x003c4854, 0x003e4956, 0x003f4c59, 0x003f4c5a, 0x003d4b58, 0x003a4a58, 0x003a4958, 0x003c4a58, 0x003c4a59, 0x003c4a59, 0x003d4858, 0x003b4655, 0x003b4657, 0x003c4858, 0x003d495a, 0x003d4b5b, 0x003f4b59, 0x003f4b58, 0x00404c5b, 0x003d4c5b, 0x003d4c5b, 0x003c4b59, 0x00394654, 0x00343f4c, 0x00323b48, 0x002f3540, 0x002c333a, 0x00282f37, 0x00262d34, 0x00262b33, 0x00262a34, 0x002a2d37, 0x002b2e37, 0x002a2d34, 0x00292c33, 0x00282c34, 0x00282c34, 0x00282d35, 0x002c3038, 0x002d323c, 0x002e333c, 0x002e343e, 0x00303640, 0x002f3640, 0x00303740, 0x00303741, 0x00303742, 0x002e3641, 0x002e3641, 0x002d3540, 0x002d3540, 0x002a323d, 0x002a303c, 0x002c303c, 0x002c303c, 0x002c303c, 0x00292e38, 0x00282d37, 0x00282c36, 0x00282c36, 0x00262c36, 0x00282e37, 0x00282f38, 0x00282e38, 0x00262c36, 0x00252a34, 0x00242a32, 0x00242b34, 0x00242b37, 0x00272e3b, 0x002c3442, 0x00303c4a, 0x0034414f, 0x00384453, 0x003d4858, 0x00404a5a, 0x00404a58, 0x003f4a58, 0x003e4958, 0x003d4858, 0x003e4859, 0x003c4658, 0x003b4456, 0x003a4457, 0x00384355, 0x00394554, 0x003c4958, 0x00414d5c, 0x00414f5e, 0x00435060, 0x00445261, 0x00425260, 0x00435261, 0x00445362, 0x00445364, 0x00415061, 0x003c4c5c, 0x00384756, 0x00344350, 0x0032404d, 0x00343f4c, 0x00323c49, 0x002c3644, 0x00283240, 0x0027313c, 0x0027303b, 0x00273039, 0x00283039, 0x0028303c, 0x002a313d, 0x002a313d, 0x002a323d, 0x002a313d, 0x0029303c, 0x0028303c, 0x0029303c, 0x0028303c, 0x0029333d, 0x002c3741, 0x00303a44, 0x00303845, 0x00313846, 0x00323c48, 0x00313c49, 0x00303c48, 0x002f3b47, 0x002e3945, 0x002f3b47, 0x00303c48, 0x00303c48, 0x002f3c48, 0x002d3844, 0x002c3643, 0x002c3440, 0x00242b38, 0x001e232d, 0x00191e26, 0x00181e25, 0x00181e25, 0x00151d26, 0x001b232c, 0x001e2830, 0x00202830, 0x001d262d, 0x001d242c, 0x0020262f, 0x00232c34, 0x0028303b, 0x002b333d, 0x002a313c, 0x00262c39, 0x00242937, 0x00242a37, 0x00282e3c, 0x002c3340, 0x002a323f, 0x00212d38, 0x00192833, 0x0014242f, 0x0012212c, 0x00121f2b, 0x00121e2a, 0x00121e2a, 0x00101c28, 0x000d1924, 0x000d1924, 0x000c1924, 0x000b1823, 0x000b1822, 0x000b1822, 0x000c1924, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000d1a25, 0x000d1a26, 0x000d1b26, 0x000d1b24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000d1a25, 0x000d1b26, 0x000d1b26, 0x000c1a25, 0x000c1924, 0x000c1924, 0x000d1a24, 0x000d1a24, 0x000c1924, 0x000b1824, 0x000b1824, 0x000c1a24, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0016363b, 0x00183d41, 0x001a4347, 0x001c4a4d, 0x001e5053, 0x00215659, 0x00235c5e, 0x00287a8c, 0x0033a6ca, 0x002c8091, 0x00296c6e, 0x002a6e70, 0x002b7072, 0x002c7274, 0x002c7374, 0x002c7475, 0x002c7475, 0x002c7475, 0x002c7475, 0x002c7374, 0x002c7374, 0x002c7274, 0x002b7173, 0x002b7072, 0x002b7071, 0x002c7071, 0x002b6f70, 0x002b6f70, 0x002b6f70, 0x002b6f70, 0x002b6f70, 0x002b6f70, 0x002b6f70, 0x002b6f70, 0x002a6e70, 0x002a6d6f, 0x00296c6e, 0x00286a6c, 0x0028686a, 0x002e91ad, 0x00309ec0, 0x00245c60, 0x00215659, 0x00205154, 0x001d4b4e, 0x001b4448, 0x00183f43, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0012242c, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081319, 0x0009141a, 0x0009141a, 0x000a141b, 0x000a141b, 0x0009141c, 0x0008141d, 0x0008141d, 0x0009151d, 0x000a161e, 0x000b171f, 0x000b171f, 0x000b171f, 0x000a171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b1621, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1620, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000c161f, 0x000c161f, 0x000b1620, 0x000b1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000b1620, 0x000b1620, 0x000b1720, 0x000c1821, 0x000c1821, 0x000c1823, 0x000c1824, 0x000c1823, 0x000a1820, 0x000a1820, 0x00091720, 0x00091720, 0x00091720, 0x00091720, 0x00091720, 0x00091720, 0x000a1821, 0x000b1821, 0x00091720, 0x000a1821, 0x000c1821, 0x000c1823, 0x000b1b25, 0x000f1e2a, 0x00142431, 0x001f2e3c, 0x00243340, 0x00232f3d, 0x00202c3a, 0x00242d3c, 0x00242d3a, 0x00232b37, 0x00212934, 0x001e2731, 0x001f2834, 0x00232c39, 0x00293340, 0x00323e4a, 0x0034414e, 0x0032404c, 0x0030404b, 0x00303f4a, 0x002f3c48, 0x002f3b47, 0x002f3b47, 0x002f3945, 0x00303845, 0x00303844, 0x002f3744, 0x002e3642, 0x002e3641, 0x002d3540, 0x002d3540, 0x002d3440, 0x002e343f, 0x002c333c, 0x002a303a, 0x002a313b, 0x002c323c, 0x002b333e, 0x00303b47, 0x00313d4b, 0x0034404e, 0x00384451, 0x003b4753, 0x003d4855, 0x003e4a58, 0x00404c5a, 0x0043505f, 0x0040505e, 0x003d4d5c, 0x003f4e5d, 0x0040505e, 0x00404e5d, 0x00404b59, 0x003d4858, 0x003d485a, 0x00404a5c, 0x00404d5e, 0x00404e5f, 0x00414d5d, 0x003f4c5a, 0x003d4a59, 0x003c4a59, 0x003b4b59, 0x003c4b59, 0x003b4858, 0x0034404c, 0x00313a47, 0x002e3440, 0x002c333b, 0x00292f37, 0x00272d35, 0x00282d35, 0x00292e38, 0x002c303a, 0x002c2f37, 0x00292c34, 0x00272b32, 0x00262b32, 0x00282c34, 0x00282d35, 0x002c313a, 0x002e333c, 0x002f343d, 0x002f3540, 0x00303640, 0x002f3640, 0x00303740, 0x00303741, 0x002f3642, 0x002d3540, 0x002d3540, 0x002d3540, 0x002d3540, 0x002c343f, 0x002c323e, 0x002d313d, 0x002c303c, 0x002c303c, 0x002b2f3a, 0x002a2f38, 0x00282c37, 0x00282c36, 0x00272c36, 0x00272d37, 0x00272d37, 0x00282e37, 0x00282e37, 0x00282d37, 0x00262d34, 0x00262c34, 0x00252c37, 0x00282e39, 0x002b323f, 0x002f3846, 0x00343e4b, 0x00364250, 0x003b4656, 0x003f4858, 0x00404a59, 0x00404b5b, 0x00404c5c, 0x00414c5c, 0x00414c5e, 0x00404b5c, 0x003e495b, 0x003d485a, 0x003b4657, 0x003c4857, 0x00414c5c, 0x0044505f, 0x00424e5d, 0x003f4c5b, 0x003d4b5a, 0x003e4c5c, 0x00404f5d, 0x00404e5e, 0x00404d5d, 0x003e4c5c, 0x003a4858, 0x00374453, 0x0034414f, 0x00313d4b, 0x00333c4b, 0x00323c49, 0x00303847, 0x002c3542, 0x0028313d, 0x00273039, 0x00272f38, 0x00283039, 0x0029313c, 0x002c323f, 0x002d3340, 0x002d3440, 0x002d3340, 0x002c3340, 0x002c333e, 0x002d333f, 0x002d343f, 0x002c343f, 0x002c3640, 0x002f3843, 0x00323a47, 0x00333b48, 0x00333d49, 0x00323d49, 0x00313d49, 0x00303c48, 0x002f3b47, 0x00303c48, 0x00303c48, 0x00303c48, 0x00303c48, 0x002d3844, 0x002c3642, 0x002a313e, 0x00232936, 0x001e232e, 0x001a1f27, 0x00181e26, 0x00181f27, 0x00182028, 0x001c242d, 0x001f2830, 0x00212a31, 0x00202830, 0x001e2730, 0x00232b35, 0x0028303b, 0x002c3641, 0x002f3844, 0x002f3844, 0x002b3440, 0x00262e3c, 0x00262d3b, 0x002b323f, 0x002c3440, 0x0028303c, 0x001c2834, 0x00152430, 0x0013232d, 0x0011202c, 0x00111e2a, 0x00111d29, 0x00111c28, 0x00101c28, 0x000d1925, 0x000c1924, 0x000c1923, 0x000b1822, 0x000b1822, 0x000b1822, 0x000c1924, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1a25, 0x000d1a26, 0x000e1b26, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c26, 0x000e1c27, 0x000e1c27, 0x000d1b26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1b24, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1a24, 0x000b1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00122c32, 0x00143036, 0x0015363b, 0x00183c40, 0x001a4245, 0x001c484c, 0x001e4f51, 0x00205457, 0x0022595c, 0x0028788b, 0x0032a5ca, 0x002b7f90, 0x00286a6c, 0x00296c6f, 0x002a6e70, 0x002b7071, 0x002c7173, 0x002c7173, 0x002c7173, 0x002c7173, 0x002c7173, 0x002b7173, 0x002b7072, 0x002b7071, 0x002b6f70, 0x002a6e70, 0x002a6d6f, 0x002a6d6f, 0x00296c6f, 0x002a6c6e, 0x002a6c6e, 0x002a6c6e, 0x002a6c6e, 0x002a6c6e, 0x002a6c6e, 0x002a6c6e, 0x00296c6e, 0x00296b6d, 0x0028696c, 0x00286769, 0x0026676c, 0x002f95b4, 0x002f9dc0, 0x00235a5e, 0x00205457, 0x001e4f51, 0x001c484c, 0x001a4347, 0x00183d41, 0x0015363b, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081319, 0x0009141a, 0x0009141a, 0x000a141a, 0x000a141b, 0x0009141b, 0x0008141c, 0x0008141d, 0x0009151d, 0x000a161e, 0x000b171f, 0x000b171f, 0x000b171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x000a171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b1620, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1620, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000c161d, 0x000c161d, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000b1620, 0x000b1620, 0x000b1720, 0x000b1820, 0x000c1821, 0x000c1823, 0x000c1824, 0x000c1823, 0x000a1820, 0x000a1820, 0x00091720, 0x00091720, 0x00091620, 0x000b1620, 0x000a1620, 0x00091620, 0x000a1720, 0x000b1720, 0x00091720, 0x00091720, 0x000b1821, 0x000b1821, 0x000a1923, 0x000d1c27, 0x0012202d, 0x001c2b38, 0x00243340, 0x00253240, 0x00232e3c, 0x00242e3c, 0x0028313d, 0x0028303d, 0x00262e39, 0x00222a35, 0x00202a35, 0x00212c38, 0x0026303d, 0x00323d4c, 0x00344150, 0x00344150, 0x0033414d, 0x00313f4c, 0x00303c49, 0x002f3b48, 0x00303b48, 0x00303b48, 0x00323a48, 0x00333947, 0x00303845, 0x002f3743, 0x002e3641, 0x002d3541, 0x002d3540, 0x002e3440, 0x002f3540, 0x002c323c, 0x002a303b, 0x002c323c, 0x002c333d, 0x002b343f, 0x002e3744, 0x00313b48, 0x00343f4c, 0x0037414e, 0x0038434f, 0x003b4551, 0x003c4755, 0x003e4958, 0x00404d5c, 0x0041505f, 0x0040505e, 0x0040505e, 0x0041505f, 0x00404e5d, 0x003f4b59, 0x003f4a59, 0x00404c5d, 0x00424d5f, 0x00424f60, 0x00405060, 0x00414e5e, 0x00404d5c, 0x003d4c5b, 0x003c4a58, 0x003b4958, 0x003a4857, 0x00364351, 0x00313c49, 0x002f3844, 0x002c333e, 0x002c313a, 0x002a2f37, 0x00282d35, 0x002b3038, 0x002d313b, 0x002d323c, 0x002b3038, 0x00282c34, 0x00252a32, 0x00262b31, 0x00282c34, 0x002a2f37, 0x002d323b, 0x002e333c, 0x002f343e, 0x00303640, 0x00303640, 0x002f3740, 0x00303740, 0x00303741, 0x002f3641, 0x002c3440, 0x002c3440, 0x002c3440, 0x002d3440, 0x002d3540, 0x002f3440, 0x00303440, 0x002e323e, 0x002d323d, 0x002c303c, 0x002c303b, 0x00282d38, 0x00282c37, 0x00272c37, 0x00262c37, 0x00272c37, 0x00282e38, 0x00282f38, 0x00282e38, 0x00282f36, 0x00293037, 0x00292f38, 0x00292e38, 0x002a303b, 0x002c3440, 0x00303946, 0x00343d4a, 0x00384250, 0x003c4554, 0x003e4857, 0x003f4b5a, 0x00404c5c, 0x00414d5e, 0x00414e5f, 0x00404d5e, 0x00404c5d, 0x00404c5d, 0x00414c5d, 0x00404c5b, 0x00414e5c, 0x00404d5c, 0x003e4a58, 0x003c4857, 0x003c4957, 0x003d4a58, 0x003d4b58, 0x003c4857, 0x003b4856, 0x003b4755, 0x00394453, 0x0035414f, 0x00333e4c, 0x00313c49, 0x00303847, 0x002e3644, 0x002e3644, 0x002d3542, 0x002b333d, 0x002b333c, 0x002a323c, 0x002a323c, 0x002c3440, 0x002e3442, 0x002f3442, 0x00303643, 0x00303643, 0x002f3442, 0x002e3440, 0x002f3540, 0x002f3642, 0x002e3742, 0x002d3741, 0x002e3842, 0x00333b47, 0x00343c49, 0x00343e4a, 0x00323e4a, 0x00323e4a, 0x00323d49, 0x00313c49, 0x00313d49, 0x00323e4a, 0x00323d49, 0x00303c48, 0x002d3844, 0x002c3542, 0x002a313e, 0x00232936, 0x001f232f, 0x001b1f28, 0x00192028, 0x00192028, 0x00182028, 0x001b232c, 0x001c2730, 0x00202a33, 0x00212b34, 0x00222a34, 0x0028303b, 0x002e3742, 0x00343d49, 0x00343e4c, 0x00343d4b, 0x00303a48, 0x002c3443, 0x002a3240, 0x002c3442, 0x002c3440, 0x00232c38, 0x00192531, 0x0014232e, 0x0013222d, 0x00101f2a, 0x00101e29, 0x00111c28, 0x00111c28, 0x00101c28, 0x000d1925, 0x000d1a25, 0x000c1a24, 0x000c1923, 0x000c1923, 0x000c1923, 0x000c1924, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1a25, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x000e1b27, 0x000e1c27, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x000e1c27, 0x000e1c27, 0x000d1b26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1b24, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00132c32, 0x00143036, 0x00143439, 0x00183c40, 0x00194044, 0x001c474b, 0x001d4c50, 0x00205254, 0x0021585a, 0x0027788a, 0x0031a5ca, 0x002a7d8f, 0x0028686a, 0x00286a6c, 0x00296c6e, 0x002a6d6f, 0x002b6e70, 0x002b6f70, 0x002b7071, 0x002b7071, 0x002b7071, 0x002b6f70, 0x002b6f70, 0x002a6e70, 0x002a6d6f, 0x00296c6f, 0x00296c6e, 0x00296b6d, 0x00286a6c, 0x0028696c, 0x0028696c, 0x0028696c, 0x0028696c, 0x0028696c, 0x0028686b, 0x0028686b, 0x0028686b, 0x00286769, 0x00276668, 0x0027686e, 0x002d90ac, 0x0030a4c9, 0x002985a0, 0x00205659, 0x001f5154, 0x001d4c50, 0x001b4649, 0x00194044, 0x00173a3e, 0x00143439, 0x00143036, 0x00122c32, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0008121a, 0x0009141a, 0x0009141a, 0x000a131a, 0x000a131a, 0x000a131a, 0x0008141b, 0x0009141b, 0x0009141c, 0x000a141d, 0x000a161e, 0x000a161e, 0x000a161e, 0x000b171f, 0x000b171f, 0x000a1820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000b1820, 0x000a1820, 0x000a1820, 0x000a1720, 0x000a1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000a1620, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x000b171f, 0x000c161e, 0x000c161e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000b1620, 0x000b1620, 0x000b1620, 0x000a171f, 0x00091720, 0x000a1821, 0x000a1823, 0x000b1822, 0x000c1820, 0x000c1820, 0x00091720, 0x00091720, 0x00091620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000a1620, 0x00081720, 0x00081720, 0x00091820, 0x00091821, 0x000a1923, 0x000d1b27, 0x0012202d, 0x001b2a37, 0x0023323f, 0x00243240, 0x00232f3c, 0x00242e3b, 0x0028323e, 0x0029313e, 0x00272f3b, 0x00222c35, 0x00202933, 0x00202b35, 0x00242f3a, 0x00323c4a, 0x00374250, 0x00364350, 0x00344350, 0x0033404e, 0x00303e4b, 0x00303d4a, 0x00303c4a, 0x00323c4a, 0x00343d4b, 0x00343c4b, 0x00343948, 0x00313845, 0x00303744, 0x002f3542, 0x002d3440, 0x002e3441, 0x00303540, 0x002c333e, 0x002c323d, 0x002f3440, 0x002f3540, 0x002f3542, 0x002f3643, 0x00303946, 0x00363e4b, 0x0039424e, 0x0039444f, 0x003a4552, 0x003c4855, 0x003e4958, 0x003f4c59, 0x00404e5c, 0x0042505f, 0x00435160, 0x0043505f, 0x00404e5d, 0x003f4c5b, 0x003f4c5b, 0x00424f5f, 0x00445060, 0x00415060, 0x003f505e, 0x003e4e5d, 0x003f4f5d, 0x00404f5d, 0x003e4c5a, 0x003c4855, 0x00384451, 0x00333e4b, 0x00303845, 0x002d3541, 0x002c323c, 0x002b313b, 0x002b3038, 0x002a2f37, 0x002c3038, 0x002d323b, 0x002d323c, 0x002c303b, 0x002a2e37, 0x00272c34, 0x00272c34, 0x00282d36, 0x002b3039, 0x002c313c, 0x002d333c, 0x002f343f, 0x00303742, 0x00313842, 0x00303843, 0x00313843, 0x00303742, 0x00303641, 0x002d343f, 0x002c343e, 0x002c343f, 0x002d3440, 0x002f3540, 0x00303541, 0x00303440, 0x002f343f, 0x002e323e, 0x002b303b, 0x002a303a, 0x00292f38, 0x00282e38, 0x00262c36, 0x00262c36, 0x00272c36, 0x00282d36, 0x00292e37, 0x00292e37, 0x00292e36, 0x002b3038, 0x002b2f3a, 0x002c303c, 0x002c303c, 0x002b313d, 0x002d343f, 0x00323944, 0x00373f4b, 0x003a4350, 0x003c4654, 0x003d4a59, 0x003f4d5c, 0x00404e5c, 0x003f4e5d, 0x003f4d5d, 0x00404d5c, 0x00404d5c, 0x00424f5e, 0x0042505d, 0x00414f5c, 0x00404e5c, 0x00404d5c, 0x003e4c5a, 0x00404e5b, 0x00404d5b, 0x003f4c59, 0x003c4957, 0x003c4856, 0x003a4553, 0x00384150, 0x00343e4c, 0x00333c4a, 0x00323a48, 0x002e3643, 0x002a323f, 0x002b333e, 0x002c343e, 0x002c343d, 0x002d353f, 0x002d3640, 0x002e3742, 0x002f3743, 0x002f3744, 0x00303643, 0x00303643, 0x00303744, 0x00303643, 0x002f3641, 0x00303742, 0x00303843, 0x00303944, 0x002f3843, 0x002e3842, 0x00303a46, 0x00333c49, 0x00333e4a, 0x00333e4a, 0x00343f4c, 0x00343f4c, 0x00333f4c, 0x00333f4c, 0x00333e4c, 0x00323d4a, 0x00303c48, 0x002f3844, 0x002c3641, 0x002b323d, 0x00242b37, 0x001f2430, 0x001c212b, 0x001a2029, 0x001a202a, 0x00182029, 0x0018222c, 0x00192530, 0x001c2832, 0x00222c36, 0x00262f39, 0x002a3340, 0x00303947, 0x00353e4d, 0x00353f4f, 0x00364050, 0x00343d4c, 0x00303947, 0x002d3644, 0x002e3644, 0x0028303e, 0x001c2533, 0x0016212d, 0x0014212d, 0x0012212c, 0x000f1e29, 0x000e1c28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000c1925, 0x000d1a25, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1925, 0x000c1924, 0x000c1925, 0x000c1925, 0x000c1a25, 0x000e1c26, 0x000e1c27, 0x000e1c26, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x000e1c27, 0x000e1c27, 0x000c1c24, 0x000c1c24, 0x000c1c24, 0x000c1c24, 0x000c1c24, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1c25, 0x000d1c25, 0x000e1c25, 0x000d1b25, 0x000d1b26, 0x000d1b26, 0x000e1c25, 0x000e1c25, 0x000e1c24, 0x000e1c24, 0x000e1c24, 0x000d1c24, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153439, 0x00173a3e, 0x00183f43, 0x001b4448, 0x001d4b4e, 0x001f5053, 0x00205558, 0x00267689, 0x0030a4ca, 0x00297b8e, 0x00266467, 0x00286769, 0x0028696c, 0x00296b6d, 0x00296c6e, 0x00296c6f, 0x002a6d6f, 0x002a6d6f, 0x002a6d6f, 0x00296c6f, 0x00296c6f, 0x002a6c6e, 0x00296b6d, 0x00286a6c, 0x0028696c, 0x0028686b, 0x0028686a, 0x00286769, 0x00286769, 0x00276668, 0x00276668, 0x00276668, 0x00276668, 0x00266568, 0x00266467, 0x00266466, 0x00276a71, 0x002d94b2, 0x0030a2c8, 0x00288098, 0x0021595c, 0x001f5254, 0x001d4d50, 0x001c484c, 0x001a4347, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0013282e, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0008121a, 0x0009141a, 0x0009141a, 0x000a1319, 0x000a1219, 0x00091219, 0x00081319, 0x0009141a, 0x0009141c, 0x000a141d, 0x000a151e, 0x000a161e, 0x000a161e, 0x000b171f, 0x000b171f, 0x000b1820, 0x000b1820, 0x000a1820, 0x000b1920, 0x000b1920, 0x000b1920, 0x000a1820, 0x000a1820, 0x000a1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x00091620, 0x0008181f, 0x0008181f, 0x0008181f, 0x0008171f, 0x0009171f, 0x000a151e, 0x000a151e, 0x000a151e, 0x000a151e, 0x000b161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b161f, 0x000a171f, 0x00091720, 0x00081821, 0x00081823, 0x000a1822, 0x000c1820, 0x000c1820, 0x00091720, 0x00091720, 0x00091620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000a1620, 0x00081720, 0x00081820, 0x00081820, 0x00081821, 0x000a1923, 0x000d1b27, 0x0013202d, 0x001b2a37, 0x0023323f, 0x00243240, 0x00222f3c, 0x0024303c, 0x002a3440, 0x002a3440, 0x0028303c, 0x00242d37, 0x00202a33, 0x00202a33, 0x00242d39, 0x00303947, 0x00384250, 0x00384452, 0x00344451, 0x00344350, 0x0034404e, 0x00323f4c, 0x00323d4b, 0x00333e4c, 0x0036404d, 0x00373f4d, 0x00343c4b, 0x00343b48, 0x00333947, 0x00313845, 0x002d3441, 0x002f3542, 0x00303742, 0x002f3540, 0x00303640, 0x00303742, 0x00313844, 0x00313845, 0x00313845, 0x00313946, 0x00353d4a, 0x003b4350, 0x003b4550, 0x003b4652, 0x003d4955, 0x003f4c59, 0x00404d5b, 0x00414f5c, 0x0043515f, 0x00455261, 0x00445160, 0x00435060, 0x00404f5f, 0x003f4e5d, 0x00415060, 0x00435160, 0x0040505e, 0x003e505c, 0x003d4e5c, 0x003c4d5b, 0x003d4d5b, 0x003d4956, 0x003c4551, 0x0038404c, 0x00333a46, 0x00313743, 0x002f3440, 0x002b313c, 0x002a303b, 0x002c3039, 0x002a2f37, 0x002c3038, 0x002d303a, 0x002e303b, 0x002d303b, 0x002c3038, 0x00282d35, 0x00282d36, 0x00293039, 0x002c323c, 0x002e343e, 0x002e343e, 0x002f3540, 0x00313843, 0x00313843, 0x00313843, 0x00313843, 0x00303742, 0x00303641, 0x002d343f, 0x002c343e, 0x002c343f, 0x002e3440, 0x002f3541, 0x00303541, 0x002f3440, 0x002f343f, 0x002d323d, 0x002a313b, 0x002a303a, 0x002a303a, 0x00282f38, 0x00272e37, 0x00252c35, 0x00272c36, 0x00282d36, 0x00292e36, 0x00292e36, 0x00292e36, 0x002a2f38, 0x002b303a, 0x002c303c, 0x002c303c, 0x002b313c, 0x002c323d, 0x002f3540, 0x00323844, 0x00373e4a, 0x00394450, 0x003b4756, 0x003d4c5b, 0x003e4d5c, 0x003d4d5c, 0x003f4d5c, 0x003e4d5c, 0x003f4c5c, 0x00445060, 0x00455362, 0x00425160, 0x003f4e5c, 0x003d4c5b, 0x003c4c5a, 0x003d4b58, 0x003e4a58, 0x003d4957, 0x003d4856, 0x003c4754, 0x00384250, 0x00343c4b, 0x00333a48, 0x00323a45, 0x00303843, 0x002d3540, 0x002a323d, 0x0029313c, 0x002a333c, 0x002b343d, 0x002d3540, 0x002e3742, 0x00303945, 0x00303a46, 0x00303946, 0x00303845, 0x00303844, 0x00303844, 0x00303844, 0x00303843, 0x00303844, 0x00303944, 0x00303944, 0x00303a44, 0x00303944, 0x00303a46, 0x00323c48, 0x00333e4a, 0x00343f4c, 0x0034404d, 0x0034404e, 0x00343f4c, 0x00343f4c, 0x00333f4c, 0x00323d4a, 0x00303c48, 0x002f3944, 0x002c3741, 0x002b333e, 0x00272d38, 0x00202732, 0x001d232e, 0x001b212b, 0x001c232c, 0x001b232b, 0x0018232c, 0x001b2630, 0x001d2a34, 0x00222d38, 0x002a333e, 0x002f3845, 0x00333c4b, 0x0035404e, 0x00364150, 0x00394452, 0x00384151, 0x00333c4b, 0x00303947, 0x002c3543, 0x00212b38, 0x0016202e, 0x00131f2b, 0x0014202c, 0x0011202c, 0x000e1d28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000b1a25, 0x000c1b25, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1924, 0x000b1824, 0x000b1824, 0x000b1824, 0x000c1925, 0x000c1925, 0x000e1c27, 0x000e1c27, 0x000e1c26, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x000e1c27, 0x000e1c27, 0x000c1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000c1c24, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x000e1c27, 0x000e1c27, 0x000e1c25, 0x000e1c25, 0x000e1c24, 0x000e1c24, 0x000e1c24, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012242c, 0x00112a30, 0x00142e34, 0x00153338, 0x0017383c, 0x00183d41, 0x001a4347, 0x001c484c, 0x001d4d50, 0x00205254, 0x00257488, 0x0030a4ca, 0x00297f94, 0x00276a73, 0x00286c75, 0x00286f77, 0x00297078, 0x00297179, 0x002a737b, 0x002a737b, 0x002a737b, 0x002b747c, 0x002a747c, 0x002a737b, 0x002a737b, 0x00297179, 0x0028696c, 0x0028686a, 0x00286769, 0x00276668, 0x00266568, 0x00266467, 0x00266466, 0x00266466, 0x00266466, 0x00266364, 0x00266364, 0x00256264, 0x00266c75, 0x002d97b8, 0x0030a0c5, 0x0027788c, 0x0021585b, 0x00205356, 0x001e4f51, 0x001c4a4d, 0x001b4649, 0x001a4044, 0x00183c40, 0x0016363b, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0009121b, 0x000a141b, 0x000a141b, 0x000a1219, 0x000a1219, 0x00091219, 0x00081319, 0x0009141a, 0x000a141c, 0x000b141c, 0x000b151e, 0x000a161e, 0x000a161e, 0x000b171f, 0x000c171f, 0x000b1820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000b1820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000a1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x00091620, 0x0008181f, 0x0008181f, 0x0008181f, 0x0008171f, 0x0009171f, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000b151e, 0x000c161f, 0x000d1720, 0x000c161d, 0x000c161d, 0x000b161e, 0x000a171f, 0x0009171f, 0x00091821, 0x00091822, 0x000b1822, 0x000c1820, 0x000c1820, 0x000a1720, 0x000a1720, 0x000a1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000a1620, 0x00081720, 0x00081820, 0x00081820, 0x00081821, 0x000a1923, 0x000e1c27, 0x0013212e, 0x001b2a37, 0x0020303d, 0x0023303f, 0x0023303d, 0x0027333f, 0x002c3744, 0x002c3643, 0x0028333f, 0x0025303a, 0x00212c35, 0x001f2933, 0x00242d38, 0x002c3644, 0x0035404e, 0x00384554, 0x00364553, 0x00364452, 0x00354352, 0x0033404f, 0x00333e4c, 0x0035404f, 0x00384250, 0x00384050, 0x00363e4c, 0x00353c4a, 0x00353c49, 0x00343b48, 0x00303543, 0x00303744, 0x00323844, 0x00323843, 0x00333944, 0x00333944, 0x00333945, 0x00333b47, 0x00323a46, 0x00313844, 0x00323a46, 0x00353d49, 0x0037414c, 0x00394450, 0x003d4854, 0x00404c5a, 0x00414f5d, 0x00404f5d, 0x00404f5d, 0x00404f5e, 0x003d4b5a, 0x003e4c5b, 0x00404f5e, 0x0040505f, 0x003f4f5d, 0x0040505d, 0x0040505d, 0x003e505c, 0x003c4f5b, 0x003b4c58, 0x00384854, 0x0037424e, 0x00373f4c, 0x00343c48, 0x00333a45, 0x00323741, 0x0030343f, 0x002c313b, 0x002b303a, 0x002c3038, 0x002a2f37, 0x002b3038, 0x002c303a, 0x002c303a, 0x002c303a, 0x002c3039, 0x002c3039, 0x002c323b, 0x002e343e, 0x00303640, 0x00303640, 0x002f3440, 0x002f3440, 0x00303742, 0x00313844, 0x00313843, 0x00313843, 0x00303742, 0x00303641, 0x002d343f, 0x002c343e, 0x002c343f, 0x002e3440, 0x002f3440, 0x002f3440, 0x002f3440, 0x002f3440, 0x002f3440, 0x002c343e, 0x002e343e, 0x002d343d, 0x002c333d, 0x002c323c, 0x00293039, 0x00282c37, 0x00282d37, 0x00292e37, 0x00292e37, 0x00292e37, 0x00292e38, 0x00292e38, 0x002a2f3a, 0x002c303c, 0x002b303c, 0x002c323d, 0x002f3540, 0x00323844, 0x00353c48, 0x0036404c, 0x00364150, 0x00384655, 0x00394857, 0x003b4a58, 0x003c4b59, 0x003b4a58, 0x003b4858, 0x003f4c5c, 0x00404f5e, 0x003e4e5c, 0x003b4c5a, 0x00384958, 0x003a4a58, 0x00394856, 0x00384452, 0x00374350, 0x00364250, 0x0035404d, 0x00343c4a, 0x00323948, 0x00303844, 0x00303843, 0x002f3742, 0x002c3440, 0x002b333d, 0x002b333d, 0x002b343c, 0x002b333c, 0x002c343f, 0x002e3742, 0x00303946, 0x00323c48, 0x00333c49, 0x00323c48, 0x00303a48, 0x00303947, 0x00303845, 0x00303844, 0x00313945, 0x00313a46, 0x00303a46, 0x00313b48, 0x00313b48, 0x00303a47, 0x00323c48, 0x00343f4b, 0x0034404c, 0x0034404e, 0x0034404e, 0x00343f4c, 0x00343f4c, 0x00333f4c, 0x00323d4a, 0x00303c48, 0x002f3944, 0x002c3741, 0x002b343f, 0x00282f3a, 0x00212834, 0x001f2430, 0x001c212c, 0x001c232c, 0x001c252d, 0x001c2630, 0x001e2833, 0x00202c37, 0x0025313b, 0x002b3641, 0x00313c48, 0x00343e4c, 0x0037414f, 0x00384451, 0x003a4654, 0x003b4554, 0x0037404f, 0x00323c4a, 0x00293341, 0x001b2433, 0x00121c2a, 0x00121e2a, 0x0014202c, 0x0011202b, 0x000e1d28, 0x000d1c28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1b26, 0x000c1b25, 0x000c1b24, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000b1824, 0x000b1824, 0x000c1925, 0x000c1925, 0x000d1b26, 0x000e1c27, 0x000f1c28, 0x000e1c27, 0x000e1c26, 0x000e1c26, 0x000e1c26, 0x000e1c26, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000c1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000c1c24, 0x000d1c24, 0x000e1c25, 0x000e1c25, 0x000e1c27, 0x000e1c27, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c24, 0x000e1c24, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0016363b, 0x00183c40, 0x00194044, 0x001c4649, 0x001c4a4d, 0x001e4f51, 0x00226674, 0x002c9dc3, 0x002ea1c7, 0x0030a0c5, 0x0030a1c5, 0x0031a1c5, 0x0031a2c6, 0x0032a3c6, 0x0032a3c6, 0x0033a3c6, 0x0033a4c6, 0x0033a4c6, 0x0033a4c7, 0x0033a4c7, 0x0033a4c7, 0x0032a2c4, 0x00286d73, 0x00286769, 0x00266568, 0x00266467, 0x00266466, 0x00256364, 0x00256264, 0x00256264, 0x00256163, 0x00246062, 0x00246062, 0x00266e7b, 0x002e9bbd, 0x002f9dc2, 0x00257183, 0x00215659, 0x00205356, 0x001e5053, 0x001d4b4e, 0x001c474b, 0x001a4245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a121b, 0x000b131c, 0x000b131c, 0x000b121a, 0x000a1219, 0x000a1219, 0x00091219, 0x000a131a, 0x000b141a, 0x000c141b, 0x000b151d, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000b171f, 0x000b171f, 0x000b171f, 0x0009171f, 0x000a1820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000c1821, 0x000c1821, 0x00091620, 0x0008181f, 0x0008181f, 0x0008181f, 0x0008171f, 0x0009171f, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b161e, 0x000a171f, 0x0009171f, 0x000a1820, 0x000a1821, 0x000c1820, 0x000d1720, 0x000d1720, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000a1620, 0x00081720, 0x00081820, 0x00081820, 0x00081821, 0x000b1924, 0x000f1c28, 0x0014222f, 0x001b2a37, 0x001e2d3b, 0x0021303d, 0x0023303d, 0x00283540, 0x002c3844, 0x002c3844, 0x002b3541, 0x0028323d, 0x00232e38, 0x001f2a34, 0x00212c37, 0x00273240, 0x00323e4c, 0x00384553, 0x00364552, 0x00374553, 0x00374453, 0x00354251, 0x00354050, 0x00384451, 0x00394452, 0x00384150, 0x00353f4d, 0x00353f4c, 0x0037404c, 0x00373f4c, 0x00323946, 0x00313845, 0x00353c48, 0x00363d48, 0x00353c48, 0x00343b47, 0x00333a45, 0x00333c47, 0x00323b45, 0x00303742, 0x00303641, 0x00303742, 0x00313944, 0x00343c49, 0x00363f4c, 0x00384251, 0x003b4857, 0x003b4858, 0x003b4958, 0x003b4a58, 0x003b4a58, 0x003c4958, 0x003e4c5b, 0x003f4c5c, 0x003c4b5a, 0x003d4b5a, 0x003d4b58, 0x003a4956, 0x00384754, 0x00344451, 0x0034404c, 0x00313c48, 0x00313844, 0x00313844, 0x00323841, 0x00313540, 0x0030343f, 0x002f343c, 0x002d323a, 0x002c3139, 0x002b3038, 0x002b3038, 0x002c303a, 0x002c2f3a, 0x002c2f39, 0x002c303a, 0x002f333d, 0x00313640, 0x00313841, 0x00313841, 0x00303742, 0x002e343f, 0x002d333f, 0x00303541, 0x00313843, 0x00313843, 0x00303843, 0x00303742, 0x00303641, 0x002d343f, 0x002c333e, 0x002d343f, 0x002e343f, 0x002e343f, 0x002e3440, 0x002f3440, 0x00303541, 0x00303742, 0x00303843, 0x00313842, 0x00303742, 0x00303541, 0x002d343f, 0x002b313c, 0x00282e38, 0x00282d37, 0x00282d37, 0x00282d37, 0x00282d37, 0x00282d37, 0x00282d38, 0x00292e39, 0x002b2f3b, 0x002b303c, 0x002c323d, 0x002e3440, 0x00303541, 0x00303844, 0x00303947, 0x00303c4b, 0x00344050, 0x00374251, 0x00384554, 0x003b4857, 0x003c4958, 0x003b4857, 0x003b4858, 0x003d4c5b, 0x003d4e5c, 0x003c4d5c, 0x003a4b59, 0x00384857, 0x00384856, 0x00364250, 0x00323e4c, 0x00323c4b, 0x00323c48, 0x00323b48, 0x00313946, 0x00303744, 0x002f3742, 0x00303842, 0x002f3742, 0x002e3640, 0x002d353f, 0x002d353f, 0x002d353f, 0x002d3540, 0x002f3843, 0x00303946, 0x00313b48, 0x00343e4a, 0x00343e4c, 0x00333c4b, 0x00323c4a, 0x00313b48, 0x00333b48, 0x00343b48, 0x00343c49, 0x00343d49, 0x00343e4a, 0x00343e4a, 0x00323c49, 0x00343e4a, 0x0035414d, 0x0035414e, 0x0035404f, 0x0034404e, 0x00343f4c, 0x00343f4c, 0x00333f4c, 0x00323d4b, 0x00303c4a, 0x002e3945, 0x002b3743, 0x002a3440, 0x0027303a, 0x00212934, 0x001f2832, 0x001c2430, 0x001c2430, 0x001f2730, 0x00202832, 0x00202b35, 0x00232f38, 0x0026323c, 0x002c3743, 0x00303b48, 0x00343d4b, 0x0037404f, 0x003a4452, 0x003d4856, 0x003d4856, 0x003a4452, 0x00343d4c, 0x00283140, 0x0018202f, 0x00101b28, 0x00131e2b, 0x0013202c, 0x0010202b, 0x000e1d28, 0x000d1c28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1b25, 0x000c1a24, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000c1924, 0x000c1924, 0x000c1a25, 0x000d1b26, 0x000e1c27, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000c1d25, 0x000c1d24, 0x000c1d24, 0x000c1d24, 0x000c1d24, 0x000c1d24, 0x000c1d24, 0x000c1d24, 0x000c1d24, 0x000c1d24, 0x000d1d24, 0x000d1d24, 0x000e1c25, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00111f27, 0x00102229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4245, 0x001c474b, 0x001d4c50, 0x001e5053, 0x00236877, 0x00298ba8, 0x002b8dab, 0x002c8eab, 0x002c8fac, 0x002d90ad, 0x002d91ad, 0x002e92ae, 0x002e92af, 0x002f93af, 0x003093b0, 0x003094b0, 0x003094b0, 0x00319bba, 0x0033a5c9, 0x00286c73, 0x00276668, 0x00266467, 0x00266466, 0x00256364, 0x00256264, 0x00256163, 0x00246062, 0x00245f61, 0x00245e60, 0x00277484, 0x002f9dc1, 0x002c99bc, 0x00246b78, 0x00205558, 0x00205254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0009121b, 0x000a131b, 0x000a131b, 0x000b121a, 0x000b1219, 0x000b1219, 0x000a1219, 0x000b131a, 0x000b141a, 0x000c141b, 0x000b151d, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000b171f, 0x000b171f, 0x000b1820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000b1820, 0x000a1820, 0x000a1820, 0x000b1920, 0x000b1920, 0x000c1821, 0x000c1821, 0x000a1620, 0x0008171f, 0x0008181f, 0x0008181f, 0x0008171f, 0x0009171f, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000b151e, 0x000b151e, 0x000b151f, 0x000a1720, 0x00091720, 0x000a1820, 0x000a1821, 0x000c1820, 0x000d1720, 0x000d1720, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000a1620, 0x00091720, 0x00081820, 0x00081821, 0x00081821, 0x000c1b24, 0x00101c28, 0x00142330, 0x001b2a37, 0x001d2c3a, 0x0020303d, 0x0023323f, 0x00293844, 0x002c3946, 0x002d3a47, 0x002d3846, 0x002a3643, 0x0024303b, 0x001f2b34, 0x00202b36, 0x0025303d, 0x002f3b48, 0x00384452, 0x00384654, 0x00384654, 0x00384554, 0x00384454, 0x00384452, 0x00384452, 0x00384350, 0x00374250, 0x0037404f, 0x0038424f, 0x00384350, 0x00394350, 0x0036404c, 0x00353d4b, 0x0037404c, 0x0038414c, 0x00363f4a, 0x00333c47, 0x00323b45, 0x00333b46, 0x00333b45, 0x00313844, 0x00303642, 0x002f3440, 0x002f3641, 0x00313944, 0x00343c48, 0x00373f4c, 0x00384250, 0x00374351, 0x00384452, 0x00394654, 0x003b4856, 0x003c4857, 0x003c4857, 0x003a4755, 0x00384454, 0x00384453, 0x00394452, 0x00384450, 0x0034404d, 0x00313d4a, 0x00303b47, 0x002f3844, 0x00303743, 0x00303641, 0x00313540, 0x00323640, 0x00333640, 0x0031363e, 0x0030353d, 0x0030343c, 0x0030343c, 0x002f343c, 0x002d313c, 0x002c303b, 0x002c303b, 0x002d323c, 0x0030343f, 0x00333842, 0x00323843, 0x00323843, 0x00313843, 0x00303641, 0x002f3440, 0x00303641, 0x00313843, 0x00313843, 0x00303742, 0x00303742, 0x00303641, 0x002d343f, 0x002d333e, 0x002e343f, 0x002e3440, 0x002f3440, 0x002e3440, 0x002f3440, 0x00303641, 0x00313844, 0x00343c46, 0x00343a46, 0x00313844, 0x00303641, 0x002e3440, 0x002b313c, 0x00282d38, 0x00282d38, 0x00282d37, 0x00282d37, 0x00282d37, 0x00292e38, 0x002a2f39, 0x002b2f3b, 0x002b2f3b, 0x002a303c, 0x002c323d, 0x002c333e, 0x002e343f, 0x002f3541, 0x00303844, 0x00313a48, 0x00353f4e, 0x00384150, 0x00394453, 0x003b4754, 0x003c4855, 0x003c4856, 0x003a4754, 0x003a4856, 0x00394957, 0x00394957, 0x00384855, 0x00374754, 0x00354451, 0x00333f4c, 0x00323c4b, 0x00313a48, 0x00303845, 0x00313946, 0x00303845, 0x00303844, 0x00313944, 0x00333b46, 0x00333b46, 0x00313944, 0x002f3742, 0x002f3742, 0x002f3842, 0x00303944, 0x00303a44, 0x00313b47, 0x00313b48, 0x00333c49, 0x00343d4c, 0x00343e4c, 0x00343e4c, 0x00343d4b, 0x00343c4a, 0x00363e4c, 0x0037404d, 0x0037404d, 0x0036404e, 0x0036404d, 0x00353f4c, 0x00353f4c, 0x0036414e, 0x0036424e, 0x0035414e, 0x0034404d, 0x00343f4c, 0x00343f4c, 0x00333f4c, 0x00323d4b, 0x00303c4a, 0x002e3945, 0x002b3742, 0x002a3440, 0x0027303a, 0x00212a34, 0x00202833, 0x001e2631, 0x001d2530, 0x00202831, 0x00202933, 0x00202b35, 0x00202d37, 0x0024313c, 0x00283440, 0x002d3844, 0x00303a48, 0x00343f4c, 0x003a4453, 0x003e4958, 0x003f4958, 0x003d4655, 0x00353e4d, 0x0026303e, 0x00151d2c, 0x00111a28, 0x00141d2a, 0x0013202c, 0x0010202b, 0x000e1e28, 0x000d1c28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1b26, 0x000c1a24, 0x000c1924, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1a24, 0x000d1b25, 0x000e1c27, 0x000e1c27, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000c1d26, 0x000c1d25, 0x000c1d25, 0x000c1d25, 0x000c1d25, 0x000c1d25, 0x000c1d25, 0x000c1d25, 0x000c1d25, 0x000c1d25, 0x000c1d25, 0x000d1d25, 0x000e1c25, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000e1c26, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00143036, 0x0015363b, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001c474b, 0x001d4c50, 0x001f5053, 0x00205457, 0x0021575a, 0x0022595c, 0x00245c5f, 0x00245e60, 0x00246062, 0x00256164, 0x00266466, 0x00266568, 0x00266668, 0x00276668, 0x00286769, 0x002b8093, 0x0033a4c9, 0x00286c73, 0x00266568, 0x00266467, 0x00266466, 0x00256364, 0x00256163, 0x00246062, 0x00245e60, 0x00245e60, 0x0027788c, 0x002ea0c5, 0x002c95b7, 0x0023636e, 0x00205457, 0x00205254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081118, 0x00081219, 0x00081219, 0x00091118, 0x000b1219, 0x000b1219, 0x000a1219, 0x000a1219, 0x000a131a, 0x0009141a, 0x000a141c, 0x000a141c, 0x000a151d, 0x000a161e, 0x000b171f, 0x000a1820, 0x000a1820, 0x000a1820, 0x000a1821, 0x000a1821, 0x000b1821, 0x000b1923, 0x000c1923, 0x000b1821, 0x000b1821, 0x000b1821, 0x000a1821, 0x000a1821, 0x000a1720, 0x000a171f, 0x000a171f, 0x000a171f, 0x000a171f, 0x000a171f, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a151e, 0x0009141c, 0x0009141c, 0x000b141d, 0x000c141d, 0x000c1520, 0x000b1622, 0x000b1622, 0x00091721, 0x00091721, 0x000a1721, 0x000c1720, 0x000c1720, 0x000a1720, 0x00091720, 0x000a1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000a1620, 0x00091720, 0x00091822, 0x00091924, 0x000e1c27, 0x00101e29, 0x0014232f, 0x001a2936, 0x001d2c3a, 0x0020303e, 0x00243341, 0x00283845, 0x002c3b48, 0x00303d4b, 0x00303c4b, 0x002d3847, 0x0026323d, 0x00202c36, 0x001f2b34, 0x00242f3b, 0x002d3947, 0x00374452, 0x00384854, 0x00384654, 0x00374655, 0x00384554, 0x00384453, 0x00384452, 0x00374350, 0x00364250, 0x00384250, 0x003a4451, 0x003b4452, 0x003b4451, 0x003a4450, 0x0038414e, 0x0037404c, 0x0037414c, 0x00343e4b, 0x00333c48, 0x00333b46, 0x00333b46, 0x00333b46, 0x00343a46, 0x00333846, 0x00313844, 0x00313844, 0x00323944, 0x00343c47, 0x00373e48, 0x00363e49, 0x00353e49, 0x00353d48, 0x0038404c, 0x0039434e, 0x003c4551, 0x003a4451, 0x0037414e, 0x0037404e, 0x0036404d, 0x0038404c, 0x00383f4b, 0x00343c48, 0x00313946, 0x00303844, 0x00303844, 0x00303843, 0x00303843, 0x00303742, 0x00303842, 0x00313742, 0x00313740, 0x00303640, 0x0030343f, 0x0030343f, 0x002f343e, 0x002e333c, 0x002e333c, 0x002f343d, 0x002f343e, 0x00303540, 0x00323742, 0x00303843, 0x00313843, 0x00313843, 0x00303743, 0x00303742, 0x00303741, 0x00313841, 0x00303640, 0x00303741, 0x00303641, 0x002f3540, 0x002e343f, 0x002d333f, 0x002f3440, 0x002f3440, 0x002f3440, 0x002f3440, 0x002f3440, 0x002f3540, 0x00313845, 0x00323c48, 0x00343c48, 0x00323a47, 0x00303844, 0x002f3542, 0x002c323f, 0x00272c38, 0x00282c38, 0x00292e38, 0x00282d38, 0x00282d37, 0x00292e38, 0x002c303a, 0x002c303b, 0x002b303c, 0x002a303c, 0x002a303c, 0x002b313c, 0x002d333f, 0x002f3540, 0x002f3743, 0x00303944, 0x00343c49, 0x0037404d, 0x00394250, 0x00384350, 0x00384450, 0x00384450, 0x00384450, 0x00384551, 0x00384752, 0x00384752, 0x00374652, 0x00354450, 0x0033404c, 0x00323e4a, 0x00323c49, 0x00303946, 0x00303844, 0x00303844, 0x00303844, 0x00303845, 0x00333b47, 0x00343c48, 0x00353c4a, 0x00343c49, 0x00323a47, 0x00323947, 0x00323a47, 0x00333b46, 0x00323b46, 0x00333c49, 0x00343d49, 0x00353f4c, 0x00353f4d, 0x00343e4c, 0x00343e4c, 0x00353e4c, 0x00353d4c, 0x00373e4d, 0x00384150, 0x00374350, 0x0036414f, 0x0035404d, 0x00353f4d, 0x0035404e, 0x0035414d, 0x0035414d, 0x0034404c, 0x00333e4a, 0x00323d4a, 0x00323d4a, 0x00333e4a, 0x00333d4a, 0x00313c48, 0x00303944, 0x002c3640, 0x0028333d, 0x00242e38, 0x00212a34, 0x00212934, 0x00202833, 0x001f2732, 0x00202834, 0x00202b35, 0x00212c36, 0x00222e38, 0x0026323c, 0x00283440, 0x002c3845, 0x00303b49, 0x0036404e, 0x003b4553, 0x003d4958, 0x00404a5b, 0x003e4858, 0x00343d4d, 0x00242c3b, 0x00121a26, 0x000e1824, 0x00111d29, 0x0011202b, 0x000f202a, 0x000c1e28, 0x000c1d28, 0x000d1c28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000d1a26, 0x000d1a25, 0x000d1b25, 0x000d1b24, 0x000d1b24, 0x000c1b24, 0x000c1b24, 0x000c1c26, 0x000d1c27, 0x000d1c28, 0x000f1e28, 0x000f1e29, 0x000f1d28, 0x000f1c28, 0x000f1d28, 0x000d1d28, 0x000d1d28, 0x000d1d28, 0x000d1d28, 0x000d1d28, 0x000c1d28, 0x000c1d28, 0x000c1d27, 0x000c1d26, 0x000c1d26, 0x000c1e27, 0x000c1d26, 0x000c1d26, 0x000c1d26, 0x000c1d26, 0x000c1e26, 0x000c1e26, 0x000c1e26, 0x000c1d26, 0x000c1d26, 0x000e1d26, 0x000d1c26, 0x000d1c26, 0x000d1c26, 0x000d1c26, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0016363b, 0x00183c40, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4c50, 0x001e5053, 0x00205254, 0x00205558, 0x0021585a, 0x00235a5c, 0x00245c5f, 0x00245e60, 0x00246062, 0x00256264, 0x00266466, 0x00266467, 0x00276568, 0x002b8092, 0x0032a4c9, 0x00286c73, 0x00266568, 0x00266467, 0x00266466, 0x00256364, 0x00256163, 0x00245f61, 0x00245e61, 0x00287e94, 0x002ea1c7, 0x002a90af, 0x00215e67, 0x00205356, 0x001f5154, 0x001d4d50, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0017383c, 0x00143338, 0x00143036, 0x00122c32, 0x0010282e, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00061017, 0x00071118, 0x00081018, 0x00081018, 0x000a1018, 0x00091018, 0x00081118, 0x00091119, 0x00091319, 0x00091419, 0x000a141a, 0x000a141a, 0x000a151c, 0x0009161e, 0x0009171f, 0x00081820, 0x00091920, 0x00091820, 0x000b1822, 0x000b1822, 0x000b1822, 0x000c1a24, 0x000c1a24, 0x000b1823, 0x000b1822, 0x000b1822, 0x000a1821, 0x000a1821, 0x000a1720, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000a151e, 0x0009141c, 0x0009141c, 0x000c141d, 0x000c141d, 0x000c1520, 0x000c1622, 0x000c1723, 0x00091722, 0x00091722, 0x00091722, 0x000a1820, 0x000a1820, 0x00081820, 0x00081821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1720, 0x000b1620, 0x00091720, 0x00091822, 0x000a1924, 0x000e1d28, 0x00101f2a, 0x0014242f, 0x00192834, 0x001c2b38, 0x001f2f3d, 0x00243442, 0x00283847, 0x002c3b49, 0x00333e4e, 0x00323e4d, 0x002d3948, 0x0026323e, 0x00202c36, 0x001f2b34, 0x00232f3b, 0x002c3846, 0x00354250, 0x00384854, 0x00374754, 0x00374655, 0x00384554, 0x00384453, 0x00384351, 0x00384350, 0x00384451, 0x00394451, 0x003b4452, 0x003b4452, 0x003c4452, 0x003c4451, 0x003b4350, 0x0038414e, 0x0036404c, 0x00343e4b, 0x00343d4a, 0x00363e4a, 0x00373f4a, 0x00373f4b, 0x0038404c, 0x00383e4b, 0x00353c49, 0x00353c48, 0x00333944, 0x00343a45, 0x00353c46, 0x00363c46, 0x00353c46, 0x00343c45, 0x00384049, 0x003a434d, 0x003b4450, 0x0038424f, 0x0038414e, 0x0038404c, 0x00383e4b, 0x00363d48, 0x00343b47, 0x00343945, 0x00333944, 0x00333844, 0x00323945, 0x00313944, 0x00303843, 0x00303844, 0x00303844, 0x00313842, 0x00303840, 0x0030353f, 0x002d333c, 0x002d323c, 0x002e333c, 0x002e333c, 0x002e333c, 0x002f343d, 0x002f343e, 0x00303540, 0x00313542, 0x00303642, 0x00303742, 0x00313843, 0x00323844, 0x00313843, 0x00313841, 0x00303740, 0x00303640, 0x00303640, 0x00303641, 0x002f3440, 0x002d343f, 0x002c333e, 0x002e3440, 0x002f3440, 0x002f3440, 0x002f3541, 0x00303541, 0x00303642, 0x00303844, 0x00303a46, 0x00313a47, 0x00303845, 0x002f3744, 0x002f3543, 0x002a303d, 0x00242a34, 0x00272c36, 0x00282d38, 0x00282c36, 0x00282d37, 0x00292e38, 0x002c303a, 0x002c303b, 0x002c303c, 0x002a303c, 0x002a303c, 0x0029303c, 0x002c323d, 0x002d3440, 0x002f3742, 0x00303843, 0x00323a44, 0x00343c48, 0x0037404c, 0x0035404c, 0x0035414d, 0x0037434f, 0x0036424e, 0x0037434f, 0x0035434f, 0x0035434e, 0x0034424d, 0x00343f4b, 0x00313d49, 0x00303c48, 0x00313c48, 0x00303a47, 0x00303845, 0x00303845, 0x00323946, 0x00333b48, 0x00343c49, 0x00363e4c, 0x00383f4d, 0x0038404f, 0x0038404e, 0x00373e4c, 0x00363e4b, 0x00363e4a, 0x00353e4a, 0x00353f4b, 0x0037404d, 0x00384250, 0x00384150, 0x0037404f, 0x0037404f, 0x0038404e, 0x00373f4d, 0x0038404f, 0x00394452, 0x003a4553, 0x00374250, 0x00353f4d, 0x0036404e, 0x0035414e, 0x0035424e, 0x0034404c, 0x00343f4a, 0x00313d4a, 0x00313c49, 0x00303c48, 0x00303c48, 0x00313c48, 0x00313b48, 0x00303944, 0x002c3540, 0x0028333d, 0x00242d38, 0x00212b35, 0x00242c38, 0x00232c37, 0x00202a34, 0x00202a34, 0x00202c36, 0x00202c37, 0x00232e38, 0x0028333d, 0x002c3844, 0x002e3a48, 0x00323e4c, 0x00374350, 0x003b4754, 0x003c4857, 0x003f495c, 0x003e485a, 0x00303a49, 0x00202835, 0x000e1620, 0x000c1722, 0x00101c28, 0x0010202b, 0x000d202a, 0x000b1e28, 0x000c1d28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1c27, 0x000e1c27, 0x000e1c26, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000d1c26, 0x000d1d26, 0x000d1c27, 0x000d1c28, 0x000e1d28, 0x000f1f29, 0x000f1f29, 0x00101e28, 0x00101d28, 0x000e1d28, 0x000d1d28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000c1f27, 0x000c1f27, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00143036, 0x00153439, 0x0017383c, 0x00183c40, 0x00194044, 0x001b4448, 0x001c474b, 0x001d4b4e, 0x001e4f51, 0x001f5154, 0x00205457, 0x00215659, 0x0022595c, 0x00245c5f, 0x00245e60, 0x00246062, 0x00256264, 0x00266466, 0x00266568, 0x002b8092, 0x0033a4c9, 0x00286c73, 0x00286668, 0x00266568, 0x00276467, 0x00256364, 0x00256163, 0x00246164, 0x0029849c, 0x0030a2c8, 0x00298aa6, 0x00215b60, 0x00205356, 0x001f5154, 0x001d4d50, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183d41, 0x0017383c, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00041017, 0x00061017, 0x00071018, 0x00081018, 0x000a1018, 0x00091018, 0x00081118, 0x00091118, 0x00091318, 0x00091418, 0x000a1419, 0x000a1419, 0x000a151c, 0x0009161e, 0x0009171f, 0x00081820, 0x00091920, 0x000a1920, 0x000b1923, 0x000b1923, 0x000b1923, 0x000b1924, 0x000c1923, 0x000b1822, 0x000b1822, 0x000b1822, 0x000a1821, 0x000a1821, 0x000a1720, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000a161e, 0x0009141d, 0x0009141c, 0x000b141d, 0x000b141d, 0x000c1520, 0x000b1622, 0x000b1722, 0x00091722, 0x00091722, 0x00091722, 0x000a1820, 0x000a1820, 0x00081820, 0x00081821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1720, 0x000b1620, 0x00091720, 0x00091821, 0x000a1924, 0x000e1d27, 0x00101f29, 0x0012222c, 0x00172632, 0x001a2937, 0x00202f3d, 0x00243442, 0x00283846, 0x002c3a49, 0x00333e4e, 0x00333e4e, 0x002d3948, 0x0026313d, 0x00202c37, 0x001e2a34, 0x00222e39, 0x002b3644, 0x0033404d, 0x00374553, 0x00364654, 0x00364655, 0x00374554, 0x00384454, 0x00384453, 0x00394452, 0x003a4553, 0x003b4453, 0x003b4453, 0x003b4453, 0x003c4453, 0x003c4552, 0x003c4451, 0x0039424f, 0x0037404d, 0x0037404e, 0x0037414d, 0x0039424f, 0x003a424f, 0x003b4450, 0x003c4451, 0x003d4450, 0x003c424f, 0x003b414d, 0x00383e4a, 0x00363c48, 0x00373d48, 0x00383e48, 0x00383e48, 0x00353c46, 0x00383e48, 0x003b424d, 0x0038404d, 0x00363e4b, 0x00343f4b, 0x00353d4a, 0x00343c48, 0x00343b46, 0x00343a44, 0x00333a44, 0x00343a44, 0x00333a44, 0x00323944, 0x00313845, 0x00303843, 0x00303844, 0x00303842, 0x002e3640, 0x002e353f, 0x002d343d, 0x002c323c, 0x002c323c, 0x002c333c, 0x002d333c, 0x002d333c, 0x002e333c, 0x002f343e, 0x00303540, 0x00303541, 0x00303641, 0x00303641, 0x00303742, 0x00323844, 0x00313843, 0x00313841, 0x00303740, 0x002f353f, 0x00303640, 0x00303641, 0x002e3440, 0x002c333e, 0x002c333e, 0x002d333f, 0x002e343f, 0x002e343f, 0x002f3540, 0x00303742, 0x00303742, 0x00303843, 0x002e3743, 0x002d3542, 0x002e3643, 0x002f3743, 0x002f3641, 0x0029303b, 0x00252c36, 0x00272c36, 0x00282d37, 0x00282d37, 0x00282d37, 0x00292e38, 0x002a2f39, 0x002b303b, 0x002c303c, 0x002a303c, 0x002a303c, 0x002c323d, 0x002f3440, 0x00303742, 0x00303843, 0x00303843, 0x00303843, 0x00323a45, 0x00333c48, 0x00323d49, 0x0034404c, 0x0036424e, 0x0038434f, 0x0038434f, 0x0036424e, 0x0034404c, 0x00323e4a, 0x00333d49, 0x00323c48, 0x00313b48, 0x00323c48, 0x00323b48, 0x00333b48, 0x00343c48, 0x00363e4a, 0x00383f4c, 0x0038404d, 0x00394150, 0x003b4351, 0x003c4352, 0x003c4352, 0x003a4250, 0x00394150, 0x0039414f, 0x0038404d, 0x0038414e, 0x00394350, 0x003b4453, 0x003b4453, 0x003b4452, 0x003b4452, 0x003c4453, 0x003b4452, 0x003b4452, 0x003b4654, 0x003b4754, 0x00394451, 0x00374150, 0x00384150, 0x00374250, 0x0035414d, 0x00333f4b, 0x00333e4a, 0x00323d4b, 0x00323d4c, 0x002e3947, 0x002d3844, 0x00313b48, 0x00313b48, 0x00303944, 0x002c3640, 0x0028323c, 0x00222c37, 0x00212a34, 0x00242f39, 0x0024303a, 0x00202c36, 0x001f2b34, 0x001f2c35, 0x00202c37, 0x00232e38, 0x0027333d, 0x002c3844, 0x00303c49, 0x0034404e, 0x00394453, 0x003c4855, 0x003d4856, 0x003f485b, 0x003c4557, 0x002c3543, 0x0018202c, 0x000c141c, 0x000c1721, 0x00101d28, 0x0010202b, 0x000d202b, 0x000c1f28, 0x000c1e28, 0x000e1e28, 0x000d1d28, 0x000d1c28, 0x000d1c28, 0x000e1c28, 0x000e1c27, 0x000e1c27, 0x000e1c26, 0x000e1c26, 0x000e1c26, 0x000d1d27, 0x000d1d27, 0x000d1d28, 0x000e1e28, 0x000e1e28, 0x000f1f29, 0x000f1f2a, 0x000f1e28, 0x000f1e28, 0x000e1e28, 0x000d1e28, 0x000d1e28, 0x000d1e28, 0x000d1e28, 0x000d1e28, 0x000d1e28, 0x000d1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e27, 0x000c1f27, 0x000c1f27, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00143036, 0x00143439, 0x0017383c, 0x00183c40, 0x00194044, 0x001b4448, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205457, 0x00215659, 0x0022595c, 0x00245c5f, 0x00245e60, 0x00256163, 0x00266364, 0x00266467, 0x002b8092, 0x0033a4c9, 0x00286d74, 0x00286769, 0x00276668, 0x00266467, 0x00266466, 0x0026656a, 0x002c8ca6, 0x0030a2c8, 0x0029849c, 0x00225a5f, 0x00205457, 0x00205254, 0x001e4f51, 0x001d4b4e, 0x001c484c, 0x001b4448, 0x001a4245, 0x00183d41, 0x00183a3e, 0x00153439, 0x00153338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00040f16, 0x00041017, 0x00061017, 0x00081018, 0x000a1018, 0x000a1018, 0x00091018, 0x000a1118, 0x000a1318, 0x00091418, 0x000a1419, 0x000a1419, 0x000a151c, 0x0009161e, 0x0009171f, 0x00081820, 0x00091920, 0x000b1a21, 0x000b1a24, 0x000c1b24, 0x000b1a24, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1820, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000a161e, 0x000a161e, 0x0009151e, 0x000b151e, 0x000b151e, 0x000b1520, 0x00091622, 0x00091722, 0x00091722, 0x00091722, 0x00091722, 0x000a1820, 0x000a1820, 0x00081820, 0x00081821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1720, 0x000b171f, 0x0009171f, 0x000a1820, 0x000c1923, 0x000e1c25, 0x000f1d28, 0x0010202b, 0x00142430, 0x00182835, 0x001e2d3c, 0x00233241, 0x00283846, 0x002b3948, 0x00303d4c, 0x00323e4d, 0x002d3848, 0x0025303e, 0x00202b37, 0x001d2934, 0x00202c38, 0x00293443, 0x00313f4c, 0x00344250, 0x00334451, 0x00354554, 0x00374554, 0x00394555, 0x003a4554, 0x003a4654, 0x003b4754, 0x003c4654, 0x003c4455, 0x003c4555, 0x003c4655, 0x003c4654, 0x003c4654, 0x003c4552, 0x003b4451, 0x003b4451, 0x00394450, 0x0039434f, 0x003b4450, 0x003d4653, 0x00404855, 0x00414856, 0x00404754, 0x003e4451, 0x003c424d, 0x003a404c, 0x00383f4a, 0x00373d48, 0x00373d48, 0x00373d48, 0x00383f48, 0x0039404b, 0x00363d4a, 0x00343c48, 0x00333c48, 0x00343c48, 0x00323a46, 0x00323a44, 0x00323a43, 0x00303840, 0x00303840, 0x00323843, 0x00313844, 0x00303844, 0x00303744, 0x002f3742, 0x002e3640, 0x002c343d, 0x002c333c, 0x002d333c, 0x002c333c, 0x002d333c, 0x002c323c, 0x002c323c, 0x002c323c, 0x002d323c, 0x0030343e, 0x00313640, 0x00313642, 0x00303641, 0x00303641, 0x00303641, 0x00303742, 0x00303741, 0x002f3740, 0x00313841, 0x00303740, 0x00303740, 0x00303641, 0x002e343f, 0x002c333e, 0x002c323d, 0x002c323d, 0x002c323d, 0x002c323d, 0x002e3440, 0x00303742, 0x00303742, 0x00303641, 0x002c343f, 0x002c343f, 0x002e3641, 0x002f3742, 0x00303742, 0x002d333f, 0x002b313c, 0x00293039, 0x00282f38, 0x00282e37, 0x00292e38, 0x00292e38, 0x002a2f38, 0x002b303b, 0x002c303c, 0x002a303c, 0x002a303c, 0x002a303c, 0x002d333e, 0x002f3641, 0x002f3742, 0x002f3742, 0x002f3742, 0x00303844, 0x00323b45, 0x00323c48, 0x00333e4a, 0x0036414d, 0x0037424e, 0x0037424e, 0x0038414e, 0x0037404c, 0x00343c49, 0x00343d4a, 0x00353e4b, 0x00343e4b, 0x00353e4b, 0x00353e4b, 0x00363e4b, 0x0038404c, 0x003a424f, 0x003a424f, 0x003b4350, 0x003c4453, 0x003e4554, 0x003f4655, 0x003f4655, 0x003d4554, 0x003c4453, 0x003c4452, 0x00394350, 0x0038434f, 0x003a4451, 0x003c4654, 0x003d4755, 0x003d4755, 0x003d4755, 0x003d4755, 0x003d4755, 0x003d4755, 0x003c4855, 0x003b4754, 0x003b4554, 0x003a4452, 0x003a4452, 0x00384350, 0x0035414d, 0x00333e4a, 0x00313c48, 0x00313c4a, 0x00313c49, 0x002e3846, 0x002e3844, 0x00313b48, 0x00313b48, 0x00303944, 0x002c3741, 0x0028323c, 0x00212c36, 0x00212a34, 0x00242f39, 0x0025303b, 0x00212c37, 0x001e2a34, 0x001f2c36, 0x00222e38, 0x00232f38, 0x0026313c, 0x002b3744, 0x00303c49, 0x0034404d, 0x00384451, 0x003c4754, 0x003c4856, 0x003e4858, 0x00374051, 0x00282f3c, 0x00111823, 0x000b111b, 0x000e1823, 0x00101d29, 0x0010202c, 0x000e202b, 0x000c2029, 0x000c2029, 0x000e1f29, 0x000d1f29, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000d1c28, 0x000d1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000f1f29, 0x000f1f29, 0x000f202b, 0x000f202b, 0x000f1f2a, 0x000f1f29, 0x000f1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000d1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1f27, 0x000c1f27, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00153338, 0x00143439, 0x0017383c, 0x00183d41, 0x00194044, 0x001b4448, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205457, 0x0021585a, 0x00235a5c, 0x00245d60, 0x00246062, 0x00266364, 0x00266467, 0x002b8092, 0x0033a4c9, 0x00286d74, 0x0028686a, 0x00286769, 0x00266568, 0x00276a70, 0x002e92af, 0x0030a2c6, 0x00287d93, 0x00225b5e, 0x0021585a, 0x00205356, 0x001f5154, 0x001d4c50, 0x001d4a4d, 0x001b4649, 0x001a4245, 0x00183f43, 0x00183c40, 0x0016363b, 0x00143338, 0x00143036, 0x00132c32, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00040f16, 0x00041017, 0x00061017, 0x00081018, 0x000a1018, 0x000a1018, 0x000a1018, 0x000a1118, 0x000a1318, 0x00091418, 0x000a1419, 0x000a1419, 0x000a151c, 0x0009161e, 0x0009171f, 0x00081820, 0x00091920, 0x000b1a21, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1823, 0x000b1823, 0x000b1822, 0x000b1822, 0x000b1820, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000a161e, 0x000a161e, 0x000a161e, 0x000b151e, 0x000b151e, 0x000b1520, 0x000a1622, 0x00091722, 0x00091722, 0x00091722, 0x00091722, 0x000a1820, 0x000a1820, 0x00081820, 0x00081821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1720, 0x000b171f, 0x0009171f, 0x000a1820, 0x000c1923, 0x000d1b24, 0x000e1c26, 0x00101e28, 0x0012212c, 0x00172634, 0x001c2c3a, 0x00213140, 0x00263645, 0x00283847, 0x002d3b4a, 0x00313e4d, 0x002e3949, 0x0026313f, 0x00202c38, 0x001d2935, 0x00202c38, 0x00283441, 0x00303d4b, 0x0032404e, 0x00334350, 0x00344452, 0x00384454, 0x00394454, 0x003a4655, 0x003b4754, 0x003c4855, 0x003c4655, 0x003c4656, 0x003c4657, 0x003c4656, 0x003d4755, 0x003c4654, 0x003d4754, 0x003d4754, 0x003c4554, 0x003c4452, 0x003b4350, 0x003b4350, 0x003c4452, 0x003f4754, 0x003f4754, 0x003f4754, 0x003e4450, 0x003b404c, 0x003a404c, 0x00393f4b, 0x00383f4b, 0x003a414c, 0x003c424d, 0x003b424d, 0x0038404c, 0x00353d49, 0x00343c49, 0x00343c48, 0x00343c48, 0x00323a47, 0x00323a44, 0x00313943, 0x002f3740, 0x002f3640, 0x00313843, 0x00313845, 0x00313845, 0x00303844, 0x002f3742, 0x002d3540, 0x002c323c, 0x002c313b, 0x002c323c, 0x002d313c, 0x002e313c, 0x002d323c, 0x002c323c, 0x002c323c, 0x002d323c, 0x0030343e, 0x00323742, 0x00343844, 0x00303743, 0x00303641, 0x00303541, 0x00303541, 0x002f3540, 0x002e353f, 0x00303740, 0x00303841, 0x00303640, 0x00303541, 0x002e3440, 0x002d333e, 0x002c323d, 0x002b313c, 0x002a303c, 0x002b313c, 0x002d343f, 0x00303642, 0x00303742, 0x002f3541, 0x002c343f, 0x002c333d, 0x002c3540, 0x002f3742, 0x002f3742, 0x002e3540, 0x002c333d, 0x002c323c, 0x002b313b, 0x00293039, 0x00292e38, 0x00292e38, 0x00292e38, 0x002b2f3b, 0x002c303c, 0x0029303c, 0x002a303c, 0x002a303c, 0x002b313c, 0x002c343f, 0x002d3541, 0x002e3641, 0x002f3742, 0x00303843, 0x00333a45, 0x00343c48, 0x00343c48, 0x0036404c, 0x0037404d, 0x0038404d, 0x0038404c, 0x00373f4c, 0x00353d4a, 0x00363e4b, 0x0038404d, 0x0038414e, 0x0038404d, 0x0039414e, 0x0039414e, 0x003a424f, 0x003b4351, 0x003c4452, 0x003d4453, 0x003e4655, 0x00404857, 0x00404858, 0x00404858, 0x00404857, 0x00404857, 0x00404755, 0x003d4654, 0x003c4553, 0x003c4654, 0x003d4755, 0x003e4856, 0x003e4856, 0x003e4856, 0x003e4856, 0x003e4857, 0x003f4857, 0x003e4857, 0x003c4856, 0x003b4754, 0x003c4654, 0x003a4554, 0x00384450, 0x0036414d, 0x00343f4b, 0x00333d4a, 0x00313b49, 0x00303a48, 0x00303a47, 0x00303a47, 0x00313b48, 0x00303a47, 0x002f3944, 0x002c3842, 0x0028323c, 0x00212c36, 0x00232c38, 0x0027313c, 0x0025313c, 0x00212c38, 0x001f2b36, 0x00212e38, 0x0026333d, 0x0025313c, 0x0025323d, 0x00293644, 0x002e3947, 0x00313c4b, 0x00364250, 0x003c4754, 0x003e4957, 0x003c4554, 0x00313848, 0x001f2531, 0x000d141d, 0x00091019, 0x000e1722, 0x00111e2a, 0x0011212c, 0x000f212c, 0x000d202b, 0x000e202b, 0x000f202b, 0x000f202b, 0x0010202b, 0x0010202b, 0x00101f2a, 0x000e1e28, 0x000e1e28, 0x00101d28, 0x00101d28, 0x00101d28, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x0010202a, 0x0010202b, 0x000f202b, 0x000f202b, 0x000f1f2a, 0x000f1f29, 0x00101f2a, 0x000e1f2a, 0x000e1f2a, 0x000e1f2a, 0x000e1f2a, 0x000e1f2a, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000c1e28, 0x000c1e28, 0x000d1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000d1f28, 0x000c1f27, 0x000c1f27, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x000f2229, 0x0012242c, 0x0011242c, 0x00112a30, 0x00132c32, 0x00142e34, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183d41, 0x00194044, 0x001b4448, 0x001c474b, 0x001d4b4e, 0x001e4f51, 0x00205254, 0x00205558, 0x0022595c, 0x00245c5f, 0x00245f61, 0x00256264, 0x00266467, 0x002b8092, 0x0033a5c9, 0x002c7c8a, 0x002b7884, 0x002a7784, 0x00297885, 0x003098b7, 0x0030a0c4, 0x0028788a, 0x00245e60, 0x0022595c, 0x00215659, 0x00205356, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00183d41, 0x0017383c, 0x00143439, 0x00153338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00060f14, 0x00051017, 0x00051017, 0x00081018, 0x00091018, 0x000a1018, 0x000a1018, 0x000a1118, 0x00091319, 0x0008141a, 0x0008141a, 0x0008151b, 0x0008151c, 0x000a161c, 0x000a171d, 0x0009181e, 0x00091820, 0x00091920, 0x00091921, 0x000a1921, 0x000a1920, 0x000b1920, 0x000b1920, 0x000c1923, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000b1822, 0x000b1821, 0x000b1821, 0x000a1820, 0x000a1820, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000b171f, 0x000a161e, 0x000a161e, 0x000b151e, 0x000b151e, 0x000b151f, 0x000b1620, 0x000a1620, 0x00091722, 0x00091722, 0x000b1722, 0x000c1821, 0x000b1821, 0x00091821, 0x00081821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1821, 0x000a1820, 0x00081820, 0x00091922, 0x000c1a24, 0x000d1b24, 0x000e1a24, 0x000e1c24, 0x00101f29, 0x00152431, 0x00192a37, 0x001d303c, 0x00233543, 0x00253845, 0x00293a48, 0x002f3d4c, 0x002c3a48, 0x0024303f, 0x00202c39, 0x001e2a35, 0x00212d39, 0x0027333f, 0x002f3c48, 0x0032414d, 0x00344350, 0x00344351, 0x00364454, 0x00394655, 0x003b4857, 0x003d4958, 0x003e4959, 0x003c4858, 0x003c4656, 0x003b4656, 0x003c4757, 0x003c4756, 0x003c4656, 0x003c4655, 0x003d4654, 0x003d4554, 0x003d4454, 0x003c4453, 0x003c4451, 0x003b4350, 0x003a424e, 0x0038404c, 0x0039414d, 0x0039404d, 0x00383f4c, 0x0039404d, 0x003b414f, 0x003d4451, 0x003d4551, 0x003c4450, 0x003a424e, 0x0038404c, 0x00383e4b, 0x00363e4b, 0x00343c49, 0x00333c48, 0x00333b48, 0x00323a47, 0x00333a45, 0x00313843, 0x00303742, 0x00313843, 0x00323844, 0x00343944, 0x00333844, 0x00313641, 0x002f343f, 0x002c313c, 0x002b303b, 0x002b303a, 0x002c303b, 0x002c303b, 0x002d313b, 0x002d313b, 0x002d323c, 0x002e343e, 0x00303641, 0x00333944, 0x00343a45, 0x00313842, 0x00303540, 0x002f343d, 0x002f343d, 0x002e343d, 0x002f343e, 0x0030343e, 0x0030343f, 0x0030343f, 0x002e343f, 0x002d333f, 0x002c333e, 0x002c323d, 0x002c303c, 0x002a2f3b, 0x0029303a, 0x002c333c, 0x00303640, 0x00303640, 0x002e3440, 0x002d333e, 0x002c323d, 0x002c343f, 0x002e3642, 0x002f3742, 0x002e3642, 0x002f3641, 0x002e3440, 0x002c333d, 0x002a313c, 0x002a303c, 0x00292f3b, 0x00292f3b, 0x00292f3b, 0x00292e39, 0x00292e39, 0x002a2f3b, 0x002b313c, 0x002c323d, 0x002c323d, 0x002d343f, 0x002e3440, 0x00303641, 0x00303843, 0x00343945, 0x00343b46, 0x00333b46, 0x00343d49, 0x00343f4b, 0x0036404c, 0x00363e4b, 0x00353d4a, 0x00353d4a, 0x00383f4c, 0x003a424f, 0x003a424f, 0x003a424f, 0x003b4350, 0x003c4450, 0x003c4453, 0x003c4453, 0x003d4554, 0x003e4755, 0x003f4857, 0x00404958, 0x00404a59, 0x003f4a59, 0x003f4958, 0x0040495a, 0x00404959, 0x003f4858, 0x003d4857, 0x003d4757, 0x003e4858, 0x003f4858, 0x00404a59, 0x00404b5a, 0x003e4a59, 0x003e4959, 0x003f4a5a, 0x003e4959, 0x003d4858, 0x003b4756, 0x003c4856, 0x003c4754, 0x00394452, 0x00364250, 0x0037404e, 0x00353f4b, 0x00323c4a, 0x00323c4a, 0x00313c49, 0x00323c48, 0x00313b48, 0x00303a46, 0x002e3844, 0x002c3541, 0x0028313c, 0x00222c37, 0x0024303b, 0x00293742, 0x0024323d, 0x00202e3a, 0x00202d38, 0x0023303c, 0x00273542, 0x00263441, 0x00253340, 0x00283644, 0x002c3848, 0x00313d4b, 0x00384350, 0x003c4855, 0x003e4957, 0x0038414f, 0x00272d3c, 0x00151c28, 0x000b111b, 0x000a101a, 0x000f1823, 0x00111f2a, 0x0011212c, 0x000f222c, 0x000e212c, 0x000e212c, 0x000f202c, 0x000f202c, 0x0010202b, 0x000f2029, 0x000e1f28, 0x000e1f28, 0x000e1f28, 0x000f1f28, 0x000f1f28, 0x000f1f28, 0x000e1f28, 0x000e1f28, 0x000f202a, 0x0010202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000e202b, 0x000e202b, 0x000e202b, 0x000e202b, 0x000e202b, 0x000f202b, 0x000f202b, 0x000e1f2a, 0x000e1f29, 0x000e1f2a, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000e1e2a, 0x000d1d29, 0x000d1d29, 0x000d1d29, 0x000d1d29, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1c25, 0x000b1c25, 0x000b1c25, 0x000b1c25, 0x000c1c25, 0x000c1b24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00132c32, 0x00143036, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183f43, 0x001a4245, 0x001b4649, 0x001d4a4d, 0x001d4d50, 0x00205154, 0x00205457, 0x0022585b, 0x00245c5e, 0x00245f61, 0x00256264, 0x00266467, 0x002b7f91, 0x0034a6cb, 0x0033a6c9, 0x0033a5c9, 0x0033a4c9, 0x0033a4c9, 0x00309fc0, 0x00287482, 0x00246062, 0x00245d60, 0x0022595c, 0x00215659, 0x001f5254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0017383c, 0x00153439, 0x00143036, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00060e14, 0x00061017, 0x00051017, 0x00080f17, 0x00090f17, 0x00090f17, 0x000a1018, 0x000a1018, 0x00091319, 0x0008141a, 0x0008141a, 0x0008151b, 0x0008151c, 0x0009161c, 0x000a161c, 0x000a171d, 0x00091820, 0x00091920, 0x00091920, 0x00091920, 0x00091920, 0x000b1920, 0x000b1a21, 0x000c1a23, 0x000d1b24, 0x000d1b24, 0x000c1924, 0x000c1924, 0x000b1823, 0x000b1822, 0x000b1822, 0x000a1821, 0x000a1821, 0x000b1821, 0x000c1821, 0x000c1821, 0x000c1820, 0x000c1820, 0x000b171f, 0x000a161e, 0x000a161e, 0x000b151e, 0x000b151e, 0x000b151f, 0x000b1620, 0x000b1620, 0x00091722, 0x00091722, 0x000b1722, 0x000c1821, 0x000b1821, 0x00091821, 0x00081821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1821, 0x00091821, 0x00081821, 0x000a1923, 0x000c1b24, 0x000d1b24, 0x000d1924, 0x000d1b23, 0x000e1d26, 0x0014232e, 0x00172934, 0x00192e38, 0x00203542, 0x00223744, 0x00253846, 0x002c3c4b, 0x002c3a48, 0x00243240, 0x00202e3b, 0x001f2c38, 0x00222f3b, 0x0026343f, 0x002c3b46, 0x0032414c, 0x00344350, 0x00344452, 0x00364454, 0x00394756, 0x003c4958, 0x003e4b5a, 0x00404b5b, 0x003e485a, 0x003d4858, 0x003c4858, 0x003c4857, 0x003d4858, 0x003d4757, 0x003c4655, 0x003c4654, 0x003d4654, 0x003f4755, 0x003f4755, 0x00404854, 0x003f4754, 0x003c4451, 0x0039424f, 0x0038404d, 0x0038404d, 0x0038404d, 0x00394250, 0x003c4453, 0x003d4654, 0x003b4451, 0x0038424f, 0x0038404d, 0x0038404c, 0x00383f4c, 0x00383e4c, 0x00353c49, 0x00333b48, 0x00323a47, 0x00333b48, 0x00343a47, 0x00333944, 0x00313843, 0x00313843, 0x00323844, 0x00323944, 0x00333844, 0x00313640, 0x002f343e, 0x002c313b, 0x002b313b, 0x002c323c, 0x002e333c, 0x002e323c, 0x002e303b, 0x002e303b, 0x002f333d, 0x00303640, 0x00313843, 0x00343a45, 0x00343a45, 0x00313842, 0x002e343d, 0x002c303b, 0x002c303b, 0x002c303b, 0x002c303b, 0x002c303b, 0x002c303b, 0x002c303b, 0x002c303c, 0x002c323d, 0x002c333e, 0x002c323d, 0x002c303c, 0x002a2f3b, 0x00282e38, 0x00293039, 0x002b313b, 0x002c323b, 0x002b313c, 0x002b303c, 0x002a303c, 0x002a313d, 0x002d3340, 0x00303643, 0x00303844, 0x00303844, 0x002f3742, 0x002d3540, 0x002c3440, 0x002b333e, 0x002b323d, 0x002b313c, 0x002a2f3b, 0x00292e38, 0x00282d37, 0x002a2f38, 0x002c323c, 0x002c333e, 0x002c333e, 0x002c323d, 0x002e343f, 0x00303541, 0x00303742, 0x00333945, 0x00333b46, 0x00323a45, 0x00323c48, 0x00333e4a, 0x00343e4a, 0x00343e4a, 0x00343e4b, 0x00363f4c, 0x0038404d, 0x0039424f, 0x0039434f, 0x003a4450, 0x003c4551, 0x003d4653, 0x003e4756, 0x003d4755, 0x003d4755, 0x00404a58, 0x00434c5b, 0x00414b58, 0x003f4957, 0x003d4857, 0x003d4958, 0x00404b5b, 0x00414c5c, 0x00404b5b, 0x003f4a5a, 0x003e4959, 0x003e4959, 0x00404b5a, 0x00414e5d, 0x00414f5e, 0x003f4c5c, 0x003e4b5c, 0x003e4b5c, 0x003d495b, 0x003d4858, 0x003c4858, 0x003e4958, 0x003c4755, 0x00394453, 0x00374250, 0x0037414f, 0x00353f4c, 0x00323c4a, 0x00323c4a, 0x00333c4a, 0x00323c48, 0x00303b47, 0x00303945, 0x002d3743, 0x002b3441, 0x0027313c, 0x00212c37, 0x0025323d, 0x002a3944, 0x0023323d, 0x0022313c, 0x0021303c, 0x0023323d, 0x00273643, 0x00263643, 0x00273644, 0x00293845, 0x002e3b49, 0x0034404e, 0x00394553, 0x003c4855, 0x003a4553, 0x002f3844, 0x001b212d, 0x000d141e, 0x00080f18, 0x000b111c, 0x00101926, 0x0012202b, 0x0011212c, 0x000f222c, 0x000f222c, 0x000f222c, 0x0010232d, 0x0010222c, 0x000f212c, 0x000f2028, 0x000e2028, 0x000e2028, 0x000e1f28, 0x000f1f26, 0x000f1f26, 0x000f1f26, 0x000e1f28, 0x000e1f28, 0x000f202a, 0x0010202c, 0x0010202c, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000f202b, 0x000f202b, 0x000e1f2a, 0x000e1f29, 0x000e1f2a, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f1e29, 0x000e1d28, 0x000d1d28, 0x000c1e28, 0x000c1e28, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000b1c25, 0x000b1c25, 0x000b1c25, 0x000b1c25, 0x000c1c25, 0x000c1a24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0012242c, 0x0010282e, 0x00132c32, 0x00142e34, 0x00153338, 0x0015363b, 0x00183a3e, 0x00183d41, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4c50, 0x001e5053, 0x00205457, 0x0021585a, 0x00245c5e, 0x00245e60, 0x00256163, 0x00266466, 0x00286e76, 0x002c8194, 0x002c8396, 0x002c8497, 0x002c8497, 0x002c8497, 0x0028707b, 0x00266364, 0x00246062, 0x00245d60, 0x0022595c, 0x00215659, 0x001f5254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0017383c, 0x00153439, 0x00143036, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00080e14, 0x00071017, 0x00071017, 0x00080f17, 0x00080f17, 0x00080f17, 0x00091018, 0x00091018, 0x00091319, 0x0008141a, 0x0008141a, 0x0008151b, 0x0008151c, 0x000a151c, 0x000b151c, 0x000b171d, 0x000b1820, 0x000b1920, 0x000b1920, 0x000a1920, 0x000a1920, 0x000b1a21, 0x000b1a21, 0x000c1a23, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1a24, 0x000c1923, 0x000b1823, 0x000b1822, 0x000a1821, 0x000a1821, 0x000b1821, 0x000b1821, 0x000c1821, 0x000c1820, 0x000c1820, 0x000b171f, 0x000a161e, 0x000a161e, 0x000b151e, 0x000b151e, 0x000b151f, 0x000b1620, 0x000b1620, 0x000a1721, 0x000a1821, 0x000b1721, 0x000c1821, 0x000b1821, 0x00091821, 0x00091821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1821, 0x00091821, 0x00091922, 0x000a1923, 0x000b1a24, 0x000c1a24, 0x000c1923, 0x000c1a22, 0x000e1d26, 0x0013222c, 0x00162833, 0x00182c38, 0x00203441, 0x00223644, 0x00243745, 0x00293a49, 0x002a3948, 0x00243440, 0x0022303c, 0x00212f3b, 0x00212f3b, 0x0026343f, 0x002b3945, 0x0030404b, 0x00344350, 0x00344453, 0x00364554, 0x00384655, 0x003b4858, 0x003c4958, 0x003e4959, 0x003e495b, 0x003f4c5c, 0x003e4b5a, 0x003c4958, 0x003e4958, 0x003e4858, 0x003c4755, 0x003c4654, 0x003c4655, 0x003f4858, 0x00404858, 0x00434a59, 0x00434a59, 0x00414957, 0x003f4754, 0x003c4452, 0x003c4452, 0x003b4351, 0x003a4451, 0x003c4554, 0x003b4453, 0x0038424f, 0x0038404d, 0x0037404c, 0x00373e4b, 0x00373e4b, 0x00373e4a, 0x00353d49, 0x00343c48, 0x00343c48, 0x00343b47, 0x00343a47, 0x00343945, 0x00313843, 0x00313843, 0x00323844, 0x00323844, 0x00333843, 0x00303540, 0x002e333d, 0x002d313c, 0x002c323c, 0x002e343d, 0x002f343d, 0x0030333d, 0x002f313c, 0x0030333d, 0x00313540, 0x00323842, 0x00333945, 0x00343946, 0x00323944, 0x002f3740, 0x002c323c, 0x002a2f39, 0x002a2e38, 0x00292e38, 0x002a2f38, 0x002a2f39, 0x002c303a, 0x002c303b, 0x002c303c, 0x002c323d, 0x002c323d, 0x002c313d, 0x002c303c, 0x00292e39, 0x00262c36, 0x00272d37, 0x00272d37, 0x00272d37, 0x00282e38, 0x00282e39, 0x00282e39, 0x00292f3b, 0x002b313c, 0x002f3440, 0x00303843, 0x00313944, 0x00313944, 0x00303843, 0x00303843, 0x002f3742, 0x002e3641, 0x002e3540, 0x002e333f, 0x002d313c, 0x002b2f39, 0x002b303a, 0x002c323c, 0x002d343f, 0x002c333e, 0x002c333e, 0x002e3440, 0x00303541, 0x00303742, 0x00333945, 0x00333a45, 0x00323a45, 0x00303a46, 0x00303a47, 0x00333d49, 0x0036404c, 0x0038414e, 0x0038424f, 0x0039424e, 0x0039424f, 0x003a4450, 0x003b4451, 0x003c4552, 0x003c4653, 0x003d4755, 0x003d4755, 0x003d4755, 0x00414b59, 0x00454f5c, 0x00424c5a, 0x003e4856, 0x003c4856, 0x003e4958, 0x00424d5d, 0x0044505f, 0x00444f5f, 0x00434e5d, 0x00414c5c, 0x00414c5c, 0x00424e5d, 0x0043505f, 0x00435060, 0x00424f5f, 0x00424f60, 0x00404d5e, 0x00404d5e, 0x00404d5e, 0x00404c5c, 0x003f4b5b, 0x003c4858, 0x00394454, 0x00364250, 0x00374150, 0x00353f4c, 0x00323c4a, 0x00333c4b, 0x00333d4a, 0x00323c48, 0x00303a47, 0x002e3844, 0x002c3642, 0x002a3440, 0x0027313c, 0x00242e39, 0x0027343f, 0x00273640, 0x0021303c, 0x0022313c, 0x0023323d, 0x0024333f, 0x00273643, 0x00283844, 0x002b3a47, 0x002d3c49, 0x00323f4c, 0x00384451, 0x003b4754, 0x003a4553, 0x00313c4a, 0x00222c37, 0x00111823, 0x000a101a, 0x00091018, 0x000c131e, 0x00111b27, 0x0013202c, 0x0012222d, 0x0010232d, 0x0010242d, 0x0010232d, 0x0010232e, 0x0010232d, 0x000f222c, 0x000e202b, 0x000e202a, 0x000e202a, 0x000e202a, 0x000f2028, 0x000f2028, 0x000f2028, 0x000e2029, 0x000e202a, 0x000f202b, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e202b, 0x000e202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f1f29, 0x000e1e28, 0x000d1e28, 0x000d1e28, 0x000d1e28, 0x000d1d27, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1c26, 0x000b1c25, 0x000b1c25, 0x000a1c24, 0x000a1c24, 0x000b1b24, 0x000c1a24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f2229, 0x0012242c, 0x0012242c, 0x0010282e, 0x00132c32, 0x00132e34, 0x00153338, 0x00153439, 0x0017383c, 0x00183d41, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4c50, 0x001e5053, 0x00205356, 0x0022585a, 0x00235a5c, 0x00245e60, 0x00256163, 0x0028737f, 0x00309ab8, 0x00319dbe, 0x00319ebe, 0x00319dbd, 0x00319cbc, 0x00309bbb, 0x0028737e, 0x00256364, 0x00246062, 0x00245d60, 0x00235a5c, 0x00215659, 0x00205356, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00173c40, 0x0017383c, 0x00143439, 0x00153338, 0x00142e34, 0x00132c32, 0x0010282e, 0x0012242c, 0x00102229, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00080e14, 0x00080f17, 0x00080f17, 0x00080f16, 0x00080f16, 0x00080f16, 0x00091018, 0x000a1018, 0x000b1219, 0x0009141a, 0x0009141a, 0x0008151b, 0x0009151c, 0x000b151c, 0x000c151c, 0x000c171d, 0x000c1820, 0x000c1820, 0x000c1820, 0x000b1920, 0x000b1920, 0x000b1a21, 0x000c1a21, 0x000c1a22, 0x000d1b23, 0x000d1b23, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1924, 0x000b1823, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000c1822, 0x000c1822, 0x000b1720, 0x000a161e, 0x000a161e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1822, 0x000a1923, 0x000a1923, 0x000b1a24, 0x000b1a24, 0x000c1924, 0x000c1822, 0x000c1a22, 0x000f1c26, 0x0011202c, 0x00142630, 0x00182c37, 0x001e3340, 0x00223744, 0x00243845, 0x00283847, 0x00283744, 0x0024333f, 0x0024323d, 0x0023303c, 0x0023303c, 0x0025333e, 0x002a3944, 0x002f3e49, 0x0033424f, 0x00344453, 0x00364454, 0x00384655, 0x00394756, 0x00394656, 0x003c4857, 0x003f4a5c, 0x00404c5c, 0x003f4c5c, 0x003d4b5a, 0x003e4b5a, 0x003f4a5a, 0x003d4857, 0x003d4755, 0x003d4756, 0x003d4757, 0x003f4858, 0x00434c5a, 0x00444c5b, 0x00434a59, 0x00404857, 0x00404855, 0x003f4655, 0x003e4654, 0x003d4754, 0x003c4654, 0x003a4452, 0x0037404d, 0x00373f4c, 0x00363e4b, 0x00373e4b, 0x00363d49, 0x00363d48, 0x00353d48, 0x00343c48, 0x00343c48, 0x00343c47, 0x00343b47, 0x00343945, 0x00323844, 0x00313843, 0x00313843, 0x00313844, 0x00313642, 0x00303540, 0x002f343e, 0x002e333d, 0x002d333c, 0x0030343e, 0x0030343e, 0x0030343e, 0x0030343f, 0x00313540, 0x00343844, 0x00353c48, 0x00353b49, 0x00333947, 0x00313844, 0x002e343f, 0x002c303b, 0x00292e38, 0x00282d36, 0x00282c34, 0x00282d36, 0x002a2f39, 0x002c303b, 0x002d323c, 0x002d323d, 0x002c323d, 0x002c323d, 0x002c313c, 0x002b2f3a, 0x00282c37, 0x00262b35, 0x00272c36, 0x00272c36, 0x00272c35, 0x00262b35, 0x00262c37, 0x00282d39, 0x00292f3a, 0x002a303c, 0x002e3440, 0x00313844, 0x00343c47, 0x00353d48, 0x00343c48, 0x00343c48, 0x00333b45, 0x00313944, 0x00313844, 0x00303743, 0x00303540, 0x002e333d, 0x002d343d, 0x002e343e, 0x002d343f, 0x002d343f, 0x002d343f, 0x002f3440, 0x00303540, 0x00303742, 0x00333944, 0x00343a45, 0x00343a45, 0x00323a46, 0x00313b47, 0x00343d4a, 0x0038404d, 0x003b4350, 0x003c4450, 0x003c4450, 0x003b4450, 0x003a4450, 0x003b4451, 0x003c4552, 0x003c4551, 0x003c4654, 0x003c4554, 0x003c4654, 0x00404a58, 0x00444d5c, 0x00424c5a, 0x003f4958, 0x003f4b58, 0x00404c5b, 0x00434e5e, 0x00455060, 0x00455060, 0x00455060, 0x00455060, 0x00455060, 0x00455160, 0x00445261, 0x00445160, 0x00445262, 0x00455263, 0x00445062, 0x00435061, 0x00445062, 0x00424f60, 0x00404c5c, 0x003c4858, 0x00394454, 0x00364251, 0x00354150, 0x00333f4d, 0x00313c4a, 0x00323c4b, 0x00343d4a, 0x00323c48, 0x00303a47, 0x002e3844, 0x002c3542, 0x00293340, 0x0028323e, 0x0027313d, 0x00283440, 0x0024333e, 0x00202f3a, 0x0024333e, 0x00243440, 0x00253541, 0x00283744, 0x002c3a48, 0x002f3e4c, 0x0032404e, 0x00364450, 0x00394554, 0x00384654, 0x00313d4b, 0x00242f3c, 0x00151e2a, 0x000b121d, 0x00091019, 0x00091019, 0x000d1520, 0x00141e2a, 0x0015222d, 0x00142430, 0x00122530, 0x00122530, 0x0011242f, 0x0010232f, 0x0010232f, 0x000f222e, 0x000e212c, 0x000e212c, 0x000e202c, 0x000d202c, 0x000e202b, 0x000f202a, 0x000f202b, 0x000e212c, 0x000e212c, 0x000f202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f202b, 0x000f202b, 0x000f202c, 0x000f212c, 0x000f222c, 0x000f222c, 0x000f222c, 0x000f222c, 0x000e212c, 0x000e212c, 0x000f212c, 0x0010212c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f202b, 0x000e1f2a, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1e27, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1c25, 0x000b1c25, 0x000a1c24, 0x000a1c24, 0x00091b24, 0x000a1b24, 0x000c1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f2229, 0x0012242c, 0x0012242c, 0x0010282e, 0x00132c32, 0x00142e34, 0x00153338, 0x0015363b, 0x00183a3e, 0x00183d41, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4c50, 0x001f5053, 0x00205457, 0x0021585a, 0x00235a5c, 0x00245e60, 0x00287686, 0x0030a0c2, 0x00319ec0, 0x002d8ba3, 0x002e8ca3, 0x002f8ca4, 0x003093ae, 0x0033a5ca, 0x00297886, 0x00266466, 0x00256163, 0x00245e60, 0x00235a5c, 0x0021585a, 0x00205457, 0x001f5053, 0x001d4c50, 0x001c484c, 0x001b4649, 0x001a4245, 0x00183f43, 0x00183c40, 0x0016363b, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00080e14, 0x00080f17, 0x00080f17, 0x00080f15, 0x00080f15, 0x00080f16, 0x00091018, 0x000a1018, 0x000b1219, 0x0009141a, 0x0009141a, 0x0008151b, 0x0009151b, 0x000b151c, 0x000c151c, 0x000c161d, 0x000c1820, 0x000c1820, 0x000c1820, 0x000b1820, 0x000b1920, 0x000c1921, 0x000c1a21, 0x000c1a22, 0x000d1b23, 0x000d1b23, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000c1822, 0x000c1822, 0x000b1720, 0x000a161e, 0x000a161e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c1821, 0x000c1822, 0x000c1821, 0x000c1821, 0x000c1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1822, 0x000b1924, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000b1924, 0x000c1822, 0x000c1a24, 0x000f1d27, 0x0011202b, 0x00142430, 0x00172a35, 0x001c303e, 0x00213644, 0x00243846, 0x00273847, 0x00273644, 0x00243440, 0x00263440, 0x0024323d, 0x0023303c, 0x0026323e, 0x00293742, 0x002f3c47, 0x0034404d, 0x00374351, 0x00374454, 0x00384655, 0x00394755, 0x00384555, 0x003b4757, 0x00404b5c, 0x00414d5d, 0x00404d5c, 0x00404c5c, 0x003f4c5c, 0x00404c5c, 0x00404c5b, 0x00424c5b, 0x003f4958, 0x003d4857, 0x003e4857, 0x00424b59, 0x00444c5b, 0x00424a59, 0x00414958, 0x00424a59, 0x00424a5a, 0x00414958, 0x00404958, 0x00404957, 0x003c4454, 0x0038404e, 0x00363e4b, 0x00373e4b, 0x00373f4c, 0x00383e4a, 0x00373e49, 0x00363e49, 0x00353d48, 0x00343c48, 0x00343c48, 0x00343b47, 0x00343a45, 0x00323844, 0x00313843, 0x00313843, 0x00313843, 0x00323743, 0x00313541, 0x00303540, 0x00303540, 0x00303640, 0x00323741, 0x00323741, 0x00333843, 0x00343a45, 0x00353c48, 0x0038404c, 0x003a4350, 0x0038404e, 0x00333948, 0x00303644, 0x002c323d, 0x002b3039, 0x00282c36, 0x00262b34, 0x00262a33, 0x00282c34, 0x002a2e38, 0x002c303b, 0x002e323c, 0x002e333e, 0x002c333e, 0x002c333e, 0x002c313d, 0x002c2f3b, 0x00292c37, 0x00252934, 0x00262a34, 0x00262b34, 0x00262a34, 0x00242833, 0x00252a35, 0x00282c38, 0x00282e3a, 0x002b303c, 0x002e343f, 0x00313844, 0x00363d49, 0x0038404c, 0x0038414d, 0x0038414c, 0x0037404c, 0x0037404c, 0x00363d4b, 0x00343b48, 0x00333846, 0x00313742, 0x00303640, 0x002f3540, 0x002e3440, 0x002e343f, 0x002e343f, 0x002f3440, 0x002f3440, 0x00303541, 0x00333844, 0x00343b46, 0x00353c47, 0x00343b48, 0x00343c48, 0x00363d4a, 0x0038404d, 0x003b4350, 0x003c4450, 0x003c4451, 0x003c4450, 0x003b4450, 0x003b4451, 0x003c4551, 0x003b4451, 0x003a4451, 0x003b4453, 0x003c4654, 0x003f4857, 0x00404a59, 0x0040495a, 0x00414b5c, 0x00444f5f, 0x00445060, 0x00445061, 0x00475363, 0x00485363, 0x00485364, 0x00485364, 0x00485464, 0x00485465, 0x00485465, 0x00485465, 0x00485566, 0x00485567, 0x00475465, 0x00445264, 0x00445062, 0x00424e60, 0x00404c5d, 0x003c4858, 0x00394454, 0x00364251, 0x00354150, 0x00333f4d, 0x00313c4a, 0x00323c4b, 0x00343e4a, 0x00323c48, 0x00303a47, 0x00303945, 0x002e3844, 0x002c3541, 0x0028323f, 0x0028333f, 0x00293440, 0x0025333f, 0x001e2d38, 0x0024343e, 0x00283742, 0x00283744, 0x002a3947, 0x002f3e4c, 0x0032414f, 0x00354450, 0x00384553, 0x00374350, 0x0033404d, 0x00283441, 0x00182330, 0x000f1824, 0x0009111e, 0x000a101b, 0x000c121c, 0x00101a24, 0x0016212c, 0x00162430, 0x00142530, 0x00132630, 0x00122630, 0x00122430, 0x0010232f, 0x0010232f, 0x000f222e, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000f202c, 0x000f202b, 0x000f202c, 0x000f222c, 0x000f222c, 0x0010212c, 0x0010212c, 0x0010212c, 0x0010212c, 0x0010212c, 0x0010212c, 0x0010212c, 0x0010212c, 0x000f222c, 0x000f222c, 0x000f222c, 0x000f222c, 0x000f222c, 0x000e212c, 0x000e212c, 0x000f212c, 0x0010222c, 0x0010212c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f202b, 0x000e1f2b, 0x000e1f2a, 0x000e1f2a, 0x000e1f2a, 0x000e1f2a, 0x000e1e27, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1c25, 0x000c1c25, 0x000b1c24, 0x000a1b24, 0x000a1b24, 0x000a1a24, 0x000c1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0013282e, 0x00102a30, 0x00132c32, 0x00153036, 0x00143439, 0x0016363b, 0x00183c40, 0x00183f43, 0x001a4347, 0x001b4649, 0x001d4a4d, 0x001d4d50, 0x001f5154, 0x00205457, 0x0021585a, 0x00235b5e, 0x00287a8e, 0x0030a0c5, 0x003099b9, 0x00287079, 0x00276668, 0x00286769, 0x00286769, 0x002a7784, 0x0033a4c8, 0x00297886, 0x00266466, 0x00256163, 0x00245e60, 0x00245c5e, 0x0022585b, 0x00205558, 0x00205254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x001a4245, 0x00183d41, 0x00183a3e, 0x0015363b, 0x00143338, 0x00142e34, 0x00132c32, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00080f14, 0x00071015, 0x00080f15, 0x00090f15, 0x00090f15, 0x00090f16, 0x000a1018, 0x000a1018, 0x000a1219, 0x0009141a, 0x0009141a, 0x0008151b, 0x0008151b, 0x0009151c, 0x000a161c, 0x000b171d, 0x000a1820, 0x000a1820, 0x000b1820, 0x000b1821, 0x000b1822, 0x000c1923, 0x000c1923, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000b1823, 0x000b1823, 0x000c1821, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000b1720, 0x000b171f, 0x000b171f, 0x000b161e, 0x000b161e, 0x000c1720, 0x000d1720, 0x000d1720, 0x000c1821, 0x000c1822, 0x000c1821, 0x000b1821, 0x000b1821, 0x00091821, 0x00091822, 0x000a1823, 0x000c1923, 0x000c1923, 0x000c1823, 0x000c1823, 0x000c1823, 0x000b1924, 0x000b1924, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000c1c24, 0x000f1e28, 0x0013222d, 0x00152530, 0x00172834, 0x001c2e3b, 0x00203440, 0x00243744, 0x00273846, 0x00283745, 0x00253442, 0x00273542, 0x0024323d, 0x00232f3b, 0x0026323e, 0x002a3642, 0x002f3946, 0x00343e4c, 0x00364150, 0x00384452, 0x00384654, 0x00394754, 0x00384654, 0x003b4856, 0x00414c5c, 0x00435060, 0x00425060, 0x00414f60, 0x00414f60, 0x00435061, 0x00445060, 0x00445060, 0x00414d5c, 0x003f4b58, 0x003e4956, 0x00404b58, 0x00424c58, 0x00414a58, 0x00414958, 0x00424a58, 0x00424a59, 0x00414b59, 0x00404b58, 0x003f4857, 0x003c4554, 0x003a4350, 0x0039424d, 0x0039414d, 0x0039404c, 0x0039404c, 0x0039404c, 0x0038404c, 0x00363e49, 0x00353d48, 0x00353c48, 0x00353c47, 0x00343b46, 0x00333944, 0x00323844, 0x00323843, 0x00323842, 0x00313741, 0x00313741, 0x00313740, 0x00313741, 0x00313843, 0x00343a45, 0x00363d48, 0x0038404c, 0x003a424f, 0x003a4450, 0x003a4550, 0x003c4551, 0x0038414e, 0x00333b48, 0x00313744, 0x002d323e, 0x00292e38, 0x00272b35, 0x00272a34, 0x00272a34, 0x00282b34, 0x002b2d38, 0x002d303b, 0x002f313c, 0x0030333f, 0x002d333e, 0x002c323e, 0x002d303c, 0x002b2e39, 0x00282b35, 0x00252833, 0x00262934, 0x00262934, 0x00252934, 0x00242832, 0x00242834, 0x00272b35, 0x00282c37, 0x002a3039, 0x002e343d, 0x00313843, 0x00343c48, 0x0035404c, 0x0037414e, 0x00384450, 0x00394452, 0x003b4453, 0x003a4351, 0x0038404f, 0x00353c4c, 0x00343b48, 0x00323845, 0x00303743, 0x002f3542, 0x002f3440, 0x002e343f, 0x002f3440, 0x002e3440, 0x002f3540, 0x00313742, 0x00343944, 0x00353b46, 0x00353c48, 0x00343c48, 0x00363d4a, 0x0038404d, 0x003a424f, 0x003c4450, 0x003c4451, 0x003c4450, 0x003c4450, 0x003c4551, 0x003d4653, 0x003e4653, 0x003d4554, 0x003d4655, 0x003e4856, 0x003f4957, 0x0040495a, 0x00414b5c, 0x00444e60, 0x00485363, 0x00475363, 0x00465363, 0x00485464, 0x00485465, 0x00495568, 0x00495568, 0x00485668, 0x00485769, 0x00485768, 0x00485668, 0x00485566, 0x00485464, 0x00475464, 0x00455364, 0x00425060, 0x003f4b5c, 0x003f4a5b, 0x003c4857, 0x00394454, 0x00374250, 0x0036404f, 0x00343d4c, 0x00313b49, 0x00323c4a, 0x00333d4a, 0x00313c48, 0x00303a46, 0x00303945, 0x002f3945, 0x002d3744, 0x00293340, 0x0029333f, 0x00283440, 0x0025343f, 0x001f2e39, 0x0024343f, 0x00293844, 0x00283845, 0x002b3b48, 0x0030404c, 0x00334450, 0x00354450, 0x00374350, 0x00313d4b, 0x002a3644, 0x001d2834, 0x00101a26, 0x000b1520, 0x0008111c, 0x00081018, 0x000a131b, 0x00101c25, 0x0014222d, 0x00142430, 0x00122530, 0x00102630, 0x00102631, 0x00102530, 0x00112430, 0x0010232f, 0x0010232f, 0x000f222e, 0x000f222e, 0x000f222c, 0x000e212c, 0x000f212b, 0x0010202a, 0x0010212c, 0x000f222d, 0x000f222d, 0x000f222d, 0x0010222d, 0x0010222d, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x000f222c, 0x0010232e, 0x0010232e, 0x0010232e, 0x0010232e, 0x000f222e, 0x000e212c, 0x000e212c, 0x000f212c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f202b, 0x000f202b, 0x000e202b, 0x000e1f2a, 0x000e1f28, 0x000d1f28, 0x000c1e27, 0x000c1e27, 0x000c1d26, 0x000c1d26, 0x000c1c26, 0x000c1c24, 0x000c1c24, 0x000c1c24, 0x000b1a23, 0x000b1a23, 0x000c1923, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00153338, 0x0015363b, 0x00183a3e, 0x00183d41, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4b4e, 0x001e4f51, 0x00205254, 0x00205558, 0x0022595c, 0x00287f96, 0x0030a2c8, 0x002c94b3, 0x00266970, 0x00266466, 0x00266467, 0x00276668, 0x00276668, 0x00297684, 0x0032a4c8, 0x00297886, 0x00266466, 0x00256264, 0x00245f61, 0x00245c5f, 0x00235a5c, 0x0021585a, 0x00205457, 0x001f5154, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00183d41, 0x00183a3e, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0010282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00061013, 0x00041013, 0x00051014, 0x00080f17, 0x00080f17, 0x00080f17, 0x00091018, 0x000a1018, 0x000a1219, 0x0009141a, 0x0009141a, 0x0008151b, 0x0008151b, 0x0008151c, 0x0008161c, 0x0008171d, 0x00081820, 0x00081820, 0x00091820, 0x000b1822, 0x000b1822, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1821, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000b171f, 0x000b171f, 0x000b171f, 0x000a161e, 0x000a161e, 0x000c1720, 0x000e1820, 0x000e1820, 0x000c1822, 0x000c1822, 0x000c1822, 0x00091822, 0x00091922, 0x00081922, 0x00081922, 0x000b1923, 0x000d1b24, 0x000d1b24, 0x000d1a24, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000b1924, 0x000b1a24, 0x000b1a24, 0x00091b24, 0x000b1c25, 0x000e1f28, 0x0012232e, 0x00142430, 0x00162532, 0x001a2c38, 0x001d303c, 0x00203440, 0x00233643, 0x00253845, 0x00253644, 0x00263543, 0x0024313e, 0x0022303b, 0x0026323e, 0x002a3642, 0x002d3845, 0x00323e4c, 0x00354150, 0x00374351, 0x00384552, 0x00384654, 0x00384654, 0x003a4855, 0x00404d5c, 0x00425060, 0x00435163, 0x00445264, 0x00445264, 0x00455466, 0x00475464, 0x00465363, 0x00445060, 0x00424e5c, 0x00404c59, 0x00404a58, 0x00404a58, 0x00404957, 0x00404957, 0x00404a58, 0x00404b59, 0x00404b59, 0x00404b58, 0x003d4856, 0x003b4654, 0x003c4553, 0x003c4551, 0x003c4451, 0x003d4450, 0x003c434e, 0x003c4350, 0x0039414e, 0x00373e4a, 0x00353d48, 0x00353c48, 0x00353c47, 0x00353b47, 0x00343945, 0x00323844, 0x00323843, 0x00313840, 0x0030373f, 0x00313841, 0x00323843, 0x00333944, 0x00333b46, 0x00353d49, 0x003a4250, 0x003d4654, 0x003d4854, 0x003c4754, 0x00394550, 0x0039444f, 0x0037404c, 0x00323c48, 0x00303844, 0x002c313d, 0x00272c36, 0x00252934, 0x00262934, 0x00272a34, 0x00282a34, 0x002b2d38, 0x002c303a, 0x002f313c, 0x0030323e, 0x002e333c, 0x002d323c, 0x002d303a, 0x002b2d38, 0x00282b35, 0x00272a34, 0x00272a34, 0x00272a34, 0x00262934, 0x00252832, 0x00242832, 0x00262934, 0x00282c35, 0x00292f38, 0x002c333c, 0x002f3740, 0x00303944, 0x00313d48, 0x0034404c, 0x003a4653, 0x003e4958, 0x003f4b5b, 0x003e4a5a, 0x003c4857, 0x00384453, 0x0037404e, 0x00343c4a, 0x00323946, 0x00313845, 0x00313844, 0x00303541, 0x002e3440, 0x002e3440, 0x002f3540, 0x00313642, 0x00333743, 0x00343844, 0x00343b46, 0x00363c48, 0x00353d4a, 0x00373f4c, 0x0039414e, 0x003a424f, 0x003b4350, 0x003b4350, 0x003b444f, 0x003c4451, 0x003d4552, 0x003e4653, 0x003f4754, 0x003f4856, 0x00404957, 0x00414b59, 0x00424c5c, 0x00434c5d, 0x00454e60, 0x00485364, 0x00485466, 0x00475466, 0x00485466, 0x00485668, 0x00495669, 0x004a586b, 0x0049586c, 0x0048586b, 0x00485868, 0x00485768, 0x00475565, 0x00475463, 0x00465363, 0x00465364, 0x00414e5f, 0x003d4859, 0x003d4859, 0x003a4555, 0x00384452, 0x0038424e, 0x00353f4c, 0x00333c48, 0x00303a47, 0x00323c48, 0x00333c49, 0x00313b48, 0x00303b48, 0x00303a47, 0x00303a46, 0x002f3844, 0x002a3441, 0x00283440, 0x00273440, 0x00263440, 0x0020303b, 0x0024343f, 0x00283a47, 0x00283a48, 0x002b3c4a, 0x0030414e, 0x00334450, 0x0032404e, 0x002f3c49, 0x0026343f, 0x00212e39, 0x0016212c, 0x000b161f, 0x0009141c, 0x00081019, 0x00071017, 0x0009141b, 0x000e1d26, 0x0011242d, 0x0010252f, 0x0010262f, 0x000e2630, 0x000d2631, 0x000f2531, 0x00112430, 0x00102430, 0x0010232f, 0x0010232f, 0x0010232e, 0x000f222c, 0x000f222c, 0x0010212b, 0x0010212a, 0x0010222c, 0x000f222e, 0x000f222e, 0x000f222e, 0x0010232f, 0x0010232e, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222c, 0x000f222c, 0x000f212c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f202b, 0x000f202b, 0x000e1f29, 0x000e1f28, 0x000d1f28, 0x000c1e27, 0x000c1e27, 0x000c1d26, 0x000c1d26, 0x000c1d26, 0x000c1c24, 0x000c1c24, 0x000c1c24, 0x000c1b23, 0x000c1b23, 0x000c1a21, 0x000b1920, 0x000c1920, 0x000d1921, 0x000d1921, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00143036, 0x00143439, 0x0017383c, 0x00183c40, 0x00194044, 0x001a4347, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205356, 0x0021595e, 0x002884a0, 0x0030a2c8, 0x002c8eab, 0x0025646b, 0x00256163, 0x00256364, 0x00266466, 0x00266467, 0x00266568, 0x00297684, 0x0032a4c8, 0x00297786, 0x00266466, 0x00256264, 0x00246062, 0x00245e60, 0x00245c5e, 0x0022595c, 0x0021585a, 0x00205457, 0x001f5154, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00183d41, 0x00183a3e, 0x00143439, 0x00143036, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00061013, 0x00051013, 0x00061014, 0x00080f17, 0x00080f17, 0x00090f17, 0x00091018, 0x000a1018, 0x000a1219, 0x0009141a, 0x0009141a, 0x0008151b, 0x0008151b, 0x0008151c, 0x0008171c, 0x0008171d, 0x00081820, 0x00081820, 0x00091820, 0x000b1822, 0x000b1822, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1821, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000b171f, 0x000b171f, 0x000b171f, 0x000a161e, 0x000a161e, 0x000c1720, 0x000d1820, 0x000d1820, 0x000c1821, 0x000c1822, 0x000c1822, 0x00091822, 0x00091922, 0x00081922, 0x00081922, 0x000a1923, 0x000c1a24, 0x000c1b24, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000c1a24, 0x000b1a24, 0x000a1b24, 0x000b1c25, 0x000c1e28, 0x000f222c, 0x0012232e, 0x0014242f, 0x00172834, 0x001a2e38, 0x001c313c, 0x001f3340, 0x00243744, 0x00263846, 0x00263644, 0x00243340, 0x0022303c, 0x0025323e, 0x00283440, 0x002c3844, 0x00323d4c, 0x00354150, 0x00374351, 0x00374451, 0x00374451, 0x00384552, 0x00394754, 0x00404d5c, 0x00425061, 0x00445264, 0x00455467, 0x00465468, 0x00465468, 0x00465466, 0x00465464, 0x00455363, 0x00455060, 0x00444e5c, 0x00414a59, 0x00404957, 0x003f4857, 0x00404a58, 0x00424c5a, 0x00414c5a, 0x00404c59, 0x00404b59, 0x003e4957, 0x003c4754, 0x003e4855, 0x003e4854, 0x003e4754, 0x003e4451, 0x003d4350, 0x003c4350, 0x0039404e, 0x00373d49, 0x00353c48, 0x00353c47, 0x00363c48, 0x00353c48, 0x00343b46, 0x00343945, 0x00333943, 0x00313840, 0x00313840, 0x00333941, 0x00353b46, 0x00383e4b, 0x0038404d, 0x003b4450, 0x003e4754, 0x00404957, 0x003d4855, 0x003b4653, 0x0038434f, 0x00343f4b, 0x00323c47, 0x002f3843, 0x002e3641, 0x002b303b, 0x00272c36, 0x00262a34, 0x00262a34, 0x00262934, 0x00272a34, 0x002a2c37, 0x002c2f39, 0x002d303b, 0x002f323d, 0x002e333c, 0x002c303b, 0x002c303a, 0x002a2d38, 0x00292c36, 0x00282b35, 0x00262833, 0x00252832, 0x00252832, 0x00242731, 0x00242831, 0x00262833, 0x00282c35, 0x00292e38, 0x002b313b, 0x002b333c, 0x002c3540, 0x002d3944, 0x00303c48, 0x0035404e, 0x003b4654, 0x003c4858, 0x003e4b5b, 0x00404c5c, 0x003e4a59, 0x003b4553, 0x00384250, 0x00363e4c, 0x00343c48, 0x00343a47, 0x00323844, 0x00303743, 0x00303743, 0x00313743, 0x00333843, 0x00343844, 0x00333743, 0x00333844, 0x00343c47, 0x00343c49, 0x00353c49, 0x0038404c, 0x003a424f, 0x003a424f, 0x003b4350, 0x003a434f, 0x003a4350, 0x003b4350, 0x003d4552, 0x00404854, 0x00404958, 0x00404a58, 0x00414b59, 0x00434c5c, 0x00444d5f, 0x00454f61, 0x00485264, 0x00485567, 0x00475667, 0x00485667, 0x00485769, 0x004a586b, 0x004a5a6c, 0x004a5b6e, 0x0049596d, 0x0048586a, 0x00485768, 0x00475566, 0x00475464, 0x00465463, 0x00455263, 0x00404d5e, 0x003a4658, 0x003a4557, 0x00394455, 0x00384352, 0x0038414e, 0x00353f4b, 0x00323c48, 0x00303a47, 0x00313b48, 0x00323c48, 0x00323c48, 0x00313b48, 0x00303a47, 0x00303945, 0x002e3844, 0x002a3541, 0x00283440, 0x00283642, 0x00283642, 0x0023323d, 0x0023333f, 0x00293b48, 0x00293c4b, 0x002b3d4b, 0x002f404c, 0x002f404c, 0x00283844, 0x00202e3b, 0x00182630, 0x001a2630, 0x00131d27, 0x0009131c, 0x0009131a, 0x00081118, 0x00081018, 0x000b161d, 0x00101f28, 0x0013242f, 0x0011252f, 0x0010262f, 0x000e2630, 0x000d2631, 0x000f2531, 0x00102430, 0x00102430, 0x0010232f, 0x0010232f, 0x0010232e, 0x000f222c, 0x000f222c, 0x0010222b, 0x0010212b, 0x0010222c, 0x000f222e, 0x000f222e, 0x0010232f, 0x0010232f, 0x0010232e, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222c, 0x000f222c, 0x000f212c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f202b, 0x000f202b, 0x000e1f29, 0x000e1f28, 0x000d1f28, 0x000c1e27, 0x000c1e27, 0x000c1d27, 0x000c1d27, 0x000c1d26, 0x000c1c24, 0x000c1c24, 0x000c1c24, 0x000c1b23, 0x000c1b23, 0x000c1a22, 0x000b1921, 0x000c1921, 0x000d1922, 0x000d1922, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00142e34, 0x00143338, 0x0016363b, 0x00183c40, 0x00183f43, 0x001a4347, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5053, 0x00205356, 0x00215b61, 0x00298aa8, 0x002ea3c9, 0x002a88a2, 0x00246064, 0x00245f61, 0x00246062, 0x00266264, 0x00256364, 0x00266466, 0x00266467, 0x00287583, 0x0032a4c8, 0x00297786, 0x00266466, 0x00256364, 0x00256163, 0x00245f61, 0x00245d60, 0x00245c5e, 0x0022595c, 0x0021585a, 0x00205457, 0x001f5154, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00183c40, 0x0017383c, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00041013, 0x00041013, 0x00051014, 0x00070f17, 0x00080f17, 0x00081017, 0x00091018, 0x00091018, 0x000a1118, 0x0009141a, 0x0009141a, 0x0008151b, 0x0008151b, 0x0008151c, 0x0008171c, 0x0008181d, 0x00081820, 0x00081820, 0x00091820, 0x000b1822, 0x000b1822, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1821, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000c1820, 0x000c1820, 0x000c1821, 0x000c1822, 0x000c1822, 0x00091822, 0x00091922, 0x00091922, 0x00091922, 0x00091922, 0x000b1a24, 0x000b1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000b1b24, 0x000b1c25, 0x000c1e27, 0x000d202b, 0x0010212c, 0x0011232d, 0x00142731, 0x00182c37, 0x001c303c, 0x001e333f, 0x00233744, 0x00253946, 0x00273845, 0x00263743, 0x0023333e, 0x0023323d, 0x0025333e, 0x00293742, 0x00303c4a, 0x0034414f, 0x00354350, 0x00364450, 0x00374450, 0x00374451, 0x003a4754, 0x00404c5b, 0x00425061, 0x00445264, 0x00455466, 0x00465468, 0x00465568, 0x00465566, 0x00465565, 0x00475465, 0x00485464, 0x00465160, 0x00444c5d, 0x00414a5a, 0x00414b5a, 0x00424c5b, 0x00444d5c, 0x00444e5c, 0x00414d5b, 0x00404c5a, 0x00404b59, 0x00404958, 0x00404958, 0x003f4754, 0x003c4451, 0x003a404d, 0x00383d4b, 0x00373c4a, 0x00383f4c, 0x00363c49, 0x00343b48, 0x00353c48, 0x00373d48, 0x00363c48, 0x00353c47, 0x00353b47, 0x00343b44, 0x00323941, 0x00323840, 0x00343b44, 0x00373d49, 0x003c4250, 0x003e4654, 0x003d4755, 0x00414b59, 0x003f4958, 0x003b4452, 0x00373f4c, 0x00343c47, 0x002c343e, 0x0028303a, 0x0028303a, 0x002b323c, 0x002a3039, 0x00282c36, 0x00262a34, 0x00252833, 0x00252833, 0x00262934, 0x00282b35, 0x002a2c37, 0x002b2e39, 0x002e303c, 0x002d323c, 0x002d313b, 0x002d303a, 0x002c2f39, 0x00292c37, 0x00282b35, 0x00262934, 0x00262833, 0x00262934, 0x00252833, 0x00252832, 0x00262931, 0x00272b34, 0x00282d37, 0x002b3039, 0x00293039, 0x00283039, 0x0028313c, 0x002b343f, 0x002e3643, 0x00333b48, 0x00384150, 0x003e4858, 0x00424e5c, 0x00424f5e, 0x00404b59, 0x003c4754, 0x003a4250, 0x00383f4c, 0x00363c48, 0x00343a45, 0x00323844, 0x00313843, 0x00313843, 0x00333843, 0x00333843, 0x00343844, 0x00343944, 0x00343b47, 0x00343c48, 0x00343c49, 0x00373f4c, 0x0039414e, 0x003b4350, 0x003b4350, 0x003a444f, 0x003a4450, 0x003c4450, 0x003f4754, 0x00404856, 0x00424b59, 0x00424c5a, 0x00404a58, 0x00424c5c, 0x00454e60, 0x00464f62, 0x00465264, 0x00485567, 0x00485668, 0x00485868, 0x004a586a, 0x004b596c, 0x004b5b6e, 0x004b5c70, 0x004a5b6f, 0x0048586c, 0x00475769, 0x00455568, 0x00455464, 0x00455464, 0x00445263, 0x003f4c5d, 0x003b4758, 0x00394457, 0x00384454, 0x00384351, 0x0037404d, 0x00343e4a, 0x00323c48, 0x00313b48, 0x00323c48, 0x00323c48, 0x00313b48, 0x00303a47, 0x00303945, 0x002e3844, 0x002c3542, 0x00293440, 0x00293541, 0x002a3844, 0x002b3944, 0x0024343f, 0x00243440, 0x00293b49, 0x002b3e4c, 0x002c3f4c, 0x002d404c, 0x00283946, 0x00192835, 0x00101d2a, 0x00121e29, 0x0018232d, 0x00121c25, 0x0008121b, 0x00091319, 0x00091118, 0x000a1219, 0x000f1920, 0x0012212b, 0x00142530, 0x00112630, 0x00102630, 0x000f2530, 0x000e2430, 0x000f2430, 0x00102430, 0x00102430, 0x0010232f, 0x0010232f, 0x0010232e, 0x0010232d, 0x0010232d, 0x0010222c, 0x0010222c, 0x0010222d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232e, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232d, 0x0010232d, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010212c, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000d1f29, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000d1d26, 0x000d1d24, 0x000d1d24, 0x000c1c24, 0x000c1c24, 0x000c1b24, 0x000b1a24, 0x000b1924, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153338, 0x0016363b, 0x00183a3e, 0x00183f43, 0x001a4347, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205254, 0x00225e67, 0x002a90b0, 0x002ea1c8, 0x00288099, 0x00245e61, 0x00245c5f, 0x00245e60, 0x00245f61, 0x00256163, 0x00256264, 0x00256364, 0x00276466, 0x00297482, 0x0032a4c8, 0x00297786, 0x00276466, 0x00256364, 0x00256264, 0x00256163, 0x00245f61, 0x00245d60, 0x00245c5e, 0x0022595c, 0x0021585a, 0x00205558, 0x00205254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00051013, 0x00051013, 0x00051014, 0x00071017, 0x00071017, 0x00071017, 0x00080f17, 0x00091018, 0x000a1118, 0x0009141a, 0x0009141a, 0x0008151b, 0x0008151b, 0x0008151c, 0x0008171c, 0x0008181d, 0x00081820, 0x00081820, 0x00091820, 0x000b1822, 0x000b1822, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1822, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1821, 0x000c1822, 0x000c1822, 0x00091822, 0x00091922, 0x00091922, 0x00091922, 0x00091922, 0x000b1a24, 0x000b1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000b1b24, 0x000b1c25, 0x000c1e27, 0x000e202a, 0x0010202c, 0x0011212c, 0x00132430, 0x00172a36, 0x001c303c, 0x00203440, 0x00243846, 0x00273a48, 0x00283b48, 0x00283946, 0x00263643, 0x00243340, 0x0024313d, 0x00293742, 0x002f3c48, 0x0033404e, 0x0034414f, 0x0034424e, 0x00364350, 0x00374551, 0x00394754, 0x003e4b59, 0x00425060, 0x00435264, 0x00455466, 0x00475668, 0x00475668, 0x00465567, 0x00465566, 0x00465566, 0x00485567, 0x00485464, 0x00475163, 0x00444f60, 0x00444e60, 0x00454e5e, 0x0046505e, 0x0046505f, 0x0044505d, 0x00424e5c, 0x00404c5a, 0x00404a58, 0x00404857, 0x003d4552, 0x003a404e, 0x00353a48, 0x00343845, 0x00363c49, 0x00383e4b, 0x00363c49, 0x00353c48, 0x00363c48, 0x00373d48, 0x00373d48, 0x00353c47, 0x00353c47, 0x00353c45, 0x00343a42, 0x00343b43, 0x00383e48, 0x003b414f, 0x003f4654, 0x003f4857, 0x003f4858, 0x00404959, 0x003b4454, 0x00343c49, 0x002e3441, 0x002a303a, 0x00252c34, 0x00232932, 0x00252b34, 0x00292f38, 0x00292e38, 0x00282c36, 0x00262a34, 0x00262934, 0x00262934, 0x00282a34, 0x00282b35, 0x002a2c37, 0x002a2c38, 0x002c2f3b, 0x002c303b, 0x002c303b, 0x002e303b, 0x002c303a, 0x002a2c37, 0x00282b35, 0x00272a34, 0x00272a34, 0x00262934, 0x00262934, 0x00262932, 0x00262931, 0x00262932, 0x00282c36, 0x00292e38, 0x00282e37, 0x00242b34, 0x00232833, 0x00232933, 0x00242b35, 0x00292f3a, 0x002d3441, 0x0038404f, 0x00414c59, 0x00434e5e, 0x00404d5c, 0x00404a58, 0x003d4654, 0x003b4250, 0x00383f4c, 0x00353b47, 0x00333945, 0x00323844, 0x00313843, 0x00323642, 0x00333743, 0x00343844, 0x00343945, 0x00363c48, 0x00373e4b, 0x00373f4c, 0x0038404d, 0x003a424f, 0x003b4350, 0x003c4452, 0x003c4552, 0x003c4451, 0x003c4453, 0x003f4756, 0x00414958, 0x00434c5b, 0x00444d5c, 0x00434c5c, 0x00424b5c, 0x00454e60, 0x00465061, 0x00465264, 0x00485567, 0x00485768, 0x00495869, 0x004b596c, 0x004c5b6d, 0x004b5b6e, 0x004b5c6f, 0x004b5c70, 0x0048596c, 0x00475769, 0x00465568, 0x00465465, 0x00455464, 0x00435162, 0x003e4c5d, 0x003c485a, 0x003b4658, 0x003a4453, 0x00384350, 0x0037404d, 0x00343e4a, 0x00333c49, 0x00323c48, 0x00333d49, 0x00313c48, 0x00303a47, 0x00303a46, 0x00303945, 0x002d3743, 0x002b3441, 0x00293440, 0x00293542, 0x002c3a46, 0x00303f4a, 0x00283844, 0x00243641, 0x002c3e4c, 0x002c404d, 0x002c404c, 0x002c3e4b, 0x00263643, 0x0014222e, 0x000c1824, 0x00131c28, 0x0018212c, 0x00111924, 0x0009111b, 0x000b131c, 0x000a131b, 0x000c161e, 0x00131e26, 0x0015242e, 0x00142630, 0x00122630, 0x00112630, 0x000f2530, 0x000e2430, 0x000f2430, 0x00102430, 0x00102430, 0x0010242f, 0x0010232f, 0x0010232e, 0x0010232d, 0x0010232d, 0x0010222c, 0x0010222c, 0x0010222d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232d, 0x0010232d, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010212c, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000d1f29, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000d1e28, 0x000d1d28, 0x000d1d26, 0x000d1d24, 0x000d1d24, 0x000c1c24, 0x000c1c24, 0x000c1b24, 0x000b1a24, 0x000b1924, 0x000c1a24, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012242c, 0x0010282e, 0x00132c32, 0x00143036, 0x00143439, 0x0017383c, 0x00183d41, 0x001a4245, 0x001b4649, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205356, 0x0022626d, 0x002b95b7, 0x002ea0c6, 0x00287a90, 0x00235c5f, 0x00245c5f, 0x00245d60, 0x00245e60, 0x00245f61, 0x00246062, 0x00256163, 0x00256264, 0x00256364, 0x00287481, 0x0031a4c8, 0x002c89a2, 0x002b7f93, 0x002b7f92, 0x002a7f91, 0x002a7d90, 0x00297c90, 0x00287c8f, 0x0028798d, 0x0028798c, 0x0027788c, 0x0026758a, 0x00257488, 0x00236d80, 0x001f5257, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183d41, 0x00183a3e, 0x00153439, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00080f14, 0x00080f14, 0x00080f14, 0x00080f16, 0x00071017, 0x00081017, 0x00091018, 0x000a1018, 0x000a1118, 0x000a131a, 0x0009141a, 0x0008141b, 0x0008151b, 0x0008151c, 0x0008171c, 0x0008171d, 0x00081820, 0x00081820, 0x00091820, 0x000b1822, 0x000b1823, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1923, 0x000c1923, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1923, 0x00091a23, 0x00091a23, 0x00091a23, 0x00091a23, 0x00091a23, 0x000b1a24, 0x000b1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000c1b24, 0x000c1c25, 0x000c1d27, 0x000e1f2a, 0x0010202c, 0x0011202c, 0x0012232f, 0x00172834, 0x001c303c, 0x00223644, 0x00263a49, 0x00293c4c, 0x002b3c4b, 0x002a3848, 0x00283645, 0x00263342, 0x00253340, 0x002a3844, 0x002f3c49, 0x0032404c, 0x0032404c, 0x0033414c, 0x00354350, 0x00374451, 0x00394755, 0x003c4958, 0x00404e5d, 0x00435061, 0x00445364, 0x00455466, 0x00475568, 0x00455668, 0x00465568, 0x00475568, 0x00475668, 0x00475667, 0x00475464, 0x00445062, 0x00445062, 0x00455062, 0x00465161, 0x00465261, 0x00455160, 0x00444e5c, 0x00414c5a, 0x00404857, 0x003f4554, 0x003c4250, 0x003a3f4c, 0x00363a48, 0x00353947, 0x00363c48, 0x00373d49, 0x00373d49, 0x00373d4a, 0x00373d48, 0x00373d48, 0x00363d48, 0x00353c47, 0x00353c47, 0x00353b46, 0x00353c45, 0x00373e49, 0x003c4350, 0x00404858, 0x00444c5c, 0x00404959, 0x003b4352, 0x0039404f, 0x00333947, 0x002d323e, 0x00262b36, 0x00232831, 0x00212530, 0x0020242d, 0x0022252e, 0x00262b34, 0x00282c36, 0x00272b35, 0x00282b35, 0x00282b35, 0x00282b35, 0x00282c37, 0x00282c37, 0x00282c37, 0x00292d38, 0x002a2e39, 0x002c303a, 0x002c303a, 0x002c303a, 0x002c2f39, 0x002a2c37, 0x00282b35, 0x00272a34, 0x00272a34, 0x00262a34, 0x00262932, 0x00252a32, 0x00242831, 0x00262a34, 0x00282c36, 0x00282d37, 0x00262b34, 0x00212630, 0x001e222c, 0x001f232c, 0x0020242d, 0x00252831, 0x00282c37, 0x002f3440, 0x003b4350, 0x003f4856, 0x00404c5c, 0x00414d5c, 0x003f4a59, 0x003d4655, 0x003a4250, 0x00383f4d, 0x00353c4a, 0x00343a48, 0x00343844, 0x00303542, 0x00303642, 0x00333943, 0x00343b45, 0x00363c48, 0x00383e4b, 0x0039404c, 0x003a404c, 0x003b434e, 0x003c4450, 0x003d4654, 0x003e4655, 0x003d4554, 0x003e4556, 0x00404858, 0x00414a59, 0x00434c5b, 0x00434c5c, 0x00444d5d, 0x00434c5d, 0x00465060, 0x00475364, 0x00485467, 0x00485668, 0x00485869, 0x0049586a, 0x0049596b, 0x004a5a6c, 0x004a5a6c, 0x004a5b6d, 0x004a5b6d, 0x0048596b, 0x0048586a, 0x0046566a, 0x00455568, 0x00455466, 0x00445061, 0x00404d5d, 0x00404b5b, 0x003d4756, 0x003b4452, 0x00384250, 0x0037404f, 0x00353f4c, 0x00343e4a, 0x00343c49, 0x00343c48, 0x00323b46, 0x00303944, 0x00303944, 0x00303944, 0x002d3844, 0x00293440, 0x00283441, 0x00273443, 0x002e3d4c, 0x00334452, 0x002e424f, 0x00263a48, 0x002c404d, 0x002c404d, 0x002c3e4c, 0x002b3c48, 0x00253440, 0x00192630, 0x000f1a25, 0x00131d28, 0x00161f2a, 0x000c161f, 0x0008131c, 0x000a141e, 0x000a161e, 0x000c1a23, 0x0013212b, 0x00142631, 0x00162733, 0x00142632, 0x00142631, 0x00112531, 0x00102530, 0x00102430, 0x00102531, 0x00102531, 0x00112430, 0x00112430, 0x0011242f, 0x0010242d, 0x0010242d, 0x0010232d, 0x0010222c, 0x0010232d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232e, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010242f, 0x0010242f, 0x000f242f, 0x000f232f, 0x000f232f, 0x000f232d, 0x000e232d, 0x000f232d, 0x0010232d, 0x0010232d, 0x000f222d, 0x000e212c, 0x000f202c, 0x000f202b, 0x0010202c, 0x000f212c, 0x000f212c, 0x000e202b, 0x000c1f29, 0x000c1f28, 0x000c1e28, 0x000c1e28, 0x000d1d28, 0x000e1d28, 0x000e1d28, 0x000d1d26, 0x000d1d24, 0x000d1d24, 0x000c1c24, 0x000c1c24, 0x000c1b26, 0x000b1a25, 0x000c1a25, 0x000d1b25, 0x000d1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153338, 0x0016363b, 0x00183c40, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4d50, 0x001f5154, 0x00205356, 0x00236877, 0x002c99bc, 0x002d9ec3, 0x00267588, 0x00245c5f, 0x00245c5f, 0x00245d60, 0x00245d60, 0x00245e60, 0x00245f61, 0x00245f61, 0x00246062, 0x00256163, 0x00256264, 0x00287481, 0x0031a4c8, 0x0032a5cb, 0x0032a5cb, 0x0032a5cb, 0x0032a5cb, 0x0032a5cb, 0x0032a5cb, 0x0032a5cb, 0x0031a4cb, 0x0031a4cb, 0x0030a4cb, 0x0030a4cb, 0x002fa4cb, 0x002da2c9, 0x002885a3, 0x001d4e51, 0x001c4a4d, 0x001a4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a0f15, 0x000a0f15, 0x000a0f15, 0x00080f17, 0x00071017, 0x00081017, 0x00091018, 0x000a1018, 0x000a1118, 0x000a131a, 0x000a141a, 0x0009141b, 0x0008151b, 0x0008151c, 0x0008161c, 0x0008171d, 0x00081820, 0x00081820, 0x000a1821, 0x000b1822, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000c1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000d1a24, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000c1924, 0x00091a24, 0x00091b24, 0x00091b24, 0x00091b24, 0x00091a24, 0x000b1a24, 0x000b1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000c1b24, 0x000c1c25, 0x000c1d27, 0x000e1f2a, 0x0010202b, 0x0011202c, 0x0012232e, 0x00152834, 0x001c303c, 0x00233847, 0x00283c4c, 0x002b3e4d, 0x002c3c4c, 0x002b394a, 0x002a3848, 0x00283546, 0x00283544, 0x002b3845, 0x00303d49, 0x00313f4a, 0x0032404b, 0x0033404c, 0x00354250, 0x00374451, 0x00394755, 0x003c4958, 0x00404d5c, 0x00415060, 0x00435263, 0x00465466, 0x00465468, 0x00465668, 0x00475668, 0x00475668, 0x00485768, 0x00485768, 0x00485465, 0x00445162, 0x00445062, 0x00455062, 0x00465163, 0x00475362, 0x00465160, 0x00444e5c, 0x00424b59, 0x00414756, 0x003f4452, 0x003c404e, 0x003b3f4d, 0x00393e4c, 0x00383c4a, 0x00373c48, 0x00383e49, 0x0039404b, 0x003a404c, 0x00383f4a, 0x00383d48, 0x00373c48, 0x00363c47, 0x00363c47, 0x00373c48, 0x00383f4c, 0x003a4250, 0x00414a5a, 0x00475062, 0x00495364, 0x00434b5a, 0x00393f4e, 0x00343847, 0x002f333f, 0x002a2d38, 0x00252832, 0x0021252e, 0x0020242c, 0x001f232b, 0x0020232b, 0x00252831, 0x00272b35, 0x00272c35, 0x00282c36, 0x00292c36, 0x00292c36, 0x00282d37, 0x00292e38, 0x00292e38, 0x00292e38, 0x002b303a, 0x002c303a, 0x002c303a, 0x002b2f39, 0x00292e38, 0x00282c35, 0x00272b35, 0x00272b35, 0x00272c34, 0x00272c34, 0x00262b33, 0x00252a32, 0x00242933, 0x00262a35, 0x00282c36, 0x00282c36, 0x00242730, 0x001d2029, 0x001c1f28, 0x001c2028, 0x001e212a, 0x0021242b, 0x00242830, 0x00282c36, 0x00303642, 0x0038404d, 0x003d4757, 0x00444f5f, 0x00434d5d, 0x00424b5b, 0x003d4755, 0x003c4452, 0x003a404f, 0x00383f4d, 0x00363c48, 0x00303642, 0x00303641, 0x00333943, 0x00353c46, 0x00363c48, 0x00373d4a, 0x00383e49, 0x003a404c, 0x003a424d, 0x003c4450, 0x003c4654, 0x003e4856, 0x00404958, 0x00414a5a, 0x00444c5c, 0x00434d5c, 0x00444d5c, 0x00434f5c, 0x0044505f, 0x00445060, 0x00465262, 0x00485768, 0x0049576a, 0x0048586a, 0x0048586a, 0x0048586a, 0x0048586b, 0x00495a6c, 0x0048596b, 0x0048596b, 0x0048596b, 0x0048596b, 0x0049596c, 0x0048586c, 0x0046566a, 0x00465467, 0x00435060, 0x00404d5c, 0x00404c5b, 0x003e4856, 0x003b4453, 0x00384250, 0x0037404f, 0x00353f4c, 0x00353f4b, 0x00343d49, 0x00333c46, 0x00323a44, 0x00313944, 0x00313944, 0x002f3844, 0x002c3643, 0x002a3440, 0x00283441, 0x00283544, 0x002e3e4d, 0x00314452, 0x00304653, 0x002b404e, 0x002a3e4c, 0x002b3d4c, 0x002a3c48, 0x00283844, 0x0023313c, 0x0016222b, 0x000d1922, 0x00121c27, 0x00141d27, 0x000b141c, 0x000b141d, 0x000b1821, 0x000c1823, 0x000c1c27, 0x0013242e, 0x00152834, 0x00152834, 0x00152633, 0x00142633, 0x00122531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00112430, 0x00112430, 0x0011242f, 0x0011242e, 0x0011242e, 0x0011232d, 0x0011232d, 0x0011232d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232e, 0x0010242d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x00102430, 0x00102430, 0x000f242f, 0x000f242f, 0x000f242f, 0x000e242d, 0x000d242d, 0x000e242d, 0x000f242d, 0x000f232d, 0x000f222d, 0x000e212d, 0x000f202c, 0x0010202c, 0x0010212c, 0x0010222c, 0x0010232d, 0x000e212c, 0x000c2029, 0x000c2029, 0x000c1e28, 0x000c1e28, 0x000d1d28, 0x000e1d28, 0x000e1d28, 0x000d1d26, 0x000d1d24, 0x000d1d24, 0x000d1d24, 0x000c1c25, 0x000c1c26, 0x000c1b26, 0x000c1a26, 0x000e1c25, 0x000e1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x00153439, 0x00183a3e, 0x00183f43, 0x001a4347, 0x001c484c, 0x001d4c50, 0x001f5154, 0x00205457, 0x00246f80, 0x002d9cc1, 0x002d9cc0, 0x0026707e, 0x00245d60, 0x00245d60, 0x00245d60, 0x00245e60, 0x00245e60, 0x00245e60, 0x00245f61, 0x00245f61, 0x00246062, 0x00256163, 0x00266264, 0x0026686f, 0x00297d90, 0x002a7f92, 0x002a7f92, 0x002a7f93, 0x002a7f92, 0x002a7f92, 0x002a7f92, 0x002a7e91, 0x00297e91, 0x00297d91, 0x00287c90, 0x00287b90, 0x00277a90, 0x002c98bc, 0x002c9bc0, 0x001f5054, 0x001d4c50, 0x001c474b, 0x00194245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0013282e, 0x00102229, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091016, 0x00091016, 0x00091016, 0x00081017, 0x00071017, 0x00081017, 0x00091018, 0x000a1018, 0x000a1118, 0x000b131a, 0x000a131a, 0x000a141b, 0x0009141b, 0x000a151c, 0x000a161c, 0x000a171d, 0x00091820, 0x00091820, 0x000a1821, 0x000b1822, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000c1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000c1924, 0x00091b24, 0x00091b24, 0x00091b24, 0x00091b24, 0x00091b24, 0x000b1a24, 0x000b1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000c1b24, 0x000c1c25, 0x000c1d27, 0x000e1f2a, 0x0010202b, 0x0011202c, 0x0012222d, 0x00142733, 0x00192c38, 0x00213544, 0x00273c4b, 0x002c3e4e, 0x002c3c4c, 0x002c3a4b, 0x002c394a, 0x002b3849, 0x002c3949, 0x002c3a47, 0x00303e4a, 0x0032404b, 0x0032404b, 0x0032404c, 0x0034414f, 0x00364350, 0x00384654, 0x003c4958, 0x003f4c5b, 0x00404f5e, 0x00445262, 0x00465466, 0x00465468, 0x00475668, 0x00475668, 0x00475668, 0x00485769, 0x00485768, 0x00485466, 0x00455263, 0x00445162, 0x00465163, 0x00455062, 0x00445060, 0x00434e5d, 0x00414b5a, 0x00414958, 0x00414756, 0x00404453, 0x003c414f, 0x003b404d, 0x003b404d, 0x003a3f4c, 0x00383e4b, 0x0039404c, 0x003b404c, 0x003b414c, 0x0039404b, 0x00383d49, 0x00383c48, 0x00383c48, 0x00373c48, 0x00383e4b, 0x003b4250, 0x003f4756, 0x00454f5f, 0x00495465, 0x004b5566, 0x00424958, 0x00383d4b, 0x00323442, 0x002c2e3a, 0x00282a34, 0x00242630, 0x0021242d, 0x0020242c, 0x0020232b, 0x0020222b, 0x00252831, 0x00272b35, 0x00272c35, 0x00282c36, 0x00292c36, 0x00292c37, 0x00282d37, 0x00292e38, 0x002a2f38, 0x002c303a, 0x002c303b, 0x002c303b, 0x002c303a, 0x002b303a, 0x00292e38, 0x00282c37, 0x00282c36, 0x00282c36, 0x00282c35, 0x00282c36, 0x00272b34, 0x00272b34, 0x00252a34, 0x00272b36, 0x00282c38, 0x00282c36, 0x0022252d, 0x001c1f28, 0x001c1f27, 0x001c1f28, 0x001c2028, 0x001d2027, 0x0020232a, 0x00242830, 0x002a2f3a, 0x00343a47, 0x00394150, 0x00404b5b, 0x00465060, 0x0046505f, 0x00414b59, 0x003f4655, 0x003b4351, 0x003a404f, 0x00383e4a, 0x00363c48, 0x00333a45, 0x00333a44, 0x00353c46, 0x00363d49, 0x00373d4a, 0x00383e4a, 0x003a404c, 0x003a424d, 0x003b4350, 0x003c4654, 0x00404a58, 0x00434c5b, 0x00434c5c, 0x00444e5e, 0x00444e5e, 0x00444e5c, 0x0044505e, 0x00465362, 0x00475463, 0x00465463, 0x00485768, 0x0049586a, 0x0048586a, 0x0048586a, 0x0048586a, 0x0048596c, 0x004a5b6c, 0x00495a6c, 0x0048596c, 0x0048596b, 0x0048596b, 0x00495a6c, 0x0047576b, 0x0046556a, 0x00455467, 0x00414f5f, 0x00404c5c, 0x003f4a59, 0x003d4755, 0x003b4452, 0x00394350, 0x0037404f, 0x00353f4d, 0x00343e4b, 0x00333c48, 0x00323944, 0x00303843, 0x00303844, 0x00313944, 0x002f3844, 0x002c3743, 0x00293340, 0x00273340, 0x002a3846, 0x002e3f4d, 0x002d404e, 0x002b414e, 0x002d4450, 0x0029404c, 0x002a3e4c, 0x00283c48, 0x00263642, 0x00202e38, 0x00111e27, 0x000b171f, 0x00101a23, 0x00101a22, 0x000c161d, 0x000e1820, 0x000e1b24, 0x000d1c27, 0x0010202c, 0x00142532, 0x00152834, 0x00142834, 0x00142733, 0x00132633, 0x00122532, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00112430, 0x00112430, 0x0011242f, 0x0011242e, 0x0011242e, 0x0010232d, 0x0010222c, 0x0010232d, 0x0010232e, 0x000f232e, 0x0010232f, 0x0010232f, 0x0010232e, 0x0010242d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x00102430, 0x00102430, 0x000f242f, 0x000f242f, 0x000f242f, 0x000e242d, 0x000d242d, 0x000e242d, 0x000f242d, 0x000f242d, 0x000f222e, 0x000e212d, 0x000f212c, 0x000f202c, 0x0010212c, 0x000f222d, 0x000f222d, 0x000e212c, 0x000d202a, 0x000c202a, 0x000c1e29, 0x000c1e28, 0x000c1d28, 0x000d1d28, 0x000d1d28, 0x000d1d26, 0x000d1d24, 0x000d1d24, 0x000d1d24, 0x000c1c25, 0x000c1c26, 0x000c1b26, 0x000c1b26, 0x000e1c25, 0x000e1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4245, 0x001b4649, 0x001d4b4e, 0x001f5053, 0x00205457, 0x0025758a, 0x002ea0c4, 0x002d98bb, 0x00256c78, 0x00245e60, 0x00245f61, 0x00245f61, 0x00245f61, 0x00245f61, 0x00245f61, 0x00245f61, 0x00245f61, 0x00245f61, 0x00246062, 0x00256163, 0x00256163, 0x00256264, 0x00256364, 0x00276466, 0x00266466, 0x00266467, 0x00266467, 0x00266467, 0x00266467, 0x00266466, 0x00266364, 0x00256264, 0x00246062, 0x00245e60, 0x00245d60, 0x002b93b2, 0x002c9bc0, 0x00205457, 0x001d4d50, 0x001c484c, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00142e34, 0x00132c32, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091016, 0x00091016, 0x00091016, 0x00081017, 0x00081018, 0x00081018, 0x000a1018, 0x000a1018, 0x000a1118, 0x000c131a, 0x000c131a, 0x000b141b, 0x000b141b, 0x000b141c, 0x000c151c, 0x000c161d, 0x000c1820, 0x000b1820, 0x000b1821, 0x000b1822, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000c1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1a24, 0x000e1a24, 0x000c1b24, 0x000a1b24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000a1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000d1b24, 0x000e1c25, 0x000d1c27, 0x00101f2a, 0x0010202b, 0x0012202c, 0x0011202c, 0x00142430, 0x00182936, 0x001e313e, 0x00283c4a, 0x002c3f4d, 0x00283a49, 0x002a3a49, 0x002c3c4b, 0x002c3c4b, 0x002c3c4a, 0x002b3946, 0x002e3c49, 0x0032404c, 0x0031404b, 0x0031404c, 0x0034414f, 0x00364350, 0x00384654, 0x003c4858, 0x003d4b59, 0x003f4c5b, 0x00445160, 0x00475465, 0x00485468, 0x00475668, 0x00485769, 0x00475668, 0x00485769, 0x00485768, 0x00485567, 0x00475465, 0x00465364, 0x00465163, 0x00455062, 0x00424e5e, 0x00404c5c, 0x00404b5b, 0x00414a5a, 0x00414857, 0x003f4454, 0x003c4150, 0x003b4050, 0x003b4050, 0x003a404e, 0x003b404e, 0x003b414e, 0x003c424e, 0x003c424d, 0x003b414c, 0x003b404c, 0x003b3f4b, 0x003a3e4a, 0x00393e4b, 0x003b404f, 0x003f4757, 0x00464f5f, 0x00485263, 0x00475364, 0x00465262, 0x003c4452, 0x00373b49, 0x00313441, 0x002a2c38, 0x00262833, 0x00232530, 0x0021242c, 0x0020232b, 0x0020232b, 0x0023242c, 0x00272932, 0x00282c36, 0x00282c36, 0x00282c36, 0x00292c36, 0x00292c37, 0x00282d37, 0x00292e38, 0x002c303b, 0x002d323c, 0x002d323c, 0x002d323c, 0x002d313c, 0x002c303b, 0x002a2f39, 0x00292e38, 0x00292e38, 0x00292e38, 0x00282d37, 0x00282d37, 0x00282c36, 0x00282c36, 0x00272b35, 0x00282c37, 0x00292e39, 0x00282c37, 0x0022242e, 0x001c1f28, 0x001c1f27, 0x001c2028, 0x001d2028, 0x001d2028, 0x00202329, 0x00242630, 0x002a2d38, 0x00343845, 0x00383e4d, 0x003e4654, 0x00485160, 0x00485361, 0x0046505e, 0x00414a59, 0x003e4654, 0x003b4250, 0x003b414e, 0x003a414d, 0x0039414d, 0x0038404c, 0x00363e4a, 0x00373f4c, 0x00383f4c, 0x00383f4c, 0x003a404d, 0x003a424d, 0x003b4350, 0x003e4654, 0x00424b59, 0x00444e5c, 0x00444e5d, 0x00444d5e, 0x00444d5d, 0x00444e5d, 0x00475260, 0x00485564, 0x00485566, 0x00485566, 0x00485769, 0x0048586a, 0x00485769, 0x0048586a, 0x0048596c, 0x004b5c6e, 0x004c5c6f, 0x004c5c6e, 0x004a5b6d, 0x00495a6c, 0x00495a6c, 0x0048586b, 0x0047576b, 0x00455468, 0x00445265, 0x00414e5e, 0x003e4b5a, 0x003d4858, 0x003c4755, 0x003c4553, 0x003b4452, 0x00384250, 0x0036404e, 0x00343e4c, 0x00323b49, 0x00303844, 0x002f3742, 0x00303843, 0x00313944, 0x00303944, 0x00303945, 0x002a3440, 0x00222e3b, 0x00283444, 0x002c3c4b, 0x002a3d4b, 0x00273d4b, 0x002c4350, 0x002c4350, 0x002c414e, 0x00283b47, 0x0021333e, 0x001c2c36, 0x00131e28, 0x000c1620, 0x000d1720, 0x000c171f, 0x000d1820, 0x00101c25, 0x00101e28, 0x000f1f2a, 0x0012232f, 0x00152834, 0x00142936, 0x00142835, 0x00132734, 0x00122734, 0x00102533, 0x00102533, 0x00102532, 0x00102531, 0x00102530, 0x00102430, 0x0010232f, 0x0010242f, 0x0011242e, 0x0010242d, 0x0010222d, 0x0010222c, 0x0010222c, 0x000f232d, 0x000f242d, 0x000f232e, 0x0010232f, 0x0010232e, 0x0010242d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x000e242d, 0x000d242d, 0x000e242d, 0x000f242d, 0x000f242d, 0x000f242f, 0x000f232f, 0x000f222e, 0x000f222e, 0x000f222e, 0x000e222e, 0x000e222e, 0x000e212d, 0x000e212c, 0x000d202c, 0x000c1e2b, 0x000c1e2a, 0x000c1e2a, 0x000c1e2a, 0x000c1e28, 0x000d1d26, 0x000d1d24, 0x000d1d24, 0x000d1d24, 0x000d1d24, 0x000c1c24, 0x000c1c25, 0x000d1c25, 0x000e1c25, 0x000e1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153439, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001d4a4d, 0x001e4d50, 0x00205458, 0x00267c94, 0x002fa1c8, 0x002c94b4, 0x00266871, 0x00246062, 0x00256163, 0x00256163, 0x00256163, 0x00256163, 0x00256163, 0x00246062, 0x00246062, 0x00246062, 0x00246062, 0x00246062, 0x00256163, 0x00256163, 0x00256264, 0x00256364, 0x00266466, 0x00266466, 0x00266467, 0x00266467, 0x00266467, 0x00266467, 0x00266467, 0x00266466, 0x00256364, 0x00266264, 0x00245f61, 0x00245e61, 0x002c93b3, 0x002c9cc0, 0x00205458, 0x001e4f51, 0x001d4a4d, 0x001a4448, 0x00183f43, 0x00173a3e, 0x00153439, 0x00142e34, 0x00122c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091016, 0x00091016, 0x00091016, 0x00081017, 0x00081018, 0x00081018, 0x000a1018, 0x000a1018, 0x000a1118, 0x000c131a, 0x000c131a, 0x000c141b, 0x000c141b, 0x000c141c, 0x000c151c, 0x000c161d, 0x000c1720, 0x000c1820, 0x000b1821, 0x000b1822, 0x000b1924, 0x000b1924, 0x000c1a24, 0x000c1b24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000c1b24, 0x000d1b24, 0x000d1b24, 0x000d1a24, 0x000d1a24, 0x000d1b25, 0x000d1c25, 0x000d1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1a24, 0x000e1a24, 0x000c1b24, 0x000b1b24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000a1b24, 0x000c1b24, 0x000c1b24, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000d1b24, 0x000e1c25, 0x000d1c27, 0x000f1f29, 0x0010202b, 0x00111f2b, 0x0010202b, 0x0012232f, 0x00152734, 0x001a2d3a, 0x00273a48, 0x002c3f4f, 0x00283b4a, 0x00283949, 0x002a3b4a, 0x002b3c4a, 0x00293a48, 0x00283844, 0x002a3845, 0x00303f4b, 0x00303f49, 0x0031404c, 0x0034414f, 0x00354250, 0x00384453, 0x003a4756, 0x003c4957, 0x003e4c59, 0x00424f5f, 0x00445263, 0x00475467, 0x00475568, 0x00465668, 0x00465668, 0x00475668, 0x00475667, 0x00475667, 0x00475566, 0x00475464, 0x00485364, 0x00465163, 0x00445060, 0x00434e5d, 0x00424d5c, 0x00414b5b, 0x00414858, 0x003f4454, 0x003c4150, 0x003c4150, 0x003c4150, 0x003c4150, 0x003c4250, 0x003c424f, 0x003c424f, 0x003c424e, 0x003c424f, 0x003c404e, 0x003d414f, 0x003c404e, 0x003d4250, 0x003f4454, 0x00434b5c, 0x00495465, 0x004b5769, 0x00485467, 0x00434d5e, 0x003c4250, 0x00373a48, 0x00323440, 0x002a2c38, 0x00262833, 0x00232530, 0x0021242c, 0x001f222b, 0x0020222b, 0x0023252e, 0x00272a33, 0x00282c36, 0x00282c36, 0x00292c36, 0x00292c36, 0x00292c37, 0x00282d37, 0x002a2f38, 0x002c313b, 0x002d323c, 0x002d323c, 0x002d313c, 0x002d313c, 0x002d313c, 0x002c303a, 0x002a2f39, 0x002b303a, 0x002b3039, 0x00292e38, 0x00282d38, 0x00282d38, 0x00292e38, 0x00292e38, 0x00292f39, 0x002b2f3b, 0x002a2d39, 0x00232630, 0x001d202a, 0x001c1f28, 0x001d2028, 0x001d2028, 0x001e2128, 0x0020242a, 0x0024262e, 0x00292c36, 0x00303440, 0x00363b48, 0x003c4452, 0x00454d5c, 0x00485261, 0x00485362, 0x00444e5e, 0x00424a5a, 0x003e4655, 0x00404654, 0x003f4654, 0x003e4653, 0x003c4453, 0x003b4350, 0x003a4250, 0x003a414e, 0x003b404e, 0x003b404e, 0x003b424e, 0x003c4451, 0x003f4755, 0x00404958, 0x00434c5b, 0x00444e5e, 0x00444e5e, 0x00444d5d, 0x00454f5e, 0x00485461, 0x00485665, 0x00495768, 0x004a5868, 0x004a5869, 0x0049586a, 0x004a586b, 0x00495a6c, 0x004a5b6d, 0x004c5c6f, 0x004c5d70, 0x004c5c6f, 0x004b5c6e, 0x004a5b6c, 0x0048586a, 0x00465668, 0x00455568, 0x00455467, 0x00445063, 0x00404c5c, 0x003e4a59, 0x003c4856, 0x003c4654, 0x003c4553, 0x003b4452, 0x00384250, 0x0036404f, 0x00343e4c, 0x00323b49, 0x00303844, 0x002f3742, 0x00303843, 0x00313944, 0x00303945, 0x00303b48, 0x002d3844, 0x0024303c, 0x00243240, 0x00283948, 0x00283c4a, 0x00273c4a, 0x0029404d, 0x002c4250, 0x002f4350, 0x002b3d4b, 0x0020303d, 0x001b2834, 0x00121c28, 0x000c1620, 0x000c161e, 0x000e1820, 0x00121c25, 0x0015202c, 0x0014232e, 0x0012232f, 0x00142532, 0x00162936, 0x00142937, 0x00132836, 0x00132734, 0x00122734, 0x00112634, 0x00102533, 0x00102532, 0x00102531, 0x00102530, 0x00102430, 0x0010232f, 0x0010242e, 0x0011242e, 0x0010242d, 0x0010232c, 0x0010222c, 0x0010222c, 0x000f232d, 0x000f242d, 0x000f232e, 0x0010232f, 0x0010232e, 0x0010242d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x000e242d, 0x000d242d, 0x000e242d, 0x000f242d, 0x000f242d, 0x000f242f, 0x000f242f, 0x000f232e, 0x000f222e, 0x000f222e, 0x000e222e, 0x000e222e, 0x000e212d, 0x000e212d, 0x000d202c, 0x000c1f2c, 0x000c1e2a, 0x000c1e2a, 0x000c1e2a, 0x000c1e28, 0x000d1d26, 0x000d1d24, 0x000d1d24, 0x000d1d24, 0x000d1d24, 0x000c1c24, 0x000c1c25, 0x000d1c25, 0x000e1c25, 0x000e1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00132c32, 0x00143036, 0x0015363b, 0x00183c40, 0x00194044, 0x001b4649, 0x001d4b4e, 0x001f5154, 0x00225e68, 0x002da0c6, 0x002c94b3, 0x0025656c, 0x00256163, 0x00266364, 0x00266466, 0x00266466, 0x00266466, 0x00256364, 0x00256364, 0x00256264, 0x00256163, 0x00256163, 0x00256163, 0x00256163, 0x00266163, 0x00256163, 0x00256264, 0x00256364, 0x00266466, 0x00276466, 0x00266467, 0x00266467, 0x00266467, 0x00266467, 0x00266467, 0x00266466, 0x00266466, 0x00256264, 0x00246062, 0x00246062, 0x002c93b3, 0x002c9cc0, 0x00205458, 0x001e4f51, 0x001c4a4d, 0x001a4448, 0x001a4044, 0x00183a3e, 0x00153439, 0x00142e34, 0x00122c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091016, 0x00091016, 0x00091016, 0x00081017, 0x00081018, 0x00081018, 0x00091018, 0x00091018, 0x00091118, 0x000b131a, 0x000b131a, 0x000b141b, 0x000b141b, 0x000b141c, 0x000c151d, 0x000b151e, 0x000c171f, 0x000c1820, 0x000b1820, 0x00091921, 0x000a1921, 0x000a1a22, 0x000a1b23, 0x000c1b24, 0x000b1b24, 0x000b1b24, 0x000a1c24, 0x000a1c24, 0x000c1c26, 0x000d1c27, 0x000d1c27, 0x000d1b27, 0x000e1b27, 0x000d1c27, 0x000c1c27, 0x000c1c27, 0x000c1c25, 0x000c1c25, 0x000d1c25, 0x000d1c25, 0x000d1c25, 0x000e1c25, 0x000f1b25, 0x000e1b24, 0x000d1b24, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b24, 0x000d1c24, 0x000e1c24, 0x000c1c24, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b23, 0x000c1a23, 0x000c1a23, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c26, 0x000f1d28, 0x00101e28, 0x00101e29, 0x0010202b, 0x0011232e, 0x00142632, 0x00182a37, 0x00243744, 0x002c404e, 0x002a3d4c, 0x00263848, 0x00283948, 0x002b3a4a, 0x00293847, 0x00283644, 0x00293744, 0x00303d48, 0x00303e49, 0x0034404d, 0x0035414f, 0x0035414f, 0x00374350, 0x003b4654, 0x003c4855, 0x003e4c59, 0x00414f5e, 0x00445161, 0x00465464, 0x00445465, 0x00445565, 0x00445565, 0x00465667, 0x00475667, 0x00455667, 0x00465566, 0x00465565, 0x00485465, 0x00475264, 0x00424e5f, 0x00414c5c, 0x00424c5c, 0x00424a5b, 0x00414859, 0x003f4655, 0x003c4452, 0x003c4352, 0x003c4452, 0x003c4452, 0x003c4350, 0x003b424f, 0x003c4350, 0x003c4450, 0x003e4451, 0x003f4452, 0x00404553, 0x003f4452, 0x00414756, 0x00454c5c, 0x00495263, 0x004b5768, 0x004c586a, 0x00495465, 0x00414b5c, 0x003b4250, 0x00363c48, 0x00313540, 0x002a2c37, 0x00262934, 0x00242730, 0x0023252e, 0x0020232c, 0x0020232c, 0x0024252f, 0x00282c34, 0x002a2d38, 0x00292d38, 0x002b2e38, 0x002a2e39, 0x002a2e39, 0x00292e38, 0x002c303b, 0x002d323c, 0x002f343e, 0x002e333e, 0x002d323c, 0x002d323c, 0x002d323c, 0x002c303b, 0x002c303b, 0x002c313b, 0x002c303b, 0x002b2f3a, 0x00292e3a, 0x002a303c, 0x002b313c, 0x002b323d, 0x002c313d, 0x002c303c, 0x002b2e39, 0x00252832, 0x001e202a, 0x001c1f28, 0x001e2028, 0x0020212a, 0x0020242b, 0x0021242c, 0x0024262e, 0x00272a34, 0x002c303c, 0x00333844, 0x0038404d, 0x00424a58, 0x00485160, 0x00495262, 0x00475060, 0x00444c5c, 0x00414959, 0x00404858, 0x00404755, 0x003e4554, 0x003c4453, 0x003c4351, 0x003c4251, 0x003b4150, 0x003c414f, 0x003c4250, 0x003c4450, 0x003e4653, 0x00404856, 0x003f4857, 0x00404a59, 0x00434c5c, 0x00454e5f, 0x00444e5f, 0x00455060, 0x00485565, 0x004a5868, 0x0049586a, 0x00485869, 0x0049586b, 0x0049596c, 0x00495a6d, 0x00495b6e, 0x00495b6d, 0x00495c6e, 0x00495c6e, 0x004a5c6e, 0x004a5b6d, 0x0048596b, 0x00465868, 0x00445565, 0x00455465, 0x00455363, 0x00434f60, 0x00414c5c, 0x003e4858, 0x003c4654, 0x003b4452, 0x003b4452, 0x003a4450, 0x00384250, 0x0037404e, 0x00353f4c, 0x00323c49, 0x00313a48, 0x00303944, 0x00303844, 0x00303846, 0x00303946, 0x002f3b48, 0x002d3b48, 0x00263543, 0x00243444, 0x00283948, 0x00293c4b, 0x00283d4b, 0x00293d4c, 0x002c404e, 0x00324553, 0x0030414e, 0x00243441, 0x001b2834, 0x000d1924, 0x000a1520, 0x000c1720, 0x00101b23, 0x00141f28, 0x0016232e, 0x00152431, 0x00142432, 0x00142633, 0x00142835, 0x00142835, 0x00132834, 0x00132734, 0x00122733, 0x00112633, 0x00112632, 0x00112632, 0x00112632, 0x00102531, 0x00102430, 0x00102430, 0x0010242f, 0x0010242f, 0x0010242f, 0x0010232f, 0x0010232f, 0x0010242f, 0x0010242f, 0x0010242f, 0x0010242f, 0x00102430, 0x0010242f, 0x000f232e, 0x000f222e, 0x000f232e, 0x000f242e, 0x000f242e, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x000f242f, 0x000f242f, 0x000f242e, 0x0010242e, 0x0010242e, 0x0010242f, 0x00102430, 0x0010242f, 0x0010232f, 0x0010232f, 0x000f232f, 0x000f222e, 0x000e222e, 0x000e212d, 0x000e212d, 0x000c202a, 0x000c2029, 0x000d1f28, 0x000d1f28, 0x000d1e28, 0x000d1d26, 0x000d1d24, 0x000d1d25, 0x000d1d25, 0x000d1d25, 0x000d1c26, 0x000d1c26, 0x000d1c26, 0x000d1c26, 0x000d1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00153338, 0x0016363b, 0x00183d41, 0x001a4347, 0x001c484c, 0x001d4d50, 0x00205356, 0x0023616b, 0x0030a2c8, 0x002a849c, 0x00256163, 0x00266466, 0x00266467, 0x00276568, 0x00276568, 0x00276568, 0x00266467, 0x00266467, 0x00266466, 0x00256364, 0x00256264, 0x00266264, 0x00256163, 0x00256163, 0x00256264, 0x00256264, 0x00256364, 0x00256364, 0x00276466, 0x00276466, 0x00266467, 0x00266467, 0x00266467, 0x00266467, 0x00276466, 0x00256364, 0x00266264, 0x00246062, 0x00245e61, 0x002c93b3, 0x002c9cc0, 0x00205458, 0x001e4f51, 0x001c4a4d, 0x001a4448, 0x00183f43, 0x00173a3e, 0x00153439, 0x00142e34, 0x00122c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081016, 0x00081017, 0x00081017, 0x00081018, 0x00081018, 0x00081018, 0x00081016, 0x00081016, 0x00081218, 0x0009131a, 0x0009141a, 0x0008151b, 0x0008151b, 0x0009141c, 0x000a141d, 0x000b151e, 0x000c161f, 0x000b171f, 0x000a1820, 0x00081920, 0x00081a20, 0x00081b21, 0x00091b22, 0x000a1c24, 0x000c1b24, 0x000c1b24, 0x000a1c24, 0x000a1c24, 0x000c1c27, 0x000d1c28, 0x000d1c28, 0x000e1c27, 0x000d1c27, 0x000c1c27, 0x000a1d28, 0x000a1d27, 0x000b1d26, 0x000c1d26, 0x000c1c26, 0x000d1c26, 0x000d1c26, 0x000f1c26, 0x00101c26, 0x000f1b24, 0x000c1b21, 0x000c1c20, 0x000c1c20, 0x000c1b20, 0x000d1b21, 0x000e1c24, 0x000f1c24, 0x000c1c24, 0x000c1c25, 0x000c1c24, 0x000c1c24, 0x000c1c23, 0x000b1a22, 0x000b1a21, 0x000b1a22, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000f1c26, 0x000f1c26, 0x000f1d28, 0x0010212c, 0x0010232e, 0x00122430, 0x00162935, 0x0020323d, 0x002a3f4b, 0x002c404f, 0x00273949, 0x00263747, 0x00293948, 0x00293947, 0x00293744, 0x00293743, 0x002f3c47, 0x00303d48, 0x0034404e, 0x0035414f, 0x0035414f, 0x0035404f, 0x00384451, 0x003b4654, 0x003d4958, 0x00414e5c, 0x0043505f, 0x00445263, 0x00445364, 0x00445364, 0x00445464, 0x00455565, 0x00465465, 0x00445464, 0x00445464, 0x00455464, 0x00475464, 0x00465264, 0x00404c5d, 0x00404b5b, 0x00414c5c, 0x00414a5b, 0x00404958, 0x00404857, 0x003e4856, 0x003d4755, 0x003c4654, 0x003c4554, 0x003c4453, 0x003b4350, 0x003c4451, 0x003e4754, 0x00404855, 0x00404855, 0x00404855, 0x00434b58, 0x00444d5c, 0x00485060, 0x004d5767, 0x004e5868, 0x004b5565, 0x00485060, 0x00404757, 0x0039404f, 0x00373d4b, 0x00323743, 0x00292e39, 0x00262a34, 0x00252830, 0x0024272c, 0x0021242a, 0x0022242b, 0x00262730, 0x002b2d36, 0x002c303a, 0x002c303b, 0x002d323c, 0x002c313c, 0x002c303c, 0x002c303b, 0x002e333c, 0x0030343e, 0x00303440, 0x002f3440, 0x002e333f, 0x002d323e, 0x002e333d, 0x002d323c, 0x002d313c, 0x002c313b, 0x002c303a, 0x002a2f39, 0x002a2f3b, 0x002b303c, 0x002c333e, 0x002c343f, 0x002c333e, 0x002c303c, 0x002c2f39, 0x00262833, 0x001f222b, 0x001d2028, 0x001f2129, 0x0021222c, 0x0022242d, 0x0023252e, 0x00252730, 0x00272934, 0x002b2f39, 0x00303641, 0x00363e49, 0x003f4754, 0x00454e5c, 0x004a5162, 0x00495363, 0x00454f5f, 0x00444b5c, 0x00414959, 0x00404757, 0x003c4352, 0x003c4150, 0x003c4150, 0x003c4150, 0x003c4150, 0x003c4251, 0x003d4451, 0x003e4653, 0x003f4754, 0x00404856, 0x003e4856, 0x003d4756, 0x00404959, 0x00444d5f, 0x00454f60, 0x00465163, 0x00485667, 0x004a5869, 0x00485969, 0x00485868, 0x0048586a, 0x0048586b, 0x0048596c, 0x00485a6c, 0x00485b6d, 0x00485a6c, 0x0047596c, 0x0047596b, 0x0048586b, 0x00455768, 0x00435564, 0x00445462, 0x00455463, 0x00445260, 0x00434e5d, 0x0040495a, 0x003e4758, 0x003a4453, 0x00394350, 0x00384250, 0x003a4450, 0x003a4450, 0x0038414e, 0x0035404c, 0x00343d4b, 0x00343d4a, 0x00323c48, 0x00303a47, 0x00303946, 0x002f3948, 0x002e3b49, 0x002c3c49, 0x00283a47, 0x00283a49, 0x002a3d4c, 0x002b3e4c, 0x002a3e4c, 0x00283d4b, 0x00283b4b, 0x00304352, 0x0030424f, 0x00273744, 0x001f2c38, 0x000e1924, 0x000b1620, 0x000c1922, 0x00101e25, 0x0013212a, 0x00142430, 0x00152532, 0x00142532, 0x00142532, 0x00132734, 0x00132835, 0x00132734, 0x00112631, 0x00112630, 0x00112630, 0x00112630, 0x00112631, 0x00112632, 0x00102531, 0x00102531, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x000f242f, 0x000e232e, 0x000e222e, 0x000f232f, 0x000f242f, 0x000f242f, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x0010242f, 0x0010242e, 0x0010242e, 0x00102430, 0x00102430, 0x0010242f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222e, 0x000e212d, 0x000e212d, 0x000d202a, 0x000d2029, 0x000d2028, 0x000e1f28, 0x000e1f28, 0x000d1e26, 0x000d1d24, 0x000d1d25, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012242c, 0x00112a30, 0x00142e34, 0x00153338, 0x0017383c, 0x00183f43, 0x001b4448, 0x001c4a4d, 0x001e5053, 0x00205457, 0x0023636c, 0x0030a2c8, 0x002b859c, 0x00266467, 0x00276668, 0x0028686a, 0x0028686b, 0x0028686b, 0x0028686b, 0x0028686a, 0x00276769, 0x00276668, 0x00276568, 0x00256466, 0x00256466, 0x00256264, 0x00256264, 0x00256264, 0x00256264, 0x00256264, 0x00256466, 0x00256466, 0x00266467, 0x00276467, 0x00276467, 0x00276467, 0x00276467, 0x00256466, 0x00256264, 0x00256164, 0x00246062, 0x00245e61, 0x002c93b3, 0x002c9bc0, 0x001f5457, 0x001e4f51, 0x001d4a4d, 0x001b4448, 0x00183f43, 0x00183a3e, 0x00153439, 0x00142e34, 0x00132c32, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081016, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00081118, 0x00081117, 0x00081117, 0x00081218, 0x0008141a, 0x0009141a, 0x0008151b, 0x0008151b, 0x0009141c, 0x000a141d, 0x000b151e, 0x000c161f, 0x000b171f, 0x000a1820, 0x00081920, 0x00081a20, 0x00081b21, 0x00091b22, 0x000b1b24, 0x000c1b24, 0x000c1b24, 0x000a1c24, 0x000b1c25, 0x000c1c27, 0x000d1c28, 0x000d1c28, 0x000e1c27, 0x000e1c27, 0x000c1c27, 0x000a1d28, 0x000a1d28, 0x000b1d27, 0x000c1d26, 0x000c1d26, 0x000d1d26, 0x000e1c26, 0x000f1c26, 0x00101c26, 0x000f1b24, 0x000c1c22, 0x000c1c21, 0x000c1c21, 0x000c1c21, 0x000d1c22, 0x000e1c24, 0x000f1c24, 0x000d1c24, 0x000c1c25, 0x000c1c24, 0x000c1b23, 0x000c1b23, 0x000b1a22, 0x000b1a21, 0x000b1a22, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000f1c26, 0x000f1c26, 0x000f1d28, 0x000f202b, 0x0010222d, 0x00112430, 0x00142834, 0x001b2e38, 0x00263a46, 0x002c404e, 0x00293c4b, 0x00283848, 0x002b3a4b, 0x002b3a4a, 0x002b3947, 0x002a3844, 0x002f3c48, 0x00303e49, 0x0034404e, 0x00354250, 0x0034404f, 0x00343f4d, 0x0036414f, 0x00394552, 0x003e4a57, 0x00434f5c, 0x0043505e, 0x00435061, 0x00445263, 0x00445363, 0x00445464, 0x00445464, 0x00445464, 0x00445363, 0x00445363, 0x00445363, 0x00455363, 0x00445162, 0x00404d5d, 0x00404c5b, 0x00414c5b, 0x00414b59, 0x00404a58, 0x00404c59, 0x00404c5a, 0x00404a58, 0x00404856, 0x003d4654, 0x003c4454, 0x003d4454, 0x003f4755, 0x00404a58, 0x00424c5a, 0x00434d59, 0x00444d5a, 0x0046505c, 0x0046505d, 0x004a5463, 0x00505869, 0x004f5868, 0x004a5263, 0x00464c5d, 0x003f4555, 0x00383f4e, 0x00383f4c, 0x00313743, 0x002c303c, 0x00292e37, 0x00282c34, 0x0025292f, 0x0024272c, 0x0026272d, 0x00282932, 0x002d2e38, 0x002e303b, 0x002e333d, 0x002f343d, 0x002e333d, 0x002d313d, 0x002e323d, 0x0030353f, 0x00323640, 0x00323642, 0x00313541, 0x00303440, 0x00303440, 0x00303440, 0x002f343f, 0x002f343f, 0x002e333d, 0x002a2f39, 0x002a2f39, 0x002c303c, 0x002c323d, 0x002d343f, 0x002c3440, 0x002c343f, 0x002c333d, 0x002c303a, 0x00262934, 0x0020242c, 0x0020232a, 0x0021242c, 0x0024252f, 0x00242630, 0x00252831, 0x00292b34, 0x00292c37, 0x002c303a, 0x00313640, 0x00383f4a, 0x003c4451, 0x00424c5a, 0x00464e5f, 0x00485060, 0x00485161, 0x00465060, 0x00434c5c, 0x00414a5a, 0x003f4655, 0x003e4453, 0x003e4453, 0x00404454, 0x003f4453, 0x003d4452, 0x003d4553, 0x00404854, 0x00404854, 0x00404855, 0x003f4856, 0x003f4857, 0x0040495a, 0x00444d5e, 0x00454f61, 0x00445061, 0x00455364, 0x00475667, 0x00475868, 0x00475868, 0x00485868, 0x0048586a, 0x0048586b, 0x0048596b, 0x0048596c, 0x0048596b, 0x00465869, 0x00455668, 0x00465668, 0x00445566, 0x00425463, 0x00435462, 0x00455362, 0x00445260, 0x00424e5d, 0x00404959, 0x003d4757, 0x00394352, 0x00384250, 0x00384250, 0x003a4450, 0x0038434f, 0x0037404d, 0x0035404c, 0x00343e4c, 0x00343d4a, 0x00323c48, 0x00313b48, 0x00303947, 0x002f3947, 0x002e3c4a, 0x002f404c, 0x002c3e4b, 0x002c3f4c, 0x002d414f, 0x002d404e, 0x002b3f4c, 0x00293d4b, 0x00273948, 0x00293b4a, 0x00293a47, 0x00243441, 0x001f2c38, 0x00111c27, 0x000c1822, 0x000d1a24, 0x00122028, 0x0015242e, 0x00152632, 0x00152834, 0x00142734, 0x00142733, 0x00132734, 0x00122734, 0x00122734, 0x00112631, 0x00112630, 0x00112630, 0x00112630, 0x00112631, 0x00112632, 0x00102531, 0x00102531, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x000f242f, 0x000e232e, 0x000e222e, 0x000f232f, 0x000f242f, 0x000f242f, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x0010242f, 0x0010242f, 0x0010242f, 0x00102430, 0x00102430, 0x00102430, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222e, 0x000e212d, 0x000e212d, 0x000d202a, 0x000d2029, 0x000d2028, 0x000e1f28, 0x000e1f28, 0x000d1e26, 0x000d1d24, 0x000d1d25, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0013282e, 0x00102a30, 0x00142e34, 0x00153439, 0x00183a3e, 0x00183f43, 0x001c4649, 0x001d4b4e, 0x001f5154, 0x00215659, 0x0024646d, 0x0031a3c8, 0x00309cbe, 0x002f95b2, 0x002f96b3, 0x003097b3, 0x003097b3, 0x003096b3, 0x003097b3, 0x003097b3, 0x002f96b3, 0x002f96b3, 0x002f94b2, 0x002f94b2, 0x002e94b2, 0x002e94b2, 0x002d94b2, 0x002d94b2, 0x002d94b2, 0x002d94b2, 0x002d94b2, 0x002d94b2, 0x002e94b2, 0x002e94b2, 0x002e94b2, 0x002e94b2, 0x002d94b2, 0x002d94b2, 0x002d94b2, 0x002d93b1, 0x002c92b1, 0x002c91b1, 0x002e9fc4, 0x002c9bc0, 0x00205256, 0x001d4c50, 0x001c484c, 0x001a4347, 0x00183d41, 0x00183a3e, 0x00153439, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081016, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00081118, 0x00081117, 0x00081117, 0x00081218, 0x0008141a, 0x0008141a, 0x0008151b, 0x0008151b, 0x0009141c, 0x000a141d, 0x000b151e, 0x000c161f, 0x000b171f, 0x000a181f, 0x0009191f, 0x0009191f, 0x000a1a20, 0x000b1b21, 0x000c1b23, 0x000c1b23, 0x000c1b24, 0x000c1b24, 0x000c1c26, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000e1c28, 0x000e1c28, 0x000c1c28, 0x000a1d29, 0x000a1d28, 0x000b1d28, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000c1c28, 0x000e1c28, 0x000f1c28, 0x000d1c26, 0x000c1c24, 0x000b1c24, 0x000c1c24, 0x000c1c24, 0x000d1c24, 0x000e1c24, 0x000e1c24, 0x000e1c24, 0x000e1c25, 0x000d1b24, 0x000c1a22, 0x000b1a21, 0x000b1a21, 0x000b1a21, 0x000b1a22, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000e1c28, 0x000d1e29, 0x000e202c, 0x00102430, 0x00132632, 0x00182b35, 0x00203541, 0x00293e4c, 0x002c3e4c, 0x002c3d4c, 0x002d3c4c, 0x002c3b4a, 0x002b3a49, 0x002b3947, 0x002e3c48, 0x00303e4b, 0x0033404e, 0x0034414f, 0x0034404f, 0x00343f4d, 0x0034404e, 0x00384450, 0x003d4955, 0x00424e5a, 0x00404e5c, 0x00404d5c, 0x00404f5e, 0x00425160, 0x00435260, 0x00415160, 0x00435261, 0x00445261, 0x00445261, 0x00445261, 0x00445261, 0x00445160, 0x00414f5e, 0x003f4c5b, 0x00404b59, 0x00414b59, 0x00424c5a, 0x00424c5b, 0x00424d5b, 0x00424c5a, 0x00424a58, 0x003e4756, 0x003e4554, 0x003e4554, 0x00414958, 0x00444c5a, 0x00444d5c, 0x0046505c, 0x00454f5c, 0x0048515f, 0x004c5664, 0x00505a6a, 0x004f5969, 0x004d5767, 0x00485060, 0x0042495a, 0x003c4253, 0x003c4251, 0x003c4350, 0x00333945, 0x002f333f, 0x002c303b, 0x002b2e38, 0x00282a32, 0x0025282e, 0x00272830, 0x002a2c34, 0x002d3038, 0x002e303a, 0x002e323c, 0x002e333d, 0x002f343e, 0x002f3440, 0x00303440, 0x00333741, 0x00343843, 0x00343944, 0x00333843, 0x00333743, 0x00333843, 0x00333743, 0x00323642, 0x00323742, 0x0030343f, 0x002c303a, 0x002c303b, 0x002e333e, 0x00303540, 0x00303742, 0x002f3742, 0x002e3641, 0x002f3440, 0x002e313c, 0x00282c36, 0x00242730, 0x0023262e, 0x00242830, 0x00282934, 0x00282a35, 0x002a2d38, 0x002d2f3a, 0x002d303b, 0x002e323d, 0x00343844, 0x0038404b, 0x003b4350, 0x003f4856, 0x00444c5c, 0x00454f5d, 0x00475260, 0x00485363, 0x00455060, 0x00444c5d, 0x00434b5a, 0x00414857, 0x00404756, 0x00414756, 0x003f4454, 0x003c4352, 0x003d4453, 0x00404854, 0x003f4754, 0x00404854, 0x00414a58, 0x00424c5b, 0x00414b5c, 0x00424c5d, 0x00455062, 0x00485364, 0x00465464, 0x00445364, 0x00455465, 0x00445465, 0x00465668, 0x00475769, 0x0048586a, 0x0047586a, 0x0048596b, 0x0049596b, 0x0047576a, 0x00465668, 0x00475668, 0x00445566, 0x00435462, 0x00425260, 0x00445261, 0x0044515f, 0x00424d5c, 0x00404959, 0x003c4656, 0x003a4452, 0x00394350, 0x00394351, 0x003a4450, 0x0035404c, 0x00343e4b, 0x00343e4a, 0x00343d4b, 0x00323c4a, 0x00313c48, 0x00313b48, 0x00303947, 0x002d3845, 0x002c3a48, 0x0030404d, 0x002f404e, 0x002f4150, 0x00304452, 0x002d404d, 0x00263a48, 0x00283b49, 0x00283847, 0x00243443, 0x00223340, 0x0020303c, 0x001d2b36, 0x00121e28, 0x000c1822, 0x000d1a24, 0x00122029, 0x0016242f, 0x00172733, 0x00152836, 0x00142836, 0x00142835, 0x00132734, 0x00112634, 0x00112633, 0x00112630, 0x00112630, 0x00122831, 0x00132831, 0x00132832, 0x00112632, 0x00102531, 0x00102531, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x000f242f, 0x000f242f, 0x000f242f, 0x000f242f, 0x000f242f, 0x000f2430, 0x00102430, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102430, 0x00112430, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222e, 0x000e212d, 0x000e212d, 0x000d202a, 0x000d2029, 0x000d2028, 0x000e1f28, 0x000e1f28, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153439, 0x00173a3e, 0x00194044, 0x001c4649, 0x001d4c50, 0x00205254, 0x0021585a, 0x00246066, 0x002e94b4, 0x0032a5c9, 0x0033a5c9, 0x0034a6c9, 0x0034a6c9, 0x0034a7c9, 0x0034a7c9, 0x0034a7c9, 0x0034a6c9, 0x0034a6c9, 0x0033a6c9, 0x0033a5c9, 0x0032a5c9, 0x0032a5c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0030a4c9, 0x0030a4c9, 0x0030a4c9, 0x002ea3c9, 0x002da1c9, 0x0027839f, 0x001f5054, 0x001d4b4e, 0x001b4649, 0x00194245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00102a30, 0x0013282e, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00071018, 0x00081018, 0x00081018, 0x00081118, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00081218, 0x0008141a, 0x0008141a, 0x0008151b, 0x0008151b, 0x0009141c, 0x000a141d, 0x000b151e, 0x000c161f, 0x000b171f, 0x000b1820, 0x000a191f, 0x000a1920, 0x000a1a20, 0x000b1b21, 0x000c1b23, 0x000d1b23, 0x000c1b24, 0x000c1b24, 0x000c1c26, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000f1c28, 0x000e1c28, 0x000c1c28, 0x000b1d29, 0x000b1d29, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000c1c28, 0x000e1c28, 0x000f1c28, 0x000e1c27, 0x000c1c24, 0x000c1c24, 0x000c1c24, 0x000c1c24, 0x000d1c24, 0x000e1c24, 0x000e1c24, 0x000e1c24, 0x000e1c25, 0x000d1b24, 0x000c1a22, 0x000b1a21, 0x000b1a21, 0x000b1a21, 0x000b1a22, 0x000c1a24, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000e1c28, 0x000d1e28, 0x000e202c, 0x0010232f, 0x00122531, 0x00152834, 0x001c313d, 0x00273c49, 0x002b3f4c, 0x002c3e4c, 0x002c3c4c, 0x002a3948, 0x00293847, 0x002c3a48, 0x002c3b48, 0x002e3d4a, 0x00313f4c, 0x0033404e, 0x0033404e, 0x0034404e, 0x0034404e, 0x00384450, 0x003c4854, 0x003d4955, 0x003c4a58, 0x003e4c5b, 0x003f4d5c, 0x003f4d5c, 0x00404f5d, 0x00404f5d, 0x00415060, 0x00435160, 0x00445260, 0x00445160, 0x00445160, 0x00445160, 0x0043505f, 0x00404d5b, 0x00404c5a, 0x00414c5a, 0x00434c5b, 0x00434d5c, 0x00414d5c, 0x00434d5c, 0x00444c5c, 0x003f4858, 0x003e4655, 0x00404857, 0x00444c5b, 0x00464f5d, 0x00464f5e, 0x0045505e, 0x0047515f, 0x00495462, 0x004f5969, 0x00515c6c, 0x004c5868, 0x00495363, 0x00434c5c, 0x003e4657, 0x003c4454, 0x003e4655, 0x003f4654, 0x00363c4a, 0x00323744, 0x00303541, 0x002f323e, 0x002c3038, 0x002a2d36, 0x002b2e38, 0x002c3039, 0x002d303b, 0x002e323c, 0x002f343d, 0x0030343f, 0x00303540, 0x00323743, 0x00343945, 0x00373c48, 0x00373c48, 0x00383c49, 0x00363b48, 0x00363a46, 0x00353a46, 0x00343945, 0x00343944, 0x00343a45, 0x00333844, 0x002f3440, 0x002e3340, 0x00303542, 0x00323845, 0x00323946, 0x00303844, 0x002e3643, 0x00303542, 0x002f333f, 0x002c303a, 0x00292c36, 0x00292c35, 0x002b2e37, 0x002c303d, 0x002d3140, 0x002e3341, 0x00303442, 0x00303543, 0x00303744, 0x00353c48, 0x0038404c, 0x003a424f, 0x003c4453, 0x00414859, 0x00434c5c, 0x0044505d, 0x00485362, 0x00485464, 0x00485160, 0x00464f5e, 0x00434b59, 0x00434a58, 0x00444958, 0x00404655, 0x003c4454, 0x003b4452, 0x003d4654, 0x00404756, 0x00414855, 0x00444b59, 0x00474f5e, 0x00434c5c, 0x00404a5c, 0x00444f60, 0x00485465, 0x00475465, 0x00445162, 0x00435162, 0x00445263, 0x00445466, 0x00455668, 0x00465769, 0x00475769, 0x00485769, 0x0048576a, 0x00485669, 0x00475568, 0x00485468, 0x00455465, 0x00425262, 0x0040505f, 0x00435261, 0x0044515f, 0x00414d5c, 0x00404959, 0x003d4656, 0x003b4453, 0x003a4451, 0x003a4451, 0x0038434f, 0x00343d49, 0x00333d49, 0x00343d49, 0x00343e4b, 0x00323c49, 0x00313b48, 0x00313b48, 0x00303948, 0x002b3644, 0x00283643, 0x002f3f4c, 0x0030414f, 0x002e414f, 0x00324654, 0x002e414f, 0x00213443, 0x00223442, 0x00263544, 0x00212f3d, 0x00202d39, 0x00202d39, 0x001d2a35, 0x00131f29, 0x000d1823, 0x000d1a24, 0x00122029, 0x0016242f, 0x00172733, 0x00152936, 0x00152937, 0x00142836, 0x00132834, 0x00122734, 0x00122734, 0x00122731, 0x00122731, 0x00132831, 0x00142832, 0x00132832, 0x00122733, 0x00102531, 0x00102531, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x000f242f, 0x000f242f, 0x000f242f, 0x000f242f, 0x00102430, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00112430, 0x00112430, 0x00112430, 0x0010232f, 0x0010232f, 0x000f222e, 0x000e212d, 0x000e212d, 0x000d202a, 0x000d2029, 0x000d2028, 0x000e1f28, 0x000e1f28, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012282e, 0x00132c32, 0x00142e34, 0x00153439, 0x00183c40, 0x00194044, 0x001b474b, 0x001d4d50, 0x00205356, 0x0022585b, 0x00245d60, 0x0026666b, 0x00287078, 0x0029727b, 0x002a747c, 0x002b757e, 0x002b767e, 0x002b767e, 0x002a757e, 0x002b757d, 0x002a747c, 0x002a737c, 0x0029727b, 0x00287079, 0x00287078, 0x00286e77, 0x00276d76, 0x00276c76, 0x00276c75, 0x00266c75, 0x00266b74, 0x00266b74, 0x00276b74, 0x00276b74, 0x00266b74, 0x00266b74, 0x00256a74, 0x00256973, 0x00256872, 0x00246771, 0x00236670, 0x0023646f, 0x0021606c, 0x00205458, 0x001d4d50, 0x001c4a4d, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00071018, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00081118, 0x00091118, 0x00091118, 0x00081218, 0x0008141a, 0x0008141a, 0x0008141a, 0x0009141b, 0x000a141c, 0x000a141d, 0x000b151e, 0x000c161f, 0x000c171f, 0x000c1820, 0x000c1821, 0x000b1821, 0x000b1922, 0x000c1a22, 0x000c1b23, 0x000d1b24, 0x000c1b25, 0x000b1c26, 0x000c1c27, 0x000c1c28, 0x000c1c28, 0x000c1c28, 0x000d1c28, 0x000e1d27, 0x000d1d28, 0x000c1e29, 0x000c1e29, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1d27, 0x000c1d27, 0x000e1d27, 0x000f1c27, 0x000f1d27, 0x000d1d26, 0x000d1d25, 0x000d1d24, 0x000d1d24, 0x000d1c24, 0x000e1c24, 0x000e1c24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1b24, 0x000c1c23, 0x000c1c23, 0x000c1b24, 0x000c1b24, 0x000c1c24, 0x000d1c25, 0x000e1c26, 0x000e1c26, 0x000e1d26, 0x000e1d26, 0x000f1c26, 0x000f1c26, 0x000f1c27, 0x000e1d28, 0x000e1f29, 0x000f202c, 0x00102330, 0x00132632, 0x00142834, 0x001a2f3c, 0x00243847, 0x00293d4c, 0x002b3f4d, 0x002c3d4e, 0x00283848, 0x00293948, 0x002c3c4a, 0x002a3a47, 0x002c3c48, 0x00303e4a, 0x0032404c, 0x0033404d, 0x0033404e, 0x0034414f, 0x00364450, 0x003c4955, 0x003c4a57, 0x003c4b58, 0x003e4c5a, 0x003f4c5c, 0x003f4d5c, 0x00404e5d, 0x00404d5c, 0x00414f5e, 0x0042505f, 0x0043505e, 0x0042505f, 0x0043505f, 0x0043505f, 0x0043505d, 0x00414d5b, 0x00404c5a, 0x00404c5a, 0x00404c5a, 0x00404c5a, 0x00404c5b, 0x00434e5c, 0x00434c5c, 0x003e4857, 0x003f4858, 0x00444c5b, 0x0048505f, 0x00485160, 0x00485161, 0x00475261, 0x00485463, 0x004c5766, 0x004f5a6a, 0x004f596a, 0x004b5566, 0x00464f60, 0x003f4858, 0x003d4554, 0x003e4756, 0x003d4655, 0x003c4453, 0x00373f4c, 0x00343c4a, 0x00343a48, 0x00343946, 0x00333843, 0x00303641, 0x002f3540, 0x002f343f, 0x002f3540, 0x00303640, 0x00323843, 0x00343845, 0x00343948, 0x00373c4a, 0x00393f4c, 0x003b414e, 0x003b414f, 0x003c424f, 0x003b404d, 0x003b404d, 0x003a404c, 0x00393e4b, 0x00383d4a, 0x00373d4a, 0x00363c49, 0x00343a47, 0x00333846, 0x00333947, 0x00343948, 0x00333a49, 0x00303847, 0x00303844, 0x002f3644, 0x002f3441, 0x002d323e, 0x002b303c, 0x002c313c, 0x00303440, 0x00323846, 0x00313948, 0x00333a48, 0x00343a49, 0x00343a49, 0x00343a48, 0x00363e4b, 0x003a424e, 0x003b4350, 0x003d4554, 0x00404858, 0x00434c5a, 0x00444e5c, 0x00485161, 0x00495464, 0x00495463, 0x00475160, 0x00444c5c, 0x00444c5c, 0x00444b5c, 0x00434a5b, 0x00404a5a, 0x00404959, 0x00424c5c, 0x00444d5d, 0x00434b5b, 0x00424a59, 0x00444c5a, 0x00424c5b, 0x00404a5b, 0x00434d5e, 0x00455061, 0x00435060, 0x00424f5f, 0x00424f5f, 0x00425061, 0x00435264, 0x00445465, 0x00445465, 0x00445364, 0x00455465, 0x00455467, 0x00465467, 0x00465467, 0x00475366, 0x00465264, 0x00445061, 0x0041505f, 0x00425060, 0x0042505e, 0x00404d5c, 0x00404b5b, 0x003e4958, 0x003c4554, 0x003b4452, 0x003b4451, 0x00384250, 0x00333c4a, 0x00333d4a, 0x00343e4b, 0x00343e4b, 0x00333c49, 0x00313b48, 0x00303a47, 0x00303a47, 0x002c3744, 0x00263340, 0x002a3a47, 0x0030424e, 0x002f4350, 0x00344857, 0x002c4050, 0x00203442, 0x00233340, 0x00233240, 0x001f2d3b, 0x001e2c38, 0x00212f39, 0x001c2934, 0x00121f29, 0x000e1924, 0x000e1b24, 0x00122028, 0x0015242e, 0x00162633, 0x00152836, 0x00162a36, 0x00152a36, 0x00142935, 0x00142834, 0x00142834, 0x00132834, 0x00132833, 0x00132833, 0x00142833, 0x00132833, 0x00112733, 0x00112632, 0x00112531, 0x00112431, 0x00112430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x0011232f, 0x0011232f, 0x0011232f, 0x0011232f, 0x0010232f, 0x000f232f, 0x000f2330, 0x00102430, 0x00102430, 0x00102432, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00112431, 0x00112431, 0x00112431, 0x00112431, 0x00112430, 0x00112430, 0x00102430, 0x0010232e, 0x000f222d, 0x000f222c, 0x000e212c, 0x000e212c, 0x000d202a, 0x000d2029, 0x000d1f28, 0x000e1f28, 0x000e1f28, 0x000e1d28, 0x000e1d28, 0x000e1e28, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012282e, 0x00132c32, 0x00142e34, 0x00143439, 0x00183c40, 0x00194245, 0x001c474b, 0x001d4d50, 0x00205356, 0x0022595c, 0x00246064, 0x00286f7b, 0x0027686b, 0x0028696c, 0x00296c6e, 0x00296d6f, 0x002a6e70, 0x002b6f70, 0x002a6e70, 0x00296d6f, 0x002a6c6f, 0x00296b6d, 0x0028696c, 0x0028686a, 0x00276668, 0x00266467, 0x00256364, 0x00256264, 0x00256163, 0x00246062, 0x00245f61, 0x00245e60, 0x00245e60, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00245c5e, 0x00235a5c, 0x0022595c, 0x0021585a, 0x00205558, 0x00205356, 0x001e5053, 0x001c4b4e, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00143439, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081016, 0x00081015, 0x00081016, 0x00081118, 0x000a1219, 0x000a1219, 0x000b131a, 0x000b131a, 0x0009131a, 0x0009141a, 0x0009141a, 0x0009141a, 0x0009141b, 0x000a141d, 0x000a141d, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c1821, 0x000c1822, 0x000c1822, 0x000c1924, 0x000c1923, 0x000d1b23, 0x000d1c25, 0x000c1c27, 0x000b1c27, 0x000b1e28, 0x000c1f28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000e1f28, 0x000e1f28, 0x000e1f2a, 0x000e1f2a, 0x000e1f2a, 0x000e1f2a, 0x000e1f28, 0x000e2026, 0x000e1f26, 0x000f1e26, 0x00101e26, 0x00101e26, 0x000e1e27, 0x000e1e27, 0x000e1e25, 0x000e1e25, 0x000e1d24, 0x000f1c24, 0x000f1c24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000f1c26, 0x000f1c26, 0x000d1d24, 0x000d1d24, 0x000c1c24, 0x000b1c25, 0x000b1c25, 0x000c1d26, 0x000c1e27, 0x000c1e27, 0x000e1e27, 0x000e1e27, 0x000f1d27, 0x00101d27, 0x000f1d27, 0x000f1e28, 0x000f202a, 0x0010212d, 0x00112430, 0x00132632, 0x00142834, 0x00192e3c, 0x00223746, 0x00273c4b, 0x002b3f4e, 0x002c3f50, 0x00293c4c, 0x00293c4b, 0x002b3c4b, 0x00283a47, 0x00293a45, 0x002c3c47, 0x00303d4a, 0x00303e4b, 0x0032404c, 0x0034414f, 0x00364450, 0x003b4856, 0x003c4a57, 0x003c4a57, 0x003d4a58, 0x003d4b5a, 0x00404d5c, 0x00424f5e, 0x00404d5c, 0x00404d5c, 0x00404d5c, 0x00404c5a, 0x003f4c59, 0x00404b58, 0x00404b59, 0x00404c58, 0x003f4a57, 0x003f4a58, 0x003e4a58, 0x003e4958, 0x003f4a58, 0x00404c59, 0x00424e5c, 0x00404b58, 0x003c4855, 0x003f4857, 0x00444e5c, 0x0046505f, 0x00465160, 0x00455160, 0x00455362, 0x00485464, 0x004a5767, 0x004b5768, 0x004a5466, 0x00474f60, 0x00434b5a, 0x003d4553, 0x003c4451, 0x003c4553, 0x003c4554, 0x003a4351, 0x0037404e, 0x0038404f, 0x0039404f, 0x003b4150, 0x0039414e, 0x0038404d, 0x00343d4b, 0x00323c48, 0x00313b48, 0x00333c48, 0x00343d4a, 0x0039404e, 0x003a4050, 0x003b4150, 0x003c4250, 0x003c4451, 0x003e4654, 0x00404856, 0x00404854, 0x003e4654, 0x003c4451, 0x003c4450, 0x0039414e, 0x0039414e, 0x0039414e, 0x0038404d, 0x00373f4d, 0x00363e4d, 0x00363d4d, 0x00353c4c, 0x00313b49, 0x00303a47, 0x00303a48, 0x00313948, 0x00303844, 0x00303744, 0x00303844, 0x00353c48, 0x0038404d, 0x00384150, 0x003a4351, 0x003a4150, 0x0038404f, 0x00373f4d, 0x0038404d, 0x003c444f, 0x003c444f, 0x003e4752, 0x003f4754, 0x00424a58, 0x00464e5c, 0x00475060, 0x00485464, 0x004a5565, 0x00495465, 0x00455060, 0x00424c5c, 0x00424c5c, 0x00424c5c, 0x00414c5c, 0x00434d5d, 0x00455060, 0x00434e5e, 0x00404a5a, 0x003f4857, 0x00404a58, 0x00424b5a, 0x00424c5c, 0x00444d5d, 0x00434d5d, 0x00404d5c, 0x00414e5d, 0x00414e5d, 0x00404d5c, 0x00414f5e, 0x0040505e, 0x0040505e, 0x00415060, 0x00445362, 0x00445262, 0x00445363, 0x00445364, 0x00455263, 0x00465162, 0x00455060, 0x00424f5d, 0x00404e5d, 0x003f4c5c, 0x003f4c5c, 0x003f4c5c, 0x003e4c59, 0x003d4857, 0x003c4553, 0x003b4451, 0x00384150, 0x00343d4c, 0x00343e4c, 0x00353f4c, 0x00343f4c, 0x00333d49, 0x00303b48, 0x002f3a48, 0x002f3a48, 0x002d3947, 0x00283543, 0x00293845, 0x002e3f4c, 0x00304352, 0x00324656, 0x002d4250, 0x00243845, 0x00233440, 0x0020303c, 0x001c2b36, 0x001f2f38, 0x0023323c, 0x001a2832, 0x00121f29, 0x000f1b24, 0x000f1b24, 0x00111e27, 0x0014222d, 0x00172532, 0x00152834, 0x00162935, 0x00162b37, 0x00152b36, 0x00142c34, 0x00142b34, 0x00142a35, 0x00142a35, 0x00142934, 0x00142834, 0x00132733, 0x00112632, 0x00112632, 0x00122632, 0x00122431, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x0011232f, 0x0011232f, 0x0011232f, 0x0011232f, 0x0010222e, 0x000f222e, 0x000f242f, 0x00102430, 0x000f2432, 0x000f2534, 0x00102532, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00112632, 0x00102531, 0x00102531, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x0010232f, 0x0010232c, 0x000f232b, 0x000f222b, 0x000e212a, 0x000e212a, 0x000d202b, 0x000d202a, 0x000d1f28, 0x000e1f28, 0x000e1f28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012282e, 0x00132c32, 0x00142e34, 0x00143439, 0x00183c40, 0x00194245, 0x001c474b, 0x001d4d50, 0x00205356, 0x0022595c, 0x00256870, 0x0031a3c6, 0x003094b1, 0x002c7e8e, 0x002a6f72, 0x002b6f70, 0x002c7071, 0x002c7071, 0x002c7071, 0x002b6f70, 0x002a6e70, 0x00296c6f, 0x00296b6d, 0x0028686b, 0x00286769, 0x00276568, 0x00266466, 0x00266264, 0x00246062, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00245c5e, 0x00245c5e, 0x00235a5c, 0x0022595c, 0x0022585b, 0x0021585a, 0x00205558, 0x00205356, 0x001f5154, 0x001d4d50, 0x001c4a4d, 0x001b4649, 0x001a4245, 0x00183d41, 0x0017383c, 0x00153439, 0x00142e34, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081015, 0x00081014, 0x00081015, 0x00081118, 0x000a1219, 0x000a1219, 0x000b131a, 0x000b131a, 0x000a131a, 0x0009141a, 0x0009141a, 0x0009141a, 0x0009141b, 0x000a141d, 0x000a141d, 0x000b151e, 0x000c161f, 0x000c1720, 0x000c1821, 0x000c1822, 0x000c1822, 0x000c1924, 0x000c1923, 0x000d1b23, 0x000d1c25, 0x000c1c27, 0x000b1c27, 0x000c1e28, 0x000c1f28, 0x000d1e28, 0x000e1f29, 0x000e1f29, 0x000f1f29, 0x000e202b, 0x000e202c, 0x000e202c, 0x000e202c, 0x000e202c, 0x000e202b, 0x000f2028, 0x000f2027, 0x00102027, 0x00102027, 0x00101f27, 0x000f1f28, 0x000f1f28, 0x000f1f27, 0x000f1f26, 0x000e1d25, 0x000f1c24, 0x000f1c24, 0x000d1c24, 0x000d1b24, 0x000d1b24, 0x000f1c26, 0x000f1c26, 0x000e1d25, 0x000d1d24, 0x000c1d24, 0x000b1c25, 0x000b1c25, 0x000c1d26, 0x000c1e27, 0x000c1e27, 0x000e1e27, 0x000e1e27, 0x000f1e27, 0x00101d27, 0x00101d28, 0x000f1f29, 0x0010202a, 0x0010212d, 0x00112430, 0x00142632, 0x00142834, 0x00192e3c, 0x00213645, 0x00273c4b, 0x002b3f4e, 0x002c3f50, 0x002b3e4e, 0x002b3e4d, 0x002a3c4b, 0x00273845, 0x00273845, 0x002b3a46, 0x00303c4a, 0x002f3c4a, 0x0033404e, 0x0034414f, 0x00364350, 0x003a4754, 0x003c4856, 0x003c4956, 0x003c4857, 0x003c4958, 0x003f4c5b, 0x00404e5c, 0x00404d5c, 0x003f4c5b, 0x003d4a58, 0x003c4855, 0x003c4855, 0x003b4754, 0x003b4754, 0x003c4854, 0x003b4753, 0x003b4754, 0x003c4855, 0x003c4856, 0x003e4958, 0x00404b58, 0x003f4a58, 0x003e4957, 0x003e4a58, 0x00404c5a, 0x00444f5c, 0x0044505d, 0x00455060, 0x00475262, 0x00485464, 0x00485665, 0x00495766, 0x004a5567, 0x00475062, 0x00414959, 0x003f4755, 0x003c4450, 0x003b4350, 0x00394150, 0x0038404f, 0x0038404e, 0x0038404f, 0x003c4452, 0x003e4654, 0x00404a58, 0x00414a58, 0x00404958, 0x003c4554, 0x00384250, 0x0037404f, 0x0038414f, 0x00384250, 0x003d4554, 0x00404858, 0x00414858, 0x00404857, 0x003f4856, 0x00414a58, 0x00444c5b, 0x00444d5b, 0x00424a59, 0x00414857, 0x00404856, 0x003f4755, 0x003e4754, 0x003d4654, 0x003c4654, 0x003c4454, 0x003c4454, 0x003b4353, 0x00394152, 0x00384050, 0x0036404e, 0x00374050, 0x00384050, 0x00373f4d, 0x0037404c, 0x0039414e, 0x003d4653, 0x003f4858, 0x00404b5a, 0x00424c5b, 0x003f4757, 0x003b4353, 0x0038404f, 0x0038404d, 0x003a434f, 0x003a424e, 0x003c444f, 0x003c4450, 0x00404855, 0x00444c5a, 0x00444e5d, 0x00495464, 0x004a5567, 0x004a5567, 0x00485364, 0x00444e60, 0x00434c5e, 0x00444d5e, 0x00424d5d, 0x00424e5d, 0x00444f5f, 0x00445060, 0x00414c5c, 0x003f4858, 0x00404a58, 0x00414c5a, 0x00424c5c, 0x00434c5c, 0x00424c5c, 0x00414e5d, 0x00414e5d, 0x00404e5d, 0x00404c5c, 0x00404d5c, 0x003f4e5c, 0x00404f5d, 0x0040505f, 0x00404e5d, 0x00404f5e, 0x00415060, 0x00435261, 0x00435160, 0x00445060, 0x00445060, 0x00424f5d, 0x00404c5d, 0x003e4b5c, 0x003c495b, 0x003c4a5a, 0x003e4c59, 0x003e4a58, 0x003c4654, 0x003a4451, 0x0037404f, 0x0038414f, 0x00384150, 0x0036404d, 0x00353f4c, 0x00333c49, 0x00303a47, 0x002e3947, 0x002d3947, 0x002d3946, 0x002b3846, 0x002b3b48, 0x002c3e4c, 0x00304352, 0x00304454, 0x002d4250, 0x00283b48, 0x00233542, 0x001e2e39, 0x001b2b36, 0x0020303a, 0x0024343d, 0x00192831, 0x0013202a, 0x00111d26, 0x000f1b24, 0x00101d26, 0x0013202c, 0x00152431, 0x00142634, 0x00152834, 0x00162b37, 0x00162c37, 0x00142c35, 0x00142b35, 0x00142a35, 0x00142a35, 0x00142934, 0x00142834, 0x00132733, 0x00112632, 0x00112632, 0x00122632, 0x00122431, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x0011232f, 0x0011232f, 0x0011232f, 0x0011232f, 0x0010222e, 0x000f222e, 0x000f242f, 0x00102430, 0x000f2432, 0x000f2534, 0x00102532, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00112632, 0x00102531, 0x00102531, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x0010232f, 0x0010232c, 0x000f232b, 0x000f222b, 0x000e212a, 0x000e212a, 0x000d202b, 0x000d202a, 0x000d1f28, 0x000e1f28, 0x000e1f28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012282e, 0x00132c32, 0x00142e34, 0x00153439, 0x00183c40, 0x00194245, 0x001b474b, 0x001d4d50, 0x00205356, 0x0023595c, 0x00256871, 0x0033a6ca, 0x0031a0c1, 0x0034a6c8, 0x00339ebc, 0x002f889a, 0x002c767c, 0x002b7173, 0x002b7173, 0x002b7072, 0x002c7071, 0x00296d6f, 0x00296c6e, 0x0028696c, 0x0028686a, 0x00276668, 0x00266466, 0x00266264, 0x00256062, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0022595c, 0x0022585b, 0x0021585a, 0x00205558, 0x00205457, 0x00205154, 0x001e4f51, 0x001d4b4e, 0x001c484c, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081015, 0x00081015, 0x00081015, 0x00081118, 0x00081118, 0x000a1219, 0x000b141a, 0x000c141b, 0x000a141a, 0x0009141a, 0x0009141a, 0x0009141a, 0x0009141b, 0x000a141b, 0x000a141c, 0x000b151d, 0x000c161f, 0x000d1720, 0x000d1721, 0x000e1822, 0x000d1822, 0x000d1924, 0x000d1923, 0x000d1b23, 0x000d1c25, 0x000c1c27, 0x000b1c27, 0x000c1d28, 0x000c1e28, 0x000e1f29, 0x000e1f2a, 0x000f202b, 0x000f202b, 0x000f202c, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212c, 0x000e212b, 0x000e212a, 0x0010212a, 0x0010202a, 0x0010202a, 0x000f202b, 0x000f202b, 0x00102029, 0x00102029, 0x000f1f28, 0x000e1e27, 0x000e1e27, 0x000e1c26, 0x000d1b24, 0x000d1b24, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101d27, 0x000f1d27, 0x000c1d26, 0x000c1d26, 0x000c1d26, 0x000c1e27, 0x000e1f28, 0x000e1f28, 0x000e1f28, 0x000f1f28, 0x000f1f28, 0x00101f28, 0x00111f29, 0x0012202a, 0x0012222c, 0x0012242e, 0x00152631, 0x00152734, 0x00192d3a, 0x00223645, 0x00293d4d, 0x002c4050, 0x002b3f50, 0x002b3f4e, 0x002b3e4d, 0x00293a4a, 0x00263745, 0x00283845, 0x002b3a47, 0x002e3c49, 0x002e3c49, 0x0034414f, 0x0034414f, 0x00354350, 0x00394754, 0x003b4856, 0x003c4855, 0x003b4754, 0x003c4855, 0x003d4956, 0x003e4b58, 0x003f4a58, 0x003c4755, 0x00394552, 0x00394451, 0x00394450, 0x00384450, 0x00384450, 0x0038444f, 0x0039444f, 0x003a4652, 0x003c4854, 0x003d4957, 0x003d4957, 0x003e4a58, 0x003e4957, 0x003f4a58, 0x00404c5a, 0x00414d5b, 0x00414c5a, 0x00424d5c, 0x00455060, 0x00485464, 0x00485565, 0x00485565, 0x00495464, 0x00485163, 0x00444c5e, 0x00404656, 0x003c4250, 0x003a414d, 0x0039404c, 0x00373e4b, 0x00353c49, 0x00363d4a, 0x00383e4c, 0x003b4250, 0x00434b59, 0x00444f5c, 0x0044505e, 0x0044505d, 0x00424d5c, 0x003e4957, 0x003c4755, 0x003c4754, 0x003d4857, 0x00404a5a, 0x00434c5d, 0x00434d5d, 0x00434d5e, 0x00444e5f, 0x00454f60, 0x00465061, 0x00475061, 0x00465060, 0x00454e60, 0x00444d5e, 0x00434c5d, 0x00434d5e, 0x00424c5d, 0x00414b5c, 0x00404859, 0x003f4658, 0x003f4658, 0x003f4758, 0x003d4455, 0x003d4555, 0x003c4657, 0x003c4758, 0x003b4654, 0x003c4756, 0x003f4a58, 0x00414e5c, 0x00475463, 0x00485566, 0x00485464, 0x00444d5f, 0x003c4656, 0x00343e4d, 0x00333c4a, 0x00343f4b, 0x0037404d, 0x0038414c, 0x0039424d, 0x003d4552, 0x00414956, 0x00434c5b, 0x00475160, 0x00485364, 0x00495566, 0x004a5567, 0x00455062, 0x00444e60, 0x00444e5f, 0x00414e5d, 0x00404c5c, 0x003e4b5a, 0x00404e5d, 0x00404d5c, 0x00404b59, 0x003f4a58, 0x00404c5a, 0x00414c5c, 0x00404c5c, 0x00404c5c, 0x00414d5d, 0x00404c5c, 0x003e4b5b, 0x003f4b5b, 0x003f4c5b, 0x00404d5c, 0x00404e5d, 0x003e4c5c, 0x003d4c5c, 0x0040505e, 0x00404f5e, 0x0040505f, 0x0041505e, 0x00404d5c, 0x00414e5c, 0x00424f5e, 0x00404d5d, 0x003e4c5c, 0x003c495b, 0x003c4858, 0x003c4a58, 0x003e4a57, 0x003c4854, 0x00384350, 0x00384150, 0x00394350, 0x003a4451, 0x00384150, 0x00353f4c, 0x00303a47, 0x002f3845, 0x002e3947, 0x002c3846, 0x002b3845, 0x002b3a47, 0x002d3e4b, 0x002c3e4c, 0x002d404e, 0x002e4350, 0x002c404e, 0x00283c49, 0x00243642, 0x001f2e3a, 0x001e2d38, 0x0021313b, 0x0022323c, 0x00192832, 0x0016242f, 0x00132029, 0x00111c26, 0x00121e27, 0x0014202c, 0x00152430, 0x00142634, 0x00162935, 0x00172c38, 0x00172c38, 0x00152c36, 0x00142c36, 0x00142a35, 0x00142a35, 0x00132934, 0x00122834, 0x00112833, 0x00102732, 0x00102732, 0x00102632, 0x00102531, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00112430, 0x00112430, 0x0011232f, 0x0011232f, 0x0011232f, 0x0011232f, 0x0010232f, 0x000f242f, 0x000f242f, 0x00102430, 0x000f2432, 0x00102634, 0x00112633, 0x00112632, 0x00112632, 0x00112632, 0x00112632, 0x00112632, 0x00112632, 0x00112632, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x0010232f, 0x0010232c, 0x000f232b, 0x000f222b, 0x000e212a, 0x000e212b, 0x000d202c, 0x000d202c, 0x000d1f2a, 0x000e1f29, 0x000e1f29, 0x000c1e28, 0x000c1e28, 0x000d1e28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153439, 0x00173a3e, 0x00194044, 0x001b474b, 0x001d4d50, 0x00205356, 0x0022595c, 0x00256870, 0x0032a4c9, 0x002a7c8a, 0x002c7f8e, 0x003298b4, 0x0035a7c8, 0x0035a4c2, 0x003291a7, 0x002c787e, 0x002c7274, 0x002b7072, 0x002b6f70, 0x002a6d6f, 0x00296b6d, 0x0028686b, 0x00276668, 0x00266466, 0x00256264, 0x00256062, 0x00245e60, 0x00245d60, 0x00245c5e, 0x00235a5c, 0x0022595c, 0x0022595c, 0x0022585b, 0x0022585a, 0x00215659, 0x00205558, 0x00205457, 0x00205254, 0x001f5053, 0x001d4d50, 0x001c4a4d, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0013282e, 0x0013242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091016, 0x00091016, 0x00091016, 0x00081118, 0x00081118, 0x000a1219, 0x000b141a, 0x000c141b, 0x000b141b, 0x000a141b, 0x000a141b, 0x000a141b, 0x000a141b, 0x000a141b, 0x000b151c, 0x000b151d, 0x000c161f, 0x000d1720, 0x000d1721, 0x000e1822, 0x000c1822, 0x000c1924, 0x000c1923, 0x000d1b23, 0x000d1c26, 0x000c1c27, 0x000b1c27, 0x000c1e28, 0x000d1f29, 0x000e1f2a, 0x000f202b, 0x000f202c, 0x0010212c, 0x0010222d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232e, 0x000f232c, 0x000f232b, 0x0010222b, 0x0010222b, 0x0010212b, 0x0010202c, 0x0010202c, 0x0010202a, 0x0010202a, 0x00102029, 0x00102028, 0x00101f28, 0x00101d27, 0x000e1c25, 0x000e1c25, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101d27, 0x000f1d27, 0x000c1d26, 0x000c1d26, 0x000c1d26, 0x000c1e27, 0x000e1f28, 0x000f2028, 0x000f2029, 0x00102029, 0x00102029, 0x00102029, 0x0012202a, 0x0013202b, 0x0012222c, 0x0013242e, 0x00152631, 0x00152734, 0x00182c39, 0x00213544, 0x002a3f4e, 0x002c4150, 0x002a3f50, 0x002a3f4e, 0x002a3d4c, 0x00283949, 0x00273846, 0x00283846, 0x002c3a47, 0x002c3947, 0x002b3845, 0x0032404d, 0x00313f4c, 0x0034424f, 0x003b4855, 0x003c4856, 0x003c4855, 0x003b4554, 0x003b4453, 0x003c4654, 0x003c4754, 0x003c4653, 0x003a4450, 0x00394450, 0x00384450, 0x0038434f, 0x0037424e, 0x0038434f, 0x0038434d, 0x0038434d, 0x00384450, 0x003a4652, 0x003b4754, 0x003c4855, 0x003e4957, 0x003f4b58, 0x00404c59, 0x00414c5b, 0x00434e5c, 0x00404b5a, 0x00404c5c, 0x00455160, 0x004a5565, 0x00485564, 0x00475463, 0x00485362, 0x00444e5e, 0x00404858, 0x003c4251, 0x00383f4b, 0x00363c48, 0x00353c48, 0x00353a48, 0x00343846, 0x00343a48, 0x00343a48, 0x00343948, 0x00404756, 0x0047505f, 0x00485260, 0x00485260, 0x0047505f, 0x00444e5c, 0x00434c5a, 0x00434c5c, 0x00444e5e, 0x00454f60, 0x00455062, 0x00475364, 0x00485466, 0x00475467, 0x00475466, 0x00485467, 0x004a5468, 0x004a5468, 0x004a5468, 0x00495467, 0x00485467, 0x00495568, 0x00495468, 0x00465164, 0x00444e61, 0x00434c60, 0x00444d60, 0x00444d60, 0x00424b5c, 0x00414a5b, 0x00434c5e, 0x00444e60, 0x00444f5e, 0x0044505f, 0x0044505e, 0x00465260, 0x004b5767, 0x004c5869, 0x004a5566, 0x00454e60, 0x00384052, 0x00303848, 0x002f3645, 0x00303845, 0x00333b48, 0x00343c48, 0x00363e49, 0x0038404c, 0x003c4451, 0x00404956, 0x00404a58, 0x00465060, 0x00485465, 0x004b5668, 0x004a5567, 0x00475164, 0x00455061, 0x00424f5e, 0x00414f5e, 0x00404c5c, 0x003f4c5c, 0x003f4b5b, 0x00414c5c, 0x00414c5c, 0x00404c5c, 0x00404b5b, 0x003e4a59, 0x003d4858, 0x003e4a59, 0x003f4a5a, 0x003f4a5a, 0x003e4958, 0x003d4858, 0x003e4a59, 0x003f4a5a, 0x003a4656, 0x003d4b59, 0x00404f5e, 0x00404f5d, 0x003f4d5c, 0x00404c5b, 0x003f4b5a, 0x003c4857, 0x003f4c5b, 0x00404d5d, 0x00404d5e, 0x003f4c5d, 0x003d4a5b, 0x003c4a58, 0x003d4a58, 0x003b4754, 0x00384451, 0x00394451, 0x003a4451, 0x00394350, 0x00384150, 0x00343e4c, 0x00303a46, 0x002e3946, 0x002f3c49, 0x002e3b48, 0x002c3b48, 0x002c3c48, 0x0030404c, 0x002f414e, 0x002b3f4c, 0x002b404d, 0x002a3f4c, 0x00283c49, 0x00243643, 0x0020303d, 0x0020303c, 0x0021303c, 0x00203039, 0x001b2a34, 0x00182732, 0x0013202b, 0x00101e28, 0x00132029, 0x0015232d, 0x00162431, 0x00162835, 0x00172a37, 0x00182c39, 0x00182c38, 0x00162d37, 0x00152c37, 0x00142a36, 0x00142a35, 0x00132934, 0x00122834, 0x00112833, 0x00102833, 0x00102732, 0x00102632, 0x00102531, 0x00102430, 0x00102430, 0x00102430, 0x00112430, 0x00112430, 0x00112430, 0x0011232f, 0x0011232f, 0x0011232f, 0x0011232f, 0x0010232f, 0x000f242f, 0x000f2430, 0x00102430, 0x000f2433, 0x00102634, 0x00122734, 0x00122733, 0x00112632, 0x00112632, 0x00112632, 0x00112632, 0x00112632, 0x00112632, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x0010232f, 0x0010232c, 0x000f232c, 0x000f222b, 0x000e212a, 0x000e212b, 0x000d202c, 0x000d202c, 0x000d1f2a, 0x000e1f29, 0x000e1f29, 0x000c1e28, 0x000c1e28, 0x000d1e28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0011242c, 0x00102a30, 0x00142e34, 0x00153439, 0x00173a3e, 0x00194044, 0x001c4649, 0x001d4c50, 0x00205356, 0x0022585b, 0x0025676f, 0x0032a4c8, 0x002b7c8c, 0x00286b6d, 0x002a7071, 0x002d7d87, 0x003294aa, 0x0036a6c6, 0x003293a8, 0x002e7b81, 0x002e8390, 0x002b7274, 0x002a6e70, 0x00296c6e, 0x0028696c, 0x00286769, 0x00266467, 0x00256364, 0x00256062, 0x00245e60, 0x00245d60, 0x00235c5e, 0x00235a5c, 0x0021595c, 0x0022585b, 0x0022585a, 0x0021585a, 0x00215659, 0x00205558, 0x00205356, 0x00205254, 0x001e5053, 0x001e4c50, 0x001c4a4d, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x0016363b, 0x00153338, 0x00132e34, 0x00102a30, 0x0013282e, 0x0013242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081118, 0x00091117, 0x00091117, 0x00091118, 0x00091118, 0x000a1219, 0x000b131a, 0x000b141a, 0x000a141b, 0x000a141b, 0x000a141b, 0x000a141b, 0x000a141b, 0x0009151c, 0x000a161c, 0x000b161e, 0x000b171f, 0x000c1720, 0x000c1821, 0x000c1921, 0x000c1922, 0x000c1a24, 0x000c1a24, 0x000c1b24, 0x000c1c27, 0x000c1c28, 0x000c1e28, 0x000c1f29, 0x000d202a, 0x000e202b, 0x000f202c, 0x000f212d, 0x0010212e, 0x0010232f, 0x0010242f, 0x0010242f, 0x00102430, 0x00102430, 0x00102430, 0x0010242e, 0x0010242e, 0x0010232e, 0x0010232d, 0x000f222d, 0x000f202d, 0x000f202d, 0x0010202c, 0x0010202c, 0x0010202b, 0x00102029, 0x000f2028, 0x000f1e28, 0x000e1d26, 0x000d1c26, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000c1d27, 0x000c1e27, 0x000c1e28, 0x000d1e28, 0x000e1f28, 0x00102029, 0x0010202a, 0x0010202a, 0x0010202a, 0x0010202b, 0x0011202c, 0x0012212d, 0x00122330, 0x00122430, 0x00142633, 0x00152834, 0x00182c3a, 0x00203544, 0x002a3f4e, 0x002c4050, 0x00293e4d, 0x002a3e4c, 0x002c3d4c, 0x002a3b48, 0x00283744, 0x00293845, 0x002c3b48, 0x002c3a48, 0x00283644, 0x002e3b48, 0x002e3c49, 0x00374452, 0x003c4856, 0x003c4855, 0x003b4654, 0x00394351, 0x00384150, 0x00384250, 0x00384350, 0x0038434f, 0x0038434f, 0x0039434f, 0x0038434f, 0x0035414d, 0x00343f4b, 0x00353f4b, 0x00343f48, 0x00354049, 0x0037404c, 0x0038424e, 0x0038424f, 0x003b4653, 0x003d4a56, 0x00404d59, 0x00424e5b, 0x00434e5c, 0x00444f5f, 0x00444e5f, 0x00434d5e, 0x00465162, 0x00485464, 0x00485362, 0x00475160, 0x0046505e, 0x00424958, 0x003d4452, 0x00383d4b, 0x00343b46, 0x00323843, 0x00313843, 0x00323844, 0x00323744, 0x00303642, 0x002e3440, 0x002c323e, 0x00313744, 0x003c4350, 0x00454b58, 0x00464b59, 0x003f4452, 0x003d4452, 0x00404855, 0x00454c5b, 0x00484f5f, 0x00454e60, 0x00445064, 0x00465668, 0x00495a6c, 0x00495c6d, 0x00485b6d, 0x004c5b6f, 0x004d5b70, 0x004d5b6f, 0x004d5b70, 0x004c5a6f, 0x004c5b70, 0x004d5d71, 0x004d5c71, 0x004a596d, 0x004a576c, 0x004a566b, 0x00495569, 0x00485466, 0x00455061, 0x00455060, 0x0047505f, 0x0046505f, 0x00444d5c, 0x00414a58, 0x003d4654, 0x003f4856, 0x0047505e, 0x00495261, 0x00454d5c, 0x00383f4e, 0x002c3140, 0x002c3141, 0x002e3241, 0x002e3340, 0x002e3440, 0x00313842, 0x00343945, 0x00353c47, 0x0039404c, 0x003d4552, 0x003f4754, 0x00444c5b, 0x00485262, 0x004b5668, 0x004c5869, 0x00485466, 0x00445060, 0x00414d5e, 0x00434f60, 0x00445061, 0x00445060, 0x00424d5d, 0x00414c5c, 0x00414c5c, 0x00404b5b, 0x00404959, 0x003e4858, 0x003d4857, 0x003e4958, 0x003e4a58, 0x003c4756, 0x003b4554, 0x003b4654, 0x003c4856, 0x003b4654, 0x00384453, 0x003d4958, 0x00404d5c, 0x003f4c5c, 0x003c4958, 0x003c4857, 0x003c4959, 0x003a4756, 0x003b4858, 0x003e4b5c, 0x00404d5e, 0x00404d5e, 0x003f4c5d, 0x003d4a5b, 0x003c4958, 0x003a4654, 0x00384452, 0x00394452, 0x00394451, 0x0037404e, 0x00313b49, 0x00303a48, 0x00333d4a, 0x00303c49, 0x002f3c4a, 0x00303e4c, 0x00303e4c, 0x002d3d4b, 0x0030404e, 0x00304350, 0x002c404d, 0x002b3f4c, 0x002a3f4c, 0x002c3f4c, 0x00283a48, 0x00253544, 0x00233240, 0x00202f3c, 0x001e2d38, 0x001c2b36, 0x00182832, 0x0014222c, 0x0014202a, 0x0014212c, 0x0017242f, 0x00182633, 0x00182938, 0x00192c3b, 0x00192e3c, 0x00182e3b, 0x00162e3a, 0x00162d39, 0x00142c38, 0x00142b37, 0x00132a35, 0x00122834, 0x00122834, 0x00122834, 0x00112834, 0x00112632, 0x00102531, 0x00102531, 0x000f2531, 0x000f2531, 0x00102431, 0x00102431, 0x00102431, 0x00112430, 0x00112430, 0x0011232f, 0x0011232f, 0x0010232f, 0x000f2430, 0x000f2430, 0x000f2431, 0x00102532, 0x00102633, 0x00112733, 0x00112733, 0x00112732, 0x00112732, 0x00112732, 0x00112632, 0x00102531, 0x00102531, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x00102430, 0x0010232e, 0x000f222d, 0x000f222c, 0x000e212c, 0x000e212c, 0x000d202c, 0x000d202b, 0x000c202a, 0x000d202a, 0x000d202a, 0x000d1e28, 0x000d1e28, 0x000d1e28, 0x000e1e28, 0x000e1e28, 0x000e1e28, 0x000e1e28, 0x000e1e28, 0x000d1e28, 0x000d1e28, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012242c, 0x00112a30, 0x00142e34, 0x00153338, 0x00183a3e, 0x00183f43, 0x001c4649, 0x001d4b4e, 0x001f5254, 0x0022585b, 0x0024646c, 0x0030a0c4, 0x002c8598, 0x00296b6d, 0x002b6f70, 0x002b7173, 0x002c7375, 0x00349ab4, 0x00349db8, 0x00349cb7, 0x0037a8ca, 0x00349cb8, 0x002e8190, 0x002a6f72, 0x00286a6c, 0x0028686a, 0x00276568, 0x00266364, 0x00256163, 0x00245e60, 0x00245d60, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0022585b, 0x0022585a, 0x00215659, 0x00205558, 0x00205558, 0x00205356, 0x00205254, 0x001e5053, 0x001e4d50, 0x001c4a4d, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081319, 0x00091318, 0x00091318, 0x000a1219, 0x000a1219, 0x000a1219, 0x000b131a, 0x000b131a, 0x000a141c, 0x000b151d, 0x000b151d, 0x000b151d, 0x000a151d, 0x0009161c, 0x0009161c, 0x0009171e, 0x000a1820, 0x000b1820, 0x000b1a21, 0x000c1b22, 0x000c1b23, 0x000a1c24, 0x000b1c25, 0x000c1c27, 0x000c1d28, 0x000c1e28, 0x000c1f29, 0x000c202a, 0x000d202b, 0x000e212c, 0x000e212c, 0x000f222e, 0x0010232f, 0x0010242f, 0x00102430, 0x00102430, 0x00102531, 0x00112632, 0x00102531, 0x00102430, 0x00102430, 0x000f242f, 0x000f242f, 0x000f2230, 0x000f2230, 0x000f222f, 0x0010222f, 0x0010222e, 0x0010212c, 0x000f2029, 0x000f2028, 0x000e1f28, 0x000d1e27, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000d1e28, 0x000d1f29, 0x000e1f29, 0x000e202a, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202d, 0x0011212f, 0x00112230, 0x00122431, 0x00122432, 0x00132534, 0x00142835, 0x00172c39, 0x001c313f, 0x00253c48, 0x002a404d, 0x00283f4c, 0x002b404d, 0x002d3f4c, 0x002a3b48, 0x00283643, 0x00283643, 0x002d3b47, 0x002d3b46, 0x00283441, 0x002a3844, 0x002c3947, 0x00384452, 0x003a4754, 0x003a4554, 0x003a4553, 0x00394451, 0x0036404d, 0x00343d4a, 0x00343f4a, 0x0037404c, 0x0037414c, 0x0038434e, 0x0038424f, 0x0034404c, 0x00323c48, 0x00323c48, 0x00313c45, 0x00323c45, 0x00343e48, 0x0036404a, 0x0037404d, 0x00394450, 0x003c4955, 0x00404d59, 0x00424d5c, 0x00414d5c, 0x00445060, 0x00445061, 0x00434e60, 0x00445061, 0x00455062, 0x00465060, 0x00444e5c, 0x00424958, 0x003c4350, 0x00373d4b, 0x00313743, 0x002f3540, 0x002e343e, 0x002e343e, 0x002e343f, 0x002d343e, 0x002b313b, 0x00292f38, 0x00292e38, 0x00282d37, 0x002a2d38, 0x002f313d, 0x00323440, 0x00343641, 0x00343843, 0x00353a45, 0x00343a46, 0x003c4452, 0x00414a5c, 0x00445060, 0x00475668, 0x004a5b6d, 0x00495d6f, 0x004b6072, 0x00506276, 0x00526377, 0x00536478, 0x00526377, 0x00516276, 0x00526278, 0x0054657a, 0x0054667b, 0x00506277, 0x00506075, 0x00506074, 0x004d5b6e, 0x00485667, 0x00475361, 0x00475160, 0x00434b59, 0x003c4350, 0x0038404c, 0x00383f4b, 0x00383f4a, 0x00383f4b, 0x003b404d, 0x003b404d, 0x00343845, 0x002b2f3c, 0x00262a38, 0x00282c3a, 0x002c303d, 0x002c313c, 0x002c323c, 0x00303640, 0x00323842, 0x00313843, 0x00343a46, 0x0038404c, 0x003c4452, 0x00404857, 0x00454d5d, 0x004a5364, 0x004c5869, 0x004a5668, 0x00465163, 0x00434d5f, 0x00434e5f, 0x00445061, 0x00434e60, 0x00424c5c, 0x00414a5a, 0x00404a58, 0x003e4856, 0x003c4654, 0x003d4756, 0x003d4856, 0x003d4856, 0x003c4855, 0x00384350, 0x0035404e, 0x0036424f, 0x00394451, 0x00384350, 0x00384451, 0x003c4756, 0x003d4a58, 0x003d4b58, 0x00394654, 0x00374452, 0x003c4858, 0x003a4757, 0x00394756, 0x003c4a5a, 0x003f4c5d, 0x003f4c5d, 0x003d4a5c, 0x003c495a, 0x003c4959, 0x00394755, 0x00394554, 0x003a4453, 0x003a4452, 0x00353f4d, 0x002d3745, 0x002c3644, 0x00343e4c, 0x0033404e, 0x00303e4b, 0x002f3e4d, 0x0031404f, 0x0030404f, 0x002d404e, 0x002c404e, 0x002c4250, 0x002c424f, 0x002c404e, 0x002c404d, 0x002c3f4d, 0x002a3c4a, 0x00253544, 0x0022323f, 0x0022313d, 0x001e2d38, 0x00182832, 0x00162430, 0x0014222d, 0x0014222d, 0x00172530, 0x00192834, 0x00192a39, 0x00192c3c, 0x001a2e3d, 0x00182f3c, 0x00162e3c, 0x00162d3b, 0x00162c39, 0x00152c38, 0x00142a35, 0x00122834, 0x00122834, 0x00122835, 0x00112834, 0x00112633, 0x00102531, 0x00102631, 0x000e2631, 0x000e2631, 0x000f2631, 0x000f2631, 0x00102531, 0x00102531, 0x00102430, 0x0010242f, 0x000f242f, 0x000f242f, 0x000f2530, 0x000f2530, 0x00102631, 0x00102632, 0x00112632, 0x00112833, 0x00112833, 0x00112833, 0x00112833, 0x00112833, 0x00112632, 0x00102531, 0x00102531, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x00112430, 0x0010232f, 0x000f222e, 0x000f222e, 0x000e212d, 0x000e212d, 0x000e212c, 0x000d202b, 0x000d202b, 0x000d202b, 0x000d202b, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00143338, 0x0017383c, 0x00183f43, 0x001b4448, 0x001d4b4e, 0x001f5154, 0x0021585a, 0x00245f63, 0x002f98b8, 0x002e93af, 0x00296c6e, 0x002b6e70, 0x002b7173, 0x002c7475, 0x003499b3, 0x00359db9, 0x0035a0bc, 0x0036a5c4, 0x0035a0be, 0x0036a8c8, 0x00339cb8, 0x002c808e, 0x00286b6f, 0x00276668, 0x00266466, 0x00256163, 0x00245f61, 0x00245d60, 0x00245c5e, 0x00235a5c, 0x0021595c, 0x0022585b, 0x0022585a, 0x0022585a, 0x00215659, 0x00205558, 0x00205457, 0x00205254, 0x001f5053, 0x001d4d50, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081419, 0x00091418, 0x00091418, 0x00091319, 0x00091219, 0x00091219, 0x000a131a, 0x000b141a, 0x000b141c, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151d, 0x0009161c, 0x0008161c, 0x0009171e, 0x000a1820, 0x000b1920, 0x000b1a22, 0x000c1b23, 0x000c1c24, 0x000b1c25, 0x000b1c26, 0x000c1d28, 0x000c1d29, 0x000c1e29, 0x000d1f29, 0x000d202b, 0x000e212c, 0x000e212c, 0x000f222c, 0x000f222e, 0x0010232f, 0x00102430, 0x00102530, 0x00102531, 0x00112632, 0x00122733, 0x00122733, 0x00112632, 0x00102632, 0x00102530, 0x00102430, 0x00102432, 0x00102433, 0x00102332, 0x000f2331, 0x00102330, 0x0010222e, 0x000f212c, 0x000e212b, 0x000e202a, 0x000d202a, 0x000c2029, 0x000c1f29, 0x000c1f29, 0x000c1f29, 0x000c1f29, 0x000c1f29, 0x000d202a, 0x000d202b, 0x000d202b, 0x000e212c, 0x000f212c, 0x000f222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222e, 0x00112330, 0x00112331, 0x00122432, 0x00122433, 0x00132534, 0x00142734, 0x00152b38, 0x0019303d, 0x00243a47, 0x0029404c, 0x00293e4c, 0x002c414f, 0x002d3f4d, 0x00273745, 0x00233140, 0x00243340, 0x002b3944, 0x002d3b46, 0x00293742, 0x002a3844, 0x002a3845, 0x0034424f, 0x00384552, 0x00394452, 0x00384451, 0x00394451, 0x00343f4c, 0x00303a46, 0x00343d48, 0x00343f49, 0x00343e48, 0x0036404b, 0x00353f4c, 0x00323c48, 0x00303a47, 0x00313a46, 0x00313a44, 0x00323b44, 0x00333c47, 0x00343e4a, 0x0036404d, 0x00384450, 0x003b4854, 0x00404c58, 0x00404c5a, 0x00404c5b, 0x00444f5e, 0x00445060, 0x00444f60, 0x00444e5f, 0x00444e5f, 0x00444c5c, 0x00404857, 0x003c4251, 0x00363c49, 0x00303643, 0x002c313d, 0x002c303c, 0x002c313c, 0x002c333c, 0x002c323c, 0x002b313b, 0x00282f36, 0x00282c34, 0x00292d35, 0x00292d35, 0x00282b34, 0x00252730, 0x0024242e, 0x00272831, 0x002c2d37, 0x0030313b, 0x002c2f39, 0x002b303c, 0x00353c4b, 0x00414b5c, 0x00495668, 0x004c5a6c, 0x004c5c6f, 0x004c6072, 0x00506477, 0x00536579, 0x0057687c, 0x0057687c, 0x0056687d, 0x0056687f, 0x00566980, 0x00546980, 0x0054677e, 0x0054677c, 0x00526378, 0x004a5a6c, 0x00475565, 0x0044505e, 0x003c4453, 0x00323847, 0x00313543, 0x00313642, 0x00333842, 0x00333843, 0x00333641, 0x002f323d, 0x002b2e39, 0x00282834, 0x00272834, 0x00272834, 0x00282a34, 0x002a2d38, 0x00292e37, 0x002b3039, 0x002f343e, 0x00303540, 0x002f3440, 0x00303742, 0x00343c48, 0x0038404d, 0x003d4553, 0x00414958, 0x00465060, 0x004a5464, 0x00495666, 0x00485464, 0x00455062, 0x00444f60, 0x00444f60, 0x00455061, 0x00444d5f, 0x00404958, 0x00404957, 0x003c4654, 0x003c4553, 0x003b4453, 0x003a4453, 0x00394553, 0x00384452, 0x0035404e, 0x00333e4c, 0x0034404c, 0x0036424e, 0x0036414e, 0x00384350, 0x00384251, 0x00384453, 0x00384653, 0x00364350, 0x0033404e, 0x00384553, 0x00394654, 0x00394655, 0x003c4959, 0x003f4c5c, 0x003d4a5b, 0x003c4859, 0x003b4858, 0x003c4858, 0x00394755, 0x00394654, 0x003b4654, 0x00394452, 0x0036404e, 0x00303948, 0x002e3847, 0x00313d4b, 0x00344250, 0x0030404d, 0x002f404e, 0x00314250, 0x00304250, 0x002d404e, 0x002a3f4c, 0x002c404e, 0x002c4250, 0x002c424f, 0x002b404d, 0x002c3f4c, 0x002c3d4c, 0x00283948, 0x00253744, 0x00253642, 0x0020303a, 0x00192932, 0x00172530, 0x0014242f, 0x0014232e, 0x00172631, 0x001a2936, 0x00192b39, 0x00192c3c, 0x001a2e3c, 0x00182f3c, 0x00182f3c, 0x00172e3b, 0x00162d39, 0x00152c38, 0x00142a36, 0x00132935, 0x00132934, 0x00132936, 0x00122835, 0x00122734, 0x00112634, 0x00102633, 0x000e2631, 0x000e2631, 0x000f2631, 0x000f2631, 0x00102631, 0x00102531, 0x00102430, 0x00102430, 0x000f242f, 0x000f2430, 0x000f2530, 0x000f2531, 0x00102732, 0x00102732, 0x00112732, 0x00112833, 0x00112833, 0x00112833, 0x00112833, 0x00112833, 0x00112632, 0x00102531, 0x00102531, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x00112430, 0x0010232f, 0x000f222e, 0x000f222e, 0x000e212d, 0x000e212d, 0x000f222c, 0x000f222c, 0x000e212c, 0x000d202b, 0x000d202b, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00122c32, 0x00153338, 0x0016363b, 0x00183d41, 0x001b4347, 0x001c4a4d, 0x001f5053, 0x00205558, 0x00245c5f, 0x002c88a0, 0x0032a3c4, 0x002a757e, 0x002a6e70, 0x002b7072, 0x002c7475, 0x003499b3, 0x00359db9, 0x0035a0bc, 0x00349fbb, 0x002c767a, 0x002f8898, 0x00349ebc, 0x0034a6c9, 0x003099b7, 0x002b7d8e, 0x0027666a, 0x00256264, 0x00245f61, 0x00245e60, 0x00245c5f, 0x00235a5c, 0x0022595c, 0x0022595c, 0x0022585b, 0x0022585a, 0x0021585a, 0x00215659, 0x00205558, 0x00205356, 0x00205154, 0x001e4f51, 0x001d4c50, 0x001c484c, 0x001b4448, 0x001a4044, 0x00183d41, 0x0017383c, 0x00153439, 0x00142e34, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0007141a, 0x0008141a, 0x0008141a, 0x0008141a, 0x0008141a, 0x0008141a, 0x0009141a, 0x0009141a, 0x000a141c, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x0009161e, 0x0008161e, 0x0009171f, 0x000a1820, 0x000b1920, 0x000b1a22, 0x000c1b23, 0x000c1c24, 0x000c1d27, 0x000b1c26, 0x000b1c27, 0x000b1c28, 0x000c1d28, 0x000d1f29, 0x000d202b, 0x000f222c, 0x000f222c, 0x0010232d, 0x0010232f, 0x00112430, 0x00112431, 0x00102531, 0x00112632, 0x00122632, 0x00132733, 0x00132834, 0x00132833, 0x00132733, 0x00112632, 0x00112632, 0x00102533, 0x00102534, 0x00102434, 0x00102434, 0x00102432, 0x00102430, 0x0010232e, 0x000f232d, 0x000e222c, 0x000e212c, 0x000d212c, 0x000d202b, 0x000d202b, 0x000d202b, 0x000d202b, 0x000d202b, 0x000e202c, 0x000f202c, 0x000f212c, 0x0010212c, 0x0010222d, 0x000f222c, 0x000f222c, 0x000f222c, 0x0010232d, 0x0010232f, 0x00112431, 0x00112432, 0x00122433, 0x00122433, 0x00142734, 0x00142834, 0x00162b38, 0x001a303c, 0x00233946, 0x0029404c, 0x00293f4c, 0x002d414f, 0x002d3e4c, 0x00253544, 0x0022303f, 0x00243240, 0x00293843, 0x002c3944, 0x002c3945, 0x002f3c49, 0x002d3b48, 0x00303e4b, 0x0034414f, 0x00384350, 0x00384451, 0x00374350, 0x00303c48, 0x00303945, 0x00343e48, 0x00313c46, 0x00303944, 0x00333c47, 0x00313c46, 0x00303944, 0x00303844, 0x00303843, 0x00303841, 0x00303942, 0x00333b46, 0x00343e4a, 0x0037404f, 0x00384451, 0x003a4754, 0x003d4957, 0x00404b59, 0x00404b59, 0x00434e5c, 0x0044505f, 0x00444f5e, 0x00444d5d, 0x00414b5b, 0x003f4755, 0x003c4450, 0x00363c4a, 0x00303642, 0x002b303c, 0x002a2e39, 0x002a2e38, 0x002b2f38, 0x002b2f39, 0x002a2f39, 0x00292e38, 0x00282c34, 0x00272b32, 0x00282c33, 0x00292c33, 0x00282930, 0x0024242b, 0x00212129, 0x00212029, 0x00222129, 0x0024242d, 0x0024252e, 0x00262833, 0x00292c3a, 0x00323848, 0x00414c5d, 0x00485568, 0x0049596c, 0x004b5d70, 0x004c6073, 0x00506074, 0x00526276, 0x00546478, 0x0057667c, 0x0058687f, 0x0056687f, 0x0054667c, 0x0052647b, 0x00516379, 0x004c5b70, 0x00475568, 0x00434f60, 0x00363f4d, 0x002b3140, 0x002b303c, 0x002c303b, 0x002d313b, 0x002d303a, 0x002a2e37, 0x00282a34, 0x00242630, 0x00262630, 0x0027252f, 0x00282830, 0x00282831, 0x00282831, 0x00282a34, 0x00282c35, 0x002a2f38, 0x002d323c, 0x002e333c, 0x002e333d, 0x0030343f, 0x00323844, 0x00363d49, 0x003c4350, 0x003f4854, 0x00434c5b, 0x00475160, 0x00485464, 0x004a5566, 0x004a5566, 0x00465163, 0x00455062, 0x00444f60, 0x00424c5d, 0x003f4858, 0x003f4857, 0x003d4755, 0x003c4654, 0x003c4553, 0x00394452, 0x00374250, 0x0035404f, 0x00333e4c, 0x00323d4b, 0x00323d4a, 0x00343f4b, 0x00343e4b, 0x00343f4c, 0x00364050, 0x00384351, 0x00364350, 0x0034414f, 0x0032404c, 0x0034414f, 0x00384553, 0x00384553, 0x003c4a58, 0x003f4c5c, 0x003d4959, 0x003b4656, 0x00394454, 0x00394554, 0x00384554, 0x00384655, 0x003a4654, 0x003a4452, 0x0037404f, 0x00313b4b, 0x00313c4c, 0x00303c4b, 0x00324050, 0x00324150, 0x00334351, 0x00324351, 0x00304250, 0x002d414f, 0x002b404c, 0x002c404d, 0x002c4250, 0x002b414f, 0x002c404e, 0x002c404d, 0x002a3d4b, 0x00293c4a, 0x00283a46, 0x00243641, 0x001c2d38, 0x00182831, 0x00182530, 0x0015242f, 0x0014242f, 0x00172631, 0x001a2935, 0x001a2b39, 0x001a2c3b, 0x001b2e3c, 0x001a2e3c, 0x00192f3c, 0x00182e3c, 0x00182e3b, 0x00172d38, 0x00152c38, 0x00142b36, 0x00142a37, 0x00132936, 0x00132936, 0x00132835, 0x00122734, 0x00112734, 0x000f2732, 0x000f2732, 0x00102732, 0x00102732, 0x00102732, 0x000e2530, 0x000e2430, 0x00102530, 0x00102531, 0x00112531, 0x00102531, 0x00112632, 0x00112833, 0x00112833, 0x00112834, 0x00102934, 0x00112934, 0x00112834, 0x00122834, 0x00122834, 0x00122733, 0x00112632, 0x00112632, 0x00122632, 0x00122531, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x00112430, 0x0010232f, 0x000f222e, 0x000f222e, 0x000e212d, 0x000e212d, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00132c32, 0x00143036, 0x0016363b, 0x00183c40, 0x001a4245, 0x001c484c, 0x001e4f51, 0x00205457, 0x00235a5c, 0x00266c76, 0x0032a2c5, 0x003095b0, 0x002a7073, 0x002b7072, 0x002c7475, 0x003499b3, 0x00359db9, 0x0036a0bc, 0x00349fbb, 0x002c7476, 0x002c7274, 0x002c7276, 0x002d8394, 0x00329cba, 0x0033a5c8, 0x003098b8, 0x00297a8b, 0x00256368, 0x00245f61, 0x00245d60, 0x00235c5f, 0x00235b5e, 0x00225a5c, 0x00225a5c, 0x0022595c, 0x0022595c, 0x0022585b, 0x0021575a, 0x00205558, 0x00205457, 0x001f5054, 0x001e4e51, 0x001c4a4d, 0x001b4649, 0x001a4245, 0x00183d41, 0x00183a3e, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0007141a, 0x0008141a, 0x0008141a, 0x0008141a, 0x0008141a, 0x0008141a, 0x0009141a, 0x0009141a, 0x0009141c, 0x000a141d, 0x000b151e, 0x000b151e, 0x000b151e, 0x0009161e, 0x0009171f, 0x0009171f, 0x000a1820, 0x000b1920, 0x000c1b23, 0x000c1c23, 0x000c1c25, 0x000c1e28, 0x000c1e27, 0x000c1d28, 0x000c1d29, 0x000c1e29, 0x000e202a, 0x000e212c, 0x000f222c, 0x0010232d, 0x0010242e, 0x00112430, 0x00122431, 0x00122633, 0x00122734, 0x00132835, 0x00132936, 0x00142935, 0x00142a35, 0x00142a36, 0x00142936, 0x00142834, 0x00132834, 0x00122835, 0x00112737, 0x00102636, 0x00102634, 0x00102533, 0x00102534, 0x00102432, 0x00102430, 0x0010232e, 0x000f232c, 0x000f222c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000f212c, 0x000f222c, 0x0010222c, 0x0011222d, 0x0011232d, 0x0010232d, 0x0010242d, 0x0010242d, 0x0010242d, 0x00102430, 0x00122432, 0x00122433, 0x00122433, 0x00122433, 0x00142734, 0x00142834, 0x00162c37, 0x001a303c, 0x00223845, 0x00283f4c, 0x002c404f, 0x002d4251, 0x002c3e4e, 0x00273848, 0x00243241, 0x00263442, 0x00293844, 0x002c3b46, 0x002f3c48, 0x00303e4b, 0x002e3b48, 0x002d3a48, 0x00303e4b, 0x0034414f, 0x0035424f, 0x00333f4c, 0x002e3a46, 0x00303946, 0x00333d48, 0x00303a44, 0x002e3843, 0x00303a44, 0x00303944, 0x002e3842, 0x002e3641, 0x002e3640, 0x002d363f, 0x002f3741, 0x00323a46, 0x00353f4d, 0x00384250, 0x00394452, 0x003b4855, 0x003e4a58, 0x00404c59, 0x00404b59, 0x00424e5c, 0x0044505e, 0x00444f5e, 0x00414c5b, 0x003f4757, 0x003c4150, 0x00383e4b, 0x00323644, 0x002c2f3b, 0x00292c38, 0x00282b36, 0x00282b35, 0x00282b35, 0x00282c36, 0x00282c36, 0x00282c35, 0x00262930, 0x0025282f, 0x0025282f, 0x0025282f, 0x0024252c, 0x00222328, 0x00202027, 0x00202027, 0x001f1f27, 0x001e1e26, 0x001d1f25, 0x00202028, 0x0023242f, 0x00282c39, 0x00303949, 0x00404b5c, 0x00485566, 0x004a5a6c, 0x004c5c6f, 0x004e5c70, 0x004f5d72, 0x00505e72, 0x00526074, 0x00546378, 0x00526377, 0x00506074, 0x004e5e72, 0x004b586d, 0x00465368, 0x00414c5e, 0x00313b4a, 0x0029303e, 0x00272a38, 0x00272a34, 0x00262931, 0x00252830, 0x0024272e, 0x0022252c, 0x0020242a, 0x00212229, 0x00222229, 0x0024242c, 0x0027262f, 0x0027252f, 0x00272730, 0x00282932, 0x00282c35, 0x002a2f38, 0x002c303a, 0x002c303b, 0x002d313c, 0x002d323c, 0x002f343f, 0x00313843, 0x00383f4a, 0x003c4450, 0x00404854, 0x00444c5c, 0x00485060, 0x00495464, 0x004b5668, 0x00485364, 0x00444f60, 0x00414c5d, 0x00404a5b, 0x003f4858, 0x003e4856, 0x003d4755, 0x003d4755, 0x003c4554, 0x00394452, 0x00364250, 0x0034404d, 0x00323c4b, 0x00313c4a, 0x00313b48, 0x00313b47, 0x00323c48, 0x00343e4b, 0x00343e4d, 0x00374250, 0x0035404e, 0x00333f4c, 0x0034404e, 0x00303c4b, 0x00333f4c, 0x0035424f, 0x003a4654, 0x003c4858, 0x003a4555, 0x00384353, 0x00374251, 0x00374352, 0x00374453, 0x00374453, 0x00384453, 0x00384350, 0x0034404d, 0x00303b49, 0x00323c4c, 0x002e3a4a, 0x002e3c4b, 0x0031404f, 0x00344452, 0x00324452, 0x00314351, 0x00304451, 0x002c404e, 0x002b3f4e, 0x002c4050, 0x002b414f, 0x002c4250, 0x002c4250, 0x002a3e4c, 0x002a3d4b, 0x00273a46, 0x0020313d, 0x001a2b35, 0x00172730, 0x0016242f, 0x0015242f, 0x0014242f, 0x00162530, 0x001a2934, 0x001a2c38, 0x001a2c3a, 0x001b2e3c, 0x001a2e3c, 0x00192e3c, 0x00192e3c, 0x00182f3c, 0x00182f3a, 0x00172d38, 0x00142c37, 0x00142b37, 0x00142a37, 0x00132936, 0x00142835, 0x00142835, 0x00132734, 0x00102833, 0x00102833, 0x00112833, 0x00112833, 0x00102732, 0x000f2631, 0x000e2530, 0x00102531, 0x00112632, 0x00122632, 0x00112632, 0x00122733, 0x00122834, 0x00122834, 0x00122834, 0x00112a34, 0x00112a34, 0x00112934, 0x00122834, 0x00122834, 0x00122733, 0x00122733, 0x00112632, 0x00132632, 0x00132632, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x00112430, 0x0010232f, 0x000f222e, 0x000f222e, 0x000e212d, 0x000e212d, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00143036, 0x00153439, 0x00183a3e, 0x00194044, 0x001b4649, 0x001d4c50, 0x00205356, 0x0022585b, 0x00245f61, 0x002c859c, 0x0033a6c9, 0x003090a7, 0x002b7175, 0x002c7374, 0x003499b3, 0x00359db9, 0x0036a0bc, 0x00349fbb, 0x002c7476, 0x002c7274, 0x002b7071, 0x002a6d6f, 0x00296d71, 0x002c7e8f, 0x003099b8, 0x0031a3c8, 0x002f99ba, 0x002d92b1, 0x002c92b0, 0x002c91b0, 0x002c91b0, 0x002c91b0, 0x002b90b0, 0x002b90b0, 0x002b90b0, 0x002b90b0, 0x002a90b0, 0x002a90b0, 0x00298fb0, 0x00288eaf, 0x002787a5, 0x001d4c50, 0x001c484c, 0x001a4347, 0x00183f43, 0x00173a3e, 0x0015363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0008141b, 0x0008141b, 0x0008141b, 0x0008141a, 0x0008141a, 0x0008141a, 0x0009141a, 0x0009141a, 0x0009141c, 0x000a141d, 0x000b151e, 0x000b151e, 0x000b151e, 0x000a161e, 0x000a171f, 0x000a1820, 0x000b1920, 0x000c1a21, 0x000c1b23, 0x000d1c23, 0x000d1c25, 0x000c1d28, 0x000c1e28, 0x000c1e28, 0x000c1f2b, 0x000d202c, 0x000e212c, 0x000f222d, 0x00102430, 0x00102430, 0x00112431, 0x00112532, 0x00122633, 0x00132734, 0x00122837, 0x00132a39, 0x00142c3a, 0x00142c39, 0x00142c39, 0x00142c39, 0x00142c39, 0x00142b38, 0x00142b38, 0x00132b38, 0x00122937, 0x00112836, 0x00122835, 0x00122734, 0x00112634, 0x00112633, 0x00112633, 0x00112430, 0x00102430, 0x0010242f, 0x000e222d, 0x000e212d, 0x000f222e, 0x000f222e, 0x000f222e, 0x000f222d, 0x000f232e, 0x0010232e, 0x0011242e, 0x0011242e, 0x0011242f, 0x00102430, 0x00102530, 0x00102530, 0x00102531, 0x00102532, 0x00112532, 0x00122533, 0x00132633, 0x00142834, 0x00162a36, 0x00182d39, 0x001a303d, 0x00213844, 0x00283f4e, 0x002c4150, 0x002d4350, 0x002c3f4e, 0x00283848, 0x00243443, 0x00243542, 0x00283744, 0x002b3a46, 0x002d3c48, 0x002f3d49, 0x002b3946, 0x00293844, 0x002c3a47, 0x00313f4b, 0x0035424f, 0x00303d49, 0x002e3a46, 0x002f3946, 0x00303b45, 0x00303a44, 0x00303c46, 0x00313b46, 0x00303944, 0x002c3540, 0x0028303b, 0x0029323c, 0x002c343d, 0x002f3642, 0x00323a47, 0x0036404c, 0x0038424f, 0x00394452, 0x003b4855, 0x003d4a58, 0x003e4b58, 0x003f4b59, 0x00404c5a, 0x00434e5b, 0x00434d5a, 0x00404957, 0x003c4351, 0x00383c4a, 0x00343844, 0x002c303c, 0x00282b34, 0x00272a34, 0x00282a34, 0x00282a34, 0x00272a34, 0x00262a34, 0x00262a34, 0x00262831, 0x0023262d, 0x0021242c, 0x0023262c, 0x0022252c, 0x0020232a, 0x00212329, 0x001d1f25, 0x001c1d24, 0x001c1d24, 0x001a1c22, 0x00191c22, 0x001b1d24, 0x001f2029, 0x00222530, 0x00252c38, 0x002c3542, 0x003b4453, 0x00465261, 0x004a5768, 0x00495769, 0x004a586b, 0x004a586c, 0x004d5c70, 0x004f5e70, 0x00505d6f, 0x004f5c6d, 0x004b5768, 0x00465061, 0x003e4758, 0x00303948, 0x00272d3b, 0x00272b38, 0x00242833, 0x0022242d, 0x001f2229, 0x001d2028, 0x001c1e25, 0x001d1f26, 0x00202028, 0x00202129, 0x00202128, 0x0023232a, 0x0024242d, 0x00262630, 0x00252730, 0x00262930, 0x00282c34, 0x00292d37, 0x002b2e38, 0x002c2f3a, 0x002c303a, 0x002c303a, 0x002c313b, 0x002c333c, 0x00323841, 0x00383e48, 0x003c424e, 0x00414956, 0x00444d5c, 0x00485160, 0x00485262, 0x00455060, 0x00434e5e, 0x00414c5c, 0x00404b5a, 0x003c4755, 0x003c4754, 0x003b4553, 0x003b4452, 0x00394451, 0x0037424f, 0x0034404d, 0x00333e4c, 0x00323d4a, 0x00323c49, 0x00313b47, 0x00303944, 0x00303944, 0x00313b46, 0x00323c48, 0x00353f4c, 0x00323c48, 0x002f3a46, 0x00323d49, 0x002f3946, 0x002d3844, 0x00323d49, 0x00384350, 0x00394452, 0x00384351, 0x0034404f, 0x00343f4e, 0x0034404f, 0x00354250, 0x00354250, 0x00354250, 0x0034414e, 0x00313e4b, 0x002d3847, 0x00303b49, 0x002d3a48, 0x002b3947, 0x00303e4c, 0x0030414f, 0x00304251, 0x00304252, 0x00314454, 0x002d4150, 0x002a3f4e, 0x002a404f, 0x002c4250, 0x002d4350, 0x002e4350, 0x002c404d, 0x002c3e4c, 0x00273846, 0x001e2f3b, 0x00192834, 0x00182732, 0x00172631, 0x00162531, 0x00152531, 0x00172733, 0x001a2a37, 0x001a2c39, 0x001a2d3b, 0x001a2d3b, 0x00182d3b, 0x00182c3b, 0x00182d3b, 0x00182e3c, 0x00182f3c, 0x00182e3b, 0x00162c39, 0x00142b38, 0x00142a37, 0x00142a37, 0x00142836, 0x00142836, 0x00132834, 0x00112834, 0x00112834, 0x00112833, 0x00112833, 0x00112833, 0x00102732, 0x00102732, 0x00112733, 0x00112733, 0x00122733, 0x00122834, 0x00122834, 0x00122834, 0x00122834, 0x00122834, 0x00122935, 0x00122935, 0x00122834, 0x00122834, 0x00122834, 0x00142834, 0x00142834, 0x00132732, 0x00132632, 0x00132631, 0x00122531, 0x00112531, 0x00102430, 0x00112430, 0x00102430, 0x0010232f, 0x0010232f, 0x000f222e, 0x000e212d, 0x000e212d, 0x000f212c, 0x000f212c, 0x000f212c, 0x000f212c, 0x000f202c, 0x000f202b, 0x000f202b, 0x0010202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013282e, 0x00112a30, 0x00142e34, 0x00153439, 0x00183a3e, 0x00183f43, 0x001c4649, 0x001d4b4e, 0x001f5154, 0x0021585a, 0x00245d60, 0x00266469, 0x002f90aa, 0x0035a8ca, 0x00339ab6, 0x002e8390, 0x00349ab4, 0x00359db9, 0x0035a0bc, 0x00349fbb, 0x002c7476, 0x002c7274, 0x002b7071, 0x002a6e70, 0x00296b6d, 0x0028686b, 0x0027686c, 0x00297c8c, 0x002e94b3, 0x002f99bb, 0x002e99ba, 0x002d98ba, 0x002d98ba, 0x002d98ba, 0x002c98ba, 0x002c98ba, 0x002c98ba, 0x002c98ba, 0x002c98ba, 0x002b98ba, 0x002b96b9, 0x002c9dc4, 0x002b9ac0, 0x001e4f53, 0x001c4a4d, 0x001b4649, 0x001a4044, 0x00183c40, 0x0017383c, 0x00143338, 0x00142e34, 0x00102a30, 0x0012282e, 0x00102229, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0008141a, 0x0008141a, 0x0008141a, 0x0009141a, 0x0009141a, 0x0009141a, 0x0009141a, 0x0009141a, 0x0009141c, 0x000a141d, 0x000a141d, 0x000b151e, 0x000b161e, 0x000b171f, 0x000c1820, 0x000b1820, 0x000b1920, 0x000c1a22, 0x000d1b23, 0x000d1b23, 0x000d1c25, 0x000c1d27, 0x000c1e28, 0x000c1f2a, 0x000d202c, 0x000e212d, 0x000f222e, 0x000f2430, 0x00102432, 0x00102433, 0x00102533, 0x00112634, 0x00122734, 0x00132835, 0x00132937, 0x00142b3a, 0x00142c3b, 0x00132c3b, 0x00132c3b, 0x00142c3b, 0x00142c3b, 0x00142c3b, 0x00142c3b, 0x00132c3a, 0x00122b36, 0x00122934, 0x00132834, 0x00132834, 0x00132733, 0x00132733, 0x00132733, 0x00112632, 0x00102531, 0x00102430, 0x000f232f, 0x000e222e, 0x000f232e, 0x000f232e, 0x000f232f, 0x000f242f, 0x00102430, 0x00102430, 0x00112430, 0x00122430, 0x00112430, 0x00102632, 0x00102732, 0x00112733, 0x00102632, 0x00102631, 0x00102632, 0x00122632, 0x00142834, 0x00152a38, 0x00182e3b, 0x0018303c, 0x0019303c, 0x001f3543, 0x00283e4d, 0x002b4150, 0x002c4350, 0x002b3f4c, 0x00273845, 0x00243441, 0x00233440, 0x00253643, 0x00293a46, 0x002c3b48, 0x002c3b49, 0x00283744, 0x00283844, 0x00263540, 0x002d3b47, 0x0033404c, 0x00303e49, 0x00303c48, 0x002d3844, 0x002e3844, 0x002f3944, 0x00323c47, 0x00323c46, 0x002e3641, 0x00273039, 0x00242c35, 0x00242d36, 0x002a323c, 0x002f3742, 0x00343c48, 0x0037404c, 0x0038424e, 0x00384450, 0x00394653, 0x003a4854, 0x003d4856, 0x00404a58, 0x00414c58, 0x00414b58, 0x00404855, 0x003d4552, 0x00383e4c, 0x00333744, 0x002f323c, 0x00282c34, 0x0024282f, 0x0024262f, 0x00242730, 0x00242730, 0x0024262e, 0x0023262d, 0x0023262d, 0x0021252c, 0x001f242a, 0x001d2128, 0x0020242c, 0x0020222c, 0x001e212a, 0x001c2026, 0x00181b20, 0x00181b20, 0x00191c21, 0x00191c22, 0x00181c23, 0x00191d24, 0x001a1e25, 0x001d2229, 0x0020242d, 0x00242834, 0x00292f3b, 0x00343947, 0x003e4756, 0x00434d5e, 0x00455062, 0x00485264, 0x00485465, 0x00495464, 0x00495462, 0x0047505f, 0x003e4654, 0x00373d4c, 0x002b313f, 0x00232836, 0x00222732, 0x00212630, 0x001f222c, 0x001c2028, 0x001a1d24, 0x00181b22, 0x00181921, 0x00191a23, 0x001d1e28, 0x00202029, 0x001e2027, 0x001e2028, 0x0020242c, 0x0024262f, 0x0024272f, 0x0024272f, 0x00252831, 0x00262934, 0x00282b35, 0x00292c37, 0x002c2f38, 0x002c3038, 0x002b3038, 0x002b3038, 0x002c323a, 0x00323740, 0x00373d47, 0x003c444e, 0x003f4753, 0x00444e5b, 0x00444f5d, 0x00404d5b, 0x00404c5b, 0x00404c5a, 0x003f4b58, 0x003b4653, 0x00384450, 0x00384450, 0x00394350, 0x0036424e, 0x0034404c, 0x00333e4a, 0x00323d49, 0x00313c48, 0x00313c48, 0x00303a45, 0x002c3740, 0x002c3740, 0x002e3841, 0x002f3843, 0x00303b45, 0x002f3843, 0x002c3540, 0x002f3843, 0x002e3843, 0x002b3540, 0x002d3742, 0x00353f4b, 0x0035414e, 0x0034404c, 0x00303c48, 0x002f3b47, 0x00303c49, 0x0032404c, 0x0032404d, 0x0031404c, 0x0031404e, 0x0032404d, 0x002f3c48, 0x002c3947, 0x002c3947, 0x002b3947, 0x002f3e4b, 0x002d3f4c, 0x002c3f4e, 0x002c404f, 0x002e4352, 0x002e4352, 0x002c4152, 0x002b4152, 0x002c4352, 0x002e4451, 0x002d4450, 0x002c4250, 0x002c404d, 0x00273846, 0x001e2e3c, 0x00192836, 0x00182834, 0x00182734, 0x00162634, 0x00162735, 0x00182a38, 0x001b2c3a, 0x001b2d3b, 0x001b2e3c, 0x001a2c3b, 0x00182b39, 0x00182c39, 0x00182c3a, 0x00182d3b, 0x00182e3b, 0x00182e3c, 0x00172d3b, 0x00142b38, 0x00142a37, 0x00142937, 0x00142836, 0x00142836, 0x00142835, 0x00132734, 0x00132734, 0x00122834, 0x00122834, 0x00122834, 0x00122834, 0x00112833, 0x00122834, 0x00122834, 0x00122834, 0x00122835, 0x00122835, 0x00122835, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00122835, 0x00122835, 0x00132835, 0x00142834, 0x00142834, 0x00142732, 0x00142731, 0x00142731, 0x00122631, 0x00102531, 0x00102430, 0x00102430, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222e, 0x000f222e, 0x000f222e, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f212c, 0x0010212c, 0x0010212c, 0x0010212c, 0x0010202c, 0x000e202c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x00102229, 0x0012242c, 0x00102a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001b4448, 0x001c4a4d, 0x001e5053, 0x00215659, 0x00235c5e, 0x00256163, 0x0027686c, 0x002e889c, 0x0034a3c3, 0x0036a8c9, 0x0036a8ca, 0x00349db8, 0x0035a0bc, 0x00359fbc, 0x002c7578, 0x002c7274, 0x002b7071, 0x002a6d6f, 0x00296b6d, 0x0028686b, 0x00276668, 0x00266466, 0x00256366, 0x00256267, 0x00246166, 0x00246064, 0x00246064, 0x00245f64, 0x00245e63, 0x00235e63, 0x00235e63, 0x00235d62, 0x00225c61, 0x00225c60, 0x00225a60, 0x002889a7, 0x002b9ac0, 0x001e5054, 0x001d4b4e, 0x001c474b, 0x001a4245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0008141a, 0x0008141a, 0x0008141a, 0x0009141a, 0x0009141a, 0x0009141a, 0x0009141a, 0x0009141a, 0x000a141c, 0x000a141d, 0x000b151e, 0x000b151e, 0x000b161e, 0x000b171f, 0x000c1820, 0x000c1820, 0x000c1a21, 0x000d1b23, 0x000d1b23, 0x000e1b23, 0x000d1c25, 0x000c1d27, 0x000c1e28, 0x000d1f2a, 0x000e212c, 0x000f222e, 0x000f232f, 0x00102430, 0x00102432, 0x00102533, 0x00102533, 0x00112634, 0x00132734, 0x00132836, 0x00132a38, 0x00142c3a, 0x00142c3b, 0x00142d3c, 0x00142d3c, 0x00162e3c, 0x00162e3c, 0x00152e3c, 0x00152e3c, 0x00142c3b, 0x00132c37, 0x00122a34, 0x00132934, 0x00142834, 0x00142834, 0x00142834, 0x00132834, 0x00112733, 0x00112632, 0x00102531, 0x00102430, 0x000f242f, 0x000f2430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00122431, 0x00122431, 0x00122532, 0x00122734, 0x00122834, 0x00132835, 0x00112833, 0x00102833, 0x00102733, 0x00132733, 0x00142935, 0x00182d3b, 0x0019303d, 0x0019303c, 0x00182e3b, 0x001c323f, 0x00253c49, 0x002a414f, 0x002c4350, 0x002b3f4c, 0x00273846, 0x00243542, 0x00243542, 0x00283845, 0x00283a46, 0x002b3a48, 0x002a3a48, 0x00283745, 0x00283742, 0x00273641, 0x002b3844, 0x0032404b, 0x0033404c, 0x0034404c, 0x002f3945, 0x002d3842, 0x00303944, 0x00313a45, 0x002f3741, 0x0028303b, 0x00232b34, 0x00232b34, 0x00252e36, 0x002b343d, 0x002f3843, 0x00333c46, 0x00353f49, 0x0036414c, 0x00384450, 0x003b4753, 0x003c4854, 0x003d4856, 0x00404957, 0x00404957, 0x003f4754, 0x003c4450, 0x00383e4b, 0x00323744, 0x002d313c, 0x00282a34, 0x0022252e, 0x0021242b, 0x0020232a, 0x001e2129, 0x001f2129, 0x001e2128, 0x001f2228, 0x001d2027, 0x001b1f25, 0x001a1e24, 0x001a1f24, 0x001c2027, 0x001c1f28, 0x001a1d26, 0x00171a1f, 0x00191c20, 0x001c1f24, 0x001d2025, 0x001c2025, 0x001a1f25, 0x001b2026, 0x001c1f26, 0x001c2026, 0x001d2026, 0x001e2129, 0x0020242d, 0x00222630, 0x00252b38, 0x002b303f, 0x00303645, 0x00343c4a, 0x00343c4a, 0x00313946, 0x002d343f, 0x002a313c, 0x002a303a, 0x00292c38, 0x00242832, 0x0020242d, 0x001e222a, 0x0020232a, 0x001a1d24, 0x00191c23, 0x00181c22, 0x00181921, 0x00171820, 0x00181921, 0x001c1d26, 0x001e1f28, 0x001e2027, 0x001c1f26, 0x001c2028, 0x001f222a, 0x0020232b, 0x0020222c, 0x0020232d, 0x0021242f, 0x00232530, 0x00242630, 0x00272a33, 0x00282c34, 0x00282c34, 0x00282c34, 0x00282e36, 0x002d323b, 0x00343a43, 0x00384048, 0x003c444f, 0x00404a57, 0x00444f5c, 0x00424f5c, 0x00414e5c, 0x00424d5b, 0x00414c59, 0x003d4955, 0x00394551, 0x00384450, 0x0038424e, 0x0035414d, 0x00343f4b, 0x00313c48, 0x002f3b47, 0x002e3a46, 0x00303946, 0x002e3843, 0x002b343d, 0x0029343c, 0x002b343d, 0x002a343e, 0x002c3640, 0x002c3640, 0x002a343f, 0x002c3741, 0x002f3843, 0x002c3640, 0x0029333d, 0x002e3843, 0x00333e48, 0x00323d48, 0x002d3945, 0x002c3844, 0x002d3946, 0x002e3948, 0x00303c4a, 0x00303e4c, 0x0031404d, 0x0033404e, 0x00313f4c, 0x002c3a48, 0x00293844, 0x00283845, 0x002d3c49, 0x002c3e4b, 0x002d3f4e, 0x002c3e4e, 0x002c3f4e, 0x002f4453, 0x00314556, 0x00304455, 0x002f4654, 0x002f4553, 0x002c4450, 0x002c414f, 0x002b3f4c, 0x00253744, 0x001f2f3c, 0x001a2937, 0x00192834, 0x00182835, 0x00172836, 0x00182938, 0x001b2c3b, 0x001c2e3c, 0x001c303d, 0x001c303e, 0x001b2e3c, 0x00192c3a, 0x00182c3a, 0x00182c3a, 0x00182c3b, 0x00182e3b, 0x00182e3c, 0x00182e3b, 0x00142b38, 0x00142a37, 0x00142937, 0x00142836, 0x00142836, 0x00142836, 0x00142835, 0x00142835, 0x00132834, 0x00122834, 0x00122834, 0x00122834, 0x00122834, 0x00122834, 0x00122834, 0x00122834, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00142834, 0x00142834, 0x00142732, 0x00142731, 0x00142731, 0x00122631, 0x00102531, 0x00102430, 0x00102430, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222e, 0x000f222e, 0x000f222e, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x000f222c, 0x0010222c, 0x0010222c, 0x0010212c, 0x0010202c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x00102229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00153338, 0x0016363b, 0x00183d41, 0x001a4347, 0x001c484c, 0x001e4f51, 0x00205457, 0x00235a5c, 0x00246062, 0x00266467, 0x0028686b, 0x002b747b, 0x0030899c, 0x00349bb6, 0x003397b0, 0x00349eba, 0x0037a8c9, 0x00349fbc, 0x00308ea3, 0x002c7982, 0x002a6f71, 0x00296b6d, 0x0028686a, 0x00276668, 0x00266466, 0x00266264, 0x00246062, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0022585b, 0x002888a6, 0x002b9bc0, 0x001e5054, 0x001d4c50, 0x001c474b, 0x001a4347, 0x00183d41, 0x00183a3e, 0x00153439, 0x00142e34, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0009141b, 0x0009141b, 0x0009141b, 0x000a141b, 0x000a141b, 0x000a141b, 0x000a141b, 0x000a141b, 0x000a141c, 0x000b151c, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c1720, 0x000d1720, 0x000c1820, 0x000d1921, 0x000e1a23, 0x000e1a23, 0x000f1b24, 0x000f1c24, 0x000e1c26, 0x000e1e27, 0x000f1f29, 0x000f212c, 0x0010232d, 0x0010242e, 0x00102430, 0x000f2432, 0x000f2533, 0x00102634, 0x00112834, 0x00122835, 0x00122a36, 0x00132b38, 0x00142c39, 0x00142d3b, 0x00142e3c, 0x00152e3c, 0x00162e3c, 0x00172e3c, 0x00142e3c, 0x00142e3c, 0x00142d3b, 0x00122c38, 0x00112b35, 0x00122a34, 0x00132934, 0x00122834, 0x00132934, 0x00132834, 0x00112833, 0x00112733, 0x00102732, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00122531, 0x00132632, 0x00132632, 0x00132834, 0x00122834, 0x00122836, 0x00122834, 0x00122834, 0x00122834, 0x00142834, 0x00162a37, 0x001a303c, 0x001b313f, 0x0019303d, 0x00172d3a, 0x001a303e, 0x00253c49, 0x002b4250, 0x002c4250, 0x002b3f4c, 0x00283b48, 0x00253846, 0x00283947, 0x002c3e4a, 0x00293a47, 0x002b3a48, 0x002a3948, 0x00293846, 0x00283843, 0x00293844, 0x002d3c47, 0x0034404c, 0x0034414d, 0x0038434e, 0x00303b45, 0x002e3843, 0x00303a45, 0x00303944, 0x0028303c, 0x00242c37, 0x00222a34, 0x00252d37, 0x0028313a, 0x002d3640, 0x00303944, 0x00313c46, 0x0035404a, 0x0036424c, 0x00394450, 0x003c4854, 0x003c4854, 0x003d4854, 0x003d4854, 0x003d4754, 0x0038404d, 0x00343c48, 0x002f3542, 0x00292e3b, 0x00252934, 0x0023252e, 0x001f2128, 0x001e2127, 0x001e2128, 0x001c1f27, 0x001a1d24, 0x001a1d23, 0x001b1e23, 0x00191c21, 0x0015191e, 0x00171c20, 0x00181d22, 0x00181d23, 0x00181b23, 0x00161920, 0x00171a1f, 0x001c2023, 0x00202328, 0x001f2227, 0x001a1d22, 0x00181c21, 0x00181c20, 0x00191c21, 0x001a1d22, 0x001b1e21, 0x001a1d22, 0x001c2026, 0x001d2128, 0x001e2129, 0x001c2028, 0x001b1d28, 0x001c1e28, 0x001c1f28, 0x001d222a, 0x001f242c, 0x001f242b, 0x0020242c, 0x001f222a, 0x001c1e27, 0x001c2028, 0x001e2128, 0x001c1f26, 0x00161920, 0x00181b21, 0x00191c23, 0x001a1c23, 0x00181920, 0x0016181f, 0x0014161f, 0x00171820, 0x001c1f26, 0x001c2027, 0x001c1f27, 0x001c1f28, 0x001c1f28, 0x001d2029, 0x001d202a, 0x001e212b, 0x001d202a, 0x001e212b, 0x0021242c, 0x0024262f, 0x00242830, 0x00232830, 0x00252a32, 0x00282d35, 0x002f343c, 0x00343b44, 0x0039424e, 0x003f4854, 0x00404b59, 0x00404d5a, 0x00404c5a, 0x00404c59, 0x00404c58, 0x003c4854, 0x00384450, 0x0036424e, 0x0037404d, 0x0034404c, 0x00333e4b, 0x00303c48, 0x002c3844, 0x002b3642, 0x002c3541, 0x002c353f, 0x0028333c, 0x0028313a, 0x0029333c, 0x002a333d, 0x002b343f, 0x002b343f, 0x002a343e, 0x002a343f, 0x002d3741, 0x002e3842, 0x0029343e, 0x0028323c, 0x00303b45, 0x00323d48, 0x002e3a45, 0x002d3844, 0x002c3844, 0x002a3442, 0x002b3644, 0x002c3a48, 0x00303f4c, 0x0033404e, 0x0033404e, 0x002f3c4a, 0x002b3a47, 0x00283844, 0x002b3c48, 0x002d3d4c, 0x002f3f4f, 0x002f3f50, 0x002b3d4d, 0x002c4050, 0x00334858, 0x00324858, 0x00314856, 0x002e4552, 0x0029404d, 0x00283d4a, 0x00273b48, 0x00243544, 0x0020303d, 0x001c2b38, 0x00182834, 0x00182835, 0x00182837, 0x00192b39, 0x001a2d3c, 0x001c2f3d, 0x001d3040, 0x001e3140, 0x001d303f, 0x001b2e3c, 0x00192d3b, 0x00192c3c, 0x001a2d3c, 0x00192e3c, 0x00182f3c, 0x00182f3c, 0x00152c38, 0x00132936, 0x00142836, 0x00142836, 0x00142836, 0x00142836, 0x00142836, 0x00142835, 0x00132935, 0x00132935, 0x00132935, 0x00132935, 0x00132935, 0x00132935, 0x00132935, 0x00132936, 0x00132a37, 0x00132a37, 0x00132a37, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132935, 0x00122833, 0x00112833, 0x00132833, 0x00142833, 0x00142833, 0x00122733, 0x00102531, 0x00102430, 0x00102430, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222e, 0x000f222e, 0x000f222e, 0x000f222d, 0x0010212d, 0x0010212d, 0x0010212d, 0x0010222e, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x000f212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00153338, 0x0016363b, 0x00183c40, 0x001a4245, 0x001c484c, 0x001e4f51, 0x00205457, 0x0022595c, 0x00245e60, 0x00256364, 0x00286769, 0x00296b6d, 0x002a6d6f, 0x002b7073, 0x002b7375, 0x002d7b83, 0x00308c9f, 0x00349cb7, 0x0035a5c6, 0x0036a6c8, 0x003298b4, 0x00286b6e, 0x0028686a, 0x00276568, 0x00266466, 0x00256163, 0x00246062, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022585b, 0x002989a6, 0x002c9bc0, 0x001f5256, 0x001d4c50, 0x001c484c, 0x001b4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00142e34, 0x00122c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b151c, 0x000b151c, 0x000b151c, 0x000b151c, 0x000b151c, 0x000b151c, 0x000b151c, 0x000b151c, 0x000b151c, 0x000c161d, 0x000c161f, 0x000c161f, 0x000d1720, 0x000d1820, 0x000e1820, 0x000d1922, 0x000e1a23, 0x000f1c24, 0x000f1c24, 0x00101c24, 0x000f1c24, 0x000e1c26, 0x000e1e27, 0x000f1f29, 0x000f222c, 0x0010242e, 0x0010242f, 0x00102430, 0x00102533, 0x00102634, 0x00112834, 0x00122835, 0x00122836, 0x00132a37, 0x00142c38, 0x00142c39, 0x00142d3b, 0x00142f3c, 0x00162e3c, 0x00172f3d, 0x00172f3d, 0x00142f3c, 0x00142f3c, 0x00142e3c, 0x00132d38, 0x00122c37, 0x00132b36, 0x00142a35, 0x00132935, 0x00142a35, 0x00132934, 0x00122834, 0x00122834, 0x00112733, 0x00102531, 0x00102531, 0x00122531, 0x00122431, 0x00122531, 0x00102631, 0x00102531, 0x00102531, 0x00122632, 0x00132733, 0x00132733, 0x00132934, 0x00132935, 0x00132a36, 0x00132934, 0x00132934, 0x00132934, 0x00142934, 0x00162b38, 0x001a303d, 0x001a303e, 0x0019303c, 0x00182f3c, 0x001c3340, 0x00273d4c, 0x002c4150, 0x002c4250, 0x002a3f4c, 0x00283c49, 0x00273a48, 0x002a3c49, 0x002f404c, 0x00283a46, 0x00283845, 0x00293846, 0x00283845, 0x00283743, 0x00283843, 0x002d3c47, 0x00323f4b, 0x0034414d, 0x0037434e, 0x002f3844, 0x00303944, 0x00323c48, 0x00303945, 0x0026303b, 0x00252e39, 0x00242d37, 0x0028303a, 0x002a343e, 0x00303843, 0x00313b46, 0x00323c48, 0x0035414c, 0x00384450, 0x003a4551, 0x003b4753, 0x003c4753, 0x003d4854, 0x003c4854, 0x0038424e, 0x00303844, 0x002c343f, 0x00262c38, 0x00202731, 0x001e232d, 0x001e232a, 0x001e2128, 0x001b1e24, 0x001b1e24, 0x001a1d24, 0x00171920, 0x00181b20, 0x001a1d22, 0x00181c20, 0x0016191e, 0x00181c21, 0x00181d22, 0x00161b21, 0x00141820, 0x00171a21, 0x001c1f24, 0x001b1e22, 0x00191d21, 0x0016191e, 0x0013161a, 0x0011161a, 0x0011171b, 0x00171b20, 0x001a1d22, 0x00181c20, 0x00191c20, 0x001b1e22, 0x001c1f24, 0x00181b20, 0x0018191f, 0x00181a20, 0x001c1d23, 0x001d1f24, 0x001e2026, 0x001d2028, 0x001d2027, 0x001b1e24, 0x001c1d24, 0x00181920, 0x00191c21, 0x001d1f24, 0x001c1d24, 0x00181a1f, 0x0015181d, 0x00171a20, 0x001a1d24, 0x00191c23, 0x00151820, 0x0010141c, 0x0010131b, 0x0014171f, 0x00181c23, 0x001a1d26, 0x00191c24, 0x00191c24, 0x001c2028, 0x00191c25, 0x001c2028, 0x001a1d25, 0x001a1d26, 0x001c1f28, 0x0020232c, 0x0020232b, 0x001f232b, 0x0020252d, 0x00232830, 0x00272d36, 0x002e343e, 0x00323844, 0x0038404c, 0x003b4551, 0x003d4854, 0x003d4955, 0x003c4854, 0x003c4854, 0x003b4753, 0x00384450, 0x0036414d, 0x00343d4a, 0x00303b47, 0x00303c48, 0x002e3a46, 0x002b3541, 0x0028323e, 0x002b3440, 0x002c353f, 0x002c353e, 0x0029323b, 0x0029323b, 0x002c343e, 0x002c3540, 0x002b343f, 0x0029333d, 0x0026303b, 0x0027303c, 0x002a3440, 0x002a3440, 0x00252f3b, 0x002c3843, 0x00323d49, 0x002f3b46, 0x002f3b47, 0x002f3b48, 0x002a3543, 0x00273340, 0x00293644, 0x002c3947, 0x00303c4b, 0x0032404d, 0x00303d4c, 0x002f3e4c, 0x002c3c4a, 0x002c3c49, 0x002c3d4c, 0x00304050, 0x00304051, 0x002d404f, 0x002c4050, 0x00334758, 0x00344a5a, 0x00334957, 0x002f4552, 0x00293f4c, 0x00243948, 0x00243847, 0x00243744, 0x00213140, 0x001c2c39, 0x00182834, 0x00182835, 0x00192a38, 0x001b2c3b, 0x001b2f3d, 0x001d3040, 0x001e3242, 0x001e3341, 0x001d3240, 0x001c303f, 0x001b303d, 0x001b2e3d, 0x001b2e3d, 0x001a303d, 0x001b313f, 0x001a303f, 0x00172d3b, 0x00142a37, 0x00142937, 0x00142836, 0x00142937, 0x00142a37, 0x00152a37, 0x00152a37, 0x00142a37, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132b38, 0x00132c38, 0x00132c38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142a37, 0x00122834, 0x00112833, 0x00122834, 0x00142934, 0x00142834, 0x00122733, 0x00102531, 0x00102430, 0x00112430, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010222f, 0x0011222f, 0x0010222f, 0x0010232e, 0x0010232d, 0x0011232d, 0x0010222c, 0x0010222c, 0x000f222c, 0x000f222c, 0x000f222c, 0x000f222c, 0x000f222c, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00153338, 0x0016363b, 0x00183c40, 0x00194245, 0x001c474b, 0x001e4d50, 0x00205356, 0x0022585b, 0x00245d60, 0x00256264, 0x00276668, 0x0028696c, 0x00296c6f, 0x002a6e70, 0x002b7072, 0x002b7072, 0x002b7173, 0x002c7174, 0x002c777e, 0x003296b0, 0x0034a4c5, 0x00286b6e, 0x00286769, 0x00276568, 0x00266364, 0x00256163, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x002989a6, 0x002c9bc0, 0x00205256, 0x001d4c50, 0x001c484c, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00142e34, 0x00122c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b161d, 0x000b161d, 0x000b161d, 0x000b161c, 0x000b161c, 0x000b161c, 0x000b161c, 0x000b161c, 0x000b161e, 0x000c1720, 0x000c1620, 0x000d1721, 0x000d1822, 0x000d1922, 0x000d1923, 0x000d1b24, 0x000e1c24, 0x000f1c24, 0x000e1c24, 0x000e1c24, 0x000f1d26, 0x000f1e27, 0x000f1f28, 0x0010202b, 0x000f212c, 0x0010232d, 0x0010242f, 0x00102531, 0x00102634, 0x00112834, 0x00112834, 0x00122836, 0x00142a37, 0x00142b38, 0x00142c39, 0x00142c39, 0x00142d3b, 0x00142f3c, 0x00152e3c, 0x00162f3d, 0x00162f3d, 0x00142f3c, 0x00142f3c, 0x00142f3c, 0x00142e3b, 0x00142d3a, 0x00142c39, 0x00142b38, 0x00142a37, 0x00142b37, 0x00142a37, 0x00132935, 0x00132934, 0x00122834, 0x00112632, 0x00112632, 0x00122631, 0x00132631, 0x00122631, 0x00112730, 0x00112731, 0x00112732, 0x00112733, 0x00132733, 0x00142834, 0x00142834, 0x00142a35, 0x00152a35, 0x00142a35, 0x00142a35, 0x00142a35, 0x00152a35, 0x00162b38, 0x001a303c, 0x001a303f, 0x0019303e, 0x001c3140, 0x00213745, 0x00294050, 0x002b4150, 0x002b4150, 0x002a3f4c, 0x00283c4a, 0x00283b49, 0x002a3c4a, 0x002f404d, 0x00273844, 0x00273643, 0x00293844, 0x00283643, 0x00263440, 0x00283540, 0x002c3945, 0x002f3c48, 0x00323f4b, 0x0034404c, 0x002c3743, 0x002f3945, 0x00313b48, 0x002c3541, 0x0026303b, 0x0029333c, 0x0028303b, 0x0027303a, 0x002b3540, 0x00323c48, 0x00343f4b, 0x0034404c, 0x0037444f, 0x00394551, 0x00394652, 0x00394551, 0x003a4551, 0x003c4552, 0x0038404c, 0x00313944, 0x002c333c, 0x00262e37, 0x00212730, 0x001e242c, 0x001c2028, 0x001b1f26, 0x001c2027, 0x00161a20, 0x0014181e, 0x0013161c, 0x0014181f, 0x00181c22, 0x00191d23, 0x00181c23, 0x00191d24, 0x001b1f25, 0x001c2028, 0x00181e25, 0x00181d24, 0x001b1e26, 0x001c1e25, 0x00181b21, 0x00181c22, 0x001a1c23, 0x00191c22, 0x00161a20, 0x00161b20, 0x001a1f24, 0x00181c22, 0x0014181d, 0x00191d20, 0x001c2024, 0x00181d21, 0x000e1217, 0x00101318, 0x0015181c, 0x00181c20, 0x001a1d21, 0x001a1d22, 0x00181c22, 0x00181c23, 0x001e2128, 0x00202229, 0x0016181f, 0x0013141c, 0x0014161c, 0x0015181c, 0x0014171c, 0x00121419, 0x00111319, 0x00161920, 0x001c1f26, 0x00181c23, 0x00141820, 0x0012151d, 0x00141820, 0x00171a21, 0x00161820, 0x0014171f, 0x001a1c25, 0x001b1f27, 0x00171c24, 0x001a1e26, 0x001b1e27, 0x001b1f27, 0x00191c25, 0x001c1f28, 0x001d212a, 0x001e232c, 0x0020252e, 0x0020262f, 0x00232832, 0x00282e38, 0x002d323c, 0x00313742, 0x00333b45, 0x0038414c, 0x003c4650, 0x003c4853, 0x003b4753, 0x003b4753, 0x0037434f, 0x0035404c, 0x00343e4a, 0x00303945, 0x002e3844, 0x002f3844, 0x002d3843, 0x0027303c, 0x0028313c, 0x002c353f, 0x002e3841, 0x002d3842, 0x002b343f, 0x002b3440, 0x002d3843, 0x002c3842, 0x002c3743, 0x002c3643, 0x00283440, 0x0026303d, 0x0028323f, 0x0024303c, 0x00283440, 0x00303c48, 0x002c3845, 0x002c3845, 0x00303c48, 0x002f3a48, 0x002a3544, 0x002c3947, 0x002b3947, 0x00283744, 0x002f3d4c, 0x002f3e4c, 0x00324250, 0x00324351, 0x002d3f4c, 0x002c3e4d, 0x00314352, 0x00334454, 0x002f4251, 0x002f4453, 0x00324858, 0x00324858, 0x00304855, 0x002e4451, 0x002b404e, 0x00283d4b, 0x00253a49, 0x00243845, 0x00213340, 0x001c2c39, 0x00182835, 0x001a2a38, 0x001c2d3c, 0x001c303e, 0x001c3040, 0x001c3243, 0x001e3343, 0x001e3340, 0x001d323f, 0x001d323f, 0x001c313f, 0x001c303e, 0x001b2f3d, 0x001b303e, 0x001c3340, 0x001c3340, 0x00182f3c, 0x00162c39, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142b38, 0x00142b38, 0x00132c38, 0x00132b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00132a37, 0x00122934, 0x00112834, 0x00122834, 0x00142934, 0x00142834, 0x00122733, 0x00102532, 0x00102431, 0x00112430, 0x00112430, 0x0010232e, 0x0010242e, 0x0010232e, 0x0010232e, 0x0010232e, 0x000f232e, 0x000f232e, 0x0010232e, 0x0010232e, 0x0010232e, 0x0010242e, 0x0010242d, 0x0011242d, 0x0010242d, 0x0010232d, 0x0010242d, 0x0010242d, 0x0010242d, 0x0010242d, 0x0010242d, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x00102229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00153338, 0x0016363b, 0x00183c40, 0x00194245, 0x001c474b, 0x001d4d50, 0x00205356, 0x0022585b, 0x00245d60, 0x00256163, 0x00276568, 0x0028686b, 0x00296b6d, 0x00296d6f, 0x002b6f70, 0x002c7071, 0x002b7071, 0x002c7378, 0x002e8494, 0x00329dbc, 0x0034a3c5, 0x00286a6d, 0x00276668, 0x00266467, 0x00256264, 0x00246062, 0x00245f61, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x0022585b, 0x002989a6, 0x002c9bc0, 0x001f5256, 0x001d4c50, 0x001c484c, 0x001b4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00142e34, 0x00122c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a171e, 0x000a171e, 0x000a181e, 0x000a181e, 0x000a181e, 0x000a181e, 0x000a181e, 0x000a181f, 0x000c1821, 0x000c1822, 0x000d1823, 0x000e1824, 0x000d1925, 0x000d1b25, 0x000c1c25, 0x000d1c25, 0x000d1d26, 0x000e1e27, 0x000e1e28, 0x000e1f28, 0x000e2028, 0x000f2029, 0x000f2029, 0x0010202c, 0x000f212c, 0x000f222c, 0x0010242e, 0x00112530, 0x00112734, 0x00122835, 0x00132936, 0x00142a37, 0x00142b38, 0x00142c38, 0x00142c39, 0x00142d39, 0x00132d3b, 0x00132f3c, 0x00142f3c, 0x0015303d, 0x0015303d, 0x0015303d, 0x0015303d, 0x00142f3c, 0x00142f3c, 0x00152d3c, 0x00152d3c, 0x00142c39, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142a36, 0x00142a35, 0x00132834, 0x00122733, 0x00112632, 0x00132631, 0x00132630, 0x00142732, 0x00132834, 0x00132934, 0x00132934, 0x00132934, 0x00132834, 0x00142834, 0x00142834, 0x00152934, 0x00162935, 0x00162935, 0x00152a35, 0x00152a35, 0x00152a36, 0x00162b38, 0x001a2f3c, 0x001b3140, 0x001c3241, 0x001d3444, 0x00223a49, 0x00294051, 0x00294050, 0x00283f4d, 0x00283d4c, 0x00283c4c, 0x002a3d4d, 0x002c404e, 0x002f414e, 0x00263844, 0x00273644, 0x002b3846, 0x00283542, 0x0024323e, 0x0024323d, 0x00283642, 0x002c3944, 0x002f3c48, 0x00303c48, 0x002a3642, 0x002e3945, 0x002f3a46, 0x00293440, 0x0026323c, 0x0028343c, 0x0028333c, 0x00252f38, 0x002e3843, 0x0037424e, 0x0036444f, 0x0034434f, 0x00384551, 0x00384652, 0x00384651, 0x00384450, 0x0037414d, 0x00363e4b, 0x00313844, 0x002c333d, 0x00293038, 0x00252b33, 0x0021262e, 0x001d222a, 0x001c2028, 0x00191d24, 0x001a1f25, 0x00181c21, 0x0014181e, 0x0014181f, 0x00151a20, 0x00161b21, 0x00171c23, 0x00181d25, 0x00181d24, 0x00161b21, 0x001e242a, 0x001d242a, 0x001b2026, 0x001a1f25, 0x00181c22, 0x0014181f, 0x00181c22, 0x001b1e24, 0x001b2026, 0x001b2025, 0x00191e24, 0x00181d24, 0x0014181f, 0x0014191d, 0x001b2024, 0x001c2025, 0x0014181c, 0x000d1116, 0x000f1216, 0x00121517, 0x0016191a, 0x00181b1d, 0x00171a1e, 0x00171b21, 0x001b2026, 0x001c2027, 0x001c2026, 0x0015181f, 0x000f1218, 0x000f1218, 0x00101418, 0x0013161b, 0x000c1014, 0x00101318, 0x0014191f, 0x00191e24, 0x001a1f25, 0x00181c24, 0x00181d24, 0x00181c23, 0x00181c22, 0x00161920, 0x0012151c, 0x00161a21, 0x00191e24, 0x00181e24, 0x00191f27, 0x00181c24, 0x00171b24, 0x00171c25, 0x00181c26, 0x00181d27, 0x001b202a, 0x00202730, 0x001f252d, 0x001f252d, 0x0020252f, 0x00242933, 0x002b2f39, 0x002d343f, 0x00313844, 0x0038414c, 0x003c4651, 0x003b4652, 0x003a4652, 0x0037434f, 0x0035404c, 0x00333d49, 0x00303a46, 0x002c3640, 0x002e3842, 0x00303944, 0x0029333d, 0x00242f39, 0x0026323c, 0x002b3741, 0x002f3b47, 0x002d3945, 0x002b3743, 0x002e3a46, 0x002b3844, 0x002b3843, 0x00303b48, 0x002f3b47, 0x002b3743, 0x0027333f, 0x00232f3c, 0x00242f3c, 0x002e3845, 0x002c3743, 0x00293440, 0x002d3945, 0x002d3948, 0x002c3848, 0x002e3c4a, 0x002c3d4a, 0x00283846, 0x002c3a49, 0x002e3d4c, 0x00334251, 0x00324351, 0x002c3f4d, 0x002c4050, 0x00304454, 0x00324755, 0x00304452, 0x00304555, 0x00314858, 0x002f4856, 0x002d4653, 0x002c4350, 0x002a404e, 0x0029404c, 0x00263d4a, 0x00243946, 0x001f333f, 0x001a2c38, 0x00192b38, 0x001b2d3a, 0x001c303d, 0x001d3340, 0x001d3341, 0x001c3442, 0x001e3442, 0x001d3340, 0x001d3240, 0x001d3240, 0x001c3240, 0x001c303e, 0x0019303c, 0x001a303e, 0x001b3340, 0x001b3340, 0x001a303e, 0x00182e3b, 0x00162c3a, 0x00152c39, 0x00162c3a, 0x00142c39, 0x00132c38, 0x00132c38, 0x00142b38, 0x00142a38, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142b38, 0x00142b38, 0x00142c38, 0x00132c38, 0x00132c38, 0x00132c38, 0x00132c38, 0x00132c38, 0x00132c38, 0x00122b37, 0x00122b35, 0x00112a34, 0x00122934, 0x00132934, 0x00132733, 0x00122733, 0x00102531, 0x00112431, 0x00122431, 0x00112430, 0x0011242d, 0x0011242c, 0x0010242c, 0x0010242c, 0x0010232c, 0x000f242d, 0x000f242d, 0x000f242d, 0x0010232d, 0x000f232d, 0x0010242e, 0x0010242e, 0x0010242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x00102229, 0x0012242c, 0x00112a30, 0x00142e34, 0x00153338, 0x0016363b, 0x00183d41, 0x001b4347, 0x001c484c, 0x001e4d50, 0x00205356, 0x0022585b, 0x00245c5f, 0x00256163, 0x00276467, 0x0028686a, 0x00286a6c, 0x002a6c6f, 0x002a7074, 0x002d7f8c, 0x003093aa, 0x0034a3c3, 0x0034a6c9, 0x00329dbd, 0x002e8aa0, 0x0028686b, 0x00276568, 0x00256364, 0x00256163, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00245c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0022585b, 0x002888a6, 0x002b9bc0, 0x001e5054, 0x001d4c50, 0x001c474b, 0x001a4347, 0x00183d41, 0x00183a3e, 0x00153439, 0x00142e34, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a1820, 0x000a1820, 0x000a1820, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1920, 0x000c1923, 0x000c1924, 0x000d1824, 0x000e1925, 0x000f1b27, 0x000e1c27, 0x000d1c27, 0x000d1d27, 0x000e1e28, 0x000f1f28, 0x000f2029, 0x000f202a, 0x000f202a, 0x000f202a, 0x000f202a, 0x0010202c, 0x000f212c, 0x000f222c, 0x0010242e, 0x00112530, 0x00112734, 0x00132936, 0x00132936, 0x00142a38, 0x00142b38, 0x00142c38, 0x00142c39, 0x00142d39, 0x00132d3b, 0x00132f3c, 0x00142f3c, 0x0015303d, 0x0015303d, 0x0015303d, 0x0015303d, 0x00152f3c, 0x00152e3c, 0x00152d3c, 0x00152c3c, 0x00142c3a, 0x00142b39, 0x00142b38, 0x00142b38, 0x00142a36, 0x00142a35, 0x00142934, 0x00142834, 0x00142834, 0x00142834, 0x00142834, 0x00142834, 0x00142934, 0x00132934, 0x00132934, 0x00132934, 0x00132934, 0x00142934, 0x00142934, 0x00142934, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a36, 0x00162b38, 0x001a303d, 0x001b3240, 0x001c3442, 0x001d3544, 0x00233b4a, 0x00284050, 0x00283f4e, 0x00273d4c, 0x00283e4d, 0x00293e4d, 0x002c4050, 0x002d4250, 0x00304451, 0x00283948, 0x00283846, 0x002b3946, 0x00283543, 0x0025333e, 0x0024313d, 0x00283642, 0x002b3844, 0x002c3b46, 0x002c3a44, 0x0027343e, 0x002c3844, 0x00303c48, 0x002b3742, 0x002b3740, 0x0029353d, 0x0028343c, 0x00263039, 0x00303b46, 0x00384450, 0x00384450, 0x00364550, 0x00394753, 0x00394753, 0x00384650, 0x0037434e, 0x00333d49, 0x00313946, 0x002f3540, 0x002c323c, 0x00282f37, 0x00242a32, 0x0020252d, 0x001d222a, 0x001d222a, 0x001a1f26, 0x00171c22, 0x0014191f, 0x0013171d, 0x0013181f, 0x0014191f, 0x00161b21, 0x00161a22, 0x00141921, 0x0012171e, 0x00161b21, 0x001c2128, 0x00192025, 0x00181c23, 0x00161b21, 0x00151a20, 0x00141920, 0x00181c23, 0x001b1e24, 0x00191e24, 0x00181c23, 0x00171c22, 0x0014181f, 0x00161b21, 0x00181d22, 0x00191f23, 0x00181d22, 0x00101519, 0x000d1115, 0x00101315, 0x00121516, 0x0015191a, 0x00161a1c, 0x0014181c, 0x00171b21, 0x001a1f25, 0x00191e24, 0x00181b22, 0x0014171e, 0x00101319, 0x000d1017, 0x000d1015, 0x00111419, 0x00101317, 0x00111419, 0x0013181d, 0x0014191f, 0x00171c23, 0x00171c24, 0x00191e26, 0x00181d24, 0x00161b21, 0x00161b21, 0x00161b20, 0x00181d24, 0x00181d24, 0x00151c22, 0x00181e24, 0x00161b23, 0x00131820, 0x00191d27, 0x001a1e28, 0x00181d27, 0x00191f28, 0x001f252f, 0x001e242c, 0x001b2129, 0x001c212b, 0x0020242f, 0x00262b34, 0x002a3039, 0x002d343e, 0x00333b44, 0x0038414c, 0x003b4450, 0x003a4450, 0x00394450, 0x0036414e, 0x00343e4b, 0x00303a46, 0x002c3640, 0x002c3640, 0x002d3842, 0x002a343f, 0x0026313b, 0x0024303a, 0x0028343f, 0x002e3a46, 0x002e3a46, 0x002a3642, 0x002e3a46, 0x002c3a45, 0x00293642, 0x00293642, 0x002c3844, 0x002f3b47, 0x002c3743, 0x0024303c, 0x00212c38, 0x0026303c, 0x002a3441, 0x00293440, 0x002a3642, 0x00293443, 0x00293544, 0x002c3948, 0x002c3d4a, 0x002c3c4a, 0x002c3c4b, 0x002d3c4c, 0x00334250, 0x00314250, 0x002a3d4b, 0x002c4050, 0x00304454, 0x00314655, 0x00314554, 0x00304655, 0x00304856, 0x002c4554, 0x002b4450, 0x002a414f, 0x002a404d, 0x0029404c, 0x00283f4c, 0x00263b48, 0x001e333f, 0x001a2c38, 0x001c2e3b, 0x001c303c, 0x001e333f, 0x001f3440, 0x001e3542, 0x001d3544, 0x001f3443, 0x001e3240, 0x001d3240, 0x001d3240, 0x001c3140, 0x001c313e, 0x0019303d, 0x001a313e, 0x001b3340, 0x001b3340, 0x001a303d, 0x00182e3c, 0x00172d3b, 0x00172d3a, 0x00172d3a, 0x00152d3a, 0x00142c39, 0x00142c39, 0x00142c39, 0x00142b38, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142b38, 0x00142b38, 0x00142c38, 0x00132c38, 0x00132c38, 0x00132c38, 0x00132c38, 0x00132c38, 0x00132c38, 0x00122b37, 0x00122b35, 0x00112a34, 0x00122934, 0x00132934, 0x00132834, 0x00122733, 0x00102531, 0x00112431, 0x00122431, 0x00112430, 0x0011242d, 0x0011242c, 0x0010242c, 0x0010242c, 0x0010232c, 0x000e252e, 0x000e252e, 0x000e242d, 0x000f242d, 0x000f242d, 0x0010242e, 0x0010242e, 0x0010242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013282e, 0x00102a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4347, 0x001c484c, 0x001d4d50, 0x00205356, 0x0021585b, 0x00245c5f, 0x00256163, 0x00266467, 0x0028696c, 0x002a757f, 0x002f8ca2, 0x00339fbe, 0x0034a6c9, 0x0034a4c5, 0x003094ae, 0x002c7c8a, 0x00286d71, 0x0028686a, 0x00276668, 0x00266466, 0x00256264, 0x00246062, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00235c5e, 0x00245c5e, 0x00235a5c, 0x00235a5c, 0x00235a5c, 0x00235a5c, 0x00235a5c, 0x0021595c, 0x0022585b, 0x0021575a, 0x002888a6, 0x002b9ac0, 0x001e5054, 0x001d4b4e, 0x001c4649, 0x001a4245, 0x00183d41, 0x0017383c, 0x00153439, 0x00142e34, 0x00122a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a1a21, 0x000a1a21, 0x000a1a21, 0x000a1b22, 0x000a1b22, 0x000a1b22, 0x000a1b22, 0x000a1b23, 0x000b1b25, 0x000c1a27, 0x000d1a26, 0x000e1a26, 0x000f1c28, 0x000f1d28, 0x000e1d28, 0x000e1e28, 0x000f1f29, 0x0010202b, 0x0010202b, 0x000f202b, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f212c, 0x000f222c, 0x0010242e, 0x00112530, 0x00112734, 0x00132936, 0x00132936, 0x00142a37, 0x00142a37, 0x00142b38, 0x00142c39, 0x00142c39, 0x00142d3b, 0x00142f3c, 0x00142f3c, 0x0015303d, 0x0015303d, 0x0015303d, 0x0015303d, 0x00162f3d, 0x00162e3c, 0x00172c3c, 0x00172c3c, 0x00152c3b, 0x00152c3b, 0x00152c3b, 0x00152c3b, 0x00142a38, 0x00142a37, 0x00142936, 0x00142934, 0x00142934, 0x00152834, 0x00162834, 0x00152834, 0x00142a35, 0x00142a36, 0x00142a35, 0x00142a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00162b37, 0x001a303c, 0x001c3341, 0x001d3544, 0x001f3745, 0x00243c4b, 0x00284050, 0x00273e4e, 0x00283e4d, 0x002a4050, 0x002b4050, 0x002c4152, 0x002d4252, 0x00304554, 0x00293c4b, 0x00293a48, 0x002a3946, 0x00283644, 0x0024333f, 0x0024313d, 0x00293842, 0x002a3843, 0x00293742, 0x0027343e, 0x0024323c, 0x002c3843, 0x00303c47, 0x002e3a44, 0x002f3b44, 0x002c3841, 0x0028343d, 0x0028343c, 0x00303c47, 0x0038434f, 0x00384450, 0x00384752, 0x00384652, 0x00384551, 0x0038444f, 0x00333d48, 0x002e3843, 0x002f3742, 0x002c343f, 0x002b313a, 0x00282e36, 0x00242931, 0x001f232b, 0x001b1f28, 0x00161b23, 0x0013181f, 0x0011171d, 0x0011161c, 0x0013181f, 0x0012181f, 0x00151c21, 0x00171d24, 0x00161d24, 0x00161c24, 0x00141920, 0x0010171c, 0x00141c21, 0x00161c23, 0x00181c23, 0x00171c22, 0x00161b21, 0x00181c23, 0x00191d24, 0x001a1d24, 0x0014181e, 0x0013181e, 0x00141920, 0x0013181e, 0x00161b20, 0x00151a20, 0x00141a1e, 0x0014181d, 0x0010151a, 0x0012161a, 0x00101418, 0x00111417, 0x00141819, 0x0015181c, 0x0014181c, 0x00181c22, 0x001b2025, 0x00191e24, 0x00191d24, 0x00171920, 0x0013151c, 0x000f1218, 0x000e1116, 0x0012151a, 0x00171a1f, 0x0012151a, 0x0011171c, 0x0014181f, 0x00171c23, 0x00181c24, 0x001a1e26, 0x001c2027, 0x00181c23, 0x0015181f, 0x001a1d24, 0x001c2026, 0x00181d24, 0x0013191f, 0x00151c22, 0x00181e24, 0x00171d24, 0x00181e25, 0x001a2028, 0x001c222a, 0x001c232b, 0x0020262e, 0x0021282f, 0x001f252c, 0x001f242c, 0x00212630, 0x00242933, 0x00262c36, 0x00283039, 0x002c343e, 0x00303a45, 0x00394350, 0x003a4452, 0x003a4553, 0x00384350, 0x00343e4c, 0x002f3846, 0x002d3842, 0x002c3741, 0x002c3640, 0x002a343e, 0x0028323c, 0x0025313c, 0x0028343d, 0x002c3843, 0x002d3844, 0x002b3743, 0x002d3945, 0x002e3a46, 0x00283440, 0x0026333e, 0x0026333f, 0x002c3945, 0x002e3b47, 0x00293441, 0x0026303c, 0x00232c39, 0x0028313e, 0x00293440, 0x00293541, 0x00283442, 0x00283443, 0x002a3846, 0x002c3c49, 0x002e3f4c, 0x002e3e4c, 0x002e3e4d, 0x00334353, 0x00304151, 0x00283c4c, 0x002c4050, 0x002d4153, 0x002f4454, 0x00304755, 0x00304756, 0x00304655, 0x002c4351, 0x0028414e, 0x00273f4c, 0x00273f4c, 0x0028404c, 0x00283f4c, 0x00253a46, 0x001e333e, 0x001b2f39, 0x001d303c, 0x001e313e, 0x001f3440, 0x001f3541, 0x00203644, 0x00203845, 0x00203544, 0x001e3340, 0x001d323e, 0x001c313e, 0x001c313d, 0x001c313d, 0x001b323d, 0x001b313e, 0x001b313f, 0x001b313f, 0x0019303d, 0x00182e3c, 0x00182e3b, 0x00182e3b, 0x00182e3b, 0x00162d3a, 0x00152d3a, 0x00142c39, 0x00152c39, 0x00152c39, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00162b38, 0x00162b38, 0x00152b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00132b37, 0x00122b35, 0x00112a34, 0x00122934, 0x00132934, 0x00122834, 0x00102733, 0x00102631, 0x00102531, 0x00102531, 0x00102430, 0x0010242d, 0x0010242c, 0x000f242c, 0x000f242c, 0x000f242c, 0x000e252e, 0x000e252e, 0x000e252d, 0x000e252c, 0x000e252c, 0x000f2630, 0x000f2631, 0x00102531, 0x00102531, 0x00102531, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0013282e, 0x00112a30, 0x00142e34, 0x00153439, 0x0017383c, 0x00183f43, 0x001b4448, 0x001c4a4d, 0x001e4f51, 0x00205457, 0x0022585b, 0x00245d60, 0x00266a72, 0x002b8398, 0x003098b7, 0x0034a4c8, 0x0034a5c9, 0x00329ab8, 0x002e869a, 0x002a727a, 0x00286b6d, 0x0028696c, 0x0028686a, 0x00276668, 0x00266467, 0x00256264, 0x00256163, 0x0025666e, 0x00298097, 0x002a86a1, 0x002886a0, 0x002885a0, 0x002885a0, 0x002885a0, 0x002885a0, 0x002885a0, 0x002885a0, 0x002885a0, 0x002885a0, 0x002884a0, 0x0027849f, 0x002b96ba, 0x002b9ac0, 0x001e4f53, 0x001c4a4d, 0x001b4649, 0x001a4044, 0x00183c40, 0x0017383c, 0x00143338, 0x00142e34, 0x00102a30, 0x0012282e, 0x00102229, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091c24, 0x00091c24, 0x00091c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c25, 0x000b1c28, 0x000c1c28, 0x000d1c28, 0x000f1c28, 0x000f1c28, 0x000f1e28, 0x000e1e28, 0x000f1f29, 0x0010202a, 0x0010202b, 0x0010202b, 0x000f202b, 0x0010202c, 0x0010222c, 0x0010222c, 0x0010222c, 0x000f222c, 0x000f222c, 0x0010242e, 0x00112530, 0x00112734, 0x00132936, 0x00132936, 0x00142a37, 0x00142a37, 0x00142b38, 0x00142c39, 0x00142c39, 0x00142d3b, 0x00142f3c, 0x00142f3c, 0x0015303d, 0x0015303d, 0x0015303d, 0x0015303d, 0x00162f3d, 0x00162e3d, 0x00172c3c, 0x00172c3c, 0x00152c3b, 0x00152c3b, 0x00162c3c, 0x00162c3b, 0x00142a38, 0x00142a37, 0x00142a36, 0x00152a35, 0x00152a35, 0x00162935, 0x00172935, 0x00162936, 0x00152a38, 0x00152a37, 0x00152a36, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00172c38, 0x001b303d, 0x001c3342, 0x001e3644, 0x001f3745, 0x00243c4b, 0x0028404f, 0x00283f4f, 0x00283f4f, 0x002a4151, 0x002b4152, 0x002c4253, 0x002d4352, 0x00324654, 0x002c3d4c, 0x002a3b49, 0x00293845, 0x00253441, 0x0023323e, 0x0024333f, 0x002a3843, 0x00293742, 0x00283440, 0x0026323c, 0x0024303b, 0x00293541, 0x002c3844, 0x002f3b47, 0x00313d48, 0x002f3b43, 0x002a363f, 0x002a363f, 0x0034404a, 0x0038444f, 0x00384450, 0x00374450, 0x0036424e, 0x0036424e, 0x00343f4a, 0x002f3944, 0x002c3741, 0x002e3641, 0x002c333c, 0x00272e35, 0x00212830, 0x001e232a, 0x00181c24, 0x00161921, 0x000f141c, 0x000c131a, 0x0010161c, 0x00141b20, 0x00141a20, 0x0014191f, 0x00151c21, 0x00171d24, 0x001b2128, 0x00181f26, 0x000e131a, 0x000d1419, 0x00141a20, 0x00181f25, 0x00181e24, 0x0014191f, 0x0013181e, 0x00181d23, 0x00181d24, 0x00181c23, 0x000f141a, 0x00141920, 0x00151a20, 0x00151a20, 0x00151a20, 0x00171c22, 0x00161b20, 0x0012181d, 0x0012171c, 0x0014181d, 0x0014181d, 0x0014181c, 0x00181b1f, 0x0016191d, 0x00191c21, 0x001c2025, 0x001a1f25, 0x001c2027, 0x001c2026, 0x00181b22, 0x00171920, 0x0014181e, 0x0012151b, 0x0015181d, 0x00181b20, 0x0013161b, 0x0011161b, 0x0014191f, 0x00151a21, 0x00141921, 0x00131820, 0x00181d24, 0x001a1e24, 0x00181b21, 0x00191c23, 0x00171a21, 0x001b2026, 0x00192026, 0x001a2027, 0x001c2228, 0x001c2228, 0x001b2129, 0x001b2229, 0x001d242c, 0x0020272e, 0x0020272f, 0x00232930, 0x00242a31, 0x00242a31, 0x00242832, 0x00242934, 0x00242a34, 0x00252c36, 0x00272f39, 0x0028323e, 0x00303a48, 0x00374250, 0x00394452, 0x00384451, 0x00343e4c, 0x00303946, 0x002d3843, 0x002d3842, 0x002c3741, 0x0028333d, 0x0028323c, 0x0027323c, 0x0028333d, 0x002a3440, 0x002b3441, 0x002b3441, 0x002b3541, 0x002c3743, 0x002a3441, 0x0028323f, 0x0026323d, 0x002a3742, 0x002d3945, 0x002c3844, 0x002c3642, 0x00242d3a, 0x00242d3a, 0x00283440, 0x0028333f, 0x00283441, 0x002b3746, 0x002d3b4a, 0x002d3e4c, 0x0030404e, 0x00304050, 0x00304151, 0x00344555, 0x00304252, 0x00283c4c, 0x00293e4f, 0x002c4052, 0x002c4152, 0x002e4454, 0x00304756, 0x00304655, 0x002c4251, 0x0028404c, 0x00263e4b, 0x00273f4c, 0x00283f4c, 0x00283f4c, 0x00253a47, 0x001e343f, 0x001c303b, 0x001e313d, 0x001f3440, 0x00203543, 0x00203744, 0x00203745, 0x00203847, 0x00203646, 0x001f3442, 0x001d323e, 0x001c313d, 0x001c313d, 0x001c323e, 0x001c333e, 0x001b323e, 0x001a303e, 0x001a303e, 0x0019303d, 0x00182f3c, 0x00182e3b, 0x00182e3b, 0x00182e3b, 0x00172e3b, 0x00152d3a, 0x00152d3a, 0x00162d3a, 0x00152c39, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00162b38, 0x00162b38, 0x00152b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00132a37, 0x00122b35, 0x00112a34, 0x00122934, 0x00132934, 0x00122834, 0x00102833, 0x00102631, 0x00102531, 0x00102531, 0x00102430, 0x0010242d, 0x0010242c, 0x000f242c, 0x000f242c, 0x000f242c, 0x000e252e, 0x000f262f, 0x000f262e, 0x000e252e, 0x000e252e, 0x000f2630, 0x000f2631, 0x00102631, 0x00102531, 0x00102531, 0x0011242f, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00143036, 0x00143439, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001d4a4d, 0x001f5053, 0x0020575b, 0x00267689, 0x002c90ad, 0x0030a1c6, 0x0033a5ca, 0x00319fc0, 0x002e8ea8, 0x002a7883, 0x00286c6f, 0x0028696c, 0x0028686b, 0x0028686b, 0x00286769, 0x00276568, 0x00266467, 0x00256264, 0x00266971, 0x002a849c, 0x002f9dc1, 0x002f9fc4, 0x002c9bbf, 0x002c9bbf, 0x002c9bbf, 0x002c9bbf, 0x002c9bbf, 0x002c9bbf, 0x002c9bbf, 0x002c9abf, 0x002c9abf, 0x002c9abf, 0x002c9abf, 0x002b99be, 0x002b99be, 0x002990b4, 0x001d4c50, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x0015363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1e27, 0x000a1e26, 0x000b1e26, 0x000c1e27, 0x000d1e27, 0x000d1e27, 0x000e1d27, 0x000e1d27, 0x000d1d28, 0x000c1d28, 0x000e1d28, 0x000e1d27, 0x000f1e28, 0x000f1e29, 0x00101f2a, 0x00101f2a, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f202b, 0x0010212c, 0x0010222c, 0x0010222c, 0x0010222c, 0x000f222c, 0x0010232d, 0x0010242e, 0x00112430, 0x00122734, 0x00132936, 0x00132936, 0x00142a37, 0x00142a37, 0x00142b38, 0x00142c38, 0x00142c39, 0x00152c3b, 0x00162d3c, 0x00152e3c, 0x00152f3c, 0x00152f3c, 0x00142f3c, 0x00142f3c, 0x00152e3c, 0x00162d3b, 0x00162c3b, 0x00152c3a, 0x00142b39, 0x00142a38, 0x00152b39, 0x00162b39, 0x00152a37, 0x00152a36, 0x00152a36, 0x00152a35, 0x00152a35, 0x00172935, 0x00172935, 0x00172936, 0x00162b38, 0x00152a38, 0x00152a35, 0x00142934, 0x00142934, 0x00152834, 0x00152834, 0x00152834, 0x00162834, 0x00162935, 0x00162934, 0x00162a34, 0x00162b35, 0x00182c38, 0x001c303c, 0x001c3340, 0x001d3542, 0x001f3744, 0x00243b48, 0x0028404f, 0x00283f50, 0x00284050, 0x00284150, 0x002b4251, 0x002c4251, 0x002c4150, 0x00314552, 0x002e404d, 0x002c3c49, 0x00283745, 0x00233340, 0x0020303d, 0x00243440, 0x00293844, 0x00293643, 0x0026333f, 0x0026333c, 0x0024303a, 0x0028343d, 0x0028343f, 0x002d3944, 0x00303c45, 0x002f3b43, 0x002a373f, 0x002a3640, 0x0034404a, 0x0035414d, 0x0035424d, 0x00323e49, 0x00313c48, 0x00323c48, 0x00323b48, 0x002e3844, 0x002d3741, 0x002c333d, 0x00282d38, 0x00212830, 0x00191f27, 0x00161a22, 0x0010141c, 0x0010141c, 0x000f151c, 0x00121920, 0x00161e24, 0x00171d23, 0x00141a20, 0x0013181e, 0x0013181e, 0x00161c22, 0x001b2128, 0x00131920, 0x0010151c, 0x0010161c, 0x00151c21, 0x00171c21, 0x00181c21, 0x00151b21, 0x00171c23, 0x00191e24, 0x00181c23, 0x00171c23, 0x00131820, 0x00181e25, 0x00181e25, 0x00171c24, 0x00151b22, 0x00181f26, 0x00161c24, 0x00171c24, 0x00181c24, 0x00181c24, 0x00191c25, 0x001a1d24, 0x001b1e26, 0x00181c23, 0x001a1e25, 0x001b2028, 0x001b2027, 0x001d2229, 0x001b1f25, 0x00171a20, 0x00171a20, 0x0012161c, 0x000f1318, 0x0014171c, 0x00161a1e, 0x0014181c, 0x0014181e, 0x00161b21, 0x00181c23, 0x00181c24, 0x00141921, 0x00181d24, 0x001c2128, 0x001a2026, 0x00151a21, 0x00131820, 0x00171c24, 0x001d242a, 0x001c2228, 0x001f262b, 0x0020272e, 0x001d242b, 0x001a2028, 0x001c222b, 0x001d242e, 0x001b222c, 0x001c242c, 0x001d252d, 0x00222931, 0x00242c34, 0x00222a34, 0x00202831, 0x00202832, 0x00222c36, 0x00232c38, 0x00252f3b, 0x002d3743, 0x00333d49, 0x0037404d, 0x0037404d, 0x00323c48, 0x002b3542, 0x00293541, 0x002a3542, 0x0028313e, 0x0027313c, 0x0026313c, 0x0026313c, 0x0028313c, 0x0028323d, 0x0029323e, 0x0028323d, 0x002b3440, 0x002c3641, 0x002b3440, 0x0029333e, 0x0028333d, 0x00283440, 0x002b3743, 0x00293540, 0x00222e39, 0x00202c37, 0x00283540, 0x00293843, 0x00293845, 0x002a3847, 0x002b3b4a, 0x002d3e4c, 0x0030404f, 0x00304150, 0x00314454, 0x00344757, 0x00304454, 0x002a3f4e, 0x002a3f4e, 0x002d4251, 0x002c4352, 0x002c4352, 0x00304755, 0x00304756, 0x002c4251, 0x00283f4d, 0x00283d4b, 0x00283f4c, 0x00283d4b, 0x00283c4a, 0x00243946, 0x00203440, 0x001d323d, 0x001e333f, 0x00203543, 0x00223745, 0x00213845, 0x00203847, 0x00203848, 0x00203847, 0x00203544, 0x001f3341, 0x001d3240, 0x001c313f, 0x001c323e, 0x001c333f, 0x001b313e, 0x001a303e, 0x001a303e, 0x001a303d, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182e3b, 0x00182e3b, 0x00162d3a, 0x00162d3a, 0x00152c39, 0x00142b38, 0x00162a38, 0x00162a38, 0x00152a37, 0x00152a37, 0x00152a37, 0x00152a37, 0x00152a37, 0x00152a37, 0x00142a37, 0x00142a38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142a38, 0x00142a36, 0x00142936, 0x00142836, 0x00132836, 0x00132834, 0x00122733, 0x00122633, 0x00122633, 0x00122633, 0x00112532, 0x00102530, 0x0010252f, 0x0010252f, 0x000f242f, 0x000f242f, 0x000f2530, 0x00102530, 0x00102530, 0x00102530, 0x00102530, 0x00102530, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00112430, 0x00122530, 0x00112430, 0x00102430, 0x00102430, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00132c32, 0x00143036, 0x0015363b, 0x00173a3e, 0x00194044, 0x001b4649, 0x001d4b4e, 0x001e5053, 0x0021606a, 0x002ea3c9, 0x0030a2c8, 0x002d94b2, 0x002a7b8d, 0x00276b70, 0x00286769, 0x00286769, 0x0028686a, 0x0028686a, 0x00286769, 0x00276668, 0x00266467, 0x00266466, 0x00276a72, 0x002b87a0, 0x00309ec2, 0x002f9fc4, 0x002986a0, 0x0024646f, 0x00225d64, 0x00225d64, 0x00215c63, 0x00225c63, 0x00225c63, 0x00225c63, 0x00215c62, 0x00215c62, 0x00215c62, 0x00205a61, 0x00205960, 0x00205860, 0x001f565e, 0x001e535a, 0x001c4a4d, 0x001b4649, 0x001a4245, 0x00183d41, 0x00183a3e, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1e28, 0x000c1f27, 0x000c1e27, 0x000e1f28, 0x000f1f28, 0x000f1e27, 0x00101d27, 0x00101d27, 0x000f1d27, 0x000e1d27, 0x000e1e27, 0x000d1e27, 0x000d1e27, 0x000f1f29, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010232d, 0x0010232d, 0x0010242f, 0x00112430, 0x00132734, 0x00132936, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a38, 0x00142b38, 0x00142b38, 0x00152c3a, 0x00172c3c, 0x00162d3c, 0x00162e3a, 0x00162e3a, 0x00142f3a, 0x00142f3a, 0x00162d3a, 0x00152c39, 0x00142b38, 0x00142b38, 0x00142a37, 0x00142936, 0x00142834, 0x00152834, 0x00152935, 0x00162935, 0x00162935, 0x00152a35, 0x00152a35, 0x00172935, 0x00172935, 0x00172936, 0x00162b38, 0x00152a38, 0x00152a35, 0x00142934, 0x00142934, 0x00142834, 0x00142834, 0x00142834, 0x00152834, 0x00162834, 0x00172934, 0x00172934, 0x00182c35, 0x00192e38, 0x001c313c, 0x001c313e, 0x001c333f, 0x001e3440, 0x00233945, 0x00273d4a, 0x00283e4d, 0x0028404e, 0x00294350, 0x002c4451, 0x002c4350, 0x002c4350, 0x00314551, 0x002f424e, 0x002a3c48, 0x00283644, 0x00243442, 0x00223341, 0x00273744, 0x00283845, 0x00273542, 0x0024323e, 0x0025333d, 0x0024303a, 0x0027323c, 0x0027333d, 0x002a3640, 0x002d3843, 0x002c3842, 0x002a3640, 0x002a3640, 0x00313d47, 0x0034404a, 0x00344049, 0x00323e48, 0x00333d48, 0x00323c48, 0x00323a47, 0x002f3744, 0x002c333f, 0x00262c36, 0x00212630, 0x001b2028, 0x00151b21, 0x00141820, 0x000c1119, 0x000f141c, 0x00141a21, 0x001b2229, 0x00192128, 0x00151d23, 0x00141a20, 0x0014181e, 0x00151a20, 0x00191d25, 0x00181f26, 0x0010161e, 0x00141820, 0x00191f24, 0x001c2126, 0x00181c20, 0x00151a1f, 0x00141b20, 0x00181f24, 0x00192026, 0x00161d24, 0x00141b22, 0x00181f27, 0x001a2229, 0x001b232b, 0x00182027, 0x00171f26, 0x00181f27, 0x00182028, 0x00192028, 0x00181f27, 0x00181f27, 0x001c2229, 0x001e242b, 0x001c222a, 0x001b2028, 0x001b2028, 0x00181e25, 0x001c2328, 0x001c2028, 0x00181c22, 0x00161a20, 0x00171a20, 0x0012171c, 0x000d1317, 0x00101519, 0x0014181c, 0x00171a1f, 0x00171c22, 0x00191e24, 0x001a1f26, 0x001b2028, 0x001b2028, 0x001c222a, 0x001f282f, 0x001d242c, 0x00171d24, 0x00171d25, 0x00181f25, 0x001e242a, 0x001b2026, 0x00181d23, 0x00181e24, 0x00191e26, 0x00191f26, 0x001b212a, 0x001f2530, 0x001d2430, 0x001a232c, 0x0018222b, 0x001c262f, 0x00202b33, 0x00212b34, 0x00202932, 0x001e2830, 0x001e2832, 0x00222c35, 0x00202b34, 0x00212b34, 0x0029343d, 0x00323c47, 0x0035404b, 0x00323d49, 0x002b3743, 0x00283440, 0x00283440, 0x0028333f, 0x0027303d, 0x0026303c, 0x0028303c, 0x002b333e, 0x002c343f, 0x0028303b, 0x0026303a, 0x0028323c, 0x002b3540, 0x002a343f, 0x0028333d, 0x0025313b, 0x0023303c, 0x00263440, 0x0025333f, 0x0022303b, 0x00202e38, 0x0024323d, 0x002b3a45, 0x00303f4c, 0x002d3c4a, 0x002c3d4c, 0x002d404e, 0x002f404f, 0x00314452, 0x00334555, 0x00344757, 0x00314555, 0x002c4251, 0x002b4150, 0x002e4453, 0x002e4454, 0x002d4454, 0x002f4755, 0x002f4655, 0x002d4352, 0x00293e4d, 0x00283c4a, 0x002a3f4c, 0x00293c4b, 0x00283c49, 0x00243846, 0x00203541, 0x001e333f, 0x00203541, 0x00223745, 0x00213847, 0x00203847, 0x00203848, 0x00203848, 0x00203848, 0x00213746, 0x00203444, 0x001d3240, 0x001c313f, 0x001c313f, 0x001b313f, 0x001b313f, 0x001a303d, 0x001a303d, 0x0019303c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182e3b, 0x00182e3b, 0x00172d3a, 0x00172d3a, 0x00172d3a, 0x00162b38, 0x00182a37, 0x00182a37, 0x00172935, 0x00172935, 0x00162935, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a36, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00152a37, 0x00152a37, 0x00142937, 0x00142836, 0x00142835, 0x00142734, 0x00142734, 0x00142734, 0x00142734, 0x00142734, 0x00112631, 0x00112630, 0x00102630, 0x000f2631, 0x000f2631, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00122531, 0x00132632, 0x00122531, 0x00102531, 0x00102531, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0015363b, 0x00173c40, 0x001a4044, 0x001b4649, 0x001c4b4e, 0x001f5154, 0x0021606b, 0x002fa4cb, 0x002a88a3, 0x00256063, 0x00256264, 0x00276467, 0x00266568, 0x00276668, 0x00276668, 0x00276668, 0x00276568, 0x00266467, 0x00276c75, 0x002c88a1, 0x00309fc3, 0x0030a0c4, 0x002986a1, 0x00236670, 0x0022585b, 0x00215659, 0x00205558, 0x00205558, 0x00205457, 0x00205457, 0x00205457, 0x00205457, 0x00205457, 0x00205457, 0x00205356, 0x00205356, 0x00205154, 0x001f5053, 0x001d4d50, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00183d41, 0x0017383c, 0x00153439, 0x00142e34, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1e28, 0x000c1f27, 0x000c1e27, 0x000e1f28, 0x000f1f28, 0x000f1e28, 0x00101d27, 0x00101d27, 0x000f1e27, 0x000e1e27, 0x000e1e27, 0x000c1e27, 0x000d1e27, 0x000f1f28, 0x0010202a, 0x0010202a, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010232d, 0x0010242e, 0x00112430, 0x00122531, 0x00142734, 0x00132936, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142b38, 0x00142b38, 0x00142b38, 0x00152c3b, 0x00172c3c, 0x00162d3c, 0x00162e39, 0x00162f39, 0x00142f39, 0x00142f39, 0x00162d39, 0x00162c39, 0x00152b38, 0x00142a37, 0x00142937, 0x00142835, 0x00142734, 0x00142733, 0x00142834, 0x00152834, 0x00162935, 0x00152a35, 0x00152a35, 0x00172935, 0x00172935, 0x00172936, 0x00162b38, 0x00152a38, 0x00152936, 0x00142835, 0x00142834, 0x00142834, 0x00142834, 0x00142834, 0x00142834, 0x00152834, 0x00162833, 0x00162934, 0x00172b35, 0x001a2f38, 0x001c313c, 0x001c313c, 0x001b313d, 0x001d343f, 0x00203541, 0x00243946, 0x00263c4a, 0x0028404d, 0x002a4450, 0x002c4451, 0x002c4450, 0x002d4350, 0x002f4450, 0x002c404c, 0x00283946, 0x00273745, 0x00263544, 0x00283847, 0x002a3b48, 0x002a3946, 0x00293844, 0x0024313e, 0x0024313c, 0x00243039, 0x0025303b, 0x0026323c, 0x0029353f, 0x002c3842, 0x002c3842, 0x0029353f, 0x002b3740, 0x002f3b45, 0x00303c45, 0x00323c47, 0x00343f49, 0x00353f4a, 0x00343d48, 0x00323a46, 0x002d3541, 0x0029303b, 0x00232831, 0x001c212a, 0x00171c24, 0x00161c22, 0x0014181f, 0x000e1419, 0x0011161c, 0x00171e25, 0x00182128, 0x00182027, 0x00151c21, 0x0013181e, 0x0012171c, 0x00171c23, 0x00181d24, 0x00171d24, 0x0010161e, 0x00161b22, 0x001e2328, 0x001d2226, 0x00181c20, 0x0014181d, 0x000d141a, 0x00151c22, 0x00181f24, 0x00181f26, 0x00182027, 0x001d262d, 0x001c262d, 0x001c242b, 0x00192229, 0x00182027, 0x00151e25, 0x00141c23, 0x00141b22, 0x00141c23, 0x00151c24, 0x00192028, 0x001a2028, 0x00181f27, 0x001a2028, 0x001b2129, 0x00181e25, 0x0020252c, 0x0020242b, 0x00181d24, 0x00171b21, 0x00181c22, 0x00161b20, 0x000e1317, 0x000f1418, 0x0012171b, 0x00171a1e, 0x00161b21, 0x00151a20, 0x00171c24, 0x001a1f27, 0x001c2028, 0x001c242b, 0x00202830, 0x0020282f, 0x00151c24, 0x00121820, 0x00141b21, 0x00181f25, 0x001b2026, 0x00181e24, 0x00161b22, 0x00151a21, 0x00161c24, 0x00181f28, 0x001e242f, 0x00222934, 0x001c252f, 0x00152028, 0x0019232c, 0x001c2730, 0x00202933, 0x00212b34, 0x00202b34, 0x00202b34, 0x00202b33, 0x00222c35, 0x00232c35, 0x00242e37, 0x002b3540, 0x00303a45, 0x00313c48, 0x002d3945, 0x002a3843, 0x002a3642, 0x002b3441, 0x0027313d, 0x00252f3a, 0x0028303c, 0x0029313c, 0x002b333e, 0x0028303b, 0x00252e38, 0x00242d38, 0x00252f39, 0x0027313c, 0x0027313c, 0x0025303a, 0x00202e38, 0x0024313c, 0x0024323e, 0x0024313c, 0x0023313b, 0x0022313c, 0x00283742, 0x0030404c, 0x0031404e, 0x002d3e4c, 0x002e404f, 0x002f4150, 0x00344755, 0x00334656, 0x00344757, 0x00324756, 0x002d4453, 0x002f4454, 0x00304856, 0x00304857, 0x002f4856, 0x002e4856, 0x002f4856, 0x002c4452, 0x00293f4d, 0x00283d4b, 0x002a3e4c, 0x00293c4b, 0x00283b48, 0x00243946, 0x00203742, 0x00213642, 0x00233844, 0x00233846, 0x00213847, 0x00203847, 0x00203848, 0x001f3848, 0x00203848, 0x00223847, 0x00203444, 0x001d3240, 0x001c313f, 0x001c313f, 0x001b313f, 0x001b313f, 0x0019303d, 0x0019303c, 0x0019303c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182e3b, 0x00182e3b, 0x00172d3a, 0x00172d3a, 0x00172d3a, 0x00162c38, 0x00182a37, 0x00182a37, 0x00172935, 0x00172935, 0x00162935, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a36, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00162b39, 0x00162b39, 0x00162b38, 0x00152a38, 0x00152937, 0x00152836, 0x00142835, 0x00142835, 0x00142835, 0x00142835, 0x00132733, 0x00122831, 0x00112832, 0x00102732, 0x00102732, 0x00122632, 0x00122632, 0x00112531, 0x00112531, 0x00112431, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00122531, 0x00132632, 0x00122531, 0x00102531, 0x00102531, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00122c32, 0x00143036, 0x0016363b, 0x00183c40, 0x001a4044, 0x001c474b, 0x001d4c50, 0x001f5154, 0x0021606b, 0x002fa4cb, 0x002986a0, 0x00245f61, 0x00256163, 0x00256364, 0x00266466, 0x00266466, 0x00266466, 0x00266466, 0x00276d76, 0x002c88a2, 0x0030a0c4, 0x002fa0c4, 0x002a88a4, 0x00246670, 0x0022595c, 0x00215659, 0x00205558, 0x00205457, 0x00205356, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x001f5154, 0x001f5053, 0x001d4f51, 0x001d4c50, 0x001c4a4d, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000f1f2a, 0x000f202a, 0x0010202a, 0x00102029, 0x00102029, 0x00101f28, 0x000f1f28, 0x000f1f28, 0x000e1f28, 0x000e1f28, 0x00101f28, 0x00102029, 0x00102029, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010202c, 0x0010212c, 0x0011232d, 0x0011232d, 0x0010232d, 0x0010232d, 0x0011242e, 0x0012252f, 0x00132630, 0x00142834, 0x00132936, 0x00132936, 0x00142b38, 0x00142b38, 0x00152c39, 0x00152c39, 0x00152c39, 0x00172c3b, 0x00182e3c, 0x00182e3c, 0x00182e39, 0x00172e39, 0x00162f39, 0x00162f39, 0x00172d39, 0x00162c39, 0x00162b37, 0x00152a36, 0x00142936, 0x00142835, 0x00142733, 0x00142733, 0x00142834, 0x00152834, 0x00162834, 0x00172935, 0x00172935, 0x00172935, 0x00172935, 0x00172936, 0x00162b38, 0x00152a38, 0x00152937, 0x00142836, 0x00142835, 0x00142734, 0x00142734, 0x00142734, 0x00142734, 0x00142834, 0x00142833, 0x00142834, 0x00172a36, 0x001a2d39, 0x001c303c, 0x001c303c, 0x001c313d, 0x001c303c, 0x001c2f3c, 0x001e3240, 0x00213744, 0x00273e4b, 0x002c4450, 0x002c4450, 0x002c4450, 0x002c4350, 0x002c414d, 0x00293d48, 0x00243744, 0x00283847, 0x00283847, 0x00293a48, 0x002b3b48, 0x002c3b48, 0x002b3947, 0x0024313f, 0x0024323c, 0x00202d38, 0x00212e38, 0x0025323c, 0x0029353f, 0x0028343e, 0x0028343e, 0x0028343d, 0x002c3841, 0x002e3a44, 0x002d3843, 0x00303b45, 0x00353f49, 0x0036404a, 0x00343e48, 0x00313944, 0x002b333c, 0x00262d36, 0x0020262e, 0x001c2028, 0x00181d25, 0x00171c24, 0x0013181f, 0x0010151c, 0x0013181e, 0x00182025, 0x00172025, 0x00151e24, 0x0010181e, 0x0010161c, 0x000f141a, 0x00161b22, 0x00151921, 0x00181e25, 0x00181e26, 0x001a1f26, 0x001c2026, 0x001c2025, 0x00181c20, 0x0013181c, 0x000f151b, 0x0012181f, 0x00131920, 0x00141c23, 0x001c232a, 0x00202930, 0x001c262d, 0x001a232a, 0x00182128, 0x00182028, 0x00182028, 0x00182028, 0x00151d25, 0x00141b23, 0x00181f27, 0x00171d25, 0x001b2129, 0x001d242c, 0x001c222a, 0x001b2129, 0x001c232b, 0x0022282f, 0x00242a30, 0x001c2027, 0x00181d24, 0x00181d24, 0x00181c22, 0x0011161a, 0x000f1418, 0x0014181c, 0x00181b20, 0x0014181f, 0x0012171d, 0x0010151d, 0x0010151d, 0x0012171f, 0x00192028, 0x001f272e, 0x00192129, 0x00131b22, 0x000c141b, 0x000e151b, 0x00171d23, 0x001c2027, 0x00191e24, 0x00171d24, 0x00141a22, 0x0010171f, 0x00141a23, 0x00181e29, 0x001c242f, 0x001f2832, 0x001b242d, 0x0018232b, 0x001c262f, 0x001c2730, 0x001c2730, 0x001e2830, 0x001e2831, 0x00202a32, 0x00252f38, 0x00273039, 0x00232d36, 0x0026303a, 0x002f3844, 0x00333e4a, 0x00303c48, 0x002c3a45, 0x002d3944, 0x002c3643, 0x0028313e, 0x00242e39, 0x0027303a, 0x0028303b, 0x00272f39, 0x00262e39, 0x00252e38, 0x00242e39, 0x00222c36, 0x00222c36, 0x00242e39, 0x0024303b, 0x0023303a, 0x0024313c, 0x0025333e, 0x0025343f, 0x0025333c, 0x0023323c, 0x0024343f, 0x002c3c48, 0x00324150, 0x002c3e4c, 0x00293e4c, 0x002c404e, 0x00334755, 0x00344757, 0x00344858, 0x00344958, 0x002f4554, 0x00304856, 0x00344a59, 0x00324958, 0x002f4856, 0x002f4857, 0x00304857, 0x002c4453, 0x002a404f, 0x002a3f4c, 0x00293e4c, 0x00293c4b, 0x00283b49, 0x00253a47, 0x00233844, 0x00233844, 0x00243945, 0x00243947, 0x00223848, 0x00203847, 0x00203848, 0x00203848, 0x00213848, 0x00233847, 0x00203544, 0x001d3140, 0x001c303e, 0x001c303f, 0x001b313f, 0x001b313f, 0x0019303d, 0x0019303c, 0x0019303c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182e3b, 0x00182e3b, 0x00172d3a, 0x00172d3a, 0x00172d3a, 0x00152b38, 0x00172936, 0x00172935, 0x00162834, 0x00152834, 0x00152834, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152b37, 0x00162b38, 0x00162c39, 0x00162c39, 0x00162c39, 0x00162c39, 0x00172c3a, 0x00172c3a, 0x00162c39, 0x00162b38, 0x00162b38, 0x00172938, 0x00172937, 0x00172937, 0x00162836, 0x00162836, 0x00142834, 0x00142834, 0x00142834, 0x00132834, 0x00132834, 0x00132632, 0x00132632, 0x00132632, 0x00132632, 0x00132632, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x00142431, 0x00142532, 0x00132431, 0x00122431, 0x00122431, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00153036, 0x0016363b, 0x00183c40, 0x001a4044, 0x001b4649, 0x001d4c50, 0x001e5053, 0x0021606a, 0x002fa4cb, 0x0029859f, 0x00245e60, 0x00256062, 0x00256163, 0x00256264, 0x00256264, 0x00276c76, 0x002c8ba5, 0x0030a0c4, 0x0030a1c5, 0x002b88a4, 0x00246771, 0x0022595c, 0x00215659, 0x00205558, 0x00205356, 0x00205254, 0x001f5154, 0x001f5154, 0x001e5053, 0x001e5053, 0x001e5053, 0x001f5154, 0x001f5154, 0x001f5154, 0x001f5154, 0x001f5154, 0x001f5053, 0x001d4f51, 0x001d4d50, 0x001d4b4e, 0x001c484c, 0x001b4649, 0x001a4245, 0x00183f43, 0x00183a3e, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202a, 0x000f202a, 0x000f202a, 0x000f202b, 0x000f202b, 0x0010202b, 0x0011202a, 0x0011202a, 0x00102029, 0x000f1f28, 0x000f1f28, 0x000f1f28, 0x00101f28, 0x00102029, 0x00102029, 0x00102029, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010202c, 0x0010212c, 0x0011232d, 0x0012242e, 0x0010232d, 0x0010242e, 0x0011242e, 0x0012252f, 0x00132630, 0x00142834, 0x00132936, 0x00132936, 0x00142b38, 0x00152c39, 0x00162c39, 0x00162c3a, 0x00162d3a, 0x00182d3c, 0x00182e3d, 0x00182e3c, 0x00182e39, 0x00182e39, 0x00162e39, 0x00162f39, 0x00172d39, 0x00162c38, 0x00152a36, 0x00152935, 0x00142835, 0x00142734, 0x00142733, 0x00142632, 0x00142833, 0x00152834, 0x00162834, 0x00172935, 0x00172935, 0x00172935, 0x00172935, 0x00172936, 0x00162a38, 0x00152a38, 0x00152937, 0x00142836, 0x00142835, 0x00142734, 0x00142734, 0x00142734, 0x00142734, 0x00142734, 0x00142733, 0x00142733, 0x00152834, 0x00192c38, 0x001b2d3a, 0x001b2d3a, 0x001b2d39, 0x00182a37, 0x00152834, 0x00172938, 0x001a2e3c, 0x00233846, 0x002c4350, 0x002c4450, 0x002c4350, 0x002c414e, 0x00293e4a, 0x00283b47, 0x00243744, 0x002b3b4a, 0x002b3c4a, 0x00283948, 0x00283947, 0x002c3c4a, 0x002d3b49, 0x00253240, 0x0025333d, 0x001f2c36, 0x00202d38, 0x0024313c, 0x0027333d, 0x0024303a, 0x0026323c, 0x0026323c, 0x002b3741, 0x002e3a44, 0x002c3741, 0x002e3944, 0x00343e49, 0x0038424c, 0x00343e48, 0x00303640, 0x00282f38, 0x00202830, 0x001c222a, 0x001a2028, 0x001a2028, 0x00181e26, 0x00151b23, 0x00161b23, 0x00192027, 0x00192027, 0x00131c21, 0x00141c22, 0x0011181e, 0x0011171d, 0x0012171d, 0x00171c23, 0x00181c24, 0x00181f27, 0x001b2129, 0x001c2129, 0x001c2228, 0x001c2128, 0x00191d24, 0x0014191f, 0x0012181f, 0x0012191f, 0x00141c21, 0x00181f27, 0x00202830, 0x00232c33, 0x001f2830, 0x001d2730, 0x001b242d, 0x001d262f, 0x001e2830, 0x0018212a, 0x00141c25, 0x00181f28, 0x00192029, 0x00141c24, 0x001a212a, 0x001e262f, 0x001e252f, 0x001b222c, 0x00202831, 0x00242b33, 0x00272d34, 0x0021272e, 0x001a1e26, 0x00191e24, 0x00181f25, 0x00171c22, 0x00141a20, 0x00181c23, 0x00191d24, 0x00141920, 0x0013171f, 0x00141921, 0x0013171f, 0x0011171f, 0x00141a22, 0x001d252c, 0x001a232a, 0x001b242b, 0x00131b22, 0x00131b20, 0x00161d23, 0x00192026, 0x00141b21, 0x00181d25, 0x00181e25, 0x000f151c, 0x00111820, 0x00131923, 0x00141c26, 0x001f2831, 0x001f2931, 0x0019242c, 0x0019242c, 0x001c2730, 0x001b252f, 0x001a242d, 0x001a242e, 0x001d2730, 0x00232d36, 0x00263039, 0x00232d36, 0x00222c36, 0x0028323c, 0x002d3844, 0x00303c48, 0x002c3945, 0x002c3844, 0x002b3541, 0x0028323e, 0x00242d38, 0x00242c38, 0x00272f3a, 0x00262e38, 0x00242c38, 0x00252e38, 0x00242f39, 0x00222c37, 0x00202a34, 0x00212c36, 0x00242f3a, 0x0026333d, 0x0025333e, 0x00273440, 0x00263440, 0x0026343f, 0x0023323e, 0x0023323e, 0x002a3946, 0x00324150, 0x002e404e, 0x00273c49, 0x00283e4c, 0x00324856, 0x00334857, 0x00344858, 0x00364b5b, 0x00314856, 0x00304655, 0x00344b59, 0x00344b59, 0x002f4755, 0x002f4958, 0x00304a58, 0x002e4454, 0x002c4352, 0x002b404e, 0x00293e4c, 0x00283c4a, 0x00283c49, 0x00263b48, 0x00233945, 0x00243844, 0x00243945, 0x00253947, 0x00233948, 0x00203847, 0x00203848, 0x00203848, 0x00223848, 0x00233847, 0x00203543, 0x001c313f, 0x001c303e, 0x001c303e, 0x001b313f, 0x001b313f, 0x0019303d, 0x0019303c, 0x0019303c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182e3b, 0x00182e3b, 0x00172d3a, 0x00172d3a, 0x00172c3a, 0x00152b38, 0x00172936, 0x00172935, 0x00152834, 0x00152834, 0x00152834, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00162b37, 0x00172c39, 0x00172c39, 0x00172c39, 0x00172c39, 0x00172c39, 0x00172d3b, 0x00182e3b, 0x00172d3a, 0x00162c3a, 0x00162c39, 0x00182a38, 0x00182a38, 0x00182a38, 0x00172938, 0x00172937, 0x00142934, 0x00142834, 0x00142835, 0x00142836, 0x00142836, 0x00142733, 0x00132632, 0x00132632, 0x00132632, 0x00132632, 0x00122430, 0x00112430, 0x00112430, 0x00112430, 0x00122430, 0x00142431, 0x00142532, 0x00142431, 0x00122431, 0x00122431, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00122c32, 0x00143036, 0x0016363b, 0x00183c40, 0x00194044, 0x001b4649, 0x001d4b4e, 0x001f5053, 0x0021606a, 0x002ea3ca, 0x0028859f, 0x00245c5f, 0x00245e60, 0x00246062, 0x00266c77, 0x002c8aa5, 0x0030a0c4, 0x0030a1c5, 0x002a89a4, 0x00246874, 0x0022595c, 0x00215659, 0x00205558, 0x00205356, 0x00205254, 0x001f5053, 0x001e4f51, 0x001e4f51, 0x001d4d50, 0x001d4d50, 0x001d4f51, 0x001d4f51, 0x001e5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001d4f51, 0x001e4d50, 0x001c4b4e, 0x001c474b, 0x001b4649, 0x001a4245, 0x00183f43, 0x00183a3e, 0x00153439, 0x00143036, 0x00132c32, 0x00102a30, 0x0013282e, 0x0013242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010202c, 0x0010202b, 0x0011202b, 0x0011202b, 0x0011202a, 0x0010202a, 0x0010202a, 0x00102029, 0x00102029, 0x00102029, 0x00102029, 0x00102029, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010222c, 0x0011232c, 0x0011232d, 0x0012242e, 0x0011242e, 0x0011242e, 0x0011242f, 0x00122530, 0x00132631, 0x00142834, 0x00142836, 0x00142936, 0x00142b38, 0x00142b38, 0x00152c39, 0x00162c39, 0x00162c39, 0x00172c3b, 0x00182d3c, 0x00182c3b, 0x00182c39, 0x00182c39, 0x00172d39, 0x00172d39, 0x00162c38, 0x00162a37, 0x00152835, 0x00152834, 0x00152734, 0x00152734, 0x00152632, 0x00142632, 0x00152732, 0x00162832, 0x00172833, 0x00162935, 0x00162935, 0x00162935, 0x00162936, 0x00172937, 0x00182a38, 0x00182a38, 0x00182938, 0x00172937, 0x00162836, 0x00142834, 0x00142834, 0x00142734, 0x00142734, 0x00142733, 0x00162632, 0x00152731, 0x00162832, 0x00182934, 0x00182834, 0x00182731, 0x00162430, 0x0012212e, 0x0010202d, 0x00132431, 0x00162836, 0x001f3340, 0x002c404f, 0x002e4451, 0x002c4450, 0x002b404c, 0x00283d49, 0x00283c48, 0x00253844, 0x002c3d4b, 0x002c3f4c, 0x00283a48, 0x00283a48, 0x002f3f4c, 0x002c3a48, 0x0025323f, 0x0023303a, 0x001f2c36, 0x0024303a, 0x0024303a, 0x0025313b, 0x00232f39, 0x0026313c, 0x0026323c, 0x002c3843, 0x002c3944, 0x002a3641, 0x002d3a44, 0x00343f4a, 0x00353f4a, 0x00333a45, 0x002c323c, 0x00222833, 0x00192028, 0x00181f26, 0x00192028, 0x00192128, 0x00151d24, 0x00141b23, 0x00151c24, 0x00181f26, 0x00131920, 0x000d151b, 0x00151d23, 0x00141c21, 0x00141b20, 0x00141920, 0x00141c22, 0x00182027, 0x001c242c, 0x001b232c, 0x001d242c, 0x001c222a, 0x001a2028, 0x001b2027, 0x001c2128, 0x00192028, 0x001a2128, 0x00212a31, 0x00232c34, 0x00242c35, 0x00242d36, 0x00222b34, 0x00212c35, 0x001e2830, 0x001f2932, 0x001e2830, 0x00141e26, 0x00131c24, 0x00161e27, 0x00171f28, 0x0018202a, 0x001c242d, 0x001c242e, 0x001e272f, 0x001c252d, 0x00222b33, 0x00252c34, 0x00272e35, 0x00282f37, 0x001f242c, 0x001c2128, 0x001b2128, 0x00181e25, 0x00181e25, 0x00191e25, 0x00191d24, 0x00171c23, 0x00131820, 0x00161c23, 0x00141a22, 0x00121820, 0x00131921, 0x001c242c, 0x001c242c, 0x001c262e, 0x001a232b, 0x00172026, 0x00182027, 0x00182127, 0x00131b21, 0x00131921, 0x00181f26, 0x0010161d, 0x0011181f, 0x0010171f, 0x0010161e, 0x00181f28, 0x00202a32, 0x00202a32, 0x001e2830, 0x001e2830, 0x001e2833, 0x001c2631, 0x001e2832, 0x001e2832, 0x001f2833, 0x00222c37, 0x00242e37, 0x00222c36, 0x0026303b, 0x002a3541, 0x002d3844, 0x002c3643, 0x002b3440, 0x002b3440, 0x0028313d, 0x00242d38, 0x00232b36, 0x00252d38, 0x0028303b, 0x0028303b, 0x00252f39, 0x00242d38, 0x00232c38, 0x00202a37, 0x00202b37, 0x00232d39, 0x0026333d, 0x0028343f, 0x00283440, 0x00263441, 0x00253441, 0x00243442, 0x00243341, 0x00273745, 0x002f3f4e, 0x002c3f4d, 0x00283d4b, 0x00273d4b, 0x002f4454, 0x00314655, 0x00314655, 0x00364c5b, 0x00334958, 0x00304655, 0x00334958, 0x00324a59, 0x00304858, 0x00304a5a, 0x00314c5c, 0x00314859, 0x00304656, 0x002c4150, 0x00283d4c, 0x00273c49, 0x00263b48, 0x00243946, 0x00223845, 0x00233845, 0x00243846, 0x00243846, 0x00233847, 0x00213846, 0x00213847, 0x00213847, 0x00223848, 0x00223847, 0x00203544, 0x001c3240, 0x001c303f, 0x001b303f, 0x001b303e, 0x001c303e, 0x001b303d, 0x001a303c, 0x001a303c, 0x001a2e3c, 0x001a2e3c, 0x00182f3c, 0x00182f3c, 0x00182d3b, 0x00182d3a, 0x00182c39, 0x00182c39, 0x00182c39, 0x00172b38, 0x00172936, 0x00172936, 0x00172935, 0x00172935, 0x00162935, 0x00162a36, 0x00162a37, 0x00162a37, 0x00162b37, 0x00162b38, 0x00162b39, 0x00172c39, 0x00172c39, 0x00172c39, 0x00182c3a, 0x00182e3b, 0x00182e3b, 0x00172e3b, 0x00172e3b, 0x00172c3a, 0x00182c3a, 0x00182c39, 0x00182b39, 0x00182b38, 0x00172b38, 0x00152a37, 0x00152a36, 0x00152a36, 0x00152a36, 0x00142936, 0x00142834, 0x00142733, 0x00142632, 0x00142532, 0x00132531, 0x00132431, 0x00122431, 0x00122430, 0x00122430, 0x00122430, 0x00142431, 0x00142532, 0x00142431, 0x00122431, 0x00122431, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0015363b, 0x00183a3e, 0x00194044, 0x001b4448, 0x001c4a4d, 0x001d4d50, 0x00215d68, 0x002ea3ca, 0x0028849f, 0x00235b5e, 0x00246a76, 0x002b8ba6, 0x0030a0c6, 0x002fa0c5, 0x002a8ba7, 0x00246772, 0x0022585c, 0x00215659, 0x00205558, 0x00205356, 0x00205154, 0x001f5053, 0x001d4d50, 0x001d4c50, 0x001d4c50, 0x001d4b4e, 0x001d4b4e, 0x001e4c50, 0x001e4c50, 0x001d4d50, 0x001d4f51, 0x001e4f51, 0x001f5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001d4f51, 0x001e4d50, 0x001d4b4e, 0x001c484c, 0x001b4649, 0x001a4245, 0x00183f43, 0x00183a3e, 0x00143439, 0x00153338, 0x00132c32, 0x00102a30, 0x0013282e, 0x0013242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0010212a, 0x0010212a, 0x0010212a, 0x0010222c, 0x0010222c, 0x0010212c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011202c, 0x0011202c, 0x0010212a, 0x0010212a, 0x00102029, 0x00102029, 0x00102029, 0x0010202b, 0x0010202b, 0x0010212b, 0x0010222b, 0x0012242c, 0x0012242c, 0x0012242e, 0x0012242e, 0x0012242f, 0x00122431, 0x00122431, 0x00132632, 0x00142734, 0x00142835, 0x00142936, 0x00142b38, 0x00142b38, 0x00152b38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00172b39, 0x00182b39, 0x00182b39, 0x00162a38, 0x00152a38, 0x00152936, 0x00142834, 0x00142834, 0x00162733, 0x00162732, 0x00162733, 0x00152631, 0x00152631, 0x00152731, 0x00162832, 0x00152832, 0x00142834, 0x00142834, 0x00142835, 0x00142836, 0x00152936, 0x00182a38, 0x00182a38, 0x00172a38, 0x00172a38, 0x00172936, 0x00152834, 0x00142832, 0x00142730, 0x0014262f, 0x00162530, 0x00182530, 0x0016242c, 0x0016242c, 0x0014232c, 0x0014202a, 0x00132029, 0x00121f29, 0x00101d27, 0x00101f2a, 0x00142430, 0x00182b37, 0x001e333f, 0x0028404c, 0x002c4552, 0x002c4451, 0x002b414c, 0x002c404c, 0x002b404b, 0x00263b47, 0x00293d4b, 0x002c404d, 0x00283c48, 0x002b3e4a, 0x0030404c, 0x002b3945, 0x0026343f, 0x00202e38, 0x00212e38, 0x0028343d, 0x0026303a, 0x0025303a, 0x00243039, 0x0025303b, 0x0026313d, 0x002a3743, 0x002b3844, 0x00283742, 0x002c3945, 0x00323e4a, 0x00333d49, 0x002f3843, 0x00283039, 0x0020272f, 0x00171f27, 0x00182028, 0x00192128, 0x00172027, 0x00121b22, 0x00111a21, 0x00141c23, 0x00151c24, 0x0010171e, 0x0011181d, 0x00192025, 0x00192025, 0x00181e26, 0x00171e25, 0x00151f26, 0x00182329, 0x00202830, 0x001e272e, 0x001f282f, 0x00182128, 0x001a2229, 0x00212830, 0x00242c34, 0x001c242b, 0x00252d36, 0x002c363f, 0x0027323c, 0x0027313c, 0x0028323c, 0x0027303b, 0x00232d38, 0x00202b34, 0x00212a33, 0x001f272e, 0x001b2429, 0x00182027, 0x00161e27, 0x0018212a, 0x001c242d, 0x00202933, 0x00202932, 0x00212c33, 0x001e282f, 0x00232c33, 0x00242d34, 0x00272f36, 0x002b323a, 0x0020272e, 0x001a2028, 0x00192027, 0x00192027, 0x00181d25, 0x00191e26, 0x001a1e27, 0x001a2028, 0x00181f26, 0x00171d24, 0x00171d26, 0x00151c25, 0x00182029, 0x00202831, 0x001d2730, 0x001c2730, 0x001c262f, 0x00182229, 0x001b242c, 0x001b242b, 0x00192128, 0x00121920, 0x001b2128, 0x0012181e, 0x0013191f, 0x0012191f, 0x0010171d, 0x00121920, 0x001d252c, 0x00202930, 0x00202a30, 0x00202a31, 0x00202b34, 0x00202b35, 0x00222c36, 0x00202a34, 0x00202933, 0x00202b34, 0x00253038, 0x00242f38, 0x00242e38, 0x0027303c, 0x0027303c, 0x0028323d, 0x002a323d, 0x0028303c, 0x0028303b, 0x00252e38, 0x00212b34, 0x00202a34, 0x00252f3a, 0x0029333d, 0x0029333d, 0x0028313c, 0x00252f39, 0x00232c38, 0x00202a37, 0x00202b36, 0x00232f39, 0x0028343d, 0x0028343f, 0x0027343f, 0x00253441, 0x00273844, 0x00263946, 0x00273847, 0x002e3f4e, 0x002e4050, 0x002b404f, 0x00283e4c, 0x002c4150, 0x00314655, 0x00304454, 0x00324858, 0x00334958, 0x00304757, 0x00304858, 0x00304959, 0x00304a5a, 0x00304c5e, 0x00334f60, 0x00344d5f, 0x0034495a, 0x002d4453, 0x00283e4c, 0x00263b47, 0x00243a46, 0x00223845, 0x00203744, 0x00203744, 0x00213744, 0x00213644, 0x00213643, 0x00223743, 0x00223844, 0x00223945, 0x00223847, 0x00213847, 0x00203544, 0x001c3241, 0x001b3040, 0x001b2f3f, 0x001b2e3c, 0x001b2e3c, 0x001a2e3c, 0x001a2d3c, 0x001a2e3c, 0x00192d3c, 0x00192e3c, 0x00182e3b, 0x00182e3b, 0x00182c39, 0x00182c38, 0x00182c38, 0x00182b38, 0x00182a37, 0x00182a37, 0x00172936, 0x00172936, 0x00172936, 0x00172936, 0x00172936, 0x00172937, 0x00172937, 0x00162a38, 0x00172c39, 0x00172c39, 0x00162b38, 0x00162b38, 0x00162c39, 0x00182c3a, 0x00182c3a, 0x00182e3b, 0x00182e3b, 0x00172e3b, 0x00162e3b, 0x00162e3b, 0x00182d3b, 0x00182d3b, 0x00172d39, 0x00162c38, 0x00162c38, 0x00162b39, 0x00162b38, 0x00162b38, 0x00162b37, 0x00152a36, 0x00152834, 0x00142834, 0x00142633, 0x00142431, 0x00132430, 0x00142431, 0x00142532, 0x00142532, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x00132431, 0x00122431, 0x00122431, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00122c32, 0x00143036, 0x00153439, 0x00183a3e, 0x00183f43, 0x001a4347, 0x001c474b, 0x001d4c50, 0x00205c68, 0x002da2ca, 0x00288caa, 0x00298ba8, 0x002ea0c5, 0x002ea0c6, 0x002989a6, 0x00246874, 0x0022595c, 0x00215659, 0x00205457, 0x00205356, 0x001f5154, 0x001e4f51, 0x001e4d50, 0x001d4b4e, 0x001c4a4d, 0x001d4a4d, 0x001d4a4d, 0x001d4a4d, 0x001d4a4d, 0x001c4b4e, 0x001d4b4e, 0x001e4c50, 0x001d4f51, 0x001e5053, 0x001f5053, 0x001f5154, 0x001f5154, 0x001f5154, 0x001f5053, 0x001e4f51, 0x001d4c50, 0x001d4a4d, 0x001b4649, 0x001a4347, 0x00183f43, 0x00183a3e, 0x0015363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0010212a, 0x0010212a, 0x0010212a, 0x0010222c, 0x0010222c, 0x0010222c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011202c, 0x0010212a, 0x00102029, 0x00102029, 0x00102029, 0x00102029, 0x0010202b, 0x0010202b, 0x0010212b, 0x0011232c, 0x0012242c, 0x0012242c, 0x0012242e, 0x0012242e, 0x0012242f, 0x00122431, 0x00122431, 0x00132632, 0x00142734, 0x00142834, 0x00152935, 0x00152b38, 0x00152b38, 0x00152b38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00172b38, 0x00182b39, 0x00182a39, 0x00152a37, 0x00142836, 0x00142835, 0x00142834, 0x00142834, 0x00152733, 0x00162732, 0x00152633, 0x00152631, 0x00152631, 0x00152732, 0x00162832, 0x00162832, 0x00142734, 0x00142734, 0x00142734, 0x00142835, 0x00142835, 0x00172935, 0x00172935, 0x00162935, 0x00162935, 0x00162834, 0x00162832, 0x00142732, 0x00142730, 0x0015262f, 0x0016242f, 0x0015232c, 0x00122028, 0x00101d25, 0x000f1c24, 0x00101c25, 0x00111e27, 0x0014212a, 0x0016242c, 0x00192831, 0x001c2c36, 0x001f303b, 0x00233843, 0x002b4350, 0x002f4854, 0x00304956, 0x00324854, 0x00324854, 0x002d434f, 0x00273c49, 0x00293f4c, 0x00293f4d, 0x00273c49, 0x002c404d, 0x002e404c, 0x002c3b48, 0x00293743, 0x0023303b, 0x0024313b, 0x0029343e, 0x0027313c, 0x0025303a, 0x00242e38, 0x00242e38, 0x0027323e, 0x002a3541, 0x002c3844, 0x00293843, 0x00283843, 0x002d3b46, 0x002f3a46, 0x002a3440, 0x00202931, 0x001b242b, 0x00182229, 0x001c242c, 0x00182128, 0x00161f28, 0x00141d25, 0x00131c23, 0x00131b22, 0x00141a22, 0x00141a21, 0x00171e24, 0x001c2329, 0x001b2228, 0x001a2028, 0x001a2129, 0x0018232a, 0x001c252c, 0x00212c32, 0x00202a31, 0x00212c33, 0x001d272d, 0x001f2830, 0x00283138, 0x00242d35, 0x001c252e, 0x00242e36, 0x00243038, 0x0028343e, 0x002a3540, 0x002b3540, 0x0028313c, 0x00242f39, 0x00222c37, 0x00232c35, 0x00212a31, 0x00212a30, 0x001e272c, 0x001c242c, 0x001d262f, 0x001f2830, 0x00232d36, 0x00263039, 0x0028333a, 0x00232c34, 0x00222932, 0x00262c35, 0x00293038, 0x00262d35, 0x001f252f, 0x001e242c, 0x00151c24, 0x001c2229, 0x001c232a, 0x001c212a, 0x001c212b, 0x001c232b, 0x001d242c, 0x00192028, 0x00182028, 0x001b212b, 0x001e2730, 0x00212a33, 0x001f2830, 0x001e2830, 0x001b242d, 0x00182329, 0x0019242a, 0x001a242b, 0x001c242b, 0x00151e25, 0x001b2228, 0x00141b21, 0x00161c22, 0x00151c22, 0x00141c21, 0x00121920, 0x001a2128, 0x00242c34, 0x00232c34, 0x00202b32, 0x001c2831, 0x001f2833, 0x00222c37, 0x00232c37, 0x00212c35, 0x00202b34, 0x00242e37, 0x00263039, 0x00242d37, 0x00222c37, 0x00212b35, 0x00252f3a, 0x0028303c, 0x0028303a, 0x00252d38, 0x00242e37, 0x00222c35, 0x00202a34, 0x0025303a, 0x0028323c, 0x0028323c, 0x0028333d, 0x0028323d, 0x00242e3b, 0x00222c38, 0x00202c37, 0x00212d37, 0x0024303a, 0x0029343f, 0x00293641, 0x00283643, 0x00283a46, 0x002a3d4b, 0x00293c4b, 0x00304152, 0x00314454, 0x002e4453, 0x002b4150, 0x002d4252, 0x00314655, 0x002f4454, 0x002d4454, 0x002e4454, 0x002f4554, 0x00304758, 0x002f4858, 0x00304a5a, 0x00335060, 0x00375465, 0x00385364, 0x00374f60, 0x00314858, 0x002a404f, 0x00263b48, 0x00253a47, 0x00233946, 0x00203643, 0x00203542, 0x00203442, 0x00203440, 0x00203440, 0x00223742, 0x00233944, 0x00243c46, 0x00243a48, 0x00223848, 0x001f3544, 0x001c3241, 0x001b3040, 0x001a2e3e, 0x00192c3b, 0x00192c3a, 0x00192c3a, 0x001a2d3b, 0x001a2d3b, 0x00182d3b, 0x00182d3b, 0x00182d3b, 0x00172d3a, 0x00182c39, 0x00182c38, 0x00182c38, 0x00182a37, 0x00182a37, 0x00182936, 0x00172935, 0x00172935, 0x00172935, 0x00172935, 0x00172935, 0x00172937, 0x00172938, 0x00162a38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00172c39, 0x00182c3a, 0x00182d3b, 0x00182e3b, 0x00182e3b, 0x00172e3b, 0x00162e3b, 0x00162e3b, 0x00182e3b, 0x00182e3b, 0x00172e3a, 0x00162c38, 0x00152c38, 0x00172c39, 0x00162b38, 0x00162b38, 0x00162b37, 0x00162b36, 0x00162834, 0x00142834, 0x00142633, 0x00142431, 0x00132430, 0x00142431, 0x00142532, 0x00142532, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x00132431, 0x00122431, 0x00122431, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00111f27, 0x00102229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4245, 0x001b4649, 0x001c4a4d, 0x00205964, 0x002ca1c9, 0x002da2cb, 0x002ca0c6, 0x002888a6, 0x00236674, 0x00215659, 0x00205558, 0x00205356, 0x00205254, 0x001f5154, 0x001e4f51, 0x001d4c50, 0x001d4b4e, 0x001c484c, 0x001c474b, 0x001c474b, 0x001c4649, 0x001c4649, 0x001c474b, 0x001c484c, 0x001d4a4d, 0x001c4b4e, 0x001e4c50, 0x001d4f51, 0x001f5053, 0x001f5154, 0x00205254, 0x00205254, 0x00205254, 0x001f5154, 0x001e5053, 0x001d4d50, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0010212a, 0x0010212a, 0x0010222b, 0x0010222c, 0x0010222d, 0x0011222c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011202c, 0x000f2029, 0x00102029, 0x00102029, 0x00102029, 0x00102029, 0x0011202c, 0x0011202c, 0x0011222c, 0x0011232c, 0x0012242c, 0x0012242c, 0x0013232e, 0x0014242e, 0x0014242f, 0x00142530, 0x00142530, 0x00142631, 0x00142732, 0x00152834, 0x00162834, 0x00162a37, 0x00162a37, 0x00162b38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00172a38, 0x00182a38, 0x00172938, 0x00152836, 0x00142835, 0x00142835, 0x00142835, 0x00142734, 0x00142633, 0x00142532, 0x00152632, 0x00162732, 0x00162832, 0x00162832, 0x00162832, 0x00152732, 0x00152633, 0x00152633, 0x00142734, 0x00142734, 0x00142734, 0x00172834, 0x00172834, 0x00162834, 0x00152834, 0x00152834, 0x00152731, 0x00152631, 0x00152630, 0x0015252e, 0x0014222c, 0x00131f29, 0x000f1b24, 0x000d1a22, 0x00101c25, 0x0015212c, 0x0018252f, 0x001c2b34, 0x00202f38, 0x0021313c, 0x0023343e, 0x00233742, 0x00253c48, 0x002c4452, 0x00314c59, 0x0036505e, 0x0038505d, 0x00354c59, 0x002d4451, 0x00283f4c, 0x002b414e, 0x0029404e, 0x00283e4c, 0x002d4150, 0x002f404d, 0x002f3c4a, 0x00283642, 0x0023303b, 0x0025333c, 0x002b3741, 0x0028333d, 0x0027313c, 0x00242e38, 0x00242f38, 0x0028333e, 0x00293541, 0x002c3844, 0x002a3844, 0x002b3b46, 0x002e3c47, 0x002e3945, 0x00242e3a, 0x001b242d, 0x00182329, 0x001a242b, 0x001c262d, 0x00182129, 0x00162029, 0x00172028, 0x00161f26, 0x00151e25, 0x00121921, 0x00131920, 0x00181f24, 0x001b2228, 0x001b2127, 0x001c232a, 0x00222931, 0x00232c34, 0x00212c33, 0x00202a31, 0x00263038, 0x002c373f, 0x00243038, 0x00242f38, 0x002e3841, 0x00232c36, 0x001d2830, 0x00232d36, 0x0026333b, 0x002c3741, 0x002c3841, 0x002e3843, 0x002c3741, 0x0029343e, 0x0028323c, 0x0028303a, 0x00252d34, 0x00222a30, 0x001f282e, 0x00212932, 0x00242c34, 0x00252e37, 0x0029343c, 0x002c363f, 0x0029333b, 0x00232a32, 0x00202830, 0x0020262e, 0x00212830, 0x00252c34, 0x00202730, 0x0020262f, 0x00161c24, 0x001a2028, 0x001d242c, 0x001d242d, 0x001e242d, 0x0020262e, 0x001f252c, 0x001b2129, 0x001b2129, 0x001d242c, 0x001c242c, 0x001e262f, 0x001e2730, 0x001e2830, 0x001c262e, 0x00182229, 0x0019242b, 0x001c262f, 0x001a232c, 0x001a222b, 0x001b232a, 0x00171d24, 0x00192026, 0x00192026, 0x00182025, 0x00141b22, 0x00161e25, 0x00222a31, 0x00273037, 0x00212c34, 0x001e2a34, 0x001c2731, 0x001f2934, 0x00232c37, 0x00202b34, 0x001d2830, 0x001c2730, 0x00212b34, 0x00242f39, 0x00232d38, 0x00202934, 0x00222b36, 0x00252d38, 0x00252e38, 0x00242c38, 0x00242d37, 0x00242e37, 0x00242f39, 0x0028323c, 0x002a343f, 0x0029343e, 0x0028333d, 0x0028323c, 0x00252f3b, 0x0026303c, 0x0025303b, 0x00232f39, 0x00222e3a, 0x0028343f, 0x002c3743, 0x002b3945, 0x00293b47, 0x002b3e4c, 0x00293b4b, 0x00324354, 0x0036495b, 0x00324758, 0x00304656, 0x00324657, 0x00324656, 0x002d4352, 0x002c4251, 0x002c4352, 0x00304656, 0x00314859, 0x002f485a, 0x002f4a5b, 0x00345163, 0x003a576a, 0x003c5668, 0x00395264, 0x00344c5c, 0x002e4654, 0x0029404d, 0x00283e4b, 0x00253c49, 0x00233844, 0x00203541, 0x001e3340, 0x001c323f, 0x001c313d, 0x00203440, 0x00233944, 0x00243c47, 0x00243b47, 0x00213845, 0x001e3442, 0x001b313f, 0x001b303d, 0x001a2e3c, 0x00182c39, 0x00182c39, 0x00182c3a, 0x00182c3a, 0x00192c3b, 0x00182d3b, 0x00182d3b, 0x00172d3a, 0x00172c3a, 0x00182c39, 0x00192b39, 0x00192a38, 0x00192a38, 0x00182938, 0x00182936, 0x00172935, 0x00172935, 0x00172935, 0x00172935, 0x00172935, 0x00162835, 0x00152835, 0x00152935, 0x00152a36, 0x00162b38, 0x00162b38, 0x00162b38, 0x00172c39, 0x00182c3a, 0x00182d3b, 0x00182e3c, 0x00182e3c, 0x00182e3c, 0x00182e3c, 0x00182e3c, 0x00182e3b, 0x00182e3b, 0x00182e3b, 0x00172d39, 0x00152c38, 0x00172c39, 0x00162b38, 0x00162b38, 0x00162b37, 0x00162b36, 0x00162834, 0x00152834, 0x00142733, 0x00142532, 0x00142431, 0x00142431, 0x00142431, 0x00132430, 0x00122430, 0x00122430, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00102a30, 0x00132c32, 0x00143036, 0x0016363b, 0x00183a3e, 0x00183f43, 0x001a4347, 0x001c474b, 0x001d4b50, 0x00216a7e, 0x0025809b, 0x00206270, 0x00205256, 0x00205254, 0x00205254, 0x001f5154, 0x001e5053, 0x001d4d50, 0x001d4c50, 0x001d4b4e, 0x001c484c, 0x001c474b, 0x001b4649, 0x001a4448, 0x001a4448, 0x001a4448, 0x001a4448, 0x001c4649, 0x001c474b, 0x001d484c, 0x001c4b4e, 0x001d4d50, 0x001e5053, 0x001f5154, 0x00205356, 0x00205457, 0x00205457, 0x00205457, 0x00205356, 0x00205254, 0x001e5053, 0x001d4c50, 0x001d4a4d, 0x001b4649, 0x001a4245, 0x00183d41, 0x0017383c, 0x00153439, 0x00143036, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0010222b, 0x0010222b, 0x0010222b, 0x0011232d, 0x0011232e, 0x0011222d, 0x0012212d, 0x0012212d, 0x0012212c, 0x0012212c, 0x0011202c, 0x0010202b, 0x0010202b, 0x0010202a, 0x00102029, 0x00102029, 0x0011202c, 0x0012212c, 0x0012222c, 0x0011232c, 0x0012242c, 0x0012242c, 0x0014232e, 0x0014242e, 0x00142430, 0x00142530, 0x00152631, 0x00152631, 0x00162832, 0x00172833, 0x00172834, 0x00182a36, 0x00182a37, 0x00172a38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00172a38, 0x00182a38, 0x00172938, 0x00152836, 0x00142835, 0x00142835, 0x00142835, 0x00142734, 0x00142633, 0x00142532, 0x00142532, 0x00152731, 0x00162832, 0x00162832, 0x00162732, 0x00152732, 0x00152633, 0x00142533, 0x00142734, 0x00142734, 0x00142734, 0x00172633, 0x00172633, 0x00162633, 0x00152733, 0x00162633, 0x00162631, 0x00162530, 0x0014232c, 0x00102029, 0x000f1c26, 0x000d1923, 0x00101c25, 0x00142029, 0x001c2830, 0x001f2c36, 0x001f2d38, 0x0022323d, 0x00253641, 0x00273a45, 0x00283c48, 0x00283d4b, 0x0028404e, 0x002d4856, 0x00334e5d, 0x00385363, 0x003c5766, 0x003a5260, 0x00324957, 0x002c4350, 0x00304654, 0x002d4453, 0x002c4250, 0x002f4351, 0x0030424f, 0x002e3c4a, 0x0024313c, 0x00202e38, 0x0024323c, 0x002c3842, 0x0028343e, 0x0027313c, 0x00242e38, 0x0026313c, 0x00283440, 0x00293642, 0x002b3844, 0x002c3a45, 0x002d3c48, 0x002f3d48, 0x002d3a46, 0x00202c38, 0x0018242c, 0x001a252c, 0x001d272e, 0x001c272e, 0x0018222b, 0x0017212a, 0x0018222b, 0x0018222b, 0x00151c26, 0x00121822, 0x00141a22, 0x00182027, 0x001d242b, 0x001e242c, 0x00242b34, 0x002c333c, 0x002a343d, 0x00232d37, 0x0027323c, 0x00333e48, 0x0037424d, 0x002c3843, 0x00303c47, 0x0035404c, 0x00242e3a, 0x00222e39, 0x00293540, 0x00303d48, 0x00333e49, 0x0036404c, 0x00363f4b, 0x00303844, 0x002a343f, 0x002b3440, 0x00212934, 0x00212833, 0x00212932, 0x00242c34, 0x00232933, 0x00242c35, 0x002b333c, 0x002c363f, 0x002a343c, 0x00202932, 0x00202831, 0x00232933, 0x00212830, 0x00252c34, 0x00242a32, 0x001f252f, 0x001f252e, 0x001c222b, 0x001a2029, 0x001e252d, 0x00202730, 0x001c242c, 0x00252c34, 0x00252c34, 0x00202730, 0x00202831, 0x00202831, 0x001b242c, 0x001e2730, 0x00202831, 0x00202a34, 0x00222c36, 0x001e2832, 0x001d2831, 0x00212b35, 0x001b242d, 0x001d2530, 0x001f272f, 0x00192028, 0x001b2228, 0x001c2228, 0x001b2228, 0x00182027, 0x00171d24, 0x00182027, 0x00232b32, 0x00212c34, 0x001b2830, 0x0017222c, 0x00142029, 0x001a242f, 0x001d2830, 0x001c2730, 0x001a242d, 0x001c2730, 0x0025303a, 0x0027313c, 0x00212b35, 0x00202833, 0x00202833, 0x00212934, 0x00202834, 0x00222b34, 0x00242d37, 0x00262f39, 0x0029323c, 0x002c3540, 0x002d3741, 0x002c3640, 0x002c3540, 0x0027313c, 0x0028333d, 0x002a3540, 0x0027333e, 0x0024303b, 0x0025313d, 0x002a3743, 0x002c3c48, 0x002c3e4a, 0x002b3d4c, 0x00273949, 0x00304254, 0x00374b5c, 0x0034495a, 0x00344a5b, 0x00354b5c, 0x00304555, 0x002b4150, 0x002c4252, 0x002e4454, 0x0033495b, 0x00364e60, 0x00355063, 0x00345063, 0x0038586b, 0x003d5e70, 0x003c5a6d, 0x003c5668, 0x00395364, 0x00365061, 0x00334c5c, 0x002f4754, 0x002b414f, 0x00283f4b, 0x00253b47, 0x00223744, 0x00203441, 0x001b303c, 0x00192e3a, 0x001d333e, 0x00223844, 0x00223844, 0x00203442, 0x001c323f, 0x001b303e, 0x001b2f3c, 0x00182d3b, 0x00172c38, 0x00162b38, 0x00172b39, 0x00172c39, 0x00182c3a, 0x00182c3a, 0x00182c3a, 0x00182c3a, 0x00172c3a, 0x00192c39, 0x00192b39, 0x00192a38, 0x00192a38, 0x00182937, 0x00182937, 0x00182a36, 0x00182a36, 0x00182a36, 0x00182a36, 0x00182a36, 0x00162935, 0x00162935, 0x00152a35, 0x00152a36, 0x00172c38, 0x00172c39, 0x00172c39, 0x00182c3a, 0x00182d3b, 0x00182d3b, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182e3c, 0x00182e3b, 0x00182e3b, 0x00182e3b, 0x00172d3a, 0x00152c39, 0x00162c3a, 0x00152b38, 0x00152b38, 0x00152b38, 0x00152b38, 0x00162835, 0x00152834, 0x00152734, 0x00152633, 0x00142532, 0x00142431, 0x00142431, 0x00132430, 0x00122430, 0x00122430, 0x00122430, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x00102229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x00143439, 0x0017383c, 0x00183c40, 0x00194044, 0x001b4448, 0x001c474b, 0x001c4a4d, 0x001d4b4e, 0x001e4d50, 0x001e4d50, 0x001d4d50, 0x001e4d50, 0x001d4c50, 0x001d4b4e, 0x001c4a4d, 0x001c484c, 0x001c474b, 0x001b4448, 0x001a4347, 0x001a4245, 0x001a4245, 0x001a4245, 0x001b4245, 0x001a4347, 0x001a4448, 0x001c474b, 0x001d4a4d, 0x001d4c50, 0x001e4f51, 0x001f5154, 0x00205459, 0x0020585e, 0x0021595f, 0x00215a60, 0x00215a60, 0x0021595f, 0x0020585e, 0x0020555b, 0x001e4f53, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x0015363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0011232e, 0x0011232e, 0x0011232e, 0x0011232d, 0x0011232d, 0x0011222d, 0x0012212c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011202b, 0x0010202a, 0x0010202a, 0x00101f29, 0x00101f28, 0x00102029, 0x0011202c, 0x0011202c, 0x0012212c, 0x0012212c, 0x0013222c, 0x0012232c, 0x0014242d, 0x0014242f, 0x00142430, 0x00142530, 0x00152631, 0x00152731, 0x00162832, 0x00162833, 0x00172833, 0x00172935, 0x00172936, 0x00172a37, 0x00162a37, 0x00162b37, 0x00162b37, 0x00162b38, 0x00172a38, 0x00182a38, 0x00172938, 0x00172937, 0x00162936, 0x00172936, 0x00172835, 0x00162834, 0x00162834, 0x00152733, 0x00152733, 0x00152731, 0x00152731, 0x00152631, 0x00142530, 0x00142531, 0x00142532, 0x00142532, 0x00142734, 0x00142734, 0x00142633, 0x00142531, 0x00142531, 0x00142532, 0x00152632, 0x00162531, 0x0018242f, 0x0015212b, 0x00101c25, 0x000c1922, 0x000e1b25, 0x00101e28, 0x00182630, 0x001f2c38, 0x0024323f, 0x00273543, 0x00263743, 0x00273947, 0x00293c4a, 0x002c404e, 0x002e4452, 0x002d4453, 0x002d4655, 0x00314c5c, 0x00355263, 0x00385768, 0x003c5a6c, 0x003a5566, 0x00344c5d, 0x00304758, 0x00314859, 0x002f4555, 0x002f4452, 0x00304451, 0x0030414e, 0x002b3a47, 0x00202e3b, 0x00202c38, 0x0025333d, 0x002c3843, 0x00293540, 0x0026323c, 0x0026333c, 0x00283540, 0x00293743, 0x00293843, 0x00293844, 0x002b3b45, 0x002c3c46, 0x002b3944, 0x002a3742, 0x00202b35, 0x0019252c, 0x001c282e, 0x001f282f, 0x001c272e, 0x0019242b, 0x0018232b, 0x001a242c, 0x0018232b, 0x00161f28, 0x00151c26, 0x00131a23, 0x001a2128, 0x00222931, 0x00252c34, 0x002b323c, 0x002f3843, 0x002c3843, 0x002c3844, 0x0035424f, 0x00394654, 0x003b4755, 0x00323e4c, 0x00343f4c, 0x00323e4b, 0x00293440, 0x002e3945, 0x0034404c, 0x0035404c, 0x00384350, 0x003c4452, 0x0039414e, 0x00333b48, 0x002e3644, 0x002d3543, 0x00252d3b, 0x0029303d, 0x002f3842, 0x002f3741, 0x00282e39, 0x002e3540, 0x002d343f, 0x002c343e, 0x002c343e, 0x001d2631, 0x00252d37, 0x002a303b, 0x0028303a, 0x00323944, 0x002d343e, 0x00272e38, 0x00202732, 0x00202833, 0x00202832, 0x00202832, 0x00212a33, 0x001f2730, 0x00232b35, 0x002c333e, 0x002b333e, 0x0026303b, 0x0026303c, 0x00202b35, 0x001f2834, 0x00212b36, 0x002a343f, 0x0028343f, 0x00242f3b, 0x00242e3a, 0x0028333f, 0x00212a36, 0x001d2632, 0x00202832, 0x0019222a, 0x001a2329, 0x001c242b, 0x001a2229, 0x00192128, 0x00182028, 0x00161e25, 0x001a232a, 0x00202b32, 0x001e2a32, 0x001b2730, 0x0017232b, 0x00152029, 0x001a242d, 0x001d2830, 0x001c2730, 0x001d2831, 0x00242e38, 0x0029333d, 0x00242f39, 0x00202a34, 0x001e2731, 0x001c242f, 0x001a222d, 0x001c242f, 0x00202831, 0x00232b36, 0x00262e38, 0x00262f39, 0x0028303b, 0x002a333d, 0x002b3440, 0x0028313e, 0x0029333f, 0x002a3542, 0x002a3642, 0x00283440, 0x00273440, 0x00293744, 0x002e3d4b, 0x002f404d, 0x002b3e4b, 0x00273a4a, 0x00304454, 0x00344859, 0x00314858, 0x00324959, 0x00334959, 0x002f4454, 0x002b4151, 0x002c4353, 0x002f4555, 0x00344c5e, 0x00385367, 0x003d5d72, 0x00456a80, 0x004b7488, 0x004a7287, 0x0045697e, 0x00406176, 0x003e5e72, 0x003e5f74, 0x003c5b70, 0x00395468, 0x00344c5e, 0x00304858, 0x002d4453, 0x002c4050, 0x00293e4c, 0x00213643, 0x00182c38, 0x00152834, 0x00182a34, 0x001c2d39, 0x001c2e3b, 0x001c2f3c, 0x001c303d, 0x001c2f3c, 0x001a2d3b, 0x00172b37, 0x00162a37, 0x00162b38, 0x00172b39, 0x00172c39, 0x00182c39, 0x00182c39, 0x00182c39, 0x00182c39, 0x00182b38, 0x00182a38, 0x00182a38, 0x00182937, 0x00182937, 0x00182937, 0x00182a38, 0x00182b38, 0x00192c38, 0x00192c39, 0x001b2f3c, 0x001d323f, 0x001d3340, 0x001c3340, 0x0019303d, 0x00182f3c, 0x00182e3c, 0x00182d3b, 0x00182d3b, 0x00182d3b, 0x00182d3b, 0x00182e3c, 0x00182e3c, 0x00182e3c, 0x00182e3c, 0x00182e3c, 0x00182e3b, 0x00182e3b, 0x00182e3b, 0x00182d3b, 0x00172d3a, 0x00172c39, 0x00172c39, 0x00162b38, 0x00162a38, 0x00162a38, 0x00152934, 0x00142834, 0x00142734, 0x00142633, 0x00142532, 0x00142430, 0x00132430, 0x00132430, 0x0012242f, 0x0012242f, 0x00122430, 0x00122430, 0x00122430, 0x00122531, 0x00122531, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153338, 0x00153439, 0x00183a3e, 0x00183d41, 0x00194044, 0x001a4347, 0x001c4649, 0x001c484c, 0x001d4a4d, 0x001c4a4d, 0x001c4a4d, 0x001c4a4d, 0x001c484c, 0x001c484c, 0x001b4649, 0x001b4448, 0x001a4347, 0x001a4245, 0x00194044, 0x00194044, 0x00194044, 0x00184044, 0x00194044, 0x001b4347, 0x001a4448, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001e5053, 0x00205960, 0x00298cac, 0x002c99bd, 0x002c99bd, 0x002c9abd, 0x002c9abd, 0x002c99bd, 0x002b98bd, 0x002b98bc, 0x00247c94, 0x001e4e51, 0x001d4a4d, 0x001c4649, 0x001a4044, 0x00183c40, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0013282e, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00132430, 0x00132430, 0x00132430, 0x0012242f, 0x0011232d, 0x0011222d, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011202a, 0x00102029, 0x00102029, 0x00102029, 0x00101f28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x0012202a, 0x0013202a, 0x0013212b, 0x0013222c, 0x0014242c, 0x0014242e, 0x00152530, 0x00142530, 0x00152631, 0x00162832, 0x00162832, 0x00162832, 0x00162832, 0x00172834, 0x00162834, 0x00162836, 0x00162936, 0x00162b37, 0x00152a36, 0x00172c38, 0x00172b38, 0x00182a37, 0x00182b37, 0x00182c38, 0x00182c38, 0x00192c37, 0x00192a35, 0x00192a35, 0x00182934, 0x00182934, 0x00162832, 0x00152731, 0x00152631, 0x00142530, 0x0014242f, 0x00142430, 0x00142532, 0x00142532, 0x00142633, 0x00132633, 0x00132531, 0x00142531, 0x00142531, 0x00142632, 0x00142631, 0x0015242e, 0x00152029, 0x00101a22, 0x000c181f, 0x000f1b23, 0x0016242e, 0x001d2c39, 0x00223440, 0x00263845, 0x002b3c4b, 0x002c4050, 0x002c4151, 0x002c4353, 0x002e4656, 0x00304a5b, 0x00314c5c, 0x00304a5b, 0x00314b5c, 0x00355163, 0x0038586b, 0x003c6073, 0x00426579, 0x0039596c, 0x00355365, 0x00314c5e, 0x0030485a, 0x002e4657, 0x002d4453, 0x002d4451, 0x002d404c, 0x00283a46, 0x00202e3c, 0x00202c39, 0x0026343f, 0x002a3844, 0x00283742, 0x00263540, 0x00273541, 0x002a3844, 0x002a3a45, 0x002a3a45, 0x002a3944, 0x00293843, 0x002c3944, 0x002b3741, 0x0028343e, 0x00212a34, 0x001d2830, 0x001f292e, 0x001f292e, 0x001c262d, 0x001a242b, 0x0019242a, 0x001b252c, 0x00182329, 0x00141f25, 0x00141d24, 0x00111b23, 0x001c262d, 0x00242d35, 0x00252f38, 0x002d3641, 0x0037434f, 0x0034434e, 0x00384652, 0x003c4a59, 0x003e4a5b, 0x003d4a5a, 0x00384554, 0x0034404e, 0x00303b48, 0x00333e4c, 0x003b4452, 0x003a4450, 0x00394250, 0x003c4454, 0x003e4555, 0x003d4454, 0x003a4250, 0x0038404f, 0x00394150, 0x0038404f, 0x00394250, 0x003c4753, 0x003c4751, 0x0037404b, 0x0039414c, 0x003a404c, 0x00383f4a, 0x00303642, 0x0028303c, 0x002c3441, 0x00343c48, 0x00343c48, 0x003b434f, 0x00343c48, 0x00343c48, 0x002d3541, 0x002c343e, 0x00272f3a, 0x0027303b, 0x0028303d, 0x00252e3c, 0x0026303d, 0x002e3744, 0x00303a48, 0x00303c49, 0x002c3846, 0x00283340, 0x0025303c, 0x0028323f, 0x00293440, 0x00283440, 0x002a3743, 0x00293642, 0x002c3743, 0x002b3441, 0x001e2834, 0x00202934, 0x0019232c, 0x001b242c, 0x001c252d, 0x00162027, 0x00182229, 0x0018232a, 0x0018232a, 0x0018242a, 0x001c282f, 0x001d2932, 0x001c2830, 0x001b262f, 0x0018232c, 0x0018232c, 0x0018242c, 0x001d2a32, 0x001f2b34, 0x00202c36, 0x0027303b, 0x0026313c, 0x00202c36, 0x001e2832, 0x001c242e, 0x0018202c, 0x001b232e, 0x001d2630, 0x00202832, 0x00222b34, 0x00242d36, 0x00262e37, 0x00273039, 0x0027303b, 0x00262f3c, 0x0028333f, 0x00283441, 0x00273643, 0x00283844, 0x002a3948, 0x00283847, 0x002e404e, 0x002d414e, 0x00273c49, 0x00253a49, 0x00324656, 0x00334857, 0x002f4554, 0x002d4554, 0x002f4554, 0x002e4453, 0x002d4453, 0x002e4454, 0x002f4658, 0x00334e61, 0x003b5c71, 0x0048748b, 0x005f90a9, 0x00699cb4, 0x006597b0, 0x006492ac, 0x005c89a4, 0x00547f99, 0x004e7893, 0x004b728c, 0x00496c86, 0x0045677f, 0x003c5a71, 0x00365065, 0x00344c60, 0x0032485a, 0x002b404f, 0x00213340, 0x00162632, 0x000e1c27, 0x00101e28, 0x00162430, 0x001a2a37, 0x001c2c3a, 0x001c2d3b, 0x001b2c3a, 0x00182b37, 0x00172936, 0x00172938, 0x00182a38, 0x00182a38, 0x00182c38, 0x00182c38, 0x00182c38, 0x00182c38, 0x00182c38, 0x00172b37, 0x00172b37, 0x00162a36, 0x00162a36, 0x00172b38, 0x00182c3b, 0x00192f3c, 0x001e3541, 0x00233b47, 0x00263f4d, 0x00284250, 0x00294451, 0x00294451, 0x00284450, 0x0026414f, 0x00203847, 0x001b3342, 0x00193040, 0x00192f3e, 0x00192e3d, 0x001a2f3c, 0x001b2f3c, 0x00192e3c, 0x00182d3b, 0x00192d3c, 0x001a2e3c, 0x001a2e3c, 0x00192d3b, 0x00182d3b, 0x00182d3b, 0x00192d39, 0x00192c38, 0x00182c38, 0x00182a37, 0x00182a37, 0x00162934, 0x00142834, 0x00142834, 0x00142733, 0x00132631, 0x0013242f, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012252f, 0x00122530, 0x00132630, 0x00132630, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0012242c, 0x0010282e, 0x00132c32, 0x00143036, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183d41, 0x001a4044, 0x001b4347, 0x001b4448, 0x001b4649, 0x001b4649, 0x001b4649, 0x001b4649, 0x001b4649, 0x001a4448, 0x001a4347, 0x001a4245, 0x00194044, 0x00194044, 0x00193f43, 0x00193f43, 0x00193f43, 0x00193f43, 0x00194044, 0x001a4347, 0x001b4649, 0x001c484c, 0x001d4b4e, 0x001e4f51, 0x00205254, 0x00246d7f, 0x002ea3cb, 0x002c99bc, 0x002c94b5, 0x002c94b5, 0x002c94b5, 0x002c94b5, 0x002c94b4, 0x002d9ec4, 0x002c9bc0, 0x001f5054, 0x001e4c50, 0x001c474b, 0x001a4347, 0x00183d41, 0x0017383c, 0x00153439, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00142431, 0x00142431, 0x00142431, 0x0013242f, 0x0011232d, 0x0011222d, 0x0012212c, 0x0012212c, 0x0011202b, 0x00102029, 0x00102029, 0x00102029, 0x00102029, 0x00101f29, 0x00101e28, 0x00101e28, 0x00101d27, 0x00101d27, 0x00111f29, 0x0013202a, 0x0013212b, 0x0013222c, 0x0014242c, 0x0014242e, 0x00152530, 0x00142530, 0x00152631, 0x00162832, 0x00162832, 0x00162832, 0x00162832, 0x00162832, 0x00152834, 0x00152836, 0x00162836, 0x00162a36, 0x00162a36, 0x00172c38, 0x00182c38, 0x00192c38, 0x00192c38, 0x001a2d39, 0x001a2d39, 0x001a2c38, 0x001a2c37, 0x001a2b36, 0x00192a34, 0x00182934, 0x00172833, 0x00152731, 0x00152631, 0x00142530, 0x0014242f, 0x0014242f, 0x00132430, 0x00132430, 0x00122430, 0x0012242f, 0x0012242e, 0x0013242f, 0x0014242f, 0x00142430, 0x0014242d, 0x00132029, 0x00111b24, 0x000e1820, 0x00121c24, 0x001c2831, 0x0024323f, 0x00263948, 0x002b404e, 0x002f4453, 0x00334858, 0x0033495c, 0x00324c5e, 0x00344f61, 0x00385465, 0x00385668, 0x00365568, 0x00345265, 0x00375468, 0x00406176, 0x004c7186, 0x00588095, 0x00588095, 0x0043677c, 0x003c5c70, 0x00345264, 0x002e495a, 0x002d4756, 0x002c4553, 0x002c4350, 0x002b3e4b, 0x00283a47, 0x00243240, 0x00212f3c, 0x00283541, 0x002a3843, 0x00283844, 0x00293844, 0x002a3944, 0x002c3b46, 0x002c3c48, 0x002c3c48, 0x00283743, 0x00273540, 0x00293540, 0x0029353f, 0x0026313c, 0x00242d38, 0x00202b33, 0x001d282e, 0x001b252a, 0x001b252c, 0x0019242a, 0x001a242b, 0x001d282f, 0x00182329, 0x00152027, 0x00152027, 0x00172128, 0x00202b31, 0x001f2930, 0x002a343d, 0x00343f4a, 0x003c4853, 0x003b4a54, 0x003d4c58, 0x003f4c5a, 0x00404a5a, 0x003f4959, 0x003d4855, 0x00374150, 0x00343f4c, 0x003a4453, 0x003d4755, 0x003d4554, 0x003c4452, 0x003e4554, 0x003f4657, 0x00404757, 0x00404857, 0x00404857, 0x00444c5a, 0x00454d5c, 0x00474f5d, 0x0047505e, 0x0048515e, 0x00454e5b, 0x003f4754, 0x003c4250, 0x00383e4a, 0x00353c48, 0x00373e4b, 0x0039414e, 0x003d4553, 0x00404856, 0x00444c59, 0x00414957, 0x00414957, 0x003b4350, 0x00343c49, 0x00373f4c, 0x0038414e, 0x00353f4c, 0x00313b4a, 0x00333c4b, 0x00363f4e, 0x00384250, 0x00394453, 0x00384453, 0x002a3543, 0x00333e4b, 0x00384451, 0x0034404d, 0x00283542, 0x002b3844, 0x00303d48, 0x002c3844, 0x002f3845, 0x00222c38, 0x00222c36, 0x001c262f, 0x001a242d, 0x001f2830, 0x001a242c, 0x001c242c, 0x001c252e, 0x001c2730, 0x001d2830, 0x001c2830, 0x001c2830, 0x001c2830, 0x001c2730, 0x001c252e, 0x001b252e, 0x0019252e, 0x001d2931, 0x001f2b34, 0x001e2a34, 0x00242e38, 0x0028343e, 0x00232f38, 0x00202b35, 0x001e2631, 0x001c2530, 0x001f2731, 0x00202831, 0x001e2730, 0x00212932, 0x00242d36, 0x00273038, 0x00272f38, 0x00242c38, 0x00262d3a, 0x00283440, 0x00283542, 0x00243340, 0x00233440, 0x00283a48, 0x00283948, 0x002d404e, 0x002c414f, 0x00283c4a, 0x00283c4b, 0x00314655, 0x00334757, 0x002f4554, 0x002c4452, 0x002d4453, 0x002f4554, 0x00304656, 0x00304657, 0x0031495b, 0x00345265, 0x0040647c, 0x005c8ca4, 0x0079aec3, 0x0088bcc9, 0x0084b8c8, 0x0086b7c8, 0x0086b7c8, 0x0081b1c4, 0x007aa9bd, 0x0073a0b5, 0x006893aa, 0x005c869f, 0x0050758f, 0x0044667f, 0x00405c74, 0x00395468, 0x00304959, 0x00293d4c, 0x0021303d, 0x0014202c, 0x000c1824, 0x000c1a25, 0x0012202c, 0x00182633, 0x001a2a36, 0x001b2c38, 0x00182b37, 0x00172936, 0x00172937, 0x00182a38, 0x00182a38, 0x00182a37, 0x00182b37, 0x00182c38, 0x00182c38, 0x00182a37, 0x00172a37, 0x00162b37, 0x00152a36, 0x00162b37, 0x00192e3b, 0x001d3240, 0x00233946, 0x00273f4b, 0x002c4551, 0x002f4856, 0x002f4a58, 0x002f4b58, 0x00304c59, 0x00304c5a, 0x00304c5a, 0x002e4858, 0x00284250, 0x00213948, 0x001d3443, 0x001c3040, 0x001b303d, 0x001b303c, 0x00192e3c, 0x00182d3b, 0x00182d3b, 0x001a2e3c, 0x001a2e3c, 0x00192d3c, 0x00182d3b, 0x00182d3b, 0x001a2d39, 0x001a2d39, 0x00182c38, 0x00182a37, 0x00182a37, 0x00162834, 0x00152833, 0x00142833, 0x00142732, 0x00132631, 0x0013242f, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012252f, 0x00122530, 0x00132630, 0x00132630, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x000f2229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00143036, 0x00143439, 0x0017383c, 0x00183c40, 0x00183d41, 0x00194044, 0x001a4245, 0x001a4347, 0x001a4347, 0x001a4448, 0x001a4448, 0x001a4347, 0x001b4347, 0x001b4245, 0x00184044, 0x00183f43, 0x00193f43, 0x00193f43, 0x00193f43, 0x00193f43, 0x00194044, 0x001a4245, 0x001b4448, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205356, 0x00247081, 0x002fa4cb, 0x0027778a, 0x00245c60, 0x00245d60, 0x00245c60, 0x00245c5f, 0x00235c5f, 0x002b90af, 0x002c9bc0, 0x00205457, 0x001d4d50, 0x001c484c, 0x001b4448, 0x00183f43, 0x00183a3e, 0x00153439, 0x00143036, 0x00122c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00142430, 0x00142430, 0x00142430, 0x0013242f, 0x0011232d, 0x0012222d, 0x0013222e, 0x0012212d, 0x0011202c, 0x00102029, 0x00102029, 0x00102029, 0x00102029, 0x00102028, 0x00112027, 0x00111f27, 0x00111f28, 0x00111f29, 0x00122029, 0x00132028, 0x0014212a, 0x0014222c, 0x0014232c, 0x0015242e, 0x00162430, 0x00162530, 0x00172631, 0x00172732, 0x00182732, 0x00182732, 0x00182732, 0x00182732, 0x00172833, 0x00172834, 0x00172834, 0x00182a34, 0x00182b36, 0x00182c38, 0x00192c38, 0x00192c38, 0x00192c38, 0x00192c38, 0x00192c39, 0x001a2c38, 0x001a2b37, 0x001a2b36, 0x00192a34, 0x00182934, 0x00172833, 0x00152731, 0x00152631, 0x00142530, 0x0014242f, 0x0012242e, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0012222c, 0x0013222c, 0x0013222c, 0x0012202a, 0x00101c26, 0x000c1822, 0x000d1821, 0x00131f28, 0x001e2c35, 0x00263642, 0x002b3d4c, 0x002f4557, 0x00344c5e, 0x00385062, 0x00395265, 0x003a556a, 0x003c5c70, 0x00406276, 0x00416579, 0x0042687b, 0x0041697d, 0x00436c82, 0x004b748c, 0x005c89a0, 0x006f9db3, 0x0078a5bc, 0x006b97ad, 0x00527b91, 0x003f6177, 0x0038576b, 0x00324e60, 0x002e4859, 0x002f4655, 0x002d4450, 0x00283c48, 0x00273945, 0x00253240, 0x0024303e, 0x00283644, 0x002b3844, 0x00293845, 0x00293845, 0x002b3a47, 0x002d3c49, 0x002e3e4b, 0x00283845, 0x0023323f, 0x00273440, 0x0025313c, 0x0028343d, 0x0025303b, 0x00242f39, 0x00202a33, 0x001a242b, 0x00182228, 0x001b252c, 0x001c262d, 0x001f2930, 0x00232d34, 0x001c262d, 0x001c262c, 0x001b252c, 0x001a242c, 0x001e282f, 0x001d282e, 0x002d3740, 0x00333c46, 0x00333e48, 0x0037434c, 0x0038444e, 0x003a4450, 0x003a4250, 0x003c4351, 0x003f4552, 0x003d4450, 0x003c434f, 0x003e4553, 0x00404856, 0x00404855, 0x003f4754, 0x00404856, 0x00404858, 0x00424959, 0x00444c5a, 0x00454d5c, 0x00464e5c, 0x00484f5e, 0x00484f5e, 0x00444d5d, 0x00444c5c, 0x00444c5c, 0x00414858, 0x003d4453, 0x003d4452, 0x00404653, 0x00404754, 0x00404856, 0x00424959, 0x00485060, 0x004b5363, 0x004a5262, 0x00495161, 0x00474f5d, 0x00404957, 0x00404956, 0x00424c59, 0x00414b59, 0x00404b5b, 0x00404c5c, 0x00414d5d, 0x00424f5f, 0x00414e5e, 0x00435060, 0x00354250, 0x00323f4c, 0x003a4754, 0x003b4855, 0x00323e4c, 0x002e3b47, 0x00303c48, 0x002d3844, 0x0029323f, 0x00262e3b, 0x0029323d, 0x00252d38, 0x001d2530, 0x00222b34, 0x00242c34, 0x001e262f, 0x001c242e, 0x00202831, 0x00232d36, 0x00202a33, 0x001c2730, 0x001e2931, 0x00202c34, 0x001c2830, 0x001a262f, 0x001c2830, 0x001c2a32, 0x001d2b34, 0x001d2a34, 0x001e2a34, 0x0028343d, 0x0024303a, 0x00222c37, 0x00202833, 0x001f2832, 0x00202833, 0x00212932, 0x001f2730, 0x00202831, 0x00242d36, 0x00273038, 0x00272f38, 0x00242c38, 0x0028303c, 0x002b3643, 0x002a3844, 0x00233340, 0x0021323f, 0x00283948, 0x002b3c4a, 0x002e404e, 0x002d4150, 0x002c4150, 0x002e4352, 0x00324756, 0x00324656, 0x00304655, 0x002d4554, 0x002d4353, 0x00304757, 0x00334a5a, 0x0031495b, 0x00344d60, 0x003d5c70, 0x00497288, 0x00679ab0, 0x008dc0ca, 0x00a1cbcc, 0x00a5cacc, 0x00a7c9cc, 0x00a8c9cc, 0x00a8cacc, 0x00a4c8cc, 0x009fc4cb, 0x0094bcc8, 0x0086b0c0, 0x0077a1b5, 0x00628ca1, 0x0050778e, 0x0044687f, 0x003a586c, 0x00314b5e, 0x002b3e4f, 0x001f2f3d, 0x0012202c, 0x000a1821, 0x00081620, 0x00101e28, 0x0016242f, 0x001a2936, 0x00182936, 0x00172834, 0x00172834, 0x00172835, 0x00182936, 0x00182a37, 0x00182a37, 0x00182b38, 0x00182c38, 0x00182a37, 0x00172936, 0x00152a35, 0x00152a36, 0x00192e39, 0x001e3340, 0x00243a48, 0x0029414e, 0x002d4753, 0x00304957, 0x00304b59, 0x00304c5a, 0x00314c5b, 0x00314c5b, 0x00314c5b, 0x00314c5b, 0x00324d5b, 0x00314c5a, 0x002c4554, 0x00263d4c, 0x00203644, 0x001c303e, 0x001b303c, 0x001a2e3c, 0x00182d3b, 0x00192e3c, 0x001b2f3c, 0x001b303c, 0x001a2f3c, 0x001a2e3c, 0x00192e3c, 0x00192c39, 0x00192c38, 0x00182c38, 0x00182a37, 0x00182a37, 0x00162834, 0x00152833, 0x00142832, 0x00142731, 0x00132630, 0x0013242d, 0x0012242c, 0x0012242d, 0x0012242e, 0x0012242e, 0x0013242e, 0x0014242f, 0x00142430, 0x00142530, 0x00142530, 0x000d1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00143036, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183c40, 0x00183d41, 0x00194044, 0x00194044, 0x001b4245, 0x001a4245, 0x001a4245, 0x001b4245, 0x001b4245, 0x00194044, 0x00184044, 0x00193f43, 0x00193f43, 0x00193f43, 0x00193f43, 0x00194044, 0x001a4245, 0x001a4347, 0x001b4649, 0x001c484c, 0x001d4c50, 0x001e5053, 0x00205254, 0x00205558, 0x00257082, 0x0030a4cb, 0x0028788a, 0x00245e60, 0x00245e60, 0x00245e60, 0x00245d60, 0x00245c5f, 0x002b90af, 0x002c9bc0, 0x00205458, 0x001e4f51, 0x001c4a4d, 0x001c4649, 0x00194044, 0x00183c40, 0x0015363b, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0012252f, 0x0012252f, 0x0013242f, 0x0014242f, 0x0013232e, 0x0013222e, 0x0013222f, 0x0012212e, 0x0011202c, 0x00102029, 0x00102029, 0x00102029, 0x00102029, 0x00102028, 0x00112027, 0x00112027, 0x00132029, 0x0013202a, 0x00132029, 0x00132028, 0x00142129, 0x0014222c, 0x0015232c, 0x0016242e, 0x00162430, 0x00162530, 0x00172631, 0x00182732, 0x00182732, 0x00182732, 0x00182732, 0x00182732, 0x00182733, 0x00172833, 0x00172833, 0x00182a34, 0x00182b36, 0x00192c38, 0x00192c39, 0x00192c38, 0x00192c38, 0x00192c38, 0x00192c38, 0x001a2c38, 0x001a2b37, 0x001a2b36, 0x00192a34, 0x00182934, 0x00172833, 0x00152732, 0x00152631, 0x00142530, 0x0014242f, 0x0012242e, 0x0011232d, 0x0011232d, 0x0011232e, 0x0011222d, 0x0012212c, 0x0013202b, 0x00111f27, 0x000e1b24, 0x000b1720, 0x000c1822, 0x0014212c, 0x00202f3a, 0x00283a46, 0x00304451, 0x00354c5d, 0x003a5467, 0x003d596d, 0x00405c71, 0x00436075, 0x0045667c, 0x004c7187, 0x00568095, 0x00608ba1, 0x006996ab, 0x0071a0b3, 0x0077a5b8, 0x0080afc0, 0x008abac8, 0x0090c0cb, 0x008cbcca, 0x0079a8bc, 0x00628ca2, 0x00446b81, 0x003d6074, 0x00395669, 0x00344f60, 0x00324858, 0x002c414f, 0x00263846, 0x00243542, 0x0023313e, 0x00263340, 0x002a3744, 0x002a3844, 0x00293845, 0x002a3946, 0x002e3e4b, 0x0030404c, 0x002e3f4c, 0x00253441, 0x00243340, 0x00283541, 0x0025313c, 0x0027333c, 0x0024303a, 0x00222d37, 0x001c262f, 0x00172128, 0x00172027, 0x001a242b, 0x00202930, 0x00263037, 0x00242e34, 0x00202930, 0x001c272e, 0x001c252c, 0x001c252d, 0x00212b32, 0x00212b31, 0x00262f36, 0x00283039, 0x00242b34, 0x00222932, 0x00202832, 0x00212833, 0x00242935, 0x002b2f3c, 0x00343843, 0x00383c45, 0x00383c46, 0x003b404a, 0x003e4450, 0x003f4451, 0x003f4552, 0x003f4552, 0x00404654, 0x00404754, 0x00424854, 0x00424855, 0x00444957, 0x00454858, 0x00444858, 0x00404756, 0x00404656, 0x00434858, 0x00434858, 0x00434857, 0x00434856, 0x00434855, 0x00444956, 0x00444958, 0x00444959, 0x00474c5c, 0x00484f5f, 0x00495060, 0x00484f5f, 0x00474d5c, 0x00464c5c, 0x00474e5c, 0x00474e5d, 0x00484f60, 0x00484f61, 0x00465062, 0x00475163, 0x00454f61, 0x00434d5f, 0x00434f60, 0x003f4a5a, 0x00344050, 0x00384352, 0x003c4657, 0x00394352, 0x0039424f, 0x0037404c, 0x00323b48, 0x002a323f, 0x002e3541, 0x00343c47, 0x002b323c, 0x00202832, 0x00232a34, 0x00242c35, 0x00262e38, 0x0018212a, 0x001c242d, 0x00202a32, 0x00242d36, 0x001b252e, 0x001a242d, 0x001c262f, 0x001c252e, 0x001a252e, 0x001c2931, 0x001d2b33, 0x001e2c35, 0x001d2b34, 0x001c2833, 0x00202c36, 0x00243039, 0x001f2a34, 0x001f2832, 0x00202832, 0x00202832, 0x00202831, 0x00202832, 0x00222b34, 0x00242c36, 0x00262e38, 0x0028303b, 0x00272f3b, 0x00262e3c, 0x00293542, 0x002c3a47, 0x00253542, 0x0021333f, 0x00283948, 0x002c3c4b, 0x002f414f, 0x002d4250, 0x002e4350, 0x00314655, 0x00334857, 0x00324757, 0x00304756, 0x00304858, 0x00314858, 0x00334a5b, 0x00384f60, 0x00375062, 0x00385468, 0x0043667b, 0x00578499, 0x0074a9bc, 0x009ac7cb, 0x00aecccc, 0x00b5cccc, 0x00b8cccc, 0x00b9cccc, 0x00b9cccc, 0x00b8cccc, 0x00b5cccc, 0x00b1cbcc, 0x00acc9cc, 0x00a1c6cb, 0x0090bac4, 0x0079a4b8, 0x00618ca1, 0x004e7288, 0x00405f75, 0x00344c61, 0x002a3d4f, 0x001d2d3a, 0x00101f28, 0x0008161e, 0x0008161e, 0x00101e27, 0x00172531, 0x00182734, 0x00182734, 0x00162734, 0x00162834, 0x00162834, 0x00162834, 0x00162834, 0x00172936, 0x00172936, 0x00172935, 0x00162834, 0x00162935, 0x00182c38, 0x001c313d, 0x00243946, 0x002a404e, 0x002d4552, 0x00304956, 0x00314c58, 0x00324c5c, 0x00314c5b, 0x00314c5b, 0x00314d5c, 0x00324e5c, 0x00324e5c, 0x00324e5c, 0x00324e5c, 0x00314c5a, 0x002d4554, 0x00253c4b, 0x001f3441, 0x001b303d, 0x001a2e3c, 0x00182d3b, 0x00192e3c, 0x001b303c, 0x001b303c, 0x001b303c, 0x001b303c, 0x001a2e3c, 0x00192c39, 0x00192c38, 0x00182c38, 0x00182a37, 0x00182a37, 0x00162834, 0x00152833, 0x00142832, 0x00142731, 0x00132530, 0x0012242d, 0x0012242c, 0x0012242d, 0x0012242e, 0x0012242e, 0x0013242e, 0x0014242f, 0x00142430, 0x00142530, 0x00142530, 0x000d1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f2229, 0x00102229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00142e34, 0x00153338, 0x00143439, 0x0017383c, 0x00183c40, 0x00183d41, 0x00193f43, 0x00184044, 0x001b4245, 0x001b4245, 0x001b4245, 0x001b4245, 0x001b4245, 0x001b4245, 0x001a4245, 0x00194044, 0x00194044, 0x00194044, 0x001a4245, 0x001a4245, 0x001a4347, 0x001b4649, 0x001c484c, 0x001d4b4e, 0x001e4f51, 0x001f5154, 0x00205457, 0x0021585a, 0x00277284, 0x0030a4cb, 0x0028788b, 0x00245f61, 0x00246062, 0x00245f61, 0x00245f61, 0x00245d60, 0x002c90af, 0x002c9cc0, 0x00205559, 0x001f5053, 0x001d4b4e, 0x001c4649, 0x001a4245, 0x00183c40, 0x0015363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0014242f, 0x0014242f, 0x0013242f, 0x0014232e, 0x0013222d, 0x0013222d, 0x0013222f, 0x0012212e, 0x0012202c, 0x00112029, 0x00112029, 0x00112029, 0x00112029, 0x00112028, 0x00112028, 0x00122028, 0x0013202a, 0x0013202a, 0x0014212a, 0x00142129, 0x0014212a, 0x0014222c, 0x0014222c, 0x0015232e, 0x00162430, 0x00162530, 0x00172631, 0x00182732, 0x00182732, 0x00182732, 0x00182732, 0x00182732, 0x00182733, 0x00172834, 0x00172935, 0x00192b37, 0x00182c38, 0x00182c38, 0x00192c39, 0x00192c38, 0x00192c38, 0x00192c38, 0x00192c38, 0x001a2c38, 0x001a2b37, 0x001a2b36, 0x00192a34, 0x00182934, 0x00172833, 0x00152732, 0x00152631, 0x00142530, 0x0014242f, 0x0012242e, 0x0011232d, 0x0011232d, 0x0012222c, 0x0012202a, 0x00121f29, 0x00111d26, 0x000d1820, 0x000a151d, 0x000b1720, 0x0014212e, 0x001f3040, 0x00283e50, 0x002f495b, 0x003b576b, 0x00436278, 0x0044657c, 0x0047687f, 0x004b6e85, 0x0054788f, 0x00648ca1, 0x0078a1b5, 0x008ab4c4, 0x0096bfc9, 0x009ec4cb, 0x00a4c8cc, 0x00a8c9cc, 0x00adcbcc, 0x00b0cccc, 0x00b0cccc, 0x00a8c8cc, 0x008eb8c4, 0x00709dae, 0x00507c91, 0x00446d83, 0x00406176, 0x00385265, 0x00324858, 0x00293c4a, 0x00223441, 0x0022333f, 0x00263542, 0x00273642, 0x00273542, 0x00273542, 0x002a3947, 0x002d3d4a, 0x00324450, 0x0031424f, 0x002c3b47, 0x0025333f, 0x00273340, 0x00283340, 0x0026303c, 0x0026313c, 0x00242f38, 0x00202b34, 0x001c262e, 0x0018232a, 0x00161f27, 0x00192329, 0x001f282e, 0x00283138, 0x00212b32, 0x001f2930, 0x001b242b, 0x001b222a, 0x001f262e, 0x00242c34, 0x00232b32, 0x00222931, 0x00222830, 0x001c232a, 0x00181c24, 0x00171921, 0x00141820, 0x00141620, 0x0014161f, 0x00171920, 0x00181b21, 0x001b1e24, 0x001f2129, 0x0024272f, 0x00282a32, 0x002c2f37, 0x002e3039, 0x002d303a, 0x002f313c, 0x0031343e, 0x00343640, 0x00363743, 0x00383844, 0x00383844, 0x00373844, 0x00383844, 0x00383944, 0x003a3b45, 0x003c3d48, 0x003e404c, 0x0040414d, 0x0040414d, 0x003f404c, 0x003c3e4b, 0x003c3e4a, 0x003d3f4c, 0x0040424e, 0x00424450, 0x00424552, 0x00434553, 0x00424553, 0x00424554, 0x00414454, 0x00404454, 0x00414757, 0x00424757, 0x00404455, 0x003f4352, 0x003e4351, 0x003c414f, 0x00383e4b, 0x00343947, 0x00343846, 0x00303541, 0x002e323d, 0x00282c38, 0x00252834, 0x0021242f, 0x0020232c, 0x0023262f, 0x0020242c, 0x001c2028, 0x001e232b, 0x001e242d, 0x00242b34, 0x0018202a, 0x001d262f, 0x001f2831, 0x00263038, 0x001e2830, 0x0018212a, 0x0019212a, 0x001b242c, 0x001c242d, 0x001c262e, 0x001a252d, 0x001b2630, 0x001c2832, 0x00202c36, 0x001c2832, 0x00243039, 0x00202c36, 0x00202a34, 0x00202832, 0x00212834, 0x00232934, 0x00242c37, 0x00252d38, 0x00242d38, 0x00242c38, 0x0028303c, 0x0028303e, 0x00242e3c, 0x0025323f, 0x002b3845, 0x002a3a46, 0x00243541, 0x00283847, 0x002f4050, 0x00304251, 0x002f4251, 0x002c4050, 0x002e4151, 0x00314655, 0x00334858, 0x00324958, 0x00344c5c, 0x00354c5d, 0x00384f60, 0x003c5468, 0x003c596d, 0x00426779, 0x00588695, 0x007cabb7, 0x009bc3ca, 0x00aecbcc, 0x00bbcccc, 0x00c0cccc, 0x00c3cccc, 0x00c4cccc, 0x00c4cccc, 0x00c4cccc, 0x00c2cccc, 0x00c0cccc, 0x00bfcccc, 0x00bacccc, 0x00b4cbcc, 0x00a7c6cb, 0x0090b4c1, 0x007299ac, 0x00598096, 0x0043647c, 0x00324d62, 0x00253a4a, 0x001a2b38, 0x00101c27, 0x0008141c, 0x000c161f, 0x00131f2a, 0x00162430, 0x00162532, 0x00152632, 0x00172633, 0x00162734, 0x00152834, 0x00152834, 0x00162834, 0x00162834, 0x00172834, 0x00162834, 0x00172936, 0x001a2e3a, 0x00203541, 0x00283d4b, 0x002c4451, 0x002f4855, 0x00304b58, 0x00304c5a, 0x00314c5c, 0x00304c5c, 0x00304c5c, 0x00324e5c, 0x00324f5c, 0x00334f5d, 0x00334f5d, 0x00344e5d, 0x00344e5d, 0x00314a59, 0x002a4150, 0x00243a48, 0x001e3440, 0x001b303d, 0x00192f3c, 0x001a2f3c, 0x001b303c, 0x001b303c, 0x001b303c, 0x001b303c, 0x001a2f3c, 0x001a2e3a, 0x00192d39, 0x00182c38, 0x00182c37, 0x00182b36, 0x00172934, 0x00152833, 0x00142832, 0x00142731, 0x00142630, 0x0014242e, 0x0014242e, 0x0013242e, 0x0013242e, 0x0013242e, 0x0013242f, 0x00132430, 0x00142430, 0x00142631, 0x00142631, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f2229, 0x00102229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00142e34, 0x00153338, 0x00143439, 0x0016383c, 0x00183c40, 0x00183d41, 0x00183f43, 0x001a4245, 0x001b4245, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001b4448, 0x001b4649, 0x001c474b, 0x001c484c, 0x001d4b4e, 0x001e4f51, 0x001f5154, 0x00205457, 0x0021585a, 0x0022595c, 0x00277384, 0x0030a4cb, 0x0028798c, 0x00256163, 0x00256163, 0x00256163, 0x00246062, 0x00245e60, 0x002c90b0, 0x002c9cc0, 0x0020565a, 0x001f5154, 0x001d4c50, 0x001c474b, 0x001a4245, 0x00183d41, 0x0017383c, 0x00153338, 0x00142e34, 0x00112a30, 0x0011242c, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0014242f, 0x00142430, 0x0013242e, 0x0013232e, 0x0014232e, 0x0013222e, 0x0013222f, 0x0013222f, 0x0014212c, 0x0013202a, 0x0013202a, 0x00132029, 0x00132029, 0x00132029, 0x0013202a, 0x0013202a, 0x0013202a, 0x0013202a, 0x0014212b, 0x0014212b, 0x0014212b, 0x0014222c, 0x0014222d, 0x0014232e, 0x0014242f, 0x00162530, 0x00172631, 0x00182732, 0x00182833, 0x00182833, 0x00182732, 0x00172633, 0x00172633, 0x00182834, 0x00182b37, 0x00192c38, 0x00182c38, 0x00182c38, 0x00182c39, 0x001a2d39, 0x001a2d39, 0x001a2c39, 0x001a2b38, 0x001a2b38, 0x001a2b37, 0x001a2b36, 0x00192a34, 0x00182934, 0x00172833, 0x00152731, 0x00152631, 0x00142530, 0x0014242f, 0x0014242d, 0x0013242d, 0x0013242c, 0x0013232b, 0x00112028, 0x00111c25, 0x000f1820, 0x000c141b, 0x000c141c, 0x0014202a, 0x00213140, 0x00284052, 0x00334e63, 0x00406078, 0x004f718c, 0x00547994, 0x00577f98, 0x006089a2, 0x00739cb2, 0x0084adbe, 0x0097bdc8, 0x00a7c7cb, 0x00b4cbcc, 0x00b9cccc, 0x00bccccc, 0x00bdcccc, 0x00c0cccc, 0x00c0cccc, 0x00c2cccc, 0x00c1cccc, 0x00bbcccc, 0x00a4c5ca, 0x0079a6b4, 0x0059899c, 0x004b778c, 0x0046697d, 0x00385465, 0x00304654, 0x00283a46, 0x0022343d, 0x0024353f, 0x002f3f4b, 0x00283944, 0x0024343f, 0x00273842, 0x002b3b48, 0x002f404d, 0x0030424f, 0x0030414d, 0x00293842, 0x0023303c, 0x0025323e, 0x0027323e, 0x0028343d, 0x0025303b, 0x00212c34, 0x001c2730, 0x001b252f, 0x001a242d, 0x00162028, 0x00182329, 0x001b252c, 0x00202930, 0x001c242b, 0x001c242a, 0x001c2429, 0x00171f26, 0x001b242c, 0x00202930, 0x001d272e, 0x001d262d, 0x001f252d, 0x0020242c, 0x001f222a, 0x00202029, 0x001d1d27, 0x00191a23, 0x0015171c, 0x00121418, 0x00101216, 0x00141418, 0x00131318, 0x00121218, 0x00121317, 0x00141419, 0x0014141a, 0x0013131a, 0x00121219, 0x00131219, 0x0013131a, 0x0016131b, 0x0017141c, 0x0017141b, 0x0018141a, 0x00171419, 0x0017141b, 0x0018161d, 0x001a181f, 0x001d1c23, 0x001d1d25, 0x001c1c24, 0x001a1b22, 0x001a1921, 0x001a1921, 0x001d1c24, 0x0023222b, 0x0025242e, 0x00272830, 0x00292933, 0x00282934, 0x00282833, 0x00242630, 0x0023242e, 0x00242630, 0x0021232d, 0x0020202a, 0x001f1e28, 0x001d1d27, 0x001d1e27, 0x001c1d26, 0x0014161f, 0x0013141c, 0x0012121a, 0x00111118, 0x000d0d14, 0x000c0d14, 0x00101017, 0x00101016, 0x00101117, 0x0014151a, 0x0015181d, 0x00151820, 0x00191f27, 0x001d242c, 0x001b232c, 0x00202831, 0x00202a32, 0x001f2931, 0x001d282e, 0x001a2329, 0x00192228, 0x00192127, 0x00182028, 0x001f262d, 0x001c242c, 0x00182029, 0x001c242e, 0x00212c35, 0x001f2c34, 0x00202f37, 0x00223038, 0x00222e38, 0x00202a34, 0x00232c36, 0x00242c37, 0x00242c38, 0x00242c39, 0x00242d3a, 0x00232d3a, 0x0025303c, 0x0028323e, 0x0026323e, 0x00293742, 0x00293743, 0x002a3a45, 0x00273844, 0x00293a48, 0x002e3f4f, 0x002e4050, 0x00304353, 0x002d4151, 0x002d4050, 0x00304454, 0x00354a58, 0x00344b5a, 0x00354d5d, 0x00385060, 0x003c5265, 0x0040586f, 0x00486c80, 0x006192a2, 0x0087bac2, 0x00a4c9cb, 0x00b3cccc, 0x00bacccc, 0x00c2cccc, 0x00c4cccc, 0x00c7cccc, 0x00c7cccb, 0x00c7cccc, 0x00c7cccc, 0x00c7cccc, 0x00c8cccc, 0x00c8cccc, 0x00c6cccc, 0x00c4cccc, 0x00bdcccc, 0x00b3c9cc, 0x009cbdc7, 0x0080a8b9, 0x00608aa0, 0x00486c82, 0x00304c5f, 0x00243a4c, 0x00192936, 0x000f1b24, 0x000b151d, 0x000d1820, 0x00121f29, 0x0014242e, 0x00152430, 0x00162531, 0x00152632, 0x00152832, 0x00142832, 0x00162833, 0x00172834, 0x00172934, 0x00152834, 0x00182b37, 0x001e333f, 0x00243b47, 0x002a414e, 0x002c4453, 0x002e4857, 0x002e4b59, 0x002f4b5a, 0x00304c5c, 0x00304c5e, 0x00304d5c, 0x00314f5d, 0x00314f5e, 0x00314f5e, 0x0032505f, 0x0033505f, 0x00334f5e, 0x00324d5d, 0x002d4856, 0x00263e4b, 0x00203642, 0x001c313f, 0x001a303f, 0x001a303f, 0x001c303e, 0x001c303e, 0x001c303d, 0x001c303c, 0x001b303c, 0x001b303b, 0x00192e3a, 0x00182d38, 0x00192c37, 0x00182c36, 0x00172a34, 0x00172934, 0x00152833, 0x00142832, 0x00152731, 0x00162630, 0x00162530, 0x00152530, 0x00142430, 0x00142430, 0x00122430, 0x00122431, 0x00122531, 0x00142733, 0x00142733, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00143036, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183d41, 0x00183f43, 0x001a4245, 0x001a4347, 0x001a4448, 0x001b4649, 0x001b4649, 0x001c4649, 0x001c474b, 0x001c474b, 0x001c4649, 0x001b4649, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c484c, 0x001c4a4d, 0x001d4c50, 0x001e4f51, 0x001f5154, 0x00205457, 0x00215659, 0x0022595c, 0x00245c5e, 0x00287484, 0x0031a4cb, 0x00297a8c, 0x00266264, 0x00256264, 0x00256163, 0x00246062, 0x00245f61, 0x002c90b0, 0x002d9cc0, 0x0020565a, 0x00205254, 0x001e4d50, 0x001c474b, 0x001a4347, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0011242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0014242f, 0x00142430, 0x0013242e, 0x0013232e, 0x0014232e, 0x0014232e, 0x00142330, 0x00142330, 0x0014222c, 0x0013202a, 0x0013202a, 0x00132028, 0x00132028, 0x00132029, 0x0013202a, 0x0013202a, 0x0013202a, 0x0014212b, 0x0014212b, 0x0014212b, 0x0014212b, 0x0014212c, 0x0014222d, 0x0014222d, 0x0014242f, 0x00152430, 0x00172631, 0x00182732, 0x00182732, 0x00182732, 0x00182732, 0x00172633, 0x00172633, 0x00182834, 0x00182b38, 0x00192c38, 0x00182c38, 0x00182c38, 0x00182d39, 0x001b2e3a, 0x001b2e3a, 0x001a2c39, 0x001a2b38, 0x001a2b38, 0x001a2b37, 0x001a2b36, 0x00192a34, 0x00182934, 0x00172833, 0x00162832, 0x00152631, 0x00142530, 0x0014242f, 0x0014242c, 0x0014242c, 0x0014222c, 0x00132029, 0x00101d25, 0x000e181f, 0x000b1318, 0x000a131a, 0x00121c27, 0x001e2d3c, 0x00293e50, 0x00334f64, 0x0043667d, 0x0059809a, 0x006b96b1, 0x0072a0b7, 0x0081acc0, 0x0093bac7, 0x00a4c4cb, 0x00b0cacc, 0x00bacccc, 0x00c2cccc, 0x00c8cccb, 0x00c8ccc8, 0x00c9ccc9, 0x00c9ccc9, 0x00c8cccb, 0x00c8cccb, 0x00c9cccc, 0x00c8cccc, 0x00c4cccc, 0x00b3cbcc, 0x0088b0bb, 0x006c9bad, 0x00538095, 0x00486c81, 0x00385466, 0x00314755, 0x00293c48, 0x0024353e, 0x00263840, 0x002f404c, 0x00263742, 0x00243440, 0x00283944, 0x002b3c49, 0x002d3f4b, 0x002e404c, 0x002c3c48, 0x0024333c, 0x0022313c, 0x0025333e, 0x0026323e, 0x0026323c, 0x00222e38, 0x001f2a32, 0x001e2831, 0x001c262f, 0x001a242c, 0x0018242b, 0x00162027, 0x00152027, 0x00192228, 0x00182127, 0x00192127, 0x001b2328, 0x00182027, 0x00182229, 0x001d282f, 0x001e2830, 0x0020282f, 0x00222830, 0x00242931, 0x00252831, 0x00262730, 0x0024242c, 0x00202128, 0x001c1e23, 0x00191c20, 0x00191b1f, 0x001a1a1e, 0x001b191e, 0x0018181c, 0x0018181c, 0x0019191d, 0x001a181d, 0x0018151a, 0x00161418, 0x00161418, 0x00151318, 0x00141116, 0x00141014, 0x00141012, 0x00130f11, 0x00110d10, 0x00100c0f, 0x00100c10, 0x00100c10, 0x00100d10, 0x000f0d10, 0x000f0c10, 0x000e0c0f, 0x000f0b0d, 0x00100c0e, 0x00100c0f, 0x00110c11, 0x00110d12, 0x00100d12, 0x00100c11, 0x000f0c11, 0x00100c11, 0x000f0c10, 0x000d0c10, 0x000d0c10, 0x000c0a0e, 0x000d090e, 0x000d080d, 0x000d0a0e, 0x00100d10, 0x00111013, 0x00101011, 0x00100f11, 0x00111013, 0x00121014, 0x00100f13, 0x00121013, 0x00171315, 0x00181416, 0x00181517, 0x001a181a, 0x001c1c1f, 0x001d1f24, 0x001d2027, 0x001c2028, 0x001d242c, 0x00212932, 0x00202a33, 0x00202a32, 0x001e282f, 0x001c242c, 0x00192228, 0x00181f25, 0x00141b22, 0x001b2129, 0x00202830, 0x00171f28, 0x00141d26, 0x001d2830, 0x00202d35, 0x001f2c34, 0x00223038, 0x0024303a, 0x00222d38, 0x00242e38, 0x00242d38, 0x00242d38, 0x00242d3a, 0x00242e3a, 0x00232e3a, 0x0025313d, 0x0025313e, 0x00283440, 0x002e3c48, 0x002d3b47, 0x00293945, 0x00273844, 0x00293a49, 0x002d3e4e, 0x002c3e4e, 0x00304453, 0x002f4453, 0x002d4251, 0x00314656, 0x00354c5c, 0x00334b5c, 0x00364e60, 0x003b5465, 0x003f586c, 0x00446178, 0x00588599, 0x0085b6c2, 0x00aacbcc, 0x00bacccc, 0x00c1cccc, 0x00c4cccc, 0x00c6cccc, 0x00c9cccb, 0x00cacccb, 0x00cbcccb, 0x00cbcccb, 0x00cbcccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cbcccb, 0x00c8cccc, 0x00c3cccc, 0x00b8cccc, 0x00a9c7cb, 0x008db5c3, 0x006d97ab, 0x004c7084, 0x00314f63, 0x0024384a, 0x00182735, 0x00101a24, 0x0009141c, 0x000c1820, 0x00111f28, 0x0013222c, 0x0015242f, 0x00152531, 0x00142731, 0x00142731, 0x00172831, 0x00182932, 0x00172934, 0x00162935, 0x00192d39, 0x00203742, 0x00273f4a, 0x002b4350, 0x002c4654, 0x002e4a58, 0x002f4b5a, 0x00304c5b, 0x00304c5c, 0x00304c5e, 0x00304d5c, 0x00304f5e, 0x0030505e, 0x0031505e, 0x0032505f, 0x00314f5e, 0x00314f5e, 0x00314e5e, 0x002f4a58, 0x0029424f, 0x00233945, 0x001e3441, 0x001b3140, 0x001c3140, 0x001c303e, 0x001c303d, 0x001c303d, 0x001c303c, 0x001c303c, 0x001b303c, 0x001b303b, 0x00192d38, 0x00192c37, 0x00182c36, 0x00182a34, 0x00172934, 0x00152833, 0x00142832, 0x00142832, 0x00162631, 0x00162631, 0x00152631, 0x00142530, 0x00142530, 0x00122430, 0x00122431, 0x00122531, 0x00142733, 0x00142733, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00143036, 0x00143439, 0x0017383c, 0x00183c40, 0x00183f43, 0x001a4245, 0x001a4448, 0x001b4649, 0x001c474b, 0x001c484c, 0x001d4a4d, 0x001c4a4d, 0x001c4a4d, 0x001c4a4d, 0x001c4a4d, 0x001d4b4e, 0x001d4b4e, 0x001d4b4e, 0x001d4c50, 0x001e4d50, 0x001e4f51, 0x001e5053, 0x00205254, 0x00205457, 0x00215659, 0x0022585b, 0x00245c5e, 0x00245d60, 0x00287586, 0x0032a5cb, 0x00297b8c, 0x00256364, 0x00256364, 0x00256264, 0x00256163, 0x00245f61, 0x002c90b0, 0x002d9cc0, 0x0020585b, 0x00205254, 0x001e4d50, 0x001c474b, 0x001a4347, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00122a30, 0x0011242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00142430, 0x0014242f, 0x0013242f, 0x0014232e, 0x0014232e, 0x0014232e, 0x00142330, 0x00142330, 0x0014222c, 0x0013202a, 0x0013202a, 0x00132028, 0x00132028, 0x0012202a, 0x0012202a, 0x0012202a, 0x0014212b, 0x0014212b, 0x0014222b, 0x0014222b, 0x0014222b, 0x0014212c, 0x0014212c, 0x0014222c, 0x0014242e, 0x00152430, 0x00162530, 0x00172631, 0x00172631, 0x00182732, 0x00172632, 0x00172632, 0x00172632, 0x00182834, 0x00182a36, 0x00192b37, 0x00182b38, 0x00182c38, 0x00192c38, 0x001a2e3a, 0x001b2e3a, 0x001a2d39, 0x001a2c38, 0x001a2b38, 0x001a2b37, 0x001a2b36, 0x00192a34, 0x00182a34, 0x00172833, 0x00162832, 0x00152731, 0x00142530, 0x0014242f, 0x0014242c, 0x0014232c, 0x0015212c, 0x00121e27, 0x000c1820, 0x0009141b, 0x00081218, 0x000d1822, 0x001c2b37, 0x00293e4e, 0x00375365, 0x004c7085, 0x006890a5, 0x0082acbe, 0x0094bcc8, 0x00a2c4cb, 0x00aec9cc, 0x00b7cccc, 0x00bccccc, 0x00c1cccc, 0x00c6cccc, 0x00cacccb, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00caccca, 0x00caccca, 0x00cbcccb, 0x00cacccc, 0x00c7cccc, 0x00bacccc, 0x009dc0c6, 0x0078a6b8, 0x005b889c, 0x00496e83, 0x00375466, 0x00334858, 0x002c3f4a, 0x00273842, 0x00253740, 0x002c3e48, 0x00233440, 0x0021323d, 0x00283944, 0x002c3c49, 0x002c3d4a, 0x002b3d49, 0x00243541, 0x0020303a, 0x0025343e, 0x00273440, 0x00232f3b, 0x00222c37, 0x001d2832, 0x001e2831, 0x00212b34, 0x001d272f, 0x0019242a, 0x001a242b, 0x00152026, 0x00182128, 0x00182027, 0x00151d23, 0x00192127, 0x001c242a, 0x001c242b, 0x001c252c, 0x00202a30, 0x00202b32, 0x00212b33, 0x00242b33, 0x00262c34, 0x00282d35, 0x002b2d36, 0x00282b34, 0x00252830, 0x0022262c, 0x0021262c, 0x0020242a, 0x00202027, 0x00201f26, 0x001c1e24, 0x001b1c21, 0x001c1c21, 0x001c1c21, 0x001b191f, 0x001a191e, 0x001a191f, 0x001b191f, 0x001b181e, 0x001a171c, 0x001a171b, 0x001a1618, 0x00181417, 0x00181316, 0x00161214, 0x00141214, 0x00141114, 0x00141114, 0x00141114, 0x00141012, 0x00140f10, 0x00151011, 0x00150f12, 0x00140f12, 0x00140f12, 0x00140f12, 0x00140e11, 0x00140e11, 0x00140e11, 0x00130e11, 0x00110e10, 0x00141013, 0x00151114, 0x00161016, 0x00140f15, 0x00140f14, 0x00151115, 0x00181518, 0x00181619, 0x00181618, 0x00161316, 0x00171416, 0x00171417, 0x00181418, 0x001c181c, 0x001c1a1e, 0x001c1c20, 0x001f1f22, 0x00222428, 0x0024282c, 0x0024252d, 0x0022242c, 0x001e222b, 0x00202630, 0x00232c34, 0x00232d35, 0x00202a31, 0x001c242c, 0x00192228, 0x00171e24, 0x00141a21, 0x00151c23, 0x001d242c, 0x001b242c, 0x00141d26, 0x0017212a, 0x001b2830, 0x001f2c34, 0x00223038, 0x0026333c, 0x00242f39, 0x00232d38, 0x00232d38, 0x00242e38, 0x00242e3b, 0x0026313d, 0x0027343f, 0x002a3843, 0x00283441, 0x00273441, 0x002c3a47, 0x002e3d4a, 0x002b3c48, 0x002a3b48, 0x00283949, 0x002c3c4c, 0x002a3d4c, 0x002e4251, 0x00304554, 0x002d4152, 0x00314657, 0x00344c5c, 0x00304858, 0x00324a5c, 0x003b5365, 0x0040596f, 0x004a6c82, 0x0078a6b4, 0x00a1c8cb, 0x00b8cccc, 0x00c3cccc, 0x00c8cccc, 0x00c8cccc, 0x00cacccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccb, 0x00cccbcb, 0x00cbcccb, 0x00cacccc, 0x00c9cccc, 0x00c5cccc, 0x00bfcccc, 0x00b4cacc, 0x00a0bfc8, 0x0079a0b1, 0x00517488, 0x00344e63, 0x00223546, 0x00162430, 0x000c1820, 0x0008141c, 0x000d1921, 0x00121e27, 0x0015222d, 0x00152431, 0x00142731, 0x00142731, 0x00172831, 0x00172832, 0x00172834, 0x00162935, 0x001b303c, 0x00223944, 0x0028414c, 0x002c4552, 0x002d4856, 0x002e4a58, 0x002f4c5a, 0x00304c5b, 0x00304c5c, 0x00304c5e, 0x00304d5d, 0x00304f5e, 0x0030505e, 0x0030505e, 0x0032505f, 0x0032505f, 0x00314f5e, 0x00324e5d, 0x00304b59, 0x002b4451, 0x00243c48, 0x001f3542, 0x001c313f, 0x001c313f, 0x001c303d, 0x001c303c, 0x001b303c, 0x001b303c, 0x001b303c, 0x001b303c, 0x001b303c, 0x00192d39, 0x00192c38, 0x00192c38, 0x00182b36, 0x00182936, 0x00162934, 0x00152833, 0x00152833, 0x00152832, 0x00152731, 0x00152631, 0x00142530, 0x00142531, 0x00132531, 0x00122531, 0x00132632, 0x00142733, 0x00142734, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0012242c, 0x0010282e, 0x00132c32, 0x00143036, 0x00143338, 0x0016363b, 0x00183c40, 0x00183f43, 0x001a4245, 0x001b4448, 0x001c474b, 0x001c4a4d, 0x001d4b4e, 0x001d4c50, 0x001d4d50, 0x001e4d50, 0x001e4f51, 0x001e4f51, 0x001e4f51, 0x001e4f51, 0x001e5053, 0x001e5053, 0x001f5053, 0x001f5154, 0x00205254, 0x00205356, 0x00205558, 0x0021585a, 0x0022595c, 0x00245c5e, 0x00245d60, 0x00245f61, 0x00297686, 0x0032a5cb, 0x00297b8c, 0x00256364, 0x00256364, 0x00256264, 0x00256163, 0x00245f61, 0x002c90b0, 0x002d9cc0, 0x0020585b, 0x00205254, 0x001e4d50, 0x001c474b, 0x001a4347, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00122a30, 0x0011242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00142430, 0x0014242f, 0x0014242f, 0x0014242e, 0x0014232e, 0x0014232e, 0x00142330, 0x00142330, 0x0014222e, 0x0013202c, 0x0013202c, 0x0013202a, 0x0013202a, 0x0012202b, 0x0012212b, 0x0012212b, 0x0014212b, 0x0014212b, 0x0014222b, 0x0015232b, 0x0014222b, 0x0014212b, 0x0014212b, 0x0013212c, 0x0014232e, 0x0014242f, 0x00162530, 0x00162530, 0x00162530, 0x00162530, 0x00162530, 0x00162530, 0x00162530, 0x00172733, 0x00172834, 0x00182935, 0x00182a37, 0x00182c38, 0x00182c38, 0x00182c38, 0x00192c39, 0x001a2d39, 0x00192c38, 0x001a2b38, 0x001a2b37, 0x001a2b36, 0x00192a34, 0x00182a34, 0x00172833, 0x00162832, 0x00162832, 0x00152530, 0x00152430, 0x0014232c, 0x0015222c, 0x00131e28, 0x000f1922, 0x000b141d, 0x0008121a, 0x000b151e, 0x00182532, 0x00283c4a, 0x00365464, 0x0052788a, 0x0075a0b4, 0x0094bcc8, 0x00aac8cc, 0x00b7cccc, 0x00becccc, 0x00c4cccc, 0x00c7cccc, 0x00c8cccc, 0x00c8cccc, 0x00c9cccc, 0x00cbccca, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00ccccc9, 0x00cbcccb, 0x00cbcccb, 0x00cbcccb, 0x00cbcccb, 0x00c9cccc, 0x00becccc, 0x00acc9cb, 0x0085b0be, 0x00628ea1, 0x00496f84, 0x00345164, 0x00304655, 0x002c3f4a, 0x00283942, 0x00243740, 0x00293b46, 0x00243440, 0x001f303b, 0x00283944, 0x002b3c48, 0x00283b47, 0x00263945, 0x00233440, 0x0024333c, 0x0027343f, 0x0024313d, 0x001f2935, 0x001f2833, 0x001c242e, 0x001e252f, 0x00222933, 0x00202831, 0x00192329, 0x00172128, 0x00172027, 0x00171d25, 0x00181e25, 0x00181d24, 0x001c2329, 0x00222830, 0x00212830, 0x001f2830, 0x00202b32, 0x00222c34, 0x00222c34, 0x00242c34, 0x00272d35, 0x002a3038, 0x002e323c, 0x002e323b, 0x002b2f38, 0x002a2f36, 0x002b3037, 0x00292d34, 0x00272931, 0x00252730, 0x0022242d, 0x001f222a, 0x001f2128, 0x00202128, 0x00202027, 0x001e1e25, 0x001f1f25, 0x00202026, 0x00211f26, 0x00201e25, 0x00211d24, 0x00201c21, 0x00201b20, 0x001f191e, 0x001c171b, 0x001b1619, 0x00191518, 0x001a1619, 0x001a1519, 0x00191418, 0x001a1317, 0x001c1418, 0x001b1317, 0x001b1318, 0x001a1217, 0x001a1217, 0x001b1317, 0x001a1317, 0x00181117, 0x00181017, 0x00181118, 0x00181318, 0x001c161c, 0x001f1920, 0x001f1920, 0x001e1a20, 0x001e1a1f, 0x001c1a1e, 0x001c191e, 0x001b181c, 0x001b181b, 0x001c181c, 0x001d1a1f, 0x001d1a21, 0x00201d25, 0x00202129, 0x0022242a, 0x0024282f, 0x00272d34, 0x00272d34, 0x00282b33, 0x00292b34, 0x00262932, 0x00222830, 0x00242b34, 0x00232b34, 0x00212c33, 0x001d262d, 0x00192228, 0x00182026, 0x00141a21, 0x00141a22, 0x001b232a, 0x001d252e, 0x00172028, 0x00151f28, 0x0018232b, 0x001c2730, 0x001d2931, 0x00242f39, 0x0026303b, 0x00242d38, 0x00262f3a, 0x0028303c, 0x0028303d, 0x00293441, 0x00283643, 0x00293844, 0x002a3845, 0x00293844, 0x002b3a47, 0x002e3d4a, 0x002c3d4a, 0x002b3c49, 0x00283948, 0x002c3d4e, 0x002c4050, 0x00304554, 0x00344858, 0x00304454, 0x00304554, 0x00344b5a, 0x00304859, 0x00324a5c, 0x003a5467, 0x00425c72, 0x0054798e, 0x0090bac4, 0x00afcccc, 0x00bfcccc, 0x00c6cccc, 0x00cacccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00cbcccc, 0x00cacccc, 0x00c8cccc, 0x00c4cccc, 0x00bacbcc, 0x00a4c4c9, 0x0080a8b7, 0x00547a8f, 0x00304e62, 0x001c3140, 0x0011202d, 0x000a1421, 0x0008121c, 0x000f1922, 0x0014202b, 0x00162430, 0x00152530, 0x00152631, 0x00162832, 0x00162832, 0x00162833, 0x00152935, 0x001c313c, 0x00233b46, 0x0028424d, 0x002c4653, 0x002c4856, 0x002e4a58, 0x002f4c5a, 0x00304c5b, 0x00304c5c, 0x00304c5e, 0x00304c5d, 0x00304e5d, 0x0030505e, 0x0030505e, 0x00324f5f, 0x00334f5f, 0x00324e5e, 0x00314c5c, 0x00304a59, 0x002b4452, 0x00243c49, 0x00203643, 0x001c313d, 0x001c303c, 0x001c303a, 0x001b3039, 0x001a2f39, 0x001a2f3a, 0x001a2f3c, 0x001b303c, 0x001a2f3c, 0x001a2d3a, 0x00192c38, 0x00192c38, 0x00182b37, 0x00182a37, 0x00172935, 0x00172934, 0x00172934, 0x00152833, 0x00142832, 0x00142732, 0x00152631, 0x00152631, 0x00132631, 0x00132632, 0x00132632, 0x00142834, 0x00142834, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153338, 0x0015363b, 0x00183a3e, 0x00183f43, 0x001a4245, 0x001b4649, 0x001c484c, 0x001d4b4e, 0x001d4d50, 0x001e5053, 0x001f5154, 0x00205254, 0x001f5254, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205457, 0x00205457, 0x00205558, 0x00215659, 0x0021585a, 0x0022585b, 0x00235a5c, 0x00245c5f, 0x00245d60, 0x00245f61, 0x00256163, 0x00297787, 0x0032a5cb, 0x002a7c8d, 0x00276466, 0x00256364, 0x00256264, 0x00256163, 0x00245f61, 0x002c90b0, 0x002d9cc0, 0x0020565a, 0x00205254, 0x001e4d50, 0x001c474b, 0x001a4347, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0011242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00142430, 0x0014242f, 0x0014242f, 0x0014242e, 0x0014232e, 0x0014232e, 0x00142330, 0x00142330, 0x0014222e, 0x0013202c, 0x0013202c, 0x0012202a, 0x00122029, 0x0012202b, 0x0013212c, 0x0013212c, 0x0014202c, 0x0014212c, 0x0015222b, 0x0015232b, 0x0014222b, 0x0014212b, 0x0014212b, 0x0014222c, 0x0014222d, 0x0014222d, 0x0014232e, 0x0015242e, 0x0014242e, 0x0014242f, 0x0014242f, 0x0014242f, 0x0014242f, 0x00152531, 0x00162834, 0x00182834, 0x00182834, 0x00182935, 0x00182936, 0x00182a36, 0x00182b37, 0x00182c38, 0x00182b37, 0x001a2b38, 0x001a2b37, 0x001a2b36, 0x00192a34, 0x00182a34, 0x00182934, 0x00172832, 0x00162731, 0x00162530, 0x0015242e, 0x0015212c, 0x00141f28, 0x00101923, 0x000c141c, 0x00091219, 0x000b141c, 0x00131f2b, 0x00203444, 0x00345164, 0x00567c8e, 0x007ea7b6, 0x00a0c3ca, 0x00b1cbcc, 0x00becccc, 0x00c4cccc, 0x00c8cccc, 0x00c9cccc, 0x00cbcbcc, 0x00cbcbcb, 0x00cacccb, 0x00cbcccc, 0x00cbccca, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00cccbc9, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cacbcc, 0x00c0cccc, 0x00b3cbcc, 0x0090b8c4, 0x00638fa3, 0x00456b80, 0x00314e5f, 0x002e4452, 0x002c3e4b, 0x00283a44, 0x00273942, 0x00293a45, 0x00233441, 0x001f313c, 0x00273844, 0x00283945, 0x00283a46, 0x00283b47, 0x00283744, 0x0024343f, 0x0026343f, 0x00222e3a, 0x001e2834, 0x001d2530, 0x001a212b, 0x001c222c, 0x00202730, 0x00202830, 0x00182128, 0x00172026, 0x00192027, 0x00131920, 0x00161b21, 0x00181d24, 0x0020262d, 0x00252c34, 0x00232c34, 0x00242c35, 0x00242d36, 0x00242e36, 0x00242d36, 0x00262e38, 0x00293039, 0x002b313b, 0x002e343d, 0x00303440, 0x00303440, 0x00303640, 0x00323841, 0x00313740, 0x002e333c, 0x002b303a, 0x00282c37, 0x00252932, 0x00262931, 0x00272831, 0x0026272e, 0x0024242c, 0x0024242c, 0x0025252c, 0x0026242d, 0x0027242d, 0x0027242c, 0x00262329, 0x00272228, 0x00262027, 0x00231d24, 0x00211c22, 0x00201b20, 0x001f1b20, 0x001e1a1f, 0x001d191d, 0x001e181c, 0x001d171c, 0x001d181c, 0x001e181d, 0x001e181d, 0x001d171d, 0x001e181f, 0x00201920, 0x00201921, 0x001e1820, 0x001d1820, 0x001c1920, 0x001f1c24, 0x00242028, 0x00242028, 0x00222028, 0x00201f25, 0x001e1d24, 0x001d1c23, 0x001c1c23, 0x001e1d24, 0x001f1f26, 0x00212028, 0x0022222b, 0x0024242f, 0x00272a34, 0x002a2f37, 0x002c3239, 0x002b333b, 0x00293039, 0x002a3038, 0x002c3038, 0x002b3038, 0x00262b34, 0x00252c35, 0x00242c34, 0x00232c34, 0x00222c33, 0x001e272c, 0x001e262c, 0x00161c24, 0x00151c24, 0x001a2128, 0x001a222a, 0x00151d25, 0x00161e27, 0x0018222b, 0x001c262f, 0x001c2730, 0x001d2833, 0x00242e38, 0x00232c36, 0x00232c37, 0x0028303c, 0x0028303f, 0x002a3442, 0x002a3744, 0x00283844, 0x002a3946, 0x002e3d4a, 0x002d3d4a, 0x002e3d4a, 0x002c3d4a, 0x002d3e4c, 0x00293a4b, 0x002e3f50, 0x00304454, 0x00344858, 0x00344b5b, 0x00324859, 0x00304758, 0x00324a5a, 0x00344c5d, 0x00365063, 0x003e586c, 0x00446278, 0x0062899c, 0x009fc4c8, 0x00b7cccc, 0x00c4cccb, 0x00c8cccb, 0x00cacccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cacccb, 0x00c8cccc, 0x00c4cccc, 0x00b9cccc, 0x00a8c7cb, 0x0084acba, 0x00567a8d, 0x002f4a5c, 0x001a2e3e, 0x00101d2c, 0x0008131f, 0x000c141e, 0x00101c27, 0x0014202c, 0x0014232e, 0x00142530, 0x00152631, 0x00162732, 0x00152832, 0x00152935, 0x001c313c, 0x00243c47, 0x0029424d, 0x002c4753, 0x002c4856, 0x002e4a58, 0x00304c5a, 0x00304c5b, 0x00304c5c, 0x00304c5e, 0x00304d5d, 0x00304e5c, 0x00304e5c, 0x00314e5c, 0x00324d5f, 0x00334d5e, 0x00324d5c, 0x00304b59, 0x002f4958, 0x002c4452, 0x00253c4a, 0x00203543, 0x001c303d, 0x001a2e3b, 0x00192e39, 0x00182e38, 0x00192e39, 0x001a2f3a, 0x001a2e3b, 0x001a2e3c, 0x00192e3c, 0x00192d39, 0x00192c38, 0x00182c38, 0x00182b37, 0x00182a37, 0x00172935, 0x00172934, 0x00162833, 0x00152834, 0x00142834, 0x00152834, 0x00152734, 0x00152733, 0x00142734, 0x00142734, 0x00142734, 0x00142835, 0x00152835, 0x000d1d28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x00153439, 0x0017383c, 0x00183d41, 0x001a4245, 0x001c4649, 0x001c4a4d, 0x001d4c50, 0x001f5053, 0x00205254, 0x00205356, 0x00205558, 0x00215659, 0x0021585a, 0x0021585a, 0x0021585a, 0x0021585a, 0x0022585a, 0x0022585a, 0x0022585b, 0x0022585b, 0x0021585b, 0x0022595c, 0x00235a5c, 0x00245c5e, 0x00245d60, 0x00245e60, 0x00245f61, 0x00256163, 0x00256264, 0x00297888, 0x0032a5cb, 0x002a7c8d, 0x00276466, 0x00256364, 0x00256264, 0x00256062, 0x00245f61, 0x002c90b0, 0x002d9cc0, 0x0020565a, 0x001f5154, 0x001d4c50, 0x001c474b, 0x001a4245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0011242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00142532, 0x00142431, 0x00142431, 0x00142430, 0x00142430, 0x0013232f, 0x00142330, 0x00142330, 0x0014222f, 0x0013202d, 0x00111f2b, 0x00101e29, 0x00111f28, 0x0011202a, 0x0012212b, 0x0012212b, 0x0014212b, 0x0014212b, 0x0014212b, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014212b, 0x0013202a, 0x0014212b, 0x0014222c, 0x0014222c, 0x0014222c, 0x0015232e, 0x0014232e, 0x0014232e, 0x0014242e, 0x00152430, 0x00182732, 0x00182833, 0x00182732, 0x00182732, 0x00182833, 0x00172934, 0x00172a35, 0x00182a35, 0x00182a36, 0x00192a37, 0x00192a37, 0x00192a37, 0x00192a34, 0x00192a34, 0x00182a34, 0x00182932, 0x00172831, 0x0017262f, 0x0017232d, 0x0014202a, 0x00111c24, 0x000d141d, 0x000b1218, 0x000b1218, 0x000f1924, 0x001c2c3b, 0x002d495f, 0x00557c93, 0x0084aebd, 0x00a8c6cb, 0x00becccc, 0x00c5cccc, 0x00cacccc, 0x00cbcccc, 0x00cccbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cacccb, 0x00c4ccca, 0x00b6cccc, 0x0096bcc5, 0x00628da2, 0x00406478, 0x00304c5d, 0x002e4453, 0x002b404c, 0x00273b47, 0x00273944, 0x00283a46, 0x00223541, 0x00203340, 0x00263945, 0x00263945, 0x00283c48, 0x002a3d49, 0x00293a47, 0x00253440, 0x0024313e, 0x00202b38, 0x001f2934, 0x001c242d, 0x00182128, 0x00182028, 0x001d252c, 0x0020282f, 0x00182027, 0x00171f25, 0x00192025, 0x0012171d, 0x0013181d, 0x00181f24, 0x00242b32, 0x00293239, 0x00242c35, 0x00272e38, 0x00272f38, 0x00262e37, 0x00262e37, 0x00293039, 0x002b323c, 0x002c323c, 0x002c333c, 0x002e343d, 0x00303640, 0x00303843, 0x00313844, 0x00303843, 0x002f3641, 0x002b323d, 0x002b323d, 0x002d343d, 0x002c323b, 0x002c3038, 0x002a2d35, 0x00292a32, 0x00282830, 0x0028282f, 0x00282832, 0x00292833, 0x00292832, 0x00282630, 0x0028262f, 0x0028242d, 0x0026222c, 0x0024212a, 0x00242029, 0x00242028, 0x00231f27, 0x00201c24, 0x001f1c23, 0x001f1c23, 0x00201c24, 0x00201c24, 0x00201c24, 0x001f1c24, 0x00201c24, 0x00232028, 0x0024222a, 0x0024222a, 0x00212128, 0x00202028, 0x00202128, 0x0024242c, 0x0024242d, 0x0020222b, 0x00202229, 0x0020232a, 0x0022242c, 0x00242730, 0x00252834, 0x00252934, 0x00262c36, 0x00272c37, 0x00282c37, 0x00292e38, 0x002f343e, 0x002f363f, 0x002f3540, 0x002e343e, 0x002b323c, 0x00293138, 0x00283038, 0x00282e36, 0x00272d34, 0x00262e35, 0x00242d34, 0x00242d34, 0x00202930, 0x00212930, 0x001a2028, 0x00171d24, 0x00192025, 0x00181f25, 0x00131b21, 0x00141c24, 0x00182129, 0x001b252e, 0x001c262f, 0x001b252f, 0x001d2832, 0x001e2832, 0x00202b35, 0x0026303c, 0x0027303e, 0x002a3442, 0x002c3844, 0x002c3b47, 0x002c3c48, 0x002e3d4b, 0x002d3c49, 0x002c3a48, 0x002a3b48, 0x002c3e4b, 0x00293c4c, 0x002f4154, 0x00304657, 0x00344b5c, 0x00334c5d, 0x00324c5c, 0x00314b5c, 0x00344c5f, 0x00375064, 0x003c576c, 0x00405c74, 0x00446980, 0x006f9dac, 0x00acc9cb, 0x00c2cccc, 0x00c9cccb, 0x00cbccca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cacccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cacccb, 0x00cacccb, 0x00c5cccc, 0x00bfcccc, 0x00abc7cb, 0x0086acb8, 0x0055788a, 0x002b4558, 0x0017293b, 0x000d1925, 0x000a141c, 0x000f1822, 0x00121e28, 0x0014212c, 0x0014242d, 0x0014242f, 0x00142630, 0x00142630, 0x00152832, 0x001b3039, 0x00243a45, 0x002a414d, 0x002d4652, 0x002f4855, 0x002f4857, 0x00304a59, 0x00314b5b, 0x00314c5c, 0x00314c5c, 0x00314c5b, 0x00314c5b, 0x00324e5c, 0x00314d5c, 0x00304c5c, 0x00304c5c, 0x00304c5a, 0x002f4b58, 0x002e4856, 0x002a414f, 0x00243947, 0x001e3441, 0x001b303e, 0x00182d3a, 0x00182c39, 0x00182c38, 0x00182d39, 0x00182d39, 0x00182d39, 0x00182d38, 0x00182c38, 0x00172c38, 0x00172c35, 0x00172b35, 0x00182a37, 0x00182a37, 0x00172935, 0x00172934, 0x00152834, 0x00152836, 0x00152836, 0x00152836, 0x00152836, 0x00152836, 0x00142835, 0x00142835, 0x00142836, 0x00152937, 0x00162937, 0x000d1d28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00112a30, 0x00142e34, 0x00153338, 0x0016363b, 0x00183c40, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4d50, 0x001f5256, 0x0020585f, 0x00215c61, 0x00225d63, 0x00235f64, 0x00246067, 0x00246168, 0x00246068, 0x00246268, 0x00246268, 0x00246269, 0x00246269, 0x0024636a, 0x0024636a, 0x0024646b, 0x0024646c, 0x0024656c, 0x0024666d, 0x0025676e, 0x0026686f, 0x00266870, 0x00266970, 0x00276c73, 0x002c89a1, 0x0032a5cb, 0x002a7b8c, 0x00276466, 0x00256364, 0x00256264, 0x00246062, 0x00245e60, 0x002c90b0, 0x002c9cc0, 0x00205559, 0x001f5154, 0x001d4c50, 0x001c474b, 0x001a4245, 0x00183d41, 0x0016363b, 0x00143036, 0x00142e34, 0x00112a30, 0x0012242c, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142430, 0x00142330, 0x00142330, 0x0014222f, 0x0013202d, 0x00111f2b, 0x00101e28, 0x00101e28, 0x00112029, 0x0012212b, 0x0012212b, 0x0014212b, 0x0014212b, 0x0014212b, 0x0014212c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014212b, 0x0013202a, 0x0013202a, 0x0014212b, 0x0014222c, 0x0014222c, 0x0014222d, 0x0014222d, 0x0014222d, 0x0013222e, 0x0014242e, 0x00152530, 0x00182732, 0x00182732, 0x00182732, 0x00182832, 0x00162932, 0x00172934, 0x00172934, 0x00182a35, 0x00192a37, 0x00192a37, 0x00192a37, 0x00192a34, 0x00192a34, 0x00192a34, 0x00182a34, 0x00182932, 0x0016252f, 0x0015212c, 0x00131c26, 0x000c141c, 0x000b1018, 0x000c1218, 0x000f151c, 0x0016232f, 0x00284053, 0x004b7084, 0x0083acbb, 0x00a9c8cc, 0x00b9cccc, 0x00c8cccc, 0x00cbcccc, 0x00cccbcc, 0x00cccbcc, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00c9cccb, 0x00c5ccca, 0x00b5cbcc, 0x0095bbc6, 0x00618ba0, 0x003b5f74, 0x00344f5f, 0x00304754, 0x002a3f4c, 0x00273c47, 0x00263a46, 0x00293c4a, 0x00243744, 0x00243844, 0x00283c48, 0x00283a46, 0x00293c48, 0x002c404b, 0x002a3c48, 0x00263643, 0x0024313f, 0x00202c39, 0x00202a35, 0x0019232b, 0x00171f25, 0x00161d24, 0x001e242b, 0x001e242c, 0x00161e25, 0x00151e24, 0x00161c24, 0x0010151c, 0x00141a1f, 0x001b2228, 0x00293138, 0x002c343c, 0x00252d36, 0x00283039, 0x00283039, 0x00272f38, 0x0028303a, 0x002c343c, 0x002e343d, 0x002d343c, 0x002c323c, 0x002d343c, 0x00303741, 0x00303843, 0x00303843, 0x002f3843, 0x002e3842, 0x002c3741, 0x00333c48, 0x00353d48, 0x00323943, 0x0030343e, 0x0030323c, 0x002f3038, 0x002c2e35, 0x002b2c34, 0x002b2c37, 0x002c2c38, 0x002b2c37, 0x00292a34, 0x002b2a34, 0x002a2933, 0x002a2832, 0x00292731, 0x00292730, 0x0028262f, 0x0028252e, 0x0025232c, 0x0025242c, 0x0025242c, 0x0027242e, 0x0028252e, 0x0027242e, 0x0025242c, 0x0024232c, 0x0026262e, 0x00282831, 0x00282832, 0x00262730, 0x0024262d, 0x0022242c, 0x0023262e, 0x00242730, 0x00242730, 0x00242830, 0x00272c33, 0x002b3038, 0x0030343f, 0x00303743, 0x00313844, 0x00313844, 0x00313843, 0x00303540, 0x002c333d, 0x002f343f, 0x00303841, 0x00303841, 0x00313841, 0x002c343d, 0x002a333b, 0x002a323b, 0x002b3139, 0x00282e36, 0x00272d35, 0x00262e35, 0x00242c33, 0x00222a31, 0x0020282f, 0x001c242b, 0x00171e24, 0x001c2328, 0x001b2127, 0x0011181e, 0x00121b21, 0x00151f26, 0x00182229, 0x001a242c, 0x001c2530, 0x001a242e, 0x0019242e, 0x001e2833, 0x00242e3b, 0x00293340, 0x002a3441, 0x002a3744, 0x00303f4b, 0x002f3e4a, 0x002c3b48, 0x002a3946, 0x002a3946, 0x00293b47, 0x00283b48, 0x00283a4b, 0x00304354, 0x0034495b, 0x00385060, 0x00344e5f, 0x00334c5e, 0x00344d60, 0x00365062, 0x003a5468, 0x003f5a6f, 0x00405c74, 0x00487086, 0x007babb8, 0x00b2cccc, 0x00c5cccc, 0x00cbccca, 0x00cccbc9, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cacccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccb, 0x00c9ccca, 0x00c4cccb, 0x00bbcccc, 0x00aac8cb, 0x0083a8b5, 0x004c6d7e, 0x00243c4e, 0x00142230, 0x000c151e, 0x000a141c, 0x000d1822, 0x00101d27, 0x0012202a, 0x0012232c, 0x0013242d, 0x0014252e, 0x00132630, 0x00182c36, 0x00233843, 0x002a404c, 0x002e4651, 0x002f4855, 0x002f4857, 0x00304a59, 0x00314b5b, 0x00314c5c, 0x00314c5a, 0x00304c5a, 0x00304c5a, 0x00304c5a, 0x00304c5a, 0x00304c5b, 0x00304b5a, 0x00304b59, 0x00304a58, 0x002c4654, 0x0028404d, 0x00243846, 0x001d3240, 0x001a2e3c, 0x00182c39, 0x00182c38, 0x00182c38, 0x00182d39, 0x00182d39, 0x00182c39, 0x00172c38, 0x00172c38, 0x00162b36, 0x00162b34, 0x00172b34, 0x00182a37, 0x00182a37, 0x00172935, 0x00172934, 0x00152834, 0x00152836, 0x00152836, 0x00152836, 0x00152836, 0x00152836, 0x00142937, 0x00152a37, 0x00162b38, 0x00162b38, 0x00162b38, 0x000e1e28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00132c32, 0x00142e34, 0x00153439, 0x00183a3e, 0x00183f43, 0x001a4347, 0x001c484c, 0x001d4c50, 0x00205458, 0x002786a2, 0x002ea0c7, 0x002fa2c8, 0x0030a2c8, 0x0030a2c8, 0x0030a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0032a4c8, 0x0032a4c8, 0x0032a4c8, 0x0032a4c8, 0x0032a4c8, 0x0032a6cb, 0x00309fc1, 0x00286d76, 0x00266466, 0x00256364, 0x00256163, 0x00245f61, 0x00245e61, 0x002c92b2, 0x002c9cc0, 0x00205559, 0x001e5053, 0x001d4b4e, 0x001c4649, 0x00194044, 0x00183c40, 0x0015363b, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00142532, 0x00142430, 0x00142330, 0x00142230, 0x0012212e, 0x0011202c, 0x00101e29, 0x00101e28, 0x00101f2a, 0x0010202b, 0x0011202b, 0x0013202b, 0x0013202b, 0x0014202c, 0x0014212c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0013202a, 0x00122029, 0x00122029, 0x00122029, 0x0013202a, 0x0014212b, 0x0014212c, 0x0014212c, 0x0014212c, 0x0014222d, 0x0014222d, 0x0014232e, 0x00172430, 0x00182631, 0x00182631, 0x00182731, 0x00172831, 0x00172932, 0x00172933, 0x00182a34, 0x00182a36, 0x00182934, 0x00182934, 0x00182934, 0x00182934, 0x00182934, 0x00182934, 0x00182832, 0x0016242e, 0x00141f28, 0x000e1720, 0x000a111a, 0x000a1018, 0x000c141a, 0x00141c24, 0x0020303e, 0x003a5a6f, 0x00739cac, 0x00a4c5ca, 0x00bccccc, 0x00c4cccc, 0x00cacccc, 0x00cccbcb, 0x00cbcccc, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00c9cccc, 0x00c3cccc, 0x00b0c9cb, 0x008cb0be, 0x00527b91, 0x00395b70, 0x00365061, 0x00304855, 0x002c414e, 0x00283c48, 0x00273b47, 0x00283b48, 0x00253844, 0x002b3e4a, 0x002c3f4b, 0x00283b47, 0x00283b46, 0x002a3e4a, 0x00273945, 0x00243542, 0x0024313f, 0x00232f3c, 0x00212c37, 0x001a242c, 0x00151d24, 0x00151c23, 0x0020272d, 0x001a2128, 0x00141b22, 0x00151c24, 0x00151c23, 0x0012181f, 0x00151c22, 0x001f262d, 0x00283239, 0x00283138, 0x00242d35, 0x00262e38, 0x00283039, 0x002c343c, 0x002c343e, 0x002e353f, 0x002f353e, 0x002d343c, 0x002c323c, 0x002d343d, 0x00303741, 0x00303944, 0x00303a44, 0x00303a45, 0x00303b45, 0x00333c48, 0x0037424c, 0x00363e49, 0x00313844, 0x00303541, 0x00313540, 0x0032343f, 0x0031343d, 0x0030333c, 0x0030333f, 0x00303340, 0x0030323e, 0x002d303c, 0x0030313d, 0x0030303d, 0x002f2f3c, 0x002e2e39, 0x0030303b, 0x0030303b, 0x002f2f3a, 0x002d2d3a, 0x002e2f3b, 0x002e2f3b, 0x002e2f3b, 0x002f2f3b, 0x002f2f3b, 0x002d2e39, 0x002c2c36, 0x002b2c36, 0x002c2d38, 0x002c2d38, 0x002c2c37, 0x00292c35, 0x00282c34, 0x002a2c36, 0x002c2f39, 0x002b303a, 0x002b313a, 0x002f353d, 0x00323842, 0x00363c48, 0x00373f4c, 0x00363f4c, 0x00353e4b, 0x00343c48, 0x00323945, 0x00303641, 0x002d333f, 0x002e3440, 0x002f3640, 0x00303842, 0x002f3841, 0x002c363f, 0x002c353e, 0x002c343c, 0x00283039, 0x00272f38, 0x00242d36, 0x00202931, 0x00222c34, 0x00212932, 0x001d242c, 0x001a2027, 0x00182025, 0x00192026, 0x00141b20, 0x00131a22, 0x00161e25, 0x00182028, 0x0019222a, 0x001d2630, 0x00202a34, 0x00202934, 0x001f2934, 0x00232e3a, 0x00283440, 0x002a3642, 0x00283742, 0x002b3b46, 0x002a3944, 0x002b3a48, 0x002c3c48, 0x002b3a47, 0x002b3c48, 0x00283b48, 0x00293c4c, 0x002f4153, 0x00334859, 0x00374f5f, 0x00354e60, 0x00354f60, 0x00364f61, 0x003a5467, 0x003d586b, 0x003f596e, 0x003f5c74, 0x004c748a, 0x0081b0bd, 0x00b2cccc, 0x00c4cccc, 0x00cbccca, 0x00cbcbca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccca, 0x00cacccb, 0x00c4cccc, 0x00bdcccc, 0x00aac5c8, 0x007b9caa, 0x003e5d70, 0x001a303e, 0x00101b26, 0x000b131c, 0x000a141e, 0x000d1823, 0x00121f28, 0x0012212a, 0x0013232c, 0x0013242d, 0x0012252d, 0x00152a33, 0x001e343c, 0x00283e48, 0x002c4450, 0x002d4855, 0x002e4957, 0x00304a59, 0x00304a5a, 0x00314b5a, 0x00304c59, 0x00304c59, 0x00304c59, 0x00304c59, 0x00304c59, 0x00304c5a, 0x002f4a5a, 0x00304959, 0x00304858, 0x002b4453, 0x00263c4a, 0x00213642, 0x001c313c, 0x00192e39, 0x00182c38, 0x00182c37, 0x00182c37, 0x00182c38, 0x00182c38, 0x00182c38, 0x00182c37, 0x00182c37, 0x00182c36, 0x00182b35, 0x00182b35, 0x00182a35, 0x00182a35, 0x00172934, 0x00172934, 0x00152834, 0x00152836, 0x00152836, 0x00152836, 0x00152836, 0x00162937, 0x00162a38, 0x00162b38, 0x00172c39, 0x00172c39, 0x00172c3a, 0x000e1e28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0015363b, 0x00183c40, 0x00194044, 0x001c4649, 0x001d4b4e, 0x001f5053, 0x00215f69, 0x002ea3c9, 0x002d9cc0, 0x002c95b5, 0x002d95b5, 0x002e95b5, 0x002e95b5, 0x002e96b4, 0x002e96b4, 0x002e95b4, 0x002e96b4, 0x002f96b4, 0x002f96b4, 0x002e95b4, 0x002e95b4, 0x002f95b4, 0x002e94b3, 0x002e94b3, 0x002e95b3, 0x002e95b3, 0x002e94b2, 0x002e94b2, 0x002e94b2, 0x002e94b2, 0x002e8fa9, 0x0028717d, 0x00276466, 0x00256364, 0x00256264, 0x00256163, 0x00245f61, 0x00246064, 0x002c9abd, 0x002c99bd, 0x00205458, 0x001e4f51, 0x001d4a4d, 0x001a4448, 0x00194044, 0x00173a3e, 0x00143439, 0x00143036, 0x00122c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152432, 0x00152431, 0x00142431, 0x0013222f, 0x0012202d, 0x00101e2a, 0x00101e29, 0x00101e29, 0x000f1f29, 0x0010202b, 0x0013202c, 0x0013202c, 0x0014202c, 0x0014212c, 0x0014222c, 0x0014222c, 0x0014212b, 0x0013202a, 0x00111f29, 0x00111f29, 0x00111f29, 0x00122029, 0x0013202a, 0x0014212b, 0x0014212b, 0x0014212c, 0x0014212c, 0x0014222d, 0x0014222d, 0x00172430, 0x00182531, 0x00182531, 0x00182530, 0x00172830, 0x00172830, 0x00172831, 0x00182933, 0x00182934, 0x00182934, 0x00182934, 0x00182934, 0x00182934, 0x00182934, 0x00172834, 0x00162531, 0x0014202b, 0x000f1923, 0x000a111a, 0x00080e17, 0x000a1017, 0x000e161e, 0x0019242e, 0x002b4052, 0x005c8095, 0x0098bdc5, 0x00b5cccc, 0x00c5cbcc, 0x00cacbcc, 0x00cccbcc, 0x00cccbca, 0x00cbcccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00c9cccc, 0x00c0cccc, 0x00a6c1c5, 0x006e92a1, 0x003a6078, 0x0037556b, 0x00385063, 0x00314856, 0x002e4350, 0x00293e4a, 0x00293c49, 0x00283a48, 0x00273a47, 0x002d404c, 0x002c3f4b, 0x00283b47, 0x00273a46, 0x00293c48, 0x00253844, 0x00233440, 0x0023323f, 0x0024303d, 0x00212d38, 0x001a242c, 0x00161e25, 0x00161d24, 0x001e252b, 0x00192028, 0x00161c24, 0x001b2128, 0x001b2129, 0x00171d24, 0x00181f25, 0x001e262c, 0x00242d34, 0x00253036, 0x00242d36, 0x00263038, 0x002c363f, 0x002f3841, 0x00303842, 0x00303842, 0x00303740, 0x002e343e, 0x002e343e, 0x002f353f, 0x00303742, 0x00303944, 0x00303a45, 0x00323c47, 0x00343d48, 0x0037404b, 0x0038444d, 0x00343f4b, 0x00343c49, 0x00353b48, 0x00343a46, 0x00363a44, 0x00343943, 0x00343944, 0x00373b48, 0x00393d4c, 0x00383d4c, 0x00373c4b, 0x003b404e, 0x003c404e, 0x00383c49, 0x00373947, 0x003b3e4b, 0x003d404c, 0x003b3e4b, 0x003b3e4c, 0x003c404d, 0x003c3f4d, 0x003b3e4c, 0x003b3e4c, 0x003b3d4b, 0x00383b48, 0x00343642, 0x00343642, 0x00343644, 0x00343644, 0x00333441, 0x0030343f, 0x00323540, 0x00343742, 0x00343845, 0x00343a46, 0x00343a45, 0x00333b44, 0x00343c47, 0x00383f4c, 0x00394250, 0x00384350, 0x0037414f, 0x00343d4c, 0x00333a48, 0x00303743, 0x002c323e, 0x002b313c, 0x002b323d, 0x002c343f, 0x002e3641, 0x002d3740, 0x002c3640, 0x002c343d, 0x0029323b, 0x00283039, 0x00242d36, 0x00202932, 0x001c2730, 0x001f2830, 0x001f252e, 0x001d242c, 0x00171d23, 0x00161c23, 0x00161d23, 0x00141c23, 0x00151e25, 0x00182028, 0x001a222b, 0x001f2731, 0x00242c38, 0x0026303a, 0x0025303b, 0x0025303c, 0x0026323e, 0x00283440, 0x00293843, 0x00263540, 0x0023323d, 0x002b3a46, 0x0030404c, 0x002b3b48, 0x00283b47, 0x00283b48, 0x002b3d4e, 0x002f4153, 0x00334859, 0x00344c5c, 0x00344c5e, 0x00375063, 0x00385063, 0x003e5769, 0x0040596c, 0x003f586d, 0x00405c74, 0x004f758c, 0x0080b0bd, 0x00b0cbcc, 0x00c2cccc, 0x00c9ccca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00c9cccc, 0x00c4cccc, 0x00bccccc, 0x00a0bec6, 0x00668a9c, 0x002b4858, 0x00142330, 0x000e1620, 0x000a131c, 0x000a141e, 0x00101c25, 0x00112027, 0x00122229, 0x0013242c, 0x0013242d, 0x00142730, 0x00192e37, 0x00243a44, 0x002a414d, 0x002c4754, 0x002d4957, 0x002f4958, 0x00304959, 0x00304a59, 0x00304c59, 0x00304c59, 0x00304c59, 0x00304c59, 0x00304c59, 0x002f4b59, 0x002f4a58, 0x00304857, 0x002f4654, 0x0029404e, 0x00223845, 0x001e333e, 0x001a2e39, 0x00182c37, 0x00182c36, 0x00182c36, 0x00182c36, 0x00192c38, 0x00192c38, 0x00192c38, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182b34, 0x00182b34, 0x00172a34, 0x00172934, 0x00152834, 0x00152836, 0x00152836, 0x00152836, 0x00152836, 0x00162937, 0x00162a38, 0x00172c39, 0x00172c39, 0x00172c3a, 0x00182c3a, 0x000e1e28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012242c, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4347, 0x001c484c, 0x001d4d50, 0x00205356, 0x0023636c, 0x0030a4cb, 0x002a88a0, 0x00256264, 0x00266467, 0x00276568, 0x00276669, 0x0028676a, 0x0028676a, 0x0028686a, 0x00276769, 0x00276669, 0x00276668, 0x00276568, 0x00266568, 0x00266568, 0x00266568, 0x00276568, 0x00276568, 0x00276568, 0x00266568, 0x00266568, 0x00266568, 0x00266568, 0x00276568, 0x00276466, 0x00266466, 0x00256364, 0x00256163, 0x00246062, 0x00245e60, 0x00256c79, 0x002ea3c9, 0x00288cab, 0x00205254, 0x001d4d50, 0x001c484c, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00142e34, 0x00132c32, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00162633, 0x00162633, 0x00162633, 0x00152633, 0x00152632, 0x00152632, 0x00162531, 0x00162531, 0x00152432, 0x00142330, 0x0012212e, 0x00111f2a, 0x00101e2a, 0x00101f2a, 0x000f1f29, 0x00101f2a, 0x0013202c, 0x0014202c, 0x0014202c, 0x0014212b, 0x0014212b, 0x0014202a, 0x0013202a, 0x0013202a, 0x00121f29, 0x00121f29, 0x00111f29, 0x00111f29, 0x0013202a, 0x0013202a, 0x0013202a, 0x0013202c, 0x0013202c, 0x0014212c, 0x0014212c, 0x00162430, 0x00182430, 0x00182430, 0x00182530, 0x00172730, 0x00172830, 0x00172830, 0x00172832, 0x00182934, 0x00182934, 0x00182934, 0x00182934, 0x00172833, 0x00162833, 0x00162732, 0x0014222d, 0x00101b24, 0x000c141c, 0x00090e18, 0x00090d16, 0x000c121a, 0x00111c27, 0x001e303e, 0x003e5e70, 0x0080a9b5, 0x00adcacc, 0x00bfcccc, 0x00cacbcc, 0x00cccbcc, 0x00cccbcc, 0x00cccbca, 0x00cbcccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00c5cccc, 0x00bbcbcc, 0x0091aeb7, 0x004b6c7c, 0x002b4a5e, 0x00334e60, 0x00365060, 0x00324957, 0x00304553, 0x002b404d, 0x002b3f4c, 0x00283b49, 0x00273a48, 0x002c3f4b, 0x002a3d48, 0x00283a46, 0x00273844, 0x00283945, 0x00243641, 0x00243440, 0x0024313d, 0x0024303c, 0x00202c37, 0x0018222b, 0x00182027, 0x00172026, 0x001c2329, 0x001a2028, 0x00192027, 0x001d242b, 0x001c232a, 0x00192027, 0x00182026, 0x001c242a, 0x001f282e, 0x00222b32, 0x00242d35, 0x0027313a, 0x002c3740, 0x002f3841, 0x00313944, 0x00323944, 0x00333944, 0x00343a45, 0x00343a45, 0x00333944, 0x00333945, 0x00343c48, 0x00343e49, 0x0036404b, 0x0038434d, 0x003c4551, 0x0036424e, 0x0034404c, 0x00384250, 0x0039414f, 0x0038404c, 0x00383e4a, 0x00363c48, 0x00373d4a, 0x003c4350, 0x00424857, 0x00424858, 0x00404857, 0x00404958, 0x00404857, 0x003f4554, 0x003e4453, 0x00434858, 0x00464c5b, 0x00454b5a, 0x00454b5a, 0x00454b59, 0x00444958, 0x00434957, 0x00444a58, 0x00444a58, 0x00444958, 0x00404554, 0x003d4251, 0x003d4151, 0x003d4151, 0x003c4050, 0x003a404d, 0x003a404d, 0x0039404d, 0x00383f4d, 0x00383f4d, 0x00383f4c, 0x00363e4b, 0x0037404c, 0x0039424f, 0x003c4453, 0x003a4554, 0x00384453, 0x00343e4e, 0x00333b49, 0x00303845, 0x002c3440, 0x002c343f, 0x002c343e, 0x002c343f, 0x002d3540, 0x002d3540, 0x002d3540, 0x002c343e, 0x002a323b, 0x0028303a, 0x00262f38, 0x00242d36, 0x00202931, 0x00202832, 0x001f262f, 0x001f262e, 0x00181f27, 0x00151c24, 0x00161c24, 0x00171e25, 0x00182028, 0x00182128, 0x001b232b, 0x001d2630, 0x00202833, 0x00202b35, 0x00222e38, 0x0026313c, 0x0027323e, 0x00273440, 0x00283742, 0x0024333e, 0x0022313c, 0x00243440, 0x002c3c48, 0x00293a47, 0x00283b47, 0x002a3d4a, 0x002a3c4d, 0x002b3d4f, 0x00314758, 0x00354c5d, 0x00354f5e, 0x00385061, 0x00385162, 0x003d5668, 0x003d5568, 0x003c566b, 0x00405c74, 0x004d7088, 0x0074a3b2, 0x00a8c8cb, 0x00bdcccc, 0x00c6cccc, 0x00cbcccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00c9cccc, 0x00c3cccc, 0x00b7cbcc, 0x008fb1bc, 0x004c6d7e, 0x001e3040, 0x00101925, 0x000a131c, 0x0009111b, 0x000e1822, 0x00101d25, 0x00122029, 0x0013232c, 0x0013242c, 0x0014242f, 0x00152833, 0x001e323e, 0x00273d4a, 0x002b4453, 0x002c4857, 0x002f4958, 0x00304958, 0x00304958, 0x00304a58, 0x002f4a58, 0x00304b58, 0x00304b58, 0x002f4b57, 0x002f4956, 0x002f4855, 0x002e4654, 0x002c4250, 0x00263b48, 0x00203441, 0x001c2f3c, 0x001a2c38, 0x00182a35, 0x00182a34, 0x00182b35, 0x00182b35, 0x00182c37, 0x00182c38, 0x00182c38, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182b35, 0x00182b34, 0x00172a34, 0x00172934, 0x00152834, 0x00152834, 0x00152834, 0x00152834, 0x00152835, 0x00162935, 0x00162b38, 0x00172b39, 0x00172c39, 0x00182c3a, 0x00182d3b, 0x000e1e28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153439, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001d4b4e, 0x001f5053, 0x00205558, 0x0024646e, 0x0031a4ca, 0x002c88a1, 0x00266467, 0x00276668, 0x0028686a, 0x0028686b, 0x0028696c, 0x0028696c, 0x0028696c, 0x0028686b, 0x0028686b, 0x0028686a, 0x00286769, 0x00286769, 0x00276668, 0x00276668, 0x00266568, 0x00266568, 0x00266568, 0x00266568, 0x00266568, 0x00266467, 0x00266467, 0x00276467, 0x00276466, 0x00256364, 0x00256264, 0x00246062, 0x00245f61, 0x00245d60, 0x002a8ca8, 0x002da3c9, 0x00246d80, 0x001e5053, 0x001d4b4e, 0x001c474b, 0x001a4245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0013282e, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00172633, 0x00172633, 0x00172633, 0x00162632, 0x00152631, 0x00152631, 0x00162531, 0x00162530, 0x00152431, 0x00142330, 0x0013222f, 0x0012212c, 0x0011202c, 0x0012202b, 0x0012202a, 0x0013202a, 0x0014212b, 0x0014212c, 0x0014212b, 0x0014212b, 0x0014212b, 0x0013202a, 0x0013202a, 0x0013202a, 0x0014202a, 0x0014202a, 0x0013202a, 0x0013202a, 0x0013202a, 0x0013202a, 0x0013202a, 0x0013202c, 0x0013202c, 0x0013202c, 0x0014202c, 0x0014222d, 0x0016242f, 0x00172430, 0x00162430, 0x00162630, 0x00162731, 0x00162831, 0x00172833, 0x00172833, 0x00182934, 0x00182a34, 0x00172934, 0x00162833, 0x00162731, 0x0015242e, 0x00121e27, 0x000c151c, 0x00080e15, 0x00070c13, 0x00080f16, 0x000d151f, 0x00152532, 0x002c4658, 0x00648c9d, 0x00a0c3c7, 0x00bccccc, 0x00c7cccc, 0x00cbcbcc, 0x00cccbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00c9cccc, 0x00c1cccc, 0x00aec4c9, 0x006d8c9c, 0x002f4d5f, 0x00274153, 0x00344b5c, 0x00354d5c, 0x00304856, 0x002f4655, 0x002d4452, 0x002b414e, 0x00283c4a, 0x00273a48, 0x002f404c, 0x002a3b47, 0x00283945, 0x00263844, 0x00263742, 0x0024343e, 0x0024333d, 0x0023303a, 0x00222e38, 0x001f2832, 0x00182029, 0x00182128, 0x00182128, 0x001a2128, 0x00171d24, 0x00171d24, 0x001b2228, 0x001b2228, 0x00192026, 0x00182025, 0x001a2127, 0x001c242a, 0x001f262d, 0x00262d36, 0x0029333c, 0x002c363f, 0x002f3941, 0x00313a44, 0x00343c47, 0x00353d49, 0x00363e4a, 0x00363e4a, 0x00343c48, 0x00343c48, 0x0037404c, 0x0037424e, 0x00394450, 0x003c4652, 0x003d4754, 0x0036414f, 0x00384451, 0x003c4754, 0x003c4654, 0x003b4453, 0x003a4350, 0x0038424f, 0x003c4453, 0x00404857, 0x00414a58, 0x00404a58, 0x00404a58, 0x003e4856, 0x003e4856, 0x00404857, 0x00404858, 0x00404a59, 0x00414c5b, 0x00404b5a, 0x00404858, 0x00404858, 0x003f4856, 0x003e4855, 0x003e4856, 0x00424c5a, 0x00464f5f, 0x00444c5c, 0x00424859, 0x00414858, 0x00404858, 0x003f4958, 0x003e4957, 0x003e4856, 0x003c4654, 0x003b4351, 0x003b4250, 0x003b4351, 0x003b4452, 0x003b4452, 0x003b4452, 0x003a4452, 0x003a4554, 0x003a4554, 0x0036414f, 0x00343d4c, 0x00323b49, 0x00303846, 0x002e3642, 0x002d3540, 0x002d3540, 0x002e3641, 0x002e3641, 0x002e3642, 0x002d3440, 0x002b313c, 0x0029303a, 0x00242d34, 0x00242d34, 0x00242c34, 0x00242c34, 0x00212933, 0x001d252f, 0x001a222c, 0x00171e28, 0x00181f28, 0x00182028, 0x00182128, 0x00192229, 0x001c252c, 0x001c2630, 0x00202933, 0x00212c36, 0x00202c35, 0x0024303a, 0x0026323d, 0x0026323e, 0x00273540, 0x0023343e, 0x0023343f, 0x00243441, 0x00273845, 0x00263846, 0x00263a48, 0x002b404d, 0x002a3f4f, 0x00283c4c, 0x00304554, 0x00354c5c, 0x0038505e, 0x00364d5c, 0x0038515e, 0x003c5662, 0x00395461, 0x003c5768, 0x00435d72, 0x004a6981, 0x005e8a9e, 0x0093bcc4, 0x00b4cccc, 0x00c3cccc, 0x00c9cccc, 0x00cbccca, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00cbccca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00c8cccc, 0x00c0cccc, 0x00acc7ca, 0x00799ca9, 0x00344e5e, 0x00142230, 0x000c141f, 0x00081019, 0x000c161f, 0x00101c24, 0x00122028, 0x0013232c, 0x0013242d, 0x0014242f, 0x00132530, 0x00182c38, 0x00203644, 0x0029404f, 0x002d4654, 0x002f4856, 0x00314958, 0x00304958, 0x002e4957, 0x002d4957, 0x002e4a58, 0x002e4a58, 0x002e4a56, 0x002d4854, 0x002d4753, 0x002c4450, 0x00283e4a, 0x00203642, 0x001c303c, 0x00192c38, 0x00182a34, 0x00172934, 0x00172934, 0x00172a35, 0x00182a34, 0x00182b35, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c37, 0x00182c38, 0x00182c38, 0x00182c38, 0x00182c38, 0x00182b37, 0x00182a36, 0x00172936, 0x00152a34, 0x00152a34, 0x00152a34, 0x00152a34, 0x00152a35, 0x00172a38, 0x00182a38, 0x00182a38, 0x00182b39, 0x00182c39, 0x000e1e28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00122c32, 0x00143036, 0x0015363b, 0x00183c40, 0x001a4245, 0x001c474b, 0x001d4d50, 0x001f5254, 0x0021585a, 0x00256770, 0x0032a5ca, 0x002c8aa2, 0x00286769, 0x0028686b, 0x00286a6c, 0x00296c6e, 0x002a6c6e, 0x002a6c6e, 0x00296c6e, 0x00296b6d, 0x00286a6c, 0x00286a6c, 0x0028696c, 0x0028686b, 0x0028686a, 0x00286769, 0x00286769, 0x00286668, 0x00276668, 0x00266568, 0x00266568, 0x00266467, 0x00266467, 0x00276466, 0x00256364, 0x00256264, 0x00256163, 0x00245f61, 0x00245d60, 0x00277485, 0x002ea1c8, 0x002a8faf, 0x00205459, 0x001d4d50, 0x001c4a4d, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00152431, 0x00152431, 0x00152431, 0x00152430, 0x00142530, 0x00142430, 0x00142530, 0x00162530, 0x00162531, 0x00142431, 0x00142430, 0x0014232e, 0x0013222d, 0x0014212c, 0x0014212b, 0x0014212b, 0x0014222c, 0x0014222c, 0x0014212b, 0x0014212b, 0x0014212b, 0x0013202a, 0x00122029, 0x00121f29, 0x00131f29, 0x00131f29, 0x00111f28, 0x00111f28, 0x00111f29, 0x00111f29, 0x00111f29, 0x00111f2b, 0x00111f2b, 0x00121f2b, 0x00121f2b, 0x0013202c, 0x0014222e, 0x0016242f, 0x00162430, 0x00162530, 0x00162631, 0x00162732, 0x00162833, 0x00172833, 0x00182833, 0x00182934, 0x00172833, 0x00172732, 0x0014242e, 0x00121e26, 0x000e181f, 0x00081016, 0x00060b11, 0x00060c13, 0x00091018, 0x00101b25, 0x001c303e, 0x00446779, 0x0086b0bc, 0x00b1cbcc, 0x00c2cccc, 0x00cacccc, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00cccbcb, 0x00cccbcb, 0x00cbccca, 0x00c8cccc, 0x00b8cacb, 0x008fabb5, 0x00486776, 0x00213a4c, 0x00283d4d, 0x00314655, 0x00324857, 0x002e4755, 0x002e4655, 0x002f4755, 0x002d4451, 0x00293c4b, 0x00283b48, 0x002f404c, 0x00293a46, 0x00283944, 0x00263844, 0x00243541, 0x0024343e, 0x0024333c, 0x00212e38, 0x00202b34, 0x001a242d, 0x00161e27, 0x00172027, 0x00182027, 0x00161f24, 0x00141b21, 0x00151c22, 0x00181e24, 0x001a2127, 0x001a2127, 0x001a2126, 0x001a2125, 0x001d2428, 0x001f252c, 0x00262d36, 0x002b343c, 0x002d3840, 0x00303943, 0x00323c48, 0x00353f4c, 0x0036404c, 0x0037404c, 0x0037404d, 0x0038414d, 0x0038414e, 0x00394350, 0x00394450, 0x003b4652, 0x003d4854, 0x003c4753, 0x00384350, 0x00394553, 0x003d4856, 0x003d4856, 0x003d4856, 0x003b4654, 0x003b4654, 0x003d4856, 0x003e4957, 0x003f4957, 0x003e4856, 0x003b4654, 0x0035404e, 0x00374250, 0x00394352, 0x003b4656, 0x003c4756, 0x003c4857, 0x00344050, 0x00333c4c, 0x00343e4e, 0x0034404d, 0x0035414d, 0x0034404c, 0x00384451, 0x00404a5a, 0x00414b5b, 0x003f4858, 0x003d4757, 0x003e4858, 0x003c4958, 0x003c4a57, 0x003d4a57, 0x003e4a58, 0x003d4855, 0x003d4654, 0x003d4654, 0x003d4755, 0x003c4654, 0x003a4451, 0x00384250, 0x00394452, 0x00394453, 0x00384250, 0x0037404e, 0x00343e4c, 0x00343c49, 0x00333b48, 0x00303844, 0x00303843, 0x002f3742, 0x002f3742, 0x002f3742, 0x002d3540, 0x002b313c, 0x0029303b, 0x00232c34, 0x00232b32, 0x00262e35, 0x00262e36, 0x00242c34, 0x001f2730, 0x00202831, 0x0019202a, 0x00182029, 0x001a212a, 0x00182129, 0x00182128, 0x001c242c, 0x001e2830, 0x001f2831, 0x00212d36, 0x00243039, 0x0025313c, 0x0025303c, 0x0024303c, 0x0024333e, 0x0023333e, 0x00263843, 0x00293a48, 0x00283948, 0x00283b49, 0x00293e4c, 0x002c414e, 0x002c4150, 0x00293e4e, 0x002e4453, 0x00324a58, 0x00354b5b, 0x00334958, 0x00354d5b, 0x0037505e, 0x00385262, 0x003f586a, 0x00445e72, 0x00456279, 0x004c7288, 0x0078a4b3, 0x00a9c9cb, 0x00becccc, 0x00c8cccc, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00cbccca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cacccb, 0x00c4cccc, 0x00b9cccc, 0x009abbc3, 0x00547483, 0x001c303f, 0x000e1823, 0x00081018, 0x00081018, 0x000d1a21, 0x00112028, 0x0013222c, 0x0013242d, 0x0013242e, 0x00122430, 0x00132632, 0x00182c39, 0x00203544, 0x00273d4c, 0x002d4453, 0x00304756, 0x00304856, 0x002c4855, 0x002c4855, 0x002c4856, 0x002c4856, 0x002d4854, 0x002c4652, 0x0029424c, 0x00253c47, 0x00203540, 0x001c303b, 0x00182b38, 0x00172935, 0x00172934, 0x00172934, 0x00172934, 0x00172934, 0x00172934, 0x00182a34, 0x00182b34, 0x00182b34, 0x00182c36, 0x00182c36, 0x00182c37, 0x00182c38, 0x00182c38, 0x00182c38, 0x00182c38, 0x00182b37, 0x00182a37, 0x00182a36, 0x00162a34, 0x00152a33, 0x00152a34, 0x00152a34, 0x00152a34, 0x00172a37, 0x00182a38, 0x00182a38, 0x00182a39, 0x00182a39, 0x000e1e28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0016363b, 0x00183c40, 0x001a4245, 0x001c484c, 0x001e4f51, 0x00205457, 0x0023595c, 0x00256870, 0x0032a5ca, 0x002c8ba2, 0x0028686b, 0x00296b6d, 0x00296c6f, 0x002a6e70, 0x002a6e70, 0x002a6e70, 0x002a6e70, 0x002a6d6f, 0x00296c6f, 0x00296c6e, 0x00296b6d, 0x00286a6c, 0x0028696c, 0x0028686b, 0x0028686a, 0x00286769, 0x00286668, 0x00266568, 0x00266568, 0x00266467, 0x00266466, 0x00256364, 0x00256264, 0x00256163, 0x00245f61, 0x00245e60, 0x00256f7d, 0x002d9cc1, 0x002c9cc0, 0x0022636f, 0x001f5053, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183d41, 0x00183a3e, 0x00153439, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0014222e, 0x0014222e, 0x0014222e, 0x0014222e, 0x0013242e, 0x0013242e, 0x00142430, 0x00162530, 0x00172632, 0x00172633, 0x00172632, 0x00162530, 0x0014242f, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014212b, 0x0013202a, 0x0013202a, 0x00132029, 0x00121e28, 0x00121e28, 0x00111d27, 0x00121e28, 0x00111e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e2a, 0x00111f2a, 0x00111f2b, 0x00121f2b, 0x0014212c, 0x0015232e, 0x0015232f, 0x00162430, 0x00162530, 0x00172631, 0x00162632, 0x00152732, 0x00152731, 0x00152731, 0x00152731, 0x0014242f, 0x00121f28, 0x000f1820, 0x00091017, 0x00060b10, 0x0004090e, 0x00060c14, 0x000b141c, 0x0015222c, 0x002c4455, 0x00668e9f, 0x00a4c4ca, 0x00bccccc, 0x00c8cccc, 0x00cccccc, 0x00cccbcc, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00cccbcc, 0x00cccbcb, 0x00cbcccb, 0x00c4cccc, 0x00a8c0c5, 0x00648491, 0x002c4858, 0x001c3040, 0x00283b48, 0x002a3d4c, 0x002b404f, 0x002c4452, 0x00304855, 0x00334b58, 0x00304754, 0x002c404d, 0x00293d4a, 0x002c3f4b, 0x00283a46, 0x00283b47, 0x00293c48, 0x00263844, 0x00253440, 0x0024333d, 0x0023303a, 0x00202c35, 0x0019242c, 0x00161e25, 0x00171e25, 0x00161e25, 0x00171e24, 0x00141c21, 0x00161d23, 0x00161c22, 0x00181f25, 0x001b2228, 0x001c2428, 0x001d2428, 0x001f252b, 0x0020282e, 0x00262c35, 0x002b343c, 0x002f3841, 0x00303a44, 0x00343d49, 0x00353f4b, 0x0037404d, 0x0038414e, 0x0039434f, 0x003b4451, 0x003c4552, 0x003c4552, 0x003b4552, 0x003c4854, 0x003e4854, 0x003c4653, 0x00384350, 0x00384452, 0x003c4855, 0x003d4856, 0x003d4856, 0x003c4855, 0x003a4754, 0x00394654, 0x00394452, 0x003c4554, 0x00394450, 0x00303c48, 0x002c3844, 0x002e3a47, 0x002c3745, 0x00343f4e, 0x0034404f, 0x00333e4d, 0x00303b4b, 0x002c3746, 0x002e3848, 0x002d3846, 0x002b3743, 0x00283440, 0x002c3844, 0x00313c4a, 0x00384451, 0x0037414f, 0x00353f4d, 0x00374151, 0x00354453, 0x00384754, 0x003a4a56, 0x003c4a57, 0x003d4a58, 0x003f4957, 0x003e4856, 0x003f4856, 0x003c4654, 0x00394351, 0x0038414f, 0x0038414f, 0x0037424f, 0x0037424f, 0x0037414f, 0x0037404e, 0x0036404c, 0x00363e4b, 0x00343d49, 0x00343c47, 0x00323a45, 0x00303843, 0x00303844, 0x002d3440, 0x002b313c, 0x002c323d, 0x00252e36, 0x00232c33, 0x00252d34, 0x00272f38, 0x00242c35, 0x00232b34, 0x00222a34, 0x001e252f, 0x001c232c, 0x001b222c, 0x00192229, 0x00192229, 0x001a232b, 0x001e2831, 0x00232c37, 0x0025303b, 0x0026333e, 0x0027333d, 0x00232f3b, 0x00212d39, 0x0021303b, 0x0024333e, 0x00283844, 0x002c3c49, 0x00293c49, 0x00283c4b, 0x002c414f, 0x002f4451, 0x002e4353, 0x002d4352, 0x002f4554, 0x00304857, 0x00314859, 0x00324859, 0x00324a59, 0x00344c5a, 0x00374f5f, 0x003f5768, 0x00445b6e, 0x00425d70, 0x003f6074, 0x00568090, 0x0094bcc3, 0x00b9cccc, 0x00c5cccc, 0x00cbcccb, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00cbccca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cacccb, 0x00c7cccc, 0x00c0cccc, 0x00afc8cb, 0x007898a6, 0x002b4454, 0x00101e29, 0x000b121a, 0x00060c14, 0x000a141c, 0x00101d25, 0x0013212b, 0x0013232c, 0x0012232d, 0x0012242e, 0x0012242f, 0x00132531, 0x00172936, 0x001c303c, 0x00263947, 0x002d404e, 0x002d4250, 0x002c4450, 0x002c4450, 0x002c4450, 0x002a4450, 0x0029424e, 0x00263e49, 0x00213843, 0x001d323d, 0x00192c38, 0x00172a36, 0x00172833, 0x00162833, 0x00172833, 0x00172833, 0x00172834, 0x00182934, 0x00182934, 0x00182a34, 0x00182a34, 0x00182b34, 0x00192c34, 0x00192c34, 0x00182c35, 0x00182c37, 0x00182c37, 0x00182c37, 0x00182c37, 0x00182c37, 0x00182b36, 0x00182b36, 0x00172c35, 0x00172c34, 0x00162b34, 0x00162b34, 0x00162b35, 0x00172a36, 0x00172938, 0x00172938, 0x00172938, 0x00172938, 0x000e1d28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0016363b, 0x00183d41, 0x001a4347, 0x001d4a4d, 0x001e5053, 0x00205558, 0x00245c5e, 0x00266972, 0x0033a6cb, 0x002d8ca3, 0x00296b6d, 0x002a6d6f, 0x002b6f70, 0x002b7071, 0x002b7072, 0x002b7072, 0x002c7072, 0x002c7071, 0x002b6f70, 0x00296d6f, 0x00296c6f, 0x002a6c6e, 0x00296a6c, 0x0028696c, 0x0028686b, 0x0028686a, 0x00276668, 0x00266568, 0x00266467, 0x00266466, 0x00256364, 0x00266264, 0x00246062, 0x00245f61, 0x00246064, 0x00287a90, 0x002d9ec3, 0x002d9ec4, 0x00246e80, 0x001f5154, 0x001d4d50, 0x001c484c, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0012242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0014222d, 0x0014222d, 0x0014222d, 0x0014222d, 0x0013232e, 0x0013232e, 0x0014242f, 0x00162530, 0x00172631, 0x00182733, 0x00182733, 0x00172632, 0x00152430, 0x0014232c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014212b, 0x0013202a, 0x0013202a, 0x00121e28, 0x00121e28, 0x00111d27, 0x00111d27, 0x00111e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e2a, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x0012202c, 0x0013202c, 0x0014212d, 0x0014232e, 0x00142430, 0x00142430, 0x00142430, 0x00142430, 0x0013242e, 0x0013232d, 0x0013202b, 0x000f1a22, 0x000b1118, 0x00080c10, 0x0006090e, 0x0004090d, 0x00080e15, 0x000d171f, 0x001b2a34, 0x00436374, 0x0088b0bc, 0x00b4cbcc, 0x00c3cccc, 0x00cbccca, 0x00cccbcb, 0x00cccbcc, 0x00cccacc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00cccbcc, 0x00cccbcb, 0x00c8cccc, 0x00bcc9cb, 0x0088a4ae, 0x00415e6e, 0x00203848, 0x001b2d3a, 0x00293a47, 0x00243544, 0x00243846, 0x0028404c, 0x002f4754, 0x00364f5c, 0x00344a57, 0x00304452, 0x00293e4c, 0x00293c49, 0x00273946, 0x00283b47, 0x002c3f4b, 0x00283845, 0x00253440, 0x0024343f, 0x0025313c, 0x00202c36, 0x0019242d, 0x00171f28, 0x00171e27, 0x00141d26, 0x00182028, 0x00151c23, 0x00151c22, 0x00161c22, 0x00181f24, 0x001c2328, 0x001f252c, 0x0022282e, 0x0022282f, 0x0020282e, 0x00232a33, 0x0029323b, 0x00303942, 0x00303944, 0x00323c48, 0x0036404c, 0x0038414e, 0x003a4450, 0x003b4450, 0x003c4653, 0x003d4754, 0x003c4653, 0x003c4653, 0x003c4854, 0x003d4854, 0x003c4552, 0x00384450, 0x00374250, 0x00394553, 0x003c4855, 0x003c4855, 0x003c4855, 0x003c4855, 0x00394553, 0x0035404e, 0x00353f4d, 0x00323c48, 0x0028343e, 0x00242f39, 0x00293540, 0x0024303c, 0x00283441, 0x002c3846, 0x002e3948, 0x00323e4c, 0x00303948, 0x002e3846, 0x002c3743, 0x00293440, 0x0027313d, 0x002a3440, 0x002a3440, 0x00293541, 0x002b3541, 0x002c3644, 0x00303c4b, 0x00334150, 0x00364554, 0x00394956, 0x003b4c58, 0x003e4c5a, 0x00404b58, 0x003d4957, 0x003f4857, 0x003c4655, 0x003b4453, 0x0038414f, 0x0036404c, 0x0036414e, 0x0036424e, 0x0036424e, 0x0037424e, 0x0038414e, 0x0037404d, 0x0038404c, 0x00353d4a, 0x00343c47, 0x00343c48, 0x00323a44, 0x002c343f, 0x002a303c, 0x00252c36, 0x00202830, 0x001e272e, 0x001f282f, 0x00222a33, 0x00242c35, 0x0028313a, 0x00262e37, 0x00202830, 0x001d242c, 0x001b222b, 0x0019222a, 0x001a232a, 0x001a232c, 0x001b2530, 0x00242e39, 0x0028333d, 0x00283641, 0x0025333e, 0x0025303c, 0x00222e39, 0x0022303c, 0x0024343f, 0x00273843, 0x002a3b48, 0x00283a48, 0x00273a48, 0x002c404e, 0x00324754, 0x00324756, 0x00314655, 0x00304655, 0x00304857, 0x00314859, 0x0033495a, 0x00334959, 0x00324a58, 0x00364d5d, 0x003d5465, 0x0043596a, 0x0042596b, 0x003b5468, 0x003b5e70, 0x00739eab, 0x00acc8ca, 0x00c0cccc, 0x00cacccb, 0x00cccbca, 0x00cbccc9, 0x00cbccc9, 0x00cbccca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00c8cccc, 0x00c4cccc, 0x00b9cccc, 0x0093b3bc, 0x00426070, 0x00142533, 0x000d151e, 0x00070c13, 0x00050c14, 0x000c171f, 0x00111f28, 0x0013222a, 0x0013232c, 0x0013242c, 0x0012242e, 0x0014242f, 0x00142430, 0x00142530, 0x00172834, 0x001c2d3a, 0x00203440, 0x00243944, 0x00253b47, 0x00243a45, 0x00233844, 0x00203541, 0x001c313c, 0x00182c38, 0x00172a36, 0x00152734, 0x00142532, 0x00162530, 0x00162630, 0x00162832, 0x00172833, 0x00172833, 0x00182934, 0x00182934, 0x00182a34, 0x00192a34, 0x00192a34, 0x001a2c34, 0x001a2c34, 0x00192c34, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182d36, 0x00182d35, 0x00172c34, 0x00162b34, 0x00162b35, 0x00162936, 0x00172937, 0x00172937, 0x00172937, 0x00172937, 0x000e1d28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00142e34, 0x00143338, 0x0017383c, 0x00183f43, 0x001b4448, 0x001d4b4e, 0x00205154, 0x0021585a, 0x00245c5f, 0x00276a73, 0x0034a6cb, 0x002f90a8, 0x002b757d, 0x002c777e, 0x002c7880, 0x002d7a81, 0x002d7a81, 0x002d7a81, 0x002d7a81, 0x002c7980, 0x002c7880, 0x002c787f, 0x002b777e, 0x002b757d, 0x002a747c, 0x002a747b, 0x0029727a, 0x00287179, 0x00287078, 0x00286f77, 0x00276d76, 0x00276d76, 0x00276c75, 0x00266b74, 0x0027717f, 0x00298299, 0x002c97b8, 0x002ea3ca, 0x002c9bbf, 0x00246d7e, 0x00205254, 0x001d4d50, 0x001c4a4d, 0x001c4649, 0x001a4245, 0x00183d41, 0x0017383c, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0014212c, 0x0014212c, 0x0014212c, 0x0012212d, 0x0013222e, 0x0013222e, 0x00142430, 0x00162531, 0x00172633, 0x00172634, 0x00172633, 0x00172633, 0x00142431, 0x0014222e, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014212b, 0x0013202a, 0x00122029, 0x00111e28, 0x00111e28, 0x00101d27, 0x00101d27, 0x00101e28, 0x00101d27, 0x00101d28, 0x00101e28, 0x00101e29, 0x00101e2a, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x0011202c, 0x0011202c, 0x0012212d, 0x0012222e, 0x0012232d, 0x0012232d, 0x0012222c, 0x0013202a, 0x00101b24, 0x000c131c, 0x00080c10, 0x0006090c, 0x0005090b, 0x00070a0e, 0x000b1017, 0x00101b23, 0x0021343f, 0x00587c8c, 0x009dc2c7, 0x00bccccc, 0x00c8cccc, 0x00cccbca, 0x00cccbcb, 0x00cccbcc, 0x00cccacc, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccca, 0x00c9cccb, 0x00c0cbcc, 0x00a1b9c0, 0x005f7c8a, 0x002d4757, 0x001c303f, 0x00192b36, 0x00293945, 0x00223340, 0x00203241, 0x00243847, 0x002c4452, 0x0038515f, 0x00354c5c, 0x00314657, 0x002c3f4f, 0x00283848, 0x00253744, 0x00263844, 0x0030424f, 0x00273844, 0x0022323d, 0x0024323d, 0x00242f39, 0x001e2833, 0x0018222c, 0x00182028, 0x001a212a, 0x0019212a, 0x001c242c, 0x00151c23, 0x00141b21, 0x00171e24, 0x00181f24, 0x001c232b, 0x00242a32, 0x00252c35, 0x00242b34, 0x00202830, 0x00202730, 0x00212a33, 0x002b343d, 0x002c3540, 0x00303a47, 0x0037404c, 0x0038424f, 0x00394450, 0x003b4450, 0x003c4653, 0x003d4754, 0x003c4652, 0x003c4551, 0x003c4652, 0x003c4551, 0x003b4552, 0x003a4452, 0x00374250, 0x00384451, 0x003b4654, 0x003b4553, 0x003b4553, 0x003a4451, 0x0038424f, 0x00343d49, 0x00333c47, 0x002f3843, 0x0028323c, 0x0028313b, 0x0028323c, 0x00202b34, 0x00202b35, 0x002b3540, 0x0028333d, 0x002a3640, 0x0027313d, 0x0028323e, 0x002b3440, 0x0028303c, 0x00263039, 0x002c343e, 0x002c353f, 0x00242d38, 0x0026303c, 0x002b3442, 0x002c3644, 0x002e3b49, 0x0033404e, 0x00374552, 0x003b4a57, 0x003e4c59, 0x003e4a58, 0x003d4957, 0x003e4856, 0x003c4855, 0x003c4654, 0x003a4350, 0x0037404d, 0x0037404d, 0x0037414e, 0x0037424e, 0x0038424e, 0x0037404d, 0x0037404d, 0x0038404d, 0x00373f4b, 0x00343c48, 0x00353d48, 0x002f3742, 0x0029303c, 0x00282e39, 0x00232a34, 0x001f272f, 0x001c242b, 0x001c252c, 0x001d252d, 0x001f2730, 0x00262e37, 0x00283038, 0x00232b34, 0x001e242e, 0x001a202a, 0x00182029, 0x001a222b, 0x001d252f, 0x001e2833, 0x00242e38, 0x0027323c, 0x00283540, 0x0026333e, 0x00283440, 0x0024303c, 0x0024343f, 0x00283844, 0x00283844, 0x00273845, 0x00283a48, 0x00283b49, 0x002e4150, 0x00364a58, 0x00344958, 0x00324857, 0x00304655, 0x00304756, 0x00344a5a, 0x00374c5c, 0x00364c5c, 0x00374b5b, 0x00384c5c, 0x003e5464, 0x00435868, 0x00405465, 0x00354b5b, 0x002e4a5b, 0x004e7886, 0x0092b8bf, 0x00b8cccc, 0x00c7cccc, 0x00cccbcb, 0x00ccccca, 0x00cbccc9, 0x00cbccca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00c7cccc, 0x00bfcccc, 0x00a4c2c7, 0x005c7f8d, 0x001c3040, 0x00101925, 0x000a1018, 0x00040b11, 0x00060f16, 0x000c1820, 0x00122028, 0x0014222c, 0x0013232d, 0x0012232e, 0x0012232e, 0x0013232e, 0x0013222e, 0x0013222f, 0x00142330, 0x00142430, 0x00132632, 0x00142733, 0x00142834, 0x00142834, 0x00132632, 0x00122531, 0x00122531, 0x00132431, 0x00142430, 0x00142430, 0x00152530, 0x00152531, 0x00152832, 0x00162833, 0x00172833, 0x00182934, 0x00182934, 0x00182a35, 0x00192a36, 0x00192a36, 0x00192b35, 0x00192b35, 0x00182b35, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c37, 0x00182c38, 0x00192d38, 0x00182c38, 0x00172c37, 0x00162b37, 0x00162936, 0x00172937, 0x00172937, 0x00172937, 0x00162936, 0x000d1d28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0013242c, 0x00112a30, 0x00142e34, 0x00143338, 0x0016383c, 0x00183f43, 0x001b4649, 0x001d4c50, 0x001f5254, 0x0022585b, 0x00245d60, 0x00276970, 0x0032a1c4, 0x0034a7cb, 0x0036a8ca, 0x0037a8ca, 0x0037a9ca, 0x0037a9ca, 0x0037a9ca, 0x0037a9ca, 0x0037a9ca, 0x0037a9ca, 0x0037a9ca, 0x0037a8ca, 0x0036a8ca, 0x0036a8ca, 0x0034a7ca, 0x0034a6ca, 0x0034a6ca, 0x0033a6ca, 0x0033a5ca, 0x0032a5ca, 0x0031a4ca, 0x0031a4ca, 0x0030a4ca, 0x0030a4ca, 0x0030a4cb, 0x0030a4cc, 0x002ea0c7, 0x00298aa8, 0x0022606c, 0x001f5154, 0x001e4f51, 0x001d4b4e, 0x001c4649, 0x001a4347, 0x00183f43, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011222d, 0x0011232d, 0x0011232d, 0x0013242f, 0x00152631, 0x00172733, 0x00162633, 0x00152532, 0x00152532, 0x00162532, 0x0014232e, 0x0013222d, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013212b, 0x0012212b, 0x0012202a, 0x00111f28, 0x00101e28, 0x00101e28, 0x00101d27, 0x00101e28, 0x00101d27, 0x000f1c26, 0x000f1c26, 0x00101d28, 0x00101d28, 0x00101e28, 0x00111f29, 0x00111f29, 0x00111f29, 0x00111f29, 0x00111f2a, 0x00111f2b, 0x00111f2b, 0x0010202b, 0x0011202c, 0x0012202c, 0x0013212c, 0x00122029, 0x00101b24, 0x000c141e, 0x00080d15, 0x0005080c, 0x00040809, 0x0005080a, 0x00080b0f, 0x000c1219, 0x00121d25, 0x00253b47, 0x00678e9d, 0x00a4c7ca, 0x00c0cccc, 0x00cacccc, 0x00cbcccb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccca, 0x00c5cccc, 0x00acc4c7, 0x0070919c, 0x003c5868, 0x00243948, 0x001a2c37, 0x001a2934, 0x00293845, 0x00243341, 0x00202f3e, 0x001f303f, 0x002b404f, 0x00395261, 0x00385060, 0x00304757, 0x002c4050, 0x00243746, 0x00213441, 0x00263844, 0x00324350, 0x00253542, 0x0021303c, 0x0022303c, 0x001f2b35, 0x001a2630, 0x0016212a, 0x00172029, 0x001c232c, 0x001d242c, 0x001d242b, 0x00151c21, 0x00131a20, 0x00182026, 0x00171f25, 0x001c242c, 0x00242d36, 0x00263038, 0x00242d37, 0x00202831, 0x001f2831, 0x001d2630, 0x00242c36, 0x002a313c, 0x00303743, 0x00353c48, 0x00383f4b, 0x0038404c, 0x003a424e, 0x003c4451, 0x003c4451, 0x003a444f, 0x0039434d, 0x0038424d, 0x0039424e, 0x003b4450, 0x003a4451, 0x0037424f, 0x0037414f, 0x00374250, 0x00384250, 0x0038414e, 0x0036404b, 0x00343e48, 0x00313c46, 0x00303a45, 0x002d3740, 0x0028323a, 0x00253038, 0x00253038, 0x001c262d, 0x001c242d, 0x0028303a, 0x00242d36, 0x00253038, 0x00242e38, 0x00232e38, 0x00242e38, 0x00202831, 0x001e252d, 0x0020272f, 0x00232b34, 0x00202832, 0x00242c36, 0x002a323e, 0x0028303d, 0x002d3744, 0x00323d4a, 0x0036414e, 0x003c4653, 0x003d4855, 0x003c4855, 0x003c4856, 0x003c4856, 0x003d4856, 0x003d4755, 0x003c4654, 0x00394450, 0x0038424f, 0x0036414c, 0x0037424c, 0x0037424c, 0x0036404a, 0x0036404b, 0x0038404c, 0x00373f4a, 0x00343c47, 0x00313944, 0x002d3540, 0x0029313c, 0x00272f3a, 0x00242c37, 0x00202830, 0x001c242b, 0x001d262d, 0x001e242c, 0x001e242c, 0x00212830, 0x00222930, 0x0020262e, 0x001c222c, 0x001a202a, 0x00192029, 0x0019222b, 0x001d262f, 0x00202b34, 0x0025303a, 0x0025313c, 0x0024303c, 0x00222e3a, 0x00242f3c, 0x001f2c39, 0x00243440, 0x002b3c48, 0x00273844, 0x00263844, 0x00283b48, 0x002a3d4b, 0x002e4351, 0x00364c5b, 0x00344a5b, 0x00314858, 0x002d4453, 0x002c4453, 0x00324958, 0x00384e5d, 0x00394e5c, 0x00394c5b, 0x00384c5a, 0x003d5160, 0x00425766, 0x003c505f, 0x00304452, 0x0029404f, 0x00345563, 0x0068909b, 0x00a7c4c7, 0x00c0cccc, 0x00c8cccc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00c9cccc, 0x00c2cccc, 0x00adc8ca, 0x007496a4, 0x00253c4c, 0x00111c28, 0x000c1019, 0x00070c11, 0x0004090f, 0x00071118, 0x00101c24, 0x0014202b, 0x0014212c, 0x0012212d, 0x0012222e, 0x0011232c, 0x0011232c, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011222e, 0x0011222e, 0x0011222e, 0x0011222f, 0x0011222f, 0x0011242e, 0x0011242e, 0x0011242e, 0x0012242e, 0x0013242f, 0x00142532, 0x00142633, 0x00142733, 0x00142833, 0x00152834, 0x00172834, 0x00172834, 0x00182935, 0x00192a35, 0x00192b36, 0x00182b37, 0x00182a36, 0x00182a36, 0x00182a36, 0x00182a36, 0x00182a36, 0x00182a37, 0x00182a37, 0x00182a37, 0x00182c38, 0x00192c39, 0x001a2d3a, 0x001a2d39, 0x00182c39, 0x00172c38, 0x00162935, 0x00152834, 0x00152834, 0x00152834, 0x00142834, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0011242c, 0x00112a30, 0x00142e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001b4649, 0x001d4c50, 0x00205356, 0x0022585b, 0x00245e60, 0x00266466, 0x002b7d8c, 0x003092ac, 0x003194ad, 0x003295ad, 0x003396ae, 0x003497ae, 0x003497ae, 0x003497ae, 0x003497ae, 0x003497ae, 0x003396ae, 0x003296ad, 0x003195ad, 0x003194ac, 0x003093ac, 0x003092ac, 0x003091ac, 0x002f90ab, 0x002e90ab, 0x002d8faa, 0x002d8faa, 0x002c8da9, 0x002c8ca9, 0x002b8ca8, 0x002a89a5, 0x00287e96, 0x00236570, 0x00205458, 0x001f5154, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183c40, 0x0016383c, 0x00153439, 0x00142e34, 0x00132c32, 0x0010282e, 0x0012242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011222d, 0x0011232d, 0x0012242e, 0x00152631, 0x00172833, 0x00172834, 0x00152633, 0x00142532, 0x00142432, 0x00152432, 0x0014232f, 0x0013222d, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0012212b, 0x0012212b, 0x0012202a, 0x00111f29, 0x00101e28, 0x00101e28, 0x00101d27, 0x00101d27, 0x00101d27, 0x000f1c26, 0x000f1c26, 0x00101d28, 0x00101d28, 0x00101e28, 0x00111f29, 0x00111f29, 0x00111f29, 0x00111f29, 0x00111f2a, 0x00111f2b, 0x00111f2b, 0x0010202b, 0x0010202b, 0x0012202b, 0x00121f28, 0x00101a23, 0x000c141c, 0x000a0e16, 0x0006080f, 0x00050709, 0x00050808, 0x0006080a, 0x00080c10, 0x000c141b, 0x0013202a, 0x002c4551, 0x00749faa, 0x00accacb, 0x00c4cccc, 0x00cacccb, 0x00cacccb, 0x00cbcccb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccc, 0x00cacccc, 0x00bccacc, 0x008cacb5, 0x00486c7a, 0x002c4454, 0x001f303d, 0x00182630, 0x0018242f, 0x00263440, 0x00243440, 0x001e2d3b, 0x001b2c39, 0x00283c4b, 0x0038505f, 0x00395261, 0x00304858, 0x002f4453, 0x00253747, 0x00203240, 0x00273844, 0x002f3e4b, 0x00243441, 0x0022303c, 0x00202e38, 0x001c2832, 0x0018242e, 0x0015202a, 0x0019242c, 0x001d252e, 0x001e262d, 0x001a2028, 0x00131a20, 0x00131a20, 0x00182127, 0x00192228, 0x001e272e, 0x00263039, 0x00263039, 0x00263038, 0x00202a33, 0x00222b34, 0x00202831, 0x00222b34, 0x00283039, 0x002d333e, 0x002f3540, 0x002e3641, 0x00303844, 0x00353d48, 0x0038404c, 0x0038404c, 0x0037404a, 0x00363e48, 0x00343c48, 0x00353d49, 0x0038404d, 0x0038414e, 0x0037404d, 0x0037404d, 0x0038414f, 0x0037404d, 0x0036404b, 0x00333c48, 0x00313b45, 0x00303944, 0x002f3842, 0x002c343d, 0x00283038, 0x00202830, 0x00242c34, 0x001c252c, 0x00192028, 0x00242c33, 0x00222a32, 0x001f272f, 0x00202831, 0x00212932, 0x00202830, 0x001b212a, 0x00181e26, 0x00181e26, 0x001c232b, 0x001f262f, 0x00202831, 0x00242b36, 0x00232b37, 0x002d3743, 0x00333c48, 0x00343d49, 0x0038424e, 0x003c4451, 0x003c4653, 0x003c4754, 0x003c4754, 0x003c4855, 0x003d4755, 0x003c4654, 0x003c4552, 0x003b4451, 0x0038434d, 0x0038434d, 0x0038414c, 0x0036404b, 0x0036404a, 0x0036404b, 0x00353e48, 0x00333c47, 0x002f3842, 0x002c343e, 0x002a323c, 0x0028303b, 0x00242d37, 0x00232b33, 0x001e272e, 0x00212930, 0x00212830, 0x0020262e, 0x0020272f, 0x001f252d, 0x001b212a, 0x001a202a, 0x00192029, 0x00192029, 0x0018212a, 0x001d262f, 0x001f2933, 0x00222d38, 0x0025313c, 0x00212d39, 0x001c2834, 0x001d2835, 0x001c2a37, 0x00223340, 0x00283946, 0x00253744, 0x00263844, 0x00283b47, 0x002b3e4b, 0x002c4250, 0x00344c5b, 0x00384f60, 0x0033495a, 0x002c4352, 0x002a4050, 0x00304655, 0x00394e5d, 0x003b4d5c, 0x00374857, 0x00354755, 0x003c4f5d, 0x00405462, 0x00384b58, 0x002a3c49, 0x00263b48, 0x00294450, 0x00446876, 0x0087acb6, 0x00b4cacc, 0x00c2cccc, 0x00cacccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccc, 0x00c5cccc, 0x00b4cbcc, 0x0087a7b2, 0x00314b5b, 0x00101e2b, 0x000c121a, 0x00080c11, 0x0004080d, 0x00040b11, 0x000b141d, 0x00141e28, 0x0015202b, 0x0013212c, 0x0012212c, 0x0011232c, 0x0011232c, 0x0011232c, 0x0011232d, 0x0011222d, 0x0012212e, 0x0012212e, 0x0012212e, 0x0012212e, 0x0012222e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0012242e, 0x0013242f, 0x00132532, 0x00142733, 0x00142733, 0x00142733, 0x00142834, 0x00162834, 0x00172834, 0x00182934, 0x00192a35, 0x001a2b36, 0x00182b37, 0x00172935, 0x00172935, 0x00172935, 0x00172935, 0x00162935, 0x00172a36, 0x00182a37, 0x00182b38, 0x00182c38, 0x00192c39, 0x001a2d3b, 0x001a2d3b, 0x00192c3b, 0x00182c39, 0x00172935, 0x00152834, 0x00152834, 0x00152834, 0x00142834, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x00183a3e, 0x00194044, 0x001c4649, 0x001e4d50, 0x00205356, 0x0022595c, 0x00245f61, 0x00266466, 0x0029727b, 0x002c7d8b, 0x002d808c, 0x002e828e, 0x00308490, 0x00308490, 0x00308490, 0x00308490, 0x002e797e, 0x002d7577, 0x002c7476, 0x002c7475, 0x002c7274, 0x002b7071, 0x002a6e70, 0x00296c6f, 0x00286a6c, 0x0028686b, 0x00276668, 0x00266466, 0x00256264, 0x00245f61, 0x00245d60, 0x00235a5c, 0x0022585b, 0x00205558, 0x00205356, 0x001f5053, 0x001d4d50, 0x001c4a4d, 0x001b4649, 0x001a4347, 0x00194044, 0x00183d41, 0x0017383c, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011222d, 0x0011232d, 0x0013242f, 0x00152731, 0x00182834, 0x00182834, 0x00172834, 0x00152633, 0x00152432, 0x00142431, 0x0013222f, 0x0013222f, 0x0013222d, 0x0013222d, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0014212b, 0x0012202a, 0x00101e28, 0x00101e28, 0x00101d27, 0x00101d27, 0x00101d27, 0x000f1c26, 0x00101d27, 0x00101d28, 0x00101e29, 0x00111e29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f2a, 0x00131f2a, 0x00111f2b, 0x00111f2b, 0x00111e27, 0x00101b22, 0x000c141c, 0x00080f14, 0x00080910, 0x0005070c, 0x00040708, 0x00050708, 0x0006080a, 0x000a0c10, 0x000e141c, 0x0014242f, 0x0034525f, 0x0082adb7, 0x00b1cccc, 0x00c5cccc, 0x00cacccb, 0x00cacccb, 0x00cbcccb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccc, 0x00c6cccc, 0x00a8bec4, 0x00648794, 0x00335262, 0x00243947, 0x001a2834, 0x00111d26, 0x00121d28, 0x001e2c37, 0x0023323e, 0x001d2c39, 0x00182835, 0x00263947, 0x00364f5c, 0x00385160, 0x00324a59, 0x00314656, 0x00293c4b, 0x00223441, 0x00243441, 0x00263542, 0x00263542, 0x0024333f, 0x00212e39, 0x001c2a34, 0x00192630, 0x0017232c, 0x001b252e, 0x001f2830, 0x001c232a, 0x00151c24, 0x00111820, 0x00131a20, 0x00182026, 0x001a232a, 0x001e262d, 0x00273138, 0x00283239, 0x00263038, 0x00232d35, 0x00262f38, 0x00252d36, 0x00242d36, 0x00262d37, 0x00282e38, 0x00282f38, 0x00272f38, 0x0028303a, 0x002d353f, 0x00303843, 0x00303842, 0x00303841, 0x00303841, 0x00323842, 0x00333944, 0x00343c48, 0x00343e49, 0x00343d48, 0x00333d49, 0x00333d4a, 0x00333c48, 0x00333c48, 0x00303944, 0x00303944, 0x002f3842, 0x0029303b, 0x00282e38, 0x00252c34, 0x001b2128, 0x001f252d, 0x001e242c, 0x00171d25, 0x001c232a, 0x001d242c, 0x001c222a, 0x001d232c, 0x001f252f, 0x00192029, 0x00181e26, 0x0012161e, 0x00181d24, 0x001e242c, 0x001d242c, 0x00202730, 0x00222933, 0x00242c37, 0x002a333d, 0x002f3843, 0x00303843, 0x00333c47, 0x00363e4b, 0x0038404d, 0x00394350, 0x003b4450, 0x003b4451, 0x003b4453, 0x003b4452, 0x003a4451, 0x00394450, 0x0038424d, 0x0038424c, 0x0037414c, 0x0036404b, 0x00353f49, 0x00343e48, 0x00323c47, 0x00303a45, 0x002d3641, 0x002b333d, 0x002b333d, 0x0027303a, 0x00242c36, 0x00222a32, 0x00222a32, 0x00242c34, 0x00242c34, 0x00242b33, 0x00222931, 0x001d252c, 0x001c232b, 0x001b222b, 0x001c222c, 0x00182029, 0x0018202a, 0x00202832, 0x001c2630, 0x001c2831, 0x00222e38, 0x00232f3a, 0x001b2733, 0x00192532, 0x001e2c39, 0x00243441, 0x00243542, 0x00243642, 0x00283946, 0x00283c48, 0x00293e4a, 0x00283f4c, 0x00344b5a, 0x00385060, 0x00344b5c, 0x002f4554, 0x002a404f, 0x002c4352, 0x00364c5b, 0x00364958, 0x00314351, 0x00324352, 0x003c4e5c, 0x00405260, 0x00344654, 0x00263744, 0x00243744, 0x00243b48, 0x002c4a5a, 0x005f8392, 0x009ebfc5, 0x00bacccc, 0x00c8cccc, 0x00cccccc, 0x00cccbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccc, 0x00c7cccc, 0x00bacccc, 0x0095b4bc, 0x003f5968, 0x00142431, 0x000e151d, 0x00080d12, 0x0003080c, 0x0002080e, 0x00070e15, 0x000f1820, 0x00151f29, 0x0014222c, 0x0013222c, 0x0012222c, 0x0012222c, 0x0012222c, 0x0012222d, 0x0012222d, 0x0012212c, 0x0011202c, 0x0012212c, 0x0012212d, 0x0012222d, 0x0011242e, 0x0012242e, 0x0013242f, 0x00142430, 0x00142430, 0x00122633, 0x00132733, 0x00132733, 0x00132733, 0x00142834, 0x00152834, 0x00152834, 0x00182935, 0x00182b36, 0x00182b37, 0x00182a37, 0x00172935, 0x00172935, 0x00162834, 0x00142834, 0x00142834, 0x00162935, 0x00182b37, 0x00182c38, 0x00192c38, 0x001a2d39, 0x001a2d3a, 0x001a2d39, 0x00192c3a, 0x00182c39, 0x00172935, 0x00152834, 0x00152834, 0x00152834, 0x00142834, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x00183a3e, 0x001a4044, 0x001c4649, 0x001d4d50, 0x00205356, 0x0022595c, 0x00245f61, 0x00286c74, 0x00319ebe, 0x0034a7ca, 0x0035a8ca, 0x0036a8ca, 0x0037a9ca, 0x0038a9ca, 0x0038aaca, 0x0038aaca, 0x003498b0, 0x002e7779, 0x002d7576, 0x002c7475, 0x002c7274, 0x002b7072, 0x002a6e70, 0x00296c6f, 0x00286a6c, 0x0028686a, 0x00266568, 0x00266364, 0x00246062, 0x00245d60, 0x00235a5c, 0x0021585a, 0x00205558, 0x00205254, 0x001e5053, 0x001d4d50, 0x001c4a4d, 0x001c4649, 0x001a4347, 0x00194044, 0x00183d41, 0x0017383c, 0x00153439, 0x00143036, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011232d, 0x0012242e, 0x0013242f, 0x00152631, 0x00172833, 0x00182834, 0x00182935, 0x00172834, 0x00152532, 0x00142330, 0x0013222f, 0x0013222f, 0x0013222d, 0x0013222d, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0014212b, 0x0013202a, 0x00101e28, 0x00101e28, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101e29, 0x00111f2b, 0x00121f2a, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00111f2b, 0x00111f2a, 0x00101c24, 0x000c151c, 0x00091016, 0x00050a10, 0x0004060c, 0x0004060b, 0x00040608, 0x00050708, 0x0007080b, 0x000c0e12, 0x0010161e, 0x00152632, 0x0040606f, 0x0090b8c0, 0x00b5cccc, 0x00c6cccc, 0x00cacccb, 0x00cacccb, 0x00cbcccb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cacbcb, 0x00b5c8ca, 0x0084a0ae, 0x00446374, 0x002a4253, 0x0020303d, 0x0015212c, 0x000d1720, 0x00101924, 0x001b2833, 0x00202f3b, 0x001c2b37, 0x0013222f, 0x00213340, 0x00354c59, 0x00374f5d, 0x00324a58, 0x00304755, 0x002c404c, 0x00243743, 0x0020323f, 0x0022323f, 0x00263542, 0x00283643, 0x0023303b, 0x001e2c35, 0x001a2831, 0x0016232c, 0x001c2730, 0x001f2831, 0x00182028, 0x00131c23, 0x00131c23, 0x00151d24, 0x00182027, 0x001b232a, 0x001c252c, 0x00263037, 0x00283238, 0x00253036, 0x00253037, 0x00273039, 0x00283039, 0x00272e37, 0x00252c35, 0x00242a34, 0x00242a32, 0x00222a31, 0x00202830, 0x00232b32, 0x00272d37, 0x00262c36, 0x00252c34, 0x00282e36, 0x002c333c, 0x002e343f, 0x00303742, 0x00303843, 0x00303843, 0x00303843, 0x00303844, 0x00303843, 0x00303741, 0x002d343f, 0x002d343f, 0x002b313c, 0x00262a33, 0x0023282f, 0x0020242c, 0x00181c24, 0x00181c24, 0x001c2028, 0x00131820, 0x00141920, 0x00181d25, 0x00191d26, 0x00191c26, 0x001c2029, 0x00171b24, 0x00161922, 0x000d1018, 0x00171c22, 0x001c2228, 0x00181f25, 0x001f262d, 0x00242c34, 0x00283039, 0x002b343c, 0x002c343e, 0x002c343e, 0x002d3540, 0x00333945, 0x00363e4a, 0x0036404c, 0x0038414d, 0x0039424e, 0x0039434f, 0x00384250, 0x0038414f, 0x0036404c, 0x00343d49, 0x00323c46, 0x00313c46, 0x00313c46, 0x00303b45, 0x00303a45, 0x002f3944, 0x002c3741, 0x0029333d, 0x0029313c, 0x002a323d, 0x0028313c, 0x00252d38, 0x00232b33, 0x00232c33, 0x00242c34, 0x00242c34, 0x00242c34, 0x00202a30, 0x001b242c, 0x001c242c, 0x001c242e, 0x001c242e, 0x0018202a, 0x00161e27, 0x001e2730, 0x0019242c, 0x0018242c, 0x00202c35, 0x00232f38, 0x001c2834, 0x001a2633, 0x00222f3c, 0x00243442, 0x00223440, 0x00243441, 0x002a3c48, 0x002b3e4a, 0x002b3f4c, 0x0029404d, 0x00324958, 0x00344b5c, 0x00334859, 0x00304655, 0x002d4151, 0x002e4252, 0x00334656, 0x00324352, 0x00303f4d, 0x00334252, 0x003b4c5b, 0x003c4f5c, 0x002f404d, 0x00223140, 0x00243340, 0x00213340, 0x00203848, 0x003a596b, 0x00799ead, 0x00a9c8cb, 0x00bfcccc, 0x00c8cccc, 0x00cbcccc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00c7cccc, 0x00bccccc, 0x00a0bdc3, 0x004d6978, 0x00152632, 0x000e171d, 0x00080d13, 0x0004080c, 0x0001070c, 0x0004080e, 0x00090e17, 0x00111822, 0x0014202b, 0x0014222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222d, 0x0012212c, 0x0011202c, 0x0011202c, 0x0012212c, 0x0013222d, 0x0013222d, 0x0012242e, 0x0013242e, 0x00142430, 0x00152631, 0x00152631, 0x00122733, 0x00122733, 0x00122733, 0x00122733, 0x00132733, 0x00142834, 0x00142934, 0x00172a36, 0x00182b37, 0x00182c38, 0x00182a37, 0x00172935, 0x00162834, 0x00142834, 0x00142733, 0x00142834, 0x00162835, 0x00182b37, 0x00182c38, 0x00192c38, 0x00192c38, 0x001a2d39, 0x001a2d39, 0x00192c3a, 0x00182c39, 0x00172935, 0x00152834, 0x00152834, 0x00152834, 0x00152834, 0x000d1d28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0011242c, 0x00122a30, 0x00142e34, 0x00153439, 0x00183a3e, 0x001a4044, 0x001c4649, 0x001d4d50, 0x00205356, 0x0022595c, 0x00245e60, 0x002c869d, 0x0034a7cb, 0x002f8ca2, 0x002d8290, 0x002f8492, 0x00308593, 0x00308694, 0x00308794, 0x00359bb4, 0x0038aac9, 0x0030828c, 0x002d7577, 0x002c7476, 0x002c7374, 0x002c7173, 0x002b6f70, 0x00296c6f, 0x00286a6c, 0x0028686a, 0x00266467, 0x00256264, 0x00245f61, 0x00245c5e, 0x0022585b, 0x00205558, 0x00205254, 0x001e4f51, 0x001d4c50, 0x001c484c, 0x001b4649, 0x001a4347, 0x00183f43, 0x00183c40, 0x0017383c, 0x00153439, 0x00143036, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x00102229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0013212c, 0x0013212c, 0x0013212c, 0x0013232d, 0x0014242f, 0x00142430, 0x00152731, 0x00172833, 0x00182834, 0x00182935, 0x00172834, 0x00152532, 0x00142330, 0x0013222f, 0x0013222f, 0x0013222e, 0x0014232e, 0x0014232e, 0x0013222d, 0x0013222d, 0x0013232c, 0x0013232c, 0x0014222c, 0x0014212b, 0x00101e28, 0x00101e28, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101e29, 0x00111f2b, 0x00121f2b, 0x00131f2a, 0x00131f2a, 0x00131f2a, 0x00131f2a, 0x00121e29, 0x00111e29, 0x00111e29, 0x00111e29, 0x00101c27, 0x000d1720, 0x00081017, 0x00070c11, 0x0004070c, 0x0004050c, 0x0003050b, 0x00040609, 0x00040609, 0x0007080b, 0x000c0e13, 0x00101820, 0x00182b36, 0x004c6d7c, 0x009bc0c5, 0x00bbcccc, 0x00c8cccc, 0x00cacccb, 0x00cacccb, 0x00cbcccb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccc, 0x00cacccc, 0x00c8cbcc, 0x009cb7bd, 0x005c7b8a, 0x00354d5f, 0x00273948, 0x001c2833, 0x00101b24, 0x000c141c, 0x00101923, 0x001c2833, 0x00202e39, 0x001c2934, 0x0012202c, 0x0020303c, 0x00344855, 0x00364c5b, 0x00324957, 0x002d4450, 0x002b404d, 0x00263946, 0x0022323e, 0x0022303d, 0x0024333f, 0x00273440, 0x0024313c, 0x00202d37, 0x00182630, 0x0015232c, 0x001c2830, 0x001c2830, 0x00172028, 0x00141c24, 0x00161e25, 0x00172027, 0x00192128, 0x001c242b, 0x001e272e, 0x00252f36, 0x00283239, 0x00242f35, 0x00253037, 0x00272f38, 0x00262c36, 0x00252c35, 0x00252c35, 0x00232832, 0x0020252d, 0x001f252c, 0x001f252d, 0x0020272f, 0x00232932, 0x00212831, 0x0020262f, 0x00212830, 0x00252c34, 0x00292f38, 0x002b303a, 0x002b313b, 0x002c343d, 0x002f353f, 0x002d343e, 0x002c333c, 0x002c303a, 0x002a2f38, 0x002a2f38, 0x00252b33, 0x0020242b, 0x001d2027, 0x001a1d24, 0x0015181f, 0x00101219, 0x00161921, 0x000d1018, 0x000e1119, 0x00141720, 0x00181a23, 0x00151820, 0x0014171f, 0x0012141c, 0x0010141b, 0x000c0f16, 0x0014181f, 0x00161c21, 0x00191f24, 0x001d242b, 0x00242b32, 0x00293039, 0x002a323c, 0x002b333c, 0x002c323c, 0x002b323c, 0x002e3440, 0x00323944, 0x00343c48, 0x00363e48, 0x00363f49, 0x00363d48, 0x00363d49, 0x00343c48, 0x00313945, 0x00303842, 0x002e3641, 0x002d3640, 0x002d3640, 0x002d3640, 0x002e3741, 0x002d3741, 0x002c3741, 0x0029333c, 0x002c343e, 0x002d3640, 0x002a323d, 0x0028303b, 0x00273038, 0x00242d35, 0x00212931, 0x00202830, 0x00212931, 0x00202830, 0x001d262e, 0x001c242d, 0x001c242c, 0x001d252f, 0x001a222c, 0x00171f28, 0x001b242c, 0x0019242c, 0x001c262f, 0x00202c34, 0x00202c36, 0x001d2934, 0x001b2634, 0x00202e3c, 0x00243340, 0x00233440, 0x00243541, 0x002a3c48, 0x002c404d, 0x002d424e, 0x002b4250, 0x00304655, 0x00304857, 0x00304656, 0x002f4453, 0x002d4250, 0x00304251, 0x00324453, 0x0030404f, 0x00303d4c, 0x00344453, 0x003b4c5b, 0x00364856, 0x00253644, 0x001f2e3c, 0x0022303d, 0x001f2d39, 0x001c2f3e, 0x002c4456, 0x00547588, 0x008cb1be, 0x00b3cacc, 0x00c4cccc, 0x00cacccc, 0x00cbcccc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcc, 0x00c8cccc, 0x00c0cccc, 0x00a9c4c8, 0x005c7888, 0x00182b37, 0x000e171f, 0x00090e14, 0x0005090e, 0x0002050b, 0x0003040b, 0x0005080f, 0x000c1018, 0x00111a23, 0x0015202a, 0x0014212c, 0x0013222c, 0x0013222c, 0x0013222d, 0x0013222d, 0x0012212c, 0x0012212c, 0x0012212c, 0x0013222d, 0x0013222d, 0x0013242e, 0x0014242f, 0x00142530, 0x00152631, 0x00152631, 0x00132733, 0x00132733, 0x00132733, 0x00122733, 0x00142733, 0x00142834, 0x00142934, 0x00162a35, 0x00182a37, 0x00182b37, 0x00182a37, 0x00172935, 0x00162834, 0x00142834, 0x00142733, 0x00142834, 0x00162835, 0x00182a37, 0x00182c38, 0x00182c38, 0x00192c38, 0x001a2d39, 0x001a2d39, 0x00192d3a, 0x00182c39, 0x00182a37, 0x00152834, 0x00152834, 0x00152834, 0x00152834, 0x000d1d28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0011242c, 0x00122a30, 0x00132e34, 0x00163439, 0x00183a3e, 0x001a4044, 0x001c4649, 0x001d4d50, 0x00205356, 0x0022585b, 0x00245e60, 0x002c89a1, 0x0034a6cb, 0x002c808e, 0x002b6f70, 0x002c7274, 0x002c7476, 0x002d7577, 0x002d7678, 0x003494aa, 0x0038aaca, 0x00308490, 0x002d7678, 0x002d7678, 0x002d7679, 0x002c7274, 0x002c7071, 0x002a6d6f, 0x00286a6c, 0x0028686a, 0x00266467, 0x00256163, 0x00245e60, 0x00235a5c, 0x0021585a, 0x00205356, 0x001f5053, 0x001d4c50, 0x001c484c, 0x001b4448, 0x001a4347, 0x00183f43, 0x00183c40, 0x0017383c, 0x00153439, 0x00143036, 0x00142e34, 0x00112a30, 0x0010282e, 0x0012242c, 0x00102229, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0012212c, 0x0012212c, 0x0013222d, 0x00142230, 0x00152331, 0x00162433, 0x00182634, 0x00182836, 0x00192836, 0x00192835, 0x00182834, 0x00152432, 0x00142330, 0x0013222d, 0x0012212c, 0x0013232c, 0x0014242c, 0x0014242d, 0x0014232e, 0x0014232e, 0x0014242d, 0x0014242c, 0x0014232c, 0x0014212b, 0x00111f29, 0x00111f29, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00131f29, 0x00131f29, 0x00131f2a, 0x00131f2b, 0x00131f2b, 0x00131f2b, 0x00131f2b, 0x00101e2a, 0x000f1e28, 0x000f1e28, 0x000f1c27, 0x000c1722, 0x000a111a, 0x00070c10, 0x0005080c, 0x0004050a, 0x0003040a, 0x00030509, 0x00030609, 0x00040609, 0x0006080c, 0x000b1014, 0x00121a23, 0x001b2f3a, 0x00527583, 0x00a2c3c7, 0x00bfcccc, 0x00cacccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00cccccc, 0x00c9cccc, 0x00c4cccc, 0x00b3c3c8, 0x00708f9c, 0x003e5c6c, 0x002c4252, 0x00223240, 0x0018212d, 0x000d141f, 0x000b101a, 0x00141b25, 0x001d2732, 0x00202c37, 0x001b2833, 0x0013202c, 0x001d2d38, 0x00304351, 0x00334858, 0x00304756, 0x002c424f, 0x002b3e4c, 0x00283845, 0x0024333f, 0x0022303c, 0x0022313c, 0x0023313c, 0x00202e38, 0x00223039, 0x0018242e, 0x0017232c, 0x001c2833, 0x001a2530, 0x0017212b, 0x00151e27, 0x00172028, 0x00182029, 0x0019222b, 0x001c242d, 0x00202831, 0x00253038, 0x0027333c, 0x00232f37, 0x00242f37, 0x00252f38, 0x00232b34, 0x00232b34, 0x00232a33, 0x0020272e, 0x001d242c, 0x001c242c, 0x001e272e, 0x00212930, 0x00212830, 0x00212830, 0x0020262e, 0x0020262e, 0x00212830, 0x00242a33, 0x00282c35, 0x002a2e38, 0x002c313a, 0x002d323b, 0x002c3139, 0x002c3038, 0x002a2f37, 0x00272c34, 0x00262b33, 0x0023282f, 0x001e2129, 0x001a1d24, 0x0016191f, 0x00111419, 0x000b0e14, 0x000f1218, 0x00080c11, 0x00090c11, 0x000f1217, 0x0014171c, 0x0013161c, 0x00101318, 0x00101317, 0x000c1014, 0x000b0d12, 0x00101217, 0x000e1418, 0x00131a1d, 0x00172024, 0x001c252b, 0x00232a33, 0x00252a34, 0x00282d37, 0x00282c36, 0x00282d36, 0x002c313a, 0x00303740, 0x00323a44, 0x00343c46, 0x00353c46, 0x00343a44, 0x00323844, 0x00303741, 0x002e343f, 0x002c323c, 0x002a303b, 0x002b313c, 0x0029313b, 0x0029313c, 0x002b333e, 0x002c3640, 0x002c3741, 0x002a343f, 0x002c3541, 0x002c3643, 0x0028303d, 0x0028303c, 0x0029333d, 0x00262f39, 0x00222a34, 0x00202831, 0x00202831, 0x00202833, 0x00212934, 0x001e2731, 0x0018222c, 0x001c2630, 0x001a242f, 0x0018222c, 0x001a242f, 0x001c2530, 0x001e2833, 0x001d2b34, 0x001d2b33, 0x001e2b33, 0x001c2832, 0x001d2c37, 0x0020303c, 0x00263842, 0x00263944, 0x00283b46, 0x002c404d, 0x002d4350, 0x002d4450, 0x002d4451, 0x00304653, 0x00304654, 0x00304452, 0x00304350, 0x00324350, 0x00344351, 0x0030404c, 0x00303f4c, 0x00364654, 0x003a4b58, 0x0031424f, 0x0020303c, 0x001f2e3a, 0x0022303b, 0x001e2934, 0x00182734, 0x00243747, 0x00395669, 0x00638799, 0x0095b9c3, 0x00b4cbcc, 0x00c1cccc, 0x00c9cccc, 0x00cbcccb, 0x00cbccc9, 0x00cbccc9, 0x00cbcbca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcc, 0x00c9cccc, 0x00c3cccc, 0x00b1c8cb, 0x006e8a9c, 0x001c3140, 0x000d1923, 0x000a0f15, 0x0006090e, 0x0003040b, 0x00020308, 0x00030408, 0x0005090d, 0x000b1116, 0x00111b24, 0x0014202c, 0x0014222d, 0x0013222d, 0x0012242e, 0x0012242e, 0x0011232d, 0x0011232d, 0x0013232f, 0x00142330, 0x00142330, 0x00142431, 0x00142532, 0x00152633, 0x00152633, 0x00152633, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142733, 0x00142834, 0x00142934, 0x00152a36, 0x00162a36, 0x00182a37, 0x00172935, 0x00142834, 0x00142733, 0x00142834, 0x00142834, 0x00152834, 0x00182a36, 0x00182b37, 0x00182c38, 0x00182d39, 0x001a2f3a, 0x00192e3a, 0x00182d3b, 0x00182c3a, 0x00192b38, 0x00182936, 0x00172834, 0x00172834, 0x00162834, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0011242c, 0x00122a30, 0x00132e34, 0x00163439, 0x00183a3e, 0x001a4044, 0x001c4649, 0x001d4c50, 0x00205356, 0x0022585b, 0x00245d60, 0x002c88a0, 0x0034a6cb, 0x002c808e, 0x002a6e70, 0x002c7173, 0x002c7475, 0x002d7576, 0x002d7678, 0x003494aa, 0x0038aaca, 0x00308490, 0x002d7678, 0x00318b9b, 0x0036a2c0, 0x003398b1, 0x002f8596, 0x002b7276, 0x00286a6c, 0x0028686a, 0x00266467, 0x00256163, 0x00245d60, 0x0022595c, 0x00205558, 0x00205254, 0x001d4d50, 0x001c4a4d, 0x001c4649, 0x001a4347, 0x00183f43, 0x00183c40, 0x0017383c, 0x00143439, 0x00143036, 0x00142e34, 0x00112a30, 0x00112a30, 0x0012242c, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0012212c, 0x0013222d, 0x0013222d, 0x00132230, 0x00142330, 0x00162433, 0x00182635, 0x00182836, 0x00192835, 0x00192835, 0x00182834, 0x00152432, 0x00142330, 0x0012212d, 0x0012212c, 0x0013232c, 0x0014242c, 0x0014242d, 0x0014232e, 0x0014232e, 0x0014242d, 0x0014242c, 0x0014232c, 0x0014212b, 0x00122029, 0x00111f29, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00131f29, 0x00131f29, 0x00131f2a, 0x00131f2b, 0x00131f2b, 0x00131f2a, 0x00121e2a, 0x00101f29, 0x000e1e27, 0x000d1c25, 0x000c1822, 0x000a131d, 0x00080c14, 0x0005080c, 0x0005050a, 0x00040408, 0x00030308, 0x00030408, 0x00030609, 0x00030609, 0x00050a0d, 0x000b1117, 0x00141d26, 0x001d323d, 0x005b808c, 0x00a9c7c9, 0x00c2cccc, 0x00cbcccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccccc, 0x00cbcccc, 0x00c7cccc, 0x00b9c9cb, 0x008fa8b5, 0x004e6c7d, 0x00334c5e, 0x00283c4a, 0x001e2c38, 0x00131c27, 0x000a101a, 0x000a0f18, 0x00151c26, 0x001d2830, 0x001e2a34, 0x001c2831, 0x0017242e, 0x00182834, 0x00283b49, 0x00324856, 0x00334858, 0x00304655, 0x002d404e, 0x00263544, 0x00243441, 0x0022323d, 0x0022313c, 0x00202e39, 0x001f2c38, 0x00202d38, 0x0018242e, 0x0018242d, 0x001f2b35, 0x001b2530, 0x0018222c, 0x0017202a, 0x00172029, 0x00182029, 0x001a222b, 0x001c242d, 0x00202831, 0x00242f37, 0x00253139, 0x00212d35, 0x00232e36, 0x00242c35, 0x00212933, 0x00202830, 0x001d262d, 0x001c242b, 0x001c242c, 0x001d262d, 0x0020282f, 0x00202830, 0x001f272f, 0x001f252e, 0x0020262e, 0x0020272e, 0x0020262f, 0x00222730, 0x00242a32, 0x00282c34, 0x00292e36, 0x002a2f37, 0x00282d35, 0x00282d35, 0x00252a32, 0x0022272e, 0x0020242b, 0x001d2228, 0x001a1c24, 0x0016181f, 0x00101418, 0x000c1014, 0x00080c10, 0x000c1014, 0x00090c11, 0x00080b0e, 0x00090c10, 0x000d1015, 0x00111419, 0x000d1014, 0x000e1114, 0x00080b0f, 0x00080a0f, 0x00090c10, 0x00080d10, 0x000e1416, 0x0011191c, 0x00141c20, 0x001a212a, 0x001e232c, 0x00252a34, 0x00232831, 0x0022272f, 0x00282c35, 0x002c313b, 0x002c333c, 0x002e343e, 0x002f353f, 0x002d343d, 0x002c323c, 0x00293038, 0x00282e36, 0x00272d35, 0x00272d35, 0x00272d37, 0x00242c35, 0x00242d36, 0x00273038, 0x002c343f, 0x002c3641, 0x002a3540, 0x002a3440, 0x002a3440, 0x0028323f, 0x0028323e, 0x002d3742, 0x0028313c, 0x00242c36, 0x00232b34, 0x001d2530, 0x001d2530, 0x00212934, 0x001f2834, 0x0018222c, 0x001a242f, 0x001c2630, 0x0019232d, 0x0019242e, 0x001d2832, 0x00202a34, 0x001e2b34, 0x00202d35, 0x00202e36, 0x001f2c36, 0x001e2c37, 0x0022313c, 0x00293b45, 0x00283c47, 0x00273c46, 0x00283e4b, 0x002c4350, 0x002f4552, 0x002e4451, 0x00304754, 0x00314754, 0x00334452, 0x00324350, 0x0031404d, 0x0032404f, 0x00313f4c, 0x0031404c, 0x00384854, 0x00384955, 0x002c3c48, 0x001b2b37, 0x001e2d38, 0x00212f3a, 0x001b2630, 0x0015212c, 0x00202e3c, 0x00304859, 0x0048687c, 0x007096a8, 0x009dbfc7, 0x00b9cccc, 0x00c4cccc, 0x00cbcccb, 0x00cbccc9, 0x00cbccc9, 0x00cbcbca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccccc, 0x00cacccc, 0x00c4cccc, 0x00b6cacc, 0x007a95a5, 0x00203644, 0x000e1a25, 0x000b1017, 0x00060910, 0x0003040a, 0x00020406, 0x00020405, 0x00030508, 0x00060a0e, 0x000d141c, 0x00131e2a, 0x0014212e, 0x0012232e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0013232f, 0x00142330, 0x00142430, 0x00142532, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142733, 0x00142834, 0x00142834, 0x00142934, 0x00152a35, 0x00172a37, 0x00172935, 0x00142733, 0x00142733, 0x00142834, 0x00142834, 0x00152834, 0x00182a36, 0x00182b37, 0x00182c38, 0x00192d39, 0x001a2f3a, 0x00192e3a, 0x00182d3b, 0x00192c3b, 0x001a2b38, 0x00182936, 0x00172834, 0x00172834, 0x00162834, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00122a30, 0x00132e34, 0x00163439, 0x00183a3e, 0x00194044, 0x001c4649, 0x001d4c50, 0x001f5254, 0x0022585b, 0x00245d60, 0x002c88a0, 0x0034a6cb, 0x002c7e8e, 0x002a6d6f, 0x002b7072, 0x002c7374, 0x002c7476, 0x002d7577, 0x003494aa, 0x0038aaca, 0x00308490, 0x002d7678, 0x00318c9d, 0x0038aacc, 0x0036a8c8, 0x0037a8ca, 0x0034a0bf, 0x002c8394, 0x0028696c, 0x00276467, 0x00256062, 0x00245c5f, 0x0022585b, 0x00205457, 0x001e5053, 0x001d4c50, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0017383c, 0x00153439, 0x00143036, 0x00142e34, 0x00112a30, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0012212c, 0x0013212d, 0x0014222d, 0x00142130, 0x00142332, 0x00152433, 0x00172534, 0x00182735, 0x00182734, 0x00172632, 0x00172632, 0x00152432, 0x00142330, 0x0013222e, 0x0013222d, 0x0012212d, 0x0013222d, 0x0013222e, 0x00142330, 0x00142330, 0x0014232f, 0x0014232e, 0x0013222d, 0x0013212c, 0x0011202a, 0x00101f2a, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e2a, 0x00121f2b, 0x00121f2b, 0x00121f2c, 0x00121f2c, 0x00111e2c, 0x00111d2b, 0x00111c2a, 0x00101d29, 0x000f1c26, 0x000c1823, 0x000a131c, 0x00080d16, 0x0006080e, 0x0005060a, 0x00040408, 0x00040406, 0x00030306, 0x00030408, 0x00020508, 0x0003070a, 0x00060c0e, 0x000c1318, 0x00141f28, 0x001f3440, 0x00608893, 0x00aec8ca, 0x00c5cccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcc, 0x00c8cccc, 0x00c0cbcc, 0x009cb8c1, 0x00628394, 0x003b5669, 0x002d4354, 0x00253543, 0x001c2733, 0x00101823, 0x00090f18, 0x000a0f18, 0x00141c25, 0x001c272f, 0x001c2832, 0x00192630, 0x0017232d, 0x0016242e, 0x001e303c, 0x00304452, 0x00384c5b, 0x00354a59, 0x002f4251, 0x00243544, 0x00243440, 0x0023323e, 0x0021313c, 0x001e2c38, 0x001f2c38, 0x001d2b37, 0x00192531, 0x0018242e, 0x001f2b35, 0x001c2731, 0x0018222c, 0x0017202b, 0x0018202b, 0x00172029, 0x0018212a, 0x001a232c, 0x00202830, 0x001f2a32, 0x001f2b33, 0x00212d35, 0x00243038, 0x00252e37, 0x00242c35, 0x00202831, 0x001c252c, 0x001c252c, 0x001d262d, 0x001d262d, 0x001c252c, 0x001c242c, 0x001c242c, 0x001c222c, 0x001d242d, 0x001f252d, 0x001f252e, 0x00202730, 0x00222831, 0x00232931, 0x00242a32, 0x00242a32, 0x00232830, 0x0022272f, 0x001e232b, 0x001c2128, 0x001b2025, 0x00181c23, 0x00171920, 0x0014141c, 0x000b0e14, 0x000d1015, 0x000a0d12, 0x000b0e12, 0x00090c10, 0x00070a0d, 0x00080b0e, 0x00090c10, 0x000e1114, 0x000d1013, 0x000c0f12, 0x00070a0d, 0x0008090f, 0x00080a0f, 0x00060b0e, 0x000b1013, 0x000c1315, 0x000d1418, 0x00131920, 0x00181c24, 0x001d2229, 0x0021252c, 0x0023282f, 0x00252a32, 0x00262c34, 0x00252c34, 0x00262c35, 0x00282e36, 0x00262c35, 0x00242b32, 0x00232a31, 0x00252c33, 0x00272d34, 0x00272d34, 0x00242c34, 0x00232b33, 0x00232b34, 0x00273038, 0x002a333c, 0x002b343e, 0x0029333d, 0x0028323e, 0x002c3542, 0x002c3643, 0x002e3844, 0x00303a44, 0x0027313b, 0x00202a33, 0x001f2731, 0x001b232e, 0x001b232e, 0x00202833, 0x00212b35, 0x001e2832, 0x0019242e, 0x001b2530, 0x001b2530, 0x001b2530, 0x001f2834, 0x00202b36, 0x00212e38, 0x00202f38, 0x0023313a, 0x0024333c, 0x0022313c, 0x00273741, 0x002a3c46, 0x00293d48, 0x00283c48, 0x00283d4a, 0x002c4350, 0x00304654, 0x00304754, 0x00334855, 0x00344854, 0x00324350, 0x0032404e, 0x00313e4c, 0x00313d4c, 0x00313e4c, 0x0033414f, 0x00394855, 0x00374754, 0x00243440, 0x00182733, 0x001e2c38, 0x00212e38, 0x0018222c, 0x00101a24, 0x001b2734, 0x002c4050, 0x003d586c, 0x0053788b, 0x007ca4b4, 0x00a9c6ca, 0x00bdcccc, 0x00c7cccc, 0x00caccca, 0x00cbccc9, 0x00cbcbca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cbcbcb, 0x00c5cccc, 0x00b9cbcc, 0x00829baa, 0x00243948, 0x00101c26, 0x000b1017, 0x0005080f, 0x0003050b, 0x00020408, 0x00020404, 0x00020406, 0x00030709, 0x00070c13, 0x000e1721, 0x00111e2a, 0x0012222d, 0x0011232d, 0x0012242e, 0x0012242e, 0x0012242e, 0x0013232f, 0x00142330, 0x00142431, 0x00142532, 0x00162734, 0x00152633, 0x00152633, 0x00152633, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142733, 0x00142733, 0x00142834, 0x00142834, 0x00152934, 0x00172936, 0x00172935, 0x00142733, 0x00142733, 0x00142733, 0x00142834, 0x00152834, 0x00182a36, 0x00182b37, 0x00182c38, 0x00182c38, 0x00192e3a, 0x00182d39, 0x00172c39, 0x00172c38, 0x00182b38, 0x00182936, 0x00172834, 0x00172834, 0x00162834, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00122a30, 0x00132e34, 0x00163439, 0x00183a3e, 0x00194044, 0x001c4649, 0x001d4c50, 0x001f5254, 0x0021585a, 0x00245c5f, 0x002c88a0, 0x0033a6cb, 0x002c7d8d, 0x00296c6f, 0x002b7071, 0x002c7274, 0x002c7475, 0x002d7576, 0x003494aa, 0x0038aaca, 0x00308490, 0x002d7678, 0x00328c9d, 0x0038a9cb, 0x002f8390, 0x00308ca0, 0x0034a4c4, 0x0034a7ca, 0x002e8ea8, 0x0027686c, 0x00256062, 0x00245c5f, 0x0021585a, 0x00205356, 0x001e4f51, 0x001c4a4d, 0x001b4649, 0x001a4245, 0x00183d41, 0x00183a3e, 0x0015363b, 0x00153338, 0x00142e34, 0x00132c32, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0013202c, 0x0013212c, 0x0014212c, 0x00142130, 0x00142232, 0x00152433, 0x00162434, 0x00172534, 0x00172532, 0x00162530, 0x00152430, 0x00152432, 0x00142330, 0x0013222e, 0x0013222d, 0x0012212c, 0x0013222d, 0x0013222d, 0x00142330, 0x00142330, 0x0014232f, 0x0014232e, 0x0013222d, 0x0012212c, 0x0010202b, 0x0010202b, 0x00101e29, 0x00101e29, 0x00101e29, 0x000f1f29, 0x00101f2a, 0x00111f2b, 0x00111f2b, 0x00111f2c, 0x00111f2c, 0x00111e2c, 0x00111c2b, 0x00111c2a, 0x00101c28, 0x000e1924, 0x000b141e, 0x00080f16, 0x00050910, 0x0004060b, 0x00040609, 0x00040408, 0x00030305, 0x00030304, 0x00030407, 0x00020508, 0x00030709, 0x00080c0f, 0x000e141a, 0x0016202a, 0x00223a46, 0x0069929c, 0x00b3cacb, 0x00c7cccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cbcbcc, 0x00c4cccc, 0x00aec1c7, 0x007394a3, 0x00446578, 0x00334b5d, 0x002a3c4c, 0x0021303c, 0x0018232f, 0x000c141e, 0x00060c14, 0x00090e17, 0x00141c25, 0x001a242d, 0x001a2630, 0x00182530, 0x001a2630, 0x0017242e, 0x001a2a37, 0x00304451, 0x003e5161, 0x00384c5c, 0x00304453, 0x00283847, 0x00243440, 0x0023323e, 0x0021313c, 0x001c2b37, 0x001f2d38, 0x001c2a35, 0x001a2632, 0x0018232e, 0x001f2a34, 0x001c2731, 0x0018222c, 0x0019232e, 0x001b242f, 0x00172029, 0x0018202a, 0x0018212a, 0x001f2730, 0x001b262e, 0x001b2730, 0x00202c35, 0x00242f38, 0x00242d36, 0x00232c34, 0x00202830, 0x001d272e, 0x001e272e, 0x001f282f, 0x001e272e, 0x001c242c, 0x001d262d, 0x001f2730, 0x001c232c, 0x001c222b, 0x001c242b, 0x001d242c, 0x001f252d, 0x001f252e, 0x0020262e, 0x0020282f, 0x00212830, 0x0020252d, 0x001e232b, 0x001a1e26, 0x001a1e25, 0x00191d24, 0x00181c22, 0x00171920, 0x0014141c, 0x000a0c13, 0x000d1015, 0x000a0d12, 0x00080b10, 0x00080c10, 0x00070b0d, 0x00080c0f, 0x000a0d10, 0x000e1214, 0x000c1013, 0x000b0e11, 0x00060a0d, 0x0008090e, 0x00080b0f, 0x00060c0e, 0x00070c0f, 0x00080e10, 0x000a1114, 0x000e141a, 0x00181c22, 0x00171c22, 0x00181d24, 0x0021262c, 0x0024282f, 0x00232830, 0x0020252d, 0x001f252d, 0x00222830, 0x00232830, 0x0022272f, 0x00242931, 0x00272d34, 0x00282e34, 0x00252c32, 0x00222930, 0x00222a31, 0x00222a32, 0x00283039, 0x0029313c, 0x002a333d, 0x0026303b, 0x0026303c, 0x0028333f, 0x0028313e, 0x002b3440, 0x002a343d, 0x00242d36, 0x001d2730, 0x001c2430, 0x001c2430, 0x001d2630, 0x00202834, 0x00232c37, 0x00242d38, 0x001c2631, 0x001c2530, 0x001e2833, 0x00202a35, 0x00212c38, 0x00242f3b, 0x0025333c, 0x00203039, 0x0023323c, 0x00283741, 0x00263641, 0x00283843, 0x002b3c47, 0x002a3f49, 0x002b404b, 0x002c414e, 0x002e4452, 0x00314855, 0x00334955, 0x00364b56, 0x00364854, 0x0033424f, 0x0033404d, 0x00313d4b, 0x00303c4b, 0x00313e4c, 0x00364451, 0x003b4956, 0x00354451, 0x00202e3a, 0x00172531, 0x001f2d38, 0x00212e38, 0x00172029, 0x000e1520, 0x0017212d, 0x0026384a, 0x00375064, 0x0043647b, 0x005e8599, 0x008eb2bf, 0x00b3cacc, 0x00c2cccc, 0x00c9cccb, 0x00cbccc9, 0x00cbcbca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cbcbcb, 0x00c7cccc, 0x00bdcbcc, 0x0088a1b0, 0x002a3e4f, 0x00121d2a, 0x000c1119, 0x00060910, 0x0004060b, 0x00040408, 0x00020405, 0x00010405, 0x00010407, 0x0003080c, 0x00070f17, 0x000d1822, 0x0011202b, 0x0011232d, 0x0012242e, 0x0012242e, 0x0012242e, 0x0013232f, 0x00142330, 0x00142431, 0x00142532, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142733, 0x00142733, 0x00142834, 0x00142834, 0x00152834, 0x00162935, 0x00172935, 0x00142733, 0x00142733, 0x00142733, 0x00142834, 0x00142834, 0x00172935, 0x00182a36, 0x00182a37, 0x00172b38, 0x00172c38, 0x00172c38, 0x00162b37, 0x00162b37, 0x00172a36, 0x00172935, 0x00172834, 0x00172834, 0x00162734, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00194044, 0x001b4649, 0x001d4c50, 0x001f5154, 0x00205659, 0x00245c5e, 0x002c87a0, 0x0033a6cb, 0x002b7d8c, 0x00296c6e, 0x002b6f70, 0x002c7173, 0x002c7374, 0x002c7476, 0x003494a9, 0x0038aaca, 0x00308490, 0x002d7678, 0x00328c9d, 0x0038a9cb, 0x002e7d87, 0x002b7072, 0x002c7881, 0x00329bb8, 0x0034a7cb, 0x002c8ca4, 0x00256264, 0x00245c5f, 0x0021585a, 0x00205356, 0x001f4f51, 0x001d4a4d, 0x001a4448, 0x001a4044, 0x00183c40, 0x0017383c, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f2b, 0x0013202c, 0x0013202c, 0x0013202e, 0x0014202e, 0x00142130, 0x00152332, 0x00162432, 0x00152430, 0x0014242f, 0x00152430, 0x00152431, 0x00142330, 0x0013222e, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0014232f, 0x00142330, 0x0014222e, 0x0014222c, 0x0014212c, 0x0012202c, 0x0010202b, 0x00101f2b, 0x00101e29, 0x00101e29, 0x00101e29, 0x000f1e29, 0x00101f2a, 0x00111f2b, 0x00111f2b, 0x00111f2c, 0x00101f2c, 0x00101e2c, 0x00111d2b, 0x00101c28, 0x00101a25, 0x000c1520, 0x00080f17, 0x00050910, 0x0003060c, 0x00020409, 0x00030408, 0x00030408, 0x00030405, 0x00030404, 0x00030407, 0x00020408, 0x00030609, 0x00080c10, 0x000f151a, 0x0017212c, 0x0024404d, 0x007299a3, 0x00b7cbcc, 0x00c8cccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cbcbcb, 0x00c8cccc, 0x00b8c7ca, 0x0088a4b1, 0x00507184, 0x00375468, 0x002f4354, 0x00253544, 0x001c2a35, 0x00141e28, 0x000a1018, 0x00050b13, 0x00080d16, 0x00141c25, 0x0019242d, 0x001a2630, 0x00192530, 0x001b2731, 0x0016232e, 0x00182734, 0x002e3f4e, 0x00405261, 0x00394d5d, 0x00314454, 0x002a3c4b, 0x00263644, 0x00253441, 0x0022303d, 0x001e2c39, 0x001f2c38, 0x001c2934, 0x001c2833, 0x0017232e, 0x001c2832, 0x001e2833, 0x001a242f, 0x001a242f, 0x001c2630, 0x0019232c, 0x001a242c, 0x001a232c, 0x001d262f, 0x001a242d, 0x001c2830, 0x001e2a32, 0x001f2a33, 0x00212b34, 0x00202832, 0x001e2730, 0x001e272e, 0x0020282f, 0x001e272e, 0x001c252c, 0x001c242b, 0x001c242c, 0x001f262d, 0x001f242c, 0x001e242c, 0x001e242c, 0x001c232a, 0x001c232a, 0x001c222a, 0x001d232a, 0x001e242c, 0x0020242c, 0x0020232b, 0x001d2028, 0x001a1c24, 0x00181b21, 0x00181b22, 0x00191c23, 0x0016181f, 0x00101218, 0x000a0d12, 0x000d1014, 0x00090c11, 0x00080a0f, 0x00090c10, 0x00080a0d, 0x000a0c0f, 0x000b0c10, 0x000e1114, 0x000c1013, 0x000a0d10, 0x00070a0c, 0x00080b0e, 0x000a0c10, 0x00080d10, 0x00070c0f, 0x00080c10, 0x000a1014, 0x000e1218, 0x0017191f, 0x0015181f, 0x0014181f, 0x001c2026, 0x001f242a, 0x001f242b, 0x001c2128, 0x001c2129, 0x0021272e, 0x00242830, 0x00242830, 0x00222830, 0x00242b30, 0x00242b30, 0x0021282e, 0x00202730, 0x00212933, 0x00232b34, 0x00273038, 0x0029313c, 0x0028313c, 0x00242e39, 0x00242d39, 0x00242e3b, 0x00252e3b, 0x0028303c, 0x00262f38, 0x00212a33, 0x001c252e, 0x001b232c, 0x001b212c, 0x001c222d, 0x001c232e, 0x00222c36, 0x00242f39, 0x00202b35, 0x001c2833, 0x001d2933, 0x00212d38, 0x00263240, 0x00273441, 0x00283844, 0x00243440, 0x0022333e, 0x00283945, 0x00283946, 0x00283a47, 0x002c3e4b, 0x002f444f, 0x00314652, 0x00334855, 0x00334956, 0x00334a57, 0x00344a56, 0x00364855, 0x00364653, 0x0034414f, 0x00333e4b, 0x00313c49, 0x00303b4a, 0x00333e4c, 0x00374452, 0x00394754, 0x00303e4a, 0x001a2834, 0x00182631, 0x00202f3a, 0x00202b35, 0x00141c26, 0x000c121c, 0x00131c27, 0x00233243, 0x0032485b, 0x003f5b70, 0x004c7085, 0x006c92a6, 0x009dbdc7, 0x00bbcbcc, 0x00c7cccc, 0x00c9cccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cbcccb, 0x00c8cccc, 0x00bdcccc, 0x008ca6b3, 0x002d4253, 0x00141f2b, 0x000e1219, 0x00080b11, 0x0004060c, 0x00030408, 0x00030405, 0x00020404, 0x00020406, 0x0002050a, 0x00030810, 0x00080e18, 0x000f1a24, 0x0013202c, 0x0013232d, 0x0012242e, 0x0012242e, 0x0013232f, 0x00142330, 0x00142431, 0x00142533, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142733, 0x00142733, 0x00142733, 0x00142834, 0x00152834, 0x00152834, 0x00152834, 0x00142733, 0x00142733, 0x00142733, 0x00142734, 0x00142834, 0x00152834, 0x00162834, 0x00172935, 0x00152935, 0x00162a36, 0x00162a36, 0x00162935, 0x00162935, 0x00162935, 0x00152834, 0x00162834, 0x00162734, 0x00162734, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00194044, 0x001b4649, 0x001d4b4e, 0x00205154, 0x00205659, 0x00245c5e, 0x002c87a0, 0x0033a6cb, 0x002b7d8c, 0x00296b6d, 0x002a6d6f, 0x002c7072, 0x002c7274, 0x002c7475, 0x003394a9, 0x0038aaca, 0x00308490, 0x002d7678, 0x00318c9d, 0x0038a9cb, 0x002e7d87, 0x002c7072, 0x002a6e70, 0x002a7278, 0x00319cba, 0x0032a4c8, 0x00287888, 0x00245c5f, 0x0021585a, 0x00205356, 0x001f4f51, 0x001d4a4d, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00143338, 0x00153036, 0x00132c32, 0x00102a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101e28, 0x00111f28, 0x00111f29, 0x00111f2a, 0x0012202a, 0x0012202c, 0x0012202c, 0x0013222e, 0x0014232e, 0x0014242e, 0x0014242f, 0x00142530, 0x0013242f, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0014232e, 0x0015232e, 0x0014222d, 0x0014212b, 0x0014212b, 0x0013202b, 0x00111f2b, 0x00101e2a, 0x00111d28, 0x00111c28, 0x00111e29, 0x00101e29, 0x00101e29, 0x00111f2b, 0x00111f2b, 0x00101f2a, 0x000f1f29, 0x00101f2a, 0x00111e2a, 0x000f1a24, 0x000c151f, 0x000a1018, 0x00070910, 0x0003060b, 0x00020509, 0x00010408, 0x00010408, 0x00010408, 0x00010405, 0x00020405, 0x00020508, 0x00020609, 0x0004080a, 0x00080d10, 0x0010161b, 0x0018232d, 0x00284452, 0x007ba2ab, 0x00bccccc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00c8cccc, 0x00bccacc, 0x0094afbb, 0x005d7c8f, 0x003e5b6e, 0x00324a5c, 0x002b3d4c, 0x0023303e, 0x001c2731, 0x00141c25, 0x000b1018, 0x00060b13, 0x00070d15, 0x00131c24, 0x0019242d, 0x001a2730, 0x0019272f, 0x0019262f, 0x0014222c, 0x00172431, 0x00293948, 0x003a4e5d, 0x00344b5a, 0x002f4654, 0x002a3f4e, 0x00253948, 0x00243644, 0x0023323e, 0x001f2d39, 0x001c2a35, 0x001a2832, 0x001a2832, 0x0018252f, 0x001d2a34, 0x001f2c35, 0x001c2731, 0x001c2731, 0x0018252f, 0x00192530, 0x001c2832, 0x001c2731, 0x001a2630, 0x001c2731, 0x001e2a34, 0x001d2832, 0x001d2832, 0x00202833, 0x00202832, 0x001f2730, 0x001e272f, 0x00202830, 0x001c242c, 0x00182029, 0x001b232c, 0x001b232c, 0x001d242d, 0x001d232b, 0x0020252c, 0x0020242c, 0x001e2329, 0x001d2128, 0x001c2027, 0x001b2026, 0x001c2127, 0x001d2228, 0x001e2128, 0x001c2026, 0x00181b22, 0x0014181e, 0x00171920, 0x00181c22, 0x0013161c, 0x000d1015, 0x000b0e12, 0x000a0d11, 0x00080b10, 0x0008090d, 0x0008090c, 0x00090b0e, 0x000b0c10, 0x000c0e11, 0x00101215, 0x000c1013, 0x00080c0f, 0x0006090c, 0x00080a0e, 0x000a0c10, 0x000c0e11, 0x000a0c10, 0x000a0c10, 0x000d0f14, 0x000f1016, 0x0014161c, 0x0010141b, 0x0010151c, 0x00181e24, 0x00181e24, 0x00181d24, 0x00191e24, 0x001a1f25, 0x001d222a, 0x0022272f, 0x00212730, 0x001f252d, 0x001e242c, 0x0020262e, 0x001f262e, 0x00202730, 0x00202831, 0x00212932, 0x00252d37, 0x00283039, 0x00272f3a, 0x00232d38, 0x00222c38, 0x00212b38, 0x00232d39, 0x00242d38, 0x00222b34, 0x00202830, 0x001c242c, 0x001c232c, 0x001c222c, 0x001d242e, 0x001c242e, 0x00202932, 0x00222d37, 0x00202c37, 0x001f2c36, 0x001c2a34, 0x00213039, 0x002a3946, 0x00293b48, 0x00283c48, 0x00273b48, 0x00243845, 0x00273a48, 0x00283b48, 0x002b404d, 0x002f4451, 0x00314855, 0x00344a58, 0x00344c5a, 0x00364e5d, 0x00374c5b, 0x00364957, 0x00334351, 0x0032404f, 0x0033404d, 0x00303c48, 0x00313b47, 0x00313b48, 0x0034404d, 0x00374552, 0x00354450, 0x00263540, 0x0015242f, 0x001b2934, 0x00202f39, 0x001d2831, 0x00111820, 0x00090e18, 0x00111924, 0x00202e3d, 0x002f4355, 0x003b556a, 0x0043647a, 0x0051778e, 0x007aa0b3, 0x00a7c4ca, 0x00bdcccc, 0x00c6cccc, 0x00cacbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbca, 0x00cbccc9, 0x00cbccca, 0x00c9cbca, 0x00bdcccb, 0x008facb7, 0x00314858, 0x0014202c, 0x000e1319, 0x00070c11, 0x0002070b, 0x00030407, 0x00020405, 0x00020405, 0x00020406, 0x00020409, 0x0002050c, 0x00050910, 0x00091118, 0x00121c24, 0x0014202c, 0x0013222d, 0x0013222e, 0x00132331, 0x00122431, 0x00132432, 0x00142433, 0x00142533, 0x00142733, 0x00142733, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00142633, 0x00132632, 0x00142733, 0x00142733, 0x00152834, 0x00162834, 0x00162834, 0x00152633, 0x00152633, 0x00152633, 0x00162734, 0x00162734, 0x00162734, 0x00162834, 0x00172834, 0x00172834, 0x00172834, 0x00172834, 0x00172834, 0x00172834, 0x00142834, 0x00142834, 0x00142734, 0x00162734, 0x00162734, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001a4448, 0x001d4b4e, 0x00205154, 0x00205558, 0x00225a5c, 0x002c87a0, 0x0032a5cb, 0x002a7c8c, 0x00286a6c, 0x00296c6f, 0x002b6f70, 0x002c7173, 0x002c7374, 0x003393a9, 0x0038aaca, 0x00308490, 0x002e7577, 0x00318c9d, 0x0038a9cb, 0x002e7d87, 0x002c7072, 0x002a6e70, 0x00296b6d, 0x002a7783, 0x0031a3c6, 0x002e98b8, 0x00245e62, 0x0021585a, 0x00205356, 0x001e4f51, 0x001d4a4d, 0x001a4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00143338, 0x00143036, 0x00132c32, 0x00102a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101d27, 0x00101e28, 0x00101e28, 0x00101e28, 0x00111f28, 0x00111f2b, 0x0011202b, 0x0012202c, 0x0012212c, 0x0013222d, 0x0014242f, 0x00152530, 0x0014242f, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0014222d, 0x0014222d, 0x0014222c, 0x0013202a, 0x0013202a, 0x0013202b, 0x00111f2b, 0x00101e2a, 0x00111c28, 0x00111c28, 0x00111e29, 0x00101e29, 0x00101e29, 0x00111f2b, 0x00111f2b, 0x00101f2a, 0x00101e29, 0x00101e2a, 0x00101c28, 0x000c1520, 0x00080f18, 0x0006090f, 0x0004060b, 0x00030508, 0x00030408, 0x00020407, 0x00010407, 0x00000407, 0x00000405, 0x00000405, 0x00010508, 0x00020609, 0x0004080a, 0x00090d10, 0x0010161b, 0x0018242e, 0x002c4855, 0x0080a8b0, 0x00becccc, 0x00cccacc, 0x00cccbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00c9cccc, 0x00c0cbcc, 0x00a4bcc4, 0x006a8a9d, 0x00436277, 0x00385063, 0x002f4454, 0x00283846, 0x00202d39, 0x001a242f, 0x00111923, 0x00091018, 0x00060b14, 0x00070c15, 0x00111822, 0x001a232c, 0x0019242f, 0x0018242c, 0x0017232b, 0x00132028, 0x0014222e, 0x00233240, 0x00304655, 0x00314958, 0x002f4756, 0x002c4150, 0x00283d4c, 0x00263a48, 0x00243440, 0x0022303c, 0x001d2b35, 0x001c2a34, 0x001d2b34, 0x00192731, 0x001e2c35, 0x001e2b35, 0x001c2832, 0x001c2832, 0x0017242f, 0x001a2831, 0x001c2a34, 0x00192630, 0x001b2831, 0x00202c36, 0x00212d37, 0x001f2b34, 0x00202c36, 0x00202b35, 0x00202a33, 0x00202932, 0x00212931, 0x00202930, 0x001b232b, 0x0019222b, 0x001c242e, 0x001c242d, 0x001c242d, 0x001c222b, 0x0020242b, 0x001e2329, 0x001c2027, 0x001c1f25, 0x001b1e24, 0x001a1e23, 0x001a2024, 0x001a1f24, 0x001b1e24, 0x001b1d23, 0x00161920, 0x0014181c, 0x0015181d, 0x00161920, 0x0011141b, 0x000c0f14, 0x00090d10, 0x000b0e11, 0x00080c0f, 0x0006080c, 0x0006080b, 0x000a0c0f, 0x000c0e11, 0x000e1013, 0x00101215, 0x000d1014, 0x00080b0e, 0x0006090c, 0x0008090d, 0x000a0c0f, 0x000c0d11, 0x000a0c0f, 0x000a0c0f, 0x000d0f14, 0x000e1015, 0x0014161c, 0x000c1118, 0x000f141a, 0x00161c23, 0x00151b23, 0x00141820, 0x00151a20, 0x00171c22, 0x001c2028, 0x0020242d, 0x00202630, 0x001f252e, 0x001c232c, 0x001c232c, 0x001c252d, 0x00202830, 0x00202830, 0x00202830, 0x00242c35, 0x00262e38, 0x00242c38, 0x00222c36, 0x00222c38, 0x00202a36, 0x00212b37, 0x00222a36, 0x001e2530, 0x001d262e, 0x001c242c, 0x001c242c, 0x001c232c, 0x00212831, 0x00212a33, 0x001f2831, 0x00202c34, 0x00232f39, 0x00202c36, 0x001f2d37, 0x0025343f, 0x002b3c48, 0x002d404e, 0x002c414f, 0x002b414e, 0x00283f4c, 0x00273d4b, 0x00283f4c, 0x002c4250, 0x00304654, 0x00314857, 0x00344a58, 0x00354d5c, 0x00395262, 0x00384c5c, 0x00354655, 0x00303e4d, 0x002d3b49, 0x002f3c48, 0x002f3b45, 0x002f3944, 0x00303a46, 0x0034404d, 0x00374552, 0x0030404c, 0x001c2c37, 0x0013222c, 0x001d2c36, 0x00213039, 0x001c2830, 0x0010151d, 0x00080c15, 0x000f1620, 0x001d2a38, 0x002d3f50, 0x00385064, 0x003e5d73, 0x00466881, 0x005a829a, 0x0084adbc, 0x00adc8cb, 0x00c0cccc, 0x00c9cccc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbca, 0x00cbccc9, 0x00cbccca, 0x00cacbca, 0x00bdccca, 0x0090adb7, 0x00334959, 0x0014202b, 0x000e1318, 0x00060c10, 0x0002070b, 0x00030407, 0x00020404, 0x00020404, 0x00020405, 0x00020408, 0x00010409, 0x0004070c, 0x00080c12, 0x000e141c, 0x00141c28, 0x0014212c, 0x0014222e, 0x00132431, 0x00122432, 0x00132433, 0x00132433, 0x00142533, 0x00142733, 0x00142733, 0x00152734, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00142633, 0x00132632, 0x00132632, 0x00142733, 0x00152834, 0x00162834, 0x00162734, 0x00152633, 0x00152633, 0x00152633, 0x00162734, 0x00162734, 0x00162734, 0x00162734, 0x00162734, 0x00162834, 0x00162834, 0x00162834, 0x00162834, 0x00162834, 0x00142733, 0x00142733, 0x00142633, 0x00152633, 0x00152633, 0x000d1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001d4b4e, 0x001e5053, 0x00215558, 0x00235a5c, 0x002b87a0, 0x0032a5cb, 0x002a7c8c, 0x0028696c, 0x00296c6e, 0x002b6f70, 0x002b7072, 0x002c7274, 0x003393a9, 0x0037a9ca, 0x0030848f, 0x002e7577, 0x00318c9d, 0x0038a9cb, 0x002d7d86, 0x002b7072, 0x002a6e70, 0x00296c6e, 0x0028686b, 0x002c8ba4, 0x0031a4c9, 0x00277281, 0x0022585b, 0x00205457, 0x001e4f51, 0x001c4a4d, 0x001b4649, 0x00194044, 0x00183d41, 0x0017383c, 0x00143439, 0x00153036, 0x00132c32, 0x00102a30, 0x0011282e, 0x0012242c, 0x0012242c, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101d27, 0x00101e28, 0x00101e28, 0x00111e27, 0x00111d26, 0x00111e28, 0x00111f29, 0x0012202c, 0x0013202c, 0x0014212d, 0x0014232e, 0x0014242f, 0x0014242f, 0x0013222d, 0x0012212c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0013212c, 0x0014212c, 0x0013202c, 0x00121f2b, 0x00121f2b, 0x00121f2b, 0x00111f2b, 0x00101e2a, 0x00111c28, 0x00111c28, 0x00111e29, 0x00111e29, 0x00111e29, 0x00121f2b, 0x00121f2b, 0x00111f2b, 0x00111f2a, 0x00101c28, 0x000e1824, 0x0009111c, 0x00060c14, 0x0004070c, 0x00030508, 0x00030406, 0x00030405, 0x00020404, 0x00020404, 0x00020404, 0x00010404, 0x00010404, 0x00020508, 0x00020609, 0x0004080a, 0x00090d10, 0x0010161b, 0x001a242c, 0x002f4b55, 0x0081aab0, 0x00becccc, 0x00cbcbcc, 0x00cccbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccca, 0x00ccccca, 0x00cacccb, 0x00c4cccc, 0x00afc4c8, 0x007c9bac, 0x004c6c80, 0x003b566b, 0x0033495c, 0x002b3e4d, 0x00243441, 0x001d2a36, 0x0018222c, 0x00101820, 0x00070c15, 0x00040811, 0x00070c14, 0x0010151f, 0x0019202c, 0x0018222c, 0x0016222a, 0x00142028, 0x00121e26, 0x00111d28, 0x001c2a37, 0x002c404d, 0x00344b59, 0x00314858, 0x002c4352, 0x00294050, 0x00253b48, 0x00243540, 0x0025343f, 0x001f2c37, 0x00202d37, 0x001d2b35, 0x00182630, 0x001f2d37, 0x001d2b34, 0x001c2933, 0x00192730, 0x001a2831, 0x001e2c35, 0x001c2933, 0x00192630, 0x001f2c35, 0x00222e38, 0x00222e38, 0x0024303a, 0x0024303c, 0x0025303b, 0x00212c35, 0x00222c35, 0x00242c35, 0x00202932, 0x001d262f, 0x00202831, 0x00202831, 0x001f2730, 0x001a222b, 0x001c212a, 0x0020242b, 0x001d2228, 0x001b1e25, 0x001b1e25, 0x001b1e25, 0x00191d24, 0x001a1f24, 0x001a1f25, 0x00181c23, 0x00191c23, 0x00171a22, 0x0015181f, 0x0013161c, 0x0013161e, 0x0010131b, 0x000a0d13, 0x00090c10, 0x000a0e10, 0x00070a0d, 0x0006080c, 0x0008090d, 0x000b0c10, 0x000f1014, 0x00101114, 0x00101215, 0x000c1013, 0x00080b0e, 0x0006090c, 0x00080a0d, 0x000a0c0f, 0x000c0d10, 0x000a0c0f, 0x000b0c10, 0x000c0d10, 0x000c0e14, 0x0015181f, 0x0010141a, 0x0012171d, 0x00171c22, 0x00191e25, 0x00181c23, 0x001a1d24, 0x001b1e25, 0x001d2128, 0x0020252d, 0x00222730, 0x00212730, 0x001f242d, 0x001d242c, 0x001e252d, 0x001f262f, 0x001d252f, 0x001f2630, 0x00242b34, 0x00242c36, 0x00242c36, 0x00242c37, 0x00242e38, 0x00212b36, 0x00202834, 0x00212834, 0x00202730, 0x001e242d, 0x001a212a, 0x001c232c, 0x001c232c, 0x00202831, 0x00232b34, 0x00212c34, 0x001d2831, 0x00202c35, 0x001d2a34, 0x001f2d37, 0x00263540, 0x00283a46, 0x002b3e4b, 0x002e4450, 0x002d4451, 0x002b4250, 0x0029404d, 0x0029404f, 0x002c4352, 0x002f4655, 0x00324a58, 0x002f4856, 0x00334b5a, 0x003b5363, 0x00384b5b, 0x00344352, 0x002f3c4b, 0x002c3746, 0x002c3744, 0x002d3842, 0x002e3842, 0x00303a45, 0x0036424f, 0x00364451, 0x002b3945, 0x0015242e, 0x0012212b, 0x001e2c36, 0x00202f38, 0x001a242d, 0x000d141c, 0x00070c14, 0x000d131c, 0x001c2734, 0x002c3c4b, 0x00354c5d, 0x003b576b, 0x00416178, 0x00486e86, 0x00638ca1, 0x0095b9c5, 0x00b6cbcc, 0x00c4cccc, 0x00cacccc, 0x00cbcbcb, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbca, 0x00cbccc9, 0x00cbccca, 0x00cacbca, 0x00bdccca, 0x0090acb7, 0x00314857, 0x0014202c, 0x000e1418, 0x00060c10, 0x0002070b, 0x00030508, 0x00020405, 0x00020405, 0x00020405, 0x00020407, 0x00000408, 0x00020509, 0x0004080d, 0x00080c13, 0x000f161f, 0x0013202b, 0x0014222e, 0x00122431, 0x00122432, 0x00132433, 0x00132432, 0x00142532, 0x00132632, 0x00142733, 0x00142633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00142633, 0x00132632, 0x00132632, 0x00132532, 0x00142632, 0x00162633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00162734, 0x00162734, 0x00162734, 0x00162734, 0x00162734, 0x00162734, 0x00162734, 0x00162734, 0x00162734, 0x00152733, 0x00142633, 0x00142633, 0x00142633, 0x00152633, 0x00152633, 0x000d1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001d4b4e, 0x001e5053, 0x00205558, 0x0023595c, 0x002b86a0, 0x0032a5cb, 0x002a7c8c, 0x0028686b, 0x002a6c6e, 0x002a6e70, 0x002b7071, 0x002c7274, 0x003393a9, 0x0037a9ca, 0x002f848f, 0x002c7576, 0x00318c9d, 0x0038a9cb, 0x002d7d86, 0x002b7072, 0x002a6e70, 0x00296c6e, 0x0028686b, 0x0028747e, 0x0031a3c8, 0x002a859f, 0x0022595c, 0x00205558, 0x001f5053, 0x001d4b4e, 0x001c474b, 0x001a4245, 0x00183f43, 0x00183a3e, 0x0016363b, 0x00153338, 0x00142e34, 0x00132c32, 0x00112a30, 0x0012282e, 0x0013242c, 0x00102229, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101c26, 0x00101c24, 0x00101d27, 0x00101e28, 0x00111f2b, 0x00121f2b, 0x0014212c, 0x0014222d, 0x0014222d, 0x0013222d, 0x0012212c, 0x0012202c, 0x0012202c, 0x0012202c, 0x0012202c, 0x0013202c, 0x0013202c, 0x0013202b, 0x00111f2b, 0x00111f2b, 0x00121f2b, 0x00111f2b, 0x00101e2a, 0x00111c28, 0x00111c28, 0x00121e29, 0x00121e29, 0x00121e29, 0x00131f2b, 0x00131f2b, 0x00131f2a, 0x00131e28, 0x000f1824, 0x000a121c, 0x00060c15, 0x0004080e, 0x00040608, 0x00020405, 0x00030304, 0x00030304, 0x00020203, 0x00020203, 0x00020204, 0x00010204, 0x00010304, 0x00030508, 0x00020609, 0x0004080a, 0x00090d10, 0x0010161b, 0x001a242d, 0x00304b56, 0x0080aab0, 0x00bdcccc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccc9, 0x00cacccc, 0x00c4cccc, 0x00b4c6ca, 0x0088a7b6, 0x0057788c, 0x003e5a71, 0x00375064, 0x002e4456, 0x00273849, 0x00202f3c, 0x001a2631, 0x00151f28, 0x0010161f, 0x00080c14, 0x00030710, 0x00060911, 0x0010141c, 0x001a202b, 0x0018212c, 0x00162029, 0x00142028, 0x00101c24, 0x000c1820, 0x0015222c, 0x00283a47, 0x00384c5b, 0x00344b5a, 0x002c4453, 0x002c4452, 0x00283d4b, 0x00263742, 0x00273540, 0x00202e39, 0x0022303b, 0x001e2c37, 0x00192731, 0x00202e38, 0x00202e38, 0x001d2b34, 0x00192831, 0x00202d37, 0x00212f38, 0x001e2c36, 0x001f2c36, 0x00232f38, 0x00222e38, 0x00222e38, 0x00243039, 0x0025313c, 0x0024303a, 0x001d2932, 0x001f2a32, 0x00202b34, 0x00202831, 0x00222a34, 0x00232b35, 0x00222a34, 0x00202832, 0x001b232c, 0x001b2029, 0x0020252c, 0x001f242a, 0x001d2028, 0x001c1e27, 0x001a1c24, 0x00191c24, 0x001b2026, 0x001a1f25, 0x00181c22, 0x00181c23, 0x00171922, 0x0014171d, 0x0010131a, 0x0013161c, 0x000e1117, 0x000a0d13, 0x00080c10, 0x00080b0e, 0x0006090c, 0x00080a0d, 0x00090b0e, 0x000a0c0f, 0x000b0c10, 0x000e1013, 0x00101316, 0x000e1114, 0x000a0d10, 0x00080c0f, 0x00080a0d, 0x00090b0e, 0x000b0c10, 0x000a0c0f, 0x000c0d10, 0x000b0c10, 0x000b0c12, 0x0014171e, 0x0011141b, 0x0011151c, 0x00161b20, 0x001c2027, 0x001b1f25, 0x001c2025, 0x001c1f25, 0x001b1e24, 0x001d2228, 0x001f242c, 0x0020242c, 0x0020252d, 0x0020262e, 0x0020272f, 0x001f262f, 0x001e242e, 0x00202630, 0x00242b34, 0x00242b34, 0x00232b34, 0x00242d36, 0x0027313c, 0x00242f39, 0x00202a34, 0x00202832, 0x00212832, 0x00202630, 0x001a202b, 0x001d242d, 0x001e242e, 0x001d252e, 0x00202932, 0x00252f38, 0x001e2932, 0x001c2832, 0x001c2a34, 0x001d2c35, 0x0024343f, 0x00273844, 0x002a3d49, 0x002f4550, 0x002f4552, 0x002c4250, 0x002b414f, 0x002e4454, 0x002f4755, 0x00314958, 0x00314b59, 0x002d4755, 0x00304857, 0x003a5060, 0x00354757, 0x00323f50, 0x00303a49, 0x002c3745, 0x002c3543, 0x002d3641, 0x002f3842, 0x00313b46, 0x0037424f, 0x0034414d, 0x0024303c, 0x00101d28, 0x0014222d, 0x00202d38, 0x00202d37, 0x0019232c, 0x000c131a, 0x00080b14, 0x000c111b, 0x00182430, 0x00293946, 0x00324758, 0x00395264, 0x00405b6f, 0x00446378, 0x004e748b, 0x00749cb0, 0x009fc2c8, 0x00bccccc, 0x00c7cccc, 0x00cacccb, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbca, 0x00cbccc9, 0x00cbccca, 0x00cacbca, 0x00bdcccb, 0x008facb5, 0x00304654, 0x0014212c, 0x000e141a, 0x00060c10, 0x0002070b, 0x00030408, 0x00020405, 0x00020404, 0x00020405, 0x00020407, 0x00000408, 0x00010408, 0x00010508, 0x0004070c, 0x00081016, 0x00101b25, 0x0013222c, 0x00122430, 0x00122431, 0x00132431, 0x00142431, 0x00132532, 0x00132632, 0x00132632, 0x00142633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00142633, 0x00132532, 0x00132532, 0x00132531, 0x00142431, 0x00162532, 0x00162532, 0x00162532, 0x00162532, 0x00162532, 0x00142532, 0x00142533, 0x00152633, 0x00152633, 0x00152633, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x000d1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001d4a4d, 0x001e5053, 0x00205457, 0x0022595c, 0x002b86a0, 0x0032a5cb, 0x002a7b8b, 0x0028686a, 0x00296b6d, 0x002a6d6f, 0x002b7071, 0x002b7173, 0x003292a8, 0x0037a9ca, 0x0030828e, 0x002c7476, 0x00318c9d, 0x0038a9cb, 0x002d7d86, 0x002b7072, 0x00296d6f, 0x00296b6d, 0x0028686b, 0x00286a6f, 0x00309dc0, 0x002c90ae, 0x00235a5c, 0x00215659, 0x00205254, 0x001d4d50, 0x001c484c, 0x001b4448, 0x00194044, 0x00183c40, 0x0017383c, 0x00143439, 0x00143036, 0x00142e34, 0x00132c32, 0x00112a30, 0x0012282e, 0x0013242c, 0x00102229, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101c26, 0x00101c24, 0x00101d27, 0x00101e28, 0x00111f2a, 0x00121f2b, 0x0014202c, 0x0014212c, 0x0014212c, 0x0013212c, 0x0012202c, 0x0012202b, 0x0012202b, 0x0013202c, 0x0013202c, 0x0012202a, 0x00111f29, 0x00111f29, 0x00111f29, 0x00111f29, 0x00111f2a, 0x00111f2b, 0x00101e2a, 0x00111d29, 0x00111d29, 0x00121f2a, 0x00121f2a, 0x00121f2a, 0x00131f2b, 0x00131f2b, 0x00141e29, 0x00111a24, 0x000c141d, 0x00070c15, 0x00040810, 0x0004060c, 0x00040406, 0x00030406, 0x00030306, 0x00030305, 0x00020203, 0x00020202, 0x00020203, 0x00000204, 0x00010304, 0x00020507, 0x00020609, 0x0004080a, 0x00090d10, 0x0010161b, 0x0019242d, 0x00304d58, 0x0083acb2, 0x00bdcccc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccca, 0x00c9ccca, 0x00c5cccc, 0x00b8c8cc, 0x0092aebd, 0x005f8196, 0x00426176, 0x003b5368, 0x00344a5e, 0x002c3f50, 0x00243444, 0x001d2c38, 0x0018242e, 0x00141d27, 0x000f151d, 0x00080c14, 0x00040810, 0x00080911, 0x0010121b, 0x00191d28, 0x0018202b, 0x00172029, 0x00151f28, 0x00101a22, 0x000a141d, 0x000f1a24, 0x0021303c, 0x00354653, 0x00354958, 0x002f4454, 0x002f4554, 0x002c404e, 0x00273845, 0x00263542, 0x0022303d, 0x0021303c, 0x001f2c38, 0x001c2934, 0x00202e39, 0x00212f39, 0x001f2c37, 0x001d2b34, 0x00222f38, 0x00222f39, 0x0023303a, 0x00212e38, 0x00202c37, 0x001f2c35, 0x00222e38, 0x0024303a, 0x0024303c, 0x00212d38, 0x001c2730, 0x001e2832, 0x00202832, 0x00202831, 0x00222a34, 0x00222a34, 0x00212933, 0x00202831, 0x001a222b, 0x001b2029, 0x001e2329, 0x001e2329, 0x001d2028, 0x001b1e27, 0x00181b24, 0x00181b24, 0x00191e25, 0x00181c24, 0x00171a21, 0x00161821, 0x0013161e, 0x0011141b, 0x0010141a, 0x0012151c, 0x000d1016, 0x000b0d14, 0x00080c11, 0x00070a10, 0x00070a10, 0x00080b0f, 0x000a0c0f, 0x00090b0f, 0x00090a0e, 0x000d0f12, 0x00101316, 0x000e1114, 0x000c1013, 0x000b0e11, 0x00090b0f, 0x00080a0f, 0x00080a0d, 0x00080a0d, 0x00090c10, 0x000a0c11, 0x00090c12, 0x000f1118, 0x000f1219, 0x0012161c, 0x00161b21, 0x001a1f26, 0x00181c22, 0x00181c21, 0x00191c23, 0x001a1d24, 0x00191d24, 0x001a1f27, 0x001b2028, 0x001f232b, 0x0020262d, 0x0020272f, 0x00202630, 0x00202830, 0x00212831, 0x00242c35, 0x00242a34, 0x00212932, 0x00242d36, 0x0028323c, 0x0027313c, 0x00242f39, 0x00212c36, 0x00222a35, 0x00202834, 0x001d2430, 0x001f2632, 0x00232b37, 0x001e2631, 0x001d2530, 0x00212b34, 0x00202c36, 0x00212d38, 0x00202d38, 0x001c2b34, 0x00202f3b, 0x00233440, 0x002b3d4a, 0x002d424f, 0x002d4450, 0x002c4450, 0x002d4452, 0x00304756, 0x00314858, 0x00334a59, 0x00334b5a, 0x00304857, 0x00304856, 0x00354a58, 0x00334252, 0x00303c4a, 0x002f3847, 0x002d3845, 0x002d3743, 0x002e3742, 0x00303944, 0x00343d48, 0x0037424d, 0x002f3b44, 0x001b2730, 0x000e1b24, 0x00172530, 0x00212e38, 0x001f2c37, 0x0018212a, 0x000b1018, 0x00070911, 0x000b1019, 0x0017222d, 0x00263541, 0x00304452, 0x00374d5f, 0x003c5468, 0x00415c71, 0x0045647d, 0x00577d94, 0x007ca8b7, 0x00adc8cb, 0x00c2cccc, 0x00c9cccc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbca, 0x00cbccc9, 0x00cbccca, 0x00cbcbca, 0x00bfcccb, 0x008eaab4, 0x002e4452, 0x0014202d, 0x000c131b, 0x00060c10, 0x0002060a, 0x00030407, 0x00020404, 0x00020404, 0x00020405, 0x00020407, 0x00000408, 0x00000408, 0x00000408, 0x00020508, 0x00050a10, 0x000a141c, 0x00101d27, 0x0014222e, 0x00142430, 0x00142431, 0x00142431, 0x00132431, 0x00132632, 0x00132632, 0x00142633, 0x00152633, 0x00152633, 0x00152633, 0x00142533, 0x00142532, 0x00152531, 0x00152531, 0x00152531, 0x00142430, 0x00142430, 0x00152431, 0x00152431, 0x00152431, 0x00152431, 0x00152431, 0x00142431, 0x00142431, 0x00142532, 0x00142533, 0x00142532, 0x00142532, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x000d1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001d4a4d, 0x001e5053, 0x00205457, 0x0022595c, 0x002b86a0, 0x0032a5cb, 0x00297b8b, 0x0028686a, 0x00286a6c, 0x00296d6f, 0x002b6f70, 0x002b7173, 0x003292a8, 0x0037a9ca, 0x002f828e, 0x002c7476, 0x00318b9c, 0x0037a9cb, 0x002d7d86, 0x002b7071, 0x002a6d6f, 0x00296b6d, 0x0028686b, 0x00276769, 0x00309aba, 0x002d95b4, 0x00245c5f, 0x0021585a, 0x00205356, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183c40, 0x0016383c, 0x00143439, 0x00153338, 0x00142e34, 0x00132c32, 0x00112a30, 0x0012282e, 0x0013242c, 0x00102229, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101d25, 0x00101c26, 0x00101c26, 0x00101c25, 0x00101c24, 0x00111d25, 0x00111d27, 0x00111e27, 0x00111e28, 0x00121e28, 0x00121e28, 0x00121e28, 0x00121e28, 0x00111f27, 0x00101f27, 0x00101f27, 0x00121f29, 0x00122029, 0x00121e29, 0x00111d28, 0x00111d28, 0x00121e28, 0x00121e28, 0x00111f29, 0x00101e2a, 0x00101e2a, 0x00111e2a, 0x00111f2a, 0x00111f2b, 0x00121f2b, 0x00121f2b, 0x0013202c, 0x00131f2a, 0x00121c25, 0x000d151e, 0x00090e17, 0x00060910, 0x0004060c, 0x00040409, 0x00020406, 0x00010206, 0x00010206, 0x00020206, 0x00010205, 0x00000204, 0x00000204, 0x00000304, 0x00000304, 0x00000405, 0x00000607, 0x0003080a, 0x00080e11, 0x000f171d, 0x0017242e, 0x002e4f58, 0x0082aeb4, 0x00bbcccc, 0x00cacccc, 0x00cbcccb, 0x00cacccb, 0x00cacccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00cccbca, 0x00cbcccb, 0x00c5cccc, 0x00bac9cc, 0x0098b4c0, 0x0066879c, 0x0046657c, 0x003c576b, 0x00364c5e, 0x00304354, 0x00283a49, 0x0022313f, 0x001c2936, 0x0017212c, 0x00141c25, 0x000e141b, 0x00090c14, 0x0005080f, 0x00080810, 0x000d1018, 0x00161b24, 0x00181f29, 0x00171f28, 0x00161e27, 0x00111a22, 0x000b141c, 0x000b141d, 0x0017242e, 0x002c3b48, 0x00344553, 0x00334554, 0x00314553, 0x002d404f, 0x00283a48, 0x00253443, 0x00233240, 0x0021303d, 0x00202d3a, 0x001f2c38, 0x00202d38, 0x001f2c37, 0x001c2a35, 0x00202d38, 0x0023303b, 0x0023303c, 0x00283540, 0x0024313c, 0x00202d37, 0x001a2831, 0x00202e37, 0x0024323c, 0x00222f39, 0x001d2833, 0x001c2732, 0x00202934, 0x00212b35, 0x00202934, 0x001f2830, 0x00212931, 0x00202830, 0x001e262d, 0x001a2129, 0x001b2028, 0x001b2127, 0x001a2026, 0x00181d24, 0x00181c24, 0x00171b21, 0x00171c21, 0x00181c22, 0x00161b20, 0x0016191e, 0x0012141a, 0x000f1218, 0x000f1218, 0x00101318, 0x000f1217, 0x000c1014, 0x000c0f14, 0x00090c11, 0x00070a0f, 0x00080b10, 0x00080c10, 0x00080b0f, 0x00080b10, 0x000b0d12, 0x000c0f14, 0x000d1014, 0x000c1014, 0x000c1115, 0x000b1014, 0x00090d11, 0x00080c10, 0x00080c10, 0x00070c10, 0x00070c10, 0x00080d11, 0x000c1116, 0x0011151c, 0x0013181d, 0x00141920, 0x00151b21, 0x00161c22, 0x0011161c, 0x0011151c, 0x00161a20, 0x00171c22, 0x00181c23, 0x00191f27, 0x00192028, 0x001c232a, 0x001e252c, 0x001d262e, 0x001d252e, 0x001e262f, 0x00212932, 0x00242c35, 0x00222b34, 0x00202831, 0x00222c35, 0x00243039, 0x00233039, 0x00222f38, 0x00232e38, 0x00242e3a, 0x00242d3a, 0x00202935, 0x00202834, 0x0025303b, 0x00212c36, 0x001c2731, 0x001d2934, 0x00222e38, 0x0026313c, 0x0023303a, 0x001c2a34, 0x001e2c37, 0x00202e3c, 0x00293948, 0x002b3e4c, 0x00293f4c, 0x002b4250, 0x002e4754, 0x00304854, 0x00314856, 0x00344958, 0x00344b59, 0x00324857, 0x00334754, 0x00344552, 0x00303f4c, 0x002c3845, 0x002d3844, 0x002d3844, 0x002c3844, 0x002d3844, 0x00313c4a, 0x0034404d, 0x00343f4a, 0x0028313c, 0x00141f28, 0x00101c26, 0x001a2731, 0x00202e39, 0x001f2c37, 0x00182029, 0x000b1018, 0x00070a10, 0x000b1017, 0x00151f28, 0x0023313c, 0x002c404d, 0x00344958, 0x003a5063, 0x0040586d, 0x00425e74, 0x00486880, 0x005a8397, 0x008cb0bc, 0x00b1c8cb, 0x00c1cccc, 0x00c9cccc, 0x00cccbcc, 0x00cccbcc, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbca, 0x00cbccc9, 0x00cbccca, 0x00c9ccca, 0x00becccb, 0x008aa3ad, 0x00283d4c, 0x00111e2a, 0x00091018, 0x0004090e, 0x00020508, 0x00020404, 0x00000304, 0x00010304, 0x00010304, 0x00010305, 0x00010306, 0x00010307, 0x00010306, 0x00020407, 0x0003060b, 0x00060d14, 0x000c161d, 0x00121e28, 0x0014222f, 0x00142431, 0x00142431, 0x00142431, 0x00142532, 0x00132532, 0x00142532, 0x00142530, 0x00142530, 0x00142530, 0x00142530, 0x00142430, 0x00142430, 0x00142430, 0x00142430, 0x00142430, 0x00142430, 0x00142330, 0x00142330, 0x00142330, 0x00142330, 0x00142330, 0x0014232e, 0x0014232e, 0x00142430, 0x00142431, 0x00142431, 0x00142430, 0x0014242f, 0x0013242f, 0x0012242e, 0x0012242f, 0x00132430, 0x00142431, 0x00132431, 0x00132431, 0x00132431, 0x000d1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001d4a4d, 0x001f5053, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297b8b, 0x0028686a, 0x00286a6c, 0x00296c6f, 0x002b6f70, 0x002b7072, 0x003292a8, 0x0037a9ca, 0x002f828e, 0x002c7475, 0x00318b9c, 0x0037a9cb, 0x002c7c86, 0x002b7071, 0x002a6d6f, 0x00296b6d, 0x0028686b, 0x00276668, 0x003098b8, 0x002e96b6, 0x00245d60, 0x0022585b, 0x00205457, 0x001f5154, 0x001d4d50, 0x001c4a4d, 0x001b4649, 0x001a4245, 0x00183f43, 0x00183c40, 0x0017383c, 0x0016363b, 0x00153338, 0x00142e34, 0x00132c32, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x00102229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00111d25, 0x00111d25, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101d24, 0x00101d25, 0x00101d25, 0x00101e28, 0x00101e28, 0x00101c28, 0x00111c28, 0x00111c28, 0x00121e28, 0x00121e28, 0x00121e28, 0x00111e28, 0x00111e28, 0x00121f29, 0x00121f29, 0x00121f2a, 0x0012202c, 0x0011202c, 0x00121f2b, 0x00101c27, 0x000d161d, 0x00090f15, 0x00070a10, 0x0005070b, 0x00040509, 0x00030408, 0x00020405, 0x00000206, 0x00000206, 0x00000206, 0x00000205, 0x00000204, 0x00000204, 0x00000304, 0x00000304, 0x00000404, 0x00000607, 0x0003080b, 0x00080e12, 0x000f181e, 0x0016242e, 0x002d4e58, 0x0084afb4, 0x00bccccc, 0x00cbcccc, 0x00cbcccb, 0x00cacccb, 0x00cacccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccc9, 0x00cbccc9, 0x00cccccb, 0x00cccccc, 0x00c8cccc, 0x00bdcbcc, 0x00a0b9c3, 0x006f90a2, 0x004c6c81, 0x003f596e, 0x003a5062, 0x00344557, 0x002c3d4d, 0x00263544, 0x00202d3c, 0x00192633, 0x0016202b, 0x00141b23, 0x000f141a, 0x00090d12, 0x0006090d, 0x0006080c, 0x000b0d13, 0x0013181e, 0x00181f26, 0x00171f26, 0x00151d24, 0x00121b22, 0x000c151c, 0x00081018, 0x00101a25, 0x0026333f, 0x0031414f, 0x00334453, 0x002f4150, 0x002b3d4c, 0x00293c49, 0x00273847, 0x00253544, 0x0020313e, 0x001e2e3a, 0x0022313c, 0x00212f39, 0x001e2c36, 0x001d2a36, 0x0023303d, 0x0025323e, 0x0024313d, 0x002a3843, 0x00283641, 0x0021303b, 0x001b2a34, 0x0022313a, 0x0024343d, 0x00202e38, 0x001c2833, 0x001f2a34, 0x00202c36, 0x00242f39, 0x00202b35, 0x001d2830, 0x00202830, 0x001e272e, 0x001b232a, 0x001b2229, 0x001a1f27, 0x00181f25, 0x00181e24, 0x00161b21, 0x00171c22, 0x00171b20, 0x00171c20, 0x00161b20, 0x00151a1e, 0x0016191e, 0x000e1116, 0x000d1017, 0x00101319, 0x00111419, 0x000d1015, 0x000d1015, 0x000c1014, 0x00080c10, 0x00070a0f, 0x00090c11, 0x00090c10, 0x00080b10, 0x00080c10, 0x000c0f14, 0x00090c11, 0x00090c13, 0x000a0f14, 0x000c1015, 0x000c1014, 0x00090e12, 0x000a0f15, 0x000b1015, 0x000c1418, 0x000c1317, 0x000c1317, 0x0013191e, 0x00151a20, 0x0013181d, 0x0011171c, 0x0014191f, 0x00141920, 0x000f141a, 0x000e1318, 0x0014181f, 0x00171c22, 0x00161b22, 0x00191f27, 0x001a2129, 0x001b242b, 0x001e272e, 0x001d2730, 0x001c272f, 0x001e2830, 0x00202b33, 0x00202b34, 0x001c262f, 0x001a242d, 0x00202c34, 0x00212d35, 0x001f2c34, 0x00202d36, 0x00232f38, 0x0025303b, 0x0024303a, 0x00212c37, 0x001f2a34, 0x0028333d, 0x0026333c, 0x00202d37, 0x00212f38, 0x0025323c, 0x0028343d, 0x0024313b, 0x001d2b34, 0x00202d39, 0x00212f3c, 0x00283846, 0x002c3e4c, 0x002a404c, 0x002c424f, 0x00314956, 0x00304854, 0x00314754, 0x00324754, 0x00344754, 0x00334654, 0x00344451, 0x0032404c, 0x002e3a46, 0x002c3642, 0x002c3742, 0x002c3743, 0x002c3844, 0x002e3946, 0x00333f4c, 0x00343f4d, 0x002f3844, 0x001c2630, 0x00101922, 0x00141f28, 0x001c2834, 0x00212d39, 0x001f2a36, 0x00151e28, 0x00090e16, 0x00070910, 0x000b0f16, 0x00141d26, 0x00202e38, 0x002a3d49, 0x00304755, 0x00374e5f, 0x003c5469, 0x003f596f, 0x00426075, 0x00486b80, 0x00688da2, 0x0094b8c4, 0x00b4cbcc, 0x00c4cccc, 0x00cbcccc, 0x00cccbcc, 0x00cccbcb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbca, 0x00cbccc9, 0x00caccca, 0x00c8ccc9, 0x00bdcbcb, 0x00859ca8, 0x00243847, 0x00101c28, 0x00091018, 0x0004090d, 0x00020508, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010408, 0x0003070c, 0x00080c12, 0x000d151d, 0x00141e2a, 0x00152330, 0x00162431, 0x00142431, 0x00142431, 0x00142532, 0x00142532, 0x00142530, 0x00142530, 0x00142530, 0x00142430, 0x0014242f, 0x0014242f, 0x0014242e, 0x0014232e, 0x0013222d, 0x0013222d, 0x0013222e, 0x0013222e, 0x0013222d, 0x0012212d, 0x0012212d, 0x0012212c, 0x0012212c, 0x0012222e, 0x0011232f, 0x0011232f, 0x0012232e, 0x0012232d, 0x0011232d, 0x0011232d, 0x0011232e, 0x00122430, 0x00122430, 0x00122430, 0x00112430, 0x00112430, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001c4448, 0x001d4a4d, 0x001f5053, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297b8b, 0x00286769, 0x00286a6c, 0x00296c6f, 0x002a6e70, 0x002b7072, 0x003192a8, 0x0037a9ca, 0x002f828e, 0x002c7475, 0x00308a9c, 0x0037a9cb, 0x002d7c86, 0x002b6f70, 0x00296c6f, 0x00296b6d, 0x0028686a, 0x00276769, 0x003098b8, 0x002f97b6, 0x00245e60, 0x0022595c, 0x00215659, 0x00205356, 0x001f5053, 0x001d4c50, 0x001d4a4d, 0x001b4649, 0x001a4245, 0x00194044, 0x00183c40, 0x00183a3e, 0x0015363b, 0x00143338, 0x00143036, 0x00132c32, 0x00102a30, 0x0012282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f1b24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101c24, 0x000f1b24, 0x000e1a23, 0x000e1a22, 0x000e1a22, 0x000e1a22, 0x000e1a22, 0x000e1b23, 0x000e1b23, 0x000e1b23, 0x000f1c25, 0x000f1c25, 0x00101c26, 0x00101c26, 0x00101c27, 0x00111d27, 0x00111d27, 0x00121e28, 0x00111e28, 0x00121e29, 0x00131f2a, 0x0013202a, 0x0013202b, 0x0012212c, 0x0012202c, 0x00111d29, 0x000d1721, 0x00081016, 0x00070b10, 0x0005080c, 0x00040508, 0x00030408, 0x00020307, 0x00010205, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000304, 0x00000304, 0x00000404, 0x00000607, 0x0003080a, 0x00080e12, 0x000f181e, 0x0016242e, 0x002d4e58, 0x0084afb4, 0x00bccccc, 0x00cbcccc, 0x00cbccca, 0x00cacccb, 0x00cacccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00caccc9, 0x00cbccca, 0x00cbcccc, 0x00cacccc, 0x00c1cbcc, 0x00a7bec8, 0x007796aa, 0x00507087, 0x00425f74, 0x003b5367, 0x0035495c, 0x002f4151, 0x00283a4a, 0x00243342, 0x001d2a39, 0x00192531, 0x0016202b, 0x00131a23, 0x000d1219, 0x00080c11, 0x0005080c, 0x0005080b, 0x00090c10, 0x0012171d, 0x00171d24, 0x00161e25, 0x00151d24, 0x00141c23, 0x000e161d, 0x00071018, 0x000e1822, 0x0023303b, 0x002e3e4b, 0x00314350, 0x002e414f, 0x002a3d4b, 0x00293c4a, 0x00283b49, 0x00283a48, 0x00223340, 0x0020303d, 0x00263540, 0x0023303c, 0x001f2c38, 0x0021303c, 0x0024323f, 0x00263440, 0x0024323e, 0x00273440, 0x002b3844, 0x0023313c, 0x0021303a, 0x0022313b, 0x0022313a, 0x001d2c35, 0x00202c37, 0x0024313b, 0x00232f38, 0x00232e38, 0x001f2a34, 0x00202a34, 0x001e2730, 0x001c252c, 0x001b232a, 0x001b2129, 0x00191e26, 0x00182028, 0x00192026, 0x00161c22, 0x00151b21, 0x00141a1f, 0x00141a1e, 0x00151a1f, 0x0014191d, 0x0015181d, 0x000d1015, 0x000d1017, 0x0011141b, 0x0013161c, 0x000e1116, 0x000d1015, 0x000c1014, 0x00080c10, 0x00080b0f, 0x000c0f14, 0x000d1014, 0x000c1014, 0x000c0f14, 0x000b0e12, 0x000a0d12, 0x000a0d14, 0x000a0e13, 0x000b1014, 0x000a0f14, 0x00090e12, 0x000c1016, 0x000d1418, 0x000c1417, 0x000a1014, 0x00080f13, 0x000f151b, 0x000f141a, 0x0010151b, 0x00141920, 0x0012171d, 0x0012171d, 0x0010151c, 0x0013181e, 0x00181c23, 0x00181c23, 0x00171c22, 0x00181d25, 0x00182027, 0x00192229, 0x001d272d, 0x001e2830, 0x00202b34, 0x00202b33, 0x001f2931, 0x001c2730, 0x001a242d, 0x0018232c, 0x001c262f, 0x001f2b33, 0x001f2c34, 0x00202e37, 0x0024303b, 0x0025313c, 0x00232f38, 0x00222e38, 0x00212c38, 0x0026323d, 0x0027343e, 0x0024333c, 0x0026343e, 0x0028343e, 0x0026333c, 0x0023303a, 0x001d2c35, 0x00202d38, 0x00202f3d, 0x00243444, 0x00283c49, 0x002c414f, 0x002e4452, 0x00324a57, 0x00304754, 0x00304653, 0x00304350, 0x002f404f, 0x002e3f4d, 0x002f3c4a, 0x002f3c48, 0x002e3944, 0x002c3641, 0x002e3742, 0x002d3743, 0x002d3844, 0x00303c48, 0x0034404c, 0x00343f4b, 0x0028323d, 0x00141e28, 0x000e1821, 0x0016202a, 0x001c2833, 0x001f2b37, 0x001c2834, 0x00121b24, 0x00070d15, 0x00070a11, 0x00090d16, 0x00131c25, 0x001f2c38, 0x00293c48, 0x002f4453, 0x00344b5c, 0x003a5266, 0x003c576b, 0x00405b70, 0x00436176, 0x00507488, 0x00739aad, 0x009ec0c8, 0x00bacccc, 0x00c7cccc, 0x00cbcccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccc9, 0x00caccca, 0x00c8ccc9, 0x00bccacb, 0x007d95a3, 0x00203442, 0x00101b26, 0x00091017, 0x0004090c, 0x00030508, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010407, 0x0002050a, 0x0004080c, 0x00080d15, 0x000f1823, 0x0014212e, 0x00152330, 0x00142431, 0x00142431, 0x00142532, 0x00142532, 0x00142530, 0x00142530, 0x0014242f, 0x0014242f, 0x0013242f, 0x0014232e, 0x0014232e, 0x0013222d, 0x0013222d, 0x0013222d, 0x0012212c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011202b, 0x0011202b, 0x0010202c, 0x0010202c, 0x0010212d, 0x0012212d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222e, 0x0012232f, 0x00122430, 0x00112430, 0x00112430, 0x00112430, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001c4448, 0x001d4a4d, 0x001f5053, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297b8b, 0x00286769, 0x00286a6c, 0x00296c6f, 0x002a6e70, 0x002c7071, 0x003192a8, 0x0037a9ca, 0x002f828d, 0x002c7374, 0x00308a9c, 0x0037a9cb, 0x002d7b85, 0x002a6e70, 0x00296c6f, 0x00286a6c, 0x0028686a, 0x00276769, 0x003098b8, 0x002f97b6, 0x00245f61, 0x00235a5c, 0x0022585b, 0x00205558, 0x00205254, 0x001f5053, 0x001d4c50, 0x001d4a4d, 0x001c4649, 0x001a4347, 0x00194044, 0x00183d41, 0x00183a3e, 0x0016363b, 0x00143338, 0x00143036, 0x00132c32, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00122229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1820, 0x000d1921, 0x000d1922, 0x000e1a22, 0x000f1a22, 0x000d1921, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c181f, 0x000c1920, 0x000c1a22, 0x000e1c24, 0x000f1b24, 0x00101b25, 0x00101b25, 0x00101c26, 0x00111d27, 0x00111e28, 0x00111f2b, 0x00111f2b, 0x0013202c, 0x0014202c, 0x0013212c, 0x0012212c, 0x00121f2b, 0x00101a25, 0x000b111c, 0x00060b12, 0x0004080c, 0x00030509, 0x00030408, 0x00030408, 0x00020307, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010404, 0x00000607, 0x0003080a, 0x00080e12, 0x000f181e, 0x0016242f, 0x002d4c57, 0x0084adb2, 0x00bdcccc, 0x00cacbcc, 0x00caccca, 0x00c9cccb, 0x00cacccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccc9, 0x00cbcccb, 0x00c9cccc, 0x00c4cccc, 0x00adc3c9, 0x0080a0b3, 0x0054788e, 0x00436278, 0x003c576d, 0x00364d60, 0x00314657, 0x002c3e4d, 0x00263848, 0x00233140, 0x001d2a38, 0x00192431, 0x00151f2a, 0x00121924, 0x000d121a, 0x00080c11, 0x0005080c, 0x0004070a, 0x00080b10, 0x0010151b, 0x00151c23, 0x00151d24, 0x00151d24, 0x00141c23, 0x000e171d, 0x00081018, 0x000f1922, 0x001c2834, 0x00273643, 0x002e404d, 0x002e404e, 0x002c3f4d, 0x00293c4b, 0x002a3c4b, 0x002a3c4b, 0x00243544, 0x00233442, 0x00283944, 0x00243340, 0x0021303e, 0x00253442, 0x00253441, 0x0024333e, 0x0023313d, 0x00253440, 0x002a3844, 0x00283742, 0x0024343d, 0x0022313b, 0x001e2d37, 0x00182831, 0x001c2934, 0x0023303a, 0x00222f38, 0x00222e38, 0x00202c36, 0x00222d38, 0x001c262f, 0x001a242c, 0x001a222a, 0x00192129, 0x00171f28, 0x00172028, 0x00182026, 0x00172024, 0x00161d23, 0x0013191d, 0x0011171b, 0x0010151a, 0x0014181c, 0x0014181c, 0x000d1015, 0x000e1118, 0x0014171d, 0x00111419, 0x000c1014, 0x000d1015, 0x000f1217, 0x000b0f14, 0x00080b10, 0x000f1218, 0x00101318, 0x000a0d11, 0x00080c10, 0x000c0f13, 0x000d1017, 0x000c0f16, 0x000a0e13, 0x00090e12, 0x00080c10, 0x00070c10, 0x00090f14, 0x0010161b, 0x000f1519, 0x000b1216, 0x000a1015, 0x000f141a, 0x000e1419, 0x0013181e, 0x00161b21, 0x0010141a, 0x000e1319, 0x0010151c, 0x00161b21, 0x00181d24, 0x00171c22, 0x00151a20, 0x00151c22, 0x00171e24, 0x00172027, 0x001b232a, 0x001d272f, 0x00202932, 0x00202a33, 0x00202a33, 0x001f2931, 0x001c2730, 0x001b252e, 0x001a242d, 0x001d2830, 0x00202c34, 0x00212f38, 0x0024323c, 0x0024313b, 0x00212f38, 0x0023303a, 0x0027343f, 0x00273440, 0x00283642, 0x00273641, 0x00283742, 0x00293843, 0x0025333e, 0x0023323c, 0x00203039, 0x001e2d38, 0x0020303e, 0x00253745, 0x00273a48, 0x002c4150, 0x00304754, 0x00324856, 0x00304553, 0x002f4350, 0x002f404e, 0x002c3c4a, 0x002b3948, 0x002c3946, 0x002d3844, 0x002d3742, 0x002e3641, 0x002f3741, 0x002f3742, 0x002e3844, 0x00323c48, 0x0034404c, 0x00333e4a, 0x00202a35, 0x000e1823, 0x00101b24, 0x0017222c, 0x001c2831, 0x001d2a34, 0x001b2630, 0x00111922, 0x00070c14, 0x00060a11, 0x00080d15, 0x00101a24, 0x001d2b36, 0x00263845, 0x002d4150, 0x00324858, 0x00384f62, 0x003b5466, 0x003d576a, 0x00405c70, 0x0044647c, 0x00547a92, 0x007ca3b7, 0x00a8c6ca, 0x00becccc, 0x00c8cccc, 0x00cbcccb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccca, 0x00cacccb, 0x00c8cccb, 0x00b8c9cb, 0x00748d9a, 0x001c303c, 0x00101a24, 0x00080f15, 0x0004080b, 0x00040507, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000306, 0x00010408, 0x0003060b, 0x00040910, 0x000b101c, 0x00101c2a, 0x0014222f, 0x00142431, 0x00142431, 0x00142532, 0x00142531, 0x00142530, 0x0014242f, 0x0014242f, 0x0014242f, 0x0012232e, 0x0013222d, 0x0012212c, 0x0011202c, 0x0011202c, 0x0011202c, 0x0011202c, 0x0012212c, 0x0011202c, 0x0011202c, 0x0011202c, 0x00102029, 0x00102029, 0x00102029, 0x0010202b, 0x0010202b, 0x0010202b, 0x0011202c, 0x0012212c, 0x0013222d, 0x0012212d, 0x0013222e, 0x0013222e, 0x0012232e, 0x0011232f, 0x0011232f, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001c4448, 0x001d4a4d, 0x001f5053, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297b8b, 0x00286769, 0x00286a6c, 0x00296c6f, 0x002a6e70, 0x002c7071, 0x003192a8, 0x0037a9ca, 0x002e828d, 0x002c7374, 0x00308a9c, 0x0037a8cb, 0x002d7b85, 0x002a6e70, 0x00296c6e, 0x00286a6c, 0x0028686a, 0x00276769, 0x003098b8, 0x002f97b6, 0x00245f61, 0x00245c5f, 0x0022595c, 0x0021585a, 0x00205457, 0x00205254, 0x001f5053, 0x001d4c50, 0x001c4a4d, 0x001c474b, 0x001b4448, 0x001a4245, 0x00183d41, 0x00183a3e, 0x0016363b, 0x00143338, 0x00143036, 0x00132c32, 0x00112a30, 0x0013282e, 0x00102229, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b161e, 0x000b161e, 0x000b161e, 0x000c151e, 0x000c151e, 0x000b151e, 0x000a151e, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c181f, 0x000c181e, 0x000c181f, 0x000c1920, 0x000d1a23, 0x000f1b24, 0x00101b25, 0x00101b25, 0x00101c26, 0x00111d27, 0x00101e28, 0x00111f2b, 0x00121f2b, 0x0013202c, 0x0013202c, 0x0013202c, 0x0012202b, 0x00101a25, 0x000b121c, 0x00080c15, 0x0004070e, 0x0004050b, 0x00030408, 0x00030408, 0x00030308, 0x00020306, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010404, 0x00000607, 0x0002080a, 0x00080e12, 0x000f171d, 0x0016242e, 0x002b4854, 0x0080a9b0, 0x00becccc, 0x00cbcbcc, 0x00caccca, 0x00c9cccb, 0x00cacccb, 0x00cbcccb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbca, 0x00cbcccc, 0x00c4cccc, 0x00b2c6cb, 0x0089a8b8, 0x005b7f94, 0x0046687e, 0x003d5b70, 0x00385065, 0x0032485b, 0x002e4353, 0x00293c4b, 0x00233443, 0x00202e3c, 0x001c2835, 0x0018232f, 0x00141d28, 0x00121923, 0x000d131b, 0x00090c12, 0x0006090d, 0x0004070a, 0x0007090e, 0x000c1218, 0x00131920, 0x00151c24, 0x00141c24, 0x00131b23, 0x000e171f, 0x00081119, 0x000c151f, 0x00131d28, 0x001f2c39, 0x002d3d4c, 0x00304150, 0x00304150, 0x002c3d4c, 0x002c3e4c, 0x002c3e4c, 0x00253846, 0x00273947, 0x002d3f4b, 0x00283846, 0x00253544, 0x00283846, 0x00263543, 0x0022313e, 0x0023323d, 0x00263640, 0x00273641, 0x00283742, 0x0024343e, 0x0024333d, 0x0020303a, 0x001c2b35, 0x00202e38, 0x0024313c, 0x00202c37, 0x00212d38, 0x00232f39, 0x00242f3a, 0x001c2630, 0x001a242d, 0x001c242d, 0x001b232c, 0x001a222b, 0x00152026, 0x00121b20, 0x00161f24, 0x00161e23, 0x0013191d, 0x0010171a, 0x000f1418, 0x0012171b, 0x0012171b, 0x000d1015, 0x0011151c, 0x00171a20, 0x0012161c, 0x000e1317, 0x000e1317, 0x000f1217, 0x000e1117, 0x000d1016, 0x0010141a, 0x00090d12, 0x0004070c, 0x0006090f, 0x000c0f14, 0x000e1117, 0x000c0f14, 0x000c1014, 0x000b1014, 0x00080d11, 0x00080c11, 0x000c1117, 0x0013191d, 0x00131a1e, 0x0010171b, 0x0012191e, 0x00141b21, 0x0011171e, 0x0010171d, 0x00161c22, 0x0010161c, 0x0010151c, 0x0010151c, 0x00151920, 0x00181c23, 0x00171c22, 0x00171c23, 0x00161c23, 0x00182026, 0x001a2229, 0x001b232a, 0x001f2730, 0x00212a34, 0x00202a33, 0x00212c35, 0x00212c35, 0x001f2932, 0x001c2730, 0x001a242d, 0x001c2730, 0x00202c34, 0x00212f38, 0x0024323c, 0x0022303b, 0x00202e38, 0x0023303c, 0x00293744, 0x00283543, 0x002c3a47, 0x002a3845, 0x00263441, 0x00263441, 0x0026343f, 0x0025343e, 0x0024343e, 0x001e2e39, 0x00223140, 0x00293a49, 0x00283c4b, 0x002c404f, 0x00304654, 0x00324754, 0x00304350, 0x002f404d, 0x002f3d4b, 0x002c3946, 0x002c3844, 0x002c3844, 0x002d3843, 0x002f3742, 0x00303742, 0x00303740, 0x00303742, 0x00303845, 0x00343d4a, 0x0034404c, 0x002d3844, 0x0019222d, 0x000d1722, 0x00131c28, 0x0019242e, 0x001c2830, 0x001c2830, 0x001a232c, 0x0010171e, 0x00080c12, 0x00050910, 0x00080d15, 0x00101a24, 0x001d2a35, 0x00253644, 0x002c3f4f, 0x00304657, 0x00344c5f, 0x00385063, 0x003a5467, 0x003d576b, 0x00405c73, 0x00466882, 0x00598299, 0x0088afbe, 0x00b0c8cc, 0x00c1cccc, 0x00c9cccc, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcccc, 0x00c9cccc, 0x00c8cccc, 0x00c4cccc, 0x00b4c7ca, 0x006c8592, 0x00192c39, 0x000e1822, 0x00080d13, 0x0002070a, 0x00040507, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000305, 0x00010408, 0x00020509, 0x0003070b, 0x00060a13, 0x00081420, 0x000d1c28, 0x0013212f, 0x00142431, 0x00142431, 0x00142431, 0x0014242f, 0x0014242f, 0x0014242f, 0x0012242e, 0x0012232d, 0x0012212c, 0x0010202b, 0x0010202b, 0x000f1f29, 0x00101f2a, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x00101f2a, 0x000e1e28, 0x000e1e27, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000f1e29, 0x00101f2a, 0x0010202b, 0x0012212c, 0x0012212c, 0x0011212d, 0x0010222e, 0x0011222e, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183f43, 0x001c4448, 0x001d4a4d, 0x001f5053, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297b8b, 0x00286769, 0x00286a6c, 0x00296c6f, 0x002a6e70, 0x002b7071, 0x003291a8, 0x0037a9ca, 0x002f818d, 0x002c7274, 0x00308a9c, 0x0037a8cb, 0x002d7b84, 0x002a6d6f, 0x002a6c6e, 0x0028696c, 0x0028686a, 0x00276769, 0x003098b8, 0x002f97b6, 0x00246062, 0x00245d60, 0x00245c5e, 0x0022585b, 0x00215659, 0x00205457, 0x00205254, 0x001f5053, 0x001d4d50, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x001a4245, 0x00183d41, 0x00183a3e, 0x0016363b, 0x00153338, 0x00142e34, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c141b, 0x000c141b, 0x000c141b, 0x000b141b, 0x000a141b, 0x000a141b, 0x000a141c, 0x000b151c, 0x000b151d, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161d, 0x000c171f, 0x000d1720, 0x000e1820, 0x000e1921, 0x000f1a23, 0x000f1b24, 0x000e1c25, 0x000e1c26, 0x00101e27, 0x00101e29, 0x00111f2b, 0x0013202c, 0x0013202c, 0x00121f2b, 0x00131f29, 0x00101a24, 0x000b131b, 0x00080c14, 0x0004080e, 0x00020409, 0x00020408, 0x00020408, 0x00020306, 0x00020306, 0x00000205, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00010406, 0x00030609, 0x00080c10, 0x0010151c, 0x0015212b, 0x00294550, 0x007da6ad, 0x00bccccc, 0x00c9cccb, 0x00c8ccc9, 0x00cacccb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbca, 0x00c9ccca, 0x00c4cccc, 0x00b3c8cb, 0x008dadbe, 0x00608499, 0x00486a7f, 0x00415d72, 0x003c5468, 0x00354c60, 0x00304557, 0x002c404f, 0x00273948, 0x00213340, 0x001d2c39, 0x001a2734, 0x0017202c, 0x00141c26, 0x00111821, 0x000d131c, 0x00090c14, 0x0005090d, 0x00030509, 0x0004060b, 0x000a0f15, 0x0010171d, 0x00131b24, 0x00131c24, 0x00121b24, 0x000c1720, 0x0008111a, 0x00071019, 0x0006101b, 0x00192531, 0x0031404d, 0x00364554, 0x00324350, 0x002d3e4b, 0x002e3f4b, 0x002c3e4a, 0x00273945, 0x00283b48, 0x002c404c, 0x002a3d4b, 0x00293c4a, 0x00293c4a, 0x00263745, 0x00213240, 0x00243440, 0x00283845, 0x00263643, 0x00243440, 0x00243440, 0x00243441, 0x00233340, 0x0020303c, 0x00283742, 0x0025333e, 0x00222f3a, 0x0026323d, 0x00232f39, 0x001f2b35, 0x001a2530, 0x001a2430, 0x001c2630, 0x0019232c, 0x00182029, 0x00141c24, 0x00121a21, 0x00181f27, 0x00181e25, 0x00141a20, 0x0010151a, 0x000d1218, 0x0010141a, 0x0012171c, 0x0010141b, 0x0013171d, 0x00141920, 0x0013181e, 0x0010151c, 0x0010161b, 0x000f1418, 0x000c1115, 0x0011161a, 0x0012171b, 0x000b0e13, 0x0005090e, 0x00080c11, 0x000d1015, 0x000c0f14, 0x00080c10, 0x000d1015, 0x000d1015, 0x000a0d12, 0x000c0f14, 0x0011141b, 0x00161b20, 0x00141a20, 0x0012181d, 0x00121a20, 0x00182028, 0x00171f28, 0x00141d26, 0x00182029, 0x00121922, 0x00101620, 0x00131820, 0x00141b21, 0x00171c23, 0x00161c24, 0x00192028, 0x00182028, 0x00182029, 0x001c252d, 0x001e2730, 0x00212c36, 0x00212b36, 0x001d2933, 0x00202c36, 0x00202c36, 0x001f2a34, 0x00202c34, 0x001b2730, 0x001c2831, 0x001f2c35, 0x0022303a, 0x00283541, 0x00243440, 0x0021313d, 0x0022313e, 0x00273744, 0x00263643, 0x002c3c48, 0x002d3c48, 0x00263542, 0x0023323f, 0x00243440, 0x00243542, 0x00243440, 0x0020303d, 0x00243544, 0x00293a48, 0x00293c4a, 0x002c3f4d, 0x002f4450, 0x00314450, 0x0030414e, 0x0030404c, 0x00303d48, 0x002e3b46, 0x002f3944, 0x002f3844, 0x002f3844, 0x00303844, 0x002f3642, 0x00303641, 0x00303744, 0x00313946, 0x00353d4a, 0x00353d4b, 0x00262e3c, 0x00131b28, 0x000d1824, 0x0014202a, 0x00192530, 0x001b2630, 0x001b242e, 0x00182028, 0x0010141c, 0x00070a10, 0x0005070f, 0x00090d14, 0x00131c24, 0x001f2c35, 0x00243642, 0x002a3f4c, 0x002e4454, 0x0033495a, 0x00374d5f, 0x00395062, 0x003a5265, 0x003d566c, 0x00425f77, 0x00496d86, 0x00658ca2, 0x0093b5c2, 0x00b2c9cc, 0x00c0cccc, 0x00c5cccb, 0x00caccca, 0x00cbccc9, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcccc, 0x00c9cccc, 0x00c8cccc, 0x00c4cccc, 0x00becccc, 0x00aac4c8, 0x00607a87, 0x00182936, 0x000e1720, 0x00080c13, 0x0002070a, 0x00030406, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020405, 0x00020407, 0x00020407, 0x00030408, 0x0004060c, 0x00030b15, 0x00091420, 0x00101d2a, 0x00152330, 0x00142431, 0x00142431, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0011222c, 0x0011202c, 0x0010202c, 0x0010202b, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x00101e29, 0x00101e28, 0x00101d28, 0x000f1d28, 0x000f1c26, 0x000e1c25, 0x000e1c26, 0x000e1c26, 0x000e1c26, 0x000e1c26, 0x000f1c26, 0x000f1c27, 0x000f1c26, 0x00101d27, 0x00101e28, 0x00101e28, 0x00101f29, 0x0010202a, 0x0010202b, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x0016383c, 0x00183f43, 0x001c4448, 0x001d4a4d, 0x001f5053, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297b8b, 0x00286769, 0x00286a6c, 0x00296c6f, 0x002a6e70, 0x002b7071, 0x003291a8, 0x0037a9ca, 0x002e808c, 0x002c7274, 0x0030899c, 0x0036a8cb, 0x002c7b84, 0x00296d6f, 0x00296b6d, 0x0028696c, 0x00286769, 0x00266668, 0x003098b8, 0x003097b7, 0x00256063, 0x00245e60, 0x00245c5f, 0x00235a5c, 0x0022585b, 0x0022585a, 0x00205558, 0x00205356, 0x001f5154, 0x001d4d50, 0x001d4b4e, 0x001c484c, 0x001b4448, 0x001a4245, 0x00183d41, 0x00183a3e, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0013282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1119, 0x000b1119, 0x000b1219, 0x000b131a, 0x0009141a, 0x0009141a, 0x000a141b, 0x000b151c, 0x000b151d, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161d, 0x000c161f, 0x000d1720, 0x000e1820, 0x000f1921, 0x000f1a23, 0x000f1c24, 0x000d1c25, 0x000d1d26, 0x000e1e28, 0x000e1f29, 0x0010202b, 0x0012202c, 0x00121f2c, 0x00121e29, 0x00101a24, 0x000b141c, 0x00070e14, 0x0004080e, 0x00020509, 0x00020308, 0x00020308, 0x00020307, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00010406, 0x00020508, 0x00080b10, 0x000f131a, 0x00141f2a, 0x0027404d, 0x0078a1a9, 0x00bccccc, 0x00c8cccb, 0x00c7ccca, 0x00cacccb, 0x00cbcbcb, 0x00cccbcb, 0x00cccccc, 0x00cbcccc, 0x00c5cccc, 0x00bbcbcc, 0x0094b4c3, 0x00668ca2, 0x004d7086, 0x00436074, 0x003f566b, 0x00394e63, 0x0034485c, 0x002e4252, 0x00293c4b, 0x00263845, 0x0020313e, 0x001c2b38, 0x001a2733, 0x0017202c, 0x00131c25, 0x00111821, 0x000d131c, 0x000a0d14, 0x0006090e, 0x00030508, 0x0003040a, 0x00070c12, 0x000e141c, 0x00111a23, 0x00131c24, 0x00111b24, 0x000d1720, 0x0009131c, 0x00050d17, 0x00030c14, 0x0018232d, 0x0031404b, 0x00384754, 0x00344450, 0x002f3f4c, 0x0030404c, 0x002e404a, 0x00293b46, 0x002a3d49, 0x002a404b, 0x002b404d, 0x002e4250, 0x002c404e, 0x00273947, 0x00233441, 0x00253844, 0x00283b47, 0x00273845, 0x00253844, 0x00243743, 0x00243643, 0x00223340, 0x001f303c, 0x00293842, 0x0024303b, 0x00222e38, 0x0024303b, 0x00222e38, 0x001d2934, 0x00192530, 0x001b2430, 0x001c2630, 0x0019232c, 0x00161e28, 0x00141c24, 0x00171e26, 0x001a2028, 0x00171d24, 0x00161b21, 0x0014191e, 0x0011171b, 0x0010151b, 0x0012171d, 0x0010141c, 0x000d1219, 0x000d1119, 0x000c1018, 0x000f141b, 0x0010141a, 0x000f1318, 0x000d1215, 0x00101418, 0x00111519, 0x00111418, 0x000d1015, 0x000c1014, 0x000e1116, 0x000c0f14, 0x00070a0f, 0x000d1015, 0x000e1116, 0x000c0f14, 0x000e1117, 0x000e1118, 0x0010141c, 0x0014181f, 0x0013191f, 0x0010171d, 0x000d161e, 0x00101922, 0x0018232c, 0x001a242c, 0x00151e27, 0x00101821, 0x00141a23, 0x00151c22, 0x00192026, 0x001c2229, 0x001d242c, 0x001e252f, 0x001f2831, 0x00202b34, 0x001e2831, 0x00242e3a, 0x00242e39, 0x001d2933, 0x00202d37, 0x00202d37, 0x001e2a34, 0x00212d37, 0x00202c36, 0x00212e38, 0x00212e38, 0x0022303b, 0x002b3947, 0x00283744, 0x00233440, 0x0020303d, 0x00263743, 0x00283845, 0x00253642, 0x00293845, 0x00283844, 0x0023323f, 0x00263542, 0x00263744, 0x00243642, 0x00233441, 0x00263745, 0x00283847, 0x00293c4a, 0x002c414e, 0x00304450, 0x0030424e, 0x0030414e, 0x0032404c, 0x00313d48, 0x00303b44, 0x00303a44, 0x00303946, 0x00303a46, 0x00303844, 0x002e3541, 0x00303541, 0x00303844, 0x00343c48, 0x00373e4b, 0x00303845, 0x001d2532, 0x000e1724, 0x000f1924, 0x0015212b, 0x00192530, 0x00192430, 0x001a242c, 0x00161d24, 0x000e1218, 0x00080910, 0x0006080f, 0x00090d14, 0x00141c24, 0x001e2b34, 0x00243541, 0x00293e4b, 0x002c4253, 0x00314658, 0x00344a5c, 0x00374d5e, 0x00384f61, 0x00395367, 0x003e5970, 0x00406078, 0x004c7188, 0x006d94a7, 0x0097b8c4, 0x00b2c8cc, 0x00bdcccc, 0x00c5cccb, 0x00c8ccca, 0x00c8cccc, 0x00c8cccc, 0x00c8cccc, 0x00c7cccc, 0x00c7cccc, 0x00c6cccc, 0x00c4cccc, 0x00c0cccc, 0x00b6cccc, 0x009cbcc4, 0x00506a77, 0x00142330, 0x000e141e, 0x00080b12, 0x0004060a, 0x00030405, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00020404, 0x00020405, 0x00020405, 0x00020405, 0x00020407, 0x00020408, 0x0003070d, 0x00050d16, 0x000c1723, 0x0014202c, 0x00162430, 0x00142430, 0x0012242e, 0x0012242e, 0x0012242e, 0x0011232d, 0x0011202c, 0x0011202c, 0x0011202c, 0x0010202b, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x00101d28, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000c1b24, 0x000c1b23, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000e1c24, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000f1c24, 0x000f1d26, 0x000e1e27, 0x000e1e27, 0x000f1f28, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x0016383c, 0x00183f43, 0x001c4448, 0x001d4a4d, 0x001e4f51, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297b8b, 0x00286769, 0x00286a6c, 0x00296c6f, 0x002a6e70, 0x002b7071, 0x003291a8, 0x0037a9ca, 0x002e808c, 0x002c7274, 0x002f899c, 0x0036a8cb, 0x002c7a84, 0x00296c6f, 0x00296b6d, 0x0028686b, 0x00286769, 0x00276668, 0x003098b8, 0x00309cbe, 0x00297c90, 0x00287c8f, 0x00287b8f, 0x00287a8f, 0x00287a8f, 0x00277a8f, 0x0026798f, 0x0026788f, 0x0025788e, 0x0024778e, 0x00237086, 0x001d4e54, 0x001c474b, 0x001b4448, 0x00194044, 0x00183c40, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1018, 0x000c1018, 0x000c1118, 0x000b131a, 0x0009141a, 0x0009141a, 0x000a141b, 0x000b151c, 0x000b151d, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161d, 0x000d1720, 0x000e1820, 0x000f1921, 0x00101a23, 0x00101b24, 0x00111c25, 0x00101c26, 0x00101d27, 0x00101f29, 0x0010202b, 0x0010202c, 0x0011202c, 0x0013202c, 0x00111c28, 0x000c151f, 0x00080e16, 0x00040a10, 0x0003060b, 0x00020408, 0x00020307, 0x00020407, 0x00020306, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00010406, 0x00020608, 0x00070a10, 0x000e121a, 0x00141d29, 0x00243d4c, 0x00709ca5, 0x00b6cccc, 0x00c5cccc, 0x00c7cccb, 0x00cacccb, 0x00cacccb, 0x00cbcccb, 0x00cccccc, 0x00c8cccc, 0x00bbcbcc, 0x00a0bbc5, 0x006f93a9, 0x0050748c, 0x00456479, 0x0040596e, 0x003c5165, 0x00364a5f, 0x00334658, 0x002d4050, 0x00293b49, 0x00253543, 0x00202f3c, 0x001c2935, 0x00192530, 0x0016202c, 0x00131b24, 0x00101720, 0x000d141c, 0x000a0d14, 0x00070a0e, 0x00040609, 0x0003050a, 0x00040a10, 0x000b1218, 0x00101820, 0x00121b24, 0x00121c24, 0x000f1820, 0x000c131c, 0x00091018, 0x00080f17, 0x0018212b, 0x002a3742, 0x0034424f, 0x0032404d, 0x00303d4b, 0x0032404d, 0x0032414e, 0x002b3c49, 0x002f4250, 0x002a3f4c, 0x002c414f, 0x00304452, 0x002f4451, 0x00263a48, 0x00213441, 0x00253844, 0x00283b47, 0x00283c48, 0x002b3e4a, 0x00283b48, 0x00273945, 0x00253743, 0x00233440, 0x00283843, 0x00222f39, 0x00202c36, 0x00202c36, 0x00202c37, 0x001e2935, 0x00192430, 0x001e2833, 0x001d2731, 0x0018212b, 0x00151f27, 0x00121c24, 0x00182028, 0x00192028, 0x00192027, 0x00181e25, 0x00141a1f, 0x0014191d, 0x0014191e, 0x0014181e, 0x000e121a, 0x000b1018, 0x000e131b, 0x000c1018, 0x000f141b, 0x000e1218, 0x000b0d14, 0x000b0e13, 0x000c0f14, 0x000b0e13, 0x0011141a, 0x0014171d, 0x00101319, 0x000d1017, 0x000c0e13, 0x00080b0f, 0x000b0e13, 0x000f1217, 0x000e1116, 0x000f1218, 0x000a0d14, 0x000c1017, 0x0010151c, 0x00141a20, 0x00161e24, 0x00141c24, 0x000f1821, 0x0019232c, 0x001b252e, 0x00172028, 0x00151c26, 0x00141b24, 0x0011181f, 0x00151c21, 0x001b2228, 0x001c232a, 0x001d262f, 0x00222e36, 0x00212d35, 0x0019262f, 0x00212d39, 0x0024303c, 0x001e2b34, 0x0023303a, 0x00223039, 0x001c2a34, 0x00202d37, 0x0024303a, 0x00293740, 0x0024333c, 0x0023313d, 0x002a3947, 0x00273744, 0x00243542, 0x0020313d, 0x00273844, 0x002b3c48, 0x001f303c, 0x0023323f, 0x00273642, 0x00243440, 0x00283744, 0x002b3c48, 0x00283b47, 0x00243744, 0x00243645, 0x00293b4a, 0x002d404e, 0x00304451, 0x00314451, 0x0030414e, 0x0030404d, 0x0032404c, 0x00313c47, 0x00303a44, 0x00313944, 0x00323a45, 0x00303945, 0x00303744, 0x002f3541, 0x00303642, 0x00323a46, 0x00363e4b, 0x00373f4c, 0x002a323f, 0x00141c29, 0x000d1523, 0x00121c27, 0x0016212c, 0x0018242d, 0x0018242e, 0x0018202a, 0x00141920, 0x000c0f16, 0x00080810, 0x0006080f, 0x00090d14, 0x00141c25, 0x001c2934, 0x00233540, 0x00283c4a, 0x002c4051, 0x00304457, 0x0034485b, 0x00364c5d, 0x00374d5f, 0x00385064, 0x003a5468, 0x003c586f, 0x00416178, 0x0053778d, 0x007095aa, 0x0091b5c2, 0x00a8c5cb, 0x00b4cacc, 0x00b6cbcc, 0x00b8cbcc, 0x00b8cbcc, 0x00b8cbcc, 0x00b8cbcc, 0x00b7cbcc, 0x00b7cccc, 0x00b5cccc, 0x00b2cccc, 0x00a9c8cc, 0x0089abb9, 0x003e5766, 0x00101d2a, 0x000b1019, 0x00080a10, 0x00040608, 0x00020405, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010404, 0x00020404, 0x00020404, 0x00020404, 0x00020404, 0x00020307, 0x00020308, 0x00030409, 0x0004080e, 0x00081018, 0x00101924, 0x0015202c, 0x0015242f, 0x0013232e, 0x0012242e, 0x0012242e, 0x0011232d, 0x0011212c, 0x0012212c, 0x0012212c, 0x0011202c, 0x0010202b, 0x0010202b, 0x00101f2a, 0x00101e28, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000c1a21, 0x000c1a21, 0x000c1921, 0x000c1923, 0x000b1823, 0x000c1923, 0x000e1923, 0x000e1a24, 0x000f1a24, 0x000f1a24, 0x000f1b23, 0x000e1b23, 0x000e1c24, 0x000f1c25, 0x00101d26, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x0016383c, 0x00183f43, 0x001c4448, 0x001c4a4d, 0x001f4f51, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297b8b, 0x00286769, 0x0028696c, 0x00296c6f, 0x002a6e70, 0x002c7071, 0x003291a8, 0x0037a8ca, 0x002e808c, 0x002b7173, 0x0030899c, 0x0036a8cb, 0x002c7984, 0x00296c6e, 0x00286a6c, 0x0028686b, 0x00276668, 0x00266568, 0x003097b7, 0x0032a5cb, 0x0030a4ca, 0x0030a4ca, 0x0030a4ca, 0x0030a4ca, 0x0030a4ca, 0x002fa4ca, 0x002fa4ca, 0x002ea3ca, 0x002da2ca, 0x002ca2ca, 0x002ca1ca, 0x00247993, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183d41, 0x00183a3e, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1018, 0x000c1018, 0x000c1018, 0x000b131a, 0x0009141a, 0x0009141a, 0x000a141b, 0x000b151c, 0x000b151d, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161d, 0x000d1720, 0x000f1921, 0x00101a23, 0x00101b24, 0x00111c24, 0x00121c25, 0x00101d28, 0x00111f28, 0x0012202a, 0x0011202c, 0x0010202c, 0x0011202c, 0x00111f2a, 0x000e1824, 0x0008101a, 0x00050b10, 0x0003070b, 0x00020508, 0x00030406, 0x00020405, 0x00020405, 0x00020404, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010405, 0x00020508, 0x00070a0f, 0x000c1119, 0x00121c28, 0x001f3846, 0x0065929d, 0x00adcacb, 0x00c1cccc, 0x00c7cccb, 0x00c9cccb, 0x00c9cccb, 0x00cbcccb, 0x00cbcccc, 0x00c4cccc, 0x00a4bfc8, 0x00789bae, 0x00537890, 0x0045667e, 0x00405c71, 0x003d5468, 0x00384c60, 0x0034475a, 0x00304153, 0x002a3c4c, 0x00273847, 0x00243341, 0x001f2c3b, 0x001c2834, 0x00182430, 0x00141f2a, 0x00111a24, 0x00101620, 0x000d141c, 0x000a0e15, 0x00080b0f, 0x0004060a, 0x0003040a, 0x0003080e, 0x00080f15, 0x000d151c, 0x00111920, 0x00131b23, 0x00101821, 0x000c141d, 0x000b1218, 0x000a1018, 0x00131b24, 0x001e2833, 0x002a3844, 0x002f3b48, 0x002f3b48, 0x00323e4c, 0x00323f4c, 0x002c3b48, 0x00324351, 0x002e414f, 0x002c4350, 0x00304653, 0x00304552, 0x00293d4b, 0x00203441, 0x00253844, 0x00283b47, 0x002a3d49, 0x002c3d4b, 0x00293c49, 0x00283c48, 0x00293a47, 0x00283a46, 0x00283843, 0x00212f39, 0x001f2b35, 0x00202c36, 0x00202d38, 0x001c2834, 0x00192430, 0x00222c37, 0x001c2731, 0x0016202a, 0x00141f28, 0x00141d25, 0x00182128, 0x00182028, 0x001a2229, 0x00181f26, 0x00141a20, 0x0013181e, 0x0011161c, 0x0011161d, 0x000f141c, 0x000b1018, 0x000e131b, 0x00090e16, 0x000b1017, 0x000f1319, 0x00090c13, 0x00080c10, 0x00080c10, 0x00080c10, 0x00080a11, 0x000a0c14, 0x000c1016, 0x000c0f15, 0x000a0d13, 0x000b0e13, 0x000c0f14, 0x000e1116, 0x000d1014, 0x000c0f14, 0x00080c12, 0x000b0f15, 0x000c1118, 0x0010171c, 0x00131b21, 0x00161e27, 0x00141f28, 0x0019242c, 0x001a242c, 0x00151e27, 0x00181f28, 0x00181e28, 0x0010161e, 0x0010171c, 0x00161c24, 0x00192028, 0x001a232c, 0x00212d35, 0x00202d35, 0x001b2830, 0x00202c38, 0x0025323d, 0x00202d37, 0x0024313b, 0x0027343e, 0x001f2c36, 0x00222f39, 0x0024343c, 0x002c3b44, 0x00273740, 0x00253641, 0x002b3c48, 0x00273844, 0x00273844, 0x00243441, 0x00283946, 0x002f404c, 0x00243440, 0x0022313c, 0x0024343f, 0x00253441, 0x00283844, 0x002c3e4a, 0x002b404b, 0x00283c49, 0x00273a49, 0x002d404f, 0x00314654, 0x00324754, 0x00314551, 0x002f3f4b, 0x002e3c48, 0x00303c48, 0x00303b45, 0x00313944, 0x00333944, 0x00323944, 0x00303843, 0x00303742, 0x00303641, 0x00303743, 0x00343b47, 0x0038404d, 0x00353c49, 0x00222a37, 0x000f1724, 0x00101824, 0x00141d28, 0x0015202b, 0x0016212c, 0x0017212c, 0x00181f28, 0x00141820, 0x000c0d14, 0x0007080f, 0x00060810, 0x00090d15, 0x00131c25, 0x001c2834, 0x00223440, 0x00273b48, 0x002a3e4f, 0x002e4254, 0x00324659, 0x00344a5c, 0x00364c5d, 0x00364d60, 0x00375064, 0x00385468, 0x003c5970, 0x0043637a, 0x0050748c, 0x00648da3, 0x007ba4b8, 0x0088b0c2, 0x008cb3c4, 0x008eb4c4, 0x008fb5c6, 0x0092b8c8, 0x0094b9c8, 0x0096bcca, 0x0098beca, 0x0098c0cb, 0x0098c0cb, 0x008db5c7, 0x006a8ca1, 0x00294152, 0x000c1824, 0x00080d14, 0x0006080d, 0x00040608, 0x00030405, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010304, 0x00020404, 0x00020404, 0x00020307, 0x00020308, 0x00020408, 0x00040509, 0x0005080f, 0x00090e17, 0x00101923, 0x0014202c, 0x0013232e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012232d, 0x0013222d, 0x0013222d, 0x0013222c, 0x0012212c, 0x0012212c, 0x0011202c, 0x0010202b, 0x00101f28, 0x000f1d27, 0x000f1c26, 0x000e1c24, 0x000c1a20, 0x000b1920, 0x000b1921, 0x000b1820, 0x000c1820, 0x000c1820, 0x000d1921, 0x000d1922, 0x000e1a22, 0x000d1920, 0x000c1920, 0x000c1a21, 0x000c1a21, 0x000d1c23, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183f43, 0x001b4448, 0x001c4a4d, 0x001e4f51, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297a8a, 0x00286769, 0x0028696c, 0x00296c6e, 0x00296d6f, 0x002b6f70, 0x003191a8, 0x0037a8ca, 0x002d808c, 0x002b7173, 0x0030899b, 0x0036a8cb, 0x002c7984, 0x002a6c6e, 0x0028696c, 0x0028686a, 0x00276568, 0x00276467, 0x00276d78, 0x0028707d, 0x0026707c, 0x00266e7b, 0x00256d79, 0x00266c78, 0x00266b77, 0x00246a76, 0x00246975, 0x00246873, 0x00236671, 0x00226470, 0x002a90b2, 0x002b99be, 0x001d4d51, 0x001c484c, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0013282e, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1018, 0x000c1018, 0x000c1018, 0x000b131a, 0x0009141a, 0x0009141b, 0x000a141c, 0x000b151c, 0x000b151d, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c171f, 0x000e1820, 0x00101a23, 0x00101b24, 0x00111c24, 0x00121c25, 0x00131d27, 0x00111f28, 0x0012202a, 0x0014212c, 0x0012212c, 0x0012212c, 0x00101f2a, 0x000e1924, 0x000a121c, 0x00060c14, 0x0004070c, 0x00030508, 0x00030405, 0x00030304, 0x00030404, 0x00020404, 0x00020404, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000405, 0x00020508, 0x0004080c, 0x00090e15, 0x000e1823, 0x0019303d, 0x005b808d, 0x00a8c5c8, 0x00bccccc, 0x00c4cccc, 0x00c8cccc, 0x00c8cccc, 0x00c8cccc, 0x00c5cccc, 0x00b5c5ca, 0x0082a4b7, 0x00587d94, 0x00486881, 0x00445f75, 0x003e556a, 0x00394f62, 0x0034485a, 0x00304354, 0x002c3e4e, 0x00293847, 0x00263544, 0x0023303f, 0x001f2b39, 0x001c2834, 0x0018232f, 0x00141e29, 0x00111923, 0x000f151f, 0x000d131b, 0x000b0e15, 0x00080c10, 0x0004070b, 0x0002040a, 0x0003070d, 0x00080c13, 0x000c131a, 0x0010181f, 0x00111921, 0x00101821, 0x000e141e, 0x000c1219, 0x00090f15, 0x00091018, 0x000f1721, 0x00232c39, 0x002d3744, 0x00303946, 0x00323c48, 0x00313c49, 0x002c3a46, 0x0030414f, 0x002e404e, 0x002c414f, 0x00304554, 0x00304654, 0x002c404f, 0x00253845, 0x00263946, 0x00283c48, 0x002b3d4a, 0x002b3d4c, 0x002d404d, 0x002e404e, 0x002c3d4b, 0x00283946, 0x00263541, 0x0023303a, 0x00202d37, 0x00222f39, 0x0022303a, 0x001b2733, 0x001d2934, 0x00242f39, 0x001e2832, 0x0019232c, 0x00162028, 0x00152028, 0x00172028, 0x00182028, 0x00172027, 0x00141b23, 0x00131920, 0x0011181e, 0x0010151c, 0x0012171f, 0x0010141c, 0x000a0f16, 0x000c1017, 0x000c1117, 0x000e1419, 0x0014181f, 0x000e1118, 0x000a0e13, 0x00080b10, 0x00080c10, 0x00080c12, 0x00080b12, 0x00080c13, 0x000c0e15, 0x000c0f15, 0x000d1117, 0x000d1016, 0x000c0f14, 0x00090d13, 0x00090c13, 0x00090c13, 0x00080d13, 0x000b1016, 0x000c1319, 0x0010181e, 0x00151e27, 0x00151f28, 0x00172129, 0x0019232c, 0x00151f28, 0x00171e27, 0x001a202a, 0x00141922, 0x0011181e, 0x00141b22, 0x00181f28, 0x001c232e, 0x00202a36, 0x00222d38, 0x0022303a, 0x0022303c, 0x0026343f, 0x0025333d, 0x0025333d, 0x002a3843, 0x0023303c, 0x0024323d, 0x00263641, 0x002c3c47, 0x00263742, 0x002c3c48, 0x002e3f4c, 0x002b3c48, 0x002a3b48, 0x00273845, 0x00283b47, 0x002d3f4c, 0x00283844, 0x0022323d, 0x0024343f, 0x00253442, 0x00253543, 0x002b3c49, 0x002c404c, 0x002c404d, 0x002c404d, 0x00304553, 0x00344856, 0x00344755, 0x00334350, 0x002f3c48, 0x002e3844, 0x00303944, 0x00303844, 0x00333944, 0x00343944, 0x00333944, 0x00313844, 0x00303742, 0x00303742, 0x00313843, 0x00343c48, 0x00373f4c, 0x002d3441, 0x0019202d, 0x000d1521, 0x000f1824, 0x00111c26, 0x00141e29, 0x0015202b, 0x0016202a, 0x00151c26, 0x0010141c, 0x00090c10, 0x0004080c, 0x0005090f, 0x00091017, 0x00141e28, 0x001c2936, 0x0021323f, 0x00273947, 0x00293d4d, 0x002d4051, 0x00314455, 0x00344858, 0x00354a5c, 0x00364c5f, 0x00364d60, 0x00384f64, 0x003b5469, 0x003e5971, 0x0044627b, 0x004c6e88, 0x00587b96, 0x005f85a0, 0x006188a4, 0x006188a4, 0x006088a4, 0x006089a5, 0x00618aa5, 0x00648ca8, 0x006790ab, 0x006993ac, 0x006a94ac, 0x00648aa3, 0x00446479, 0x00192c3c, 0x000a101c, 0x00070910, 0x00040609, 0x00040507, 0x00030405, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00020404, 0x00020307, 0x00020308, 0x00030408, 0x00040507, 0x0004060a, 0x0007090f, 0x000a1118, 0x00101b24, 0x0013212c, 0x0012232d, 0x0012242e, 0x0012242e, 0x0013232e, 0x00142430, 0x00142430, 0x00142430, 0x00142330, 0x0014232f, 0x0013222e, 0x0012222d, 0x0011212c, 0x0011202b, 0x00101e29, 0x00101d27, 0x000d1b23, 0x000c1a21, 0x000b1921, 0x000a1820, 0x000b1720, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c181f, 0x000c1820, 0x000c1820, 0x000c1920, 0x000d1b23, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0011242c, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4347, 0x001c484c, 0x001e4f51, 0x00205356, 0x0022585b, 0x002a859f, 0x0031a4cb, 0x00297a8a, 0x00286769, 0x0028696c, 0x00296c6e, 0x002a6d6f, 0x002b6f70, 0x003191a8, 0x0036a8ca, 0x002d808c, 0x002b7072, 0x0030899b, 0x0036a8cb, 0x002c7883, 0x00296b6d, 0x0028686b, 0x00286769, 0x00276568, 0x00266466, 0x00256264, 0x00256163, 0x00245f61, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0021575a, 0x00298eae, 0x002b9ac0, 0x001e5054, 0x001d4b4e, 0x001b4649, 0x001a4245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0012242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a1018, 0x000b1119, 0x000c1219, 0x000c141c, 0x000c141c, 0x000b141d, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c1620, 0x000c1720, 0x000c1821, 0x000c1821, 0x000d1923, 0x000f1b24, 0x00101c25, 0x00111c26, 0x00121d27, 0x00131f29, 0x0013202b, 0x0012212c, 0x0012212c, 0x0013212c, 0x0011202a, 0x000c1a24, 0x000a141d, 0x00080d15, 0x0005080d, 0x00040608, 0x00030405, 0x00020404, 0x00010304, 0x00010304, 0x00010304, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000405, 0x00010408, 0x0004070a, 0x00080d13, 0x000e1620, 0x00172936, 0x004b6875, 0x009ab9c1, 0x00b5cccc, 0x00bccccc, 0x00bfcccc, 0x00c0cccc, 0x00bdcccc, 0x00b3c7cb, 0x0090abba, 0x00608296, 0x004b6c83, 0x00446278, 0x0040586d, 0x003b5064, 0x00384b5e, 0x00314558, 0x002d4051, 0x00293b4a, 0x00273644, 0x00253442, 0x0022303d, 0x001f2c38, 0x001c2834, 0x0018232f, 0x00141d28, 0x00111822, 0x000f151e, 0x000c121a, 0x000b0e15, 0x00090c10, 0x0004070b, 0x0002050a, 0x0004080c, 0x00080c11, 0x000e141b, 0x0010171e, 0x00101820, 0x00101820, 0x000e141d, 0x000c1118, 0x00080d14, 0x00060b12, 0x00070c16, 0x0019202b, 0x002b313d, 0x00303844, 0x00303a45, 0x002f3b46, 0x002c3a45, 0x002e3e4c, 0x002d404e, 0x00283e4c, 0x002c4454, 0x002f4654, 0x002b4150, 0x00293c4c, 0x00273a48, 0x00283c49, 0x002b3e4c, 0x002c404d, 0x00314452, 0x00324452, 0x002f404f, 0x00283845, 0x0023323e, 0x0021303b, 0x00202f39, 0x0021303b, 0x0020303a, 0x001b2834, 0x00202d38, 0x0026303c, 0x00222c35, 0x001d262f, 0x00182129, 0x00152026, 0x00162027, 0x00172028, 0x00171f26, 0x00131a22, 0x00111920, 0x00101820, 0x00131920, 0x00131920, 0x000f141a, 0x00090e14, 0x000b1016, 0x000e1318, 0x0014181f, 0x0014191f, 0x000c1117, 0x00080c11, 0x00080c11, 0x00090d12, 0x00090d14, 0x00080c13, 0x000c1117, 0x000b0f15, 0x000c1118, 0x0010151d, 0x000d1218, 0x00090e13, 0x00080c11, 0x000b0e13, 0x000e1015, 0x000a0c12, 0x000a0e13, 0x000c1016, 0x000e141a, 0x00121a22, 0x00131c25, 0x00121c25, 0x0018242c, 0x001b242d, 0x00141c26, 0x0019202a, 0x00161c25, 0x00131921, 0x00161c24, 0x00181e29, 0x001a222f, 0x00202935, 0x00232d3a, 0x0024323f, 0x0024313f, 0x00243340, 0x00273643, 0x00283844, 0x002b3a47, 0x00263441, 0x00273642, 0x00293945, 0x002b3b48, 0x00273844, 0x002c3e4a, 0x002e404d, 0x002b3e4c, 0x002a3f4c, 0x00273a47, 0x00253846, 0x002a3d4a, 0x002b3c49, 0x00233440, 0x0022343f, 0x00243541, 0x00233443, 0x00263a48, 0x002a404d, 0x00304452, 0x00324554, 0x00364855, 0x00374854, 0x00354450, 0x00323e4b, 0x002f3945, 0x002f3844, 0x00303844, 0x00313944, 0x00323844, 0x00333944, 0x00333944, 0x00323844, 0x00313843, 0x00323844, 0x00343a46, 0x00373d48, 0x00343c47, 0x00252d37, 0x00121a24, 0x000d161f, 0x00101922, 0x00101b25, 0x00141d28, 0x00141f29, 0x00141e28, 0x00121923, 0x000c1018, 0x0006090f, 0x0003060a, 0x0005090c, 0x00091015, 0x00131d26, 0x001c2934, 0x0020313c, 0x00253844, 0x00293c4b, 0x002c3f50, 0x00304253, 0x00324657, 0x0034495a, 0x00374b5d, 0x00384c5e, 0x00384d60, 0x00385062, 0x003a5467, 0x003d586c, 0x00415d74, 0x0048657c, 0x004d6c84, 0x004f6f87, 0x004c6d86, 0x004a6a83, 0x00486880, 0x0045657d, 0x0041647c, 0x0041647b, 0x00406479, 0x00426277, 0x003e596f, 0x002d4255, 0x00101d2b, 0x00080b15, 0x0005060b, 0x00040408, 0x00030406, 0x00020404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010304, 0x00010306, 0x00010306, 0x00020406, 0x00030508, 0x00040509, 0x0005070c, 0x00070b10, 0x000c1118, 0x00101c24, 0x0013222b, 0x0012242c, 0x0012242e, 0x0012252f, 0x00142531, 0x00142532, 0x00142532, 0x00142431, 0x00142430, 0x0012242e, 0x0012242e, 0x0012222c, 0x0012212b, 0x0011202a, 0x00101e28, 0x000f1c26, 0x000d1b24, 0x000b1822, 0x000a1821, 0x000b1720, 0x000b1720, 0x000b1620, 0x000a161f, 0x000a161e, 0x000b171d, 0x000b171f, 0x000c1820, 0x000c1820, 0x000d1922, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0011242c, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4347, 0x001c484c, 0x001d4d50, 0x00205356, 0x0021585a, 0x0029859f, 0x0031a4cb, 0x00297a8a, 0x00276668, 0x0028686b, 0x00296b6d, 0x00296c6f, 0x002a6e70, 0x003191a8, 0x0036a8ca, 0x002e7f8c, 0x002c7071, 0x002f889b, 0x0035a8cb, 0x002c7883, 0x00286a6c, 0x0028686a, 0x00276668, 0x00266467, 0x00256364, 0x00256163, 0x00246062, 0x00245f61, 0x00245e60, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022585b, 0x002a8faf, 0x002b9bc0, 0x001e5054, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183d41, 0x00183a3e, 0x00153439, 0x00142e34, 0x00122a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091118, 0x000a1219, 0x000b141a, 0x000c141d, 0x000d151f, 0x000d161f, 0x000c1720, 0x000e1820, 0x000e1820, 0x000d1820, 0x000e1821, 0x000e1823, 0x000e1a24, 0x000d1b24, 0x000f1b25, 0x00101c26, 0x00111d27, 0x00121d28, 0x00121e28, 0x00121f29, 0x0012212c, 0x0012222d, 0x0013212c, 0x0013202a, 0x00101c24, 0x0009141c, 0x00070e14, 0x00060a0f, 0x00040708, 0x00040405, 0x00020403, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000405, 0x00010406, 0x00030708, 0x00080c0f, 0x000d131a, 0x0014202b, 0x00394f5d, 0x007c9fb1, 0x009cc0cb, 0x00a4c4cc, 0x00a7c5cc, 0x00a8c5cc, 0x00a2c1ca, 0x008db0c0, 0x006789a0, 0x004d6e84, 0x00466479, 0x00415c70, 0x003d5367, 0x00394c60, 0x00344659, 0x002e4154, 0x002b3c4d, 0x00283848, 0x00263443, 0x00243240, 0x00212f3c, 0x001e2b38, 0x001a2733, 0x0017222e, 0x00141d28, 0x00101821, 0x000f151d, 0x000c121a, 0x000b0e15, 0x00090c11, 0x0004070a, 0x00020508, 0x0004080b, 0x00080c10, 0x000d121a, 0x000f151d, 0x000e161e, 0x000e161f, 0x000c131c, 0x000c1018, 0x00080d14, 0x00050a10, 0x0004080f, 0x0010141c, 0x00222932, 0x002e3641, 0x00303945, 0x002c3945, 0x002c3a46, 0x002d3e4a, 0x002e414e, 0x002b404e, 0x002d4554, 0x002d4454, 0x002c4051, 0x002a3f4e, 0x00283c4c, 0x00293e4d, 0x002d4250, 0x002f4452, 0x00324554, 0x00314453, 0x00304150, 0x00283947, 0x0022313e, 0x00202f3b, 0x001f2f39, 0x0020303a, 0x00202f39, 0x001c2a35, 0x00202e39, 0x0024303b, 0x00222c37, 0x0019232c, 0x00121c24, 0x00131d24, 0x00182128, 0x00141d24, 0x00161f26, 0x00101820, 0x00131c22, 0x00141c24, 0x00111921, 0x00121820, 0x000e1318, 0x00080d11, 0x00060c0f, 0x000d1216, 0x00171c20, 0x0014191d, 0x00090f13, 0x00050a0f, 0x00080c11, 0x000a0f14, 0x00090e13, 0x00070c12, 0x000c1318, 0x000a1016, 0x000d141a, 0x0013181f, 0x0011171b, 0x000c1115, 0x00080c10, 0x00090d11, 0x000f1016, 0x000c0f14, 0x000a0d12, 0x000f1418, 0x0010161b, 0x0010171f, 0x00101a23, 0x00141e27, 0x001b262e, 0x001e2832, 0x001b232e, 0x0018202c, 0x00151c25, 0x00131921, 0x00181e28, 0x00181f2b, 0x0019212e, 0x001d2734, 0x00232f3b, 0x00253440, 0x0024323f, 0x00253340, 0x00243440, 0x00263542, 0x00283844, 0x00283844, 0x00293846, 0x00293a47, 0x00263844, 0x00253844, 0x002c3f4c, 0x002b3e4c, 0x00283f4c, 0x002a404c, 0x00283d4b, 0x00243947, 0x002b3e4c, 0x00304450, 0x00273945, 0x00233642, 0x00243844, 0x00243744, 0x00263b48, 0x002a404d, 0x00314855, 0x00354857, 0x00384856, 0x0036434f, 0x00323c48, 0x00303944, 0x002f3842, 0x002f3843, 0x00303944, 0x00313944, 0x00323844, 0x00323844, 0x00343845, 0x00333844, 0x00333944, 0x00343a46, 0x00373d48, 0x00383f48, 0x002e373f, 0x001c242c, 0x000d161d, 0x000e161d, 0x00101922, 0x00121b24, 0x00141d26, 0x00141e26, 0x00121c24, 0x0010161f, 0x00090d15, 0x0005080d, 0x0003070b, 0x00060a0e, 0x000b1117, 0x00131f26, 0x001c2934, 0x001f303c, 0x00233642, 0x00273a49, 0x002b3d4d, 0x002d4050, 0x00304454, 0x00334858, 0x00364a5c, 0x00384c5d, 0x00374c5d, 0x00354c5d, 0x00354d5f, 0x00385063, 0x003c566a, 0x00425c71, 0x00486379, 0x004b677e, 0x004a667d, 0x0046637a, 0x00436076, 0x003f5b71, 0x0039556b, 0x00365266, 0x00345061, 0x00344c5c, 0x00304251, 0x0023303d, 0x000e1420, 0x0006080f, 0x00040608, 0x00040507, 0x00030406, 0x00010404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020405, 0x00030408, 0x00030408, 0x00030508, 0x0005070a, 0x00080b0f, 0x000c1419, 0x00111d24, 0x0013232b, 0x0014252f, 0x00142630, 0x00142733, 0x00142733, 0x00142733, 0x00142733, 0x00142632, 0x0013242f, 0x0012242e, 0x0013242d, 0x0013222c, 0x0011202a, 0x00101f29, 0x00101e28, 0x000e1c25, 0x000c1a24, 0x000b1823, 0x000c1822, 0x000c1721, 0x000b1620, 0x0009151e, 0x0008141d, 0x0009151c, 0x000b171e, 0x000c1820, 0x000c1820, 0x000d1921, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0013242c, 0x00112a30, 0x00142e34, 0x00143036, 0x0016363b, 0x00183d41, 0x001a4245, 0x001c474b, 0x001e4d50, 0x00205254, 0x0021585a, 0x002a849f, 0x0031a4cb, 0x0029798a, 0x00276568, 0x0028686a, 0x00286a6c, 0x00296c6f, 0x002a6d6f, 0x003190a8, 0x0036a8ca, 0x002d7f8b, 0x002b6f70, 0x002f889a, 0x0035a8cb, 0x002c7882, 0x0028696c, 0x00286769, 0x00276568, 0x00266466, 0x00256264, 0x00246062, 0x00245f61, 0x00245e60, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x002a8faf, 0x002c9bc0, 0x001e5054, 0x001e4c50, 0x001c474b, 0x001b4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00142e34, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a131a, 0x000b141b, 0x000c141c, 0x000c151d, 0x000e171f, 0x000e1720, 0x000e1820, 0x000e1821, 0x000f1921, 0x000f1921, 0x000f1922, 0x000f1a24, 0x00101c25, 0x000f1c26, 0x00101c26, 0x00101d27, 0x00111d27, 0x00131d28, 0x00121e28, 0x00111e29, 0x0011202c, 0x0011212c, 0x0013202c, 0x00101c26, 0x000c151d, 0x00080f16, 0x00050a10, 0x0004080b, 0x00040507, 0x00030404, 0x00010303, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000404, 0x00000404, 0x00020507, 0x0005090b, 0x00090f15, 0x000e1923, 0x00283b49, 0x00587990, 0x00759cb6, 0x007ca3bb, 0x007fa5bc, 0x007ea4ba, 0x00749ab1, 0x006488a0, 0x004f7088, 0x00456279, 0x00415c70, 0x003e5669, 0x003a4f62, 0x0036485c, 0x00304356, 0x002c4050, 0x002a3c4a, 0x00283745, 0x00263442, 0x0024313f, 0x00202e3b, 0x001d2b37, 0x00192733, 0x0016222e, 0x00141d28, 0x00111822, 0x000f151e, 0x000d131b, 0x000b0f16, 0x00090c10, 0x0004080b, 0x00020508, 0x00020608, 0x0006090d, 0x000a0f17, 0x000d141c, 0x000d141d, 0x000c141e, 0x000c131b, 0x000c1018, 0x00090e14, 0x00060b11, 0x0003080e, 0x00080e14, 0x00181f27, 0x0029303b, 0x00303944, 0x002d3945, 0x002c3945, 0x002c3b48, 0x002e404d, 0x002e4351, 0x002e4454, 0x002e4554, 0x002e4454, 0x002c4251, 0x002c4050, 0x002b4050, 0x002d4251, 0x00304454, 0x00304454, 0x00304352, 0x002c3f4e, 0x00283847, 0x00233340, 0x0022313d, 0x0022313d, 0x0022313c, 0x0024333d, 0x00202d38, 0x00202d38, 0x001f2c36, 0x001f2a33, 0x001b252e, 0x00111c24, 0x00141f25, 0x001c242c, 0x00121b22, 0x00141d24, 0x000f171e, 0x00171f26, 0x00141d24, 0x00121b22, 0x00121920, 0x000c1118, 0x00070c10, 0x00040a0c, 0x000b1014, 0x0013181c, 0x0010151a, 0x000a0f13, 0x00080e12, 0x00080d12, 0x000a0f13, 0x000b1015, 0x000a0f15, 0x000d1419, 0x000c1318, 0x00131a20, 0x00141920, 0x0011161b, 0x0010151a, 0x000c1014, 0x00090d12, 0x000f1217, 0x00101418, 0x000c1014, 0x000c1014, 0x00141a20, 0x00151c24, 0x00111923, 0x00101922, 0x001c262f, 0x001e2932, 0x001e2832, 0x001c2630, 0x00141c25, 0x00141a22, 0x00181f28, 0x001a202c, 0x001c2430, 0x001f2936, 0x00273440, 0x00253540, 0x00243440, 0x00253442, 0x00253441, 0x0023323f, 0x00263542, 0x002c3b48, 0x002a3846, 0x00293a46, 0x00243541, 0x00253844, 0x002d404f, 0x00293d4b, 0x002a404d, 0x0028404c, 0x00263c4a, 0x00243947, 0x00283c49, 0x002e414e, 0x00273b47, 0x00243844, 0x00283b47, 0x00293c48, 0x002a3f4c, 0x002c4450, 0x00324855, 0x00354856, 0x00354452, 0x00333d4a, 0x00313844, 0x00313742, 0x00303741, 0x00303842, 0x00303943, 0x00313944, 0x00323844, 0x00323844, 0x00323844, 0x00323844, 0x00343945, 0x00353c47, 0x00373d48, 0x00343b45, 0x00252d35, 0x00121a21, 0x000d141c, 0x0010171e, 0x00111922, 0x00121b24, 0x00121c24, 0x00111b24, 0x00111922, 0x000f141c, 0x000a0c13, 0x0005080c, 0x0004070c, 0x00070b10, 0x000c1318, 0x00141f26, 0x001b2832, 0x001f2f3a, 0x00223440, 0x00263846, 0x002a3b4b, 0x002c3e4e, 0x002e4253, 0x00324556, 0x0034495a, 0x00364a5c, 0x00354b5c, 0x00344c5c, 0x00344c5d, 0x00354d60, 0x00385164, 0x003d576a, 0x00435c72, 0x00476178, 0x00476279, 0x00446077, 0x00415c73, 0x003e586e, 0x00385167, 0x00314c60, 0x002e4859, 0x002c4250, 0x00283845, 0x001a2431, 0x000a0e19, 0x0005070e, 0x00040508, 0x00030407, 0x00030406, 0x00010404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010305, 0x00020408, 0x00030408, 0x00030408, 0x00030508, 0x0004070a, 0x00080e12, 0x000c151b, 0x00111d25, 0x0016242d, 0x00152630, 0x00152734, 0x00142834, 0x00142834, 0x00142834, 0x00142733, 0x00132530, 0x0012242e, 0x0013242e, 0x0013242c, 0x0011212b, 0x0010202a, 0x00101f29, 0x000f1e28, 0x000e1c25, 0x000d1b24, 0x000d1924, 0x000c1821, 0x000b1620, 0x000a151f, 0x0009141e, 0x000a151c, 0x000b171e, 0x000b171f, 0x000c1820, 0x000d1921, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0015363b, 0x00183c40, 0x001a4245, 0x001c474b, 0x001d4c50, 0x001f5154, 0x00215659, 0x0029849f, 0x0030a4cb, 0x00287889, 0x00266467, 0x00286769, 0x0028696c, 0x00296b6d, 0x00296c6f, 0x003090a8, 0x0036a8ca, 0x002c7d8a, 0x00296d6f, 0x002e879a, 0x0034a7cb, 0x002b7681, 0x0028686a, 0x00276668, 0x00266467, 0x00266364, 0x00256163, 0x00246062, 0x00245e60, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x002a8faf, 0x002c9bc0, 0x001f5256, 0x001e4c50, 0x001c474b, 0x001b4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00142e34, 0x00122c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c141b, 0x000c151c, 0x000d161d, 0x000e161d, 0x0010181f, 0x00101820, 0x000f1921, 0x000f1922, 0x00101a23, 0x00101a23, 0x00101b24, 0x00101b25, 0x00101c27, 0x00101d27, 0x00101d27, 0x00101d27, 0x00111e28, 0x00141f29, 0x00131f28, 0x00111e29, 0x0010202b, 0x0010202b, 0x00121e2a, 0x000f1822, 0x000a1018, 0x00050b10, 0x0004080b, 0x00020508, 0x00030405, 0x00030304, 0x00010302, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000304, 0x00010406, 0x0004080a, 0x00080c12, 0x000b141d, 0x001c2e3a, 0x0039556b, 0x004c6f88, 0x00507590, 0x00547b93, 0x00557a92, 0x0051748c, 0x004a6a84, 0x00446179, 0x00415c71, 0x003d576a, 0x003a5063, 0x00364b5e, 0x00344658, 0x002f4254, 0x002b3e4e, 0x00293a47, 0x00273643, 0x00243240, 0x0023303e, 0x00202c3a, 0x001c2935, 0x00182632, 0x0016222e, 0x00151e29, 0x00131924, 0x0010171f, 0x000e141c, 0x000c1017, 0x00090c11, 0x0004080b, 0x00030609, 0x00020508, 0x0005090c, 0x00090d14, 0x000c1219, 0x000c131b, 0x000d141c, 0x000c1319, 0x000c1018, 0x000a0f15, 0x00080d13, 0x00040910, 0x00050911, 0x000f141b, 0x00242832, 0x00303742, 0x002f3944, 0x002f3844, 0x002d3946, 0x002f3d4b, 0x00324452, 0x00304453, 0x00304554, 0x00314858, 0x00304655, 0x00304756, 0x002c4251, 0x002c4251, 0x00304453, 0x00314655, 0x002f4252, 0x00283b4b, 0x00263846, 0x00263745, 0x00263643, 0x00253441, 0x00263542, 0x00273641, 0x00202d38, 0x00202f38, 0x001f2c35, 0x001a2630, 0x001c272f, 0x0018222a, 0x00182329, 0x001d272e, 0x00131c23, 0x00131c23, 0x00111920, 0x00171f27, 0x00161e25, 0x00161e26, 0x00121920, 0x000e1318, 0x00080d12, 0x00060b0f, 0x000b1014, 0x00101418, 0x000d1317, 0x000c1216, 0x000c1216, 0x00080e12, 0x00060b10, 0x00090e14, 0x0010151c, 0x00141b20, 0x00131920, 0x00171d24, 0x00161c22, 0x0012171c, 0x0013181c, 0x0010151a, 0x000c1015, 0x000f1216, 0x0012151a, 0x000e1216, 0x000a0e13, 0x0012171c, 0x001b2028, 0x00182028, 0x00111c24, 0x001c262e, 0x001d2931, 0x001c2731, 0x00202a34, 0x0017202a, 0x00151e27, 0x001a232c, 0x001e2632, 0x00202936, 0x00222e3a, 0x00283843, 0x00273843, 0x00263643, 0x00273644, 0x00273644, 0x00233240, 0x00243441, 0x002d3c4a, 0x002b3a47, 0x00283845, 0x00263844, 0x002b3e4b, 0x00304451, 0x002b3f4c, 0x002c4250, 0x002a414e, 0x00283f4c, 0x00243b48, 0x00243946, 0x00243a45, 0x00233844, 0x00243a45, 0x00283d49, 0x002c404c, 0x002e434f, 0x00304450, 0x00334652, 0x00354451, 0x00343e4c, 0x00313a45, 0x00313843, 0x00313841, 0x00313741, 0x00303841, 0x00303942, 0x00303943, 0x00313944, 0x00313944, 0x00313944, 0x00313842, 0x00353b47, 0x00363c48, 0x00363c48, 0x002c343d, 0x001a222a, 0x000f151c, 0x000d141b, 0x0010171e, 0x00121821, 0x00131a24, 0x00131a24, 0x00121822, 0x00111620, 0x000d1018, 0x00090a10, 0x0006080c, 0x0005080d, 0x00080b11, 0x0010141a, 0x00162028, 0x001a2832, 0x001e2d38, 0x0022323e, 0x00263544, 0x00293948, 0x002c3c4b, 0x002d4050, 0x00304353, 0x00334758, 0x00344859, 0x00344859, 0x00344a5a, 0x00334b5c, 0x00344c5d, 0x00354d60, 0x00395164, 0x003e576a, 0x00425c70, 0x00445f74, 0x00446074, 0x00425c72, 0x003f576d, 0x00385167, 0x00334b5f, 0x002e4657, 0x002a3f4c, 0x0024333f, 0x00161e2a, 0x00080b14, 0x0004070c, 0x00030408, 0x00020407, 0x00020405, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020308, 0x00020308, 0x00020308, 0x00020408, 0x00030508, 0x0004080c, 0x00070c12, 0x000d141c, 0x00141e27, 0x0015242f, 0x00142632, 0x00142834, 0x00142834, 0x00142834, 0x00142833, 0x00132630, 0x0012252f, 0x0013252f, 0x0014242f, 0x0011232d, 0x0011222c, 0x0010202b, 0x00101f29, 0x000e1e28, 0x000d1c26, 0x000e1c24, 0x000c1a24, 0x000a1720, 0x000a1620, 0x000a1520, 0x000a151e, 0x000b171e, 0x000b171f, 0x000c1820, 0x000d1921, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00122c32, 0x00143036, 0x00143439, 0x00183c40, 0x00194044, 0x001b4649, 0x001d4b4e, 0x001f5053, 0x00205457, 0x0028849e, 0x0030a4cb, 0x00287788, 0x00266364, 0x00276568, 0x0028686a, 0x0028696c, 0x00286a6c, 0x00308fa7, 0x0035a8ca, 0x002c7c89, 0x00296c6e, 0x002d8699, 0x0034a7cb, 0x002a7580, 0x00286668, 0x00266467, 0x00256364, 0x00256163, 0x00256062, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0022585b, 0x002a8faf, 0x002b9bc0, 0x001e5054, 0x001d4c50, 0x001c474b, 0x001a4347, 0x00183d41, 0x00183a3e, 0x00153439, 0x00142e34, 0x00132c32, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c151c, 0x000e171e, 0x0010181f, 0x0010181f, 0x00101820, 0x00101920, 0x00101a23, 0x00101b24, 0x00101c24, 0x00111c24, 0x00111c25, 0x00111d27, 0x00111e28, 0x00111f28, 0x00111f29, 0x00111f29, 0x0013202a, 0x0014202a, 0x0014202b, 0x0012202b, 0x00101f2a, 0x00101c28, 0x000d1722, 0x000b111a, 0x00060c12, 0x0002080c, 0x00020509, 0x00010407, 0x00020404, 0x00030303, 0x00010302, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000404, 0x00010405, 0x00030608, 0x0005080e, 0x00081017, 0x001b2a34, 0x00324a5d, 0x003b5870, 0x00405f77, 0x0046677c, 0x0048677e, 0x0046647b, 0x00446077, 0x00415b70, 0x003e566a, 0x003a5064, 0x00354c5d, 0x00334759, 0x00304455, 0x002e4051, 0x002a3d4c, 0x00283946, 0x00263542, 0x0023323e, 0x00212f3c, 0x001e2c38, 0x001c2834, 0x00182531, 0x0016212d, 0x00141e28, 0x00131924, 0x0010171f, 0x000e141c, 0x000c1017, 0x00090c12, 0x0006090d, 0x0004060b, 0x0003050a, 0x0005080c, 0x00080b11, 0x000c1017, 0x000c1219, 0x000c131a, 0x000b1218, 0x000b1017, 0x000a0f16, 0x00080d14, 0x00060a10, 0x0004080f, 0x00090d14, 0x001b2028, 0x002b313b, 0x002f3841, 0x00303844, 0x002e3844, 0x002e3a48, 0x00334150, 0x00324252, 0x00314454, 0x00334858, 0x00314857, 0x00324858, 0x002d4453, 0x002c4150, 0x002e4352, 0x00304554, 0x002f4252, 0x00263848, 0x00233544, 0x00253644, 0x00253542, 0x00263542, 0x00263542, 0x00253440, 0x00202d38, 0x0022303a, 0x00202d37, 0x0018242d, 0x0018242d, 0x001b272f, 0x001c282f, 0x001c282f, 0x00161f26, 0x00111a21, 0x00141c24, 0x0018212a, 0x00172029, 0x0018202a, 0x00141b22, 0x000e1419, 0x00080d11, 0x00060c10, 0x000b1014, 0x000f1418, 0x000e1418, 0x000e141a, 0x000f141a, 0x000a0f14, 0x00050a0f, 0x00060c11, 0x000f141a, 0x00181f25, 0x00171f25, 0x00141c23, 0x00181e24, 0x00161b20, 0x00141a1f, 0x00181c22, 0x00101418, 0x000b0e13, 0x0011151a, 0x00101419, 0x000c1115, 0x000e1318, 0x00181c25, 0x00192029, 0x00162029, 0x001c2730, 0x001f2b33, 0x001b2630, 0x001f2a34, 0x001d2830, 0x0018222b, 0x001c2830, 0x00242f3a, 0x0025303c, 0x00283440, 0x002a3a46, 0x002a3b47, 0x002b3b49, 0x00293848, 0x00283846, 0x00243342, 0x00243341, 0x002a3948, 0x002d3d4b, 0x00283846, 0x00263844, 0x002f414f, 0x00304452, 0x002c404e, 0x002c4350, 0x002d4450, 0x002b414e, 0x00283f4c, 0x00293e4c, 0x00283c48, 0x00283c48, 0x002b404c, 0x002b3f4b, 0x002c404c, 0x0030414d, 0x0030404c, 0x0031404d, 0x0033404c, 0x00333c49, 0x00323945, 0x00313843, 0x00313841, 0x00313841, 0x00313841, 0x00303842, 0x00303943, 0x00313944, 0x00313944, 0x00313944, 0x00313943, 0x00363d48, 0x00383e49, 0x00343b46, 0x00242c35, 0x00121921, 0x000d141c, 0x000f151d, 0x0011181f, 0x00141821, 0x00141823, 0x00141823, 0x00121720, 0x000f131c, 0x000c0d15, 0x0008080e, 0x0006060c, 0x0007080d, 0x000b0c14, 0x0010151c, 0x00172028, 0x001b2833, 0x001d2d38, 0x0020303c, 0x00243442, 0x00283846, 0x002a3b49, 0x002c3e4e, 0x002f4151, 0x00314555, 0x00334859, 0x00334859, 0x00334a5a, 0x00334b5b, 0x00334a5b, 0x00334b5d, 0x00374f61, 0x003a5365, 0x003e576c, 0x00415b70, 0x00415c72, 0x00415b70, 0x003f586d, 0x003a5268, 0x00344c60, 0x00304758, 0x002c3e4c, 0x0024303c, 0x00141a24, 0x00060911, 0x00040408, 0x00030406, 0x00030304, 0x00030304, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000205, 0x00020308, 0x00020308, 0x00020308, 0x00020308, 0x00030408, 0x0002050a, 0x0004080d, 0x00080c14, 0x000e151d, 0x00141f28, 0x00142430, 0x00142733, 0x00142834, 0x00142834, 0x00142833, 0x00142731, 0x00132630, 0x00132530, 0x0014242f, 0x0012242e, 0x0011232d, 0x0010222c, 0x0010202a, 0x00102029, 0x000f1e28, 0x000f1d26, 0x000e1c25, 0x000c1923, 0x000b1821, 0x000b1620, 0x000b171f, 0x000b171e, 0x000c1820, 0x000c1820, 0x000d1921, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153439, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001c484c, 0x001e4f51, 0x00205254, 0x0028839d, 0x0030a4cb, 0x00287788, 0x00256163, 0x00266466, 0x00276568, 0x00286769, 0x0028686b, 0x002f8ea6, 0x0034a7ca, 0x002b7a88, 0x0028696c, 0x002c8498, 0x0034a6cb, 0x0029747f, 0x00266467, 0x00256364, 0x00256163, 0x00256062, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x00235a5c, 0x0022595c, 0x0022585b, 0x0021575a, 0x00298eae, 0x002b9ac0, 0x001e5054, 0x001d4b4e, 0x001c4649, 0x001a4245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c161f, 0x000e1820, 0x000f1921, 0x00101922, 0x00101a23, 0x00101b23, 0x00101c24, 0x00101c24, 0x00121c25, 0x00131d26, 0x00131d28, 0x00121f29, 0x00122029, 0x00112029, 0x0011202a, 0x0011202a, 0x0012202a, 0x0014202b, 0x0014212c, 0x0013202a, 0x00101d28, 0x000e1823, 0x000b111a, 0x00080c12, 0x0004080c, 0x0001050a, 0x00020408, 0x00010406, 0x00000304, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020404, 0x00020404, 0x00030406, 0x0004080c, 0x00070e16, 0x00182732, 0x00324858, 0x003c5668, 0x003f5b6f, 0x00446075, 0x00446076, 0x00435d74, 0x0040596f, 0x003d5469, 0x003b5064, 0x00384d60, 0x00344a5b, 0x00324657, 0x00304252, 0x002c3f4e, 0x002a3b49, 0x00283744, 0x00243440, 0x0022303c, 0x00202e39, 0x001c2a36, 0x001b2833, 0x00182430, 0x0014202c, 0x00131c27, 0x00101822, 0x0010161e, 0x000e131b, 0x000c1017, 0x00090c13, 0x0006090d, 0x0005070a, 0x00040509, 0x0005070c, 0x00070910, 0x000b0e14, 0x000c1018, 0x000b1219, 0x000b1118, 0x000b1016, 0x00090e13, 0x00080c11, 0x00070b0f, 0x0006080d, 0x00070a10, 0x0011151c, 0x0021272e, 0x002d343c, 0x00303741, 0x00303843, 0x002e3844, 0x00303c49, 0x0031404d, 0x00324452, 0x00334655, 0x00304453, 0x00304654, 0x002c4350, 0x002c414f, 0x002c4150, 0x00304452, 0x002e4150, 0x00243744, 0x00223441, 0x00243541, 0x00253540, 0x00263541, 0x0024333e, 0x0023303c, 0x00202d38, 0x00212f3b, 0x00202e38, 0x00172430, 0x0018262f, 0x001c2933, 0x001f2c36, 0x001d2a32, 0x0018222a, 0x00131c24, 0x0018232b, 0x001a272f, 0x001b272e, 0x001d2930, 0x00182329, 0x000d151b, 0x00080f14, 0x00070c11, 0x000b1115, 0x0011181c, 0x00131920, 0x00121920, 0x0012181f, 0x000e131b, 0x00090e14, 0x00080c12, 0x000b1016, 0x00182025, 0x00162026, 0x00131b22, 0x00151c23, 0x00121820, 0x00181e25, 0x001a2028, 0x0010161c, 0x00090f15, 0x0011171c, 0x0011171b, 0x00101419, 0x0011161d, 0x00151b23, 0x001a222b, 0x0019232c, 0x001f2932, 0x001e2a33, 0x001c2730, 0x001d2934, 0x001c2833, 0x0018242d, 0x001b2730, 0x00212d37, 0x00222e39, 0x00253440, 0x00293946, 0x00293b47, 0x002c3c49, 0x002a3b48, 0x00283845, 0x00243542, 0x00243543, 0x00293a48, 0x002d404d, 0x002a3c4b, 0x00273c49, 0x00304553, 0x002d4250, 0x002f4451, 0x002b414e, 0x002a414e, 0x00283f4c, 0x002a414e, 0x002b414f, 0x002a404c, 0x002f4450, 0x00344754, 0x00304250, 0x002e3f4a, 0x00303e49, 0x00303c47, 0x00303c48, 0x00323c48, 0x00323b47, 0x00323945, 0x00323843, 0x00313842, 0x00333842, 0x00323842, 0x00313841, 0x00303742, 0x00313844, 0x00313844, 0x00313844, 0x00343b46, 0x00383f4c, 0x00383f4c, 0x002d3440, 0x0019202b, 0x000e141d, 0x000e141c, 0x000f161d, 0x0010181d, 0x00141820, 0x00141820, 0x00141820, 0x00111620, 0x000d111b, 0x000b0c14, 0x0008080d, 0x0006060b, 0x0007080e, 0x000b0d14, 0x0012161e, 0x0018222b, 0x001a2832, 0x001d2c38, 0x0020303b, 0x0023323f, 0x00253543, 0x00283847, 0x00293c4b, 0x002c4050, 0x002f4354, 0x00324758, 0x00324859, 0x0034495a, 0x0034495a, 0x00344859, 0x0032495b, 0x00344c5e, 0x00374f61, 0x003b5366, 0x003f576c, 0x00405a70, 0x003f5a70, 0x003e586d, 0x003c5469, 0x00364f62, 0x00324a5a, 0x002e404f, 0x00212d3a, 0x000d141e, 0x0002060c, 0x00020406, 0x00030305, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000205, 0x00000205, 0x00010305, 0x00020405, 0x00020407, 0x00030408, 0x0003040a, 0x0005060e, 0x00090c14, 0x000e161f, 0x0014202a, 0x0014242e, 0x00142631, 0x00142832, 0x00142832, 0x00142732, 0x00132632, 0x00132531, 0x00142430, 0x00132430, 0x0012242e, 0x0011232d, 0x0010212b, 0x00102029, 0x00101f28, 0x00111e28, 0x00101d28, 0x000e1c25, 0x000c1921, 0x000b1820, 0x000c1a21, 0x000c1921, 0x000c1a21, 0x000c1a21, 0x000d1a22, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x00194245, 0x001c474b, 0x001d4c50, 0x001f5053, 0x0028829d, 0x002fa4cb, 0x00277688, 0x00246064, 0x00256367, 0x00266568, 0x0027676a, 0x0027686b, 0x002e8da6, 0x0034a6ca, 0x002a7886, 0x00276668, 0x002c8397, 0x0033a6cb, 0x0028727f, 0x00266468, 0x00256266, 0x00246164, 0x00246063, 0x00245f62, 0x00245e61, 0x00235c60, 0x00225c60, 0x00225c60, 0x00225c60, 0x00225c60, 0x00225c60, 0x00215b5f, 0x00225b5f, 0x0022595e, 0x0021585c, 0x0020585c, 0x00298eaf, 0x002b9ac0, 0x001e4f53, 0x001c4a4d, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0013282e, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000e1820, 0x000f1921, 0x00101a23, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101d25, 0x00101e26, 0x00121e27, 0x00131f28, 0x00131f29, 0x0013202a, 0x0013202a, 0x0012202a, 0x0011202a, 0x0013212c, 0x0014202c, 0x0014212c, 0x0013202c, 0x00121e28, 0x00101a22, 0x000c141b, 0x00080c12, 0x0005080c, 0x00030509, 0x00010408, 0x00020308, 0x00010305, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020404, 0x00020404, 0x00030405, 0x00040609, 0x00060c14, 0x00182430, 0x00334754, 0x003c5565, 0x003e586c, 0x00405a70, 0x00405a6f, 0x003d566c, 0x003b5267, 0x00384f63, 0x00374c5e, 0x0034495a, 0x00334858, 0x00304454, 0x002d4050, 0x002a3c4c, 0x00283847, 0x00263542, 0x0023323d, 0x0021303b, 0x00202d39, 0x001c2935, 0x001c2733, 0x0018232f, 0x0014202c, 0x00111b25, 0x00101820, 0x0010161e, 0x000e131b, 0x000c1018, 0x00090e14, 0x00070a0e, 0x00040609, 0x00030508, 0x0004050a, 0x0004080e, 0x00080c12, 0x000b1017, 0x000b1119, 0x000b1119, 0x000a0f15, 0x00080e12, 0x00070c0f, 0x00070a0d, 0x0005090c, 0x0005080c, 0x000b0e12, 0x00191c22, 0x00292e35, 0x00303640, 0x00303841, 0x002d3741, 0x002c3743, 0x002c3a46, 0x0030404e, 0x00304451, 0x00304351, 0x00314654, 0x002e4451, 0x002f4452, 0x002e4350, 0x00304452, 0x002d404f, 0x00283a48, 0x00253844, 0x00263744, 0x00273742, 0x0024343f, 0x0023323d, 0x0023303c, 0x0021303b, 0x0023303c, 0x00202e3a, 0x001c2a35, 0x001b2a34, 0x001a2933, 0x001a2933, 0x001a2830, 0x0018242d, 0x0017222a, 0x00202c34, 0x001e2c34, 0x001d2c31, 0x00202f34, 0x0019252c, 0x000f181e, 0x000e141b, 0x000f141a, 0x0011181d, 0x00161e23, 0x00161f25, 0x00141c24, 0x00141a22, 0x0010161e, 0x000d1319, 0x000b1016, 0x000c1116, 0x00141c22, 0x00141e24, 0x00111b22, 0x00141d25, 0x000d161f, 0x00101820, 0x00181f26, 0x0010151d, 0x00091017, 0x0010161b, 0x0010171b, 0x0013191e, 0x00171c22, 0x00141a22, 0x001b222c, 0x001c242d, 0x001e2831, 0x001c2831, 0x001c2831, 0x001f2b35, 0x00202d37, 0x00182630, 0x001c2832, 0x001d2934, 0x001d2a34, 0x0024313d, 0x00293845, 0x00293845, 0x00293b47, 0x00283a46, 0x00273a46, 0x00283a46, 0x00283b48, 0x002c404e, 0x00304452, 0x002f4451, 0x002b414e, 0x00314854, 0x00283c4a, 0x00304552, 0x00283f4c, 0x00283e4c, 0x00263c49, 0x002a414e, 0x002b414f, 0x002c424f, 0x00304654, 0x00344755, 0x00324250, 0x00303e49, 0x00303b45, 0x00303842, 0x00313943, 0x00333943, 0x00323a44, 0x00323a44, 0x00323843, 0x00313841, 0x00343842, 0x00333842, 0x00323741, 0x00313641, 0x00313843, 0x00323844, 0x00323847, 0x00363c4b, 0x0039404d, 0x00343b48, 0x00262c38, 0x00121824, 0x000c131c, 0x000e141c, 0x0010161c, 0x0010171c, 0x0011171e, 0x0012171f, 0x0012171f, 0x0010141e, 0x000b0f18, 0x00080a11, 0x0007070c, 0x0005050b, 0x0007080e, 0x000c0d15, 0x00131820, 0x0018222d, 0x00192732, 0x001c2b36, 0x001f2e39, 0x0021303b, 0x00233440, 0x00263744, 0x00283a48, 0x002b3d4d, 0x002d4153, 0x00304556, 0x00324858, 0x00324859, 0x00334859, 0x00334758, 0x00314858, 0x0033495a, 0x00344c5d, 0x00385062, 0x003b5366, 0x003f586c, 0x003e586c, 0x003d586c, 0x003c5669, 0x00375064, 0x00344b5b, 0x00304050, 0x00202c39, 0x00081019, 0x0000050a, 0x00020405, 0x00020404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020308, 0x00020308, 0x00040409, 0x0006080c, 0x000a0e15, 0x000f1820, 0x00132028, 0x0014252e, 0x00142731, 0x00142832, 0x00142733, 0x00142733, 0x00142733, 0x00122431, 0x00132431, 0x0013242e, 0x0011232d, 0x0011222c, 0x0011202a, 0x0011202a, 0x00111f2a, 0x00101d28, 0x000d1c25, 0x000c1b24, 0x000d1c24, 0x000e1c24, 0x000f1c25, 0x000f1c25, 0x000f1c25, 0x000f1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x00102229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00143036, 0x0016363b, 0x00183c40, 0x00194044, 0x001b4448, 0x001c4a4d, 0x001d4d50, 0x00246e81, 0x002da1c8, 0x002c9bbf, 0x002c98ba, 0x002d98ba, 0x002e99bb, 0x002f99bb, 0x002f9abb, 0x0030a0c4, 0x0031a0c3, 0x00276c75, 0x00256364, 0x00287380, 0x0031a2c6, 0x002f9bbd, 0x002e99ba, 0x002d98ba, 0x002d98ba, 0x002d98ba, 0x002c98ba, 0x002c98ba, 0x002c98ba, 0x002c97ba, 0x002b97ba, 0x002b96b9, 0x002b96b9, 0x002b96b9, 0x002b96b9, 0x002b96b9, 0x002b96b9, 0x002a96b9, 0x002a95b9, 0x002c9fc5, 0x002788a8, 0x001d4c50, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f1922, 0x00101a23, 0x00101c24, 0x00101c25, 0x00101d25, 0x00101e26, 0x00101f26, 0x00122028, 0x00132029, 0x0014202a, 0x0014202a, 0x0014202a, 0x0013202a, 0x0012202a, 0x0012212b, 0x0013212c, 0x0013212c, 0x0013212c, 0x0013202a, 0x00111b24, 0x000f141c, 0x000a0f15, 0x0006090e, 0x00040509, 0x00030408, 0x00010407, 0x00020308, 0x00010305, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020404, 0x00020404, 0x00030405, 0x00040509, 0x00070a13, 0x0016202c, 0x00314451, 0x003b5363, 0x003c5568, 0x003e586c, 0x003d576a, 0x003b5467, 0x00385063, 0x00354c5d, 0x00344959, 0x00324757, 0x00314655, 0x00304353, 0x002c3f50, 0x00293c4b, 0x00273846, 0x00253441, 0x0022313c, 0x00212f3a, 0x00202c39, 0x001e2837, 0x001b2633, 0x0017232f, 0x00141f2b, 0x00101b24, 0x00101820, 0x0010181f, 0x000f141c, 0x000c1118, 0x000a0f14, 0x00080a0f, 0x0004070a, 0x00030508, 0x00030409, 0x0004060c, 0x00070a0f, 0x00090e14, 0x00090f17, 0x000a1018, 0x000a0f14, 0x00080d11, 0x00070c10, 0x00070a0d, 0x0005080b, 0x0005080c, 0x00070a0d, 0x00101418, 0x0020252c, 0x002c313a, 0x0030353f, 0x002d353f, 0x002c3540, 0x002a3743, 0x002d3c49, 0x00304150, 0x00334452, 0x00334654, 0x00304552, 0x00304654, 0x00304452, 0x00304451, 0x002e414f, 0x00293c4a, 0x00243744, 0x00263743, 0x00253540, 0x00253440, 0x0021303c, 0x0022303c, 0x0024313c, 0x0024323d, 0x0022303c, 0x00202e3a, 0x001a2933, 0x00182630, 0x00172630, 0x00192831, 0x001c2933, 0x001c2832, 0x0024303a, 0x00202e37, 0x001c2c34, 0x001c2b32, 0x0018252c, 0x00101a21, 0x00131920, 0x00141a20, 0x00131a20, 0x00121b20, 0x00151e26, 0x00131b24, 0x00111922, 0x00131921, 0x0010161d, 0x0010141b, 0x000f141b, 0x00161d24, 0x00151e26, 0x00121c24, 0x00141e27, 0x00131c25, 0x00101820, 0x00161d25, 0x00121920, 0x00081018, 0x000d161b, 0x00131b20, 0x00181f24, 0x001a2027, 0x00151c25, 0x001b232c, 0x001a242c, 0x001d2830, 0x0019262f, 0x001c2832, 0x00202d37, 0x0024313b, 0x001c2a34, 0x00202d37, 0x00202d37, 0x00222e39, 0x00212f3a, 0x00273442, 0x00283744, 0x002b3b48, 0x002a3c48, 0x00283b47, 0x00293c48, 0x002c3e4c, 0x00314554, 0x00334855, 0x00314854, 0x002d4451, 0x00304653, 0x00273c49, 0x002c404e, 0x00283f4c, 0x0029404c, 0x00263d4a, 0x00283f4c, 0x00283f4c, 0x002b424f, 0x00304552, 0x00334453, 0x00334250, 0x00313e4a, 0x00303a46, 0x00303843, 0x00313844, 0x00333944, 0x00323944, 0x00323944, 0x00323844, 0x00313842, 0x00333843, 0x00333743, 0x00323641, 0x00313541, 0x00313642, 0x00323844, 0x00343948, 0x00373e4c, 0x0038404c, 0x002d3542, 0x001d2430, 0x000d131f, 0x000b111a, 0x000d131b, 0x000f151c, 0x000f161c, 0x0010151c, 0x0010151d, 0x0010141d, 0x000d121b, 0x00080c15, 0x00070810, 0x0006050b, 0x0006050c, 0x0008090f, 0x000d1017, 0x00141b24, 0x0018232d, 0x00182732, 0x001b2b35, 0x001e2d38, 0x0020303a, 0x0021333e, 0x00243642, 0x00273946, 0x00293c4c, 0x002c3f50, 0x00304354, 0x00314657, 0x00324658, 0x00324658, 0x00334658, 0x00324758, 0x00334859, 0x00344b5c, 0x00354d5f, 0x00385063, 0x003c5467, 0x003c5668, 0x003a5668, 0x003a5567, 0x00375163, 0x00344c5c, 0x002f4050, 0x001e2a36, 0x00050d15, 0x00000508, 0x00020404, 0x00020403, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020308, 0x00020308, 0x00030408, 0x00040509, 0x0007090f, 0x000b1018, 0x000f1920, 0x0013222a, 0x0014262f, 0x00142731, 0x00142733, 0x00142834, 0x00142733, 0x00132632, 0x00142531, 0x00142430, 0x0013242e, 0x0012232c, 0x0012212b, 0x0011202a, 0x0011202c, 0x00101e29, 0x000f1c28, 0x000f1c27, 0x000f1d27, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x000c1b25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00122c32, 0x00142e34, 0x00153439, 0x0017383c, 0x00183d41, 0x001a4245, 0x001b4649, 0x001d4b4e, 0x001e5054, 0x00257a92, 0x00298fb0, 0x002a90b0, 0x002b91b0, 0x002c91b0, 0x002c91b1, 0x002c92b1, 0x002c93b1, 0x0028798c, 0x00245f61, 0x00245f61, 0x00245f61, 0x00287c90, 0x002c92b0, 0x002c92b0, 0x002c90b0, 0x002c90b0, 0x002a90b0, 0x002a90b0, 0x002a90b0, 0x00298fb0, 0x00298fb0, 0x00298fb0, 0x00298fb0, 0x00298fb0, 0x00298fb0, 0x00298fb0, 0x00298fb0, 0x00288fb0, 0x00288eb0, 0x00288eb0, 0x002788a8, 0x001e555f, 0x001c474b, 0x001b4448, 0x00194044, 0x00183c40, 0x0017383c, 0x00153439, 0x00142e34, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101b24, 0x00111c24, 0x00121c25, 0x00101e28, 0x00101f28, 0x00112028, 0x00122028, 0x00142129, 0x0014212a, 0x0014212b, 0x0014212b, 0x0014212b, 0x0014212b, 0x0014212c, 0x0014222d, 0x0013222d, 0x0013222d, 0x0012212c, 0x00121d27, 0x0010171f, 0x000b1015, 0x00080b0f, 0x00040609, 0x00030407, 0x00030408, 0x00020408, 0x00020308, 0x00010305, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020404, 0x00020404, 0x00020405, 0x00040509, 0x00070911, 0x00151d28, 0x0030404d, 0x003b505f, 0x003b5364, 0x003c5568, 0x003a5466, 0x00385063, 0x00354c5f, 0x00344a5b, 0x00344858, 0x00314655, 0x00304454, 0x002e4251, 0x002c3d4d, 0x00283a4a, 0x00263745, 0x00243341, 0x0022303c, 0x00212c3a, 0x00202a38, 0x001d2735, 0x001a2533, 0x0017222e, 0x00141f2b, 0x00111b24, 0x00101821, 0x0011181f, 0x0010141c, 0x000c1218, 0x00091013, 0x00070b0e, 0x00040809, 0x00020507, 0x00020508, 0x0004060a, 0x0006080c, 0x00080c10, 0x00090e14, 0x000b1016, 0x000b1014, 0x00090e10, 0x00080c0f, 0x00080b0e, 0x0006090c, 0x0006090c, 0x0004080c, 0x00080c10, 0x00161b20, 0x00252a33, 0x002e333c, 0x002e3540, 0x002c3540, 0x002b3541, 0x002c3a47, 0x00303f4c, 0x0033404f, 0x00344350, 0x00304450, 0x00334653, 0x00314451, 0x00314453, 0x002f4250, 0x002a3c4a, 0x00243643, 0x00253643, 0x00243440, 0x00243440, 0x0020303c, 0x0022303c, 0x0025333e, 0x0026343f, 0x0024323d, 0x001e2c37, 0x0017242f, 0x00182630, 0x00182630, 0x00182730, 0x00192730, 0x001f2c36, 0x00202e38, 0x001d2c35, 0x001b2b32, 0x0018272f, 0x0016242c, 0x000e1820, 0x0010161d, 0x0010161c, 0x0010181d, 0x00101820, 0x00141c24, 0x00141c24, 0x00111922, 0x00141c25, 0x0010181f, 0x0010141c, 0x000f141b, 0x00181f27, 0x00182028, 0x00141d26, 0x00141d27, 0x00151f28, 0x0018212a, 0x00131c23, 0x00141c24, 0x00101921, 0x000f181f, 0x00151d24, 0x001a2329, 0x00192229, 0x00141c25, 0x001c242d, 0x001b242d, 0x001b262f, 0x0018252e, 0x001c2933, 0x00202c35, 0x0026333c, 0x001c2a34, 0x00202d37, 0x0024303a, 0x00202c38, 0x001c2a37, 0x00253341, 0x00283844, 0x002b3c48, 0x002b3c49, 0x002a3d49, 0x002a3d49, 0x002b3e4b, 0x002f4250, 0x002f4450, 0x002e4451, 0x002d4451, 0x00304553, 0x00273c49, 0x00293e4b, 0x002b404e, 0x002b424f, 0x00283f4c, 0x00263c4a, 0x00273d4b, 0x002b414f, 0x002e4350, 0x00314250, 0x00334050, 0x00323c4b, 0x00313a46, 0x00313844, 0x00333844, 0x00343844, 0x00333844, 0x00323844, 0x00323844, 0x00313743, 0x00333743, 0x00323642, 0x00313541, 0x00303440, 0x00303440, 0x00323643, 0x00353a48, 0x00373e4c, 0x00353d4a, 0x00272f3c, 0x00141a28, 0x000c111d, 0x000c111c, 0x000d111c, 0x0010141c, 0x0010151d, 0x0010141c, 0x000f141c, 0x000e131b, 0x000a0f17, 0x00060a13, 0x0006080f, 0x0005050c, 0x0007080e, 0x000a0b12, 0x000f131b, 0x00151c25, 0x0018232c, 0x00182631, 0x001b2a35, 0x001e2c38, 0x001f303b, 0x0021323e, 0x00243541, 0x00263745, 0x00293a4a, 0x002c3e4f, 0x002f4153, 0x00304455, 0x00314557, 0x00334658, 0x00324558, 0x00304556, 0x00324758, 0x0034495a, 0x00344a5c, 0x00364e60, 0x003b5364, 0x003a5466, 0x00385466, 0x00385364, 0x00365060, 0x00344b5b, 0x002c3c4c, 0x0019242f, 0x00040b11, 0x00010508, 0x00020404, 0x00010303, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020308, 0x00020308, 0x00030408, 0x00030509, 0x0004070c, 0x00070b12, 0x000c1219, 0x00101b23, 0x0014222c, 0x00152630, 0x00152733, 0x00152834, 0x00142834, 0x00142734, 0x00142734, 0x00142631, 0x00142430, 0x0013242d, 0x0013222c, 0x0012222b, 0x0012212c, 0x00101f2a, 0x00101d29, 0x00101e2a, 0x00111f2b, 0x00121f2b, 0x00121f2b, 0x00121f2b, 0x00121f2b, 0x00121f2b, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0013282e, 0x00112a30, 0x00142e34, 0x00143036, 0x0016363b, 0x00183a3e, 0x00183f43, 0x001a4347, 0x001c474b, 0x001d4b4e, 0x001e4e51, 0x001f5154, 0x00205458, 0x0021575a, 0x0021585b, 0x00225a5c, 0x00235b5e, 0x00235b5e, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x00235a5c, 0x0022595c, 0x00235a5c, 0x0021585c, 0x0021585b, 0x0021575a, 0x00205659, 0x00205458, 0x00205457, 0x00205457, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x001f5154, 0x001f5154, 0x001e5054, 0x001e4f53, 0x001d4e51, 0x001c4b4e, 0x001c474b, 0x001a4448, 0x001a4245, 0x00183d41, 0x00183a3e, 0x0015363b, 0x00143036, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121c24, 0x00131d25, 0x00131e28, 0x00122029, 0x0011202a, 0x0013212a, 0x00142129, 0x0014222a, 0x0014222b, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222d, 0x0014222d, 0x0013222d, 0x0012202a, 0x000e1821, 0x000c1119, 0x00080c10, 0x0005070c, 0x00040408, 0x00030407, 0x00030408, 0x00020308, 0x00020308, 0x00010305, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020404, 0x00020404, 0x00020405, 0x00030408, 0x0006080f, 0x00111a24, 0x002c3b48, 0x00374b5a, 0x00385060, 0x00385164, 0x00375062, 0x00344c5f, 0x00344a5c, 0x00334858, 0x00324656, 0x00304454, 0x002f4351, 0x002d404f, 0x002b3c4c, 0x00283948, 0x00253644, 0x00243240, 0x00212e3c, 0x00202b38, 0x001f2836, 0x001c2634, 0x00192431, 0x0017222e, 0x00141e2a, 0x00131b26, 0x00121822, 0x00101720, 0x0010141d, 0x000e1218, 0x000b0f14, 0x00080c10, 0x0006080c, 0x00040609, 0x00040508, 0x00040609, 0x0004070a, 0x00070a0f, 0x000a0e14, 0x000c1016, 0x000b1014, 0x00090e10, 0x00080c10, 0x00080b0e, 0x0006090c, 0x0006090d, 0x0004080c, 0x0004080c, 0x000d1015, 0x001c2028, 0x00282d36, 0x002c343e, 0x002d3540, 0x002c3641, 0x002f3a46, 0x00303c48, 0x00313c48, 0x00323e4a, 0x0032404c, 0x00344350, 0x00314250, 0x00304250, 0x002f4250, 0x002b3e4c, 0x00243643, 0x00273844, 0x00253440, 0x0024343f, 0x0020303b, 0x0022313c, 0x002b3844, 0x00293742, 0x00263440, 0x00202e39, 0x001b2833, 0x001c2a34, 0x0017242e, 0x0014212c, 0x0016242f, 0x0022303b, 0x00182731, 0x00182831, 0x001a2931, 0x0018282f, 0x0018262d, 0x000c171f, 0x000f171e, 0x0010161d, 0x00141c24, 0x00141c25, 0x00101822, 0x00161f28, 0x0018212a, 0x00171f28, 0x00141b24, 0x00131921, 0x000e141c, 0x00182029, 0x0019232c, 0x00151f28, 0x00141e28, 0x0016212a, 0x001a242d, 0x00141d26, 0x00151e27, 0x0019222c, 0x00121b24, 0x00172029, 0x001c242d, 0x001c242c, 0x00141d27, 0x001d2730, 0x001d2730, 0x0018232c, 0x0018242e, 0x001c2833, 0x00202c36, 0x0027333d, 0x001c2833, 0x001b2832, 0x0024303c, 0x001f2b39, 0x00202c3c, 0x00253241, 0x00273644, 0x002b3c49, 0x002a3c4a, 0x002a3c4b, 0x002c404c, 0x002b3e4c, 0x002d404f, 0x002c404e, 0x002c4150, 0x002c4350, 0x00304754, 0x00283d4b, 0x00283c4b, 0x002e4451, 0x002e4452, 0x002e4452, 0x002a404d, 0x002d4350, 0x002f4451, 0x002e414f, 0x00303f4d, 0x00313e4d, 0x00323c4a, 0x00333c47, 0x00343a45, 0x00343944, 0x00343844, 0x00343844, 0x00323844, 0x00323844, 0x00313743, 0x00333743, 0x00313542, 0x00303440, 0x00303440, 0x00303540, 0x00343844, 0x00373c49, 0x00363c4a, 0x002f3643, 0x001d2430, 0x000f1422, 0x000c111d, 0x000c111b, 0x000d111b, 0x000f141c, 0x0010141c, 0x000f141c, 0x000e121a, 0x000c1018, 0x00080c14, 0x00040810, 0x0005080e, 0x0004060b, 0x0007080f, 0x000b0d14, 0x0010161e, 0x00161d27, 0x0017232b, 0x00182630, 0x00192934, 0x001c2c38, 0x001d2e3a, 0x0020303e, 0x00233440, 0x00253644, 0x00283849, 0x002b3c4c, 0x002e3f50, 0x00304354, 0x00314555, 0x00334656, 0x00324556, 0x00314557, 0x00324658, 0x00324859, 0x0034495c, 0x00344b5e, 0x00374f61, 0x00385063, 0x00365062, 0x00354f60, 0x00344c5d, 0x00324757, 0x00283744, 0x00141d26, 0x0002080e, 0x00020508, 0x00020404, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020308, 0x00020308, 0x00030408, 0x00030408, 0x0003050a, 0x0004080d, 0x00080c13, 0x000c131a, 0x00101c24, 0x0014232c, 0x00162631, 0x00152935, 0x00142936, 0x00142836, 0x00152835, 0x00162733, 0x00152631, 0x0014252f, 0x0014242d, 0x0014242c, 0x0013222c, 0x0011202c, 0x00111f2b, 0x00121f2b, 0x0013202c, 0x0014212c, 0x0014212c, 0x0014212c, 0x0014212c, 0x0014212c, 0x000d1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0013242c, 0x0011282e, 0x00132c32, 0x00142e34, 0x00143338, 0x0016363b, 0x00183c40, 0x00183f43, 0x001a4347, 0x001c474b, 0x001d4a4d, 0x001d4c50, 0x001e4f51, 0x001f5154, 0x00205254, 0x00205457, 0x00205558, 0x00205558, 0x00215659, 0x00215659, 0x00215659, 0x00205558, 0x00205457, 0x00205457, 0x00205356, 0x00205254, 0x00205254, 0x001f5154, 0x001f5053, 0x001e5053, 0x001e4f51, 0x001e4f51, 0x001e4f51, 0x001e4f51, 0x001d4d50, 0x001d4d50, 0x001d4d50, 0x001d4c50, 0x001d4c50, 0x001c4a4d, 0x001c484c, 0x001c474b, 0x001b4448, 0x001a4245, 0x00183d41, 0x00183a3e, 0x0016363b, 0x00143338, 0x00142e34, 0x00132c32, 0x0010282e, 0x0013242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121d26, 0x00141f28, 0x00142028, 0x00142129, 0x0014212a, 0x0015222a, 0x0015222a, 0x0016232b, 0x0014232b, 0x0015232b, 0x0015232b, 0x0015232b, 0x0014222b, 0x0014222b, 0x0014222b, 0x0014222c, 0x0013202a, 0x00101c25, 0x000b131b, 0x00070c13, 0x0005080d, 0x0004050a, 0x00030408, 0x00020307, 0x00000206, 0x00010207, 0x00010206, 0x00000206, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00020404, 0x00020404, 0x00020404, 0x00020405, 0x00020408, 0x0003070c, 0x00101820, 0x00293844, 0x00334956, 0x00344c5c, 0x00364d5e, 0x00354c5d, 0x0033495c, 0x00324759, 0x00314556, 0x002f4454, 0x002e4453, 0x002c4250, 0x002c3f4d, 0x00293b49, 0x00273846, 0x00243543, 0x0023313e, 0x00202e3a, 0x001e2a36, 0x001c2833, 0x00192530, 0x0018242e, 0x0015202c, 0x00141e29, 0x00131c26, 0x00121923, 0x00101720, 0x000f141d, 0x000e1219, 0x000b1016, 0x00090e14, 0x00080c10, 0x0005080c, 0x0004060a, 0x00040609, 0x00040609, 0x0006080c, 0x00090b10, 0x000c0d13, 0x000c0e13, 0x000b0e12, 0x000a0d11, 0x00080c10, 0x0008090e, 0x0008090d, 0x0006080c, 0x0004070a, 0x0008090d, 0x0014151c, 0x0022252d, 0x002a2f39, 0x002d343f, 0x002e3641, 0x00303945, 0x00303a45, 0x002f3842, 0x00303944, 0x00313c48, 0x0032404c, 0x0031404d, 0x002f414e, 0x002c414e, 0x002c3e4b, 0x00263744, 0x00293946, 0x00273643, 0x00243340, 0x001f2f3b, 0x0022313d, 0x002e3d49, 0x00283944, 0x0023333e, 0x0020303b, 0x001d2b35, 0x00222f38, 0x0015212c, 0x00121d28, 0x0016232f, 0x00202d39, 0x00182531, 0x001b2834, 0x001d2b34, 0x001b2832, 0x001b2830, 0x00141d26, 0x00141c25, 0x00151e27, 0x00151e28, 0x00131c26, 0x00111b26, 0x0017202b, 0x001a242c, 0x0019222b, 0x00151e27, 0x0019222a, 0x00101921, 0x00182029, 0x0018222b, 0x00151f28, 0x00141e27, 0x0014202a, 0x0018222c, 0x0018222c, 0x0017212c, 0x001a2430, 0x0017222d, 0x0018242e, 0x001c2530, 0x001c2530, 0x0016202a, 0x00202a34, 0x00202b35, 0x001c2832, 0x001b2731, 0x001c2834, 0x0023303b, 0x00273440, 0x001c2b35, 0x00182732, 0x0022303c, 0x00253340, 0x00253442, 0x00253442, 0x00243543, 0x00293b49, 0x00293b49, 0x00293c49, 0x002c3f4d, 0x002c404e, 0x00314554, 0x002d4252, 0x002d4151, 0x002e4352, 0x00344858, 0x002a3f4d, 0x00293e4d, 0x002d424f, 0x002d434f, 0x00304752, 0x002f4450, 0x00314452, 0x00334553, 0x0031404f, 0x00303d4c, 0x00303c4a, 0x00303b48, 0x00323b47, 0x00343945, 0x00333844, 0x00333844, 0x00323844, 0x00323844, 0x00323844, 0x00333843, 0x00333743, 0x00323642, 0x00323642, 0x00323643, 0x00343844, 0x00363c48, 0x00373d48, 0x00303843, 0x00222a35, 0x00101722, 0x000b111b, 0x000c111a, 0x000c1118, 0x000c1218, 0x000e1319, 0x000e1419, 0x000d1219, 0x000d1118, 0x000b0d14, 0x00080a10, 0x0005080c, 0x0004070b, 0x00040609, 0x0007080e, 0x000b0e16, 0x00121720, 0x00161d28, 0x0017222c, 0x00182530, 0x00182834, 0x001a2b37, 0x001c2d39, 0x001f303c, 0x0022323f, 0x00243442, 0x00283848, 0x002a3a4a, 0x002c3c4c, 0x00304151, 0x00304454, 0x00334656, 0x00344657, 0x00344658, 0x00334658, 0x00324759, 0x0031485a, 0x0033495c, 0x00344c5e, 0x00364d60, 0x00354c5f, 0x00344c5e, 0x0032495a, 0x00304352, 0x0024323d, 0x000f171e, 0x0002070c, 0x00010407, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010205, 0x00010205, 0x00010305, 0x00020306, 0x00030408, 0x0003060b, 0x0005080d, 0x00080d12, 0x000c141a, 0x00121d25, 0x0014242d, 0x00152835, 0x00142938, 0x00152938, 0x00152837, 0x00152834, 0x00152733, 0x00152530, 0x00152530, 0x0014242e, 0x0013222d, 0x0011202c, 0x0012202c, 0x0013202c, 0x0013212c, 0x0013232d, 0x0012232e, 0x0012232d, 0x0011232d, 0x0012222d, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00112a30, 0x00132c32, 0x00143036, 0x00153439, 0x0016383c, 0x00183c40, 0x00183f43, 0x001a4245, 0x001b4448, 0x001c474b, 0x001d4a4d, 0x001d4c50, 0x001d4d50, 0x001e4f51, 0x001e4f51, 0x001e5053, 0x001e5053, 0x001e5053, 0x001e5053, 0x001e5053, 0x001e4f51, 0x001e4f51, 0x001e4f51, 0x001e4d50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4b4e, 0x001d4b4e, 0x001d4b4e, 0x001d4b4e, 0x001c4a4d, 0x001d4a4d, 0x001d4a4d, 0x001d4a4d, 0x001c484c, 0x001c474b, 0x001b4649, 0x001b4448, 0x001a4347, 0x00194044, 0x00183d41, 0x00183a3e, 0x0016363b, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00111f27, 0x00132028, 0x00142028, 0x00142128, 0x00142129, 0x00152029, 0x00152028, 0x00152028, 0x00122027, 0x00132026, 0x00122025, 0x00111f24, 0x00111f24, 0x00121f26, 0x00131f26, 0x00101d24, 0x000f1920, 0x000c141b, 0x00080d14, 0x0005080e, 0x0004040a, 0x00020308, 0x00020306, 0x00000205, 0x00000206, 0x00000206, 0x00000206, 0x00000206, 0x00000205, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00020404, 0x00020404, 0x00020404, 0x00020405, 0x00020407, 0x0003070c, 0x000e161e, 0x00253640, 0x00304652, 0x00334a57, 0x00344959, 0x0034485a, 0x00314658, 0x00314557, 0x002f4454, 0x002c4251, 0x002c4352, 0x002c4050, 0x002a3c4c, 0x00283948, 0x00263744, 0x00243440, 0x0021303c, 0x001e2d38, 0x001c2935, 0x001c2731, 0x0018242f, 0x0017222c, 0x0014202a, 0x00141c27, 0x00121a25, 0x00111822, 0x00101620, 0x000f141c, 0x000d1119, 0x000a1016, 0x000a0f15, 0x00080c11, 0x0005080c, 0x0004060b, 0x00040609, 0x00040609, 0x00040609, 0x0008090c, 0x000b0c10, 0x000b0d12, 0x000a0d12, 0x00090c11, 0x00080c10, 0x00090a10, 0x0008090d, 0x0007080c, 0x0006080a, 0x00050708, 0x000a0c10, 0x00181a21, 0x00262933, 0x002c323d, 0x002e3642, 0x00303844, 0x002f3842, 0x002e3640, 0x002e3740, 0x00303944, 0x002f3b47, 0x002e3c49, 0x002e404c, 0x002c404c, 0x00293d49, 0x00243643, 0x002a3c48, 0x00283845, 0x00253441, 0x0020303c, 0x00243540, 0x00293946, 0x002a3b46, 0x00243540, 0x0020303c, 0x00202d38, 0x0025303c, 0x0015202c, 0x00131d28, 0x00182430, 0x00212d39, 0x001c2834, 0x001c2934, 0x001f2c36, 0x001b2831, 0x001a242e, 0x001a232c, 0x00161e28, 0x00151f29, 0x00141e28, 0x000e1824, 0x00141e2b, 0x0018222c, 0x0017212b, 0x0018222b, 0x00141f28, 0x001b242d, 0x0019232c, 0x0017212a, 0x00141f28, 0x00121c25, 0x00141d27, 0x0018232e, 0x0016212c, 0x0017222c, 0x0018232e, 0x001a2632, 0x001c2834, 0x00202c35, 0x001f2b34, 0x001a2530, 0x0017232d, 0x00202c36, 0x00212d37, 0x00202c37, 0x001a2832, 0x001c2a36, 0x00283541, 0x00293844, 0x0024343f, 0x0022323d, 0x00273643, 0x00283844, 0x00293a46, 0x00283a46, 0x00243844, 0x00263846, 0x00263846, 0x00283b49, 0x002b3f4c, 0x002d4250, 0x00364b5a, 0x00344858, 0x00324655, 0x00304454, 0x00354a5a, 0x002e4354, 0x002c4050, 0x00283d4a, 0x002b404c, 0x002f4550, 0x002f4450, 0x0030424f, 0x0033424f, 0x00333f4c, 0x00303c49, 0x002f3a46, 0x002f3945, 0x00303944, 0x00323844, 0x00323844, 0x00323844, 0x00323844, 0x00323844, 0x00333844, 0x00333843, 0x00333743, 0x00333743, 0x00343844, 0x00363b47, 0x00383c48, 0x00373e49, 0x00353d47, 0x0028303a, 0x00151d26, 0x000a121a, 0x00091118, 0x000c1118, 0x000c1216, 0x000c1216, 0x000c1216, 0x000c1216, 0x000c1016, 0x000b0e14, 0x00090b11, 0x0007080d, 0x00040609, 0x00030508, 0x00030508, 0x0006080d, 0x000b0e16, 0x00121821, 0x00161e28, 0x0018222c, 0x00182430, 0x00182732, 0x001b2a36, 0x001d2c38, 0x001f2e3c, 0x0022313e, 0x00243340, 0x00273644, 0x00283948, 0x002b3c4a, 0x002e3f4e, 0x00304352, 0x00324555, 0x00344657, 0x00344658, 0x00334658, 0x00314759, 0x00304759, 0x0031485a, 0x00334a5c, 0x00334b5c, 0x00334b5c, 0x00324a5c, 0x00304757, 0x002d3f4d, 0x00202c38, 0x000b1119, 0x0002060a, 0x00010407, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020405, 0x00020507, 0x00030708, 0x00050a0c, 0x00080e14, 0x000e171c, 0x00121e27, 0x00152633, 0x00152938, 0x00162939, 0x00152838, 0x00152835, 0x00152734, 0x00152731, 0x00142530, 0x0014242f, 0x0012242e, 0x0011222c, 0x0011212c, 0x0011222c, 0x0012222d, 0x0011242e, 0x0011242e, 0x0010242d, 0x0010232d, 0x0010232d, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00132c32, 0x00143036, 0x00153439, 0x0017383c, 0x00173a3e, 0x00183d41, 0x00194044, 0x001a4347, 0x001b4448, 0x001c4649, 0x001c474b, 0x001c484c, 0x001c4a4d, 0x001c4a4d, 0x001d4a4d, 0x001d4a4d, 0x001d4a4d, 0x001d4a4d, 0x001c4a4d, 0x001c4a4d, 0x001c484c, 0x001c484c, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c4649, 0x001b4649, 0x001b4649, 0x001b4649, 0x001c4649, 0x001a4448, 0x001b4448, 0x001a4347, 0x001a4347, 0x001a4245, 0x00194044, 0x00183f43, 0x00183c40, 0x00183a3e, 0x0016363b, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00122028, 0x00122028, 0x00132028, 0x00131f27, 0x00131f27, 0x00141d26, 0x00131c25, 0x00131b24, 0x000f1a20, 0x000e181f, 0x000d181e, 0x000c171c, 0x000c151c, 0x000d161c, 0x000e161c, 0x000d151b, 0x000c1218, 0x00090d13, 0x0006090e, 0x0003060a, 0x00010408, 0x00020406, 0x00010404, 0x00000205, 0x00000205, 0x00000205, 0x00000205, 0x00000205, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010404, 0x00020404, 0x00020404, 0x00020404, 0x00020404, 0x00020406, 0x0004080b, 0x000c141b, 0x0024343c, 0x002f444f, 0x00304754, 0x00304556, 0x00304557, 0x00304556, 0x00314556, 0x00304454, 0x002e4352, 0x002c4251, 0x002b4050, 0x00293c4c, 0x00283848, 0x00243644, 0x0022333f, 0x0020303b, 0x001d2c37, 0x001b2834, 0x001a2630, 0x0018242e, 0x0016212c, 0x00141f29, 0x00131c27, 0x00121a25, 0x00111822, 0x000f151f, 0x000e141c, 0x000d1119, 0x000a1017, 0x00090f15, 0x00080d11, 0x0005080d, 0x0004060b, 0x00040609, 0x00040609, 0x00040609, 0x0006080b, 0x00090b0e, 0x000a0c10, 0x00090c11, 0x00090c11, 0x00080c10, 0x00080a10, 0x0008090d, 0x0007080c, 0x0005070a, 0x00040608, 0x0005070b, 0x000e1016, 0x001d2029, 0x00272c36, 0x002b333d, 0x002c3440, 0x002e343e, 0x002e343d, 0x002f353f, 0x00303742, 0x002d3843, 0x002c3944, 0x002f3f4c, 0x002c3f4b, 0x00283b47, 0x00263845, 0x0030414e, 0x002c3c49, 0x00253643, 0x0021333e, 0x00293b47, 0x00273844, 0x00293a45, 0x00263741, 0x0020303c, 0x00202e39, 0x00232f3a, 0x00182430, 0x0017232d, 0x001d2934, 0x0024303b, 0x00222e39, 0x001b2833, 0x001c2933, 0x0018252f, 0x0016212b, 0x001b242f, 0x001a232c, 0x0018232c, 0x0018222c, 0x00101924, 0x0019242e, 0x001b252f, 0x00141d27, 0x00141f28, 0x00152028, 0x0018232c, 0x001c262e, 0x0019242c, 0x00141f28, 0x00131c25, 0x00151f28, 0x001a2530, 0x0016212c, 0x0018242e, 0x0018242f, 0x001b2632, 0x001d2934, 0x0024323c, 0x0026343d, 0x001f2c35, 0x00202c36, 0x00232f38, 0x001f2c36, 0x001e2c35, 0x0016242e, 0x001a2833, 0x0023323d, 0x00283944, 0x00283a44, 0x00273844, 0x00283a46, 0x002a3c48, 0x002b3c48, 0x002a3d49, 0x002a3c48, 0x00253844, 0x00223443, 0x002a3c4b, 0x002c404d, 0x002e4452, 0x00364c5c, 0x00364c5c, 0x00344b5a, 0x00304555, 0x0034495a, 0x00304456, 0x002a3f4e, 0x00253a48, 0x002c414d, 0x00304551, 0x00324450, 0x0032414e, 0x00323d4b, 0x00313a48, 0x00303845, 0x00303844, 0x00303844, 0x00313844, 0x00323844, 0x00323844, 0x00323844, 0x00323844, 0x00323844, 0x00323843, 0x00333844, 0x00333843, 0x00343844, 0x00363b46, 0x00393e49, 0x00393f4a, 0x00383f4a, 0x002f3740, 0x001f2730, 0x000e151c, 0x00081016, 0x00091117, 0x000c1218, 0x000c1216, 0x000c1216, 0x000c1216, 0x000c1116, 0x000b0f15, 0x00080c12, 0x00070810, 0x0005070c, 0x00040508, 0x00020508, 0x00030609, 0x00070a0f, 0x000c1018, 0x00141822, 0x00171e28, 0x0018222b, 0x0019242e, 0x001a2732, 0x001c2935, 0x001e2c38, 0x00202d3b, 0x0021303d, 0x0022313f, 0x00253443, 0x00283846, 0x002a3b48, 0x002d3e4c, 0x00304351, 0x00324554, 0x00334556, 0x00334557, 0x00334557, 0x00314558, 0x00304558, 0x00304758, 0x00314859, 0x00314959, 0x00314959, 0x00304858, 0x002d4353, 0x00293a48, 0x001b2731, 0x00070e15, 0x00010509, 0x00020407, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00030407, 0x00030507, 0x00040709, 0x0004090c, 0x00091015, 0x000f181f, 0x0013202c, 0x00162734, 0x00172937, 0x00152936, 0x00162834, 0x00162834, 0x00152731, 0x00142530, 0x0014242f, 0x0012242e, 0x0011232d, 0x0011232d, 0x0012242e, 0x0013242f, 0x0012252f, 0x0011252f, 0x0011242f, 0x0011242e, 0x0011242e, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00132c32, 0x00143036, 0x00143338, 0x0016363b, 0x0017383c, 0x00183c40, 0x00183d41, 0x00183f43, 0x00194044, 0x001a4245, 0x001a4347, 0x001a4347, 0x001b4448, 0x001c4448, 0x001c4448, 0x001c4448, 0x001c4448, 0x001b4448, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4245, 0x001a4245, 0x00194245, 0x00194245, 0x00194044, 0x00194044, 0x00194044, 0x00194044, 0x001a4044, 0x00194044, 0x00183f43, 0x00183d41, 0x00183d41, 0x00183c40, 0x00173a3e, 0x0017383c, 0x0016363b, 0x00153338, 0x00143036, 0x00132c32, 0x00112a30, 0x0010282e, 0x0013242c, 0x00102229, 0x00102229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101e26, 0x00111e26, 0x00101d24, 0x00101c24, 0x00101a23, 0x000f1820, 0x000e1720, 0x000e141d, 0x000b121a, 0x00091016, 0x00080f14, 0x00070f14, 0x00060d14, 0x00080f15, 0x000a1016, 0x00091014, 0x000a0d13, 0x00070a0e, 0x0004070c, 0x00020408, 0x00010406, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000104, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x0004050a, 0x000c1118, 0x0022303a, 0x002d424e, 0x002e4454, 0x002d4454, 0x002d4454, 0x002f4454, 0x00304455, 0x00304455, 0x002e4352, 0x002d4151, 0x002c3f4f, 0x00293b4b, 0x00273847, 0x00243543, 0x0021323e, 0x001f2e39, 0x001c2b36, 0x001a2833, 0x00192530, 0x0017232c, 0x0015202b, 0x00131e28, 0x00121b26, 0x00121924, 0x00101721, 0x000f151f, 0x000d141c, 0x000d1119, 0x000c1118, 0x00091015, 0x00080c12, 0x0005090e, 0x0003070b, 0x00030609, 0x00040609, 0x00040508, 0x00040508, 0x0006080b, 0x00080a0f, 0x000a0c11, 0x00090c10, 0x00080c10, 0x00080b10, 0x0008090d, 0x0007080c, 0x0005070a, 0x00040609, 0x00040509, 0x0006080e, 0x0011151c, 0x001e242c, 0x00282e39, 0x002c323d, 0x002d323c, 0x002d323c, 0x002f343f, 0x00303641, 0x002d3641, 0x002c3843, 0x002f3d48, 0x002c3d48, 0x00273844, 0x00293c48, 0x00364854, 0x002e404c, 0x00273844, 0x00213440, 0x002a3c48, 0x00283a46, 0x00283a44, 0x00273742, 0x0024343f, 0x00202e39, 0x001d2a34, 0x00182530, 0x00192630, 0x00202d37, 0x0024323c, 0x0028353f, 0x001e2b35, 0x001c2933, 0x00192530, 0x0014202b, 0x0019242e, 0x001c2630, 0x001a242e, 0x001b242d, 0x00162029, 0x00222c35, 0x001b242d, 0x00121c24, 0x00111c24, 0x00151f28, 0x0018222b, 0x001a242c, 0x0019232c, 0x00152028, 0x00101a23, 0x0018212b, 0x001d2833, 0x001e2a34, 0x0018242f, 0x001a2631, 0x001b2733, 0x001d2a35, 0x0024323c, 0x00283740, 0x0024323c, 0x00243039, 0x0024303a, 0x001e2b34, 0x001c2a34, 0x00192731, 0x00182632, 0x00202f3a, 0x00273842, 0x00283a44, 0x00263944, 0x00283a47, 0x002b3d49, 0x002c3e4b, 0x00293c48, 0x002c3c4a, 0x00263745, 0x00223543, 0x002d404e, 0x002d414f, 0x00304453, 0x00364c5c, 0x00354c5b, 0x00344a59, 0x002f4554, 0x00334959, 0x00304454, 0x00283c4c, 0x00273c49, 0x002f4450, 0x00324551, 0x00334350, 0x00313f4c, 0x00303947, 0x00303844, 0x00303744, 0x00303744, 0x00303844, 0x00313844, 0x00323844, 0x00323844, 0x00323844, 0x00323844, 0x00313843, 0x00313843, 0x00313844, 0x00323844, 0x00353a46, 0x00383c48, 0x00393e49, 0x00383e49, 0x00343a45, 0x00252c36, 0x00151b23, 0x000c1118, 0x000a1016, 0x000c1218, 0x000c1218, 0x000c1215, 0x000c1215, 0x000c1216, 0x000c1116, 0x000a0f14, 0x00060910, 0x0004060d, 0x0004050b, 0x00030508, 0x00040508, 0x00040709, 0x00080b10, 0x000e1218, 0x00141a23, 0x00171f28, 0x0018212c, 0x00192430, 0x001c2833, 0x001d2b36, 0x001f2c39, 0x00202d3b, 0x0020303c, 0x0022313e, 0x00243441, 0x00273645, 0x00293a47, 0x002c3e4c, 0x002f4150, 0x00314454, 0x00324455, 0x00324456, 0x00324456, 0x00304556, 0x00304556, 0x00304556, 0x00304557, 0x00304657, 0x00304758, 0x002f4556, 0x002c4050, 0x00273542, 0x0017202b, 0x00030a10, 0x00000408, 0x00020406, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00030406, 0x00040406, 0x00040508, 0x00030709, 0x00050b10, 0x00091018, 0x000e1924, 0x0013202d, 0x00162633, 0x00162834, 0x00162834, 0x00162833, 0x00152731, 0x00142530, 0x0014242f, 0x0013242e, 0x0012242e, 0x0013242e, 0x00142430, 0x00142530, 0x00132630, 0x00122730, 0x00112630, 0x0012252f, 0x0012242f, 0x000d1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x00102229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00132c32, 0x00142e34, 0x00143036, 0x00153439, 0x0016363b, 0x0017383c, 0x00183a3e, 0x00183c40, 0x00183c40, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183f43, 0x00183f43, 0x00183f43, 0x00183f43, 0x00183f43, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183c40, 0x00183c40, 0x00183c40, 0x00183c40, 0x00183c40, 0x00183c40, 0x00173a3e, 0x00183a3e, 0x0017383c, 0x0016363b, 0x00143439, 0x00143338, 0x00143036, 0x00142e34, 0x00132c32, 0x00112a30, 0x0011282e, 0x0012242c, 0x0012242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101922, 0x000f1821, 0x000d161e, 0x000c141c, 0x000a1219, 0x00081017, 0x00080f16, 0x00080c14, 0x00060a11, 0x00040a0f, 0x0003090e, 0x0004080e, 0x0003080d, 0x0004080d, 0x0005090e, 0x0006090e, 0x0005080c, 0x00040509, 0x00030408, 0x00020307, 0x00030304, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010306, 0x0004040a, 0x000a0f16, 0x00202c36, 0x002c3f4c, 0x002d4351, 0x002d4353, 0x002c4353, 0x002d4454, 0x00304455, 0x00304454, 0x002f4252, 0x002e4050, 0x002b3d4d, 0x0029394a, 0x00263646, 0x00233442, 0x0020303d, 0x001e2c38, 0x001c2a35, 0x00192732, 0x0018242f, 0x0016222c, 0x0014202a, 0x00131d27, 0x00121b25, 0x00121924, 0x00101821, 0x000f151f, 0x000d141c, 0x000d1118, 0x000c1017, 0x00090f14, 0x00080c11, 0x00050a0e, 0x0004070b, 0x00040609, 0x00040609, 0x00040508, 0x00030408, 0x00040508, 0x0007080c, 0x000a0c10, 0x00090c10, 0x00080c10, 0x00080b10, 0x0008090d, 0x0008090c, 0x0006080b, 0x0005070a, 0x00040509, 0x0004050c, 0x00090c13, 0x00171a22, 0x00242832, 0x00282f39, 0x002c313c, 0x002d323c, 0x0030343f, 0x00303641, 0x002e3541, 0x002d3643, 0x002f3c48, 0x002f3e4a, 0x00273844, 0x00293c48, 0x00344854, 0x00304450, 0x00283b47, 0x00243743, 0x00283b47, 0x00283945, 0x00283943, 0x00263741, 0x00263540, 0x00202f39, 0x00202e38, 0x001b2832, 0x00182630, 0x00202d38, 0x0024333d, 0x002c3944, 0x0022303c, 0x001c2a35, 0x001e2a36, 0x00192530, 0x001b2630, 0x001c2530, 0x0017212a, 0x001a242d, 0x001f2834, 0x00202b36, 0x001b242e, 0x00141f28, 0x00121c25, 0x00131c25, 0x00162029, 0x001b242d, 0x0019242c, 0x0019242c, 0x00101b24, 0x00141e28, 0x001a2630, 0x001c2933, 0x001e2b34, 0x001b2732, 0x001a2732, 0x001c2a35, 0x0021303a, 0x00273640, 0x0026353e, 0x00243039, 0x00222e38, 0x00202c37, 0x00222f38, 0x00202f38, 0x001e2c38, 0x00233340, 0x00273844, 0x00283945, 0x00283a45, 0x00293c48, 0x002a3d49, 0x00293c48, 0x002b3d4a, 0x00283a47, 0x00283948, 0x00253846, 0x002c3f4d, 0x002e4250, 0x00304654, 0x00344b59, 0x00334958, 0x00314857, 0x00304756, 0x00304655, 0x002e4252, 0x002c404d, 0x002e424e, 0x00304450, 0x00334350, 0x0032404c, 0x00303a46, 0x002f3744, 0x00303744, 0x00303744, 0x00303744, 0x00313844, 0x00313844, 0x00323844, 0x00323844, 0x00323844, 0x00323843, 0x00303742, 0x00313843, 0x00313844, 0x00333944, 0x00353b46, 0x00393d49, 0x00393e49, 0x00373c48, 0x002c323c, 0x001c212c, 0x000e131b, 0x000c1016, 0x000c1016, 0x000d1017, 0x000c1016, 0x000c1114, 0x000c1014, 0x000c1015, 0x000b1014, 0x00080c12, 0x0004080e, 0x0004050c, 0x0004050a, 0x00040508, 0x00040609, 0x0004070b, 0x00080c11, 0x000f141b, 0x00161c24, 0x00171f29, 0x0018222e, 0x00182431, 0x001a2734, 0x001c2a38, 0x001e2b38, 0x00202c3a, 0x00202e3c, 0x0022303f, 0x00233240, 0x00263444, 0x00283847, 0x002c3c4c, 0x002f4051, 0x00304254, 0x00314454, 0x00314455, 0x00314455, 0x00304455, 0x00304455, 0x002f4455, 0x002e4454, 0x002e4454, 0x002f4454, 0x002d4354, 0x002a3d4c, 0x0022303c, 0x00101820, 0x0002080c, 0x00010406, 0x00020405, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00030304, 0x00030405, 0x00030406, 0x00040508, 0x0004080c, 0x00060b11, 0x0009111a, 0x00101924, 0x00131f2b, 0x0014222e, 0x0016242f, 0x00162530, 0x00142530, 0x0014242f, 0x0013242e, 0x0014242e, 0x0013242e, 0x0013242e, 0x00142430, 0x00142530, 0x00142630, 0x00122731, 0x00122630, 0x0012252f, 0x0013242f, 0x000d1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x00102229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00132c32, 0x00142e34, 0x00142e34, 0x00143036, 0x00143338, 0x00153439, 0x00143439, 0x0015363b, 0x0016363b, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0016363b, 0x0015363b, 0x0015363b, 0x0015363b, 0x0015363b, 0x0015363b, 0x0015363b, 0x0015363b, 0x00153439, 0x00153439, 0x00143338, 0x00153338, 0x00143036, 0x00142e34, 0x00132c32, 0x00132c32, 0x00112a30, 0x0011282e, 0x0013242c, 0x0012242c, 0x000f2229, 0x000f1f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c141b, 0x000b1219, 0x00080f16, 0x00080d14, 0x00070c12, 0x00060a10, 0x00050810, 0x0004080e, 0x0004070c, 0x0003060a, 0x00030609, 0x00040509, 0x00030509, 0x00020509, 0x00030509, 0x00030509, 0x00030408, 0x00030408, 0x00020307, 0x00010206, 0x00010205, 0x00010204, 0x00000204, 0x00010204, 0x00010204, 0x00000303, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010306, 0x00030409, 0x00080e14, 0x001c2a32, 0x002b3c47, 0x002d414f, 0x002d4251, 0x002c4352, 0x002d4353, 0x002f4454, 0x00304354, 0x00304151, 0x002e3f50, 0x002b3c4c, 0x00283848, 0x00263545, 0x00243340, 0x0021303c, 0x001f2c37, 0x001c2833, 0x00192530, 0x0018242f, 0x0015202c, 0x00151f2a, 0x00141e28, 0x00141c26, 0x00141a24, 0x00121822, 0x0010161f, 0x000e141c, 0x000c1118, 0x000b1017, 0x00090e13, 0x00080c10, 0x0006090e, 0x0005070c, 0x00040608, 0x00040508, 0x00030408, 0x00030407, 0x00040508, 0x00050709, 0x0008090d, 0x00090b0f, 0x00090c10, 0x00090b10, 0x00090a0f, 0x00090a0f, 0x0008090d, 0x0007080c, 0x0005070a, 0x0005070b, 0x0005080c, 0x000d1016, 0x001c1e26, 0x00252832, 0x002b2f3a, 0x002d323c, 0x002e343e, 0x002e3540, 0x002e3541, 0x002e3543, 0x00313a47, 0x00323e4b, 0x002d3c48, 0x002d3e4a, 0x0030424e, 0x00314450, 0x00293d49, 0x00263a45, 0x00283c48, 0x00283b47, 0x00263844, 0x00263742, 0x00243540, 0x00202f39, 0x0023303b, 0x00202f39, 0x001b2a34, 0x001c2a36, 0x0022313d, 0x00273542, 0x001b2a36, 0x001a2733, 0x00232f3b, 0x001b2630, 0x0016202b, 0x0018222c, 0x00142028, 0x0018232c, 0x00212d38, 0x001d2834, 0x00192430, 0x0018232d, 0x0017222c, 0x00131e28, 0x0018222c, 0x001d2830, 0x00172029, 0x00162028, 0x00141d27, 0x001a242c, 0x001c2831, 0x0014212b, 0x001a2831, 0x0024313c, 0x001d2b37, 0x00202f3a, 0x001f2f38, 0x0022323c, 0x002a3843, 0x00232f3a, 0x0024303b, 0x0024303c, 0x0024303c, 0x0024323c, 0x0022323d, 0x00243441, 0x002c3e4b, 0x002c3c49, 0x002c3e4b, 0x002c3f4c, 0x002a3c4a, 0x00263946, 0x002c3e4c, 0x002c404d, 0x002b3d4c, 0x00273c4a, 0x00293e4c, 0x002e4452, 0x002e4554, 0x002f4756, 0x002f4755, 0x00314855, 0x00324857, 0x00304654, 0x002f4351, 0x00324452, 0x00334451, 0x0031424f, 0x0030404c, 0x002f3b47, 0x002e3744, 0x002f3642, 0x00303643, 0x00313643, 0x00323844, 0x00333844, 0x00333844, 0x00323844, 0x00323844, 0x00323743, 0x00323742, 0x00323742, 0x00323843, 0x00333844, 0x00333944, 0x00363c46, 0x00383e48, 0x00383e48, 0x00323842, 0x00242a33, 0x00141820, 0x000c1018, 0x000c1016, 0x000c1016, 0x000c0f16, 0x000c1016, 0x000c1016, 0x000c1016, 0x000b0f15, 0x000a0e14, 0x00080b10, 0x0005080d, 0x0004060b, 0x00040609, 0x00040608, 0x00040609, 0x0004080c, 0x00090e14, 0x0010161d, 0x00151d24, 0x00151f28, 0x0016202c, 0x0017232f, 0x00182531, 0x001a2834, 0x001c2937, 0x001e2b38, 0x00202c3a, 0x00202f3d, 0x00223140, 0x00243442, 0x00273544, 0x002a3a49, 0x002d3e4f, 0x002f4153, 0x00304354, 0x00314455, 0x00314455, 0x00304454, 0x002f4454, 0x002f4454, 0x002e4454, 0x002e4454, 0x002d4252, 0x002b3f50, 0x00273947, 0x001e2c38, 0x000a141c, 0x0000070b, 0x00020508, 0x00020405, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00030304, 0x00030304, 0x00020405, 0x00020406, 0x0003060a, 0x0004080d, 0x00070c13, 0x000b1219, 0x000f1820, 0x00121c25, 0x00131e28, 0x00141f29, 0x00121f28, 0x00121f28, 0x00121f28, 0x0013202b, 0x0013222c, 0x0014242e, 0x0015242e, 0x00152530, 0x00152531, 0x00142631, 0x00142530, 0x0013242f, 0x0013242e, 0x000d1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x00102229, 0x0013242c, 0x0011242c, 0x0011282e, 0x00112a30, 0x00122c32, 0x00132c32, 0x00142e34, 0x00142e34, 0x00143036, 0x00143036, 0x00143036, 0x00153338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00153338, 0x00153338, 0x00153338, 0x00153338, 0x00143036, 0x00143036, 0x00143036, 0x00143036, 0x00143036, 0x00143036, 0x00143036, 0x00142e34, 0x00142e34, 0x00142e34, 0x00132c32, 0x00112a30, 0x00112a30, 0x0011282e, 0x0013282e, 0x0013242c, 0x00102229, 0x000f2229, 0x000f1f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00080c12, 0x00070b11, 0x0007090d, 0x0007080c, 0x0005070b, 0x0004060a, 0x0004050a, 0x00030409, 0x00020407, 0x00010304, 0x00010304, 0x00010304, 0x00010304, 0x00000304, 0x00000304, 0x00000304, 0x00010304, 0x00010304, 0x00000205, 0x00000206, 0x00000205, 0x00000105, 0x00000205, 0x00020204, 0x00010304, 0x00000302, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010305, 0x00010508, 0x00050e14, 0x001a282f, 0x00283a44, 0x002c404c, 0x002d404f, 0x002c4150, 0x002d4251, 0x002d4353, 0x002f4254, 0x002e4050, 0x002c3d4d, 0x0029394a, 0x00273647, 0x00243444, 0x00233240, 0x00202e3c, 0x001e2b37, 0x001c2833, 0x00182430, 0x0018232f, 0x0015202c, 0x00151f2b, 0x00151f29, 0x00151c27, 0x00141a24, 0x00121821, 0x0010161f, 0x000e141b, 0x000c1118, 0x000b1016, 0x00090e12, 0x00090d12, 0x00080b10, 0x0006080c, 0x0004060a, 0x00030408, 0x00020407, 0x00020404, 0x00040507, 0x00040608, 0x0006080a, 0x0008090c, 0x00090a0e, 0x00090a0f, 0x00090a10, 0x00090a10, 0x00090a0f, 0x0008080c, 0x0007080c, 0x0006080b, 0x0004070a, 0x00060a0c, 0x00111418, 0x001f2228, 0x00292e38, 0x002b323c, 0x002c343d, 0x002c343f, 0x002d3440, 0x002e3441, 0x00313845, 0x00333c48, 0x00313d49, 0x00344350, 0x00334450, 0x0030434f, 0x002a3f4b, 0x00283d49, 0x002a3f4b, 0x00243947, 0x00233642, 0x00263843, 0x0023343e, 0x0023323d, 0x0024323d, 0x0021303b, 0x001d2c37, 0x001a2935, 0x0023323f, 0x0023323f, 0x001b2a37, 0x001d2c38, 0x00212e3a, 0x00192530, 0x0016212c, 0x0017242c, 0x0015212a, 0x0018242e, 0x001f2c36, 0x00202c38, 0x001b2632, 0x001a2632, 0x001e2a35, 0x0017222d, 0x001b2530, 0x001c2530, 0x00162029, 0x00111b24, 0x00172028, 0x001b242d, 0x001d2934, 0x0014232c, 0x00102028, 0x001c2c36, 0x00283742, 0x00283842, 0x0023333e, 0x0021323d, 0x00283641, 0x0025333f, 0x0022303b, 0x0024323e, 0x0024323e, 0x00273641, 0x00273744, 0x00243642, 0x0030444f, 0x002a3d49, 0x0030424f, 0x002c3f4c, 0x002c3e4c, 0x00283c49, 0x002b3e4c, 0x002e4150, 0x002a3e4d, 0x00263b4a, 0x00283d4c, 0x002f4454, 0x002e4554, 0x002e4554, 0x002f4654, 0x00314855, 0x00344a57, 0x00344856, 0x00314451, 0x00344451, 0x00364451, 0x0031404c, 0x002f3c47, 0x002e3844, 0x002f3642, 0x00303741, 0x00313742, 0x00313743, 0x00333843, 0x00343845, 0x00343845, 0x00323843, 0x00313742, 0x00323642, 0x00313541, 0x00333743, 0x00343844, 0x00343844, 0x00343a46, 0x00373d47, 0x00383e48, 0x00343b44, 0x002a303a, 0x001b2029, 0x000d121a, 0x000b1017, 0x000b0f15, 0x000c0f16, 0x000c1016, 0x000d1017, 0x000d1017, 0x000c0f16, 0x000a0e15, 0x00080c13, 0x00080a10, 0x0006080c, 0x00040609, 0x00040608, 0x00040608, 0x00040709, 0x00070a0e, 0x000c1016, 0x0012181e, 0x00151c24, 0x00151d26, 0x0016202b, 0x0017222d, 0x00182430, 0x001b2733, 0x001c2835, 0x001c2936, 0x001f2b38, 0x00202e3b, 0x0021303e, 0x00233140, 0x00243342, 0x00283747, 0x002b3c4c, 0x002e4050, 0x00304254, 0x00314455, 0x00314455, 0x002f4354, 0x002e4354, 0x002e4354, 0x002e4354, 0x002d4253, 0x002c4050, 0x00293c4c, 0x00253644, 0x001a2732, 0x00071017, 0x0001060b, 0x00020608, 0x00020406, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010304, 0x00030407, 0x0004070a, 0x0005080c, 0x00060a0e, 0x000a0f14, 0x000f141a, 0x000f151c, 0x000e161c, 0x000e161c, 0x000e161c, 0x000f171f, 0x00101a22, 0x00131e26, 0x0014212a, 0x0014232c, 0x0015242e, 0x00152431, 0x00142431, 0x00142430, 0x0014242f, 0x0014242e, 0x000d1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x00102229, 0x000f2229, 0x0012242c, 0x0013242c, 0x0013282e, 0x0011282e, 0x00112a30, 0x00112a30, 0x00112a30, 0x00122c32, 0x00132c32, 0x00132c32, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00132c32, 0x00132c32, 0x00132c32, 0x00122c32, 0x00132c32, 0x00112a30, 0x00112a30, 0x0010282e, 0x0011282e, 0x0013282e, 0x0013242c, 0x0012242c, 0x000f2229, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0004080c, 0x0004070a, 0x00040608, 0x00040508, 0x00030408, 0x00030408, 0x00020307, 0x00020307, 0x00000305, 0x00000304, 0x00000203, 0x00000203, 0x00000304, 0x00000304, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000205, 0x00000206, 0x00000205, 0x00000206, 0x00010205, 0x00020204, 0x00020204, 0x00010303, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010408, 0x00050d12, 0x001a272d, 0x00283842, 0x002c3c48, 0x002c3f4c, 0x002c404d, 0x002d404f, 0x002c4151, 0x002e4152, 0x002d3e4f, 0x002a3b4c, 0x00273848, 0x00263546, 0x00243343, 0x00223040, 0x001f2d3c, 0x001d2a37, 0x001a2733, 0x00182430, 0x0018232f, 0x0015202c, 0x00151f2b, 0x0015202a, 0x00141c28, 0x00141a24, 0x00121821, 0x0010161f, 0x000e141b, 0x000c1118, 0x000b1016, 0x00090e12, 0x00090d12, 0x00080c10, 0x0007090d, 0x0005070a, 0x00030408, 0x00020406, 0x00020405, 0x00030406, 0x00040608, 0x00040708, 0x00060809, 0x0008080c, 0x0008090d, 0x00090a0f, 0x00090a10, 0x00090a0f, 0x0008080d, 0x0007080c, 0x0006080b, 0x00040709, 0x00040708, 0x000a0d10, 0x00181c20, 0x00282d35, 0x0029313a, 0x0028303a, 0x002c343c, 0x002c343e, 0x002e3440, 0x00303743, 0x00303a46, 0x00303b47, 0x0033404c, 0x00344450, 0x0030434f, 0x002a3f4b, 0x00273c47, 0x00273c48, 0x00243846, 0x00253844, 0x00253843, 0x0023343f, 0x00263540, 0x0022303c, 0x001f2d38, 0x001c2c36, 0x001a2935, 0x00273643, 0x00243440, 0x00253441, 0x00293844, 0x00222f3b, 0x001f2a36, 0x001f2b35, 0x001c2932, 0x0017242d, 0x00192630, 0x001d2b35, 0x0024323e, 0x001d2935, 0x001e2b37, 0x00212d39, 0x001d2935, 0x001e2833, 0x001c2630, 0x0018222b, 0x00121c24, 0x00172028, 0x00141e28, 0x001d2832, 0x00192831, 0x0014242d, 0x00162530, 0x00283843, 0x002c3c47, 0x00283843, 0x0023343f, 0x0024343f, 0x00293844, 0x0024343f, 0x0024333e, 0x00283843, 0x00283843, 0x00283946, 0x00253844, 0x00334652, 0x00293c48, 0x002d404c, 0x002c3f4c, 0x002c3f4d, 0x002a3d4b, 0x002b3f4c, 0x002c3f4c, 0x002a3f4c, 0x00263c4a, 0x002a404f, 0x00304655, 0x00304654, 0x00304555, 0x00304654, 0x00324754, 0x00344856, 0x00354755, 0x00324250, 0x0033414e, 0x0034414d, 0x00313d49, 0x002f3a44, 0x002f3843, 0x00303843, 0x00323843, 0x00323844, 0x00323844, 0x00323844, 0x00323844, 0x00313844, 0x00303741, 0x00303540, 0x00303540, 0x00313541, 0x00333842, 0x00343944, 0x00353a46, 0x00363c48, 0x00373d48, 0x00333a43, 0x002a303a, 0x001c232c, 0x0010141d, 0x000b1018, 0x000a0f16, 0x000b0f15, 0x000c0f16, 0x000c1016, 0x000c1016, 0x000c0f16, 0x000c0e15, 0x00090c14, 0x00080b11, 0x0008090f, 0x0005070c, 0x00040609, 0x00040608, 0x00040608, 0x0004070a, 0x00080b10, 0x000e1118, 0x00121820, 0x00151c25, 0x00151d28, 0x0016202b, 0x0017232d, 0x00192530, 0x001c2733, 0x001c2834, 0x001d2934, 0x001f2b37, 0x00202d39, 0x00212f3c, 0x0023303f, 0x00233140, 0x00253444, 0x00293a4a, 0x002c3f4f, 0x002f4253, 0x00314455, 0x00314455, 0x002e4354, 0x002e4254, 0x002d4254, 0x002d4153, 0x002c4051, 0x00293e4e, 0x00283b4b, 0x00223240, 0x0014202b, 0x00040a11, 0x00020509, 0x00020507, 0x00010404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010405, 0x00020508, 0x00020509, 0x0003070a, 0x00060a0c, 0x000b0e12, 0x000a0f14, 0x00090f14, 0x00090f14, 0x00090f14, 0x000a1015, 0x00091118, 0x000c141a, 0x000e181f, 0x00101c24, 0x00131f28, 0x0014202b, 0x0014212c, 0x0014222c, 0x0012232d, 0x0012232d, 0x000d1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f1f27, 0x00102229, 0x00102229, 0x0012242c, 0x0013242c, 0x0012242c, 0x0013282e, 0x0012282e, 0x0010282e, 0x0010282e, 0x0010282e, 0x00112a30, 0x00112a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00112a30, 0x0010282e, 0x0010282e, 0x0010282e, 0x0011282e, 0x0012282e, 0x0013282e, 0x0012242c, 0x0013242c, 0x0012242c, 0x00102229, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00020405, 0x00020404, 0x00030405, 0x00020406, 0x00020406, 0x00020406, 0x00020406, 0x00020406, 0x00010304, 0x00000203, 0x00000203, 0x00000203, 0x00000203, 0x00010303, 0x00010302, 0x00010302, 0x00000204, 0x00000204, 0x00000104, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000407, 0x00050c12, 0x0018242d, 0x00263741, 0x00293b46, 0x002a3c48, 0x002b3e4a, 0x002c3f4c, 0x002c404f, 0x002d4050, 0x002c3d4e, 0x00293a4a, 0x00273748, 0x00263446, 0x00233242, 0x0021303f, 0x001e2c3c, 0x001c2938, 0x00192634, 0x00182331, 0x0017232e, 0x0015202c, 0x00151f2b, 0x0015202a, 0x00141d28, 0x00141a24, 0x00121821, 0x0010161f, 0x000e141b, 0x000c1118, 0x000b1016, 0x00090e12, 0x00090d12, 0x00090c11, 0x0008090d, 0x00050709, 0x00030507, 0x00020405, 0x00020404, 0x00030406, 0x00040608, 0x00040608, 0x00050708, 0x0007080b, 0x0007080c, 0x0008090e, 0x0008090f, 0x0008090f, 0x0007080d, 0x0006080c, 0x0006080c, 0x0004070b, 0x00030708, 0x0006090c, 0x0012151a, 0x00252a31, 0x00242b34, 0x00242c35, 0x00283039, 0x002a313b, 0x002e343f, 0x002f3641, 0x00303843, 0x002f3843, 0x00303c47, 0x0031404c, 0x00334450, 0x002c404c, 0x00223743, 0x00263b47, 0x00273b48, 0x00243845, 0x00243743, 0x00233440, 0x00253542, 0x00202f3b, 0x001d2c38, 0x001c2c36, 0x001e2e38, 0x00283742, 0x00273641, 0x002b3a45, 0x002d3b47, 0x0024303b, 0x00202c38, 0x0024303c, 0x001d2c34, 0x0016242e, 0x00182630, 0x001c2c36, 0x00253440, 0x001f2d3b, 0x001f2d3a, 0x00212f3b, 0x001f2b37, 0x001f2833, 0x00212b35, 0x0018222b, 0x00162028, 0x00171f28, 0x00141c26, 0x001a2530, 0x001f2c36, 0x001b2b34, 0x00192833, 0x0020303c, 0x0022313d, 0x00273843, 0x00243540, 0x0020303b, 0x00263541, 0x002a3945, 0x00283844, 0x002d3d49, 0x00293a46, 0x00283b47, 0x002a3f4a, 0x00304550, 0x00293d49, 0x00243845, 0x00273b48, 0x00293e4c, 0x00283c4a, 0x00293e4c, 0x00283d4b, 0x002b404d, 0x00293e4c, 0x00304554, 0x00324857, 0x00314756, 0x00324555, 0x00304453, 0x00324452, 0x00344554, 0x00354453, 0x00313f4e, 0x00303d4b, 0x00303c48, 0x002f3a46, 0x002f3944, 0x00313844, 0x00333944, 0x00333944, 0x00333944, 0x00323844, 0x00323844, 0x00303744, 0x00303644, 0x002f3540, 0x00303640, 0x00323640, 0x00323741, 0x00343842, 0x00353a46, 0x00373c48, 0x00383c48, 0x00343b44, 0x0029323b, 0x001c242d, 0x000e151e, 0x00090f18, 0x000a0e17, 0x000a0f16, 0x000b0f15, 0x000c0f16, 0x000c1016, 0x000c1016, 0x000c0e15, 0x00090c13, 0x00080b11, 0x00070810, 0x0007070c, 0x0004040a, 0x00040409, 0x00040509, 0x00040609, 0x0004070c, 0x00090c13, 0x000e121b, 0x00131822, 0x00141c26, 0x00151d28, 0x0016202b, 0x0018232d, 0x00192530, 0x001b2733, 0x001c2834, 0x001d2935, 0x001f2b37, 0x00202d39, 0x00212f3c, 0x0022303f, 0x00223040, 0x00243343, 0x00283949, 0x002c3d4d, 0x002f4051, 0x00304254, 0x00304254, 0x002e4253, 0x002c4052, 0x002d4153, 0x002d4153, 0x002b3f4f, 0x00283c4c, 0x00273848, 0x00202e3c, 0x00101a24, 0x0002080f, 0x00010408, 0x00010405, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000408, 0x00000408, 0x00020508, 0x00020609, 0x0005080c, 0x0004090c, 0x0004090c, 0x0004090c, 0x0004090c, 0x0004090c, 0x00040a0f, 0x00060c10, 0x00070e14, 0x00081017, 0x000a141b, 0x000d181f, 0x00101b23, 0x00121e27, 0x00121f28, 0x0012202a, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x000f2229, 0x00102229, 0x00102229, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0012242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0012242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x00102229, 0x00102229, 0x000f2229, 0x00102229, 0x000f1f27, 0x00111f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010404, 0x00020403, 0x00030303, 0x00030304, 0x00030304, 0x00030304, 0x00030304, 0x00030304, 0x00020204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020203, 0x00020202, 0x00020202, 0x00000204, 0x00000204, 0x00000104, 0x00000104, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00010405, 0x00050b10, 0x00172129, 0x0025353f, 0x00283a46, 0x00293c47, 0x002a3d49, 0x002a3e4b, 0x002b3e4c, 0x002c3e4d, 0x002b3c4c, 0x00283848, 0x00263747, 0x00263446, 0x00243242, 0x00222f3f, 0x001f2c3b, 0x001c2837, 0x00192533, 0x00182330, 0x0018232f, 0x0016202c, 0x00151f2b, 0x00151f29, 0x00141d28, 0x00141a24, 0x00121821, 0x0010161f, 0x000e141b, 0x000c1119, 0x000b1017, 0x000b0e14, 0x000a0d12, 0x000a0c11, 0x0008090e, 0x0005070a, 0x00040507, 0x00020405, 0x00020405, 0x00030406, 0x00040608, 0x00040608, 0x00050708, 0x0006080a, 0x0007080c, 0x0008090e, 0x0008090f, 0x0008090f, 0x0007080d, 0x0006080c, 0x0006080c, 0x0005080c, 0x00040809, 0x0004080a, 0x000c1015, 0x001d2229, 0x001e232b, 0x00202830, 0x00252d36, 0x00283038, 0x002d343d, 0x00303641, 0x00303843, 0x002c3641, 0x002c3741, 0x00303c48, 0x00364552, 0x00344552, 0x00273a46, 0x002a3e4a, 0x00293d4a, 0x00253945, 0x00283a46, 0x00233541, 0x00263643, 0x0020303d, 0x0020303c, 0x001f303a, 0x0024343f, 0x00263640, 0x00273641, 0x00263540, 0x0024313c, 0x00212c38, 0x00202c38, 0x0027343f, 0x00202f38, 0x00172630, 0x00172630, 0x001a2a34, 0x00273542, 0x0022303d, 0x0021303c, 0x00202e3a, 0x00202d39, 0x001d2833, 0x00212b35, 0x001b2630, 0x0018212b, 0x0018212b, 0x00161f28, 0x0017232c, 0x001f2d37, 0x00202f38, 0x001d2c37, 0x0020303c, 0x001c2c38, 0x0020303c, 0x0022333e, 0x001d2d39, 0x0022313f, 0x00283846, 0x00283948, 0x002d3e4c, 0x002b3d4b, 0x00283b48, 0x002a3f4b, 0x002b404c, 0x00273c49, 0x00223744, 0x00263b48, 0x00283d4b, 0x00283d4c, 0x002b404e, 0x002b404e, 0x002c414f, 0x002c404d, 0x00344655, 0x00344858, 0x00344757, 0x00344555, 0x00324352, 0x00324150, 0x00334150, 0x00344050, 0x00313d4c, 0x00303b49, 0x00303a46, 0x002f3844, 0x00303944, 0x00333944, 0x00343944, 0x00343944, 0x00343843, 0x00323842, 0x00303742, 0x00303542, 0x002f3440, 0x002e343e, 0x00303540, 0x00333741, 0x00343842, 0x00353a44, 0x00383c48, 0x00383c48, 0x00393d49, 0x00313740, 0x00202730, 0x00111821, 0x000a1019, 0x00080d16, 0x00090d16, 0x000a0f16, 0x000b0f15, 0x000c0e15, 0x000c0f15, 0x000c0e15, 0x000a0d14, 0x00080b11, 0x00070910, 0x0006080e, 0x0005050b, 0x00040409, 0x00030409, 0x00040509, 0x0004060a, 0x0004080c, 0x000a0d14, 0x000f141d, 0x00131924, 0x00151d28, 0x00161e29, 0x0016202a, 0x0018222b, 0x0018242d, 0x001a2530, 0x001c2832, 0x001d2934, 0x001e2a37, 0x00202c38, 0x00202d3b, 0x0022303e, 0x00223040, 0x00233242, 0x00273748, 0x002b3c4c, 0x002d3f50, 0x002e4053, 0x002f4153, 0x002c4153, 0x002c4052, 0x002c4052, 0x002c4050, 0x00283d4c, 0x00263a48, 0x00253544, 0x001d2935, 0x000a141c, 0x0000060c, 0x00010408, 0x00000407, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000407, 0x00000408, 0x00010408, 0x00010508, 0x00020609, 0x00020609, 0x00010609, 0x00010709, 0x00010709, 0x00020609, 0x00020609, 0x0003070a, 0x0004080c, 0x0004080f, 0x00050a10, 0x00060c13, 0x00090f17, 0x000b121b, 0x000d1620, 0x000f1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f1f27, 0x00102229, 0x000f2229, 0x000f2229, 0x000f2229, 0x000f2229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x000f2229, 0x000f2229, 0x000f2229, 0x000f2229, 0x00102229, 0x000f1f27, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010304, 0x00020202, 0x00020202, 0x00020203, 0x00020203, 0x00020203, 0x00020203, 0x00020203, 0x00020203, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020203, 0x00020203, 0x00020203, 0x00010204, 0x00010204, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00010406, 0x0005090e, 0x00141d24, 0x0024323c, 0x00283944, 0x00283b46, 0x00283c48, 0x00283c4a, 0x002a3c4a, 0x002b3c4a, 0x00293b4a, 0x00273847, 0x00263746, 0x00253444, 0x00243140, 0x00212e3c, 0x001f2b38, 0x001c2834, 0x001a2531, 0x00192430, 0x0018232f, 0x0017212d, 0x0016202b, 0x00161e29, 0x00151d28, 0x00141b24, 0x00111822, 0x000f161f, 0x000d141c, 0x000c1119, 0x000b1018, 0x000b0e16, 0x000a0d14, 0x000b0c11, 0x00090b10, 0x0007080c, 0x00040608, 0x00030507, 0x00030406, 0x00030406, 0x00040606, 0x00040607, 0x00040607, 0x00050708, 0x00060809, 0x0007080c, 0x0008090e, 0x0008090e, 0x0007080d, 0x0007080d, 0x0007080c, 0x0006090c, 0x0005080b, 0x0004070b, 0x00070a10, 0x0013161c, 0x00171b21, 0x001c2129, 0x00242931, 0x00292e38, 0x002d323c, 0x002f3540, 0x00303640, 0x002c343f, 0x0029333d, 0x002e3844, 0x0035404e, 0x00384452, 0x0031414d, 0x0030424e, 0x002b3c49, 0x00253744, 0x00273945, 0x00253844, 0x00283b47, 0x00213440, 0x00243541, 0x00243642, 0x002a3b47, 0x00253743, 0x00243440, 0x001e2d39, 0x00202e39, 0x00202d38, 0x0023303b, 0x0027343f, 0x00202f39, 0x00182730, 0x00182831, 0x001b2a34, 0x00202f3a, 0x0025343f, 0x0023323d, 0x00202e39, 0x0024313c, 0x00202d39, 0x00192630, 0x001d2b34, 0x00182530, 0x001c2730, 0x00152129, 0x0019262e, 0x001c2931, 0x0022303a, 0x00202f38, 0x0022313c, 0x00243640, 0x0020313c, 0x001f303c, 0x001c2c39, 0x001d2e3c, 0x00243443, 0x00283a48, 0x002c3e4c, 0x002b3f4c, 0x00273c49, 0x00273c4a, 0x002a3f4e, 0x00283d4c, 0x00263b49, 0x00293d4d, 0x0029404f, 0x002a404f, 0x002d4352, 0x00344858, 0x00344554, 0x0030404e, 0x00344553, 0x00374756, 0x00374655, 0x00374554, 0x00354251, 0x0034404f, 0x00333f4d, 0x00333e4c, 0x00323c4a, 0x00303a48, 0x00303945, 0x00303944, 0x00323a45, 0x00343b45, 0x00343944, 0x00343842, 0x00323640, 0x00303540, 0x002f343e, 0x002e333e, 0x002d323d, 0x002e323c, 0x00303440, 0x00343842, 0x00353a44, 0x00383c48, 0x00393e4a, 0x003a3f4a, 0x00373b46, 0x002b2e38, 0x00181c23, 0x000c1017, 0x00090d14, 0x000a0d14, 0x000a0d15, 0x000b0e15, 0x000c0f15, 0x000c0e15, 0x000a0d14, 0x000a0c13, 0x000a0b10, 0x0008090f, 0x0006080c, 0x0004060a, 0x00040509, 0x00040408, 0x00040408, 0x00040609, 0x0004070a, 0x00050a0f, 0x000a1017, 0x000f151e, 0x00121a24, 0x00141d28, 0x00151f29, 0x0014202b, 0x0017222c, 0x0017242d, 0x00182630, 0x001b2831, 0x001c2934, 0x001e2a36, 0x00202c38, 0x00202c3a, 0x00202e3d, 0x0021303f, 0x00223040, 0x00253444, 0x00283849, 0x002b3d4d, 0x002c3f50, 0x002d4153, 0x002c4153, 0x002c4052, 0x002c4051, 0x002b3f4f, 0x00283d4b, 0x00263a46, 0x00243440, 0x001b2630, 0x00080f15, 0x0002060b, 0x00020408, 0x00010407, 0x00010404, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010304, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000305, 0x00000305, 0x00010406, 0x00020406, 0x00020407, 0x00030408, 0x00010408, 0x00010408, 0x00010407, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00030509, 0x0004060a, 0x0005080c, 0x0005090d, 0x00080c11, 0x00090f15, 0x000c1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00111f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00020204, 0x00020202, 0x00020202, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000304, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010406, 0x0004090d, 0x00111a21, 0x00233039, 0x00273843, 0x00283a45, 0x00283b47, 0x00283c49, 0x00293b49, 0x002a3b48, 0x00283a48, 0x00263846, 0x00263644, 0x00243443, 0x0023303f, 0x00202d3c, 0x001e2a38, 0x001c2834, 0x00192531, 0x0018242f, 0x0018212e, 0x0016202c, 0x00151f2a, 0x00151e29, 0x00151d28, 0x00131c24, 0x00101822, 0x000e161e, 0x000d141c, 0x000b1119, 0x000b1018, 0x000a0e16, 0x000a0d14, 0x000a0c11, 0x000a0c10, 0x00080a0d, 0x00050708, 0x00030506, 0x00020405, 0x00030406, 0x00040505, 0x00040606, 0x00040606, 0x00050707, 0x00050708, 0x0006080b, 0x0008080c, 0x0008090d, 0x0007080d, 0x0007080d, 0x0007080d, 0x00070a0c, 0x00070a0d, 0x0004080c, 0x0003080c, 0x00080c10, 0x00101318, 0x00181b21, 0x0020252c, 0x00282b34, 0x002b2f38, 0x002d323c, 0x002f343f, 0x002c343c, 0x0029313b, 0x002c3440, 0x00313a48, 0x0034404d, 0x0034424f, 0x0032424f, 0x002c3b48, 0x00243441, 0x00243541, 0x00283b47, 0x002c404c, 0x002a3f4a, 0x00293d48, 0x00283b47, 0x00283b47, 0x00263844, 0x00233440, 0x001e2e3a, 0x0022303c, 0x0022303c, 0x00293841, 0x002b3843, 0x0023303b, 0x001c2b34, 0x001a2a34, 0x00202f38, 0x001e2d38, 0x0022313c, 0x0022313c, 0x001e2d38, 0x0024333e, 0x0023323d, 0x0016252f, 0x001c2b34, 0x001f2e38, 0x001f2d37, 0x001a2630, 0x001f2b34, 0x0018242c, 0x00202d38, 0x0025333d, 0x0022323c, 0x00273843, 0x002b3d48, 0x0020333d, 0x001c2d3a, 0x001a2b39, 0x001f303f, 0x00273948, 0x002e4150, 0x002c414f, 0x002d4251, 0x002c4050, 0x002d4251, 0x002f4453, 0x002d4151, 0x002c4050, 0x002b4250, 0x00294150, 0x002c4352, 0x00374c5b, 0x00364756, 0x0031414e, 0x00344450, 0x00364452, 0x00364351, 0x00374250, 0x0036404f, 0x0035404c, 0x00343e4b, 0x00333d4a, 0x00323c48, 0x00313b47, 0x00303944, 0x00303a44, 0x00333b45, 0x00343a45, 0x00333943, 0x00313841, 0x002f353f, 0x002e343d, 0x002d323c, 0x002d313c, 0x002c303b, 0x002e323c, 0x00313640, 0x00363a44, 0x00383d47, 0x00383f4a, 0x0039404b, 0x00373c48, 0x002d313c, 0x001d2028, 0x000e1117, 0x00090c11, 0x00090c12, 0x000a0d12, 0x000b0e14, 0x000c0e15, 0x000c0e15, 0x000b0d14, 0x00090c13, 0x00090b11, 0x0008090f, 0x0008080e, 0x0004060a, 0x00040508, 0x00040508, 0x00040508, 0x00040609, 0x00040609, 0x0006080c, 0x00080c11, 0x000c1319, 0x00101720, 0x00121b24, 0x00141d28, 0x00141f29, 0x0014202b, 0x0014222c, 0x0016242e, 0x00182630, 0x00192831, 0x001c2834, 0x001d2935, 0x001f2b38, 0x00202c3a, 0x00202d3c, 0x00202f3e, 0x00213040, 0x00223342, 0x00263748, 0x002a3c4c, 0x002c3f4f, 0x002c4051, 0x002d4153, 0x002c4152, 0x002b3f50, 0x00283d4c, 0x00273c48, 0x00263844, 0x0021303c, 0x0018212b, 0x00060c12, 0x00020509, 0x00000407, 0x00020406, 0x00020404, 0x00010204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010305, 0x00010305, 0x00010305, 0x00010304, 0x00010304, 0x00010305, 0x00010305, 0x00010305, 0x00010305, 0x00010305, 0x00030406, 0x00030406, 0x00030506, 0x00040608, 0x0005080b, 0x000b1822, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00020204, 0x00020202, 0x00020202, 0x00010102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000304, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010406, 0x0004080c, 0x00101920, 0x00212f38, 0x00263742, 0x00283845, 0x00273a47, 0x00283a49, 0x00283b4b, 0x00283a48, 0x00263947, 0x00253846, 0x00253444, 0x00243342, 0x0022303f, 0x00202d3b, 0x001d2a38, 0x001c2834, 0x00192531, 0x0018232f, 0x0018212d, 0x0016202c, 0x00151f2a, 0x00141e29, 0x00141d28, 0x00131b24, 0x00101821, 0x000f161e, 0x000d141b, 0x000b1018, 0x000a1018, 0x000a0e16, 0x00090d14, 0x00090c11, 0x00090b10, 0x00090b0e, 0x0007080a, 0x00040507, 0x00030405, 0x00030406, 0x00030506, 0x00040504, 0x00040505, 0x00040607, 0x00050708, 0x0006080a, 0x0006080b, 0x0007080c, 0x0007080c, 0x0007080c, 0x0007080d, 0x00070a0d, 0x00070a0d, 0x0004080c, 0x0003080c, 0x0005080c, 0x000c0d11, 0x0013151a, 0x001c1f24, 0x0024272e, 0x00282b34, 0x00292d37, 0x002b313a, 0x002b3139, 0x002c313a, 0x002b313c, 0x002d3542, 0x00313b48, 0x00313e49, 0x0033424d, 0x002c3c48, 0x00243441, 0x00213340, 0x00283b47, 0x002e434e, 0x002f434f, 0x002b3e4a, 0x00283c48, 0x00243844, 0x00243642, 0x00263844, 0x0020303c, 0x0022313d, 0x0024323e, 0x00273440, 0x00283642, 0x0023313c, 0x0020303a, 0x001e2d38, 0x0023323d, 0x0024333f, 0x0021313e, 0x0020303c, 0x001c2c38, 0x0021313d, 0x0024343e, 0x001a2934, 0x001c2c35, 0x0026363f, 0x00203039, 0x001e2b34, 0x00212d38, 0x0019252e, 0x00202d38, 0x002a3843, 0x001c2c37, 0x00253641, 0x002c404a, 0x00233540, 0x00213340, 0x001f303e, 0x001f303e, 0x00283a48, 0x00304452, 0x00304452, 0x00314554, 0x00324756, 0x00304655, 0x00344958, 0x00304755, 0x002c4251, 0x002e4654, 0x002c4453, 0x00304755, 0x00344857, 0x00344453, 0x0034424f, 0x0034424e, 0x0034404f, 0x0035404e, 0x00373f4e, 0x00363f4c, 0x00343e4b, 0x00333d49, 0x00333d49, 0x00323c48, 0x00333c47, 0x00333b46, 0x00333b46, 0x00333b46, 0x00343945, 0x00323844, 0x00303640, 0x002e343e, 0x002c333c, 0x002d323a, 0x002c313c, 0x002c313c, 0x0030353f, 0x00343842, 0x00383c46, 0x0039404a, 0x0039414c, 0x0038404a, 0x00303641, 0x0020242e, 0x0010141c, 0x000a0c12, 0x00090c11, 0x00090c11, 0x00090c11, 0x000a0d14, 0x000c0e14, 0x000c0e14, 0x000a0c14, 0x00090c13, 0x00080a10, 0x0007080d, 0x0005070c, 0x00040509, 0x00030408, 0x00030408, 0x00040508, 0x00040609, 0x0004070a, 0x0007090d, 0x000a0e13, 0x000e141b, 0x00111820, 0x00121b25, 0x00141e28, 0x00151f2a, 0x0014202b, 0x0014222c, 0x0016242e, 0x00172630, 0x00192831, 0x001c2834, 0x001d2935, 0x001f2b38, 0x00202c3a, 0x00202d3c, 0x00212f3e, 0x0021303f, 0x00223241, 0x00263645, 0x002a3a4b, 0x002c3d4d, 0x002c4051, 0x002c4052, 0x002c4052, 0x002a3e4e, 0x00293c4b, 0x00283a48, 0x00253643, 0x001f2c38, 0x00121b24, 0x00040910, 0x00010408, 0x00000408, 0x00020406, 0x00020404, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020304, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020404, 0x00020404, 0x00020404, 0x00030406, 0x000b1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010101, 0x00010102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000304, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020407, 0x0004080c, 0x00111a21, 0x0022303a, 0x00273743, 0x00263844, 0x00263947, 0x00283a49, 0x00283b4a, 0x00283a48, 0x00263947, 0x00253845, 0x00243444, 0x00243342, 0x0021303f, 0x001d2c3c, 0x001c2938, 0x001a2834, 0x00182532, 0x0018232f, 0x0018212d, 0x0016202c, 0x00152029, 0x00141e29, 0x00141c28, 0x00121b24, 0x00101821, 0x000e151e, 0x000c131a, 0x000b1118, 0x00091018, 0x00080e16, 0x00080c14, 0x00080b11, 0x00080b10, 0x00090b0e, 0x0008090b, 0x00040608, 0x00040507, 0x00040507, 0x00030406, 0x00030405, 0x00030506, 0x00040607, 0x00050708, 0x00060809, 0x00060809, 0x0006080a, 0x0007080c, 0x0007080c, 0x0007080c, 0x00070a0d, 0x00070a0d, 0x0005080c, 0x0004070b, 0x0004060a, 0x0008090c, 0x000f1015, 0x00181a20, 0x0020232a, 0x00252830, 0x00282b33, 0x00292f36, 0x002c3138, 0x002c3139, 0x002b303b, 0x002c333d, 0x002d3641, 0x002e3843, 0x00313e49, 0x002d3c48, 0x002a3946, 0x002a3a48, 0x00293c48, 0x002e414d, 0x0030424f, 0x002c3e4a, 0x00273944, 0x00203440, 0x0020323e, 0x00223340, 0x00202f3c, 0x0022313e, 0x0022313e, 0x0022313c, 0x0025343f, 0x0022323c, 0x0020313c, 0x001e303a, 0x0021333d, 0x00263742, 0x00253743, 0x00243542, 0x001d2e3b, 0x001f303c, 0x001f303d, 0x001d2e39, 0x001e303a, 0x00243540, 0x0022313c, 0x0022303a, 0x00202e38, 0x001c2a34, 0x0022303b, 0x002b3b46, 0x001c2c37, 0x00243440, 0x00253842, 0x0020343e, 0x00273846, 0x00283948, 0x00263745, 0x002c3f4c, 0x00334755, 0x00354a58, 0x00334857, 0x00344a59, 0x002f4655, 0x00304856, 0x002e4655, 0x002d4453, 0x002e4654, 0x002f4755, 0x00344a59, 0x00344756, 0x00344452, 0x0034434f, 0x0036424e, 0x0035404e, 0x00373f4e, 0x00383f4d, 0x00353e4b, 0x00343d48, 0x00303c47, 0x00313c48, 0x00333d48, 0x00343c48, 0x00343c47, 0x00333b46, 0x00333a45, 0x00333843, 0x00323642, 0x0030343f, 0x002e343e, 0x002f343e, 0x002f343c, 0x002f343c, 0x0030343e, 0x00313640, 0x00353944, 0x00383d47, 0x003b414b, 0x003b414c, 0x00343b46, 0x00232a34, 0x00101620, 0x000b0d15, 0x000a0c12, 0x00090c11, 0x00090c11, 0x00090c11, 0x000a0d12, 0x000c0f13, 0x000b0d13, 0x00090c13, 0x00080b12, 0x00080910, 0x0005070c, 0x00040509, 0x00040508, 0x00040508, 0x00040508, 0x00040509, 0x00040609, 0x0005070a, 0x00080a0d, 0x000b0f14, 0x000f151c, 0x00121821, 0x00131b25, 0x00141e29, 0x0015202a, 0x0014202b, 0x0016212c, 0x0017242e, 0x00182630, 0x001a2831, 0x001c2834, 0x001d2935, 0x001f2b38, 0x00202c3a, 0x00202d3b, 0x00202f3d, 0x00202f3f, 0x00223240, 0x00263445, 0x00283848, 0x002b3c4c, 0x002c404f, 0x002c4050, 0x002a3f50, 0x00293c4c, 0x00293c4a, 0x00263945, 0x00233440, 0x001c2833, 0x000c141c, 0x0004070e, 0x00010408, 0x00010408, 0x00020306, 0x00020404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010101, 0x00010102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000304, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010407, 0x0004060c, 0x00101920, 0x0021303a, 0x00263744, 0x00253845, 0x00263948, 0x00263a4a, 0x00253b4c, 0x00263a4b, 0x00273848, 0x00263646, 0x00253444, 0x00233243, 0x00212f40, 0x001d2c3b, 0x001b2838, 0x001a2834, 0x00182533, 0x00182330, 0x0018212d, 0x0017202b, 0x00152028, 0x00141e28, 0x00131c27, 0x00121b24, 0x00101821, 0x000e161e, 0x000c131a, 0x000b1219, 0x00091018, 0x00080f17, 0x00090e15, 0x000a0d14, 0x00090c12, 0x00090c0f, 0x0008090b, 0x00040608, 0x00040608, 0x00040608, 0x00030406, 0x00030405, 0x00030406, 0x00040508, 0x00040708, 0x00060809, 0x00060809, 0x0006080a, 0x0007080c, 0x0007080c, 0x0007080c, 0x00070a0d, 0x0006090c, 0x0005080c, 0x0004070a, 0x00040609, 0x0005070a, 0x000c0c12, 0x0013161b, 0x001b1e25, 0x00202329, 0x0024272d, 0x00262b31, 0x002b2f35, 0x002c3038, 0x002a3039, 0x002a313b, 0x002c343e, 0x002d3640, 0x002f3944, 0x002d3946, 0x002d3a48, 0x002f3c49, 0x002c3b48, 0x002c3c49, 0x0030404d, 0x002e3d4a, 0x00283744, 0x0022333f, 0x0021323e, 0x0022313e, 0x0022313f, 0x00233240, 0x0023323f, 0x0024343f, 0x0024343f, 0x00243440, 0x00263742, 0x0024343f, 0x0024343f, 0x00253642, 0x00253744, 0x00283948, 0x00283847, 0x00233442, 0x0020313f, 0x0021323f, 0x00243540, 0x00283844, 0x00253540, 0x0025333e, 0x0023313b, 0x00212f39, 0x001d2b36, 0x00263540, 0x0023343f, 0x0021333e, 0x00233540, 0x00243842, 0x002c3c4a, 0x0030404f, 0x002e404e, 0x002f404f, 0x00344855, 0x00344856, 0x00354a59, 0x00344b5a, 0x00304756, 0x002e4454, 0x002c4352, 0x002e4352, 0x002f4352, 0x00324655, 0x00344958, 0x00344656, 0x00344351, 0x0035424f, 0x0037414e, 0x0038404e, 0x00383f4e, 0x00383f4c, 0x00363e4a, 0x00333d48, 0x00313c46, 0x00323c47, 0x00333c48, 0x00343c47, 0x00343b46, 0x00333944, 0x00313841, 0x00313540, 0x0030343f, 0x0030343e, 0x0030343f, 0x00313540, 0x00313540, 0x0031363f, 0x00333841, 0x00343944, 0x00373c46, 0x003a3f48, 0x003b404a, 0x00353b44, 0x00282f38, 0x00141b24, 0x00090d17, 0x000a0c14, 0x000b0c12, 0x000a0c11, 0x00090c11, 0x00090c11, 0x000a0d12, 0x000a0d12, 0x00080c11, 0x00070a10, 0x00060910, 0x0006080f, 0x0005070c, 0x00040509, 0x00040609, 0x00040508, 0x00040508, 0x00040508, 0x00040609, 0x0006080b, 0x00090b10, 0x000c1014, 0x000f151c, 0x00121821, 0x00121b25, 0x00141e28, 0x0015202a, 0x0014202b, 0x0016212c, 0x0018242e, 0x00182630, 0x001a2832, 0x001c2834, 0x001d2836, 0x001f2b38, 0x00202c3a, 0x00202d3c, 0x00202f3e, 0x0020303f, 0x00233140, 0x00253444, 0x00283647, 0x0029394a, 0x002b3d4d, 0x002b3e4e, 0x00293d4d, 0x00283c4c, 0x00283b49, 0x00253844, 0x0021323e, 0x0019242f, 0x00091019, 0x0003050c, 0x00020408, 0x00030307, 0x00030306, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010101, 0x00010101, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00020408, 0x0003060c, 0x00101720, 0x00212d39, 0x00263643, 0x00253845, 0x00253948, 0x00253a4a, 0x00243b4c, 0x00243a4c, 0x00263748, 0x00253546, 0x00243444, 0x00233142, 0x00202e3f, 0x001d2b3a, 0x001b2838, 0x001b2734, 0x00182432, 0x00182330, 0x0018222d, 0x0016202a, 0x00152028, 0x00141e26, 0x00131c25, 0x00101b24, 0x00101922, 0x000d161d, 0x000c141b, 0x000c121a, 0x000b1018, 0x000a1018, 0x000b0f16, 0x000c0e15, 0x000b0d14, 0x000a0c11, 0x0008090d, 0x0005070a, 0x00040508, 0x00030508, 0x00030408, 0x00030408, 0x00030508, 0x00040608, 0x00040608, 0x00050709, 0x0005070a, 0x0005070a, 0x0006080b, 0x0006080b, 0x0006080b, 0x0006080c, 0x0006080b, 0x0004080b, 0x0004070a, 0x00040709, 0x0005070a, 0x00080a0f, 0x000d1015, 0x0016181f, 0x001b1d24, 0x001e2128, 0x0023262c, 0x00282c32, 0x002b2e35, 0x002a3038, 0x002a303a, 0x002b323c, 0x002c343f, 0x002d3741, 0x002c3743, 0x002c3643, 0x002e3744, 0x002d3744, 0x002c3844, 0x002f3a47, 0x002a3743, 0x00273541, 0x00253540, 0x0024343f, 0x00283743, 0x00273743, 0x00243440, 0x00243440, 0x0023323e, 0x0020303c, 0x0022313d, 0x00253540, 0x00253440, 0x00273642, 0x00253442, 0x00223343, 0x00243545, 0x00293c4a, 0x002f404f, 0x00293a49, 0x00283946, 0x00283945, 0x00293b47, 0x00273743, 0x00283641, 0x0026343e, 0x0024313c, 0x001d2c38, 0x00243440, 0x002a3a46, 0x00233440, 0x00283a47, 0x00314450, 0x00324452, 0x00304351, 0x00304251, 0x002e4250, 0x00324754, 0x00314654, 0x00324755, 0x00304654, 0x00304453, 0x002e4050, 0x002c3e4d, 0x002c3e4d, 0x00314251, 0x00354655, 0x00374757, 0x00354454, 0x00354251, 0x0036414e, 0x0038404e, 0x0038404e, 0x00383f4c, 0x00383f4c, 0x00363d4a, 0x00343d48, 0x00343c48, 0x00343c48, 0x00343c47, 0x00343a46, 0x00343a44, 0x00313840, 0x0030363f, 0x0030353e, 0x0030343f, 0x00303440, 0x00303440, 0x00313440, 0x00323740, 0x00333843, 0x00343b46, 0x00373d48, 0x00393f4b, 0x003a404b, 0x00373b45, 0x002c3038, 0x001c2028, 0x000c1017, 0x00080b12, 0x000a0c12, 0x000b0c11, 0x000b0c11, 0x00090c11, 0x00090c11, 0x00090c11, 0x00090c10, 0x00080a10, 0x0007090f, 0x0006080e, 0x0005070c, 0x0004060a, 0x00040609, 0x00040608, 0x00040608, 0x00030408, 0x0003040a, 0x0004050b, 0x0006080e, 0x000b0c14, 0x000c1018, 0x0010161e, 0x00121822, 0x00111a24, 0x00141d28, 0x00141e29, 0x0014202a, 0x0016212c, 0x0017242e, 0x00182530, 0x001a2831, 0x001b2834, 0x001c2836, 0x001e2938, 0x001f2b3a, 0x00202c3c, 0x00202e3d, 0x0020303f, 0x00233140, 0x00243444, 0x00273546, 0x00283848, 0x002b3b4c, 0x002a3c4c, 0x00283c4c, 0x00273c4b, 0x00273c48, 0x00243843, 0x0020303b, 0x0016202a, 0x00060c13, 0x00030408, 0x00020306, 0x00030304, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000104, 0x00000204, 0x00000204, 0x00000204, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010101, 0x00010101, 0x00010102, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020205, 0x00020408, 0x0002060b, 0x000f151f, 0x00202c38, 0x00243441, 0x00253544, 0x00263847, 0x00263a49, 0x00243a4b, 0x0024394a, 0x00263747, 0x00253545, 0x00253444, 0x00233040, 0x00202d3c, 0x001d2a38, 0x001b2835, 0x001a2634, 0x00182331, 0x00182230, 0x0018222d, 0x0016202b, 0x00152028, 0x00141d26, 0x00111c24, 0x00101a24, 0x000f1922, 0x000d161d, 0x000c141b, 0x000d131b, 0x000c1119, 0x000b1018, 0x000b0f17, 0x000c0e15, 0x000a0d14, 0x000a0c12, 0x0008090f, 0x0004060b, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00040508, 0x00040608, 0x00040608, 0x00040709, 0x0004070a, 0x0004070a, 0x0004070a, 0x0005070a, 0x0005070a, 0x0005070a, 0x0005070a, 0x0004080a, 0x0003070a, 0x0004070a, 0x00050708, 0x0006080b, 0x00090c10, 0x00101317, 0x0015181f, 0x001a1d24, 0x0020232a, 0x00252830, 0x002a2d34, 0x002c2f38, 0x002b303a, 0x002b323c, 0x002c343f, 0x002c3640, 0x002e3641, 0x002e343f, 0x002e333e, 0x002e3440, 0x002d3541, 0x00303844, 0x002c3744, 0x002b3844, 0x002a3842, 0x00283640, 0x002b3945, 0x002b3a47, 0x00283945, 0x00253642, 0x0022313e, 0x00202e3c, 0x0022303c, 0x0026343f, 0x00273440, 0x00283642, 0x00283644, 0x00263645, 0x00253746, 0x00263947, 0x002f4250, 0x00314452, 0x002e414e, 0x00293c48, 0x00243844, 0x00253542, 0x002a3844, 0x0026343e, 0x0024313d, 0x0021303c, 0x0024333f, 0x002a3947, 0x00283846, 0x002d404d, 0x00304451, 0x00324654, 0x00324655, 0x00314454, 0x002f4250, 0x00304452, 0x00314553, 0x00314553, 0x00304450, 0x00324450, 0x0030404c, 0x002e3d4c, 0x002f3e4d, 0x00344451, 0x00364553, 0x00374654, 0x00364452, 0x00374250, 0x0037414e, 0x0038404d, 0x00383f4c, 0x00373e4b, 0x00363e4b, 0x00353d48, 0x00343c48, 0x00343c48, 0x00343c48, 0x00343a46, 0x00323844, 0x00303841, 0x002f353e, 0x002e343c, 0x0030363e, 0x0031363f, 0x00303540, 0x00303540, 0x00313740, 0x00323841, 0x00333a45, 0x00363d48, 0x0038404b, 0x0039414c, 0x00383e49, 0x002f323c, 0x0020242b, 0x0010131a, 0x00080b10, 0x00080a10, 0x000a0c10, 0x000b0c11, 0x000b0c11, 0x00090c10, 0x00090c10, 0x00090b10, 0x00090a10, 0x0008090f, 0x0008090f, 0x0007080d, 0x0004060a, 0x00040508, 0x00040508, 0x00040608, 0x00040708, 0x00030409, 0x0003040b, 0x0004050c, 0x00080911, 0x000c0d17, 0x000e131a, 0x0010171f, 0x00121923, 0x00101a24, 0x00131c27, 0x00141e29, 0x0015202a, 0x0015202b, 0x0015232c, 0x0018252f, 0x00192731, 0x001a2833, 0x001b2835, 0x001d2838, 0x001f2b3a, 0x00202c3c, 0x00212d3c, 0x00202f3e, 0x00223140, 0x00233242, 0x00253445, 0x00283747, 0x00283949, 0x00283a4a, 0x00263a4a, 0x00263b49, 0x00243b48, 0x00243741, 0x001f2d38, 0x00131c25, 0x0004080e, 0x00030305, 0x00030303, 0x00020203, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010101, 0x00010101, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00010103, 0x00010103, 0x00020204, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020205, 0x00020408, 0x0001050b, 0x000e151f, 0x00202a38, 0x00243341, 0x00263544, 0x00273845, 0x00263948, 0x00253848, 0x00253948, 0x00263745, 0x00243544, 0x00243241, 0x00212f3d, 0x001f2c39, 0x001c2937, 0x001a2835, 0x00192533, 0x00182331, 0x00182230, 0x0018212c, 0x0016202b, 0x00151f2a, 0x00141e28, 0x00131c25, 0x00111a24, 0x00101922, 0x000f1720, 0x000c141c, 0x000e131c, 0x000c111b, 0x000b1019, 0x000b0f18, 0x000a0e16, 0x000a0d14, 0x000a0c12, 0x00080a10, 0x0005070c, 0x00040509, 0x00040509, 0x00030508, 0x00030508, 0x00040508, 0x00040608, 0x00040608, 0x00040708, 0x00040709, 0x0004070a, 0x00040609, 0x0004070a, 0x0005070a, 0x0004070a, 0x0005070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x00040608, 0x00040608, 0x0007090c, 0x000c0f12, 0x0011141a, 0x00161920, 0x001c2026, 0x0022252c, 0x00282b32, 0x002b2e37, 0x002b3039, 0x002b313b, 0x002c343e, 0x002c343f, 0x002e3440, 0x002f343e, 0x002f333d, 0x002f343f, 0x002f3440, 0x00313844, 0x00303844, 0x002e3844, 0x002c3843, 0x002c3842, 0x002e3b48, 0x00303d4b, 0x002d3c49, 0x002b3b47, 0x00293845, 0x00293644, 0x002a3844, 0x002c3944, 0x002b3844, 0x002c3945, 0x002c3948, 0x002c3c4b, 0x002d404e, 0x00304452, 0x002d414f, 0x002d404d, 0x002c3f4c, 0x002c3f4b, 0x00223441, 0x00223340, 0x00253440, 0x0024323c, 0x0024333e, 0x00253440, 0x0024323f, 0x00263442, 0x002f3e4c, 0x00324351, 0x002c404d, 0x002d4250, 0x00354958, 0x00354858, 0x002f4250, 0x002c414f, 0x00314553, 0x00334554, 0x00324450, 0x00344451, 0x00344350, 0x00344250, 0x00344251, 0x00354351, 0x00364451, 0x00374552, 0x00364451, 0x0037434f, 0x0038414e, 0x0038404d, 0x00383f4c, 0x00373e4b, 0x00363e49, 0x00343c48, 0x00343c48, 0x00343c48, 0x00343c46, 0x00323944, 0x00303742, 0x002f353f, 0x002e343d, 0x002e343c, 0x0030373f, 0x0031383f, 0x00313840, 0x00313840, 0x00313841, 0x00323842, 0x00343c47, 0x00373f49, 0x0038404a, 0x00363e49, 0x002f3440, 0x0021242e, 0x0011141b, 0x00080c12, 0x0007090f, 0x00080a0e, 0x000a0c10, 0x000a0c10, 0x000b0c11, 0x000a0c10, 0x00090c10, 0x00090a10, 0x0008090f, 0x0008090e, 0x0007080d, 0x0005070c, 0x0004060a, 0x00030508, 0x00040508, 0x00040608, 0x00040608, 0x00030409, 0x0003040a, 0x0006070d, 0x000b0c13, 0x000f1018, 0x0010151c, 0x00121820, 0x00131923, 0x00101a24, 0x00131c27, 0x00141e29, 0x00141e29, 0x0014202a, 0x0014212b, 0x0016242e, 0x00192731, 0x001b2833, 0x001c2834, 0x001d2837, 0x001f2b39, 0x00202c3b, 0x00212c3c, 0x00202e3d, 0x0021303f, 0x00233142, 0x00243444, 0x00263546, 0x00273747, 0x00253848, 0x00263949, 0x00243948, 0x00243845, 0x00233440, 0x001c2934, 0x000e171e, 0x0003070b, 0x00020404, 0x00020303, 0x00010303, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00010103, 0x00010103, 0x00020204, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020205, 0x00020408, 0x0002050b, 0x000e151e, 0x00202a37, 0x00243240, 0x00263544, 0x00263846, 0x00263847, 0x00243848, 0x00253948, 0x00263745, 0x00243444, 0x00233040, 0x00202d3c, 0x001d2b38, 0x001c2936, 0x001a2734, 0x00182433, 0x00182331, 0x00182230, 0x0017212c, 0x0016202b, 0x00151f2a, 0x00151e29, 0x00141c26, 0x00131b24, 0x00111923, 0x00101820, 0x000d151e, 0x000e131d, 0x000d111c, 0x000b101a, 0x000b1018, 0x00090e17, 0x00080c15, 0x00090c13, 0x00080b11, 0x0007080e, 0x0005070c, 0x0004060b, 0x00040609, 0x00040609, 0x00040609, 0x00040609, 0x00040608, 0x00040708, 0x00040708, 0x00040609, 0x00040609, 0x0004070a, 0x0004070a, 0x0004070a, 0x0005070a, 0x0005080b, 0x0006080b, 0x0006080b, 0x00050708, 0x00040608, 0x0006080a, 0x000a0b10, 0x000e1016, 0x0014161d, 0x00191c23, 0x001f2128, 0x0024272e, 0x00282c33, 0x002b3037, 0x002b3139, 0x002c333c, 0x002d343d, 0x002f343d, 0x0030343e, 0x0030343e, 0x00303440, 0x00303541, 0x00313843, 0x00303843, 0x002e3842, 0x002d3841, 0x002c3841, 0x002e3944, 0x002e3b48, 0x002e3b48, 0x002f3d49, 0x00313e4a, 0x00323f4c, 0x00323f4b, 0x00313f4a, 0x00303d49, 0x00303d49, 0x00303e4c, 0x00304150, 0x00344855, 0x00354a58, 0x00304452, 0x002c3e4c, 0x00273a48, 0x002c404c, 0x00223541, 0x00213340, 0x0022333f, 0x0021313c, 0x0024343f, 0x00273641, 0x00283643, 0x00283644, 0x002f3f4c, 0x00304150, 0x002b3f4c, 0x002b404c, 0x00324655, 0x00344655, 0x002d404e, 0x002a3e4c, 0x00314452, 0x00344553, 0x00344451, 0x00374553, 0x00384553, 0x00384451, 0x00374452, 0x00374451, 0x00374450, 0x00374451, 0x00374451, 0x0037434f, 0x0038414e, 0x0038404c, 0x00373f4c, 0x00373e4a, 0x00353d48, 0x00343c48, 0x00343c47, 0x00333b46, 0x00323a45, 0x00303742, 0x002f3541, 0x002f353f, 0x002f353f, 0x0030363e, 0x00313840, 0x00323940, 0x00323940, 0x00323941, 0x00333842, 0x00343943, 0x00343c47, 0x00353c47, 0x00333b46, 0x002c343f, 0x00232834, 0x00141620, 0x00080c11, 0x0006090e, 0x00070a0e, 0x00090b0e, 0x000b0c10, 0x000a0c10, 0x000b0c11, 0x000b0c11, 0x000a0b10, 0x0008090f, 0x0007080d, 0x0007080d, 0x0006080c, 0x0005070c, 0x00040609, 0x00040608, 0x00040508, 0x00030507, 0x00030508, 0x00030409, 0x0004040a, 0x0007080d, 0x000c0c13, 0x00101119, 0x0011151c, 0x00111820, 0x00121923, 0x00101924, 0x00121c26, 0x00141d28, 0x00141e29, 0x00141f29, 0x0014212b, 0x0017242d, 0x00192630, 0x001c2832, 0x001c2833, 0x001d2936, 0x001f2b38, 0x00202c3b, 0x00202c3c, 0x00202e3c, 0x00213040, 0x00233141, 0x00243343, 0x00243444, 0x00253545, 0x00253748, 0x00253848, 0x00243846, 0x00223643, 0x0021323d, 0x00192630, 0x000b1219, 0x0003050b, 0x00020405, 0x00010404, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00010103, 0x00010103, 0x00020204, 0x00000204, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00030304, 0x00030408, 0x0004060a, 0x000f141c, 0x00212b35, 0x00243340, 0x00253443, 0x00263745, 0x00263847, 0x00253848, 0x00253848, 0x00263846, 0x00243444, 0x00233140, 0x00202e3c, 0x001d2b38, 0x001b2836, 0x00192634, 0x00182431, 0x00182330, 0x0018222e, 0x0018212c, 0x0016202b, 0x00151f2a, 0x00151d28, 0x00141c26, 0x00131c24, 0x00121a24, 0x00101821, 0x000f161f, 0x000f141e, 0x000d121c, 0x000b101a, 0x000b1018, 0x00090e17, 0x00090c15, 0x00080c13, 0x00080b12, 0x00080910, 0x0006080c, 0x0004060b, 0x00040609, 0x00040609, 0x00040609, 0x00040609, 0x00040609, 0x00040708, 0x00040708, 0x00040609, 0x0004070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x0005070a, 0x0006080b, 0x0007080c, 0x0007080b, 0x00060809, 0x00060809, 0x00050708, 0x0007080c, 0x000b0c12, 0x00101218, 0x0015181f, 0x001b1d24, 0x0020232a, 0x0024282f, 0x00282c32, 0x002a3037, 0x002c313a, 0x002e343d, 0x002f343d, 0x0030343e, 0x0030343d, 0x0030343f, 0x002f3540, 0x002f3740, 0x00303841, 0x002f3841, 0x002d3840, 0x002d3840, 0x002d3842, 0x002d3843, 0x002e3844, 0x00303b47, 0x00333c48, 0x00343f4b, 0x0036404c, 0x0034404c, 0x0034404c, 0x0033404c, 0x0034404f, 0x00344352, 0x00384a58, 0x00384c59, 0x00374957, 0x00304150, 0x00273947, 0x002c404c, 0x00283a46, 0x00273945, 0x00243642, 0x0023343f, 0x00283844, 0x002c3c47, 0x002d3d49, 0x002d3c49, 0x002c3c4a, 0x002f404f, 0x002d404e, 0x002e404f, 0x00304250, 0x00324150, 0x002e3e4d, 0x002c3e4c, 0x00344453, 0x00374655, 0x00374554, 0x00384654, 0x003a4554, 0x00394453, 0x00384453, 0x00384452, 0x00384451, 0x00384451, 0x00384451, 0x0038424f, 0x0037404d, 0x0036404c, 0x00353e4a, 0x00363d49, 0x00353c48, 0x00343b46, 0x00323944, 0x00313843, 0x00303843, 0x00303641, 0x00303640, 0x002f353f, 0x00303640, 0x00303740, 0x00323841, 0x00333842, 0x00333842, 0x00343842, 0x00343843, 0x00343943, 0x00343944, 0x00323843, 0x002c323d, 0x00232833, 0x00171c25, 0x000b0e17, 0x0007090f, 0x00070a0f, 0x00070a0d, 0x00070a0d, 0x00090b10, 0x00090b10, 0x000a0b10, 0x00090b10, 0x00090a10, 0x0007080d, 0x0006080c, 0x0006080c, 0x0006080c, 0x0005070a, 0x00040608, 0x00040608, 0x00040608, 0x00030407, 0x00030408, 0x00030409, 0x0004040a, 0x0006080d, 0x000a0c13, 0x0010111a, 0x0010141c, 0x0010161e, 0x00101821, 0x00101824, 0x00121c26, 0x00141d28, 0x00141e29, 0x0015202a, 0x0017212c, 0x0018232e, 0x001b2630, 0x001c2831, 0x001c2832, 0x001d2935, 0x001f2b38, 0x00202c3a, 0x00202c3c, 0x00202f3e, 0x00223140, 0x00233341, 0x00233241, 0x00243341, 0x00243444, 0x00253647, 0x00243748, 0x00243645, 0x00213441, 0x001f2f39, 0x0017222b, 0x00060e14, 0x00020509, 0x00010405, 0x00000404, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010204, 0x00010204, 0x00000103, 0x00000103, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00030404, 0x00040506, 0x00040709, 0x000c1218, 0x001f2832, 0x0024323d, 0x00243441, 0x00263644, 0x00263745, 0x00253848, 0x00253848, 0x00253645, 0x00243443, 0x00223040, 0x00202e3c, 0x001d2a38, 0x001b2836, 0x00192634, 0x00182431, 0x0018232f, 0x0018222e, 0x0017212c, 0x0016202a, 0x00161e29, 0x00141d28, 0x00131c26, 0x00121a24, 0x00101823, 0x00101720, 0x000f151f, 0x000e141e, 0x000e121c, 0x000c1019, 0x000a0f18, 0x00090e16, 0x00090c14, 0x00090c12, 0x00080c11, 0x00080910, 0x0006080c, 0x0004060b, 0x00040608, 0x00040608, 0x00040608, 0x00040508, 0x00040608, 0x00040608, 0x00040608, 0x00040609, 0x0004070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x0005070a, 0x0006080b, 0x0007080c, 0x0006080b, 0x0004080a, 0x0004080a, 0x00040809, 0x0005080c, 0x00080a0e, 0x000c0e14, 0x0013151a, 0x00181a20, 0x001e2027, 0x0021242b, 0x0024282f, 0x00282c34, 0x002a3038, 0x002c323c, 0x002e343c, 0x002f343c, 0x002f343c, 0x002f353d, 0x002e353e, 0x002e363f, 0x002f3840, 0x002f3841, 0x002e3740, 0x002e3840, 0x002d3641, 0x002d3541, 0x002d3641, 0x002e3742, 0x002f3742, 0x00313945, 0x00343d49, 0x00343f4c, 0x0036404d, 0x0036414e, 0x0035414f, 0x00354351, 0x00394957, 0x003a4c58, 0x00374856, 0x00324451, 0x002c3c4b, 0x002f404d, 0x002e3f4c, 0x0030404d, 0x002b3c48, 0x00263744, 0x002c3c48, 0x0032404d, 0x0032404d, 0x0031404d, 0x00303f4c, 0x00334150, 0x00344452, 0x00354453, 0x00364553, 0x00374454, 0x00344250, 0x00344250, 0x00394855, 0x003c4957, 0x003a4755, 0x003a4755, 0x003a4655, 0x003a4654, 0x00394454, 0x00394451, 0x00384450, 0x00384450, 0x00384350, 0x0037414e, 0x0036404c, 0x00353e4a, 0x00343c48, 0x00353c47, 0x00343a45, 0x00323844, 0x00303841, 0x002f3840, 0x002f3740, 0x00303640, 0x00303640, 0x00303640, 0x00303741, 0x00313841, 0x00333844, 0x00343844, 0x00333743, 0x00323743, 0x00343844, 0x00343944, 0x00333741, 0x002e323c, 0x00242832, 0x00161a23, 0x000c1019, 0x00080c13, 0x00080b10, 0x00080b10, 0x00070a0e, 0x00070a0e, 0x00080a0e, 0x0008090e, 0x0008090e, 0x0008090d, 0x0006080c, 0x0006080c, 0x0006080b, 0x0006080b, 0x0005070a, 0x00040609, 0x00040608, 0x00040508, 0x00040508, 0x00030407, 0x00030407, 0x00030409, 0x0004050b, 0x0007080e, 0x000b0c13, 0x0010111a, 0x0010141e, 0x0010161f, 0x00111821, 0x00101a24, 0x00131c27, 0x00141d28, 0x00141e29, 0x0015202a, 0x0017212c, 0x0018232d, 0x001a2530, 0x001c2731, 0x001d2833, 0x001e2935, 0x001e2a37, 0x00202c39, 0x001f2c3b, 0x001f2f3d, 0x00213140, 0x00223240, 0x00233240, 0x00243341, 0x00243442, 0x00243544, 0x00243545, 0x00243444, 0x00213340, 0x001f2c37, 0x00121c24, 0x00040b11, 0x00020409, 0x00010406, 0x00000405, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00000002, 0x00000002, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010404, 0x00030405, 0x00040608, 0x000a0f15, 0x001c252f, 0x0023303c, 0x00253440, 0x00263543, 0x00273745, 0x00253847, 0x00253747, 0x00253644, 0x00233341, 0x0022303f, 0x00202c3c, 0x001c2a38, 0x001b2836, 0x00192634, 0x00182431, 0x0018232f, 0x0018222d, 0x0017212c, 0x0016202a, 0x00161e28, 0x00141c27, 0x00131b26, 0x00101824, 0x00101823, 0x000e1620, 0x000e141e, 0x000d141d, 0x000e121c, 0x000b1019, 0x000a0f17, 0x00090e16, 0x00090c14, 0x00090c10, 0x00080c0f, 0x00080a0d, 0x0007080a, 0x00040608, 0x00040507, 0x00030507, 0x00030507, 0x00030507, 0x00030507, 0x00040608, 0x00040608, 0x00040608, 0x0004070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x0005070a, 0x0006080b, 0x0006080b, 0x0004080b, 0x0003080b, 0x0003080b, 0x0004080b, 0x0007090d, 0x000a0c10, 0x00101217, 0x0016171c, 0x001c1d24, 0x00202228, 0x0022242c, 0x00242930, 0x00272c35, 0x00293039, 0x002c323a, 0x002d343b, 0x002f353c, 0x002f353c, 0x002d353c, 0x002d363e, 0x002e3640, 0x002f3840, 0x002f3840, 0x002f3840, 0x002f3740, 0x002f353f, 0x002e343e, 0x002e343f, 0x002e343e, 0x002f3540, 0x00313944, 0x00323c47, 0x00343e4b, 0x0036404c, 0x0037404f, 0x0035414f, 0x00374553, 0x00384956, 0x00374854, 0x00354654, 0x00344452, 0x00344453, 0x00344453, 0x00344452, 0x00314050, 0x0030404e, 0x00344453, 0x00394755, 0x00384453, 0x00384454, 0x00394654, 0x003a4754, 0x003a4754, 0x003b4754, 0x003b4654, 0x003b4656, 0x003a4554, 0x003a4654, 0x003c4a57, 0x003c4956, 0x003b4855, 0x003a4754, 0x003b4854, 0x003a4754, 0x003b4553, 0x003a444f, 0x0038424d, 0x0038424c, 0x0037404c, 0x0036404b, 0x00343d48, 0x00323c46, 0x00333b45, 0x00333944, 0x00323844, 0x00303844, 0x002f3841, 0x002e3740, 0x002f3640, 0x00303640, 0x00303742, 0x00303742, 0x00323843, 0x00323844, 0x00333844, 0x00333843, 0x00323642, 0x00323642, 0x00333743, 0x00333843, 0x002e313c, 0x00252830, 0x001a1d24, 0x000d1016, 0x00080c11, 0x00080b11, 0x00080b11, 0x00080b10, 0x00070a0f, 0x00070a0f, 0x00070a0d, 0x0006090c, 0x0006090c, 0x0006090c, 0x0004080b, 0x0005070a, 0x0005070a, 0x0005070a, 0x0004070a, 0x00040609, 0x00040609, 0x00030408, 0x00030408, 0x00030408, 0x00030407, 0x00040508, 0x0005070a, 0x00080a0f, 0x000c0f14, 0x000f1219, 0x0011151f, 0x00111620, 0x00121822, 0x00111a25, 0x00121c27, 0x00141d28, 0x00141e29, 0x0015202a, 0x0017212c, 0x0018222c, 0x001a242f, 0x001b2530, 0x001c2733, 0x001d2834, 0x001e2937, 0x001e2b38, 0x001d2c39, 0x001e2f3c, 0x0020303f, 0x00203340, 0x00223341, 0x00243442, 0x00243442, 0x00243442, 0x00243442, 0x00243442, 0x0021313e, 0x001e2a34, 0x000f1820, 0x0004080f, 0x00020409, 0x00020307, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00000002, 0x00000002, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020405, 0x00030406, 0x00070c12, 0x0019232c, 0x00232f3b, 0x0024323e, 0x00263441, 0x00273644, 0x00253745, 0x00253745, 0x00243544, 0x00223240, 0x00212f3e, 0x001f2c3a, 0x001c2938, 0x001c2836, 0x001a2634, 0x00182432, 0x00182330, 0x0018222e, 0x0016212c, 0x0015202b, 0x00141e29, 0x00141c27, 0x00131b26, 0x00111924, 0x00101822, 0x000e1620, 0x000e141e, 0x000d141d, 0x000e121c, 0x000b1019, 0x000a0f18, 0x00090e18, 0x00090c15, 0x00090c11, 0x00080c0f, 0x00080a0c, 0x00070809, 0x00040608, 0x00040507, 0x00030407, 0x00030407, 0x00030407, 0x00030507, 0x00040608, 0x00040608, 0x00040608, 0x0004070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x0005070a, 0x0005070a, 0x0006080b, 0x0006080b, 0x0004080b, 0x0003080b, 0x0003080b, 0x0004080b, 0x0006080c, 0x00080a0d, 0x000c0e12, 0x00121418, 0x00181a20, 0x001c1f24, 0x001f2228, 0x0022252c, 0x00242930, 0x00272c35, 0x00282f37, 0x002a3038, 0x002d343c, 0x002f353c, 0x002d353c, 0x002d353e, 0x002e3640, 0x002f3840, 0x002f3840, 0x002f3840, 0x002f3740, 0x002f353f, 0x002e343d, 0x002e343d, 0x002e343d, 0x002f353f, 0x002e3640, 0x002d3841, 0x00303945, 0x00323c48, 0x00343d4b, 0x00333f4c, 0x0034414e, 0x00354450, 0x00344450, 0x00344452, 0x00374554, 0x00384655, 0x00374554, 0x00384555, 0x00384655, 0x00384655, 0x003b4858, 0x003c4858, 0x00394654, 0x00394654, 0x003c4857, 0x003c4856, 0x003c4855, 0x003b4754, 0x003b4655, 0x003b4656, 0x003b4654, 0x003c4754, 0x003c4856, 0x003b4855, 0x003b4754, 0x003a4652, 0x003a4652, 0x00394551, 0x00384350, 0x0038414c, 0x0036404b, 0x0036404a, 0x00363f49, 0x00343c47, 0x00313a44, 0x00303942, 0x00303843, 0x00313844, 0x00313843, 0x00303743, 0x002e3740, 0x002e3640, 0x002f3640, 0x00303640, 0x00303742, 0x00323844, 0x00333944, 0x00333944, 0x00343944, 0x00343844, 0x00323742, 0x00313541, 0x00303440, 0x002c303c, 0x00242630, 0x00191c23, 0x000f1217, 0x00080b10, 0x00070a10, 0x00080b11, 0x00080b11, 0x00080b10, 0x00070a0f, 0x00070a0f, 0x00070a0d, 0x0006090c, 0x0006090c, 0x0006090c, 0x0004080b, 0x0005070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x00040609, 0x00040609, 0x00030408, 0x00030408, 0x00030408, 0x00030407, 0x00030508, 0x0006080b, 0x00090c10, 0x000c1015, 0x000e1319, 0x0010151e, 0x00121720, 0x00121822, 0x00111a25, 0x00121c26, 0x00141d28, 0x00141e29, 0x0015202a, 0x0017212c, 0x0018222c, 0x0019232e, 0x001a242f, 0x001b2530, 0x001c2832, 0x001d2935, 0x001e2a38, 0x001d2c39, 0x001e2e3c, 0x0020303f, 0x00203340, 0x00233341, 0x00243342, 0x00243342, 0x00243342, 0x00243342, 0x00243340, 0x0021303c, 0x001c2630, 0x000d141d, 0x0003070e, 0x00030409, 0x00010306, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020405, 0x00030407, 0x00060c11, 0x0018222c, 0x00232f3a, 0x0024313d, 0x00253440, 0x00263542, 0x00253644, 0x00253644, 0x00233443, 0x00223040, 0x00202d3d, 0x001e2b3a, 0x001c2937, 0x001c2836, 0x001a2634, 0x00182432, 0x00182330, 0x0017222f, 0x0015202c, 0x00141f2b, 0x00141d28, 0x00131c27, 0x00131b26, 0x00111a23, 0x00101821, 0x00101620, 0x000f151f, 0x000e141e, 0x000e131c, 0x000c101a, 0x000a0e18, 0x00090d18, 0x00080c16, 0x00080c12, 0x00080c10, 0x00070a0e, 0x0005080b, 0x00030609, 0x00030508, 0x00030408, 0x00030407, 0x00030407, 0x00030507, 0x00040608, 0x00040608, 0x00040608, 0x0004070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x0005070a, 0x0006080b, 0x0006080b, 0x0006080b, 0x0004080b, 0x0003080b, 0x0003080b, 0x0004080b, 0x0005080b, 0x0007080a, 0x000b0c0f, 0x00101114, 0x0015171a, 0x00191c1f, 0x001d1f24, 0x00202228, 0x0022262c, 0x00252931, 0x00272c34, 0x00282d35, 0x002c3038, 0x002e333b, 0x002e343c, 0x002f353e, 0x002f353f, 0x002e3640, 0x002e3740, 0x002f3840, 0x002f3740, 0x002e343e, 0x002c333c, 0x002d343c, 0x002e343d, 0x002e353e, 0x002d353e, 0x002c363e, 0x002d3841, 0x002f3842, 0x00303944, 0x002f3b45, 0x00313e48, 0x0034404c, 0x0033404b, 0x0034414d, 0x00374450, 0x00384551, 0x00384552, 0x00384552, 0x00394654, 0x003a4754, 0x003c4855, 0x003b4654, 0x003a4453, 0x003a4554, 0x003c4856, 0x003b4855, 0x00394654, 0x00384654, 0x003a4554, 0x003c4555, 0x003c4554, 0x003c4654, 0x003a4654, 0x00384452, 0x00384350, 0x0036414e, 0x0037414e, 0x0037414e, 0x0037404c, 0x00363e48, 0x00343d48, 0x00343d48, 0x00343c47, 0x00323944, 0x00303840, 0x00303840, 0x00303740, 0x00303640, 0x00303640, 0x00303640, 0x002f353f, 0x002f3640, 0x00303640, 0x00303740, 0x00303742, 0x00323844, 0x00333944, 0x00343945, 0x00343944, 0x00343943, 0x00323640, 0x002e333c, 0x00292e38, 0x0022252f, 0x00181b22, 0x000e1117, 0x00080c10, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00080b10, 0x00080b0f, 0x00070a0d, 0x0006090c, 0x0006090c, 0x0006090c, 0x0004080b, 0x0004080a, 0x00040709, 0x00040609, 0x00040609, 0x00040508, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00030407, 0x00040508, 0x0006080c, 0x00080c10, 0x000b1015, 0x000e1319, 0x0010151d, 0x0012171f, 0x00121820, 0x00131a24, 0x00131c24, 0x00141d27, 0x00151f2a, 0x0016202b, 0x0018212c, 0x0019232d, 0x001a242f, 0x001a242f, 0x001b2530, 0x001c2732, 0x001d2935, 0x001e2a38, 0x001d2c39, 0x001f2e3b, 0x0020303e, 0x0021323f, 0x0023313f, 0x0024313f, 0x0024313f, 0x0024313f, 0x0024313f, 0x0024313f, 0x00202d38, 0x001a222c, 0x000b0f18, 0x0003050c, 0x00020308, 0x00000205, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00030405, 0x00030508, 0x00070b10, 0x00182129, 0x00232f3a, 0x0024313e, 0x00253440, 0x00263543, 0x00253644, 0x00243544, 0x00223341, 0x00213040, 0x00202d3c, 0x001e2b39, 0x001d2837, 0x001c2835, 0x001a2634, 0x00182432, 0x00182330, 0x0016212f, 0x0014202c, 0x00141e2a, 0x00141d28, 0x00121c26, 0x00131b26, 0x00121b24, 0x00101821, 0x00101720, 0x000f151f, 0x000e141e, 0x000e131d, 0x000c101a, 0x000b0f18, 0x00090d17, 0x00090c14, 0x00090c12, 0x00080c10, 0x00070a0e, 0x0005080c, 0x00030709, 0x00030508, 0x00030408, 0x00030408, 0x00030407, 0x00030507, 0x00040608, 0x00040608, 0x00040608, 0x0004070a, 0x0004070a, 0x0004070a, 0x0005070a, 0x0005070a, 0x0006080b, 0x0006080b, 0x0006080b, 0x0004080b, 0x0003080b, 0x0003080b, 0x0004080b, 0x0005080b, 0x00060809, 0x00090b0c, 0x000d0f12, 0x00121417, 0x0017181c, 0x001a1c1f, 0x001d1f24, 0x00202328, 0x0023262d, 0x00242930, 0x00262b33, 0x00282e36, 0x002b3038, 0x002c323a, 0x002c333b, 0x002c333c, 0x002c343c, 0x002c343e, 0x002d353e, 0x002e353e, 0x002d343d, 0x002c323c, 0x002c333c, 0x002e343d, 0x002e343e, 0x002d353d, 0x002c363c, 0x002c3740, 0x002e3841, 0x002f3843, 0x002f3944, 0x00303a44, 0x00303c47, 0x00303c47, 0x00323e48, 0x0034404c, 0x0037434f, 0x0037434f, 0x0038434f, 0x00384450, 0x00384451, 0x00384452, 0x00384452, 0x00384351, 0x00394353, 0x003a4452, 0x00384451, 0x00364350, 0x00364350, 0x00384351, 0x00394352, 0x00384250, 0x00384250, 0x00374250, 0x0035414e, 0x00343f4c, 0x00343d49, 0x00343c48, 0x00343c49, 0x00343c48, 0x00343c46, 0x00323b45, 0x00313b46, 0x00313a44, 0x00313843, 0x0030363f, 0x0030363f, 0x0030363f, 0x00303640, 0x00303640, 0x002f3540, 0x002f353f, 0x002f353f, 0x00303640, 0x00303740, 0x00303742, 0x00313843, 0x00323844, 0x00333944, 0x00333843, 0x0031343f, 0x002d3039, 0x00272b33, 0x0020242c, 0x00181c24, 0x00101319, 0x00080c11, 0x00070a0f, 0x00070a0f, 0x00080b10, 0x00080b10, 0x00070a0f, 0x00070a0f, 0x00080b10, 0x00080b0f, 0x00070a0d, 0x0006090c, 0x0006090c, 0x0006090c, 0x0004080b, 0x0003070a, 0x00040608, 0x00040609, 0x00040609, 0x00030508, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x0004050a, 0x0008080f, 0x000b0e14, 0x000c1018, 0x000f131c, 0x0010151d, 0x0011171f, 0x00121820, 0x00131a24, 0x00141c25, 0x00141d27, 0x00151f2a, 0x0016202b, 0x0018212c, 0x0019232d, 0x001a242f, 0x001a2430, 0x001a2531, 0x001b2833, 0x001c2835, 0x001c2a38, 0x001d2c39, 0x001f2e3b, 0x0020303d, 0x0021323f, 0x0023313f, 0x0024313f, 0x0024313f, 0x0024313f, 0x0024313f, 0x0023313e, 0x001e2c38, 0x00161f28, 0x00080c14, 0x00030409, 0x00020308, 0x00010305, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00010204, 0x00010204, 0x00010204, 0x00010203, 0x00010103, 0x00010203, 0x00010203, 0x00010203, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00030406, 0x00030507, 0x00060a0e, 0x00182026, 0x00233039, 0x00233240, 0x00233442, 0x00243444, 0x00243544, 0x00243443, 0x00223240, 0x0021303f, 0x00202d3c, 0x001f2b39, 0x001d2837, 0x001c2735, 0x00192533, 0x00182331, 0x00182230, 0x0017202e, 0x0015202c, 0x00141e2a, 0x00131c28, 0x00121c26, 0x00121a25, 0x00121a24, 0x00111822, 0x00101720, 0x000f151f, 0x000e141e, 0x000f131c, 0x000c101a, 0x000b1018, 0x00090e14, 0x00080c13, 0x00090c12, 0x00080c10, 0x00080a10, 0x0007090d, 0x0004080b, 0x00040609, 0x00030408, 0x00030407, 0x00030406, 0x00030505, 0x00040507, 0x00040508, 0x00040608, 0x00040609, 0x0004070a, 0x0005070a, 0x0005070a, 0x0006080b, 0x0006080b, 0x0006080b, 0x0006080b, 0x0005080c, 0x0005080b, 0x0004080b, 0x0004080b, 0x0005080b, 0x0006080b, 0x00080a0d, 0x000c0e11, 0x00111316, 0x00141619, 0x0017191c, 0x001a1c21, 0x001c2026, 0x0020242a, 0x0022272d, 0x00242930, 0x00282c34, 0x00282e36, 0x00293038, 0x002a3039, 0x002b313b, 0x002c323c, 0x002c333c, 0x002e343d, 0x002e343d, 0x002c343d, 0x002c333c, 0x002c333c, 0x002c343c, 0x002d343d, 0x002d353d, 0x002c363d, 0x002d3740, 0x002e3841, 0x002f3842, 0x00303842, 0x00303842, 0x00303a43, 0x00303a44, 0x00303a45, 0x00333c48, 0x00343d49, 0x00343e49, 0x00353e4a, 0x00353e4b, 0x00343e4b, 0x00343f4c, 0x00343f4c, 0x0035404d, 0x0037404e, 0x0037404e, 0x0036404c, 0x00343f4a, 0x0034404b, 0x0034404c, 0x0036404c, 0x0036404c, 0x00353f4b, 0x0034404b, 0x00343e4a, 0x00343e49, 0x00333c48, 0x00333c47, 0x00333b46, 0x00323a44, 0x00313943, 0x00313944, 0x00303844, 0x00303742, 0x00303640, 0x002f353f, 0x002f353f, 0x002f3540, 0x002f3440, 0x002f3440, 0x002f3540, 0x002f3540, 0x002f3540, 0x00303540, 0x00303540, 0x00303640, 0x00313840, 0x00313841, 0x00313841, 0x0030353f, 0x002d3039, 0x00272931, 0x00202329, 0x00181b21, 0x00101318, 0x000b0e14, 0x00080b10, 0x00070a0f, 0x00080b10, 0x00080b10, 0x00080b0f, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x0007090d, 0x0006090c, 0x0005080b, 0x0005080b, 0x0004070a, 0x00040609, 0x00040508, 0x00040508, 0x00040508, 0x00030408, 0x00030408, 0x00030407, 0x00030407, 0x00030407, 0x00030408, 0x0006070c, 0x000a0b12, 0x000c1017, 0x000d111a, 0x000f131d, 0x0010151e, 0x0010171e, 0x00101820, 0x00111a24, 0x00121c26, 0x00141d28, 0x00141e29, 0x0015202a, 0x0017202b, 0x0018222c, 0x0019232f, 0x00192430, 0x00192531, 0x001a2834, 0x001a2835, 0x001c2a38, 0x001c2c38, 0x001e2d3b, 0x001f303d, 0x0020313e, 0x0023313f, 0x0024313f, 0x0023313f, 0x0024313f, 0x0023313f, 0x0021303d, 0x001d2b36, 0x00121b23, 0x00060b10, 0x00030408, 0x00020305, 0x00020305, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000304, 0x00000304, 0x00000304, 0x00000304, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00000102, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00020405, 0x00020404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00030406, 0x00030507, 0x0005080d, 0x00181f25, 0x00222f39, 0x00203240, 0x00223442, 0x00243544, 0x00243544, 0x00243443, 0x00233140, 0x0021303f, 0x00202d3c, 0x001f2b39, 0x001d2837, 0x001c2734, 0x00182432, 0x00182230, 0x0018212f, 0x0017202e, 0x0016202c, 0x00141e2b, 0x00141d28, 0x00121c26, 0x00111b25, 0x00121a24, 0x00121923, 0x00101720, 0x00101620, 0x000f151e, 0x000e141b, 0x000c1018, 0x000b1016, 0x00090e13, 0x00080d11, 0x00080c12, 0x00080c12, 0x00090a11, 0x0008090f, 0x0006080d, 0x0004060a, 0x00030508, 0x00030507, 0x00030504, 0x00030504, 0x00030506, 0x00040508, 0x00040609, 0x00040609, 0x00040609, 0x0005070a, 0x0006080b, 0x0006080b, 0x0007080c, 0x0007080c, 0x0007080c, 0x0007080c, 0x0006080c, 0x0004080b, 0x0004080b, 0x0005080b, 0x0006080b, 0x0007080c, 0x000a0c10, 0x000f1014, 0x00131418, 0x0015181a, 0x00181c20, 0x001b1e24, 0x001d2228, 0x0020252c, 0x0024282f, 0x00272c32, 0x00282d35, 0x00282f36, 0x00293038, 0x002a303a, 0x002b313b, 0x002c323c, 0x002c333c, 0x002d343d, 0x002c343d, 0x002c343c, 0x002a333c, 0x002a333c, 0x002c343c, 0x002c343d, 0x002d353f, 0x002d3640, 0x002d3840, 0x002d3840, 0x002e3840, 0x002e3840, 0x002e3840, 0x002f3840, 0x00303942, 0x00323a44, 0x00333b44, 0x00333c45, 0x00333c46, 0x00333b46, 0x00313b46, 0x00313b47, 0x00333c48, 0x00343f4b, 0x00353f4b, 0x00353f4a, 0x00353f49, 0x00323c47, 0x00313c46, 0x00323c47, 0x00333d48, 0x00343d48, 0x00333d48, 0x00323d48, 0x00333d48, 0x00323c47, 0x00333c47, 0x00343c47, 0x00333b46, 0x00323a44, 0x00313843, 0x00313843, 0x00303842, 0x00303641, 0x002f343e, 0x002e343d, 0x002e343f, 0x002e343f, 0x002f3440, 0x002f3440, 0x00303640, 0x00303640, 0x00303640, 0x00303540, 0x00313540, 0x0030353e, 0x0030363e, 0x0030363e, 0x002e343d, 0x002b3038, 0x00262931, 0x001e2128, 0x00181b20, 0x00101418, 0x000a0d11, 0x00080c10, 0x00080b10, 0x00080b10, 0x00080b10, 0x00080b10, 0x00070a0f, 0x0006090e, 0x0006090e, 0x0006090e, 0x0006090d, 0x0007080c, 0x0006080b, 0x0005070a, 0x0005070a, 0x00040609, 0x00040508, 0x00030508, 0x00030508, 0x00030508, 0x00030507, 0x00030407, 0x00020405, 0x00020405, 0x00030406, 0x00040609, 0x0008080e, 0x000b0c14, 0x000d1018, 0x000e121a, 0x000f141e, 0x000e161e, 0x000e181e, 0x000e1820, 0x000e1923, 0x00101b25, 0x00111c26, 0x00141d28, 0x00141f29, 0x0016202b, 0x0018212c, 0x0018232d, 0x00182430, 0x00192531, 0x001a2834, 0x00192835, 0x001b2a38, 0x001c2b38, 0x001d2d3a, 0x001e2f3c, 0x0020303e, 0x0022303e, 0x0023313e, 0x0022313e, 0x0022313e, 0x0021303d, 0x001f2e3b, 0x001b2832, 0x0010181e, 0x0004090c, 0x00030406, 0x00030305, 0x00020206, 0x00020206, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00000102, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00020404, 0x00020404, 0x00010304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020405, 0x00030406, 0x0004080c, 0x00171d24, 0x00222f38, 0x00213240, 0x00223441, 0x00243442, 0x00243442, 0x00243441, 0x00233140, 0x0021303f, 0x00202d3c, 0x001f2b39, 0x001d2837, 0x001c2734, 0x00182432, 0x00182230, 0x0018212f, 0x0017202e, 0x0016202c, 0x00141e2b, 0x00141d28, 0x00121c27, 0x00101b26, 0x00111a25, 0x00111924, 0x00101823, 0x000f1620, 0x000e141e, 0x000e141b, 0x000c1117, 0x000b1015, 0x00090e12, 0x00080d11, 0x00080c12, 0x00080c12, 0x00090a11, 0x00090a10, 0x0007080d, 0x0004060a, 0x00030408, 0x00030407, 0x00030404, 0x00030405, 0x00030408, 0x00040508, 0x00040609, 0x00040609, 0x00040609, 0x0005070a, 0x0006080b, 0x0006080b, 0x0007080c, 0x0007080c, 0x0007080c, 0x0007080c, 0x0007080c, 0x0005080b, 0x0005080b, 0x0006080b, 0x0006080b, 0x0006080b, 0x00080a0e, 0x000c0e12, 0x00101114, 0x00121418, 0x0015181d, 0x00181c21, 0x001c2026, 0x001e2329, 0x0022272d, 0x00242930, 0x00262c34, 0x00272d35, 0x00282e37, 0x00282f38, 0x00293039, 0x002a303a, 0x002b313b, 0x002b323c, 0x002a323b, 0x002a333c, 0x0029323b, 0x0029323c, 0x002b333c, 0x002c343c, 0x002c343d, 0x002c353f, 0x002c3640, 0x002c3740, 0x002c3740, 0x002c373e, 0x002c373e, 0x002e383f, 0x00303841, 0x00313942, 0x00323a43, 0x00323a43, 0x00333b44, 0x00323a45, 0x00313a44, 0x00313a46, 0x00313c48, 0x00333e4a, 0x00343e4a, 0x00343d48, 0x00343e48, 0x00323c47, 0x00313b46, 0x00313b46, 0x00323b46, 0x00323b44, 0x00313b44, 0x00303b44, 0x00303b44, 0x00303b44, 0x00313b44, 0x00323a45, 0x00323a44, 0x00313944, 0x00313843, 0x00313841, 0x002f353f, 0x002e343d, 0x002d323c, 0x002c333c, 0x002e343e, 0x002f343f, 0x00303540, 0x00303540, 0x00303640, 0x00303640, 0x00303640, 0x0030343f, 0x002f343d, 0x002d333c, 0x002c333a, 0x002a3138, 0x00282f37, 0x00252a32, 0x0020232b, 0x00181c23, 0x0013161a, 0x000c0f13, 0x00080b0e, 0x00070a0f, 0x00080b10, 0x00080b10, 0x00080b10, 0x00080b10, 0x00070a0f, 0x0006090e, 0x0006090d, 0x0006090d, 0x0006090c, 0x0006080c, 0x0006080b, 0x0005070a, 0x00040609, 0x00040609, 0x00030508, 0x00030408, 0x00030408, 0x00030408, 0x00030407, 0x00030407, 0x00020404, 0x00020404, 0x00020405, 0x0004060a, 0x0008090f, 0x000c0c14, 0x000e1018, 0x000e131b, 0x000f141e, 0x000e161e, 0x000d181e, 0x000e1820, 0x000e1923, 0x00101b25, 0x00101c26, 0x00141d27, 0x00141f29, 0x0016202b, 0x0018212c, 0x0018232d, 0x00182430, 0x00192531, 0x001a2734, 0x001a2835, 0x001c2a37, 0x001d2b38, 0x001e2d3a, 0x001e2f3c, 0x0020303d, 0x0021303e, 0x0021303e, 0x0022303e, 0x0021303d, 0x0020303a, 0x001e2d38, 0x0018242e, 0x000d1419, 0x00040708, 0x00030404, 0x00030304, 0x00020205, 0x00020206, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00000102, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020405, 0x00020405, 0x00010404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00020405, 0x00020405, 0x0004080c, 0x00161e24, 0x00222f38, 0x0022323e, 0x0021323f, 0x00233340, 0x00243440, 0x00243440, 0x0023323f, 0x0021303d, 0x00202d3b, 0x001f2b39, 0x001c2937, 0x001c2734, 0x00182432, 0x00182230, 0x0018212f, 0x0017202e, 0x0016202c, 0x00141e2b, 0x00141d29, 0x00121c28, 0x00101b27, 0x00101b25, 0x00101924, 0x00101823, 0x000d1520, 0x000e141e, 0x000d141b, 0x000b1117, 0x000b1016, 0x00090e14, 0x00080d13, 0x00080c13, 0x00090c13, 0x000a0b12, 0x00090b10, 0x0007080d, 0x0004060a, 0x00030508, 0x00030508, 0x00030507, 0x00030507, 0x00030508, 0x00040508, 0x00040609, 0x00040609, 0x00040609, 0x0005070a, 0x0006080b, 0x0006080b, 0x0007080c, 0x0007080c, 0x0007080c, 0x0007080c, 0x0007080c, 0x0006080b, 0x0007080c, 0x0007080c, 0x0007080c, 0x0007080c, 0x0007080c, 0x000a0c0f, 0x000d0f13, 0x00101316, 0x0014171b, 0x00171a1f, 0x001a1d24, 0x001d2027, 0x0020242b, 0x0022272e, 0x00242a32, 0x00252c33, 0x00262c34, 0x00282d37, 0x00282f38, 0x002a3039, 0x002a3039, 0x002a3039, 0x002a3038, 0x002a3139, 0x002a3139, 0x002b3139, 0x002c323a, 0x002c333a, 0x002c343c, 0x002d343d, 0x002c353e, 0x002d3640, 0x002d363f, 0x002c373e, 0x002c373d, 0x002d373e, 0x002f3840, 0x002f3840, 0x00303840, 0x00313942, 0x00323a43, 0x00323a43, 0x00323a43, 0x00323a45, 0x00333c47, 0x00333d48, 0x00343e48, 0x00333d48, 0x00333d47, 0x00323c47, 0x00313c47, 0x00323b46, 0x00323b45, 0x00323a43, 0x00313942, 0x00303a42, 0x00303942, 0x00303942, 0x00303943, 0x00313944, 0x00313944, 0x00313944, 0x00303742, 0x00303640, 0x002d343d, 0x002c323c, 0x002c333c, 0x002c333c, 0x002c333c, 0x002e343e, 0x00303640, 0x00303640, 0x002f353f, 0x002f353e, 0x002e343d, 0x002d333c, 0x002c303b, 0x002a2f38, 0x00272d35, 0x00252c34, 0x00232830, 0x0020242c, 0x001b1e26, 0x0014181e, 0x000e1116, 0x00080c0f, 0x00060a0d, 0x00060c0e, 0x00060c0e, 0x00070b0f, 0x00080b10, 0x00080b10, 0x00080b10, 0x00070a0f, 0x00070a0e, 0x0005080c, 0x0004080c, 0x0005080b, 0x0006080b, 0x0005070a, 0x00040609, 0x00040609, 0x00030508, 0x00030508, 0x00030508, 0x00030508, 0x00030508, 0x00030508, 0x00020405, 0x00020405, 0x00020405, 0x0005070b, 0x00090b10, 0x000c0e14, 0x000f1118, 0x000f131b, 0x0010141e, 0x000f151e, 0x000e171e, 0x000f1820, 0x000f1922, 0x00101b24, 0x00121c24, 0x00141d26, 0x00141f28, 0x0016202b, 0x0018212c, 0x0019232d, 0x0019242e, 0x001b2530, 0x001c2733, 0x001c2834, 0x001c2a36, 0x001e2b37, 0x00202d38, 0x00202f3b, 0x0020303d, 0x0021303e, 0x0021303d, 0x0021303d, 0x0020303c, 0x00202f3a, 0x001e2c38, 0x0017222b, 0x00091014, 0x00040507, 0x00030403, 0x00020304, 0x00020205, 0x00020205, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00000102, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00020404, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00030405, 0x00030405, 0x0004080c, 0x00161e24, 0x00222f38, 0x0022323d, 0x0021323f, 0x0023333f, 0x0024343f, 0x0024343f, 0x0023323f, 0x0020303d, 0x00202d3b, 0x001e2b39, 0x001c2937, 0x001c2734, 0x00182432, 0x00182230, 0x0018212f, 0x0017202e, 0x0016202c, 0x00141e2b, 0x00141d28, 0x00121c28, 0x00111b27, 0x00111a25, 0x00111924, 0x00101823, 0x000f1620, 0x000f151e, 0x000d141b, 0x000a1117, 0x000a1016, 0x00090e14, 0x00080d13, 0x00080c13, 0x00090c13, 0x000a0b12, 0x00090b10, 0x0008080e, 0x0004060a, 0x00030408, 0x00030408, 0x00030407, 0x00030407, 0x00030408, 0x00040508, 0x00040609, 0x00040609, 0x00040609, 0x0005070a, 0x0006080b, 0x0006080b, 0x0007080c, 0x0007080c, 0x0006080b, 0x0006080b, 0x0006080b, 0x0006080b, 0x0007080c, 0x0007080c, 0x0007080c, 0x0006080b, 0x0006080b, 0x0008090c, 0x000c0d10, 0x000e1014, 0x00111418, 0x0015181c, 0x00181c20, 0x001b1e24, 0x001d2228, 0x0020252c, 0x00232830, 0x00242931, 0x00242a32, 0x00272c34, 0x00282d35, 0x00292e36, 0x002a2f37, 0x002a2f37, 0x00293038, 0x002a3038, 0x002a3038, 0x002a3038, 0x002b3139, 0x002c323a, 0x002c323a, 0x002c333c, 0x002c343d, 0x002d353e, 0x002d353e, 0x002c353c, 0x002c353c, 0x002c353c, 0x002e3640, 0x002e3640, 0x002f3840, 0x00303841, 0x00313a43, 0x00323a43, 0x00323a43, 0x00323b44, 0x00333c47, 0x00333c47, 0x00333d48, 0x00323c47, 0x00323c46, 0x00323c47, 0x00323b46, 0x00333b45, 0x00323a44, 0x00323a43, 0x00313942, 0x00303841, 0x00303841, 0x00303841, 0x00303842, 0x00303843, 0x00313843, 0x00303842, 0x00303641, 0x002f353f, 0x002c333c, 0x002c323c, 0x002c333c, 0x002c333c, 0x002c333c, 0x002d343c, 0x002d343d, 0x002d343d, 0x002d333c, 0x002b313b, 0x002a303a, 0x002a3039, 0x00282d36, 0x00252b33, 0x00222830, 0x0020272e, 0x001d242b, 0x001a1f27, 0x0014171f, 0x000f1218, 0x000a0d12, 0x00080b0e, 0x00060a0d, 0x00060c0e, 0x00060c0e, 0x00070b0f, 0x00080b10, 0x00080b10, 0x00080b10, 0x00070a0f, 0x0006090e, 0x0005080c, 0x0004080c, 0x0005080b, 0x0005070a, 0x0004070a, 0x00040609, 0x00040609, 0x00030508, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00020407, 0x00020407, 0x00030407, 0x0006080c, 0x000a0b11, 0x000d0f15, 0x000f1218, 0x000f131b, 0x0010141e, 0x000f151e, 0x000f171e, 0x0010181f, 0x000f1921, 0x00111b24, 0x00121c24, 0x00141d26, 0x00141f28, 0x0016202b, 0x0018212c, 0x0019232d, 0x0019232e, 0x001b2530, 0x001c2733, 0x001c2834, 0x001e2a35, 0x001e2a36, 0x00202c38, 0x00202f3b, 0x0021303d, 0x0021303e, 0x0021303d, 0x0020303d, 0x001f2f3c, 0x001f2e39, 0x001c2934, 0x00141e25, 0x00060c10, 0x00020407, 0x00020402, 0x00020303, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000102, 0x00000102, 0x00000102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000102, 0x00000102, 0x00000102, 0x00000102, 0x00000102, 0x00010102, 0x00010102, 0x00010102, 0x00010102, 0x00010102, 0x00010103, 0x00000104, 0x00000104, 0x00000104, 0x00000104, 0x00000204, 0x00000203, 0x00000203, 0x00000203, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010304, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00030405, 0x00030407, 0x0003070b, 0x00121920, 0x00222e38, 0x0022323d, 0x0021323e, 0x0022333e, 0x00213440, 0x00223340, 0x0022313e, 0x00202f3c, 0x00202d3a, 0x001e2b38, 0x001c2836, 0x001c2734, 0x00192431, 0x00182230, 0x0018212e, 0x0017202e, 0x0016202b, 0x00141e28, 0x00141c28, 0x00131b26, 0x00121b26, 0x00121a25, 0x00111924, 0x00111723, 0x00101621, 0x000e141f, 0x000d141b, 0x000a1117, 0x000a1016, 0x00080d14, 0x00080c13, 0x00080c12, 0x00080c12, 0x00090a11, 0x00080910, 0x0008080e, 0x0006080b, 0x00040609, 0x00040508, 0x00030507, 0x00030507, 0x00030508, 0x00040508, 0x00040608, 0x00040608, 0x00040608, 0x0004070a, 0x0005070a, 0x0005070a, 0x0006080b, 0x0006080b, 0x0007080c, 0x0007080c, 0x0006080b, 0x0006080b, 0x0006080b, 0x0006080b, 0x0006080c, 0x0006080c, 0x0005080b, 0x0006080c, 0x00080b0e, 0x000c0f12, 0x000f1215, 0x0013161b, 0x0016191e, 0x00181c22, 0x001b2026, 0x001f2329, 0x0021252c, 0x0023272e, 0x00242830, 0x00262b33, 0x00282c34, 0x00292e36, 0x002a2f37, 0x00292f37, 0x00292f37, 0x002a3038, 0x002a3038, 0x002a3038, 0x002b3039, 0x002b313a, 0x002c323b, 0x002c333c, 0x002c343d, 0x002c343d, 0x002d353e, 0x002d343c, 0x002c343d, 0x002c343d, 0x002d353f, 0x002d353f, 0x002f3740, 0x00303841, 0x00323a43, 0x00323a43, 0x00323a43, 0x00323b44, 0x00333b46, 0x00333c46, 0x00323c47, 0x00333c46, 0x00333b46, 0x00323b45, 0x00323a44, 0x00333a44, 0x00323943, 0x00323942, 0x00313941, 0x00303841, 0x00303841, 0x00303841, 0x00313841, 0x00313841, 0x00313741, 0x00303640, 0x0030353f, 0x002e333c, 0x002c303a, 0x002c303a, 0x002c323b, 0x002c323a, 0x002c323a, 0x002c323a, 0x002c323a, 0x002c3139, 0x002b3039, 0x00292e38, 0x00282c36, 0x00272c34, 0x00242931, 0x0022272e, 0x0020242c, 0x001e2229, 0x001b1f25, 0x00161a20, 0x0010141b, 0x000b0e14, 0x00080b10, 0x00080b0e, 0x00080b0e, 0x00070c0e, 0x00060b0e, 0x00070b0e, 0x00080b0f, 0x00080b0f, 0x00070a0e, 0x0006090d, 0x0005080c, 0x0004080c, 0x0004080c, 0x0005080b, 0x0005070a, 0x0004070a, 0x00040609, 0x00040609, 0x00040509, 0x00030508, 0x00030508, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00040508, 0x0007080d, 0x000a0c12, 0x000c0f16, 0x000e1218, 0x000e131b, 0x000f141d, 0x0010161f, 0x0010171f, 0x00101820, 0x00101821, 0x00121a24, 0x00121c24, 0x00131d25, 0x00141f27, 0x0015202a, 0x0017212c, 0x0018222d, 0x0019232e, 0x001b2530, 0x001c2733, 0x001c2834, 0x001e2a35, 0x001e2a36, 0x00202c38, 0x00202e3b, 0x0021303d, 0x0021303e, 0x0021303d, 0x0020303c, 0x001e2f3b, 0x001e2d38, 0x001b2731, 0x00101820, 0x0004080e, 0x00020307, 0x00010303, 0x00010202, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000303, 0x00000303, 0x00000303, 0x00000303, 0x00000303, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000201, 0x00000201, 0x00000201, 0x00000102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010303, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020304, 0x00030304, 0x00030406, 0x0003060c, 0x00111820, 0x00222e38, 0x0021323b, 0x0020323c, 0x0020333d, 0x001e333f, 0x0020323f, 0x0020303d, 0x00202e3b, 0x001f2c39, 0x001d2938, 0x001c2835, 0x001b2632, 0x001a242f, 0x0019222d, 0x0018212c, 0x0018202c, 0x0016202a, 0x00141d28, 0x00131c27, 0x00131b26, 0x00131b26, 0x00121a25, 0x00111924, 0x00111723, 0x00101621, 0x000e141f, 0x000c131a, 0x000a1117, 0x00091015, 0x00080d11, 0x00070c10, 0x00080b11, 0x00080a11, 0x00080910, 0x0008080e, 0x0007080d, 0x0008080c, 0x0005070a, 0x00040507, 0x00030407, 0x00030407, 0x00030408, 0x00030408, 0x00030408, 0x00030407, 0x00030407, 0x00040508, 0x00040609, 0x00040609, 0x00040609, 0x0005070a, 0x0007080c, 0x0008090c, 0x0007080c, 0x0005070a, 0x0005070a, 0x0004080b, 0x0004080b, 0x0004090c, 0x0004080c, 0x0004080b, 0x00070a0c, 0x000b0e11, 0x000e1215, 0x0012151a, 0x0015181d, 0x00181b20, 0x001a1d24, 0x001d2027, 0x0020232a, 0x0023252c, 0x0024272e, 0x00242931, 0x00262b33, 0x00282d35, 0x00292e36, 0x00292e36, 0x00292e36, 0x00292e36, 0x00292e36, 0x002a2f37, 0x002c3039, 0x002a303a, 0x002b313b, 0x002b323c, 0x002c343c, 0x002d343d, 0x002e343d, 0x002e343d, 0x002c333d, 0x002c323c, 0x002c333e, 0x002e3540, 0x002f3740, 0x00303942, 0x00313a43, 0x00323a43, 0x00323a43, 0x00323a43, 0x00323b44, 0x00323b44, 0x00323a45, 0x00323a45, 0x00323a44, 0x00323a44, 0x00313844, 0x00313843, 0x00313842, 0x00313841, 0x00313841, 0x00303841, 0x00303841, 0x00303841, 0x00303740, 0x00303740, 0x00303640, 0x002f343e, 0x002e333c, 0x002c3139, 0x002a2f37, 0x002a2f37, 0x002b3038, 0x002b3139, 0x002b3139, 0x002b3139, 0x002b3038, 0x002a2f37, 0x00282d35, 0x00272c34, 0x00242931, 0x00232830, 0x0021262e, 0x0020242a, 0x001d2126, 0x001b1e24, 0x00181b20, 0x0013161b, 0x000c1016, 0x00080b11, 0x00080b10, 0x00080b0f, 0x00080c0f, 0x00080b0e, 0x00070a0d, 0x0006090c, 0x0006090c, 0x0006090c, 0x0007080c, 0x0006080b, 0x0005070a, 0x0005070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x00040609, 0x00040508, 0x00040508, 0x00040609, 0x00030508, 0x00030408, 0x00030406, 0x00020405, 0x00030408, 0x00040508, 0x00040508, 0x00040609, 0x0008090d, 0x00090d12, 0x000c1016, 0x000c1118, 0x000c131a, 0x000c141c, 0x0010161f, 0x00121720, 0x00121720, 0x00111821, 0x00121924, 0x00131b25, 0x00141d25, 0x00141f27, 0x0015202a, 0x0018212c, 0x0018222c, 0x0019232e, 0x001b2530, 0x001c2733, 0x001c2834, 0x001e2a35, 0x001e2a36, 0x00202c38, 0x00202e3a, 0x00202f3c, 0x0021303d, 0x0021303e, 0x0020303c, 0x001f2f3a, 0x001d2b37, 0x0018242e, 0x000b131b, 0x0004060c, 0x00020206, 0x00020203, 0x00010203, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000201, 0x00000201, 0x00000201, 0x00000102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010303, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020304, 0x00030304, 0x00030404, 0x0003060b, 0x000e141c, 0x00212d38, 0x0021313c, 0x0020313c, 0x0020323c, 0x001f333f, 0x0020323f, 0x00202f3c, 0x00202d3b, 0x001e2c39, 0x001c2a38, 0x001c2835, 0x001b2731, 0x0019242f, 0x0019232c, 0x0018212c, 0x0018202c, 0x0015202a, 0x00141d28, 0x00131c27, 0x00131b26, 0x00131b26, 0x00121a25, 0x00111924, 0x00111723, 0x00101621, 0x000f141f, 0x000c131a, 0x000a1117, 0x00091015, 0x00080d11, 0x00070c10, 0x00070b10, 0x00070a10, 0x0007090f, 0x0007080d, 0x0007080d, 0x0008080c, 0x0006080b, 0x00030507, 0x00030407, 0x00030407, 0x00030408, 0x00030408, 0x00030408, 0x00030407, 0x00030507, 0x00040508, 0x00040609, 0x00040609, 0x00040609, 0x0005070a, 0x0007080c, 0x0008080c, 0x0007080c, 0x0005080b, 0x0005080b, 0x0004080b, 0x0004090c, 0x0004090c, 0x0004090c, 0x0003080a, 0x0004080b, 0x00080c0f, 0x000c1013, 0x00101318, 0x0014171c, 0x0015181e, 0x00181b22, 0x001b1e24, 0x001e2128, 0x0020242a, 0x0022242c, 0x0022272f, 0x00242931, 0x00272c34, 0x00282d35, 0x00292e36, 0x00292e36, 0x00292e36, 0x00292e36, 0x002a2f37, 0x002b3038, 0x002a303a, 0x002a303a, 0x0029303a, 0x002b333c, 0x002c343c, 0x002e343d, 0x002e343e, 0x002c333d, 0x002b313c, 0x002c323d, 0x002d353f, 0x002f3740, 0x00303841, 0x00313942, 0x00313942, 0x00313942, 0x00313942, 0x00313942, 0x00313942, 0x00313944, 0x00313944, 0x00313944, 0x00313844, 0x00313843, 0x00303742, 0x00303641, 0x00303740, 0x00303740, 0x00303740, 0x002f3740, 0x00303640, 0x002f353f, 0x002e343e, 0x002d343c, 0x002d323c, 0x002c3039, 0x002a2f37, 0x00282d35, 0x00282d35, 0x002a2f37, 0x002a3036, 0x002c3038, 0x002b3038, 0x00292e36, 0x00282c34, 0x00252a33, 0x00242830, 0x0022272f, 0x0020242c, 0x001f232b, 0x001d2127, 0x001b1e23, 0x00181b20, 0x0014181c, 0x00101317, 0x000a0d12, 0x00070a10, 0x00070a0f, 0x00080b10, 0x00080b0f, 0x00070a0e, 0x00070a0c, 0x0006090c, 0x0006090c, 0x0006090c, 0x0006080b, 0x0004060a, 0x00040609, 0x0004070a, 0x0004070a, 0x0004070a, 0x00040609, 0x00040508, 0x00030408, 0x00030406, 0x00040508, 0x00030508, 0x00030408, 0x00030406, 0x00020405, 0x00030408, 0x00040508, 0x00040609, 0x0006080b, 0x000a0c0f, 0x000a0e12, 0x000b1016, 0x000b1118, 0x000b131a, 0x000c141c, 0x0010161f, 0x00121720, 0x00121720, 0x00111720, 0x00121824, 0x00121a25, 0x00141d26, 0x00141f27, 0x0015202a, 0x0018212c, 0x0018222c, 0x0019232e, 0x001b2530, 0x001c2733, 0x001c2834, 0x001e2935, 0x001f2a36, 0x00202c38, 0x00202e3a, 0x00202e3b, 0x0020303c, 0x0020303c, 0x001f303b, 0x001e2d38, 0x001c2a35, 0x0016212c, 0x00081018, 0x0003050b, 0x00020206, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000201, 0x00000201, 0x00000201, 0x00000102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010303, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020304, 0x00030304, 0x00030404, 0x0002060a, 0x000a1019, 0x001d2a34, 0x0021303b, 0x0020303b, 0x0020303c, 0x001f323c, 0x0020323d, 0x00202f3c, 0x00202d3b, 0x001f2c39, 0x001c2a38, 0x001b2835, 0x001a2731, 0x0018242f, 0x0018232c, 0x0018212c, 0x0017212c, 0x0015202a, 0x00141e28, 0x00131c27, 0x00131b26, 0x00131b26, 0x00121a25, 0x00111824, 0x00101723, 0x00101621, 0x0010151f, 0x000d131a, 0x000a1117, 0x00091015, 0x00080d11, 0x00060c10, 0x00060b10, 0x00060a10, 0x0005090e, 0x0006090d, 0x0006080d, 0x0007080c, 0x0006080c, 0x00040508, 0x00030408, 0x00030408, 0x00030409, 0x00030409, 0x00030409, 0x00030408, 0x00030408, 0x00040508, 0x00040609, 0x00040609, 0x00040609, 0x00040609, 0x0005080b, 0x0006080b, 0x0006080b, 0x0007080c, 0x0007080c, 0x0006090c, 0x0004090c, 0x00050a0d, 0x0004090c, 0x0004080b, 0x0004080b, 0x0006090c, 0x00090c10, 0x000c1014, 0x00111419, 0x0014171c, 0x0016191e, 0x00181d22, 0x001d2025, 0x001f2228, 0x0020232b, 0x0021252e, 0x00232830, 0x00252a32, 0x00282c34, 0x00282d35, 0x00282d35, 0x00282e36, 0x00282d35, 0x00292e36, 0x002a2f37, 0x002a3038, 0x002a3038, 0x002a3039, 0x002a303a, 0x002b323c, 0x002c323c, 0x002c333c, 0x002c333c, 0x002c323c, 0x002c333c, 0x002d353f, 0x002e3740, 0x00303841, 0x00313942, 0x00303942, 0x00303942, 0x00303841, 0x00303841, 0x00303841, 0x00303843, 0x00303843, 0x00303843, 0x00303843, 0x00303742, 0x00303641, 0x00303541, 0x00303640, 0x00303640, 0x00303640, 0x002f3640, 0x002f353f, 0x002d343d, 0x002c323c, 0x002c313b, 0x002c303a, 0x002b2f38, 0x00292e36, 0x00282d35, 0x00282d35, 0x00282e36, 0x00282e34, 0x00292e34, 0x00282d35, 0x00272c34, 0x00252a32, 0x00242830, 0x0022252e, 0x0020242c, 0x001f222a, 0x001c2028, 0x001a1d24, 0x00171a1f, 0x0014171c, 0x00101418, 0x000c0f14, 0x00080c10, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0d, 0x0006090d, 0x0006090c, 0x0006090c, 0x0007080c, 0x0006080c, 0x0004070b, 0x0004070b, 0x0004070b, 0x00040609, 0x00040508, 0x00030408, 0x00020307, 0x00020405, 0x00030508, 0x00030408, 0x00020408, 0x00020406, 0x00020405, 0x00020407, 0x00020408, 0x00040508, 0x0007080c, 0x000b0c10, 0x000a0e13, 0x000b1016, 0x000b1118, 0x000b131a, 0x000c141c, 0x0010161f, 0x00111620, 0x00121720, 0x00121720, 0x00121824, 0x00131a25, 0x00141d26, 0x00141f27, 0x0015202a, 0x0018212c, 0x0018222c, 0x0019232e, 0x001b2530, 0x001c2733, 0x001e2834, 0x001f2935, 0x00202a36, 0x00212c38, 0x00212d3a, 0x00202d3b, 0x00202f3c, 0x001f303c, 0x001f2e3a, 0x001e2d38, 0x001c2934, 0x00142029, 0x00060d15, 0x0003040a, 0x00020206, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000201, 0x00000201, 0x00000201, 0x00000102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010303, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020304, 0x00030304, 0x00040404, 0x0003060a, 0x00080f17, 0x001a2630, 0x00202f3a, 0x0020303b, 0x0020303c, 0x0020313d, 0x0020313d, 0x00202f3c, 0x00202d3a, 0x001f2b38, 0x001e2837, 0x001c2834, 0x001a2732, 0x0018242f, 0x0018232d, 0x0018212c, 0x0018202c, 0x0017202b, 0x00141e29, 0x00131c27, 0x00121b26, 0x00121a25, 0x00111924, 0x00111824, 0x00111723, 0x00101722, 0x0010151f, 0x000d141a, 0x000a1117, 0x00091015, 0x00080d11, 0x00060c10, 0x00060b10, 0x00050a0f, 0x00050a0e, 0x0006090d, 0x0006090d, 0x0007080c, 0x0007080c, 0x00040509, 0x00030508, 0x00030408, 0x0003040a, 0x0003040a, 0x00030409, 0x00030408, 0x00030408, 0x00040508, 0x00040609, 0x00040609, 0x00040609, 0x00040609, 0x0005070a, 0x0006080b, 0x0006080b, 0x0008080c, 0x0008090d, 0x0007090d, 0x00050a0d, 0x00050b0e, 0x00040a0d, 0x00050a0c, 0x0006090c, 0x0006090c, 0x00070a0d, 0x000a0d12, 0x00101318, 0x00111419, 0x0014171c, 0x00171b20, 0x001b1f23, 0x001d2028, 0x001e222a, 0x0020242c, 0x0021262f, 0x00242830, 0x00262b33, 0x00262b33, 0x00272c34, 0x00282c34, 0x00282d35, 0x00282d35, 0x00292e36, 0x002a2f37, 0x002a2f37, 0x00292f38, 0x00293039, 0x002a303a, 0x002b313b, 0x002b313b, 0x002c323c, 0x002c333c, 0x002d343d, 0x002d343e, 0x002e3740, 0x002f3840, 0x00303841, 0x00303841, 0x00303840, 0x00303840, 0x00303840, 0x002f3840, 0x002f3742, 0x00303742, 0x002f3742, 0x00303742, 0x00303641, 0x002f3440, 0x002f3440, 0x002f353f, 0x002f353f, 0x002f353f, 0x002f353f, 0x002e343d, 0x002d323b, 0x002c313a, 0x002c3039, 0x002b2f38, 0x002a2e37, 0x00282e36, 0x00282c34, 0x00282c34, 0x00272c34, 0x00272c33, 0x00282b32, 0x00272a31, 0x00252830, 0x0023262e, 0x0021242d, 0x0020222b, 0x001e2029, 0x001c1f28, 0x001a1d25, 0x00181a20, 0x0014161c, 0x00101418, 0x000d1015, 0x00090c11, 0x00080b10, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0e, 0x0006090d, 0x0006090d, 0x0006090d, 0x0007080e, 0x0006080c, 0x0004070c, 0x0004070c, 0x0004070c, 0x00040609, 0x00030508, 0x00030408, 0x00020406, 0x00020405, 0x00030408, 0x00030408, 0x00020308, 0x00020406, 0x00020405, 0x00020307, 0x00020308, 0x00040509, 0x0008080c, 0x000b0c11, 0x000b0e14, 0x000b1016, 0x000b1118, 0x000b131a, 0x000c141c, 0x0010161f, 0x00111620, 0x00121720, 0x00121720, 0x00111823, 0x00141a25, 0x00141d26, 0x00141f27, 0x0015202a, 0x0018212c, 0x0018222c, 0x0019232e, 0x001b2530, 0x001c2733, 0x001e2834, 0x00202935, 0x00202936, 0x00222c38, 0x00222d3a, 0x00222d3b, 0x00202d3b, 0x001f2f3c, 0x001e2e39, 0x001d2c38, 0x001a2833, 0x00131c25, 0x00050910, 0x00020408, 0x00020205, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000202, 0x00000202, 0x00000202, 0x00000102, 0x00010102, 0x00010102, 0x00010102, 0x00010103, 0x00010102, 0x00000102, 0x00000102, 0x00000102, 0x00000102, 0x00010103, 0x00010102, 0x00010102, 0x00010102, 0x00010102, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010304, 0x00010304, 0x00000204, 0x00000204, 0x00010304, 0x00030304, 0x00030405, 0x00030609, 0x00080d15, 0x0018242e, 0x001f2d3a, 0x0020303c, 0x0020303f, 0x0020303f, 0x0021303f, 0x00202e3c, 0x00202c3a, 0x001f2b38, 0x001f2836, 0x001d2834, 0x001c2733, 0x00192430, 0x0018222d, 0x0018212c, 0x0017202c, 0x00171f2a, 0x00151d28, 0x00131c27, 0x00121b26, 0x00121a25, 0x00111924, 0x00111824, 0x00121823, 0x00111721, 0x0010151f, 0x000d131b, 0x000b1118, 0x000a1015, 0x00080d11, 0x00060c10, 0x00060b10, 0x00050a0f, 0x00050a0f, 0x0006090e, 0x0007090f, 0x0008080d, 0x0007080c, 0x0005070a, 0x00040609, 0x00030408, 0x00030409, 0x00030409, 0x00030409, 0x00030408, 0x00030408, 0x00040508, 0x00040608, 0x00040609, 0x00040609, 0x00040609, 0x0005070a, 0x0005070a, 0x0006080b, 0x0007080c, 0x0008080c, 0x0007090c, 0x00050a0d, 0x00050a0d, 0x00050a0d, 0x00060a0d, 0x0006090c, 0x0006090c, 0x0006090c, 0x00080c10, 0x000d1014, 0x00101318, 0x0013151a, 0x0015181e, 0x00181c21, 0x001b1e25, 0x001c2028, 0x001e222b, 0x0020242c, 0x0021272f, 0x00232830, 0x00242931, 0x00252a32, 0x00262b34, 0x00282c34, 0x00282d34, 0x00292e36, 0x00292e36, 0x00292e36, 0x00282e38, 0x00282f38, 0x00293038, 0x002a3038, 0x002b3039, 0x002c323b, 0x002c333c, 0x002d333c, 0x002e343d, 0x002f343f, 0x00303540, 0x00303640, 0x00303640, 0x00303640, 0x00303640, 0x00303640, 0x00303740, 0x00303641, 0x00303640, 0x00303540, 0x00303640, 0x002f353f, 0x002d343d, 0x002c333c, 0x002c333c, 0x002c333c, 0x002e333c, 0x002e333c, 0x002d323b, 0x002c3138, 0x002b3038, 0x002b3037, 0x00292e36, 0x002a2d35, 0x00292c34, 0x00272b33, 0x00252a32, 0x00242931, 0x00252830, 0x0025282f, 0x0024282e, 0x0023262c, 0x0020242b, 0x001f2229, 0x001d2028, 0x001b1e26, 0x001a1d24, 0x00181b22, 0x0017181e, 0x0014141a, 0x00101116, 0x000c0d12, 0x000a0c10, 0x00080b0e, 0x00070a0e, 0x00070a0e, 0x00070a0d, 0x00070a0d, 0x00070a0f, 0x00070a0f, 0x0006090e, 0x0005090d, 0x0005080c, 0x0006080c, 0x0006080c, 0x0005070c, 0x0004070b, 0x0004060a, 0x00040509, 0x00030508, 0x00030408, 0x00020405, 0x00030405, 0x00030408, 0x00030408, 0x00020308, 0x00020406, 0x00020405, 0x00020407, 0x00030409, 0x0004070c, 0x00080a0f, 0x000b0c12, 0x000a0f15, 0x000c1017, 0x000c1218, 0x000c131a, 0x000d141c, 0x0010161e, 0x00111620, 0x00111720, 0x00121821, 0x00121824, 0x00141a25, 0x00141d26, 0x00141f27, 0x0015202a, 0x0018222c, 0x0018232d, 0x0019242e, 0x001a2530, 0x001c2733, 0x001d2834, 0x001f2935, 0x00202a37, 0x00202c38, 0x00212c3a, 0x00212c3b, 0x00202d3b, 0x001f2e3a, 0x001f2e39, 0x001c2c37, 0x00192630, 0x00101820, 0x0003050a, 0x00030305, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010102, 0x00010102, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24}; \ No newline at end of file From ceda2c5155022deb3df53f2e4ec30019d038c920 Mon Sep 17 00:00:00 2001 From: cowsed Date: Mon, 20 Feb 2023 20:15:07 -0500 Subject: [PATCH 177/243] Created auto for purdue --- include/intense_milk.h | 8 ++++---- include/utils/command_structure/auto_command.h | 2 +- include/utils/command_structure/command_controller.h | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/include/intense_milk.h b/include/intense_milk.h index 0fa910b..148467e 100644 --- a/include/intense_milk.h +++ b/include/intense_milk.h @@ -1,5 +1,5 @@ #include -// file: flynn.png -int intense_milk_width = 430; -int intense_milk_height = 244; -uint32_t intense_milk[104920] = {0x000a1118, 0x000b1219, 0x000b1219, 0x000c131c, 0x000c141d, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b141d, 0x000b131c, 0x000b131c, 0x000a121b, 0x000a121b, 0x00081119, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00081018, 0x00081018, 0x0009101a, 0x0009101a, 0x0009101a, 0x000a111b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000c141d, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c161f, 0x000c161f, 0x000e1823, 0x000d1824, 0x000d1925, 0x000d1925, 0x000e1a26, 0x00101926, 0x00131b25, 0x00151d27, 0x00151e27, 0x00131b24, 0x00111a23, 0x00141c25, 0x0018202a, 0x001a242d, 0x001e2830, 0x001c2830, 0x0019252e, 0x0019252e, 0x0019252f, 0x0017212c, 0x00161f2a, 0x00182029, 0x00151d26, 0x00131c24, 0x00121a21, 0x0010171f, 0x000d151c, 0x000d151c, 0x00121a20, 0x00182027, 0x001c242c, 0x00212931, 0x00232c34, 0x00212b34, 0x00202a33, 0x00202a33, 0x00222a34, 0x00222a34, 0x00232b34, 0x00262c36, 0x00282f38, 0x00293039, 0x00282e37, 0x00272d37, 0x00272d37, 0x00272d37, 0x00262c36, 0x00252c35, 0x00252c35, 0x00252c35, 0x00252c35, 0x00252c35, 0x00252c34, 0x00262c34, 0x00262d35, 0x00272d36, 0x00282e37, 0x00282f38, 0x002a303a, 0x002b313b, 0x002b313c, 0x002b313d, 0x002c333e, 0x002e3440, 0x002f3440, 0x002e3440, 0x002d333f, 0x002d333f, 0x002d333f, 0x002d333f, 0x002d333f, 0x002e3440, 0x002f3440, 0x002f3541, 0x00303540, 0x002f3540, 0x002f3540, 0x002f3540, 0x00303641, 0x00303742, 0x00303641, 0x002f3540, 0x002f353f, 0x002e343e, 0x002e343d, 0x0030343f, 0x00313640, 0x00333741, 0x00333741, 0x00333742, 0x00333743, 0x00333743, 0x00333743, 0x00313742, 0x00303642, 0x00303541, 0x00303541, 0x00313640, 0x00313640, 0x00313640, 0x00313642, 0x00303541, 0x002e3440, 0x002f3440, 0x00303541, 0x00303742, 0x00333843, 0x00333843, 0x00333843, 0x00323742, 0x00323742, 0x00323642, 0x00313642, 0x00303744, 0x00303744, 0x00313844, 0x00303744, 0x00303744, 0x00303742, 0x00303641, 0x00313541, 0x00303541, 0x002f3440, 0x002f3440, 0x002e3440, 0x00303441, 0x00313542, 0x00313541, 0x002f343f, 0x002c323c, 0x002c323c, 0x002d333c, 0x002d333c, 0x002d323c, 0x002d323c, 0x002c303b, 0x002b303a, 0x002b303a, 0x002b3039, 0x00292e38, 0x00282d37, 0x00282c36, 0x00282c36, 0x00282c36, 0x00282c36, 0x00282c36, 0x00282c36, 0x00272c35, 0x00262a34, 0x00262a34, 0x00262a34, 0x00262a34, 0x00252934, 0x00242934, 0x00242832, 0x00232831, 0x00232831, 0x00222830, 0x0021282f, 0x0022282f, 0x00232930, 0x00232832, 0x00222730, 0x00212630, 0x00212630, 0x00222730, 0x00232831, 0x00222831, 0x00212831, 0x00222831, 0x00222831, 0x00212831, 0x00202630, 0x001f242e, 0x001e242d, 0x001d232c, 0x001d232c, 0x001c232c, 0x001c222b, 0x00181f26, 0x00141b23, 0x0010171f, 0x000f151d, 0x0010161e, 0x00121820, 0x00141921, 0x00141b23, 0x00181d24, 0x001a2028, 0x001a2028, 0x00191e27, 0x00141924, 0x00121822, 0x00141a24, 0x00161c26, 0x00181f28, 0x00192029, 0x0019212c, 0x001a2430, 0x001c2733, 0x001e2834, 0x00202a36, 0x00202b37, 0x00202b34, 0x00202b34, 0x00202a34, 0x001e2831, 0x001a2430, 0x00182430, 0x00182632, 0x001c2834, 0x001c2a35, 0x001d2a35, 0x001e2a36, 0x001e2a36, 0x001d2935, 0x001a2531, 0x0014202c, 0x00152330, 0x001a2835, 0x001d2b38, 0x00202e3a, 0x0022303d, 0x00253340, 0x00253240, 0x00202d3a, 0x00182532, 0x0013202c, 0x00101d28, 0x000f1c26, 0x000c1823, 0x000a141e, 0x000a111c, 0x000c1019, 0x000b1017, 0x000b1016, 0x000b1016, 0x000b1016, 0x000b1017, 0x000b1017, 0x000b1016, 0x000b1016, 0x000b1016, 0x00081018, 0x00081118, 0x00081118, 0x00081118, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x000a1018, 0x000a1018, 0x000a1018, 0x000a1018, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x00080f18, 0x00080e18, 0x00080e18, 0x00080e18, 0x00080e18, 0x000b1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a121b, 0x000b131b, 0x000b131c, 0x000c141c, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141e, 0x000c141e, 0x000c141e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b141c, 0x000b131c, 0x000b131b, 0x000a1219, 0x000a1219, 0x0009121a, 0x000a121b, 0x0009111a, 0x0008111a, 0x0008111a, 0x0009121b, 0x000a121b, 0x000a121b, 0x0009111a, 0x0009111a, 0x0009111a, 0x000a121b, 0x000a121b, 0x000b131d, 0x000c131d, 0x000b131d, 0x000b131d, 0x000b131d, 0x000b141d, 0x000b151e, 0x000b151e, 0x000a151e, 0x000a161e, 0x000a161f, 0x000b171f, 0x000c1820, 0x000c1821, 0x000e1a24, 0x00101c28, 0x00111c28, 0x00121c28, 0x00121b24, 0x00141c25, 0x00151d26, 0x00141c25, 0x00131c24, 0x00151d26, 0x0018202a, 0x001b252e, 0x001f2831, 0x001b272f, 0x0018242e, 0x0019252f, 0x0017232c, 0x00141f29, 0x0016202a, 0x00172028, 0x00141d25, 0x00131c24, 0x00101922, 0x00101821, 0x00101a20, 0x00111b22, 0x00152026, 0x0018222a, 0x001b252d, 0x001e2730, 0x00202933, 0x00202b34, 0x001f2b34, 0x00202c35, 0x00222c36, 0x00232b35, 0x00232b35, 0x00252c38, 0x00282e3a, 0x00292f39, 0x00282f38, 0x00272d37, 0x00272d37, 0x00272d37, 0x00272d37, 0x00262c36, 0x00262c36, 0x00262d36, 0x00262c36, 0x00262c36, 0x00272d36, 0x00272e36, 0x00272e35, 0x00282e36, 0x00282f38, 0x00293038, 0x002a303a, 0x002c323c, 0x002c333d, 0x002c333e, 0x002e3440, 0x00303541, 0x002f3541, 0x002f3440, 0x002f3540, 0x002f3540, 0x002f3541, 0x002f3440, 0x00303541, 0x00303743, 0x00313843, 0x00313843, 0x00313843, 0x00323844, 0x00323844, 0x00313843, 0x00313843, 0x00313843, 0x00303743, 0x00303742, 0x00303641, 0x00303641, 0x00303740, 0x00323841, 0x00343842, 0x00343842, 0x00343842, 0x00343843, 0x00343844, 0x00343844, 0x00343844, 0x00313843, 0x00313742, 0x00333743, 0x00333844, 0x00313843, 0x00313842, 0x00313841, 0x00313842, 0x00303742, 0x00303742, 0x00303641, 0x00303742, 0x00313843, 0x00343844, 0x00343944, 0x00343944, 0x00343944, 0x00343944, 0x00343944, 0x00343944, 0x00313844, 0x00313844, 0x00313843, 0x00313843, 0x00303742, 0x00303742, 0x002f3641, 0x00303541, 0x00303641, 0x00303641, 0x002f3440, 0x00303540, 0x00313541, 0x00313542, 0x00303540, 0x002d343d, 0x002c333c, 0x002c333c, 0x002c333c, 0x002d333d, 0x002e333e, 0x002e333e, 0x002c303b, 0x002a2f39, 0x00292f38, 0x002a2f39, 0x00292e38, 0x00292e38, 0x00282d37, 0x00282c36, 0x00282c36, 0x00282d37, 0x00282d37, 0x00282c36, 0x00262b35, 0x00252a34, 0x00262a34, 0x00262a34, 0x00252934, 0x00272a34, 0x00272a34, 0x00252a34, 0x00242833, 0x00242832, 0x00232832, 0x00242a33, 0x00242a33, 0x00242b34, 0x00242a34, 0x00242933, 0x00222832, 0x00212731, 0x00212831, 0x00212831, 0x00212831, 0x00222831, 0x00242a33, 0x00242a33, 0x00222832, 0x00202730, 0x001f242e, 0x001e242e, 0x001e242e, 0x001e242e, 0x001d242c, 0x001c222c, 0x00192029, 0x00161d25, 0x00131921, 0x000f151d, 0x000f161d, 0x0010181f, 0x00121820, 0x00131923, 0x00171d25, 0x001c242b, 0x001b232a, 0x00181f28, 0x00151c25, 0x00141b24, 0x00141c25, 0x00161d27, 0x00181f28, 0x0018202a, 0x0019222c, 0x0018242e, 0x001a2630, 0x001c2834, 0x001e2a36, 0x001f2b38, 0x001f2b37, 0x001f2a36, 0x001f2834, 0x001d2833, 0x001a2430, 0x00141f29, 0x00131e28, 0x0018232c, 0x001c2731, 0x001c2731, 0x001c2832, 0x001d2832, 0x001d2935, 0x001c2834, 0x001a2531, 0x00182833, 0x001b2b35, 0x001c2c37, 0x001e2d38, 0x0022313c, 0x00253440, 0x0024343f, 0x001e2d38, 0x00162631, 0x0011202c, 0x000f1e27, 0x000d1a23, 0x000b161f, 0x000a131c, 0x000a101b, 0x000b1018, 0x000a1018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00091019, 0x00091019, 0x000a1019, 0x000b101a, 0x000a101a, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x000a1019, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x00091019, 0x00091019, 0x00080f18, 0x00080f17, 0x00080f17, 0x000b1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b131c, 0x000b131c, 0x000b131c, 0x000c141c, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141e, 0x000c141e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b141d, 0x000b131c, 0x000b131b, 0x000a1219, 0x000a1219, 0x000a121a, 0x000b131c, 0x000a121b, 0x0008111a, 0x0008111a, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000b131c, 0x000c141d, 0x000c141f, 0x000c1420, 0x000c141f, 0x000c141f, 0x000c141f, 0x000b151e, 0x000b151e, 0x000a151e, 0x0009161e, 0x0008161e, 0x0009171f, 0x0009171f, 0x000a1820, 0x000c1921, 0x000f1c25, 0x0014202c, 0x0016222d, 0x0015202b, 0x00131b25, 0x00131b24, 0x00141c24, 0x00131c24, 0x00131c24, 0x00141d26, 0x0018202a, 0x001b252d, 0x001d2730, 0x0018242c, 0x0017232c, 0x0017232d, 0x0017222c, 0x0016202b, 0x0017212a, 0x0017212a, 0x00162028, 0x00141f26, 0x00141e27, 0x00152028, 0x00152128, 0x00162228, 0x00182329, 0x0019232c, 0x001a242d, 0x001c2730, 0x00222b34, 0x00222c34, 0x00212d36, 0x00232f38, 0x00242e38, 0x00242c37, 0x00232b36, 0x00252c38, 0x00282e3a, 0x00292f3a, 0x00282f38, 0x00282e37, 0x00272d37, 0x00272d37, 0x00272d37, 0x00272d37, 0x00282e38, 0x00283038, 0x00282f38, 0x00282f38, 0x00282f38, 0x00282f37, 0x00272e35, 0x00272e36, 0x00282f38, 0x00293039, 0x002b313c, 0x002c333c, 0x002e343e, 0x002f343f, 0x00303742, 0x00313844, 0x00303843, 0x00303742, 0x00303743, 0x00313843, 0x00313843, 0x00303742, 0x00313843, 0x00333944, 0x00343945, 0x00333944, 0x00333944, 0x00343b46, 0x00343a46, 0x00333944, 0x00323844, 0x00313844, 0x00313843, 0x00313843, 0x00303743, 0x00313843, 0x00313842, 0x00333943, 0x00343944, 0x00343944, 0x00343944, 0x00343944, 0x00343a45, 0x00353a46, 0x00343a46, 0x00333945, 0x00333944, 0x00353b46, 0x00343b46, 0x00343a46, 0x00333a45, 0x00323944, 0x00313844, 0x00313844, 0x00313844, 0x00313843, 0x00313843, 0x00323844, 0x00333844, 0x00343945, 0x00343a46, 0x00343b46, 0x00353b46, 0x00343b46, 0x00333944, 0x00323844, 0x00313843, 0x00313843, 0x00303742, 0x00303742, 0x00303742, 0x002e3641, 0x00303641, 0x00303641, 0x00303641, 0x00303642, 0x00313642, 0x00323642, 0x00303540, 0x002f3440, 0x002e343e, 0x002e343d, 0x002e343e, 0x002e343d, 0x002e343e, 0x002f343f, 0x002f343f, 0x002c313c, 0x00292e38, 0x00282e38, 0x00292e38, 0x00292e38, 0x00292e38, 0x00292e38, 0x00282d37, 0x00292e38, 0x00292e38, 0x00282d37, 0x00272c35, 0x00252934, 0x00242833, 0x00252934, 0x00252a34, 0x00242934, 0x00272a34, 0x00272a34, 0x00262934, 0x00242833, 0x00242832, 0x00242832, 0x00242a34, 0x00242b34, 0x00242b34, 0x00252b35, 0x00252b34, 0x00242b34, 0x00242a34, 0x00232933, 0x00232932, 0x00232933, 0x00242a34, 0x00242b34, 0x00242b34, 0x00232933, 0x00202730, 0x001f252f, 0x001f252f, 0x00202630, 0x001f2530, 0x001e242d, 0x001c232c, 0x001a202a, 0x00181e27, 0x00141b23, 0x0010161e, 0x000f151d, 0x00121820, 0x00131a22, 0x00121822, 0x00131a22, 0x00182028, 0x001f272e, 0x001f2830, 0x0019222b, 0x00161e27, 0x00151d26, 0x00161e27, 0x00182029, 0x001a222c, 0x001b242e, 0x0018242d, 0x0018242e, 0x00192732, 0x001c2934, 0x001e2b38, 0x001f2b38, 0x001e2a38, 0x001e2834, 0x001e2834, 0x001c2631, 0x0018222c, 0x00131c25, 0x00111b24, 0x0018222b, 0x001b252f, 0x001a242f, 0x0018222c, 0x00182430, 0x001a2531, 0x001a2732, 0x001c2a36, 0x001d2d38, 0x001d2c38, 0x001e2e39, 0x0021313c, 0x0024343e, 0x0024343e, 0x001c2d37, 0x0015272f, 0x0010222b, 0x000f1e27, 0x000c1920, 0x0009141c, 0x000a121b, 0x000a111a, 0x000a1018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00071017, 0x00071017, 0x00081018, 0x00081018, 0x0009101a, 0x000a101a, 0x000b101b, 0x000c101c, 0x000b101b, 0x00081018, 0x00071017, 0x00071017, 0x00081018, 0x00081018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091019, 0x00091019, 0x00091019, 0x000a101a, 0x000a101a, 0x00091019, 0x00091019, 0x00080f18, 0x00080f17, 0x00080f17, 0x000b1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b131c, 0x000b131c, 0x000b131c, 0x000c141c, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141e, 0x000c141e, 0x000c141e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b141d, 0x000b141c, 0x000a131c, 0x000a121a, 0x000a121a, 0x000a121a, 0x000b141c, 0x000a131b, 0x0009111a, 0x0009111a, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000b131c, 0x000c141d, 0x000c141f, 0x000c1420, 0x000c141f, 0x000c141f, 0x000c141f, 0x000c151f, 0x000c151f, 0x000b151f, 0x0009161f, 0x0009161f, 0x0009161f, 0x000a1720, 0x000c1921, 0x000e1b24, 0x00101d28, 0x0017232f, 0x00182431, 0x0018222e, 0x00151d28, 0x00121b24, 0x00131c24, 0x00131c24, 0x00131c24, 0x00141c25, 0x00171f28, 0x0019222b, 0x001a242c, 0x0017222a, 0x0016222b, 0x0017232c, 0x0017222c, 0x0017212c, 0x0018212a, 0x0018222b, 0x0018222b, 0x0018212a, 0x0018212a, 0x0018212a, 0x0016222a, 0x00142028, 0x00152028, 0x0019242c, 0x001d2730, 0x00202a33, 0x00242c35, 0x00242d36, 0x00212c35, 0x00222c37, 0x00212c36, 0x00232c37, 0x00242d38, 0x00262e39, 0x00282f3b, 0x0029303b, 0x00293039, 0x00282e37, 0x00272d37, 0x00262c36, 0x00262c36, 0x00262c36, 0x00282f38, 0x00283039, 0x00283039, 0x0029303a, 0x00293039, 0x00282f37, 0x00262d35, 0x00262c35, 0x00282f38, 0x002b313b, 0x002d343d, 0x002f353e, 0x002f3540, 0x002f3540, 0x002f3641, 0x00303844, 0x00323a44, 0x00333944, 0x00333945, 0x00343945, 0x00333944, 0x00323944, 0x00333945, 0x00343a46, 0x00343945, 0x00333944, 0x00333944, 0x00343945, 0x00343a45, 0x00343a45, 0x00343a46, 0x00333944, 0x00313843, 0x00303742, 0x00303742, 0x00303742, 0x00323843, 0x00343a44, 0x00333944, 0x00323844, 0x00323844, 0x00333944, 0x00343a45, 0x00353b46, 0x00343a45, 0x00343a45, 0x00343b46, 0x00343c47, 0x00343c47, 0x00343c47, 0x00343c47, 0x00333b46, 0x00333b46, 0x00333b45, 0x00333a45, 0x00333944, 0x00323844, 0x00333944, 0x00343945, 0x00343a45, 0x00343b46, 0x00353c47, 0x00363c48, 0x00373d48, 0x00353b47, 0x00323844, 0x00313843, 0x00313843, 0x00323843, 0x00313742, 0x00303742, 0x002f3641, 0x00303641, 0x00303641, 0x00303641, 0x00303742, 0x00313643, 0x00313542, 0x00303440, 0x002f3440, 0x002e343e, 0x002f353f, 0x002f353e, 0x002d343d, 0x002d333d, 0x002f343f, 0x002f3440, 0x002c313d, 0x00292e38, 0x00292e38, 0x00292e38, 0x00292f38, 0x00292e38, 0x002b2f39, 0x002c303a, 0x002b303a, 0x002b2f3a, 0x00292e38, 0x00282c37, 0x00272b35, 0x00242933, 0x00232832, 0x00242934, 0x00242934, 0x00262934, 0x00252833, 0x00242731, 0x00252832, 0x00252833, 0x00242832, 0x00232831, 0x00212630, 0x00212630, 0x00242832, 0x00242a34, 0x00242b34, 0x00242b34, 0x00242a34, 0x00242a34, 0x00242b34, 0x00242b34, 0x00242b34, 0x00242b34, 0x00232932, 0x00212831, 0x00202630, 0x00202630, 0x00202730, 0x00202730, 0x001f252f, 0x001d242c, 0x001a202a, 0x00181f28, 0x00161c24, 0x00111820, 0x000e141c, 0x0010171f, 0x00141c24, 0x00121822, 0x00111921, 0x00101820, 0x00151e26, 0x001c252e, 0x00202831, 0x001b242c, 0x00141d26, 0x00141d26, 0x00172028, 0x001a232c, 0x001c252f, 0x0019252f, 0x0018252f, 0x00192731, 0x001c2934, 0x001e2b37, 0x001f2b38, 0x001e2a38, 0x001e2835, 0x001e2834, 0x001c2632, 0x0019242d, 0x00152028, 0x00101b24, 0x00111c25, 0x0017212c, 0x0017212c, 0x00101a24, 0x000d1824, 0x00101c28, 0x0015212d, 0x001a2733, 0x001e2c38, 0x001f2d38, 0x00202e39, 0x0022313c, 0x0024343d, 0x0023343d, 0x001c2e37, 0x00162730, 0x0012222c, 0x000f1d26, 0x000b1820, 0x0009141d, 0x000a121c, 0x000a111b, 0x000a1018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00071017, 0x00081018, 0x00081018, 0x00081018, 0x00081119, 0x00081119, 0x000a101a, 0x000b101b, 0x000b101b, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091019, 0x00091019, 0x0009101a, 0x000a101a, 0x000a101a, 0x00091019, 0x00091019, 0x00091018, 0x00080f18, 0x00080f18, 0x000b1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b131c, 0x000b131c, 0x000b131c, 0x000c141c, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141e, 0x000c141e, 0x000c141e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000b131c, 0x000b131c, 0x000b131b, 0x000c141b, 0x000b141b, 0x000a131c, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000b131c, 0x000b131c, 0x000b131c, 0x000b131e, 0x000c141f, 0x000c1420, 0x000c1420, 0x000c1420, 0x000d1520, 0x000d1520, 0x000c1520, 0x000a1520, 0x000a1520, 0x000b1620, 0x000b1720, 0x000c1823, 0x000f1b25, 0x00141f2a, 0x00182432, 0x001c2834, 0x001b2430, 0x0019212b, 0x00151d27, 0x00141c24, 0x00131c24, 0x00121a24, 0x00111923, 0x00121a24, 0x00141c25, 0x00151e27, 0x00152028, 0x0018222b, 0x0018222c, 0x0018222c, 0x0018232c, 0x001a242d, 0x001a242c, 0x0018222b, 0x0017212a, 0x0017212a, 0x0017212a, 0x0017222b, 0x00152129, 0x0017222b, 0x001b252e, 0x00202a33, 0x00222c35, 0x00232c35, 0x00212b34, 0x00212c35, 0x00242d38, 0x00242d38, 0x0025303a, 0x0027313c, 0x0028303c, 0x0029313c, 0x0029313c, 0x002a303a, 0x00282e38, 0x00262c36, 0x00262c36, 0x00262c36, 0x00272d37, 0x00282f38, 0x00293039, 0x00293039, 0x0029303a, 0x00293039, 0x00282f38, 0x00282e37, 0x00282e38, 0x0029303b, 0x002c323c, 0x002d343e, 0x002f3440, 0x002e3440, 0x002e343f, 0x002f3641, 0x00303844, 0x00333b45, 0x00333944, 0x00323844, 0x00303742, 0x00303641, 0x00303642, 0x00303642, 0x00313843, 0x00323844, 0x00323844, 0x00313843, 0x00303743, 0x00303742, 0x00323844, 0x00333944, 0x00323844, 0x00303742, 0x00303641, 0x00303641, 0x00303641, 0x00313843, 0x00323844, 0x00323844, 0x00303843, 0x00303843, 0x00313843, 0x00323844, 0x00323844, 0x00303742, 0x00303641, 0x00303641, 0x00313843, 0x00313843, 0x00313944, 0x00323a45, 0x00323a45, 0x00313a44, 0x00323a44, 0x00333b46, 0x00353b47, 0x00343b46, 0x00363c48, 0x00363c48, 0x00363c48, 0x00373d48, 0x00383e49, 0x00373d48, 0x00373d48, 0x00363c48, 0x00343c47, 0x00343b46, 0x00343944, 0x00333843, 0x00333743, 0x00313743, 0x00303642, 0x00303641, 0x00303541, 0x00313641, 0x00313642, 0x00313542, 0x00313541, 0x00303440, 0x002e343e, 0x002c333c, 0x002c333c, 0x002c333c, 0x002c333c, 0x002c323c, 0x002e333e, 0x002f343f, 0x002f3440, 0x002c313c, 0x002c303b, 0x002c303b, 0x002b3039, 0x002a2e38, 0x002c303b, 0x002c303b, 0x002c303a, 0x002a2f39, 0x00292e38, 0x00292e38, 0x00282d38, 0x00272c36, 0x00242934, 0x00242933, 0x00262a34, 0x00262934, 0x00242630, 0x0022242f, 0x00252832, 0x00262934, 0x00242832, 0x00222730, 0x0020252f, 0x00212530, 0x00232831, 0x00242a34, 0x00242b34, 0x00242b34, 0x00242b34, 0x00242c35, 0x00242c35, 0x00252c35, 0x00252c35, 0x00242b34, 0x00222832, 0x00202730, 0x00202730, 0x00212831, 0x00222831, 0x00222831, 0x00202730, 0x001d242d, 0x001a202b, 0x00192029, 0x00181e28, 0x00141b24, 0x000e141c, 0x000e141c, 0x00141a23, 0x00131923, 0x00111922, 0x000f1922, 0x00101a23, 0x00151f28, 0x001d2730, 0x00202a33, 0x0019232c, 0x00141d26, 0x00141d26, 0x00152028, 0x0016212a, 0x0018252d, 0x001c2931, 0x001b2832, 0x001a2832, 0x001c2936, 0x001d2a38, 0x001c2a38, 0x001d2837, 0x001d2837, 0x001c2734, 0x0018242f, 0x0014202a, 0x00101c26, 0x00101c26, 0x00121d28, 0x0014202a, 0x00131f29, 0x000a1521, 0x0007131f, 0x000e1a25, 0x0014202a, 0x00182430, 0x001b2731, 0x00202c36, 0x0022303a, 0x0023333c, 0x0022343c, 0x001d2f38, 0x00172830, 0x0014242c, 0x000e1c26, 0x00091620, 0x0009141e, 0x0009121c, 0x000a101c, 0x000a1019, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091019, 0x00091019, 0x00091019, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00081119, 0x000a101a, 0x000a101a, 0x00091118, 0x00091118, 0x00091118, 0x00081118, 0x00081118, 0x00081118, 0x00081118, 0x00091018, 0x000a1018, 0x000a1018, 0x0008111a, 0x0008111a, 0x0009111a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x00091019, 0x00091019, 0x00091019, 0x000c1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b131c, 0x000b131c, 0x000b131c, 0x000c141c, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141e, 0x000c141e, 0x000c141e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000b131c, 0x000b131c, 0x000b141b, 0x000c141b, 0x000c141b, 0x000b131c, 0x000b131c, 0x000b131c, 0x000b131c, 0x000b131c, 0x000b131c, 0x000b131c, 0x000b131c, 0x000b131c, 0x000b131c, 0x000c141e, 0x000c141f, 0x000c1420, 0x000d1520, 0x000d1520, 0x000d1520, 0x000d1520, 0x000c1520, 0x000b1520, 0x000a1520, 0x000b1620, 0x000b1720, 0x000c1823, 0x000f1b26, 0x0014202c, 0x001c2734, 0x001e2a38, 0x001d2733, 0x001c242f, 0x0018212b, 0x00151e27, 0x00131c24, 0x00131b24, 0x00121a24, 0x00111923, 0x00111923, 0x00111a24, 0x00141e27, 0x0018232c, 0x0018232c, 0x0018232c, 0x001a242e, 0x001d2831, 0x001c262f, 0x001b232c, 0x0018212a, 0x00172028, 0x00161f28, 0x0018222b, 0x0019242c, 0x001c272f, 0x00202a32, 0x00212c34, 0x00222c35, 0x00222c35, 0x00202b34, 0x00202b34, 0x00212c36, 0x00242d38, 0x00253039, 0x0027313c, 0x0028303c, 0x0028303c, 0x0028303b, 0x002a303a, 0x00293039, 0x00282f38, 0x00282f38, 0x00282f38, 0x00293039, 0x00293039, 0x00293038, 0x00282f38, 0x00282f38, 0x00293039, 0x00293038, 0x00282f38, 0x0029303a, 0x002a303c, 0x002b313c, 0x002d333e, 0x002e3440, 0x002d343f, 0x002c333e, 0x002d3440, 0x002f3641, 0x00313843, 0x00303742, 0x00303742, 0x00303641, 0x00303641, 0x00303641, 0x00303641, 0x00303743, 0x00323844, 0x00323944, 0x00313844, 0x00303743, 0x00303742, 0x00313843, 0x00313843, 0x00303742, 0x00303641, 0x00303641, 0x00303641, 0x00303641, 0x00313843, 0x00323844, 0x00313844, 0x00303843, 0x00303843, 0x00303843, 0x00313843, 0x00313843, 0x00313742, 0x00303742, 0x00303742, 0x00303742, 0x00303742, 0x00303742, 0x00303843, 0x00303844, 0x00303843, 0x00303843, 0x00323944, 0x00353c48, 0x00363d48, 0x00373e49, 0x00383f4a, 0x00383f4a, 0x00383e4a, 0x00373d48, 0x00363c48, 0x00353c47, 0x00343a45, 0x00333944, 0x00343844, 0x00343844, 0x00333743, 0x00323642, 0x00313642, 0x00303641, 0x00303541, 0x00313541, 0x00313542, 0x00323642, 0x00313542, 0x00313541, 0x00303440, 0x002d343e, 0x002c323c, 0x002c323c, 0x002c333c, 0x002e343d, 0x002e343e, 0x002e333e, 0x002f343f, 0x00313541, 0x00303541, 0x00303440, 0x002f343f, 0x002e333d, 0x002c303a, 0x002d313c, 0x002d323c, 0x002c303b, 0x002c303a, 0x002b2f3a, 0x002a2f39, 0x002a2f39, 0x00292e38, 0x00282d37, 0x00282c36, 0x00272c35, 0x00272934, 0x00232630, 0x0021242e, 0x00252833, 0x00282b35, 0x00242833, 0x00232831, 0x00232831, 0x00232832, 0x00242934, 0x00242a34, 0x00252c35, 0x00252c35, 0x00242c35, 0x00242c35, 0x00242c35, 0x00262c36, 0x00262c36, 0x00252c35, 0x00232933, 0x00202730, 0x00202730, 0x00202730, 0x00202730, 0x00212831, 0x00202730, 0x001f252f, 0x001c222c, 0x001b212b, 0x001a202a, 0x00181f28, 0x00161c24, 0x00121820, 0x00131921, 0x00141a24, 0x00121a24, 0x00101a23, 0x00101b24, 0x00121c25, 0x0018232c, 0x00202a33, 0x00232c36, 0x001c2730, 0x0019242d, 0x0018222b, 0x00152029, 0x0014222a, 0x0018262d, 0x001a2830, 0x00192730, 0x00182532, 0x001a2734, 0x001a2834, 0x001c2836, 0x001d2837, 0x001d2836, 0x001c2832, 0x0017232d, 0x00121e28, 0x00111d27, 0x00111c26, 0x00111c26, 0x0014202a, 0x00131d29, 0x00091420, 0x000d1824, 0x00111c25, 0x00141e28, 0x0016202a, 0x001c2630, 0x00212f38, 0x0023333c, 0x0022343c, 0x001d2e37, 0x00182830, 0x0014232c, 0x000c1a24, 0x0008151f, 0x0008141e, 0x0009121c, 0x000a101c, 0x000a1019, 0x00091018, 0x00080f17, 0x00080f17, 0x00091018, 0x00091019, 0x00091019, 0x00091019, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081218, 0x00081118, 0x00081119, 0x0009101a, 0x000a101a, 0x000a1119, 0x000a1219, 0x00091118, 0x00081118, 0x00081118, 0x00081118, 0x00081118, 0x00091018, 0x000a1018, 0x000a1018, 0x0009111a, 0x0008111a, 0x0009111a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x000a101a, 0x00091019, 0x00091019, 0x000c1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a121b, 0x000b131c, 0x000b131c, 0x000b141d, 0x000b141d, 0x000b141d, 0x000b151e, 0x000c151e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000b141e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000a141d, 0x000b141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000c141d, 0x000b141d, 0x000a141e, 0x000a141e, 0x000a141e, 0x000a141e, 0x000b141e, 0x000b141e, 0x000b141e, 0x000c141f, 0x000c141f, 0x000c141f, 0x000c151f, 0x000c151f, 0x000c151f, 0x000c1620, 0x000d1620, 0x000c1620, 0x000c1620, 0x000c1720, 0x000b1720, 0x000c1823, 0x000f1c28, 0x0015232e, 0x001c2936, 0x001e2b38, 0x001c2734, 0x001b2430, 0x001a232f, 0x0018202a, 0x00141c25, 0x00141c24, 0x00141c25, 0x00131c24, 0x00121a24, 0x00111a24, 0x00131e28, 0x0017232d, 0x0018242e, 0x0018242f, 0x001c2833, 0x001e2a34, 0x001c2830, 0x001a242c, 0x00162028, 0x00131c25, 0x00121b24, 0x00141c25, 0x00162028, 0x001a242c, 0x001e2830, 0x00202a33, 0x00202a33, 0x00202a33, 0x00202a33, 0x00212b35, 0x00232c37, 0x00242d37, 0x00242e38, 0x00263038, 0x00272f38, 0x00272f38, 0x0028303a, 0x002a323c, 0x002b323c, 0x002b313c, 0x002a303c, 0x00293039, 0x002a303a, 0x00293039, 0x00282f38, 0x00262c36, 0x00262c36, 0x00282e38, 0x00282f38, 0x00282f39, 0x002a303c, 0x00292f3b, 0x002a303b, 0x002c323c, 0x002e343f, 0x002f3440, 0x002e333e, 0x002d343d, 0x002e343f, 0x002f3540, 0x00303641, 0x00303742, 0x00323743, 0x00323743, 0x00333843, 0x00333844, 0x00333844, 0x00343944, 0x00343945, 0x00333944, 0x00323844, 0x00323844, 0x00323844, 0x00313843, 0x00303641, 0x00303641, 0x00303641, 0x00303541, 0x00303541, 0x00313642, 0x00313642, 0x00313642, 0x00323743, 0x00313843, 0x00323844, 0x00323944, 0x00333944, 0x00343943, 0x00343943, 0x00333943, 0x00333943, 0x00333944, 0x00323944, 0x00323a44, 0x00323944, 0x00323944, 0x00313743, 0x00313742, 0x00343844, 0x00343844, 0x00343945, 0x00353b47, 0x00343c47, 0x00333a45, 0x00333944, 0x00333944, 0x00343a45, 0x00333944, 0x00323844, 0x00343844, 0x00343844, 0x00343844, 0x00333844, 0x00323743, 0x00303642, 0x00303642, 0x00313642, 0x00313541, 0x00313541, 0x00313542, 0x00313542, 0x00303542, 0x002e343f, 0x002c323d, 0x002c323c, 0x002c343c, 0x002f353d, 0x0030363f, 0x00303440, 0x00303540, 0x00323642, 0x00323642, 0x00313541, 0x00303440, 0x00303440, 0x002e333e, 0x002f343f, 0x002f3440, 0x002e333d, 0x002c313c, 0x002c303b, 0x002c303b, 0x002c303b, 0x002b303a, 0x002c303a, 0x002a2f39, 0x00282c37, 0x00272b35, 0x00242833, 0x00242831, 0x00262934, 0x00262a34, 0x00242a34, 0x00242a34, 0x00242934, 0x00242a34, 0x00272b35, 0x00272c36, 0x00262c37, 0x00252c37, 0x00252d38, 0x00232b35, 0x00222a34, 0x00242c35, 0x00242c35, 0x00242c35, 0x00232a33, 0x00222832, 0x00212831, 0x001f2730, 0x001d252f, 0x001e2630, 0x00202730, 0x00202630, 0x001c232c, 0x001b212b, 0x001b212b, 0x00181f27, 0x00141b23, 0x0012181f, 0x00131920, 0x00151c24, 0x00141c24, 0x00131c24, 0x00131c24, 0x00131c24, 0x00141c25, 0x001a242e, 0x00222c38, 0x00212b37, 0x001f2834, 0x001c2531, 0x0018222d, 0x0015222b, 0x0015242b, 0x0018252d, 0x001a2830, 0x00192731, 0x00182632, 0x00182632, 0x001c2734, 0x001d2837, 0x001e2937, 0x001e2a35, 0x001b2631, 0x0015212c, 0x00131f28, 0x00131c27, 0x00111a24, 0x00111a24, 0x00131c26, 0x00101824, 0x00101925, 0x00101b27, 0x00131c28, 0x00141e2a, 0x0018222e, 0x00202b37, 0x0025333e, 0x0024323c, 0x001e2c35, 0x00182630, 0x0013202a, 0x00091720, 0x0008141f, 0x0008131d, 0x0009121c, 0x000a101c, 0x000a1019, 0x000a1018, 0x00091018, 0x00080f17, 0x00091018, 0x00091019, 0x00091019, 0x00091019, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00091019, 0x000a101a, 0x000a101a, 0x000a111a, 0x000a111a, 0x000a1119, 0x000a1118, 0x000a1118, 0x00091118, 0x00091118, 0x00091119, 0x000a111a, 0x000a111a, 0x000a1219, 0x00091119, 0x000a111a, 0x000a101a, 0x000a101a, 0x000b111b, 0x000b111b, 0x000a101a, 0x000a101a, 0x000a101a, 0x000c1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a121b, 0x000b131c, 0x000b131c, 0x000b141d, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c161f, 0x000d161f, 0x000d161f, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141f, 0x000b1420, 0x000b1420, 0x000b1420, 0x000b1420, 0x000a141f, 0x000b1520, 0x000b1520, 0x000b1520, 0x000c1620, 0x000c1620, 0x000c161f, 0x000c1720, 0x000c1720, 0x000d1720, 0x000d1721, 0x000e1822, 0x000e1822, 0x000c1821, 0x000c1821, 0x000c1823, 0x000d1c28, 0x0015242f, 0x001c2937, 0x001e2b38, 0x001c2734, 0x001a2430, 0x001a2430, 0x001b232e, 0x00182029, 0x00151d26, 0x00141c25, 0x00121a24, 0x00121a24, 0x00121c24, 0x00141f29, 0x0016232e, 0x00172430, 0x00182631, 0x001e2c37, 0x00202c36, 0x001b2730, 0x0017232c, 0x00162029, 0x00151f28, 0x00141c26, 0x00141c25, 0x00161f26, 0x001a222a, 0x001d262f, 0x001e2730, 0x001e2730, 0x001e2830, 0x00202b34, 0x00242d38, 0x00252f39, 0x00252f38, 0x00242e37, 0x00262f38, 0x00262e37, 0x00262e38, 0x0028313b, 0x002c343e, 0x002c343e, 0x002d333f, 0x002d343f, 0x002c333c, 0x002c323c, 0x00293039, 0x00272d37, 0x00252c35, 0x00252c35, 0x00262c36, 0x00272d37, 0x00282f39, 0x002a303c, 0x002a303c, 0x002b313c, 0x002c333e, 0x00303440, 0x00313541, 0x00303540, 0x002e343e, 0x002e343e, 0x002e343f, 0x00303742, 0x00313844, 0x00333844, 0x00333844, 0x00343844, 0x00343844, 0x00343944, 0x00343b46, 0x00343b47, 0x00343a45, 0x00333944, 0x00333944, 0x00323844, 0x00313844, 0x00303742, 0x00303742, 0x00303743, 0x00323643, 0x00323643, 0x00333743, 0x00333743, 0x00333743, 0x00333843, 0x00323844, 0x00333944, 0x00343945, 0x00343944, 0x00343943, 0x00343842, 0x00323842, 0x00343a43, 0x00353c45, 0x00343c47, 0x00333b46, 0x00343b46, 0x00343945, 0x00343844, 0x00323643, 0x00323642, 0x00323642, 0x00323642, 0x00333844, 0x00343b47, 0x00343c48, 0x00343c48, 0x00343b47, 0x00353c47, 0x00343b46, 0x00343b46, 0x00353a46, 0x00353a45, 0x00343a45, 0x00343945, 0x00333844, 0x00313844, 0x00313844, 0x00323844, 0x00333743, 0x00323742, 0x00323643, 0x00313543, 0x00303442, 0x002f3440, 0x002c333d, 0x002c333c, 0x002d343d, 0x0030373f, 0x00313840, 0x00303742, 0x00303742, 0x00323642, 0x00323642, 0x00313541, 0x00303440, 0x00303440, 0x00303440, 0x00303440, 0x00313541, 0x00323642, 0x00313640, 0x002f333d, 0x002d323c, 0x002c313b, 0x002c303b, 0x002c303b, 0x002c303b, 0x002b2f3a, 0x00292e38, 0x00282c36, 0x00272c35, 0x00272c35, 0x00262c35, 0x00252c35, 0x00242b34, 0x00242b34, 0x00242b34, 0x00272c36, 0x00292e39, 0x002a2f3b, 0x00282f3a, 0x0028303b, 0x00252d38, 0x00222b34, 0x00222a34, 0x00232b34, 0x00232b34, 0x00242a34, 0x00242a34, 0x00222a34, 0x00202831, 0x001d252f, 0x001c242d, 0x001f2630, 0x00202630, 0x001c232c, 0x001b212b, 0x001b212b, 0x00192028, 0x00141b22, 0x0010181d, 0x00131920, 0x00181f27, 0x001a2028, 0x00181f26, 0x00151e25, 0x00141e25, 0x00131c24, 0x00141e28, 0x001e2834, 0x00202936, 0x00202936, 0x001f2834, 0x001c2833, 0x001a2830, 0x0018252d, 0x0018262e, 0x0019272f, 0x00192730, 0x00182531, 0x00182531, 0x00192533, 0x001c2735, 0x001f2a38, 0x00202c38, 0x00202b37, 0x001c2833, 0x0017222c, 0x00141d28, 0x00131c24, 0x00111920, 0x00111922, 0x00121a24, 0x00111a25, 0x00101b27, 0x00101b27, 0x00131c29, 0x0018222e, 0x00202b38, 0x0026333e, 0x0022303b, 0x001c2833, 0x0018242e, 0x00121f28, 0x0008151f, 0x0008141e, 0x0008131d, 0x0009121c, 0x000a101c, 0x000a1019, 0x000a1018, 0x00091018, 0x00091018, 0x00091018, 0x00091019, 0x00091019, 0x00091019, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00091019, 0x000a101a, 0x000a101a, 0x000b111b, 0x000b111b, 0x000a111a, 0x000a1219, 0x000a1219, 0x000a1219, 0x000a1219, 0x000a121a, 0x000a121b, 0x000a121b, 0x000a1219, 0x000a1219, 0x000a121a, 0x000b111b, 0x000b111b, 0x000b111b, 0x000b111b, 0x000a101a, 0x000a101a, 0x000a101a, 0x000c1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0009121b, 0x000b131c, 0x000b131c, 0x000a141d, 0x000a141d, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c161f, 0x000d161f, 0x000d161f, 0x000c151e, 0x000c151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c151e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c141f, 0x000c1420, 0x000c1420, 0x000c1420, 0x000c1420, 0x000c1420, 0x000b1520, 0x000b1520, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1720, 0x000c1720, 0x000d1720, 0x000d1720, 0x000d1822, 0x000d1822, 0x000d1822, 0x000c1822, 0x000c1822, 0x000c1823, 0x000d1c27, 0x0014242f, 0x001c2937, 0x001d2a38, 0x001a2633, 0x00182430, 0x00182430, 0x001a232e, 0x001a232c, 0x00182029, 0x00151e27, 0x00141c25, 0x00141c25, 0x00141d26, 0x0015202a, 0x0018242f, 0x00182531, 0x001a2733, 0x00202e39, 0x00202c36, 0x0019242d, 0x00152129, 0x0018232b, 0x001a242c, 0x001a232c, 0x0019212b, 0x001a2229, 0x001b232a, 0x001c242d, 0x001e2630, 0x00202832, 0x00202a32, 0x00202b34, 0x00232c37, 0x00242e39, 0x00252f38, 0x00242f37, 0x00252f37, 0x00252e37, 0x00272f38, 0x002a333c, 0x002c3440, 0x002d343f, 0x002e343f, 0x002e3440, 0x002e343f, 0x002e343e, 0x002b313b, 0x00282f38, 0x00262c36, 0x00262c36, 0x00272d37, 0x00282f38, 0x002b313c, 0x002d333f, 0x002d343f, 0x002e3440, 0x00303541, 0x00313642, 0x00323642, 0x00323642, 0x00303640, 0x002f3540, 0x00303640, 0x00313843, 0x00343b46, 0x00353b47, 0x00343844, 0x00343844, 0x00343844, 0x00343945, 0x00343b46, 0x00343a45, 0x00333944, 0x00323844, 0x00323844, 0x00323844, 0x00333944, 0x00333945, 0x00333944, 0x00323844, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00333945, 0x00343b47, 0x00343b47, 0x00353a44, 0x00343944, 0x00333841, 0x00303740, 0x00323842, 0x00353c46, 0x00353c49, 0x00343c48, 0x00343c48, 0x00353b47, 0x00363a47, 0x00343a47, 0x00343945, 0x00333844, 0x00333844, 0x00343a45, 0x00353d48, 0x00373f4a, 0x00373e4a, 0x00363c48, 0x00363c48, 0x00353c47, 0x00353c47, 0x00353a46, 0x00343944, 0x00343844, 0x00343844, 0x00333844, 0x00333945, 0x00343945, 0x00343945, 0x00343844, 0x00333743, 0x00323644, 0x00333744, 0x00333744, 0x00323744, 0x00303742, 0x00303741, 0x00313841, 0x00323940, 0x00323841, 0x00313843, 0x00303742, 0x00323642, 0x00323642, 0x00313541, 0x00313541, 0x00313541, 0x00313541, 0x00323642, 0x00323643, 0x00333843, 0x00333844, 0x00333743, 0x00313541, 0x00303440, 0x002f333e, 0x002d313c, 0x002c303b, 0x002a2f39, 0x00282c36, 0x00282c36, 0x00272c35, 0x00272b35, 0x00262c35, 0x00252c35, 0x00252c35, 0x00242b34, 0x00242933, 0x00242833, 0x00242934, 0x00252a36, 0x00262c38, 0x00282e39, 0x00272e39, 0x00242d36, 0x00222b34, 0x00212933, 0x00212932, 0x00232932, 0x00232933, 0x00222933, 0x00202831, 0x001d252f, 0x001c242c, 0x001d242e, 0x001e242e, 0x001c232c, 0x00192029, 0x00192029, 0x001b212a, 0x00161c24, 0x0012191f, 0x00131920, 0x00171d26, 0x001c232c, 0x001b232a, 0x00182128, 0x00162028, 0x00141f26, 0x00131c26, 0x0018222e, 0x001e2834, 0x00202936, 0x001f2836, 0x001d2834, 0x001d2a33, 0x001e2a33, 0x001c2830, 0x001b2830, 0x00192630, 0x00182530, 0x00182530, 0x00192531, 0x00182432, 0x001c2835, 0x00212d38, 0x00212c38, 0x00202c37, 0x001c2832, 0x0018212c, 0x00171f27, 0x00141c24, 0x00121b24, 0x00121a24, 0x00111a25, 0x00101b27, 0x00111b27, 0x00131c29, 0x0018222e, 0x00202b37, 0x0024323d, 0x001f2c38, 0x001a2732, 0x0017232d, 0x00111d28, 0x000a1720, 0x0009141f, 0x0009141d, 0x0009121c, 0x000a111b, 0x000a1019, 0x00091018, 0x00091018, 0x00091018, 0x00091018, 0x00091019, 0x00081019, 0x00091019, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00091119, 0x000a101a, 0x000a101b, 0x000b111c, 0x000b111c, 0x000a121b, 0x000a1219, 0x000b1219, 0x000b1219, 0x000b1219, 0x000b121a, 0x000b121b, 0x000b121b, 0x000a121a, 0x000a1218, 0x000a1219, 0x000b111a, 0x000b111a, 0x000b111a, 0x000b111a, 0x000b111a, 0x000a101a, 0x000a101a, 0x000c1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0008121b, 0x000b131c, 0x000b131c, 0x000a141c, 0x000a141d, 0x000a141d, 0x000b151e, 0x000c161f, 0x000c161f, 0x000d161f, 0x000d161f, 0x000e1720, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c1620, 0x000c1721, 0x000c1721, 0x000c1822, 0x000d1823, 0x000c1821, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000d1a24, 0x000e1d26, 0x0015252e, 0x001c2a35, 0x001c2934, 0x00172430, 0x0017242f, 0x0017232f, 0x0018242f, 0x0019232d, 0x0018212c, 0x0018202a, 0x00171f28, 0x00171f28, 0x00162028, 0x0016202b, 0x00182630, 0x001a2833, 0x001c2934, 0x0022303c, 0x001f2c36, 0x0018242d, 0x00172329, 0x0018242a, 0x001a242c, 0x001b242d, 0x001c252e, 0x001c252d, 0x001d252d, 0x001e2730, 0x00202830, 0x00212a33, 0x00202b33, 0x00212b34, 0x00242e38, 0x0025303a, 0x00253039, 0x00253038, 0x00242f38, 0x00253038, 0x00273039, 0x002c333d, 0x002e3440, 0x002f3440, 0x002d343f, 0x002c323e, 0x002d343d, 0x002e343e, 0x002c333c, 0x002a3039, 0x00282e38, 0x00272d37, 0x00282f38, 0x002a313b, 0x002d343f, 0x00303641, 0x00303742, 0x00303742, 0x00303743, 0x00313642, 0x00323642, 0x00333743, 0x00313842, 0x00323842, 0x00333943, 0x00343b44, 0x00363c47, 0x00373c48, 0x00353945, 0x00343944, 0x00343944, 0x00343945, 0x00343b46, 0x00323844, 0x00313843, 0x00323843, 0x00323844, 0x00323844, 0x00343a45, 0x00343b47, 0x00343b46, 0x00343a45, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00343944, 0x00343a45, 0x00363c49, 0x00383f4c, 0x00393f4c, 0x003a3e4b, 0x00383c48, 0x00343944, 0x00303640, 0x00323842, 0x00363c48, 0x00363d4a, 0x00353d4a, 0x00363d4a, 0x00383d4a, 0x00383d4b, 0x00373c4a, 0x00353c49, 0x00343b47, 0x00343b46, 0x00343c47, 0x00353d49, 0x00373e4b, 0x00373e4b, 0x00373d4a, 0x00363c48, 0x00363c48, 0x00353c48, 0x00343a46, 0x00323844, 0x00323843, 0x00323844, 0x00333844, 0x00343b47, 0x00353c47, 0x00353b47, 0x00353a46, 0x00343944, 0x00343845, 0x00343947, 0x00353a48, 0x00353a48, 0x00343a45, 0x00343a45, 0x00343944, 0x00343a43, 0x00333943, 0x00323844, 0x00303742, 0x00323642, 0x00333743, 0x00333843, 0x00333843, 0x00333743, 0x00323642, 0x00313541, 0x00323642, 0x00333643, 0x00333743, 0x00343844, 0x00343944, 0x00343844, 0x00323642, 0x002f343f, 0x002c303c, 0x00292e39, 0x00282c36, 0x00272b35, 0x00262a34, 0x00262a34, 0x00262c35, 0x00262c36, 0x00252c35, 0x00242a34, 0x00222831, 0x00222731, 0x00222732, 0x00232833, 0x00242934, 0x00252c37, 0x00282f3a, 0x0028303a, 0x00252d36, 0x00222a34, 0x00202831, 0x00222832, 0x00232932, 0x00222933, 0x00212932, 0x00202830, 0x001d252f, 0x001d242d, 0x001c232c, 0x001a202a, 0x00171d27, 0x00151c25, 0x00181f28, 0x00181f28, 0x00141c22, 0x00111820, 0x00141c24, 0x001b232c, 0x001d272e, 0x001b252c, 0x0018242b, 0x00142027, 0x00111d26, 0x00131e2a, 0x001b2632, 0x00202a37, 0x00202a37, 0x001d2834, 0x001a2730, 0x001c2831, 0x001c2831, 0x001c2830, 0x001c2830, 0x001c2830, 0x001c2831, 0x001a2631, 0x0017232f, 0x0017232e, 0x001b2632, 0x001f2a36, 0x00202c38, 0x00202b37, 0x001c2631, 0x001a222c, 0x00172028, 0x00141d26, 0x00131b24, 0x00111a25, 0x00101b27, 0x00101b27, 0x00121c28, 0x0016202c, 0x001c2834, 0x001f2d38, 0x001a2934, 0x00182530, 0x0014222d, 0x000f1c27, 0x000c1821, 0x000c161f, 0x000b151e, 0x000c141c, 0x000b131b, 0x000a131a, 0x00081319, 0x00081319, 0x00081219, 0x00081119, 0x00081119, 0x00081019, 0x00081019, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081019, 0x0008111a, 0x0008111a, 0x0009121b, 0x000a121b, 0x000b131c, 0x000b131d, 0x000b131e, 0x000b131c, 0x000b131c, 0x000c131c, 0x000c131a, 0x000c131a, 0x000c131b, 0x000c131c, 0x000c131c, 0x000b131a, 0x000b1418, 0x000c1419, 0x000c131a, 0x000c131a, 0x000c131a, 0x000c131a, 0x000c121a, 0x000b111b, 0x000b111b, 0x000c1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0009131c, 0x000b131c, 0x000b131c, 0x000a141d, 0x000a141d, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000d161f, 0x000d161f, 0x000e1720, 0x000e1720, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d1720, 0x000c1821, 0x000c1822, 0x000c1823, 0x000d1924, 0x000c1922, 0x000b1920, 0x000b1920, 0x000c1920, 0x000d1921, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1d27, 0x0016252e, 0x001c2a35, 0x001a2833, 0x0016242f, 0x0015232e, 0x0016232f, 0x00182430, 0x001a242f, 0x001a232e, 0x0019222c, 0x0019222c, 0x001a232c, 0x0018222c, 0x0018232c, 0x001b2833, 0x001c2935, 0x001c2a35, 0x00202d38, 0x001d2a34, 0x001b272f, 0x001a262c, 0x0018242b, 0x0019232c, 0x001a242c, 0x0019232c, 0x0019242c, 0x001c262e, 0x001e2830, 0x00202830, 0x00202831, 0x00202a32, 0x00232c36, 0x0025303a, 0x0025303a, 0x00253039, 0x00253038, 0x00253038, 0x00242f38, 0x00273038, 0x002c323c, 0x002e3440, 0x002e3440, 0x002c323e, 0x002b313c, 0x002b313c, 0x002c323c, 0x002d343d, 0x002d343d, 0x002c313c, 0x002a303a, 0x002b313c, 0x002d333d, 0x002f3440, 0x00303642, 0x00303742, 0x00303742, 0x00313742, 0x00313642, 0x00323742, 0x00343844, 0x00333944, 0x00343b44, 0x00353c46, 0x00363c46, 0x00373d48, 0x00383c48, 0x00363a46, 0x00343944, 0x00343944, 0x00343944, 0x00333944, 0x00323743, 0x00323743, 0x00333743, 0x00333844, 0x00343944, 0x00353c47, 0x00353c47, 0x00353c47, 0x00343c47, 0x00343a45, 0x00353945, 0x00353945, 0x00353a45, 0x00363a46, 0x00373c48, 0x00383e4c, 0x0039404d, 0x003c414f, 0x003c414e, 0x00383e49, 0x00333944, 0x00303741, 0x00343a44, 0x00373e49, 0x00373f4c, 0x00383f4c, 0x0038404c, 0x003a404d, 0x003a3f4c, 0x00383e4c, 0x00353d4a, 0x00343c48, 0x00343c48, 0x00343c48, 0x00363d4a, 0x00373e4b, 0x00373f4c, 0x00373d4a, 0x00363c49, 0x00353c48, 0x00353c47, 0x00343a45, 0x00323844, 0x00323844, 0x00343b46, 0x00363c48, 0x00363d48, 0x00373d48, 0x00363c48, 0x00373c48, 0x00363b47, 0x00363b48, 0x00363b48, 0x00373b48, 0x00373c48, 0x00343b47, 0x00343a46, 0x00343a44, 0x00343b44, 0x00343a44, 0x00333944, 0x00323844, 0x00333743, 0x00343844, 0x00343944, 0x00343944, 0x00343844, 0x00333843, 0x00323642, 0x00323642, 0x00323642, 0x00323642, 0x00333743, 0x00343944, 0x00343944, 0x00333844, 0x00313541, 0x002f333f, 0x002c303c, 0x002a2f39, 0x00282c36, 0x00262a34, 0x00262b34, 0x00262c36, 0x00252c35, 0x00242c35, 0x00242a34, 0x00222832, 0x00222831, 0x00232832, 0x00232834, 0x00242935, 0x00242b36, 0x00282e39, 0x0029313b, 0x0028303a, 0x00252e37, 0x00222c34, 0x00222a34, 0x00232a34, 0x00232b34, 0x00222a34, 0x00212933, 0x00202831, 0x00202730, 0x001d242d, 0x0019202a, 0x00161d27, 0x00151c25, 0x00141c25, 0x00141c24, 0x00131b21, 0x00101820, 0x00121923, 0x0018202a, 0x001b262e, 0x001d2931, 0x001d2931, 0x0018242c, 0x00121e29, 0x00111c28, 0x0017222e, 0x00202a36, 0x00242d38, 0x00212c37, 0x001c2833, 0x001b2731, 0x001c2831, 0x001d2931, 0x001d2932, 0x001f2b34, 0x00202b34, 0x001d2934, 0x00182430, 0x0014202c, 0x0014202c, 0x00192430, 0x001d2935, 0x001f2a36, 0x001d2632, 0x001b232d, 0x0018202a, 0x00171f28, 0x00151d27, 0x00131c26, 0x00101b27, 0x00101b27, 0x00101b27, 0x00141e2a, 0x0018242f, 0x00192833, 0x00162631, 0x0015242f, 0x00111f2a, 0x000c1a24, 0x000c1820, 0x000d1720, 0x000d1720, 0x000e161e, 0x000e161d, 0x000c161c, 0x000b151c, 0x0009141a, 0x00081319, 0x00091219, 0x0008111a, 0x00081019, 0x00081019, 0x00091019, 0x00091019, 0x00081018, 0x00081018, 0x00081018, 0x00081018, 0x00081119, 0x0009111a, 0x0009111a, 0x000a121b, 0x000b131c, 0x000b131c, 0x000c121d, 0x000c121e, 0x000c121c, 0x000c131c, 0x000c131c, 0x000c141b, 0x000d141b, 0x000d141c, 0x000d141d, 0x000d141c, 0x000c141b, 0x000c1419, 0x000c141a, 0x000c141a, 0x000c131a, 0x000c131a, 0x000c131a, 0x000c121a, 0x000b111b, 0x000b111b, 0x000c1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a141c, 0x000c141c, 0x000c141d, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000d1720, 0x000d1820, 0x000d1720, 0x000d1721, 0x000d1721, 0x000e1822, 0x000e1822, 0x000d1821, 0x000d1721, 0x000d1721, 0x000d1721, 0x000d1721, 0x000d1721, 0x000d1720, 0x000d1720, 0x000e1720, 0x000e1720, 0x000d1720, 0x000c1822, 0x000c1821, 0x000c1821, 0x000c1821, 0x000d1821, 0x000e1823, 0x000e1824, 0x000d1824, 0x000d1924, 0x000d1924, 0x000c1923, 0x000c1923, 0x000e1823, 0x000e1823, 0x000f1824, 0x000f1924, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000f1b25, 0x00101f28, 0x0017242f, 0x001b2834, 0x00182631, 0x0015232e, 0x0015232e, 0x0016232e, 0x0019242f, 0x001c2630, 0x001b2530, 0x001a2530, 0x001a2530, 0x001a2630, 0x0018242f, 0x0018242f, 0x001b2832, 0x001e2c36, 0x001e2c35, 0x001e2c36, 0x001b2832, 0x0019252f, 0x0019262c, 0x0018242b, 0x0018232b, 0x0018222b, 0x0018212a, 0x0018212a, 0x001c242d, 0x001d2630, 0x001d2830, 0x001f2831, 0x00202a34, 0x00222c36, 0x00242e38, 0x00242f38, 0x00242e38, 0x00242f38, 0x00242e37, 0x00242d36, 0x00252e37, 0x002a323b, 0x002b343d, 0x002c333c, 0x0029313c, 0x0028303a, 0x0028303a, 0x002b333c, 0x002e3540, 0x00303741, 0x00303641, 0x002e3440, 0x002e343f, 0x002e3440, 0x002e333e, 0x002e333f, 0x00303440, 0x00303540, 0x00303540, 0x00303642, 0x00323844, 0x00333a45, 0x00343b46, 0x00343c48, 0x00353d48, 0x00363d48, 0x00373e49, 0x00383e49, 0x00353b47, 0x00343944, 0x00333944, 0x00333844, 0x00333844, 0x00333743, 0x00323643, 0x00323642, 0x00333843, 0x00343945, 0x00353c47, 0x00353c48, 0x00363c48, 0x00363c48, 0x00363c48, 0x00363c48, 0x00363c48, 0x00373c48, 0x00373d4a, 0x00383e4a, 0x00383f4c, 0x00383f4c, 0x00383e4b, 0x00383e4a, 0x00363c48, 0x00343b47, 0x00343b46, 0x00373d48, 0x00383f4c, 0x0038404d, 0x0038404c, 0x0038404d, 0x003b404e, 0x003a3f4c, 0x00383e4b, 0x00363d49, 0x00363c48, 0x00363d48, 0x00373d48, 0x00383e4b, 0x00383f4c, 0x0038404c, 0x00383f4c, 0x00373c4a, 0x00353b48, 0x00353c48, 0x00353c47, 0x00353b47, 0x00343b46, 0x00343c47, 0x00363c48, 0x00373d48, 0x00383f4b, 0x00383f4c, 0x00383e4c, 0x00383d4a, 0x00373d4a, 0x00373c49, 0x00363c48, 0x00343c48, 0x00343a46, 0x00343945, 0x00343a44, 0x00343a44, 0x00343a44, 0x00333a45, 0x00343a46, 0x00343a45, 0x00333844, 0x00333944, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00333743, 0x00323642, 0x00313642, 0x00323643, 0x00333843, 0x00333944, 0x00333844, 0x00323743, 0x00313642, 0x00303440, 0x002d323d, 0x002b303b, 0x00282e39, 0x00272d38, 0x00262c37, 0x00252c36, 0x00242b35, 0x00242b34, 0x00232932, 0x00232932, 0x00232832, 0x00242934, 0x00242b35, 0x00272e38, 0x00282f39, 0x00272f39, 0x0028303b, 0x0028303b, 0x00273038, 0x00262e38, 0x00242d36, 0x00242c35, 0x00232c34, 0x00232b34, 0x00222a33, 0x00202831, 0x001e2730, 0x001b242d, 0x00162028, 0x00161e27, 0x00151d26, 0x00141c24, 0x00111a20, 0x00101820, 0x00111822, 0x00161f29, 0x001a252f, 0x001c2832, 0x00202c36, 0x001c2831, 0x0015202b, 0x00101b25, 0x00142028, 0x001e2831, 0x00242d36, 0x00232d38, 0x00202c38, 0x001e2a37, 0x001d2834, 0x001c2733, 0x001c2832, 0x001d2933, 0x00202c36, 0x00202b37, 0x001c2733, 0x0016212c, 0x00131f29, 0x00131f29, 0x0018242e, 0x001c2833, 0x001c2732, 0x001a2430, 0x0017202c, 0x0017202c, 0x00171f2c, 0x00151e2a, 0x00141c27, 0x00121b26, 0x00101b25, 0x00131c27, 0x0014202b, 0x0015242e, 0x0014242e, 0x0013222d, 0x000e1d28, 0x000a1924, 0x000b1821, 0x000c1820, 0x000d1720, 0x000f1820, 0x000f1720, 0x000e171f, 0x000c151d, 0x0009131a, 0x00081319, 0x00081219, 0x0008111a, 0x0008111a, 0x00091119, 0x00091119, 0x00091119, 0x00091219, 0x00091219, 0x00091219, 0x00091219, 0x000a1219, 0x000a121b, 0x000a121b, 0x000b131b, 0x000c141c, 0x000c141c, 0x000c141d, 0x000c131d, 0x000c141c, 0x000c141b, 0x000c141b, 0x000c151c, 0x000c141c, 0x000c141c, 0x000c141c, 0x000c141c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c141c, 0x000c141c, 0x000c141c, 0x000c141c, 0x000c141c, 0x000b131c, 0x000b131c, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a141d, 0x000c141d, 0x000c141d, 0x000c151e, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b161f, 0x000b171f, 0x000b171f, 0x000c1820, 0x000c1820, 0x000c1821, 0x000c1822, 0x000c1822, 0x000d1923, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1822, 0x000e1822, 0x000e1822, 0x00101820, 0x000f1820, 0x000d1822, 0x000c1924, 0x000c1823, 0x000b1822, 0x000b1822, 0x000d1822, 0x000f1824, 0x000f1824, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000f1824, 0x000f1824, 0x000f1924, 0x00101a24, 0x00101a24, 0x000e1a24, 0x000f1a24, 0x00101c26, 0x00122029, 0x0018242f, 0x001a2833, 0x00182530, 0x0015232e, 0x0015232e, 0x0016232e, 0x0019242f, 0x001c2630, 0x001b2630, 0x00192630, 0x001a2730, 0x00192730, 0x0018252f, 0x00182530, 0x00192730, 0x001d2b34, 0x001f2c36, 0x001d2b34, 0x001b2831, 0x0019252f, 0x0018242b, 0x0018242a, 0x0017212a, 0x00162029, 0x00182029, 0x001a222b, 0x001d252f, 0x001e2730, 0x001e2830, 0x001f2932, 0x00202b34, 0x00222c36, 0x00242d38, 0x00242e38, 0x00252f39, 0x00242e37, 0x00242d36, 0x00222c35, 0x00252e37, 0x0028323b, 0x0029333c, 0x0029323c, 0x0028303a, 0x00283039, 0x002a323b, 0x002c343d, 0x002f3640, 0x00313843, 0x00313843, 0x00303641, 0x002e343f, 0x002c333c, 0x002c303b, 0x002c303b, 0x002e333c, 0x002f343e, 0x002f353f, 0x00303642, 0x00323844, 0x00333a45, 0x00333c47, 0x00343c48, 0x00343c48, 0x00343d48, 0x00353d48, 0x00363c48, 0x00343a45, 0x00333944, 0x00343944, 0x00333843, 0x00323741, 0x00333743, 0x00323643, 0x00323642, 0x00333743, 0x00343945, 0x00353c47, 0x00353c47, 0x00363c48, 0x00363d49, 0x00373d48, 0x00373f49, 0x0037404a, 0x0038404b, 0x0038404c, 0x0038404c, 0x0038404b, 0x00363e49, 0x00343c47, 0x00333b46, 0x00343c47, 0x00363e48, 0x00383f4a, 0x0038404c, 0x0039414d, 0x0039414e, 0x0038404d, 0x00383f4c, 0x00383e4b, 0x00383e4b, 0x00373d48, 0x00373d48, 0x00373d48, 0x00383e49, 0x00383e49, 0x00383e4b, 0x00383f4c, 0x0038404c, 0x00383f4c, 0x00383e4c, 0x00353c49, 0x00363c48, 0x00373d48, 0x00373d48, 0x00353c47, 0x00343c47, 0x00343c47, 0x00353c48, 0x00373e4a, 0x00383e4c, 0x0038404c, 0x00373f4c, 0x00373e4b, 0x00373d4a, 0x00353c48, 0x00343a45, 0x00343944, 0x00343844, 0x00343944, 0x00343943, 0x00343a44, 0x00343c47, 0x00343b47, 0x00323844, 0x00303642, 0x00303641, 0x00323642, 0x00323642, 0x00333843, 0x00343945, 0x00353a46, 0x00323844, 0x00313843, 0x00303641, 0x00303641, 0x00313843, 0x00323844, 0x00323844, 0x00323844, 0x00313843, 0x00303641, 0x002e3440, 0x002c323d, 0x002a303c, 0x00282e3a, 0x00262c38, 0x00252c35, 0x00252c35, 0x00242b34, 0x00242a33, 0x00242a33, 0x00242c34, 0x00252d36, 0x00272f38, 0x00283039, 0x00262e39, 0x00272f39, 0x0028303b, 0x0028313a, 0x0028313a, 0x00283039, 0x00273038, 0x00252e37, 0x00242c35, 0x00222a34, 0x00202832, 0x001d2730, 0x001b252f, 0x0018232c, 0x0016202a, 0x00151f28, 0x00141d24, 0x00111c20, 0x0010191f, 0x00101921, 0x00141e28, 0x001c2731, 0x001c2832, 0x00202c36, 0x001f2c35, 0x001a252f, 0x00111b23, 0x00151f26, 0x001c252c, 0x00202b32, 0x00232d38, 0x00222d3b, 0x00212c3b, 0x001f2b37, 0x001c2834, 0x00192531, 0x0018242f, 0x001a2630, 0x001e2a36, 0x001f2b37, 0x001b2731, 0x0015212a, 0x00121e26, 0x00131f27, 0x0018242c, 0x001c2731, 0x001b2532, 0x00192430, 0x0019222f, 0x0019202d, 0x0018202c, 0x00171f28, 0x00141c25, 0x00131c25, 0x00141e27, 0x00142029, 0x0014232c, 0x0014242d, 0x0011222c, 0x000c1c28, 0x00091924, 0x000b1822, 0x000b1822, 0x000d1820, 0x00101820, 0x00101820, 0x000e1720, 0x000c141d, 0x0009131a, 0x00081319, 0x00081319, 0x000a121b, 0x000a121b, 0x000a121a, 0x000a1219, 0x000a1219, 0x000b131a, 0x000b131a, 0x000b131a, 0x000b131a, 0x000b131a, 0x000b131a, 0x000b131a, 0x000c141b, 0x000c141b, 0x000c141b, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000c151c, 0x000b151d, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a141d, 0x000c141d, 0x000c141d, 0x000c151f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000c1820, 0x000c1820, 0x000c1822, 0x000c1823, 0x000c1823, 0x000c1823, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1823, 0x000e1822, 0x000e1822, 0x00101821, 0x000f1821, 0x000d1822, 0x000c1924, 0x000c1924, 0x000c1923, 0x000c1924, 0x000e1824, 0x000f1824, 0x000f1924, 0x000e1924, 0x000e1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x000f1a24, 0x000f1b25, 0x00101c26, 0x00121e28, 0x0018242e, 0x001b2833, 0x00182530, 0x0015232e, 0x0015222e, 0x0016232e, 0x0019242f, 0x001b2430, 0x001a2530, 0x00192630, 0x00192731, 0x00192731, 0x00182530, 0x00182530, 0x00182630, 0x001b2833, 0x001f2c37, 0x001e2c35, 0x001b2832, 0x001a2630, 0x0018252c, 0x0018242b, 0x0017212a, 0x0017212a, 0x001a232c, 0x001c242d, 0x001c242e, 0x001c262f, 0x001d2730, 0x00202932, 0x00222c37, 0x00242d38, 0x00242e38, 0x00252f39, 0x0026303b, 0x00253038, 0x00242e37, 0x00242e37, 0x00273038, 0x00273039, 0x00273139, 0x0028313a, 0x0028303a, 0x002a323c, 0x002d343d, 0x002c343c, 0x002c343e, 0x00303641, 0x00303742, 0x00303641, 0x002f353f, 0x002d343d, 0x002c313b, 0x002c313b, 0x002e333c, 0x002f343f, 0x002f3540, 0x00303642, 0x00313843, 0x00323944, 0x00323a45, 0x00343c47, 0x00343c47, 0x00343c47, 0x00333b46, 0x00333944, 0x00343a45, 0x00343a45, 0x00343944, 0x00333843, 0x00323742, 0x00333743, 0x00333743, 0x00333743, 0x00343844, 0x00353a46, 0x00373c48, 0x00373d48, 0x00383e4b, 0x00383f4c, 0x0038404b, 0x0038404c, 0x0038404c, 0x0038404c, 0x0038404c, 0x00383f4c, 0x00373f4a, 0x00363e49, 0x00343c48, 0x00343c48, 0x00363f49, 0x0038414c, 0x003a424d, 0x003a424e, 0x0039414e, 0x003a424f, 0x0039414e, 0x00383f4c, 0x00363c48, 0x00363d48, 0x00383e49, 0x00383e49, 0x00383e49, 0x00383e49, 0x00383e49, 0x00383e4a, 0x00383f4c, 0x0038404c, 0x00383f4d, 0x00383f4e, 0x00383d4c, 0x00383e4b, 0x00373e49, 0x00373e49, 0x00363d48, 0x00353d48, 0x00343c47, 0x00333b48, 0x00333c48, 0x00343c49, 0x00353e4b, 0x00353f4b, 0x00373f4c, 0x00373e4b, 0x00343c48, 0x00343a46, 0x00343944, 0x00343944, 0x00343944, 0x00343943, 0x00343b45, 0x00343c48, 0x00353d48, 0x00343b47, 0x00333944, 0x00313843, 0x00313642, 0x00313541, 0x00313541, 0x00343945, 0x00373c48, 0x00343a45, 0x00303742, 0x002f3541, 0x002f3440, 0x00313843, 0x00333944, 0x00333944, 0x00333944, 0x00333944, 0x00313843, 0x00303742, 0x002e3440, 0x002e3440, 0x002d343f, 0x002b303c, 0x00282e38, 0x00282e38, 0x00272d38, 0x00272c37, 0x00262d37, 0x00262d37, 0x00272f38, 0x00272f38, 0x00272f3a, 0x00272f3a, 0x00272f39, 0x00272f39, 0x00252e37, 0x00252d37, 0x00252d37, 0x00252d36, 0x00252e37, 0x00242d36, 0x00242c37, 0x00222c36, 0x001f2934, 0x001c2731, 0x001b2530, 0x0018232d, 0x0017202a, 0x00162026, 0x00141e24, 0x00131c21, 0x00131c24, 0x0017212b, 0x001d2a34, 0x001f2c36, 0x00202d37, 0x00202e38, 0x001e2933, 0x00151d26, 0x00151e25, 0x0019242b, 0x001f2930, 0x00222c38, 0x00242f3c, 0x0024303d, 0x00212d39, 0x001e2a36, 0x001b2732, 0x0018242f, 0x0017222c, 0x00182430, 0x001d2935, 0x001e2a35, 0x001a262f, 0x0015212a, 0x00131f27, 0x00131f28, 0x0018222d, 0x001a2430, 0x001c2632, 0x001c2431, 0x001b2430, 0x001a232f, 0x0018212a, 0x00161f28, 0x00141f27, 0x00141f28, 0x00142029, 0x0014232c, 0x0014232c, 0x0011212c, 0x000c1c27, 0x000b1924, 0x000c1924, 0x000c1924, 0x000e1922, 0x000f1921, 0x000f1921, 0x000e1820, 0x000c151e, 0x000a141c, 0x0009141b, 0x0009131b, 0x000a121b, 0x000a121b, 0x000a121a, 0x000a1219, 0x000a121a, 0x000a131a, 0x000a131a, 0x000b131a, 0x000b131a, 0x000b131b, 0x000b131b, 0x000b131b, 0x000c141c, 0x000c151c, 0x000c151c, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000c151d, 0x000b151e, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b141e, 0x000c141e, 0x000c141e, 0x000c1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000c1720, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000d1922, 0x000d1924, 0x000d1924, 0x000c1822, 0x000c1822, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000f1824, 0x000f1824, 0x000d1824, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000d1b24, 0x000f1a24, 0x00101924, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101b25, 0x00101b25, 0x00101b25, 0x00131d28, 0x0018232d, 0x001c2733, 0x00182430, 0x0016212d, 0x0016212d, 0x0016212d, 0x0018222e, 0x0018222e, 0x0018232f, 0x00182430, 0x00182631, 0x00192732, 0x00182430, 0x00182530, 0x00182531, 0x001b2834, 0x001e2c38, 0x001e2c37, 0x001c2834, 0x001c2830, 0x001b272d, 0x0019252c, 0x0018222b, 0x0018222b, 0x0019232c, 0x001a242f, 0x001b2430, 0x001c2731, 0x001d2732, 0x001f2833, 0x00232d38, 0x00242d38, 0x00242e38, 0x00252f39, 0x0026303b, 0x0026303a, 0x0027313a, 0x0026313a, 0x00273039, 0x00262f38, 0x00242e36, 0x00252f38, 0x0028313b, 0x002c343e, 0x002f353f, 0x002c333c, 0x002a313c, 0x002e3440, 0x00303641, 0x00303540, 0x002e343e, 0x002c333c, 0x002e333d, 0x002f343e, 0x0030343f, 0x00303540, 0x00303741, 0x00303742, 0x00313843, 0x00303844, 0x00303844, 0x00323a44, 0x00323a44, 0x00323a44, 0x00323a44, 0x00343a45, 0x00343b46, 0x00343a46, 0x00343944, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00343945, 0x00353a46, 0x00383c48, 0x00383e4a, 0x0039404b, 0x003a404c, 0x003b414e, 0x003a404d, 0x0039414d, 0x0039414c, 0x0039414c, 0x0038404d, 0x0038404c, 0x0037404b, 0x0038404b, 0x0038404b, 0x0038404c, 0x003a424e, 0x003c444f, 0x003c4450, 0x003c4450, 0x003b4350, 0x003a424f, 0x003a424f, 0x00373f4c, 0x00343c48, 0x00363c48, 0x00383e4a, 0x003a404c, 0x003a404c, 0x0039404b, 0x00383f4a, 0x00383e49, 0x00383f4c, 0x00383f4c, 0x00383f4c, 0x00383f4e, 0x00383f4e, 0x00383f4d, 0x00383f4b, 0x00383f4a, 0x00383f49, 0x00373f49, 0x00353d48, 0x00343c48, 0x00343c48, 0x00343c48, 0x00343d49, 0x0035404c, 0x00373f4c, 0x00373f4c, 0x00353d4a, 0x00353c49, 0x00363b47, 0x00373b47, 0x00353a45, 0x00343943, 0x00343a44, 0x00343c48, 0x00343c48, 0x00343b47, 0x00343a45, 0x00333944, 0x00333843, 0x00323642, 0x00313541, 0x00343844, 0x00383d48, 0x00343b46, 0x00303742, 0x002f3540, 0x00303540, 0x00313843, 0x00343a45, 0x00343945, 0x00333944, 0x00323844, 0x00313843, 0x00303642, 0x00303641, 0x00303742, 0x00313843, 0x00303641, 0x002c333e, 0x002a303c, 0x002a303c, 0x002b323d, 0x002a323c, 0x0029313c, 0x0028303b, 0x00272f39, 0x00272f3a, 0x0028303c, 0x0028303c, 0x00262e3a, 0x00242c37, 0x00222a35, 0x00232b36, 0x00242c35, 0x00242c35, 0x00242d36, 0x00272f39, 0x00262f39, 0x00242d38, 0x00202b35, 0x001f2833, 0x001c2630, 0x001a242e, 0x0019242b, 0x00182228, 0x00162026, 0x00182028, 0x001c2630, 0x00202c36, 0x001e2c36, 0x00202d37, 0x00212f38, 0x00202c36, 0x0018212a, 0x00141c24, 0x00162028, 0x001c262e, 0x001f2a35, 0x00232e3c, 0x0024303e, 0x00232e3a, 0x001f2a36, 0x001c2834, 0x001a2632, 0x0018232f, 0x0016222e, 0x00182430, 0x001d2934, 0x001d2a33, 0x001c2830, 0x0018242c, 0x00142029, 0x0015202c, 0x0017222e, 0x00192430, 0x001a2430, 0x001a2430, 0x0018222e, 0x0017202a, 0x00162029, 0x00152028, 0x00152028, 0x00152029, 0x0015222a, 0x0014212a, 0x00112029, 0x000d1d26, 0x000c1c24, 0x000c1c25, 0x000e1c26, 0x000f1c24, 0x00101c24, 0x00101c24, 0x000e1922, 0x000c1720, 0x000b151e, 0x000a141d, 0x000a141c, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x000a121b, 0x0009141c, 0x0009141c, 0x000a131c, 0x000b131c, 0x000b131c, 0x000c141d, 0x000c141d, 0x000c151e, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c161f, 0x000c161f, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b151e, 0x000c151e, 0x000c151e, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000c1720, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000d1922, 0x000e1a24, 0x000d1924, 0x000c1822, 0x000c1822, 0x000d1924, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1924, 0x000e1924, 0x000e1924, 0x000c1924, 0x000c1a24, 0x000e1b24, 0x000f1b25, 0x000f1a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00131c27, 0x0018222c, 0x001b2632, 0x00182430, 0x0015212c, 0x00131f2b, 0x00131f2b, 0x0015202c, 0x0015202c, 0x0016202c, 0x0015222d, 0x0016232f, 0x00182531, 0x00182430, 0x00182530, 0x00182531, 0x001b2834, 0x001e2c38, 0x001e2c37, 0x001d2a35, 0x001e2b34, 0x001d2a30, 0x001b272d, 0x0019242c, 0x0019232c, 0x001a242e, 0x001b2530, 0x001d2731, 0x00202934, 0x00202934, 0x00202b35, 0x00212c36, 0x00232c37, 0x00242e38, 0x00242d38, 0x00242e38, 0x00252f38, 0x00253038, 0x00242f38, 0x00242d36, 0x00242d36, 0x00242d36, 0x00263038, 0x0029333c, 0x002c343d, 0x002e343d, 0x002c323c, 0x002b313b, 0x002d333e, 0x002f3540, 0x002f3440, 0x002e343d, 0x002d343c, 0x0030343f, 0x00313640, 0x00323640, 0x00313741, 0x00313841, 0x00313842, 0x00313842, 0x00303843, 0x00313944, 0x00323b45, 0x00333b46, 0x00333c46, 0x00343c47, 0x00343a44, 0x00343a45, 0x00343a45, 0x00343944, 0x00343944, 0x00343a45, 0x00343944, 0x00353a45, 0x00373b47, 0x00383c48, 0x003a3f4a, 0x003b404c, 0x003a404c, 0x003a404d, 0x003c4250, 0x003c4350, 0x003b4350, 0x003b4350, 0x003b4350, 0x003a4250, 0x0039414f, 0x003a424e, 0x003c4450, 0x003e4652, 0x003f4754, 0x00404854, 0x00404854, 0x00404854, 0x003f4754, 0x003d4653, 0x003c4552, 0x003a4450, 0x0038404d, 0x00363e4a, 0x00383f4a, 0x003a404c, 0x003b414c, 0x003a414c, 0x003a414c, 0x0039404c, 0x0039404c, 0x00383e4c, 0x00373d4a, 0x00373d4b, 0x00383e4c, 0x00383f4c, 0x00383f4c, 0x00383f4c, 0x00383f4b, 0x00383f4a, 0x00373f49, 0x00373f49, 0x00373e4a, 0x00353d4a, 0x00353d4a, 0x00363f4c, 0x0036404d, 0x0037404d, 0x0038404c, 0x00373f4c, 0x00373d4a, 0x00383c48, 0x00383c48, 0x00373b46, 0x00343a44, 0x00343a45, 0x00343c47, 0x00343c48, 0x00343a46, 0x00343a46, 0x00343a46, 0x00343a45, 0x00353945, 0x00343945, 0x00343944, 0x00343b46, 0x00343a45, 0x00303742, 0x002e3440, 0x002f3440, 0x002f3540, 0x00313843, 0x00323844, 0x00323844, 0x00303641, 0x002d333f, 0x002c323e, 0x002d343f, 0x002d343f, 0x002e3440, 0x002e3440, 0x002e3440, 0x002e343f, 0x002e3440, 0x002e3540, 0x002c3440, 0x002c3440, 0x002c343f, 0x002a323d, 0x0029313d, 0x0029313e, 0x0029313e, 0x00262f3b, 0x00242c37, 0x00232b36, 0x00232b36, 0x00242c35, 0x00242d36, 0x00262f38, 0x0027303a, 0x00262e3a, 0x00232c38, 0x00202a35, 0x001c2732, 0x00192330, 0x0018222c, 0x0018222a, 0x00182328, 0x00192329, 0x00171f27, 0x00151f28, 0x00192530, 0x001b2832, 0x001d2c35, 0x00213039, 0x00222d38, 0x001b242d, 0x00141d26, 0x00141e27, 0x0019242c, 0x001e2934, 0x00212d3b, 0x00242f3d, 0x00222e3a, 0x00202b37, 0x001d2935, 0x001d2934, 0x001b2733, 0x00182430, 0x0017232f, 0x0018242f, 0x001d2a33, 0x00202c35, 0x00202c35, 0x001c2830, 0x0018232d, 0x0018232f, 0x00182430, 0x001a2430, 0x001a2430, 0x0018222e, 0x0017212b, 0x0016202a, 0x00152029, 0x00152029, 0x00152029, 0x0015222a, 0x0014222a, 0x00112029, 0x000e1e27, 0x000d1c26, 0x000e1d27, 0x000f1e28, 0x00101e26, 0x00111d25, 0x00111d25, 0x000f1b23, 0x000c1820, 0x000b161f, 0x000b151e, 0x000a141d, 0x000a131c, 0x000b131c, 0x000b131c, 0x000b131c, 0x000a131c, 0x0009141c, 0x000a141c, 0x000a141c, 0x000b141c, 0x000c141d, 0x000c141e, 0x000c141e, 0x000d151f, 0x000d161f, 0x000e1720, 0x000e1720, 0x000f1720, 0x000f1720, 0x000f1720, 0x000f1820, 0x000f1820, 0x000f1820, 0x000f1720, 0x000f1720, 0x000e1720, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c161f, 0x000c161f, 0x000c151e, 0x000b151e, 0x000b151e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1720, 0x000c1720, 0x000c1720, 0x000c1720, 0x000c1821, 0x000c1822, 0x000c1822, 0x000c1820, 0x000d1921, 0x000d1923, 0x000d1924, 0x000d1924, 0x000d1923, 0x000d1924, 0x000f1a24, 0x00101b25, 0x00101b25, 0x000f1a24, 0x000f1a24, 0x000e1a24, 0x000d1a24, 0x000d1a24, 0x000d1a24, 0x000d1a24, 0x000e1a24, 0x000f1a24, 0x000f1a24, 0x00101b25, 0x00101b25, 0x000f1a25, 0x000f1a25, 0x000f1a25, 0x00101b26, 0x00101b26, 0x00101b26, 0x000f1b25, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00111c26, 0x0016202b, 0x00182430, 0x0018242f, 0x0014202c, 0x00121e28, 0x00111d28, 0x00141e29, 0x00141e29, 0x0015202b, 0x0014202c, 0x0016232d, 0x00182430, 0x00182430, 0x00182530, 0x00192530, 0x001b2732, 0x001e2a35, 0x001f2b36, 0x00202c36, 0x00202c35, 0x00202c34, 0x001d2830, 0x001b252d, 0x001a242c, 0x001a242d, 0x001c262f, 0x001d2830, 0x00202a34, 0x00202b35, 0x00202c36, 0x00212c36, 0x00232d38, 0x00242e38, 0x00242d38, 0x00242d36, 0x00242c36, 0x00232c35, 0x00232c35, 0x00242c36, 0x00262f38, 0x0028323c, 0x002b343d, 0x002a333d, 0x002b323c, 0x002c323c, 0x002b313b, 0x002b313b, 0x002d343d, 0x002f343f, 0x002e343e, 0x002c333b, 0x002c333c, 0x00303640, 0x00333842, 0x00333842, 0x00323842, 0x00313841, 0x00313841, 0x00313841, 0x00303841, 0x00303943, 0x00333a45, 0x00343c47, 0x00353c48, 0x00343b45, 0x00323842, 0x00323843, 0x00343a44, 0x00343b44, 0x00353c46, 0x00363c48, 0x00373c48, 0x00373c48, 0x00383d48, 0x00393f4a, 0x003a404b, 0x00393f4a, 0x00383e4a, 0x003a404e, 0x003c4350, 0x003c4451, 0x003c4450, 0x003c4451, 0x003d4452, 0x003d4454, 0x003c4553, 0x003c4553, 0x003f4754, 0x00404856, 0x00414956, 0x00424a57, 0x00404855, 0x00404854, 0x00404854, 0x00404855, 0x00404854, 0x003f4753, 0x003e4550, 0x003c424e, 0x003b414c, 0x003b424c, 0x003a424d, 0x003a424d, 0x003a424d, 0x003b424d, 0x003b434e, 0x003a424d, 0x0039404c, 0x00373f4a, 0x00363d4a, 0x00383e4b, 0x00383f4c, 0x0039404c, 0x0039404c, 0x00383f4a, 0x00383f4a, 0x00373e4a, 0x00363e4b, 0x00363d4c, 0x0038404d, 0x0038404c, 0x0038404c, 0x0039404c, 0x0039404c, 0x00383f4c, 0x00373d4b, 0x00363c48, 0x00363c48, 0x00363c47, 0x00353b46, 0x00343a47, 0x00333b48, 0x00343c48, 0x00343b48, 0x00343a47, 0x00343a46, 0x00353b47, 0x00353c47, 0x00343a45, 0x00323843, 0x00303843, 0x00313843, 0x00303642, 0x002d343f, 0x002d323e, 0x002d323e, 0x002d343e, 0x002e343f, 0x002e3440, 0x002d343f, 0x002b313c, 0x002a303c, 0x00282f3a, 0x00272d38, 0x00282d38, 0x00282e39, 0x002b313b, 0x002c333d, 0x002e3440, 0x002e3540, 0x002d3540, 0x002d3641, 0x002e3641, 0x002d3540, 0x002c3440, 0x002b333f, 0x0029313c, 0x00272f3a, 0x00242c38, 0x00232c37, 0x00222c36, 0x00242c37, 0x00253039, 0x0027303b, 0x0028303b, 0x00262e39, 0x00212c36, 0x001f2934, 0x001c2731, 0x001a242f, 0x0018212c, 0x00141f28, 0x00152027, 0x0019232a, 0x001b242c, 0x0019222c, 0x001c2832, 0x001d2933, 0x001c2833, 0x00202d36, 0x00212e38, 0x001c262f, 0x00141f27, 0x00152028, 0x0018242b, 0x001d2933, 0x00202c39, 0x00222d3b, 0x00222e39, 0x00212c38, 0x00202c38, 0x001e2a36, 0x001d2a36, 0x001c2834, 0x00182531, 0x0018242f, 0x001a262f, 0x001e2a33, 0x00232f38, 0x00222e36, 0x001c2831, 0x00192631, 0x00192631, 0x00192531, 0x00192430, 0x00182430, 0x0018222d, 0x0016212c, 0x0016212c, 0x0016202c, 0x0015212c, 0x0015232c, 0x0015232c, 0x0012212b, 0x00102028, 0x00101f28, 0x00102029, 0x00112029, 0x00111f28, 0x00131f27, 0x00121e26, 0x00101c24, 0x000d1922, 0x000c1720, 0x000c161f, 0x000b151e, 0x000b141e, 0x000b131e, 0x000b131d, 0x000b131c, 0x000c141d, 0x000a141d, 0x000a141d, 0x000b141e, 0x000b141f, 0x000b141f, 0x000c151e, 0x000c151e, 0x000c161f, 0x000d1720, 0x000d1720, 0x000e171f, 0x000e181f, 0x000e1820, 0x000f1820, 0x00101820, 0x00101820, 0x00101820, 0x00101820, 0x00101820, 0x00101820, 0x000f1720, 0x000e1720, 0x000e161f, 0x000d161f, 0x000d161f, 0x000d1720, 0x000d1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1721, 0x000d1721, 0x000c1721, 0x000b1720, 0x0009171f, 0x0009171f, 0x000a1820, 0x000a1820, 0x000c1822, 0x000d1924, 0x000d1924, 0x000d1921, 0x000d1921, 0x000d1923, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x00101b25, 0x00101c26, 0x00101c26, 0x00101b25, 0x00101b25, 0x000f1b25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000e1a26, 0x000e1a26, 0x00101b27, 0x00111c28, 0x00101c26, 0x000c1c25, 0x000c1c25, 0x000e1c25, 0x000e1c25, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00141d28, 0x0016212d, 0x0016222d, 0x0014202c, 0x00111d26, 0x00101c24, 0x00131d26, 0x00141f28, 0x0016202a, 0x0016212b, 0x0018242e, 0x00192530, 0x0018242f, 0x00192530, 0x001a2630, 0x001b2630, 0x001d2933, 0x001f2b35, 0x001f2b35, 0x00202c34, 0x001f2b33, 0x001d2830, 0x001c262f, 0x001a242c, 0x0018232a, 0x0019232a, 0x001c262e, 0x00202933, 0x00212c37, 0x00222d38, 0x00232f38, 0x0024303a, 0x00253039, 0x00242d36, 0x00232b34, 0x00232b34, 0x00232b34, 0x00232c34, 0x00242c35, 0x0028303b, 0x002c3741, 0x002e3641, 0x002c343f, 0x002a323c, 0x002c323d, 0x002c333d, 0x002c323c, 0x002d343d, 0x00303640, 0x00303740, 0x002d343d, 0x002e343d, 0x00303740, 0x00323842, 0x00313841, 0x00303740, 0x002f353f, 0x002f353e, 0x002e343e, 0x002e343e, 0x002e343f, 0x002e333e, 0x00303440, 0x00303440, 0x002e343e, 0x002d333c, 0x002f343e, 0x00323841, 0x00353b44, 0x00373d47, 0x00383f4a, 0x003a404c, 0x0038404c, 0x00383f4a, 0x0039404b, 0x00383f4a, 0x00363c48, 0x00373d4a, 0x0039404d, 0x003b424f, 0x003a424f, 0x0039414e, 0x0038424e, 0x0039424f, 0x0039414f, 0x0039414e, 0x0038404e, 0x003a4150, 0x003b4150, 0x003b424f, 0x003b424f, 0x003a414e, 0x0039404d, 0x003a414e, 0x003d4451, 0x003e4651, 0x00404852, 0x00414854, 0x00404653, 0x003f4552, 0x00404651, 0x003c4551, 0x003c4550, 0x003b4450, 0x003c4551, 0x003c4550, 0x003b4450, 0x0039434f, 0x0038414d, 0x0037404d, 0x00394250, 0x003a434f, 0x003c4450, 0x003d4450, 0x003b434f, 0x003c4350, 0x003a4250, 0x0039404f, 0x003a4250, 0x003c4452, 0x0038434d, 0x0039414c, 0x003a414c, 0x003c414d, 0x003b414d, 0x003b414f, 0x0039414c, 0x0038404b, 0x00363e49, 0x00363d48, 0x00343c48, 0x00333b48, 0x00343c49, 0x00353d4a, 0x00343c48, 0x00343944, 0x00343945, 0x00343b46, 0x00333944, 0x00303742, 0x00303742, 0x00303843, 0x002f3642, 0x002e343f, 0x002d313d, 0x002c303c, 0x002b313b, 0x002c323c, 0x002d333e, 0x002c333e, 0x002c323d, 0x002b313c, 0x00282f3a, 0x00282d38, 0x00282e39, 0x00282f38, 0x00282f38, 0x00293039, 0x002b313c, 0x002b313c, 0x002a323d, 0x002b333e, 0x002c3440, 0x002e3641, 0x00303843, 0x002e3641, 0x002c343e, 0x0028303b, 0x00262e39, 0x00252e38, 0x00242d38, 0x00242d38, 0x0024303b, 0x0028323d, 0x0029313c, 0x0028303b, 0x00232b36, 0x001e2832, 0x001c2630, 0x001c2530, 0x001b232e, 0x00161f29, 0x00121c24, 0x00121c23, 0x00152028, 0x001c252e, 0x00212c36, 0x00202b35, 0x00182530, 0x001e2a34, 0x00232f38, 0x001e2933, 0x00142029, 0x00152128, 0x0018242b, 0x001c2832, 0x001f2a38, 0x00202c39, 0x00222d39, 0x00232e3a, 0x00202d38, 0x001d2c38, 0x001d2c38, 0x001c2b36, 0x00182833, 0x00182530, 0x001a262f, 0x001b272f, 0x001e2a33, 0x00222e36, 0x00202c37, 0x001d2c38, 0x001c2c37, 0x001c2934, 0x001a2833, 0x001a2733, 0x00182531, 0x00172430, 0x00172430, 0x0016242f, 0x00172430, 0x00182530, 0x00182530, 0x0014242d, 0x0013232c, 0x0013232c, 0x0013232c, 0x0014222c, 0x00142029, 0x00142028, 0x00131f28, 0x00111d25, 0x000f1b23, 0x000d1820, 0x000d1720, 0x000c1620, 0x000c1420, 0x000c1420, 0x000c141e, 0x000c141e, 0x000c141e, 0x000c161e, 0x000c161f, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d171f, 0x000d171f, 0x000e1820, 0x000f1921, 0x00101821, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x00101820, 0x00101820, 0x000f1720, 0x000e1720, 0x000d161f, 0x000d161f, 0x000d1720, 0x000d1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1721, 0x000d1721, 0x000c1821, 0x000b1720, 0x0009171f, 0x0009171f, 0x000a1820, 0x000a1820, 0x000c1822, 0x000d1924, 0x000d1924, 0x000d1921, 0x000d1921, 0x000d1923, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x00101b25, 0x00101c26, 0x00101c26, 0x00101b25, 0x00101b25, 0x000f1b25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b26, 0x000e1a26, 0x000e1a26, 0x00101b27, 0x00111c28, 0x000f1c26, 0x000c1c25, 0x000c1c25, 0x000e1c25, 0x000e1c25, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101c26, 0x00101b25, 0x00101b25, 0x00131d28, 0x0014202c, 0x0017222e, 0x0015202c, 0x00111d26, 0x00101c24, 0x00141e27, 0x00172029, 0x0018222c, 0x0018242d, 0x00192530, 0x00192530, 0x00192530, 0x00192530, 0x001b2630, 0x001b2731, 0x001e2a34, 0x00202c36, 0x00202c35, 0x001f2b34, 0x001c2931, 0x001c2830, 0x001c262f, 0x001a242d, 0x001a242b, 0x001a242d, 0x001e2831, 0x00232c36, 0x0024303a, 0x0025303c, 0x0024303b, 0x00242f3a, 0x00242d38, 0x00212c34, 0x00222b34, 0x00222a34, 0x00232c34, 0x00242c35, 0x00242d36, 0x0028313c, 0x002c3640, 0x002e3742, 0x002d3641, 0x002d343f, 0x002c333e, 0x002e343e, 0x002e343e, 0x002f353f, 0x00303740, 0x00303740, 0x002d343d, 0x002c323c, 0x002c333c, 0x002c323c, 0x002c323c, 0x002d343d, 0x002e343d, 0x002c333c, 0x002c323c, 0x002c323c, 0x002d343c, 0x002e333e, 0x002f3440, 0x002f343f, 0x002c303c, 0x002a2f38, 0x002c303a, 0x0030343e, 0x00333841, 0x00343943, 0x00343944, 0x00373d48, 0x00373e49, 0x00363c48, 0x00353c47, 0x00363c48, 0x00343b47, 0x00353c48, 0x00363c49, 0x00353c4a, 0x00343c48, 0x00333b48, 0x00333a47, 0x00343947, 0x00343947, 0x00343947, 0x00333847, 0x00333847, 0x00343848, 0x00343946, 0x00343846, 0x00333845, 0x00333845, 0x00323844, 0x00333844, 0x00333a45, 0x00343b47, 0x00383f4c, 0x003b424f, 0x003c434f, 0x003c4550, 0x003c4653, 0x003d4854, 0x00404957, 0x00414b58, 0x00404a57, 0x00404956, 0x00404956, 0x003c4653, 0x003b4452, 0x003d4754, 0x003d4854, 0x003f4854, 0x00404754, 0x003e4653, 0x003d4453, 0x003b4351, 0x00394150, 0x003b4452, 0x003d4654, 0x003c4650, 0x003d4650, 0x003e4651, 0x00404752, 0x00404652, 0x003f4453, 0x003d4550, 0x003b444e, 0x0038414c, 0x0039404c, 0x00383f4b, 0x00373f4c, 0x00373f4c, 0x00383f4c, 0x00353d4a, 0x00343944, 0x00323843, 0x00323844, 0x00323844, 0x00323844, 0x00313843, 0x00303742, 0x002f3642, 0x002e3440, 0x002d313d, 0x002c313d, 0x002a303b, 0x00282f38, 0x002a303c, 0x002b313d, 0x002b313c, 0x002a303b, 0x0029303a, 0x00282f38, 0x00252c35, 0x00262c36, 0x00293039, 0x002a303a, 0x00282e39, 0x00272e39, 0x00272e39, 0x00272e39, 0x00272f3a, 0x002a323d, 0x002d3640, 0x002f3742, 0x002f3742, 0x002b333e, 0x0028303b, 0x00272f3a, 0x00242e38, 0x00242e38, 0x0025303b, 0x0028323c, 0x002c343e, 0x002c343f, 0x0028303c, 0x00202934, 0x001b2430, 0x001c242f, 0x001b232d, 0x0019232d, 0x0018212b, 0x00141e27, 0x00121c25, 0x0019222b, 0x00222b35, 0x00212c37, 0x00192630, 0x001c2833, 0x00243039, 0x00202c35, 0x0018242c, 0x00142028, 0x0017232a, 0x001b2731, 0x001f2a38, 0x00202c39, 0x00212d39, 0x00232f3a, 0x00212e39, 0x001e2c38, 0x001d2c38, 0x001c2c37, 0x00192934, 0x001a2731, 0x001a2630, 0x001b272f, 0x001c2830, 0x001c2830, 0x001f2c36, 0x001f2d39, 0x001e2d39, 0x001f2c38, 0x001e2c37, 0x001d2a36, 0x001a2833, 0x00192732, 0x00192732, 0x00182631, 0x00192731, 0x001a2832, 0x001a2832, 0x00182730, 0x00172630, 0x0016252f, 0x0016252f, 0x0016242e, 0x0015222b, 0x00142029, 0x00131f28, 0x00111d25, 0x000f1b23, 0x000d1820, 0x000e1820, 0x000d1620, 0x000c1420, 0x000c1420, 0x000c141f, 0x000c141e, 0x000c141e, 0x000c161e, 0x000c161d, 0x000c161f, 0x000c161f, 0x000c161f, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000e1820, 0x000f1921, 0x000f1921, 0x00101821, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x00101820, 0x00101820, 0x000e1720, 0x000d161f, 0x000d161f, 0x000d1720, 0x000d1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1821, 0x000e1823, 0x000d1823, 0x000c1820, 0x000a1820, 0x000a1820, 0x000b1920, 0x000b1821, 0x000b1823, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000f1b25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b26, 0x000e1b27, 0x000e1c27, 0x00101c27, 0x00101c28, 0x000f1c26, 0x000c1c25, 0x000c1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x00101b25, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c27, 0x00131f2a, 0x0017222e, 0x0016222d, 0x00142028, 0x00121e27, 0x00152028, 0x0019232c, 0x001b262f, 0x001a2630, 0x001b2631, 0x001b2630, 0x001b2630, 0x001c2731, 0x001c2831, 0x001e2a34, 0x00202c36, 0x00212d37, 0x00202c36, 0x001e2a34, 0x001c2831, 0x001c2830, 0x001b2830, 0x001b272f, 0x001b272e, 0x001c2730, 0x00212c35, 0x00242d38, 0x00222d38, 0x00222e38, 0x00212d38, 0x00202b35, 0x00202933, 0x00202a33, 0x00232c34, 0x00242c35, 0x00242d36, 0x00262e38, 0x00272f38, 0x0029323d, 0x002b343f, 0x002d3540, 0x002e3641, 0x002e3440, 0x002e3440, 0x002f3440, 0x00303640, 0x00303640, 0x00303640, 0x002c323c, 0x00282e38, 0x00282e38, 0x00282f38, 0x0029303a, 0x002a303b, 0x002c333c, 0x002e343d, 0x002d343c, 0x002c323c, 0x002c323c, 0x002e343d, 0x00303440, 0x00303440, 0x002f3440, 0x002c303c, 0x00282c36, 0x00282d37, 0x002d313c, 0x00313640, 0x00313540, 0x00303541, 0x00333844, 0x00343a45, 0x00333944, 0x00323844, 0x00333944, 0x00343a45, 0x00343a46, 0x00333947, 0x00333947, 0x00333947, 0x00333947, 0x00343a48, 0x00343a48, 0x00363b48, 0x00373c49, 0x00353c49, 0x00343c49, 0x00343c48, 0x00343c47, 0x00333a45, 0x00323944, 0x00323944, 0x00323844, 0x00323844, 0x00313843, 0x00303842, 0x00303844, 0x00303844, 0x00303845, 0x00313944, 0x00323b48, 0x00343d4a, 0x0037404e, 0x00394250, 0x003b4451, 0x003a4350, 0x003a4450, 0x003a434f, 0x00384150, 0x0038404f, 0x00353e4b, 0x00343c49, 0x00353d4a, 0x00373e4c, 0x00343d4b, 0x00323c4a, 0x00313b49, 0x00333c4b, 0x00363e4c, 0x00363e48, 0x00363d48, 0x00363e49, 0x00373f4a, 0x0038404c, 0x00383f4d, 0x0038404b, 0x00363e49, 0x00343c47, 0x00383f4a, 0x0039404c, 0x0038404c, 0x0038404c, 0x0038404c, 0x00363d4a, 0x00353b46, 0x00333944, 0x00313843, 0x00343945, 0x00343a46, 0x00313944, 0x00303843, 0x002e3641, 0x00303641, 0x00303440, 0x002e333f, 0x002c313c, 0x00282f38, 0x00282f38, 0x0029303a, 0x00293039, 0x002a3039, 0x0029303a, 0x00293039, 0x00282e37, 0x00282e36, 0x00282f38, 0x00282f38, 0x00282d38, 0x00282d39, 0x00282d39, 0x00282e39, 0x0029313c, 0x002c343f, 0x002d3540, 0x002e3641, 0x00303843, 0x002f3742, 0x002a313c, 0x0028303b, 0x0026303a, 0x00252f39, 0x00252f39, 0x0025303a, 0x0028303b, 0x0029313c, 0x0029313c, 0x0027303b, 0x00232c38, 0x00212a35, 0x001c2630, 0x001b2530, 0x001c2731, 0x001e2832, 0x001b252f, 0x0019242e, 0x00212b36, 0x00232e38, 0x001c2933, 0x001c2831, 0x0024303a, 0x00202d37, 0x0018252f, 0x0016222b, 0x0017232b, 0x00182430, 0x001c2734, 0x001e2937, 0x00202c38, 0x00222e3a, 0x00222f3a, 0x001f2e39, 0x001e2d38, 0x001c2c37, 0x001c2b36, 0x001c2934, 0x001c2831, 0x001c2830, 0x001c2830, 0x001b2730, 0x001d2a34, 0x001f2e39, 0x001f2f3a, 0x00202e3a, 0x00202e3a, 0x001f2c38, 0x001c2a36, 0x001c2934, 0x001b2834, 0x001b2834, 0x001b2834, 0x001c2934, 0x001c2934, 0x001b2834, 0x001b2834, 0x001b2834, 0x00192732, 0x00182531, 0x0018242f, 0x0016222c, 0x00141f29, 0x00111d27, 0x000f1a24, 0x000e1924, 0x000f1924, 0x000e1823, 0x000c1620, 0x000c1620, 0x000c1520, 0x000d1520, 0x000d1520, 0x000c161e, 0x000c161d, 0x000c161e, 0x000c161f, 0x000c161f, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000e1820, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x00101821, 0x00101821, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x000f1720, 0x000f1720, 0x000e1720, 0x000e1720, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1821, 0x000e1823, 0x000e1823, 0x000c1821, 0x000b1821, 0x000b1921, 0x000b1921, 0x000b1821, 0x000b1823, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000f1b25, 0x000d1c25, 0x000d1c25, 0x000d1c25, 0x000d1c25, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b26, 0x000e1b27, 0x000e1c27, 0x00101c27, 0x00101c28, 0x000f1c26, 0x000d1c25, 0x000d1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x00101b25, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00131f2a, 0x0017222e, 0x0018242e, 0x0017222b, 0x0016222a, 0x0017212a, 0x0019242c, 0x001b262f, 0x001a2630, 0x001a2630, 0x001b2631, 0x001c2731, 0x001c2831, 0x001e2a34, 0x00202c37, 0x00212d37, 0x00222e38, 0x00202c36, 0x001f2b35, 0x001c2831, 0x001c2730, 0x001c2830, 0x001b2730, 0x001b2730, 0x001e2832, 0x00202a34, 0x00202934, 0x001f2934, 0x001f2934, 0x001c2832, 0x001c2630, 0x001c2730, 0x00202b33, 0x00242c35, 0x00252e37, 0x00262e37, 0x00283038, 0x0028303a, 0x002a333d, 0x002a343e, 0x002b333e, 0x002c3440, 0x002d3440, 0x002f3440, 0x00303640, 0x00303640, 0x00303640, 0x002e343e, 0x002a303a, 0x00272d37, 0x0029303a, 0x002b313c, 0x002c323c, 0x002c323d, 0x002c333e, 0x002e343f, 0x002e343f, 0x002c333e, 0x002c333d, 0x002e343d, 0x002f343f, 0x00303440, 0x002f3440, 0x002d323e, 0x002b3038, 0x00292e38, 0x002d323c, 0x00323740, 0x00313540, 0x00313541, 0x00333844, 0x00343a46, 0x00353b47, 0x00343b46, 0x00343b46, 0x00343a46, 0x00343a45, 0x00333944, 0x00323945, 0x00343a48, 0x00353c49, 0x00353b48, 0x00343a48, 0x00353b48, 0x00363c4a, 0x00353d4a, 0x00363d4b, 0x00373f4b, 0x00363e49, 0x00343c48, 0x00343c47, 0x00333b46, 0x00343b47, 0x00343b48, 0x00343a47, 0x00343b45, 0x00333b46, 0x00333a48, 0x00333946, 0x00303844, 0x002f3744, 0x00303844, 0x00303846, 0x00303846, 0x00303845, 0x00303744, 0x002f3744, 0x00303844, 0x00303846, 0x00303846, 0x002e3643, 0x002d3542, 0x002e3644, 0x00333a48, 0x00363d4b, 0x00363f4c, 0x00363f4d, 0x00363e4c, 0x00343c4a, 0x00333b46, 0x00323844, 0x00303843, 0x00313944, 0x00323945, 0x00333947, 0x00323a45, 0x00313844, 0x00303843, 0x00333944, 0x00333a46, 0x00313946, 0x00323a47, 0x00333b48, 0x00333b48, 0x00343a45, 0x00343a46, 0x00333944, 0x00333944, 0x00343b47, 0x00333b46, 0x00323944, 0x00303742, 0x00303742, 0x00313542, 0x002f3440, 0x002c323c, 0x002a3039, 0x00282f38, 0x00282d37, 0x00272d37, 0x00282e37, 0x00282f38, 0x0029303a, 0x002a303a, 0x002a303a, 0x002a303a, 0x00293038, 0x00282e39, 0x00282e39, 0x00282e39, 0x00282f3a, 0x002a323d, 0x002d3540, 0x002d3540, 0x002c343f, 0x002b333e, 0x002e3540, 0x002e3440, 0x002c333e, 0x002b323d, 0x0027303a, 0x00242d38, 0x00232c37, 0x00242c37, 0x00242c38, 0x00262e38, 0x00242d38, 0x00212b35, 0x00212c36, 0x001f2934, 0x0019242e, 0x0018212c, 0x001a242e, 0x001e2833, 0x001d2834, 0x0024303b, 0x0026333e, 0x00212e39, 0x001c2833, 0x0024323c, 0x00223039, 0x001b2832, 0x0017242c, 0x0017232b, 0x0018242f, 0x00182432, 0x00192532, 0x001b2733, 0x001f2b37, 0x00202d38, 0x001f2e39, 0x001f2e39, 0x001d2c38, 0x001c2c37, 0x001f2b36, 0x001f2b34, 0x001f2b34, 0x001e2a33, 0x001f2a33, 0x00202c37, 0x00202f3a, 0x0020303a, 0x00202f3a, 0x00212f3a, 0x00202e39, 0x001f2c38, 0x001f2c38, 0x001e2c37, 0x001e2c37, 0x001e2c37, 0x001e2c37, 0x001e2c37, 0x001e2c37, 0x001e2c37, 0x001e2b37, 0x001c2934, 0x00192632, 0x00182530, 0x0017222c, 0x00141f29, 0x00111d27, 0x000f1a24, 0x000f1a24, 0x00101a24, 0x000f1824, 0x000d1721, 0x000c1620, 0x000d1620, 0x000d1620, 0x000d1620, 0x000c171f, 0x000c171f, 0x000c171f, 0x000c1720, 0x000c1720, 0x000e1820, 0x000e1820, 0x000e1820, 0x000e1820, 0x000e1820, 0x000e1820, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1922, 0x000f1922, 0x00101922, 0x00101822, 0x00101822, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x00101820, 0x000e1720, 0x000e1720, 0x000e1720, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1720, 0x000d1720, 0x000c1720, 0x000c1822, 0x000c1823, 0x000c1823, 0x000b1823, 0x000b1823, 0x000b1824, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1b24, 0x000e1b24, 0x000e1b24, 0x000e1b24, 0x000e1b24, 0x000e1b25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x000f1c27, 0x00101c27, 0x00101b27, 0x00101b27, 0x00101c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x00101c28, 0x000f1c27, 0x000e1c27, 0x000e1c27, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x00101c25, 0x00101c25, 0x00101b25, 0x00101c26, 0x00111d27, 0x00101c26, 0x00101c26, 0x00121d29, 0x0015212d, 0x0018232e, 0x0018242c, 0x0017232b, 0x0018222b, 0x0018222b, 0x0019242c, 0x0018242c, 0x0018242c, 0x0019242d, 0x001a262f, 0x001c2831, 0x001d2b34, 0x001f2c36, 0x00202d37, 0x00202e38, 0x00202c36, 0x001c2933, 0x001b2830, 0x001a262f, 0x001a262f, 0x0019252f, 0x001a252e, 0x001c2630, 0x001d2731, 0x001c2731, 0x001c2731, 0x001c2631, 0x001b2630, 0x001b2630, 0x001e2831, 0x00202b34, 0x00242d36, 0x00262e37, 0x00272f38, 0x0028313a, 0x002b333d, 0x002c343f, 0x002c343e, 0x002b333c, 0x002c343d, 0x002c343e, 0x002e3540, 0x00303740, 0x00303740, 0x002f353f, 0x002e343e, 0x002b323c, 0x002a323c, 0x002c333d, 0x002d343e, 0x002e343f, 0x002e3440, 0x002e343f, 0x002f3540, 0x00303540, 0x002f343f, 0x002e343d, 0x0030333d, 0x0030343e, 0x00313440, 0x00303440, 0x0030343e, 0x002d323b, 0x002c303a, 0x002e333c, 0x00323640, 0x00333742, 0x00333844, 0x00353a46, 0x00343b46, 0x00353b47, 0x00363c48, 0x00353c47, 0x00343b46, 0x00343945, 0x00333944, 0x00333944, 0x00343945, 0x00343a47, 0x00343a46, 0x00323844, 0x00343a46, 0x00343b47, 0x00343c47, 0x00343c48, 0x00373f4a, 0x0037404b, 0x00373f4a, 0x00363e49, 0x00353d48, 0x00353d48, 0x00353d49, 0x00353d4a, 0x00363e49, 0x00353d48, 0x00353c48, 0x00343b47, 0x00333945, 0x00313844, 0x00313844, 0x00313844, 0x00323844, 0x00313744, 0x00303642, 0x00303642, 0x00303644, 0x00303744, 0x00313844, 0x00313844, 0x00313844, 0x00313844, 0x00313844, 0x00313845, 0x00313845, 0x00323946, 0x00333a48, 0x00323946, 0x00313844, 0x00313844, 0x00313944, 0x00333a45, 0x00343b47, 0x00353b48, 0x00343a46, 0x00333a45, 0x00343a47, 0x00343a47, 0x00333946, 0x00313845, 0x00313845, 0x00313845, 0x00313844, 0x00303743, 0x00323844, 0x00313844, 0x00303642, 0x00303742, 0x00303843, 0x00303641, 0x002f3540, 0x00303641, 0x00303540, 0x002d333f, 0x002c333d, 0x002c303b, 0x00282e38, 0x00272c36, 0x00272b35, 0x00272c36, 0x00272d37, 0x002a303b, 0x002b313d, 0x002c323d, 0x002c323c, 0x002c323c, 0x002b313c, 0x002a303c, 0x0029303b, 0x0028303a, 0x0028303c, 0x0029333d, 0x0028303a, 0x00262e39, 0x00282f3a, 0x002a313c, 0x002c333e, 0x002c343f, 0x002b333e, 0x0028303c, 0x00252e38, 0x00242c38, 0x00232c37, 0x00222b35, 0x00242d38, 0x00242e38, 0x00202934, 0x001e2832, 0x001e2832, 0x001d2830, 0x0019242d, 0x001b262e, 0x001c2730, 0x001a2630, 0x00202c38, 0x0024313c, 0x0023303c, 0x001f2c37, 0x0024323c, 0x0026333e, 0x001d2934, 0x0019242e, 0x0018242d, 0x0018232d, 0x0018222d, 0x0018222d, 0x0018242e, 0x001a2630, 0x001d2a35, 0x001f2c38, 0x0021303b, 0x00202f3a, 0x001d2c38, 0x001d2b36, 0x00202d36, 0x00202e36, 0x00202d35, 0x00212d35, 0x00212e38, 0x00202f3a, 0x0020303a, 0x00202f3a, 0x00212f3a, 0x00212f3a, 0x00202e3a, 0x00202e3a, 0x00202e39, 0x00202d39, 0x00202d39, 0x001e2d39, 0x001e2c38, 0x001f2d39, 0x00202c39, 0x001f2c38, 0x001c2a37, 0x001a2734, 0x00182430, 0x0016212c, 0x00121e28, 0x00101c25, 0x000f1a24, 0x00101a24, 0x000f1924, 0x000e1823, 0x000d1822, 0x000d1721, 0x000e1822, 0x000e1823, 0x000e1823, 0x000e1822, 0x000e1822, 0x000e1821, 0x000e1820, 0x000e1820, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1922, 0x00101a23, 0x00101a23, 0x00101923, 0x00111923, 0x00111923, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x000f1820, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1823, 0x000c1824, 0x000c1824, 0x000b1824, 0x000b1824, 0x000b1824, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d27, 0x00101e28, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00111d27, 0x00101c26, 0x00101c26, 0x00111d28, 0x0015202c, 0x0016222d, 0x0017222b, 0x0016222a, 0x0017212a, 0x0017212a, 0x0017212a, 0x00162228, 0x00162228, 0x00162229, 0x0017242a, 0x001a272f, 0x001c2a34, 0x001d2c35, 0x001d2c36, 0x001f2f38, 0x001e2c36, 0x001a2830, 0x001b2830, 0x001b272f, 0x0019252e, 0x0018232c, 0x00162029, 0x0018222b, 0x0019242d, 0x001a242f, 0x001c2630, 0x001c2731, 0x001e2833, 0x001d2933, 0x001f2831, 0x00212c34, 0x00242d36, 0x00262f38, 0x00283039, 0x002b343d, 0x002f3740, 0x00303841, 0x00303841, 0x002c343d, 0x002c343c, 0x002c343c, 0x002d353f, 0x002f3640, 0x00303640, 0x00303640, 0x00313841, 0x00313942, 0x00303842, 0x002f3840, 0x00303740, 0x00303741, 0x00313843, 0x00303640, 0x002f353f, 0x0030343e, 0x002f343d, 0x002f333d, 0x0030333d, 0x0031343f, 0x00323540, 0x0031343f, 0x0030343d, 0x002e333b, 0x002c303a, 0x002e323c, 0x00313540, 0x00333743, 0x00353945, 0x00373b47, 0x00353b47, 0x00353b46, 0x00363c48, 0x00363c48, 0x00343b46, 0x00343b46, 0x00343b46, 0x00343945, 0x00333944, 0x00333944, 0x00323844, 0x00313843, 0x00333944, 0x00343b46, 0x00343b46, 0x00343c48, 0x00353e49, 0x00373f4c, 0x00373f4a, 0x00373f49, 0x00363e49, 0x00373f49, 0x0038404a, 0x0038404a, 0x0038404a, 0x00373f49, 0x00353d48, 0x00343c47, 0x00343b47, 0x00343a45, 0x00333944, 0x00333944, 0x00333844, 0x00323743, 0x00313843, 0x00303743, 0x00303644, 0x00303744, 0x00303844, 0x00313844, 0x00323844, 0x00323844, 0x00323844, 0x00313844, 0x00303743, 0x00303742, 0x00323844, 0x00323844, 0x00313844, 0x00303844, 0x00303844, 0x00343a46, 0x00353b47, 0x00343a46, 0x00333944, 0x00333944, 0x00333945, 0x00333844, 0x00303542, 0x00303542, 0x00303643, 0x00303743, 0x00303742, 0x00303742, 0x00303742, 0x00303641, 0x002f3440, 0x002d333f, 0x002c323d, 0x002c323d, 0x002d333e, 0x002e343f, 0x002e3440, 0x002d333e, 0x002c333e, 0x002c313c, 0x00282d37, 0x00262b34, 0x00282c37, 0x002c303b, 0x002b313b, 0x002c323c, 0x002c343e, 0x002c343f, 0x002c343f, 0x002d3540, 0x00303641, 0x002f3540, 0x002c343f, 0x002b333e, 0x0028313c, 0x0025303a, 0x00222b35, 0x00212a34, 0x00242d38, 0x0028303a, 0x0028303b, 0x0029313c, 0x0029313c, 0x0028303c, 0x00272f3a, 0x00272f3a, 0x0028303c, 0x0028303b, 0x00242c38, 0x00202b35, 0x001c2630, 0x0018232d, 0x0018232c, 0x0019242c, 0x001c282f, 0x001c2830, 0x001f2b34, 0x001e2a34, 0x00202c36, 0x00203039, 0x00203039, 0x0023313c, 0x00273540, 0x00283440, 0x001e2a34, 0x001b2530, 0x0018222c, 0x0017212b, 0x00162029, 0x0016202a, 0x0016222a, 0x0018242c, 0x001b2732, 0x001e2c37, 0x00212f3a, 0x0023323d, 0x0020303b, 0x001d2c36, 0x001d2b34, 0x00202d37, 0x00212d35, 0x00212d35, 0x00212e38, 0x00202f3a, 0x0020303a, 0x00202f3a, 0x00212f3a, 0x00212f3a, 0x00212f3a, 0x00212f3a, 0x00212f3a, 0x00212f3a, 0x00202f3b, 0x00202f3c, 0x001f2f3c, 0x00202f3c, 0x00202d3a, 0x001e2c39, 0x001c2937, 0x00192633, 0x0017232f, 0x0014202b, 0x00111d28, 0x00101c25, 0x00101a24, 0x00101a24, 0x000f1924, 0x000e1823, 0x000e1822, 0x000e1822, 0x000e1823, 0x000f1824, 0x000f1824, 0x000f1824, 0x000f1824, 0x000f1822, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1922, 0x00101a23, 0x00101a23, 0x00101923, 0x00111923, 0x00111923, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x000f1820, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a1820, 0x000b1820, 0x000c1820, 0x000c1823, 0x000c1824, 0x000c1824, 0x000b1824, 0x000b1824, 0x000c1824, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000e1a24, 0x000e1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1d27, 0x00101d27, 0x00101c27, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c27, 0x00101c26, 0x00101c26, 0x00111d28, 0x0015202c, 0x0016212c, 0x00142029, 0x00131f27, 0x00141f28, 0x00152028, 0x00152028, 0x00142027, 0x00152128, 0x00162228, 0x00152128, 0x0018242c, 0x001b2933, 0x001c2c35, 0x001d2c36, 0x001e2d37, 0x001d2b34, 0x001b2830, 0x001c2830, 0x001c2830, 0x0018232b, 0x00141e25, 0x00131c25, 0x00161f28, 0x0017212b, 0x001a242f, 0x001d2832, 0x00202a34, 0x00202b35, 0x001e2a34, 0x00202a33, 0x00232c36, 0x00262f38, 0x00263039, 0x0028323b, 0x002c353e, 0x00303841, 0x00303841, 0x002e3740, 0x002c343d, 0x002c343d, 0x002c343e, 0x002e3640, 0x002f3740, 0x00303740, 0x00323842, 0x00353c45, 0x00343c45, 0x00333c44, 0x00303841, 0x002f3740, 0x00303741, 0x00303641, 0x002f343f, 0x002d343c, 0x002d333c, 0x002c313b, 0x002c303b, 0x002d303b, 0x0030323c, 0x0030333d, 0x0030343e, 0x0030333c, 0x002d323b, 0x002c303b, 0x002e333c, 0x00313540, 0x00323642, 0x00343844, 0x00353945, 0x00353945, 0x00353a46, 0x00373c48, 0x00363c48, 0x00353b47, 0x00353c47, 0x00353c47, 0x00343a46, 0x00333844, 0x00323844, 0x00323844, 0x00333944, 0x00343a46, 0x00363c48, 0x00363d48, 0x00343c48, 0x00343c48, 0x00353d4a, 0x00353d48, 0x00353d48, 0x00363e49, 0x00373f49, 0x0038404a, 0x0038404a, 0x00373f49, 0x00363f49, 0x00353d48, 0x00353c48, 0x00363c48, 0x00343b47, 0x00343944, 0x00343944, 0x00343844, 0x00333743, 0x00313843, 0x00313843, 0x00303644, 0x00303744, 0x00303844, 0x00323844, 0x00323844, 0x00323844, 0x00323844, 0x00313844, 0x00303742, 0x00303742, 0x00313843, 0x00323844, 0x00313843, 0x002f3742, 0x00303842, 0x00333a44, 0x00343a45, 0x00333944, 0x00303742, 0x00303642, 0x00313642, 0x00303541, 0x00303440, 0x002f343f, 0x00303441, 0x00313642, 0x00303742, 0x00303742, 0x00303742, 0x00303641, 0x002f3440, 0x002c323d, 0x002b313c, 0x002c323d, 0x002c333e, 0x002d343f, 0x002e343f, 0x002e343f, 0x002f3440, 0x0030343e, 0x002b303a, 0x00282c36, 0x002a2f39, 0x0030343f, 0x00313841, 0x00313842, 0x00303742, 0x002f3742, 0x002e3641, 0x002f3742, 0x00303843, 0x00303843, 0x002f3641, 0x002d3540, 0x002b343e, 0x0027313c, 0x00242d38, 0x00232c36, 0x00252e38, 0x00262e38, 0x0027303a, 0x0028313c, 0x0028303c, 0x0028303c, 0x0028313c, 0x0028303b, 0x0029313c, 0x002d3540, 0x002c3440, 0x00242e39, 0x001d2731, 0x0018232d, 0x0016202b, 0x00141e26, 0x00141f25, 0x00162028, 0x001b252e, 0x001e2934, 0x0024303a, 0x0026343e, 0x0023323c, 0x0023313c, 0x00273440, 0x00283540, 0x001e2934, 0x001b2630, 0x0018242d, 0x0017222b, 0x00162029, 0x00162029, 0x0016222a, 0x0018242c, 0x001a2631, 0x001c2934, 0x001f2c37, 0x0021303b, 0x0023313d, 0x00212f3a, 0x001e2c35, 0x001c2a34, 0x001f2c34, 0x00202c34, 0x00202d38, 0x00202f3a, 0x0020303a, 0x00202f3a, 0x00212f3a, 0x00212f3a, 0x00212f3a, 0x00212f3a, 0x00212f3a, 0x00212f3a, 0x00202e3a, 0x00202f3c, 0x0020303e, 0x001f303c, 0x001c2d3a, 0x001c2b38, 0x001a2835, 0x00182532, 0x0015222e, 0x0013202a, 0x00101d27, 0x00101c25, 0x00101b24, 0x00101a24, 0x000f1924, 0x000e1824, 0x000e1823, 0x000e1823, 0x000e1823, 0x000f1824, 0x000f1824, 0x000f1824, 0x000f1824, 0x000f1822, 0x000f1921, 0x000f1922, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x00101a22, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101923, 0x00111923, 0x00111923, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x000f1820, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a1821, 0x000a1821, 0x000b1821, 0x000d1823, 0x000e1824, 0x000d1824, 0x000c1824, 0x000c1824, 0x000c1824, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000e1a24, 0x000e1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x00101d28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101c28, 0x00101c28, 0x00101c28, 0x00101c28, 0x00101c28, 0x00111d28, 0x0015202c, 0x0017222d, 0x0015212a, 0x00111d25, 0x00131d25, 0x00141f27, 0x00141e26, 0x00131f24, 0x00142027, 0x00152128, 0x00152128, 0x0016222b, 0x00182730, 0x001c2b34, 0x001d2c36, 0x001d2c36, 0x001c2a34, 0x001a252e, 0x001c2730, 0x001a252d, 0x00141f26, 0x00101b21, 0x00131b24, 0x00151e27, 0x0017212b, 0x001c2630, 0x001d2731, 0x00202934, 0x001e2832, 0x001d2932, 0x00222d36, 0x0027313b, 0x0029313c, 0x0027313c, 0x0027313c, 0x002b343f, 0x002e3540, 0x002d3440, 0x002c343d, 0x002c343d, 0x002d353f, 0x002f3740, 0x00303841, 0x00323944, 0x00323844, 0x00313743, 0x00313843, 0x002e3540, 0x002b333c, 0x0029313b, 0x0029313a, 0x002c343e, 0x002d3440, 0x002e343f, 0x002d343c, 0x002c323c, 0x002c303a, 0x002a2f38, 0x002b2f39, 0x002d313c, 0x002e333c, 0x002e333c, 0x002d323c, 0x002c313b, 0x002d323c, 0x0030343f, 0x00313541, 0x00313541, 0x00313541, 0x00323642, 0x00343844, 0x00343844, 0x00353a46, 0x00363b46, 0x00353b47, 0x00353c47, 0x00353c47, 0x00343a45, 0x00303743, 0x00303743, 0x00323844, 0x00323844, 0x00323844, 0x00333a45, 0x00343a45, 0x00343a45, 0x00353c47, 0x00353c49, 0x00353c48, 0x00353c48, 0x00363d48, 0x00363d48, 0x00373f49, 0x00373f49, 0x00363e4a, 0x0038404b, 0x00373f4b, 0x00373e4b, 0x00373d4a, 0x00343b47, 0x00343844, 0x00343844, 0x00343844, 0x00333844, 0x00323844, 0x00323844, 0x00313843, 0x00313843, 0x00303843, 0x00313844, 0x00323844, 0x00323844, 0x00323844, 0x00313844, 0x00303742, 0x00313843, 0x00323844, 0x00323844, 0x00313843, 0x00303742, 0x00303742, 0x00323944, 0x00333944, 0x00323844, 0x00303641, 0x00303541, 0x00303440, 0x002f3440, 0x002e323e, 0x002d323d, 0x00303440, 0x00323743, 0x00323743, 0x00303742, 0x00303641, 0x002f3540, 0x002e3440, 0x002c333e, 0x002b323d, 0x002b313c, 0x002b313c, 0x002b313c, 0x002b313c, 0x002a303c, 0x002b313c, 0x002c313b, 0x002a2f38, 0x00272c35, 0x00282c37, 0x002d333c, 0x00323842, 0x00343b46, 0x00323944, 0x00303844, 0x00313944, 0x00303844, 0x00303843, 0x00303742, 0x00313843, 0x00303843, 0x002e3741, 0x002c3540, 0x0028313c, 0x0028303b, 0x0028303c, 0x00272f3a, 0x00272f3a, 0x002a323d, 0x002a323d, 0x0028323c, 0x002a333d, 0x002b333d, 0x002a323d, 0x002b333e, 0x002a333e, 0x0027313c, 0x00242f39, 0x001f2833, 0x0019232d, 0x00151f27, 0x00131d24, 0x00141f26, 0x0017212b, 0x0017222c, 0x001f2c35, 0x0027353f, 0x00273640, 0x0025343f, 0x0024323d, 0x00283540, 0x001d2a35, 0x001a2630, 0x0018242f, 0x0018222c, 0x00182029, 0x00182029, 0x0017212a, 0x0019232c, 0x001a252e, 0x00192530, 0x001c2832, 0x001f2c38, 0x0024313c, 0x00212f3b, 0x00202e39, 0x001d2a36, 0x001d2a34, 0x001f2b34, 0x001f2b36, 0x001e2c38, 0x001d2c38, 0x001f2c38, 0x001f2c38, 0x001f2c38, 0x001f2c38, 0x001f2c38, 0x001f2c38, 0x001f2c38, 0x001e2c38, 0x001d2c38, 0x001f2d3b, 0x001f2e3c, 0x001c2c39, 0x001a2a37, 0x00182834, 0x00162432, 0x0014212d, 0x00111e2a, 0x000f1c28, 0x00101c25, 0x00101c26, 0x00101b25, 0x00101b25, 0x000e1a24, 0x000e1924, 0x000e1924, 0x000f1a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101a24, 0x00101a24, 0x00101924, 0x00111923, 0x00111923, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x000f1820, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a1821, 0x000a1821, 0x000b1821, 0x000d1823, 0x000e1824, 0x000d1824, 0x000c1824, 0x000c1824, 0x000c1824, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000e1a24, 0x000e1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x00101d28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101c28, 0x00101e29, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101c28, 0x00101c28, 0x00101c28, 0x00101c28, 0x00101c28, 0x00121d29, 0x0015202c, 0x00182430, 0x0019252e, 0x00152129, 0x00142028, 0x00162029, 0x00162028, 0x00162228, 0x00142128, 0x00142128, 0x00152128, 0x0016222b, 0x00182630, 0x001c2b34, 0x001d2c36, 0x001d2c36, 0x001c2a34, 0x0018242d, 0x001c262f, 0x0019242c, 0x00121c24, 0x000f1921, 0x00141d25, 0x0018202a, 0x001a242e, 0x001c2630, 0x001c2730, 0x001e2830, 0x001d2830, 0x00202c34, 0x0026323c, 0x0029343f, 0x002a343e, 0x0028333d, 0x0028313c, 0x002a323d, 0x002c333e, 0x002c323d, 0x002c333d, 0x002f353f, 0x00303740, 0x00303841, 0x00303942, 0x00323a43, 0x00313843, 0x002e3440, 0x002c333e, 0x002b333d, 0x002c343d, 0x002c343d, 0x002b343c, 0x002c343e, 0x002d3440, 0x002f343f, 0x002d343d, 0x002d333c, 0x002d313c, 0x002c303b, 0x002d313c, 0x002f343d, 0x002f343d, 0x002e333c, 0x002c313c, 0x002d323c, 0x002f343d, 0x00303540, 0x00323641, 0x00323642, 0x00323642, 0x00313542, 0x00323642, 0x00323642, 0x00333844, 0x00343844, 0x00333844, 0x00323944, 0x00323844, 0x00313843, 0x002f3541, 0x00303642, 0x00313843, 0x00313843, 0x00313843, 0x00313843, 0x00313843, 0x00323844, 0x00333944, 0x00343a47, 0x00343a46, 0x00343a45, 0x00343b46, 0x00353c47, 0x00363d48, 0x00353d49, 0x00363f4c, 0x0039414e, 0x0038404d, 0x00383f4c, 0x00383e4b, 0x00363c48, 0x00343945, 0x00343844, 0x00343944, 0x00343944, 0x00323844, 0x00313844, 0x00313843, 0x00313843, 0x00303843, 0x00313843, 0x00313843, 0x00313843, 0x00323844, 0x00313843, 0x00313843, 0x00323844, 0x00333944, 0x00333944, 0x00323844, 0x00313843, 0x00323844, 0x00323844, 0x00333844, 0x00323743, 0x00313542, 0x00313541, 0x00303541, 0x002f3440, 0x002d313d, 0x002d323e, 0x00303440, 0x00323642, 0x00323642, 0x00303541, 0x002f3540, 0x002f3440, 0x002f343f, 0x002d333e, 0x002c323d, 0x002a303c, 0x00282f3a, 0x00292f3a, 0x00282f3a, 0x00282f38, 0x00282e38, 0x00282e38, 0x00282f38, 0x00282f39, 0x00292f3a, 0x002b323c, 0x002e343e, 0x00303641, 0x002f3540, 0x002d343f, 0x002c333e, 0x00303641, 0x00343a45, 0x00353b47, 0x00343b46, 0x00323a45, 0x00313944, 0x002f3843, 0x002c3640, 0x002c343f, 0x002c343f, 0x0028303c, 0x0028303c, 0x0028303c, 0x0028303c, 0x0028323c, 0x002a343f, 0x002c3640, 0x002a343f, 0x0027303b, 0x00242e38, 0x00202b35, 0x00202a34, 0x001f2833, 0x001c2630, 0x0018222a, 0x00131d24, 0x00131d24, 0x00152028, 0x0016202a, 0x0018242e, 0x00202d37, 0x0023313b, 0x0026343f, 0x0026343f, 0x00283641, 0x001f2c37, 0x001a2631, 0x001a2530, 0x0019232d, 0x00182029, 0x00182029, 0x0017212a, 0x0018232c, 0x0019242e, 0x001a2530, 0x001a2630, 0x001c2934, 0x00212f3b, 0x00202c38, 0x00202d38, 0x00202d38, 0x001e2b34, 0x001d2933, 0x001c2934, 0x001a2834, 0x00192834, 0x001a2834, 0x001b2834, 0x001b2834, 0x001b2834, 0x001b2834, 0x001a2834, 0x001a2834, 0x001b2834, 0x001b2834, 0x001c2935, 0x001d2b37, 0x001c2b37, 0x001a2935, 0x00182734, 0x00152431, 0x0013202c, 0x00101e29, 0x000f1c27, 0x00101d26, 0x00101c26, 0x00101c26, 0x00101b25, 0x00101b25, 0x000f1a24, 0x000f1a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101924, 0x00111923, 0x00111923, 0x00101821, 0x00101821, 0x00101821, 0x00101820, 0x000f1820, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1822, 0x000c1822, 0x000c1822, 0x000d1822, 0x000d1722, 0x000d1722, 0x000c1822, 0x000c1822, 0x000c1823, 0x000c1823, 0x000c1923, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000f1c27, 0x000f1c27, 0x000f1c27, 0x000f1c27, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c27, 0x00101c28, 0x00101c28, 0x00101c28, 0x00101c28, 0x00101c28, 0x00111e29, 0x00111e29, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101c28, 0x00101c28, 0x00111c28, 0x00111c28, 0x00111c28, 0x00101c28, 0x00121f29, 0x0015222c, 0x001b2832, 0x001b2730, 0x0018242d, 0x0018222b, 0x0018222b, 0x0019232c, 0x0019242c, 0x0018222a, 0x00162128, 0x00172229, 0x0018232c, 0x00192630, 0x001e2b35, 0x001f2c35, 0x001e2b35, 0x001c2832, 0x001c2730, 0x001d2830, 0x0018232b, 0x00111c24, 0x00121c24, 0x00172028, 0x0019232c, 0x001b242c, 0x001b242d, 0x001c252e, 0x001e2831, 0x00212c34, 0x0026313a, 0x002a3640, 0x002a3640, 0x002a343f, 0x0029333d, 0x0029323d, 0x0029303c, 0x002a303c, 0x002a313c, 0x002b333c, 0x002d363f, 0x002f3642, 0x002f3641, 0x002f3742, 0x002f3842, 0x002f3742, 0x002d3540, 0x002c3440, 0x002e3641, 0x00323a44, 0x00323944, 0x00303843, 0x002f3641, 0x002f3641, 0x00303640, 0x00303640, 0x0030353f, 0x00303640, 0x00303640, 0x00303540, 0x00303540, 0x00303540, 0x002e343e, 0x002e343e, 0x002f343f, 0x00303540, 0x00303540, 0x00313541, 0x00323642, 0x00323642, 0x00313541, 0x00313541, 0x00323642, 0x00333743, 0x00333844, 0x00313843, 0x00303843, 0x00303843, 0x00303742, 0x002f3541, 0x00303641, 0x00303742, 0x00303742, 0x00303742, 0x00303742, 0x00303742, 0x00313843, 0x00323844, 0x00323844, 0x00333946, 0x00343b47, 0x00343b48, 0x00343c48, 0x00343c48, 0x00343c49, 0x00353d4a, 0x0038404c, 0x0038404d, 0x0038404d, 0x0038404c, 0x00363e4a, 0x00343c48, 0x00343a47, 0x00343a47, 0x00343946, 0x00323844, 0x00323743, 0x00323843, 0x00313843, 0x00313843, 0x00313843, 0x00313843, 0x00313843, 0x00313843, 0x00303843, 0x00313843, 0x00323844, 0x00333944, 0x00343945, 0x00333944, 0x00333944, 0x00323844, 0x00333844, 0x00333844, 0x00323642, 0x00313541, 0x00303441, 0x00303440, 0x00303440, 0x002f3440, 0x002f3440, 0x00303440, 0x00303440, 0x00303440, 0x002f343e, 0x002e333d, 0x002e333d, 0x002e333d, 0x002d323c, 0x002b313c, 0x00282f39, 0x00272d38, 0x00282e38, 0x00282e38, 0x00282e37, 0x00272d37, 0x00272d37, 0x00282f39, 0x002a303c, 0x002b313d, 0x002b313c, 0x002b313c, 0x002e3440, 0x002e343f, 0x002c323d, 0x002b303c, 0x002c303c, 0x00303541, 0x00333844, 0x00333844, 0x00323a46, 0x00323b46, 0x00303945, 0x00303945, 0x002f3945, 0x002e3844, 0x002a333f, 0x0028313d, 0x0028303c, 0x0028303c, 0x0029323c, 0x002c3540, 0x002d3842, 0x002d3842, 0x0029333e, 0x00252f39, 0x00202c34, 0x001e2831, 0x001c2630, 0x001b242f, 0x0018222a, 0x00162028, 0x00141e24, 0x00152027, 0x0018232b, 0x0019242e, 0x001f2c35, 0x00212f38, 0x00212f39, 0x0025333e, 0x00293844, 0x0023313d, 0x001c2834, 0x001a2630, 0x0019242e, 0x0018222c, 0x0018212b, 0x00162029, 0x0017212a, 0x0019232c, 0x001b252f, 0x001c252f, 0x001b2731, 0x001e2a34, 0x001d2a35, 0x001e2b37, 0x00202d38, 0x001f2c37, 0x001b2833, 0x00192430, 0x00182430, 0x0018242f, 0x0017232f, 0x00192531, 0x00192631, 0x00182430, 0x0018242f, 0x0018242f, 0x0017242f, 0x0017242f, 0x0016232c, 0x0017232d, 0x0018252f, 0x001a2731, 0x001a2833, 0x00192632, 0x00172330, 0x0013202c, 0x00101e29, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101c27, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00111c26, 0x00111c26, 0x00101c26, 0x00101c26, 0x00111c26, 0x00111c26, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101a24, 0x00101a24, 0x00101924, 0x00111923, 0x00111923, 0x00101922, 0x00101921, 0x000f1821, 0x000f1820, 0x000f1820, 0x000e171f, 0x000e171e, 0x000e171e, 0x000e171e, 0x000e171e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1822, 0x000c1822, 0x000c1822, 0x000c1820, 0x000c1720, 0x000c1820, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1822, 0x000c1822, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c26, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c26, 0x000f1c27, 0x00101d27, 0x00101d27, 0x00101c28, 0x00121e29, 0x00121e29, 0x00101e29, 0x00101e29, 0x00101d28, 0x00101d28, 0x00101d28, 0x00111c28, 0x00111c28, 0x00111c28, 0x00111c28, 0x00101c28, 0x00101e28, 0x0014212b, 0x001c2933, 0x001c2731, 0x0018242e, 0x0018222b, 0x0018222b, 0x0019232c, 0x001b252e, 0x001a242d, 0x0018222b, 0x0019232c, 0x0019242c, 0x00192530, 0x00202b35, 0x001e2a34, 0x001c2831, 0x0019252f, 0x00202a33, 0x001f2a33, 0x0018232c, 0x00121c25, 0x00141e27, 0x0018212a, 0x001a232c, 0x001a232c, 0x001a242c, 0x001c262f, 0x00202a33, 0x00242d36, 0x0028323b, 0x002a3640, 0x0029353f, 0x0029333c, 0x0028333c, 0x0029333c, 0x002a313c, 0x0029303c, 0x0029313c, 0x002b343d, 0x002c3640, 0x002e3641, 0x002d3540, 0x002c333e, 0x002c343f, 0x002d3641, 0x002f3742, 0x002f3742, 0x00303844, 0x00343c48, 0x00353c48, 0x00333947, 0x00323844, 0x00313843, 0x00323842, 0x00323842, 0x00343a44, 0x00343b44, 0x00343c47, 0x00343a45, 0x00333844, 0x00313843, 0x00313843, 0x00303742, 0x00303742, 0x00303740, 0x0030343f, 0x002f343f, 0x00303440, 0x00303440, 0x00313641, 0x00333843, 0x00333743, 0x00333844, 0x00323844, 0x00303843, 0x002f3742, 0x00303742, 0x00303541, 0x00303541, 0x00303742, 0x00303743, 0x00303743, 0x00303743, 0x00303742, 0x00313843, 0x00313843, 0x00323844, 0x00333945, 0x00343b48, 0x00343c49, 0x00343c49, 0x00323c48, 0x00323b48, 0x00323b48, 0x00343c48, 0x00353d4a, 0x0038404c, 0x0038404d, 0x00383f4c, 0x00343c49, 0x00333b48, 0x00333b48, 0x00333b48, 0x00333b47, 0x00323844, 0x00323843, 0x00333944, 0x00333944, 0x00323844, 0x00333844, 0x00323844, 0x00313843, 0x00303742, 0x002f3440, 0x00303641, 0x00323844, 0x00343a46, 0x00343b46, 0x00343b46, 0x00333944, 0x00333844, 0x00333743, 0x00323642, 0x00313541, 0x002f343f, 0x002d323d, 0x002e333e, 0x00303440, 0x00303441, 0x00303440, 0x002f3440, 0x002e333e, 0x002e323e, 0x002d323c, 0x002c3139, 0x002b3038, 0x002b3038, 0x002b3038, 0x002a303a, 0x00272d37, 0x00252c36, 0x00262c36, 0x00262c36, 0x00262d37, 0x00272d37, 0x00272d37, 0x00282e38, 0x0029303b, 0x002a303c, 0x002a303c, 0x002a303c, 0x002d333e, 0x002d333f, 0x002d333f, 0x002c333e, 0x002e3440, 0x00303641, 0x00313743, 0x00323744, 0x00303744, 0x00313946, 0x00303946, 0x00303a47, 0x00313b49, 0x00303a47, 0x002c3441, 0x0028303e, 0x00272f3c, 0x00272f3c, 0x0028303c, 0x0028313c, 0x0029333d, 0x002b3540, 0x002b3540, 0x0028323c, 0x00242d36, 0x001e2830, 0x001c242f, 0x0019212c, 0x0018212c, 0x0018232b, 0x00182329, 0x0019242a, 0x001a242c, 0x001a2530, 0x00202d37, 0x00223039, 0x00202d38, 0x00202f3a, 0x00263640, 0x0023333e, 0x001c2b36, 0x00192631, 0x00192430, 0x0019232d, 0x0018222c, 0x00162029, 0x00152028, 0x0018222a, 0x001c252e, 0x001c262f, 0x001a262f, 0x001a262f, 0x001b2730, 0x001c2833, 0x001e2a34, 0x001d2a35, 0x001a2733, 0x0018232e, 0x0018222c, 0x0016202b, 0x00151f2a, 0x0018222c, 0x0018232e, 0x0015212c, 0x0014202a, 0x0014202a, 0x0014202a, 0x00142029, 0x00131f28, 0x00131f29, 0x0014202a, 0x0017232d, 0x00192530, 0x00192531, 0x0018232f, 0x0014202c, 0x00101e2a, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101c27, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00111c26, 0x00111c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00111c26, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101a24, 0x00101a24, 0x00101924, 0x00111923, 0x00111923, 0x00101922, 0x000f1921, 0x000f1821, 0x000e1820, 0x000e1820, 0x000e171e, 0x000e171e, 0x000e171e, 0x000e171e, 0x000e171e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1822, 0x000c1822, 0x000c1822, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1822, 0x000c1822, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c26, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c27, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101d28, 0x00121e29, 0x00121e29, 0x00101e29, 0x00101e29, 0x00101d28, 0x00101d28, 0x00101d28, 0x00111c28, 0x00111c28, 0x00111c28, 0x00111c28, 0x00101c27, 0x000f1d27, 0x0013202b, 0x001b2832, 0x001b2732, 0x00182430, 0x0018222c, 0x0018222b, 0x0018232c, 0x0019242d, 0x001b262f, 0x001a252e, 0x001a252e, 0x0019242c, 0x00192530, 0x001e2a34, 0x001c2833, 0x0018232d, 0x0016222c, 0x001d2934, 0x001e2a34, 0x001a252e, 0x0017212a, 0x0018212a, 0x0018232c, 0x0018232c, 0x001b242d, 0x001e2830, 0x00202b34, 0x00212c34, 0x00232d36, 0x00273039, 0x0028333c, 0x0028333c, 0x0029333c, 0x0029333c, 0x002a333c, 0x002b323c, 0x002a313c, 0x002a323d, 0x002b343e, 0x002c3540, 0x002d3540, 0x002c343f, 0x002a313d, 0x002b323d, 0x002e3540, 0x00303844, 0x00333b46, 0x00333c46, 0x00333b46, 0x00313845, 0x00313744, 0x00303644, 0x00303642, 0x00303741, 0x00313841, 0x00333943, 0x00343b45, 0x00343b46, 0x00343b46, 0x00333944, 0x00333944, 0x00333944, 0x00313843, 0x00313843, 0x00303740, 0x002f343e, 0x002c303c, 0x002e333e, 0x00303440, 0x00323742, 0x00343844, 0x00343844, 0x00333844, 0x00323844, 0x00313843, 0x00303843, 0x00303743, 0x00303642, 0x00303642, 0x00303742, 0x00313843, 0x00313843, 0x00303843, 0x00303843, 0x00303743, 0x00303742, 0x00323844, 0x00333945, 0x00343c48, 0x00343d49, 0x00343d49, 0x00323c49, 0x00323c48, 0x00333c49, 0x00343c49, 0x00353d4a, 0x00373f4c, 0x0038404c, 0x00363e4b, 0x00343c49, 0x00343c48, 0x00333b48, 0x00333b48, 0x00333b48, 0x00343a48, 0x00343a47, 0x00353b48, 0x00343b47, 0x00343a46, 0x00343a46, 0x00343945, 0x00323844, 0x002f3540, 0x002c333e, 0x002d333f, 0x00323844, 0x00343b46, 0x00343a45, 0x00333944, 0x00313843, 0x00323642, 0x00323642, 0x00323642, 0x00303440, 0x002f333d, 0x002e333e, 0x002e333e, 0x002f343f, 0x00303440, 0x00303440, 0x002e333e, 0x002c303c, 0x002b2f3c, 0x002b3038, 0x002a2f37, 0x002a2f37, 0x002a2f37, 0x002a2f37, 0x00292f38, 0x00262c36, 0x00242b34, 0x00252c35, 0x00262c36, 0x00262c36, 0x00272c36, 0x00272d37, 0x00282d38, 0x0029303b, 0x002b313c, 0x002b313c, 0x002c313d, 0x002c323d, 0x002d343f, 0x002f3440, 0x002f3440, 0x002d333f, 0x002e3440, 0x00303541, 0x00303442, 0x002c3442, 0x002b3441, 0x002c3542, 0x002f3846, 0x00313c4a, 0x00303948, 0x002d3543, 0x0028303d, 0x00272f3c, 0x00262e3b, 0x00262d39, 0x00262f39, 0x0025303a, 0x0028303b, 0x0028303c, 0x0027303a, 0x00252d36, 0x00202831, 0x001f2630, 0x001b232d, 0x00172029, 0x00162028, 0x00172128, 0x0019242b, 0x001d2830, 0x001c2630, 0x00202c37, 0x00202e38, 0x001f2c37, 0x001e2c38, 0x0022323c, 0x0024333e, 0x001d2c37, 0x00192531, 0x00192430, 0x0019232d, 0x0018222c, 0x0017212a, 0x00152029, 0x00162029, 0x001a242d, 0x001c262f, 0x0019242d, 0x0018242c, 0x0018242c, 0x001b252f, 0x001c2630, 0x001a2631, 0x00192531, 0x001a2530, 0x0019232e, 0x0016202b, 0x00141e29, 0x00151f2a, 0x0015202b, 0x00141f29, 0x00101c27, 0x00111d27, 0x00121e28, 0x00111d27, 0x00101c26, 0x00101b25, 0x00121e28, 0x0016212c, 0x0018242f, 0x00182530, 0x0017232e, 0x0014202c, 0x00101e2a, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x00101c27, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00111c26, 0x00111c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00111c26, 0x00101c26, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101a24, 0x00101a24, 0x00101924, 0x00111923, 0x00111923, 0x00101922, 0x000f1921, 0x000f1821, 0x000e1820, 0x000e1820, 0x000e171e, 0x000e171e, 0x000e171e, 0x000e171e, 0x000e171e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1822, 0x000c1822, 0x000c1822, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1822, 0x000c1822, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c26, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00111e29, 0x00121e29, 0x00121e29, 0x00121e29, 0x00111e28, 0x00101f29, 0x0014222d, 0x001a2833, 0x001a2834, 0x00172430, 0x0017222d, 0x0017232c, 0x0017232c, 0x0018242d, 0x00192530, 0x001b2630, 0x00192530, 0x0018242e, 0x00192530, 0x001d2933, 0x001b2731, 0x0016222c, 0x0015212c, 0x001b2731, 0x001c2832, 0x001c2832, 0x001b2530, 0x001a242c, 0x001a252d, 0x001b252d, 0x001e2831, 0x00202b34, 0x00202b34, 0x00212c34, 0x00212c34, 0x00242e37, 0x00252f39, 0x0028323c, 0x002c353f, 0x002d3740, 0x002d343e, 0x002b323c, 0x002c323d, 0x002c333e, 0x002c343e, 0x002c353f, 0x002d3540, 0x002d3440, 0x002c333e, 0x002c333f, 0x00303742, 0x00323a45, 0x00333b46, 0x00303844, 0x002d3641, 0x002e3542, 0x002f3643, 0x002f3643, 0x00303641, 0x002f353f, 0x002e343e, 0x002d343c, 0x002c323c, 0x002a313c, 0x002a303c, 0x002b303c, 0x002c313d, 0x002c323e, 0x002e343f, 0x00313842, 0x00303740, 0x0030343f, 0x002e333c, 0x00303440, 0x00313541, 0x00313541, 0x00323642, 0x00333743, 0x00323843, 0x00313843, 0x00323844, 0x00323844, 0x00323844, 0x00313843, 0x00303642, 0x00303641, 0x00303641, 0x00303641, 0x00303541, 0x00303541, 0x00303541, 0x002f3541, 0x00303641, 0x00303643, 0x00323a47, 0x00343c49, 0x00343c49, 0x00323c49, 0x00323c49, 0x00343c49, 0x00363d4a, 0x00353d4a, 0x00363e4b, 0x00363e4b, 0x00373e4b, 0x00373e4b, 0x00363e4b, 0x00353e4b, 0x00353d4a, 0x00353d4a, 0x00363c4a, 0x00363c49, 0x00353c49, 0x00343b48, 0x00343a46, 0x00343b47, 0x00343b46, 0x00343a46, 0x00313843, 0x00303540, 0x002f3540, 0x00323844, 0x00343c47, 0x00343b46, 0x00313843, 0x00303641, 0x00303440, 0x00303541, 0x00303441, 0x0030343f, 0x002e333c, 0x002d313c, 0x002d313d, 0x002e323e, 0x002e333e, 0x002e333e, 0x002c303c, 0x002a2f3b, 0x00292e39, 0x002a2f38, 0x002a2f37, 0x002a2f37, 0x002a2f37, 0x002a2f37, 0x002b2f39, 0x00282d38, 0x00282c36, 0x00282c36, 0x00282d37, 0x00282c36, 0x00282c36, 0x00282c36, 0x00282d38, 0x002b303a, 0x002c303c, 0x002a303c, 0x002a303b, 0x002b313c, 0x002d343f, 0x002f3641, 0x00303641, 0x002c343e, 0x002c3440, 0x002f3542, 0x002f3442, 0x002c3441, 0x002b3441, 0x0028323e, 0x00293440, 0x00303948, 0x002f3845, 0x002d3542, 0x002a323f, 0x0029313e, 0x0028303c, 0x00262f39, 0x00252d38, 0x00242d38, 0x00252f39, 0x00252d38, 0x00232a34, 0x00222933, 0x00222831, 0x00212832, 0x001e2430, 0x00161e28, 0x00121c24, 0x00141f26, 0x00162028, 0x001c262f, 0x001f2a34, 0x00202d37, 0x00212f38, 0x00212f38, 0x001c2a35, 0x00202d39, 0x0024323e, 0x00202e39, 0x00182631, 0x00192530, 0x0019242f, 0x0018232d, 0x0018222c, 0x0016202b, 0x00152029, 0x00172029, 0x0018232c, 0x0018222b, 0x00162029, 0x00162028, 0x00172129, 0x0019242c, 0x0018232c, 0x0016222c, 0x0018242e, 0x001a242f, 0x0018222c, 0x00141f29, 0x00151f2a, 0x0014202a, 0x00131f28, 0x00101c25, 0x00101b24, 0x00101b25, 0x00101a24, 0x000e1924, 0x000e1924, 0x00111c27, 0x0014202b, 0x0017232d, 0x0016242e, 0x0014222c, 0x0013202c, 0x00101e2a, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x00101c27, 0x00101c28, 0x00101c27, 0x000e1c25, 0x000e1c25, 0x00101c25, 0x00101c26, 0x00101c26, 0x000f1c26, 0x000f1c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101b25, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101924, 0x00111924, 0x00111924, 0x00101923, 0x000f1921, 0x000f1821, 0x000e1820, 0x000e1820, 0x000d181e, 0x000d181e, 0x000d171e, 0x000e171e, 0x000e171e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1822, 0x000c1822, 0x000c1822, 0x000c1822, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1822, 0x000c1822, 0x000c1822, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000d1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c26, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101e29, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00121e29, 0x00121e29, 0x00121e2a, 0x00131f2a, 0x0013202c, 0x0014222e, 0x00172633, 0x001b2936, 0x001a2835, 0x00172431, 0x0017232e, 0x0017232c, 0x0017232c, 0x0017232c, 0x00192530, 0x001c2731, 0x001a2530, 0x0018242f, 0x00192530, 0x001c2832, 0x001a2630, 0x0017222c, 0x0018232d, 0x001c2831, 0x001c2832, 0x001b2731, 0x001a2630, 0x001c2730, 0x001f2932, 0x00222d35, 0x00242d36, 0x00222c34, 0x00202b34, 0x00212c34, 0x00222c35, 0x00242d36, 0x00242f38, 0x0028313c, 0x002c343e, 0x00303840, 0x002f353f, 0x002c323c, 0x002c323d, 0x002c333d, 0x002c343d, 0x002c343e, 0x002e3641, 0x002e3641, 0x002f3541, 0x002f3541, 0x00303742, 0x002f3641, 0x002e3440, 0x002d343f, 0x002c343f, 0x002c343f, 0x002c343f, 0x002a323d, 0x0029303b, 0x00282f38, 0x00282f37, 0x002b313a, 0x002b313b, 0x00282f39, 0x00282e39, 0x00282f3b, 0x00292f3a, 0x0029303a, 0x002b313b, 0x002d343d, 0x002d343d, 0x0030353f, 0x00323740, 0x00313641, 0x00313541, 0x00303440, 0x00313541, 0x00323642, 0x00323743, 0x00313843, 0x00333944, 0x00333944, 0x00333944, 0x00323844, 0x00303742, 0x00303541, 0x002d343f, 0x002d343f, 0x002f3440, 0x002f3541, 0x00303641, 0x00303742, 0x00303742, 0x00303743, 0x00333a47, 0x00343c49, 0x00343c48, 0x00333c48, 0x00343d4a, 0x00363e4b, 0x00373f4c, 0x00363d4a, 0x00363e4b, 0x00363e4b, 0x00373f4c, 0x0038404c, 0x0038404d, 0x0039414e, 0x0039414e, 0x0039414e, 0x0039404d, 0x003a404d, 0x00383f4c, 0x00373c4a, 0x00363c48, 0x00353c47, 0x00353c47, 0x00343b46, 0x00343a45, 0x00333944, 0x00323844, 0x00313843, 0x00313844, 0x00323844, 0x00313843, 0x002f3540, 0x002e333e, 0x002e333e, 0x002f3440, 0x002e333d, 0x002d313c, 0x002c303c, 0x002c303c, 0x002c303c, 0x002c303c, 0x002d313d, 0x002d313d, 0x002c303c, 0x002c303c, 0x002a2f38, 0x002a2f37, 0x002a2f37, 0x002a2f37, 0x002a2f37, 0x002c303a, 0x002b2f39, 0x002a2f39, 0x002b303a, 0x002b3039, 0x002a2f39, 0x002b3039, 0x002a3039, 0x002b303a, 0x002c313b, 0x002d323e, 0x002d343f, 0x002e343f, 0x002e3540, 0x002f3743, 0x00303844, 0x00303844, 0x002c3440, 0x002b333f, 0x002d3441, 0x002e3442, 0x002c3542, 0x002c3542, 0x0028323e, 0x0026303c, 0x002c3542, 0x002f3643, 0x002d3440, 0x002e3441, 0x002e3442, 0x002c3340, 0x0028303c, 0x0027303a, 0x00252f39, 0x00252e38, 0x00242c37, 0x00222934, 0x001e242e, 0x001e242e, 0x00202630, 0x001f2530, 0x001a212c, 0x00141c24, 0x00141d24, 0x00172029, 0x001a242c, 0x00242f39, 0x00223039, 0x0022313c, 0x0022313c, 0x001b2834, 0x001c2935, 0x00212f3b, 0x0023303c, 0x001a2832, 0x001a2630, 0x001c2832, 0x001b2730, 0x001a242f, 0x0018222c, 0x0016202a, 0x00141e27, 0x00131c25, 0x00141f28, 0x00162029, 0x00152028, 0x00162028, 0x0018222a, 0x0018232c, 0x0016212c, 0x0016212b, 0x0018222b, 0x0018232c, 0x0018212c, 0x0017212c, 0x0018222c, 0x00162029, 0x00131d25, 0x00101a23, 0x000f1923, 0x000e1823, 0x000e1822, 0x000e1823, 0x00111c26, 0x0014202a, 0x0015212c, 0x0015232d, 0x0014222c, 0x0013202b, 0x00101e2a, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x00101c28, 0x00101c28, 0x00101c27, 0x000e1c25, 0x000e1c25, 0x000f1c25, 0x00101c26, 0x00101c26, 0x000f1c26, 0x000f1c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101b25, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101924, 0x00111924, 0x00111924, 0x00101923, 0x000f1921, 0x000f1821, 0x000e1820, 0x000e1820, 0x000d181e, 0x000d181e, 0x000d171e, 0x000e171e, 0x000e171e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1822, 0x000c1822, 0x000c1822, 0x000c1824, 0x000c1724, 0x000c1724, 0x000c1724, 0x000c1724, 0x000c1723, 0x000c1821, 0x000c1821, 0x000c1822, 0x000c1822, 0x000c1823, 0x000b1823, 0x000b1823, 0x000d1924, 0x000d1924, 0x000d1a25, 0x000d1a25, 0x000d1b25, 0x000d1b25, 0x000d1b25, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c27, 0x000f1c27, 0x000f1c28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00111e2a, 0x00131f2b, 0x00131f2b, 0x0014202c, 0x00162330, 0x001a2836, 0x001e2d3c, 0x001f2e3c, 0x001c2b38, 0x001a2834, 0x00182530, 0x0017232e, 0x0017222d, 0x0017232c, 0x00182430, 0x001a2530, 0x0018242f, 0x0018242f, 0x00192530, 0x001c2731, 0x001b2430, 0x0018222c, 0x001a242f, 0x001c2730, 0x001b2630, 0x0019242e, 0x0019242d, 0x001d2830, 0x00202c34, 0x00243038, 0x00232e36, 0x00212c34, 0x00202c34, 0x00232c35, 0x00242e37, 0x00242e37, 0x00242d38, 0x0026303b, 0x002b343e, 0x002e3640, 0x002f3640, 0x002d343e, 0x002c333d, 0x002e333d, 0x002d323c, 0x002c313c, 0x002f3540, 0x00303640, 0x002f3640, 0x002d343e, 0x002c313c, 0x002a303b, 0x002a303b, 0x002c323c, 0x002c333e, 0x002c333e, 0x002c323d, 0x002b313c, 0x0029303b, 0x00282f39, 0x00293038, 0x002c313a, 0x002c323c, 0x002c313c, 0x002a2f3a, 0x00292e39, 0x00282e38, 0x00272d37, 0x00252c35, 0x00272c36, 0x00272c36, 0x00282d37, 0x002c303a, 0x002d313c, 0x002c303b, 0x002b303b, 0x002c323c, 0x002f343f, 0x00303540, 0x00303742, 0x00303843, 0x00303843, 0x00303844, 0x00303844, 0x00303742, 0x00303642, 0x002e3541, 0x002e3540, 0x002e3540, 0x002f3741, 0x00303842, 0x00323843, 0x00303742, 0x00313844, 0x00343b47, 0x00343c48, 0x00343b47, 0x00343c48, 0x00373f4b, 0x0038404c, 0x00383f4b, 0x00373e4a, 0x00373e4a, 0x00373e4a, 0x00383f4b, 0x00383f4c, 0x0038404c, 0x0039404d, 0x0039404d, 0x0039404d, 0x003b414d, 0x003c414e, 0x003b404c, 0x00383c49, 0x00353b47, 0x00353b47, 0x00363c48, 0x00363c47, 0x00353b47, 0x00343b47, 0x00343c47, 0x00343c47, 0x00343b46, 0x00333944, 0x00303742, 0x002d343f, 0x002c313c, 0x002c313d, 0x002d323d, 0x002e313c, 0x002d303b, 0x002c303b, 0x002c2f3c, 0x002c303c, 0x002d303c, 0x002d333d, 0x002d333d, 0x002c323c, 0x002c303c, 0x002b303a, 0x002a3039, 0x00293038, 0x00292f38, 0x002b3039, 0x002c323c, 0x002c323c, 0x002c323c, 0x002d333c, 0x0030353e, 0x00303540, 0x00323841, 0x00323842, 0x00323841, 0x00333842, 0x00323844, 0x00323844, 0x00323844, 0x00313844, 0x00333b48, 0x00333b48, 0x00333b48, 0x00313946, 0x002f3643, 0x002e3543, 0x002f3643, 0x002d3543, 0x002c3540, 0x002b3440, 0x0029323d, 0x002c3440, 0x002d3440, 0x002c333f, 0x002c3440, 0x002e3441, 0x002d3540, 0x002a333d, 0x0028313c, 0x0027303c, 0x00242e38, 0x00212b35, 0x00202934, 0x001e272f, 0x001c232b, 0x001c232c, 0x001d242c, 0x001c242c, 0x00182128, 0x00151e25, 0x00172028, 0x0019232c, 0x00212c38, 0x0022303b, 0x0024333e, 0x0022303c, 0x001b2834, 0x001b2834, 0x00202d38, 0x0024323d, 0x001b2833, 0x001a2630, 0x001c2830, 0x001c2830, 0x001a242e, 0x0018222c, 0x0017202a, 0x00141d26, 0x00111a24, 0x00141d26, 0x00151f28, 0x00172028, 0x00182029, 0x0018212a, 0x0019242e, 0x0018242f, 0x0016222c, 0x00131d26, 0x00121c25, 0x0016202a, 0x001b2430, 0x001c2630, 0x0018222c, 0x00141f28, 0x00121c24, 0x00101a23, 0x000f1824, 0x000e1822, 0x000f1824, 0x00111c26, 0x00131e28, 0x0014202b, 0x0014222c, 0x0014222c, 0x0013202b, 0x00101e29, 0x00101d28, 0x000f1c28, 0x000e1c27, 0x000f1b27, 0x00101b27, 0x00101b27, 0x000e1c25, 0x000e1c25, 0x000e1b24, 0x000f1a24, 0x000f1a24, 0x000f1c25, 0x000f1c25, 0x00101c25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000f1b25, 0x000f1a24, 0x000f1a24, 0x000f1a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101924, 0x00101924, 0x000f1922, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000e1820, 0x000e181f, 0x000d171e, 0x000d161d, 0x000d161d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1822, 0x000c1822, 0x000c1823, 0x000c1825, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1724, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1821, 0x000b1822, 0x000b1822, 0x000d1924, 0x000d1924, 0x000e1a26, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x00101d28, 0x00101d28, 0x000f1c26, 0x000f1c26, 0x000f1c27, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00111f2b, 0x0013202c, 0x0013202c, 0x00142230, 0x00182735, 0x0020303e, 0x00243443, 0x00253544, 0x00243240, 0x001f2d3a, 0x001c2834, 0x00192531, 0x0018242f, 0x0017232d, 0x0018242d, 0x0018242e, 0x0018242d, 0x0018242f, 0x001b2530, 0x001b2530, 0x001a242f, 0x001a242f, 0x001b2530, 0x001c262e, 0x001b252c, 0x0019242b, 0x0019242a, 0x001c262e, 0x001c2830, 0x001b2830, 0x001b262e, 0x001c272f, 0x001f2b33, 0x00232d36, 0x00242e37, 0x00242e37, 0x00252f38, 0x0028323c, 0x002b3540, 0x002e3742, 0x00303743, 0x002e3440, 0x002d333e, 0x002e343f, 0x002e333d, 0x002d323c, 0x002f343e, 0x0030353f, 0x002c343d, 0x00282e38, 0x00262c36, 0x00282f38, 0x00293039, 0x00293039, 0x002b313c, 0x002c333e, 0x002c333e, 0x002c333e, 0x002b313c, 0x002a303c, 0x00292f39, 0x002a2e38, 0x002b2f39, 0x002b303a, 0x002b2f39, 0x002b2f39, 0x00292e38, 0x00272d37, 0x00272c36, 0x00282d37, 0x00282d38, 0x00282d37, 0x00292e38, 0x00292e38, 0x00282d37, 0x00272d37, 0x00282e38, 0x00282f38, 0x0029303a, 0x0029313c, 0x002b333d, 0x002c343f, 0x002c3440, 0x002d3540, 0x002d3540, 0x002d3541, 0x002d3540, 0x002c343f, 0x002a323d, 0x002b333d, 0x002c343e, 0x002c323c, 0x002a303a, 0x002a303b, 0x002c333e, 0x002d343f, 0x002e3440, 0x002f3540, 0x00313743, 0x00313743, 0x00313743, 0x00313843, 0x00323844, 0x00333844, 0x00323844, 0x00323845, 0x00333946, 0x00343a47, 0x00343b48, 0x00343b48, 0x00363c48, 0x00363c48, 0x00353945, 0x00303540, 0x00303440, 0x00313642, 0x00323742, 0x00343944, 0x00353b47, 0x00343c47, 0x00333c46, 0x00333b46, 0x00343a46, 0x00323844, 0x00303641, 0x002e343f, 0x002c333e, 0x002e343f, 0x002d343f, 0x002d313d, 0x002b303a, 0x002a2f39, 0x002a2f39, 0x002c303a, 0x002c313c, 0x002d343d, 0x002e343d, 0x002e343d, 0x002c333c, 0x002c323c, 0x002b313c, 0x002a303b, 0x002a303a, 0x002c333c, 0x00303640, 0x00303740, 0x00303740, 0x0030363f, 0x002f353e, 0x002c333c, 0x002d353e, 0x002e3740, 0x002f3740, 0x002e363f, 0x002c343f, 0x002d343f, 0x00303742, 0x00303844, 0x00323a48, 0x00323a48, 0x00303a47, 0x00303945, 0x002e3844, 0x002e3643, 0x002f3743, 0x002e3642, 0x002b333e, 0x0028303c, 0x0029313c, 0x0029313c, 0x002a323c, 0x002a323d, 0x002c343e, 0x002c3440, 0x002d3540, 0x002c343f, 0x002a343e, 0x002a343f, 0x0028313c, 0x00212b36, 0x00202b34, 0x00202a32, 0x001b242b, 0x00192028, 0x001b2129, 0x001d252c, 0x001d262d, 0x001a2229, 0x00152028, 0x0019232d, 0x001e2b35, 0x0022303b, 0x0026353f, 0x00202d38, 0x00192732, 0x00192732, 0x001f2d38, 0x0024343f, 0x001d2c37, 0x001a2730, 0x001a272d, 0x001a262c, 0x0019242a, 0x00182329, 0x00182128, 0x00151e25, 0x00131b23, 0x00131c24, 0x00151d27, 0x00182029, 0x0018212a, 0x0018212a, 0x0018222c, 0x0017232d, 0x0017232d, 0x00142029, 0x00101c24, 0x00131f27, 0x001a252e, 0x001d2831, 0x001c262f, 0x0018222b, 0x00141e27, 0x00101b24, 0x000f1923, 0x000f1824, 0x00101a24, 0x00121c26, 0x00121e28, 0x0014202a, 0x0014212b, 0x0014222c, 0x0012202b, 0x00101e29, 0x00101d28, 0x000f1c28, 0x000e1c27, 0x000f1b27, 0x00101b27, 0x000f1b26, 0x000d1b24, 0x000d1b24, 0x000d1a24, 0x000d1924, 0x000e1a24, 0x000f1b25, 0x00101b25, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101b24, 0x00101b24, 0x00101a23, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000d171f, 0x000d161d, 0x000d161d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1822, 0x000c1822, 0x000c1823, 0x000c1825, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1724, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1821, 0x000b1822, 0x000b1822, 0x000d1924, 0x000d1924, 0x000e1a26, 0x000e1c27, 0x000e1c27, 0x000d1b26, 0x000d1b26, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c26, 0x000f1c26, 0x000f1c27, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00111f2b, 0x0013202c, 0x0013202c, 0x00142230, 0x001b2838, 0x00213240, 0x00263846, 0x00283948, 0x00253544, 0x0021303c, 0x001f2c38, 0x001c2935, 0x001b2732, 0x00192530, 0x0017232c, 0x0017232c, 0x0018242d, 0x0018242f, 0x001b2530, 0x001b2530, 0x001a242f, 0x001a242f, 0x001b252f, 0x001b252d, 0x001b252c, 0x0019242a, 0x0019242a, 0x001b252c, 0x0018242b, 0x0017232a, 0x0018232b, 0x001b252d, 0x00202a33, 0x00232d37, 0x00242e37, 0x0028313a, 0x002a343d, 0x002c3540, 0x002c3741, 0x002e3842, 0x002f3641, 0x002d343f, 0x002d333e, 0x002e343f, 0x002e343d, 0x002d333c, 0x002e343d, 0x002d343d, 0x002b313b, 0x00262c36, 0x00252c35, 0x00282e38, 0x002a303a, 0x002a303a, 0x002a303c, 0x002b313c, 0x002c323d, 0x002d333f, 0x002c323e, 0x002c323d, 0x00282f38, 0x00282d37, 0x00282c36, 0x00282d37, 0x00292e38, 0x00292e38, 0x002a2f38, 0x00293039, 0x002a303a, 0x002c303a, 0x002b303a, 0x002b2f39, 0x002c2f39, 0x002b2f39, 0x002a2f39, 0x00293039, 0x00293039, 0x00293039, 0x00282f39, 0x0029303c, 0x002c323d, 0x002c333e, 0x002b333d, 0x002b333d, 0x002b333d, 0x002a323d, 0x002b333d, 0x002b333d, 0x002a323d, 0x002a333c, 0x002b333c, 0x002b313c, 0x002a303a, 0x002a303a, 0x002c323d, 0x002c333e, 0x002d333e, 0x002e343f, 0x002d343f, 0x002d333e, 0x002c323e, 0x002c323d, 0x002c323e, 0x002d333f, 0x002d333f, 0x002d3441, 0x002f3442, 0x00303543, 0x00303644, 0x00303643, 0x00303641, 0x00303540, 0x00303440, 0x00303440, 0x00303440, 0x00323642, 0x00323741, 0x00323742, 0x00333844, 0x00323844, 0x002f3842, 0x002e3641, 0x00303742, 0x00323844, 0x00323844, 0x00313843, 0x00313843, 0x00303742, 0x00303641, 0x002f3440, 0x002c303b, 0x002b303a, 0x002c303a, 0x002d313c, 0x002d333c, 0x002e343d, 0x002e343e, 0x002e343e, 0x002e343e, 0x002d343d, 0x002d343d, 0x002e343e, 0x002e343e, 0x002e343e, 0x002e343e, 0x002d343d, 0x002d343d, 0x002c333c, 0x002c323b, 0x00282f38, 0x00262e38, 0x00262e38, 0x00242c35, 0x00232c34, 0x00252c37, 0x00272c38, 0x00272d38, 0x00282e3a, 0x002b3240, 0x002c3442, 0x002b3441, 0x002c3542, 0x002d3743, 0x002f3744, 0x002f3743, 0x002e3641, 0x002a333d, 0x002a323c, 0x0029313c, 0x0029313c, 0x0028303c, 0x0029313c, 0x002c343e, 0x002d3540, 0x002d3540, 0x002c343f, 0x002c3540, 0x002c3640, 0x002a343f, 0x00242f39, 0x00212c35, 0x00202a33, 0x001c252d, 0x001a202a, 0x00192028, 0x001c232c, 0x001c252c, 0x001d262d, 0x0019232b, 0x0019242d, 0x001c2833, 0x0023313b, 0x00283740, 0x001e2b34, 0x00192531, 0x00182631, 0x00202f3a, 0x0023323d, 0x001e2c38, 0x001b2830, 0x0019262c, 0x0019262c, 0x0019242a, 0x00182329, 0x00182329, 0x00192128, 0x00161f26, 0x00141c24, 0x00141d26, 0x00182029, 0x0018212a, 0x0018212b, 0x0018222c, 0x0018232d, 0x0018242f, 0x0019252e, 0x0018242c, 0x00152129, 0x0017232b, 0x0018232c, 0x0019242d, 0x0019232c, 0x00172029, 0x00121c25, 0x00101923, 0x000f1924, 0x00121c26, 0x00141e28, 0x00131f29, 0x0013202a, 0x0014212b, 0x0014222c, 0x0013202b, 0x00101e2a, 0x00101e29, 0x00101d28, 0x000f1c28, 0x000f1b27, 0x000f1a26, 0x000e1a26, 0x000d1b24, 0x000d1b24, 0x000d1a24, 0x000d1924, 0x000e1924, 0x000e1a24, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101a24, 0x00101b24, 0x00101b24, 0x00101a23, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000d171f, 0x000d161d, 0x000d161d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1822, 0x000c1822, 0x000c1823, 0x000c1825, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1724, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1821, 0x000b1822, 0x000b1822, 0x000d1924, 0x000d1924, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00111f2b, 0x00111f2b, 0x00121f2c, 0x0014212f, 0x001b2837, 0x0020303f, 0x00243644, 0x00243845, 0x00243644, 0x0022313e, 0x001e2c39, 0x001d2b38, 0x001c2a36, 0x001b2732, 0x0016222c, 0x0016212c, 0x0018242d, 0x00192530, 0x001c2632, 0x001c2630, 0x001b242f, 0x0019232d, 0x001a242e, 0x001a242c, 0x0019242a, 0x0019242a, 0x001a242b, 0x0019242a, 0x00172229, 0x00162228, 0x0017232a, 0x001a242c, 0x001f2831, 0x00222c37, 0x00253039, 0x0028333c, 0x002a343e, 0x002b3540, 0x002b3540, 0x002c3540, 0x002c3440, 0x002c343e, 0x002c323e, 0x002d343f, 0x002d343d, 0x002c333c, 0x002d343c, 0x002d343c, 0x002a313b, 0x00272d37, 0x00262c36, 0x00282e38, 0x002b313b, 0x002b313b, 0x002a303b, 0x002a303b, 0x002c323c, 0x002c333c, 0x002c323c, 0x002b313b, 0x00282e38, 0x00262c36, 0x00252c35, 0x00262c36, 0x00283039, 0x002a303a, 0x002a303a, 0x0029303a, 0x002a303a, 0x002c303a, 0x002b2f3a, 0x002b2e39, 0x002c2f39, 0x002c303a, 0x002c303b, 0x002c313c, 0x002b313b, 0x00293039, 0x00282e39, 0x002a2f3b, 0x002c313d, 0x002c313d, 0x002c313c, 0x002b313c, 0x0029303c, 0x0028303c, 0x002b323d, 0x002c343f, 0x002d3440, 0x002c343e, 0x002c333c, 0x002c313b, 0x002b303a, 0x002c303a, 0x002c303c, 0x002d323e, 0x002e333e, 0x002e343f, 0x002d333e, 0x002d343f, 0x002d333e, 0x002c333e, 0x002d333e, 0x002e343f, 0x002d333e, 0x002d343f, 0x002f3540, 0x00303542, 0x00303643, 0x00303643, 0x00303742, 0x00303541, 0x00313541, 0x00303440, 0x002e333e, 0x002c303c, 0x002c303c, 0x002c303c, 0x002c323d, 0x002c323d, 0x002b313c, 0x002a313d, 0x002d343f, 0x00313843, 0x00323844, 0x00323844, 0x00313843, 0x00313843, 0x00313843, 0x00323742, 0x002f343e, 0x002d323c, 0x002f333c, 0x0030343e, 0x0030343e, 0x002e343d, 0x002c313b, 0x00292f38, 0x00293038, 0x00293039, 0x00283038, 0x00282f38, 0x00262c36, 0x00242b34, 0x00232933, 0x00222832, 0x00232932, 0x00232933, 0x00252c34, 0x00252c35, 0x00242c35, 0x00232c35, 0x00222b34, 0x00242d36, 0x00282e3a, 0x00292e39, 0x00292f3a, 0x00282e3a, 0x00282f3d, 0x00272f3d, 0x0028303d, 0x0028323e, 0x002c3441, 0x002e3744, 0x002e3643, 0x002d3540, 0x002c343f, 0x002b333d, 0x002a323d, 0x0028303c, 0x0028303b, 0x0028303b, 0x002b333d, 0x002d3540, 0x002d3540, 0x002c343f, 0x002b3540, 0x002b3540, 0x002c3540, 0x002b3440, 0x0028313c, 0x00252f39, 0x00202834, 0x001c242f, 0x0019212c, 0x0018202b, 0x00172129, 0x001b242c, 0x001c262f, 0x001a242f, 0x001c2831, 0x0023303a, 0x002c3a44, 0x001d2a34, 0x00182530, 0x001a2834, 0x0023323d, 0x0021303c, 0x001f2c38, 0x001b2830, 0x0018252c, 0x0018242b, 0x0019242a, 0x00182228, 0x00182128, 0x0019222a, 0x00182129, 0x00182028, 0x00182029, 0x0018212c, 0x001a222d, 0x001b242e, 0x001c2530, 0x001c2630, 0x001c2630, 0x001b262f, 0x001a252e, 0x0018232c, 0x00152129, 0x00141f28, 0x00151f27, 0x00161e27, 0x00151d27, 0x00141c25, 0x00111924, 0x00101a24, 0x00131c28, 0x00151f2a, 0x0014202a, 0x0014202a, 0x0014202b, 0x0014212b, 0x0014202c, 0x0013202c, 0x0012202c, 0x0012202c, 0x00111f2a, 0x000f1c27, 0x000d1925, 0x000d1925, 0x000d1b24, 0x000d1b24, 0x000d1a24, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x00101a24, 0x00101a24, 0x00101b24, 0x00101b24, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101a23, 0x000f1922, 0x000f1921, 0x000e1820, 0x000e1820, 0x000e1820, 0x000e1820, 0x000e1720, 0x000e1720, 0x000e1720, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1822, 0x000c1822, 0x000c1823, 0x000c1825, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1724, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1822, 0x000b1822, 0x000b1822, 0x000d1924, 0x000d1924, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00111f2b, 0x00111f2b, 0x00121f2c, 0x0014202e, 0x00182634, 0x001c2c3b, 0x001e303f, 0x00203441, 0x00243544, 0x00253442, 0x0023313f, 0x0022303d, 0x001f2c39, 0x001c2833, 0x0017222c, 0x0016212c, 0x0018242d, 0x001a2530, 0x001c2732, 0x001d2732, 0x001b2530, 0x0019232d, 0x001a242e, 0x001a242c, 0x0019242a, 0x001a242b, 0x001a242b, 0x001a242c, 0x0018242d, 0x0017232b, 0x0018242c, 0x001b252f, 0x001f2934, 0x00222c37, 0x0026303a, 0x0028323c, 0x0029343d, 0x002b343f, 0x002b343f, 0x002c3540, 0x002d3540, 0x002c343f, 0x002a313c, 0x002c323d, 0x002c323c, 0x002a303a, 0x002b313b, 0x002c323c, 0x0029313b, 0x00293039, 0x00293039, 0x002a303a, 0x002c323c, 0x002c333c, 0x002d343d, 0x002d343d, 0x002e343e, 0x002f353f, 0x002f353f, 0x002c333c, 0x002b313b, 0x002b313a, 0x002c323b, 0x002b313b, 0x002a303a, 0x002a303a, 0x002a303a, 0x00293039, 0x0029303a, 0x002c303a, 0x002b2f3a, 0x002b2e39, 0x002c2f39, 0x002c2f39, 0x002c303a, 0x002c323c, 0x002b313b, 0x00293039, 0x00282f39, 0x002b303b, 0x002c313c, 0x002d323d, 0x002d323d, 0x002c313d, 0x002a303c, 0x002a303c, 0x002c323e, 0x002e3440, 0x002f3440, 0x002d343e, 0x002c323c, 0x002c313c, 0x002c303a, 0x002b2f39, 0x002c303c, 0x002d313d, 0x002e333e, 0x002e333e, 0x002c333e, 0x002d343f, 0x002e343f, 0x002e3440, 0x002e343f, 0x002d333e, 0x002c333e, 0x002c323e, 0x002e3440, 0x002f3542, 0x002f3543, 0x00303542, 0x00303641, 0x00303541, 0x00313541, 0x00303540, 0x002e333f, 0x002c303c, 0x002c303c, 0x002c303c, 0x002c303c, 0x002b313c, 0x002b313c, 0x002c323d, 0x002d343f, 0x00303541, 0x00303641, 0x002d343f, 0x002c323d, 0x002c323d, 0x002c323d, 0x002c313d, 0x002c303b, 0x00292d38, 0x00282c36, 0x00282a34, 0x00262933, 0x00242933, 0x00242933, 0x00242832, 0x00232831, 0x00232831, 0x00202730, 0x00202730, 0x00212831, 0x00212831, 0x00202730, 0x00202630, 0x001f252f, 0x001f252f, 0x00202830, 0x00222832, 0x00202832, 0x00202932, 0x00212933, 0x00252d37, 0x00292f3b, 0x002a2f3b, 0x002b303c, 0x00292f3c, 0x00282f3c, 0x00282e3c, 0x0028303c, 0x0029313c, 0x002a333e, 0x002c3440, 0x002d3540, 0x002d3540, 0x002c343f, 0x002c343e, 0x002b323d, 0x0029303c, 0x00282f3a, 0x0028303b, 0x002a323d, 0x002d3440, 0x002c343f, 0x002a333d, 0x002a343e, 0x002b3540, 0x002c3542, 0x002c3643, 0x002b3641, 0x002a343f, 0x0027303b, 0x00222a35, 0x001d2631, 0x001c242f, 0x0018222c, 0x0018232c, 0x001d2830, 0x001e2832, 0x001c2832, 0x0024313b, 0x002d3c45, 0x001e2b35, 0x00162430, 0x001b2934, 0x0024333f, 0x0024313c, 0x0023303c, 0x001e2b34, 0x0018242c, 0x0018242b, 0x001a242b, 0x00182228, 0x00172028, 0x0018212a, 0x0018202a, 0x0019222b, 0x001b232d, 0x001c2430, 0x001c2430, 0x001c2430, 0x001c2630, 0x001c2630, 0x001c2630, 0x001c262f, 0x001b252e, 0x0018212a, 0x00142028, 0x00141e26, 0x00141c25, 0x00111923, 0x00101821, 0x00101821, 0x00101822, 0x00101824, 0x00121a25, 0x00141c27, 0x00141e28, 0x00141f29, 0x0014202a, 0x0014212b, 0x0014212c, 0x0014212c, 0x0014212c, 0x0014212c, 0x0013202c, 0x00101c28, 0x000d1925, 0x000d1924, 0x000d1b24, 0x000d1b24, 0x000d1a24, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x00101a24, 0x00101a24, 0x00101b24, 0x00101b24, 0x00101a23, 0x00101a23, 0x00101a23, 0x00101a23, 0x000f1922, 0x000f1821, 0x000e1820, 0x000e1820, 0x000e1820, 0x000e1820, 0x000e1720, 0x000e1720, 0x000e1720, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1825, 0x000c1825, 0x000c1826, 0x000c1826, 0x000c1826, 0x000c1824, 0x000c1823, 0x000c1823, 0x000c1824, 0x000c1824, 0x000b1824, 0x000b1824, 0x000b1824, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000d1b26, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e2a, 0x00101e2a, 0x00121f2b, 0x0014202c, 0x00142430, 0x00172835, 0x00182b38, 0x001c2e3c, 0x00213240, 0x00243442, 0x00243440, 0x0023313f, 0x001f2c38, 0x001b2832, 0x0018222c, 0x0018202c, 0x0019232d, 0x001b2430, 0x001c2531, 0x001d2731, 0x001b2530, 0x001a242f, 0x001a242e, 0x0019242c, 0x0018232b, 0x001a242b, 0x001a242b, 0x001a242c, 0x0019242e, 0x0019242c, 0x001a242d, 0x001c2530, 0x00202a34, 0x00242e38, 0x0028323b, 0x0029333c, 0x0029333c, 0x002b343f, 0x002c3540, 0x002d3540, 0x002d3540, 0x002c343e, 0x002a303c, 0x002b313c, 0x002a313b, 0x00283039, 0x0029303a, 0x002c333c, 0x002a333c, 0x002b323c, 0x002b323c, 0x002c333d, 0x002f343f, 0x002f3540, 0x002f353f, 0x002e343e, 0x002e343e, 0x002f353f, 0x00303640, 0x002f3540, 0x002f353f, 0x002f353f, 0x00303640, 0x002f353e, 0x002b313b, 0x0029303a, 0x002b313b, 0x002c323c, 0x002c323c, 0x002d323c, 0x002d313c, 0x002d303b, 0x002d303b, 0x002c303a, 0x002c303b, 0x002c323c, 0x002c323d, 0x002b313c, 0x002c313c, 0x002d313c, 0x002d323c, 0x002e333d, 0x002f343e, 0x002d343d, 0x002c333e, 0x002c333e, 0x002d333f, 0x002e3440, 0x002e3440, 0x002d333e, 0x002c323d, 0x002c303d, 0x002c303c, 0x002c303c, 0x002c303c, 0x002c303c, 0x002d323d, 0x002d323d, 0x002d323d, 0x002d333e, 0x002e343f, 0x002f3440, 0x002f3440, 0x002e343f, 0x002d343f, 0x002e343e, 0x002f343f, 0x00303540, 0x00303540, 0x00303541, 0x00303641, 0x00303541, 0x00313541, 0x00313541, 0x00303440, 0x002d323d, 0x002c303c, 0x002b303c, 0x002c303c, 0x002c313c, 0x002c323d, 0x002c333e, 0x002e3440, 0x002f3440, 0x002f3440, 0x002e3440, 0x002b313c, 0x00282e39, 0x00272d38, 0x00282d38, 0x00282d37, 0x00282c37, 0x00282c36, 0x00272b35, 0x00262a34, 0x00252a34, 0x00262a34, 0x00242934, 0x00242833, 0x00252934, 0x00252934, 0x00252a34, 0x00252b35, 0x00252c35, 0x00252c35, 0x00242b34, 0x00242a34, 0x00242a33, 0x00232933, 0x00222832, 0x00212832, 0x00232a34, 0x00242c36, 0x00252c37, 0x00282d38, 0x00282e39, 0x00282d39, 0x00272d39, 0x00272d39, 0x00282d3a, 0x00262e38, 0x00262e38, 0x00272f38, 0x0028303b, 0x0029323c, 0x002a323d, 0x002a323d, 0x002c343f, 0x002c343e, 0x002a313c, 0x00282f3a, 0x00282f3b, 0x002a313c, 0x002c343f, 0x002d343f, 0x002a343e, 0x0028313c, 0x0029343f, 0x002b3641, 0x002c3643, 0x002b3743, 0x00293641, 0x002c3743, 0x0028323f, 0x00222c38, 0x001d2833, 0x0019242e, 0x0018222c, 0x001c272f, 0x00212c35, 0x00202c37, 0x0024333d, 0x00293842, 0x001c2a35, 0x00162431, 0x001a2935, 0x0020303b, 0x001f2f39, 0x0020303a, 0x001f2c35, 0x0019262d, 0x0019242c, 0x001a242c, 0x0019242b, 0x0019242c, 0x001a232c, 0x0018222b, 0x0018232c, 0x0019242e, 0x001b2530, 0x001c2530, 0x001c2530, 0x001c2630, 0x001c2731, 0x001c2731, 0x001c2630, 0x001b252d, 0x0018212a, 0x00152028, 0x00141f27, 0x00141d27, 0x00131c25, 0x00121a24, 0x00121a24, 0x00111924, 0x00101823, 0x00101823, 0x00111a25, 0x00141d28, 0x0015202a, 0x0015212c, 0x0015212c, 0x0014212c, 0x0014212c, 0x0014212c, 0x0014222c, 0x0014212b, 0x00101d28, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1824, 0x000f1824, 0x000f1824, 0x000d1824, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000f1a24, 0x000f1a24, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x000f1a24, 0x000f1a24, 0x00101a24, 0x00101a24, 0x00101a23, 0x00101a23, 0x00101922, 0x000f1921, 0x000f1821, 0x000f1821, 0x000e1820, 0x000d1820, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d1720, 0x000d161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000c1924, 0x000b1925, 0x000b1a25, 0x000b1a27, 0x000b1927, 0x000b1926, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000b1824, 0x000b1824, 0x000c1925, 0x000d1a26, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101d28, 0x00101d28, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00111f2a, 0x0012202c, 0x0012222d, 0x00142430, 0x00142734, 0x00182b38, 0x001f303e, 0x00203240, 0x0021323f, 0x0021313e, 0x001c2c38, 0x00182631, 0x0018212c, 0x0018202b, 0x0018212c, 0x001a222c, 0x001c242e, 0x001c2630, 0x001b2631, 0x001a2630, 0x0019242f, 0x0018232c, 0x0018222b, 0x001a242b, 0x001a242b, 0x001a242c, 0x0019232c, 0x0019242c, 0x001a242e, 0x001b2530, 0x001f2934, 0x00242f38, 0x0028333c, 0x002b343f, 0x002b3540, 0x002c3540, 0x002d3640, 0x002d3640, 0x002d353e, 0x002c333c, 0x002a303a, 0x002b313b, 0x0029303c, 0x0028303a, 0x0029323b, 0x002c343d, 0x002c343f, 0x002c343f, 0x002c343f, 0x002e3540, 0x00303741, 0x00303640, 0x002d343d, 0x002b313b, 0x002a303a, 0x002b313b, 0x002c323c, 0x002c333c, 0x002c333c, 0x002c333c, 0x002c333c, 0x002c323c, 0x002a303b, 0x0029303a, 0x002c323c, 0x00303640, 0x002f353f, 0x002f353f, 0x002f343e, 0x0030333d, 0x002e313c, 0x002c303c, 0x002c313c, 0x002c333e, 0x002c333e, 0x002c323d, 0x002c323c, 0x002d323c, 0x002d323c, 0x002d323c, 0x002f343d, 0x002f343e, 0x002e343f, 0x002c333e, 0x002d333f, 0x002e343f, 0x002e343f, 0x002d333f, 0x002c313e, 0x002c303e, 0x002c303e, 0x002c303e, 0x002c303d, 0x002c303c, 0x002c303c, 0x002c303b, 0x002c313b, 0x002d323d, 0x002e333f, 0x002e343f, 0x002e343f, 0x002f343f, 0x002f343f, 0x002f343c, 0x002f343c, 0x0030343c, 0x0030353d, 0x00303540, 0x00303641, 0x00303541, 0x00313541, 0x00313541, 0x00303440, 0x002d343d, 0x002c323c, 0x002c323d, 0x002c323e, 0x002c323d, 0x002c323d, 0x002c323e, 0x002e3440, 0x002f3440, 0x002f3440, 0x002e3440, 0x002c323e, 0x002c323d, 0x002b313c, 0x002b313c, 0x002b313c, 0x002c303a, 0x00292e38, 0x00282c36, 0x00282c36, 0x00282c36, 0x00282c37, 0x00282c36, 0x00282c36, 0x00272c35, 0x00272b35, 0x00272b35, 0x00272c35, 0x00262c36, 0x00262c36, 0x00282d37, 0x00282e38, 0x00282f38, 0x00272d38, 0x00242b36, 0x00242a35, 0x00262c38, 0x00282d39, 0x00282d39, 0x00282c38, 0x00272c38, 0x00242b36, 0x00242935, 0x00232934, 0x00222934, 0x00232b34, 0x00232b34, 0x00232c34, 0x00242c36, 0x00242d38, 0x00252e38, 0x00272f3a, 0x002c343f, 0x002c343f, 0x002a323c, 0x0028303b, 0x00272f3a, 0x0029313c, 0x002c343f, 0x002c3440, 0x002b343f, 0x0028313c, 0x0028333d, 0x002a3640, 0x002c3744, 0x002c3844, 0x00283641, 0x002b3844, 0x002c3745, 0x0027313e, 0x00202b36, 0x001b2730, 0x0018242d, 0x001a262c, 0x00222d35, 0x00233039, 0x0027343d, 0x0027343e, 0x001a2833, 0x00162530, 0x0020303b, 0x001d2e38, 0x001c2c36, 0x001d2d37, 0x00202e37, 0x001c2830, 0x0018242c, 0x0018222b, 0x0019242c, 0x001b252e, 0x001b272f, 0x001b262e, 0x0018242c, 0x0018242e, 0x001a2530, 0x001b2530, 0x001a2530, 0x001a2530, 0x001c2832, 0x001d2832, 0x001c2730, 0x001a2530, 0x0018232c, 0x0016212b, 0x0017212b, 0x0018222c, 0x0018212c, 0x0017212c, 0x0015202a, 0x00141d28, 0x00131c28, 0x00121c26, 0x00111c26, 0x00141f29, 0x0017212c, 0x0017232c, 0x0017232c, 0x0015232e, 0x0014222d, 0x0014222d, 0x0014232c, 0x0014242d, 0x0012202a, 0x000f1c24, 0x000c1a23, 0x000c1823, 0x000c1822, 0x000e1823, 0x000f1824, 0x000f1824, 0x000e1824, 0x000d1924, 0x000c1823, 0x000c1822, 0x000c1823, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000f1a24, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000f1922, 0x000f1921, 0x000e1821, 0x000e1820, 0x000e1820, 0x000d1720, 0x000d1720, 0x000c1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00111f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000c1924, 0x000b1a25, 0x000b1a25, 0x000b1a27, 0x000b1a27, 0x000b1926, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1924, 0x000b1824, 0x000c1925, 0x000d1a26, 0x000d1b26, 0x000e1b27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101e29, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101f2a, 0x0010202b, 0x0010212c, 0x00122430, 0x00162834, 0x001b2c3b, 0x001d303c, 0x001d303d, 0x001e303c, 0x001b2c37, 0x00172530, 0x0017202a, 0x00171f28, 0x00182029, 0x0018212a, 0x001a222c, 0x001b252f, 0x001b2731, 0x001c2731, 0x0019252f, 0x0018232c, 0x0018222b, 0x0019242b, 0x001a242b, 0x0019242b, 0x0019232b, 0x001a242d, 0x001c2630, 0x001e2833, 0x00202b37, 0x0025303b, 0x002a343e, 0x002d3741, 0x002d3842, 0x002d3842, 0x002e3641, 0x002d363e, 0x002d353c, 0x002d343c, 0x002c323a, 0x002a313b, 0x0029303c, 0x0028303b, 0x002b333c, 0x002c353f, 0x002c3440, 0x002c3440, 0x002c343f, 0x002d3440, 0x002e343f, 0x002c323c, 0x00282f38, 0x00252c36, 0x00242a34, 0x00242a34, 0x00242b34, 0x00252c36, 0x00252c36, 0x00252c36, 0x00252c36, 0x00252c36, 0x00262c36, 0x00272d37, 0x00293039, 0x002c333c, 0x002e343d, 0x002f3440, 0x00303540, 0x00303540, 0x00303440, 0x002e343f, 0x002d333f, 0x002d3440, 0x002d343f, 0x002c333e, 0x002d333e, 0x002d323d, 0x002e333d, 0x002f343f, 0x00303440, 0x0030343f, 0x002f3440, 0x002c333e, 0x002d333f, 0x002e343f, 0x002e343f, 0x002e333f, 0x002d313e, 0x002d313f, 0x002d313f, 0x002e3240, 0x002e323e, 0x002c303c, 0x002c303b, 0x002c303a, 0x002c303a, 0x002c303c, 0x002d323e, 0x002d333e, 0x002f343f, 0x002f343f, 0x002f343f, 0x002f343c, 0x002f343c, 0x0030343c, 0x0030353d, 0x00303540, 0x00303641, 0x00303541, 0x00313541, 0x00313541, 0x00313541, 0x002f353f, 0x002e343e, 0x002d343f, 0x002d343f, 0x002d343f, 0x002c333e, 0x002c323d, 0x002e343f, 0x002e3440, 0x002e343f, 0x002d333f, 0x002c323e, 0x002c333e, 0x002e343f, 0x002e343f, 0x002c333d, 0x002c313c, 0x002a2e39, 0x00282d38, 0x00292e38, 0x002a2f38, 0x002a2f39, 0x00292e38, 0x00282d37, 0x00282c36, 0x00272c35, 0x00272c35, 0x00272c36, 0x00262c36, 0x00272d37, 0x00282e38, 0x002a2f39, 0x002b303a, 0x00292e38, 0x00262c38, 0x00262c38, 0x00272d38, 0x00282e39, 0x00282e3a, 0x00282d3a, 0x00262d38, 0x00252c37, 0x00242a35, 0x00252c36, 0x00242c35, 0x00242c35, 0x00242c34, 0x00232c35, 0x00232b36, 0x00232b36, 0x00242c37, 0x00262f39, 0x002b333e, 0x002c343f, 0x002b333d, 0x0028303b, 0x0028303b, 0x0029313c, 0x002b333e, 0x002c343f, 0x002c3540, 0x002b3540, 0x002b3540, 0x002c3742, 0x002e3844, 0x002f3945, 0x002c3844, 0x00293643, 0x00293644, 0x00283441, 0x0024303b, 0x001e2a34, 0x001c2830, 0x001b262d, 0x00212c34, 0x00243039, 0x0028343d, 0x0024303a, 0x00192630, 0x00182832, 0x001d2f3a, 0x001b2d37, 0x001a2c34, 0x001b2c34, 0x001d2c34, 0x001a272f, 0x0017232b, 0x0017212a, 0x00152029, 0x0016212a, 0x0018242d, 0x001a262f, 0x001a262f, 0x001a2630, 0x00192530, 0x00192530, 0x00192530, 0x00192530, 0x001c2832, 0x001e2833, 0x001c2731, 0x001b2731, 0x001b2731, 0x001b2630, 0x001c2832, 0x001d2934, 0x001d2934, 0x001c2834, 0x001b2631, 0x00192530, 0x00182530, 0x00182430, 0x00172430, 0x00192631, 0x001a2833, 0x001a2833, 0x001a2833, 0x00192732, 0x00172530, 0x00172430, 0x00172630, 0x00172830, 0x0015252e, 0x00101e28, 0x000c1a24, 0x000c1823, 0x000c1822, 0x000d1823, 0x000f1824, 0x000f1824, 0x000e1824, 0x000d1924, 0x000c1823, 0x000c1822, 0x000c1823, 0x000d1924, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000f1922, 0x000f1921, 0x000e1820, 0x000e1820, 0x000e1820, 0x000d1720, 0x000d1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00111f27, 0x00101f27, 0x00112229, 0x00102229, 0x000f2229, 0x000f2229, 0x000f2229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x000f2229, 0x000f2229, 0x000f2229, 0x00102229, 0x00112229, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1a25, 0x000e1a25, 0x000e1a25, 0x000d1a26, 0x000c1a26, 0x000c1b26, 0x000c1b27, 0x000c1b28, 0x000c1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1a26, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x000e1e29, 0x000f1f2a, 0x0010202d, 0x00132430, 0x00172834, 0x001b2c38, 0x001c303b, 0x001d2f3a, 0x001b2c36, 0x0017242f, 0x00182029, 0x00182029, 0x00182029, 0x0018212a, 0x001a222c, 0x001a242f, 0x001b2731, 0x001c2832, 0x001a2630, 0x0018242e, 0x0018242d, 0x0018242c, 0x0019232c, 0x0019242c, 0x001b242d, 0x001c2630, 0x001d2731, 0x001e2834, 0x00212b38, 0x0025303b, 0x002a343f, 0x002d3943, 0x002f3944, 0x002f3844, 0x002f3742, 0x002d3640, 0x002d353f, 0x002f363f, 0x002e343e, 0x002c343e, 0x002b333e, 0x0029323c, 0x002c343e, 0x002c3540, 0x002c3640, 0x002d3641, 0x002c343f, 0x002a323d, 0x0029303b, 0x00272e37, 0x00242b34, 0x00242a34, 0x00242a35, 0x00242b36, 0x00252c36, 0x00252c35, 0x00252c35, 0x00252c35, 0x00252c35, 0x00252c36, 0x00252c37, 0x00262c38, 0x00282d38, 0x002a303c, 0x002c333d, 0x002e3440, 0x00303642, 0x00323844, 0x00313843, 0x00303742, 0x002f3641, 0x002e3641, 0x002e3641, 0x002d3540, 0x002f3440, 0x002f3440, 0x002f343f, 0x00303440, 0x00303440, 0x00303440, 0x00303440, 0x002f3440, 0x002e333f, 0x002f343f, 0x002f343f, 0x002f333f, 0x002f333f, 0x00303440, 0x00303440, 0x00303440, 0x002f3440, 0x002e333f, 0x002c303c, 0x002c303b, 0x002c303a, 0x002c303c, 0x002d303d, 0x002d323e, 0x002e333e, 0x002f343f, 0x002f343f, 0x002f343c, 0x002f343c, 0x0030343c, 0x0031363e, 0x00323740, 0x00313743, 0x00313743, 0x00323642, 0x00313541, 0x00313541, 0x00303640, 0x00303640, 0x002f3540, 0x002f3440, 0x002f3440, 0x002e343f, 0x002d343f, 0x002e343f, 0x002d333e, 0x002c323d, 0x002c333e, 0x002c323d, 0x002c333e, 0x002d343f, 0x002d333f, 0x002c323d, 0x002b303c, 0x00292e3a, 0x00292e39, 0x00292e38, 0x002a2f39, 0x002b303a, 0x002a2f39, 0x00292e38, 0x00282e38, 0x00282d37, 0x00282d37, 0x00292e38, 0x00292e38, 0x002a2f39, 0x002c313c, 0x002e333c, 0x002d323c, 0x002c303b, 0x00292f3a, 0x0029303b, 0x002a303c, 0x002a303c, 0x002a303c, 0x0029303c, 0x00282f3c, 0x00272d38, 0x00262c37, 0x00272d37, 0x00282f38, 0x00262d36, 0x00262c36, 0x00252c36, 0x00242b36, 0x00232934, 0x00232a35, 0x00272f39, 0x002c343e, 0x002c3440, 0x002c343f, 0x0028303c, 0x0028303b, 0x002a323c, 0x002c343f, 0x002d3540, 0x002c3641, 0x002c3741, 0x002c3540, 0x002c3641, 0x002f3844, 0x002f3945, 0x002e3945, 0x002c3845, 0x00283544, 0x00283441, 0x0024303c, 0x00212d37, 0x00202c35, 0x001d2930, 0x00202c33, 0x00243038, 0x0025313b, 0x00232e39, 0x001b2833, 0x001a2935, 0x001a2b36, 0x001c2d36, 0x001b2c35, 0x001a2b34, 0x001b2932, 0x0018242c, 0x00162129, 0x0016222a, 0x0017212a, 0x0016212a, 0x00152129, 0x0018242c, 0x0019252e, 0x001b2630, 0x001c2731, 0x001c2831, 0x001c2832, 0x001c2731, 0x001c2832, 0x001c2832, 0x001d2934, 0x001e2a36, 0x00202c38, 0x00202c38, 0x00202c38, 0x00202c3a, 0x00202d3b, 0x00202c3a, 0x001e2b38, 0x001e2b38, 0x001f2c3b, 0x001e2d3b, 0x001f2d3b, 0x001f2d3b, 0x001f2d3b, 0x001e2c39, 0x001c2a38, 0x001a2836, 0x00192834, 0x00182834, 0x00182832, 0x00192a33, 0x00162830, 0x00102029, 0x000c1a24, 0x000c1821, 0x000c1821, 0x000d1822, 0x000e1822, 0x000e1822, 0x000d1823, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101a23, 0x00101a23, 0x000f1922, 0x000f1921, 0x000e1820, 0x000d1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x000f2229, 0x000f2229, 0x00102229, 0x00102229, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0012242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x00102229, 0x00102229, 0x000f2229, 0x00102229, 0x00112229, 0x00111f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1a26, 0x000e1a26, 0x000e1a26, 0x000d1a26, 0x000c1b26, 0x000c1b26, 0x000c1b28, 0x000c1b28, 0x000c1a27, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000e1c27, 0x000d1b26, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101d28, 0x000e1c28, 0x000e1d28, 0x0010202b, 0x0012212f, 0x00142532, 0x00182a36, 0x001c2f38, 0x001c2f39, 0x001c2c38, 0x00182530, 0x0018212a, 0x0018212a, 0x0018202a, 0x0018212a, 0x001a232c, 0x001a242f, 0x001c2731, 0x001d2933, 0x001a2630, 0x0018242f, 0x0018242f, 0x0019242e, 0x001a242d, 0x001a242d, 0x001b252f, 0x001b252f, 0x001b2530, 0x001d2734, 0x00212c38, 0x0026303c, 0x002a3640, 0x002e3a44, 0x002f3b45, 0x00303945, 0x00303844, 0x002e3640, 0x002e3740, 0x002f3841, 0x002f3740, 0x002e3740, 0x002e3742, 0x002c3640, 0x002c3640, 0x002c3540, 0x002c3540, 0x002c3540, 0x0029313c, 0x00262e38, 0x00242c37, 0x00232b34, 0x00232a34, 0x00242b36, 0x00282d38, 0x00282e39, 0x00282f39, 0x00293039, 0x00293039, 0x00293039, 0x00293039, 0x00293039, 0x00282e39, 0x00282e39, 0x00282f3a, 0x002a303c, 0x002d333e, 0x002f3540, 0x00323844, 0x00343945, 0x00343945, 0x00323944, 0x00303844, 0x00303844, 0x00303844, 0x00303843, 0x00303642, 0x00303441, 0x00303440, 0x00303440, 0x00303441, 0x00313541, 0x00313541, 0x00313541, 0x00303440, 0x002f343f, 0x002f343f, 0x0030333f, 0x00303340, 0x00313441, 0x00313541, 0x00303541, 0x00303440, 0x00303440, 0x002f343f, 0x002e333c, 0x002e333c, 0x002e333e, 0x002e333e, 0x002e333e, 0x002e333f, 0x002f3440, 0x00303440, 0x0030343e, 0x0030343c, 0x0030343d, 0x0032373f, 0x00333841, 0x00323844, 0x00323844, 0x00343844, 0x00323642, 0x00323642, 0x00313741, 0x00313841, 0x00303742, 0x00303642, 0x00303541, 0x002f3440, 0x002f3440, 0x002f3440, 0x002e343f, 0x002e343f, 0x002e3440, 0x002f3440, 0x00303540, 0x002e3440, 0x002c333e, 0x002b313d, 0x002c303c, 0x002a2f3a, 0x00292e3a, 0x002a2f39, 0x002c303a, 0x002c313c, 0x002c313b, 0x002c303b, 0x002c303b, 0x002c303b, 0x002c303b, 0x002d323c, 0x002f333d, 0x0030343e, 0x00313640, 0x00323642, 0x00303440, 0x002e333e, 0x002c323e, 0x002c323e, 0x002b313c, 0x002b303c, 0x002b303c, 0x002a303c, 0x002a303c, 0x00282e38, 0x00262c36, 0x00262c36, 0x00282d37, 0x00282d37, 0x00282d37, 0x00262c36, 0x00242b36, 0x00232834, 0x00242a35, 0x00272f3a, 0x002b333e, 0x002c3540, 0x002d3540, 0x002b343f, 0x002a343e, 0x002c343f, 0x002c343e, 0x002d3540, 0x002d3641, 0x002c3742, 0x002c3540, 0x002c3641, 0x002f3844, 0x002f3945, 0x002e3945, 0x002d3845, 0x00283543, 0x0025323f, 0x0023303b, 0x00232f38, 0x00243038, 0x0025323a, 0x00233038, 0x00243039, 0x00232f38, 0x00202d38, 0x001f2c38, 0x001d2c39, 0x00172833, 0x001b2c36, 0x001b2c35, 0x00192b34, 0x0018262f, 0x00162028, 0x00131c24, 0x00141c25, 0x00182029, 0x0019232c, 0x0018232c, 0x0018242c, 0x001a242d, 0x001c2630, 0x001c2731, 0x001d2832, 0x001f2b34, 0x00202c36, 0x00202c36, 0x00202c36, 0x001d2a36, 0x001d2a36, 0x00202c38, 0x00202d3a, 0x00212f3d, 0x0022303f, 0x00233040, 0x0023303f, 0x00212f3e, 0x0022303f, 0x00243240, 0x00233241, 0x00233241, 0x00243341, 0x00243341, 0x00223140, 0x001f2e3d, 0x001c2c39, 0x001c2b38, 0x001c2c39, 0x001d2c38, 0x001c2d36, 0x00182831, 0x0011202a, 0x000d1a24, 0x000c1821, 0x000c1821, 0x000d1821, 0x000e1822, 0x000e1822, 0x000d1823, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101a23, 0x00101a23, 0x000f1922, 0x000f1921, 0x000e1820, 0x000c1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000d161f, 0x000d161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x000f2229, 0x00102229, 0x0013242c, 0x0013242c, 0x0012242c, 0x0012282e, 0x0012282e, 0x0010282e, 0x0010282e, 0x0010282e, 0x00112a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00112a30, 0x0010282e, 0x0010282e, 0x0010282e, 0x0012282e, 0x0013282e, 0x0012242c, 0x0013242c, 0x0012242c, 0x00102229, 0x000f2229, 0x00112229, 0x00111f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1b26, 0x000e1b26, 0x000e1b26, 0x000d1b25, 0x000c1b25, 0x000c1b26, 0x000c1b27, 0x000c1a27, 0x000c1a26, 0x000c1a26, 0x000c1a26, 0x000c1a26, 0x000c1a26, 0x000c1a25, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000e1b27, 0x000e1c27, 0x000e1c27, 0x000d1a26, 0x000d1a26, 0x000d1b26, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000e1c28, 0x000e1c28, 0x000f1d28, 0x000f1d28, 0x000f1d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x00101e29, 0x0012202d, 0x00142430, 0x00152732, 0x00182a34, 0x001c2d38, 0x001e2c38, 0x001b2630, 0x001a232b, 0x0018222a, 0x00182028, 0x0018212a, 0x001a242d, 0x001a2530, 0x001c2832, 0x001d2933, 0x001c2831, 0x001a2630, 0x001a2630, 0x001b262f, 0x001c262f, 0x001b252e, 0x001a252e, 0x0018232c, 0x0018232e, 0x001c2734, 0x00222c39, 0x0028333e, 0x002b3842, 0x002e3b45, 0x002f3a47, 0x00303947, 0x00303844, 0x002f3743, 0x002f3742, 0x00303842, 0x00303842, 0x002f3842, 0x002f3842, 0x002d3740, 0x002c3540, 0x002c343e, 0x002b323c, 0x002a313c, 0x00262c38, 0x00242b36, 0x00232b35, 0x00232c34, 0x00242c35, 0x00262e38, 0x00282f3b, 0x0029303c, 0x002a313c, 0x002b313c, 0x002b313c, 0x002c323c, 0x002c333c, 0x002c333d, 0x002c333e, 0x002c333e, 0x002c333d, 0x002c333d, 0x002b323e, 0x002c343e, 0x002f3641, 0x00303743, 0x00313844, 0x00323944, 0x00323a45, 0x00323a45, 0x00323945, 0x00313845, 0x00323845, 0x00343845, 0x00343845, 0x00343844, 0x00323643, 0x00313541, 0x00303440, 0x00303440, 0x00303440, 0x002f3440, 0x002f3440, 0x0030343f, 0x00303440, 0x00303440, 0x00303541, 0x00303441, 0x00303440, 0x00303541, 0x00303540, 0x00303440, 0x0030343f, 0x00303440, 0x00303440, 0x002f3440, 0x00303440, 0x00303440, 0x00303440, 0x00303440, 0x00303540, 0x00313540, 0x00323741, 0x00333842, 0x00333844, 0x00333844, 0x00343844, 0x00343844, 0x00333843, 0x00323843, 0x00323843, 0x00313844, 0x00313843, 0x00303742, 0x00313541, 0x00313541, 0x00313541, 0x00303541, 0x00313642, 0x00323743, 0x00313844, 0x00303742, 0x002f3440, 0x002c323d, 0x002c333e, 0x002d333e, 0x002d323e, 0x002d313d, 0x002d323e, 0x002e343e, 0x002f343e, 0x002f343f, 0x002f3440, 0x002f343f, 0x002f343e, 0x002d323d, 0x002f343f, 0x00313741, 0x00323842, 0x00323743, 0x00303541, 0x002d333e, 0x002c323d, 0x002a303b, 0x00282f39, 0x00252c36, 0x00242934, 0x00242a35, 0x00232934, 0x00232934, 0x00232934, 0x00242a34, 0x00232933, 0x00242934, 0x00282c37, 0x00282e38, 0x00282e37, 0x00282d38, 0x00262c38, 0x00242c36, 0x00242d38, 0x0028313c, 0x002b3540, 0x002d3741, 0x002e3641, 0x002f3742, 0x002d3540, 0x002c343e, 0x002c343f, 0x002c3540, 0x002c3741, 0x002c3640, 0x002c3641, 0x002e3844, 0x002f3944, 0x002f3944, 0x002e3844, 0x00293642, 0x0024313c, 0x00222f39, 0x00223038, 0x00233039, 0x0029363e, 0x0029373f, 0x0028353f, 0x0024313c, 0x0021303b, 0x0021303c, 0x001c2c38, 0x00152530, 0x00192932, 0x001a2b34, 0x001b2b34, 0x0017232b, 0x00141c24, 0x00141a23, 0x00121921, 0x00161d25, 0x00172028, 0x001a222b, 0x001a232c, 0x001a222c, 0x001c2430, 0x001e2530, 0x001e2730, 0x00202b34, 0x00232f38, 0x00232f38, 0x00222e38, 0x001f2c38, 0x001d2b37, 0x00202c39, 0x00212f3d, 0x00243140, 0x00253342, 0x00263443, 0x00263443, 0x00263444, 0x00273545, 0x00273848, 0x00283948, 0x00283848, 0x00273848, 0x00273847, 0x00263646, 0x00243443, 0x00213140, 0x00233340, 0x00243441, 0x00233440, 0x001e303c, 0x00172833, 0x00101f2a, 0x000c1a24, 0x000c1823, 0x000c1822, 0x000d1822, 0x000e1822, 0x000e1822, 0x000e1822, 0x000d1923, 0x000d1923, 0x000d1923, 0x000d1923, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x000f1a24, 0x000f1a24, 0x000f1922, 0x000f1921, 0x000e1820, 0x000e1820, 0x000d1720, 0x000c1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f1f27, 0x000f2229, 0x00102229, 0x0013242c, 0x0012242c, 0x0012282e, 0x0010282e, 0x00112a30, 0x00112a30, 0x00132c32, 0x00122c32, 0x00132c32, 0x00132c32, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00132c32, 0x00132c32, 0x00122c32, 0x00112a30, 0x00112a30, 0x00112a30, 0x0011282e, 0x0012282e, 0x0013242c, 0x0013242c, 0x000f2229, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1c27, 0x000e1c27, 0x000e1c27, 0x000e1c25, 0x000d1b24, 0x000d1b24, 0x000d1a26, 0x000d1a26, 0x000c1a26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000c1c28, 0x000c1c28, 0x000c1d28, 0x000c1d28, 0x000e1d28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101e29, 0x0012202c, 0x0013222f, 0x00142431, 0x00182734, 0x001d2d39, 0x0022303a, 0x001c2832, 0x001a242c, 0x00182229, 0x00182026, 0x00182129, 0x0019242e, 0x001b2630, 0x001d2933, 0x001e2a34, 0x001d2933, 0x001c2832, 0x001c2830, 0x001b272f, 0x001a252e, 0x001a242c, 0x0018232b, 0x00172329, 0x0017232a, 0x001b2731, 0x00212c38, 0x00293540, 0x002d3b46, 0x002f3c48, 0x00303b48, 0x002f3948, 0x002f3846, 0x002f3844, 0x002f3844, 0x002f3843, 0x002f3843, 0x002f3843, 0x002e3841, 0x002c3740, 0x002c343e, 0x002c323c, 0x00282e38, 0x00252c36, 0x00242b35, 0x00242a34, 0x00232a34, 0x00232b34, 0x00242d36, 0x00263038, 0x0028303b, 0x0029313c, 0x002b323d, 0x002c333e, 0x002d343f, 0x002e3440, 0x00303641, 0x00303641, 0x002e3641, 0x002e3641, 0x002d3540, 0x002c3440, 0x002c3440, 0x002c3440, 0x002d3540, 0x002d3540, 0x002d3540, 0x00303844, 0x00323a47, 0x00343c49, 0x00353d4a, 0x00363d4a, 0x00383d4b, 0x00393e49, 0x00383c48, 0x00373b47, 0x00343945, 0x00323641, 0x00313540, 0x00303441, 0x00303541, 0x00303440, 0x00303440, 0x00303440, 0x00303440, 0x00303440, 0x002f343f, 0x002f343f, 0x00303440, 0x00303742, 0x00313742, 0x00313742, 0x00323642, 0x00323642, 0x00313642, 0x00303440, 0x00313541, 0x00313541, 0x00313541, 0x00313542, 0x00323642, 0x00323642, 0x00323642, 0x00323741, 0x00333841, 0x00343843, 0x00343844, 0x00343844, 0x00343844, 0x00323843, 0x00313843, 0x00313843, 0x00313843, 0x00313843, 0x00323642, 0x00323642, 0x00323642, 0x00313541, 0x00333642, 0x00333843, 0x00313844, 0x00303744, 0x00303542, 0x002e3440, 0x002f3540, 0x00303641, 0x00313742, 0x00313743, 0x00303843, 0x00303843, 0x00303742, 0x00303742, 0x00303843, 0x00303843, 0x00303742, 0x002c333e, 0x002c333e, 0x00303642, 0x00313843, 0x00303641, 0x002d333e, 0x002b313c, 0x002b313c, 0x00293039, 0x00282f38, 0x00272d37, 0x00242c35, 0x00222934, 0x00212833, 0x00202631, 0x00202631, 0x00202731, 0x00202630, 0x001f252f, 0x00202730, 0x00242a34, 0x00262d37, 0x00293039, 0x0029323c, 0x0026303b, 0x00242f39, 0x0024303a, 0x0028343f, 0x002c3741, 0x002d3842, 0x002f3742, 0x002d3540, 0x002c343e, 0x002c343e, 0x002c3540, 0x002c3741, 0x002c3640, 0x002c3641, 0x002e3842, 0x002f3843, 0x00303944, 0x002f3844, 0x002b3541, 0x0027313e, 0x00242f3a, 0x00202c36, 0x001f2b34, 0x00232f37, 0x0027333c, 0x0028353f, 0x0027353f, 0x0024333e, 0x0023313c, 0x001e2e39, 0x00162530, 0x00182730, 0x001c2b34, 0x001a2832, 0x00152028, 0x00141c21, 0x00141a20, 0x0011181e, 0x00131a20, 0x00141b22, 0x00151c24, 0x00151d24, 0x00161e28, 0x0019202b, 0x001c232c, 0x001c242d, 0x001e2830, 0x00202c34, 0x00222e36, 0x00222f38, 0x00202e38, 0x001f2c37, 0x00202e3a, 0x0023303e, 0x00253341, 0x00263544, 0x00283846, 0x00283847, 0x00293a49, 0x002a3c4c, 0x002c3f4f, 0x002c404f, 0x002c3f4f, 0x002c3f4f, 0x002a3d4d, 0x002a3d4d, 0x002a3d4d, 0x00283a4a, 0x00283b4a, 0x00293c4a, 0x00283b49, 0x00233544, 0x001a2a38, 0x00111f2c, 0x000c1a26, 0x000c1824, 0x000c1824, 0x000c1822, 0x000c1821, 0x000c1822, 0x000c1820, 0x000c181f, 0x000c181f, 0x000c181f, 0x000c1820, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000f1821, 0x000e1820, 0x000d1820, 0x000d1720, 0x000d1720, 0x000c1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x000f2229, 0x0013242c, 0x0012242c, 0x0012282e, 0x00112a30, 0x00112a30, 0x00132c32, 0x00142e34, 0x00142e34, 0x00142e34, 0x00143036, 0x00143036, 0x00143036, 0x00153338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00153338, 0x00153338, 0x00143036, 0x00143036, 0x00143036, 0x00143036, 0x00142e34, 0x00142e34, 0x00132c32, 0x00132c32, 0x00112a30, 0x0010282e, 0x0012282e, 0x0013242c, 0x00102229, 0x000f2229, 0x000f1f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1c28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000d1c26, 0x000d1c26, 0x000c1b27, 0x000c1b27, 0x000c1b27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1b26, 0x000c1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000c1d28, 0x000c1d28, 0x000c1e28, 0x000c1d28, 0x000e1d28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d29, 0x00111f2c, 0x0011202d, 0x00142330, 0x00182734, 0x00202f3c, 0x0026333e, 0x00222e37, 0x001c2830, 0x001a242c, 0x001a2329, 0x001b232b, 0x0019242f, 0x001c2731, 0x001e2a34, 0x001e2a34, 0x001e2a34, 0x001e2a34, 0x001c2831, 0x001a252e, 0x0019232c, 0x0019232c, 0x0019232b, 0x00182329, 0x00182429, 0x001c2831, 0x00243039, 0x002d3844, 0x00303d48, 0x00303d49, 0x00303c48, 0x002e3947, 0x002d3845, 0x002d3844, 0x002f3844, 0x002f3843, 0x002f3843, 0x002f3843, 0x002c3740, 0x002b353d, 0x002b333c, 0x00282f38, 0x00242a34, 0x00222831, 0x00242a34, 0x00242a34, 0x00242a34, 0x00242b34, 0x00242d36, 0x00272f38, 0x00273039, 0x0028313c, 0x002b323d, 0x002c333e, 0x002d333f, 0x002f3440, 0x00303742, 0x00303742, 0x002f3742, 0x002e3540, 0x002d3540, 0x002d3541, 0x002e3641, 0x002e3642, 0x002f3742, 0x002f3742, 0x00303844, 0x00303845, 0x00323a47, 0x00343c48, 0x00353d4a, 0x00373f4c, 0x0039404d, 0x00393f4b, 0x00383c48, 0x00363c48, 0x00363a46, 0x00343944, 0x00333842, 0x00323743, 0x00333743, 0x00323642, 0x00313541, 0x00323642, 0x00323642, 0x00303541, 0x002f3440, 0x002f343f, 0x00303541, 0x00313742, 0x00313843, 0x00323843, 0x00343844, 0x00343844, 0x00333743, 0x00303440, 0x00313541, 0x00323642, 0x00323642, 0x00323642, 0x00323642, 0x00323642, 0x00303440, 0x002f343e, 0x00313540, 0x00333842, 0x00343844, 0x00343844, 0x00343844, 0x00323844, 0x00323844, 0x00333944, 0x00323844, 0x00313843, 0x00323642, 0x00323642, 0x00323642, 0x00323743, 0x00333642, 0x00333743, 0x00323845, 0x00333946, 0x00343a47, 0x00343a45, 0x00333944, 0x00343a45, 0x00353c47, 0x00353c47, 0x00343a46, 0x00313a44, 0x00313944, 0x00313944, 0x00323a44, 0x00333b46, 0x00343b46, 0x00303742, 0x002f3540, 0x00303641, 0x002f3540, 0x002c333e, 0x002b313c, 0x0029303b, 0x00282f39, 0x00272d37, 0x00282e37, 0x00282f38, 0x00252d37, 0x00232b36, 0x00232a34, 0x00212833, 0x00202732, 0x00202730, 0x00202630, 0x001f252f, 0x001e242e, 0x001f252f, 0x00212831, 0x00262c36, 0x0029323b, 0x002a343d, 0x0028333c, 0x0024303b, 0x0026313c, 0x002a343f, 0x002c3640, 0x002c3641, 0x002c343f, 0x002c343e, 0x002c343e, 0x002c3540, 0x002c3741, 0x002c3640, 0x002c3641, 0x002e3842, 0x002e3843, 0x002f3844, 0x002e3844, 0x002a3440, 0x00252f3b, 0x00232d38, 0x00202a34, 0x001d2831, 0x00202b33, 0x00212d37, 0x0024303a, 0x0024323c, 0x0024333d, 0x0025343f, 0x0024333e, 0x00192832, 0x0014242d, 0x00192832, 0x001a2832, 0x0017222a, 0x00151e24, 0x00141b20, 0x0010181d, 0x0012181e, 0x00131920, 0x00121820, 0x00101820, 0x00131b24, 0x00151c28, 0x00171d27, 0x00181f28, 0x0019222b, 0x001b252e, 0x001c2830, 0x00202c36, 0x00212f38, 0x00212f39, 0x0021303c, 0x00243340, 0x00263542, 0x00283846, 0x002a3c4a, 0x002b3c4b, 0x002b3d4c, 0x002c3f4f, 0x002c404f, 0x002a3f4e, 0x002a3e4d, 0x002c4050, 0x002d4251, 0x002f4353, 0x00304453, 0x002d4151, 0x002c4050, 0x002a3f4c, 0x00283c4a, 0x00253847, 0x0021303f, 0x00182533, 0x00111e2a, 0x000c1a26, 0x000c1824, 0x000c1822, 0x000c1821, 0x000c1822, 0x000c1820, 0x000c181f, 0x000c181f, 0x000c181f, 0x000c1820, 0x000d1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1820, 0x000e1820, 0x000d1720, 0x000d1720, 0x000d1720, 0x000c1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0013282e, 0x0010282e, 0x00112a30, 0x00132c32, 0x00142e34, 0x00143036, 0x00153338, 0x00143338, 0x00153439, 0x0015363b, 0x0015363b, 0x0016363b, 0x0016383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0016383c, 0x0016363b, 0x0015363b, 0x0015363b, 0x0015363b, 0x00143439, 0x00153439, 0x00143338, 0x00143036, 0x00143036, 0x00142e34, 0x00132c32, 0x00112a30, 0x0011282e, 0x0012242c, 0x0012242c, 0x000f2229, 0x000f1f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1c28, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000d1c28, 0x000d1c28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1b26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1d28, 0x000d1e28, 0x000c1e28, 0x000d1e28, 0x000e1e28, 0x000e1d28, 0x000e1c25, 0x000d1b25, 0x000e1c26, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000e1c27, 0x000f1c28, 0x00101d29, 0x00101e2c, 0x00101e2c, 0x0012212e, 0x00182734, 0x0022313f, 0x002b3844, 0x00283440, 0x001f2b34, 0x0019242c, 0x0019222a, 0x0019232c, 0x00192430, 0x001c2831, 0x001f2a34, 0x00202c36, 0x001e2a34, 0x001d2933, 0x001c2830, 0x0018242c, 0x0019242c, 0x0019232c, 0x0018222a, 0x00172228, 0x001b272c, 0x00202c34, 0x0027333c, 0x00303b46, 0x00303c48, 0x00303c48, 0x00303c48, 0x002f3a48, 0x002e3946, 0x002e3945, 0x00303946, 0x00303a44, 0x002f3843, 0x002d3842, 0x002a343e, 0x0028323b, 0x00283039, 0x00252c35, 0x00202730, 0x00202730, 0x00232933, 0x00242b34, 0x00242a34, 0x00242b34, 0x00242c35, 0x00252e37, 0x00242d36, 0x00272f39, 0x0028303c, 0x002b313c, 0x002c323d, 0x002d343f, 0x002f3641, 0x002d3540, 0x002d3540, 0x002c3440, 0x002d3540, 0x002e3641, 0x002f3742, 0x00303843, 0x00313944, 0x00323a44, 0x00333b46, 0x00333b47, 0x00343c48, 0x00333b48, 0x00313946, 0x00323a47, 0x00343c48, 0x00343b47, 0x00333844, 0x00323844, 0x00343945, 0x00343a45, 0x00343944, 0x00343844, 0x00343945, 0x00343945, 0x00343945, 0x00343a45, 0x00343a45, 0x00343945, 0x00333844, 0x00323642, 0x00323743, 0x00323843, 0x00333843, 0x00333843, 0x00343844, 0x00343844, 0x00333843, 0x00323642, 0x00323642, 0x00333743, 0x00333743, 0x00333743, 0x00333743, 0x00323642, 0x00313541, 0x0030343f, 0x00313640, 0x00343844, 0x00343945, 0x00343944, 0x00343945, 0x00343945, 0x00333945, 0x00343b46, 0x00343b46, 0x00333944, 0x00333844, 0x00333744, 0x00333744, 0x00333844, 0x00343844, 0x00343945, 0x00363c48, 0x00383c4a, 0x00383d4a, 0x00383d49, 0x00383d48, 0x00373c48, 0x00373d48, 0x00363c48, 0x00333947, 0x00313945, 0x00343c47, 0x00353d48, 0x00343c48, 0x00323c46, 0x00323b45, 0x00303843, 0x002f3742, 0x002e3541, 0x002c3440, 0x002c343e, 0x0029303c, 0x00282e39, 0x00262c36, 0x00242b34, 0x00252c35, 0x00262d36, 0x00262c36, 0x00252c37, 0x00252b37, 0x00232935, 0x00232834, 0x00232933, 0x00222832, 0x00212831, 0x00202730, 0x001f252f, 0x001f252f, 0x00202730, 0x00242c35, 0x0028323a, 0x0029343d, 0x0025313b, 0x0024303b, 0x0027313c, 0x0029343e, 0x002c3440, 0x002c343f, 0x002c343e, 0x002c343e, 0x002c3540, 0x002c3741, 0x002c3640, 0x002c3641, 0x002d3842, 0x002c3741, 0x002c3741, 0x002d3642, 0x002a3340, 0x00242c38, 0x00212a36, 0x00202a34, 0x001c2630, 0x001e2831, 0x00202a32, 0x00202d36, 0x00223039, 0x0023303a, 0x0024313b, 0x0026343f, 0x001e2d37, 0x00182630, 0x00182831, 0x0018252f, 0x0018222b, 0x00182027, 0x00171d23, 0x00131a20, 0x0012181e, 0x00131920, 0x00121921, 0x00111920, 0x00131c24, 0x00161c27, 0x00171d27, 0x00171f28, 0x00172029, 0x0018232c, 0x001a262f, 0x001e2a34, 0x00202d37, 0x00212f39, 0x0023313c, 0x00253441, 0x00283844, 0x002b3a48, 0x002c3d4c, 0x002c3f4c, 0x002c3e4c, 0x002b3e4d, 0x002a3e4d, 0x00293e4d, 0x002a3e4d, 0x002b404f, 0x002e4353, 0x00304557, 0x00304556, 0x002f4454, 0x002c4051, 0x00263c4a, 0x00203745, 0x001f3342, 0x001f3040, 0x001c2a39, 0x00152230, 0x000f1c28, 0x000c1924, 0x000c1823, 0x000c1823, 0x000c1824, 0x000c1822, 0x000c1820, 0x000c1820, 0x000c1820, 0x000d1921, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x000e1a24, 0x000d1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1921, 0x000e1820, 0x000e1820, 0x000d1720, 0x000d1720, 0x000c1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b151e, 0x000b151e, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00132c32, 0x00142e34, 0x00143036, 0x00143338, 0x00143439, 0x0016363b, 0x0017383c, 0x00173a3e, 0x00183c40, 0x00183c40, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183c40, 0x00183c40, 0x00173a3e, 0x00183a3e, 0x0017383c, 0x0015363b, 0x00153439, 0x00153338, 0x00143036, 0x00132c32, 0x00112a30, 0x0010282e, 0x0012242c, 0x0012242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1c28, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000d1c28, 0x000d1c28, 0x000e1d28, 0x000e1d28, 0x000d1c28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1b26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1b26, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1d28, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1d28, 0x000e1c25, 0x000d1b24, 0x000e1c26, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000e1c28, 0x000e1b28, 0x000f1c28, 0x000f1c29, 0x000d1c28, 0x0011202c, 0x00172734, 0x0023313f, 0x002f3a47, 0x002d3944, 0x00212d37, 0x001a242d, 0x0018222b, 0x0019232c, 0x001b2630, 0x001e2a34, 0x00202c36, 0x00222e38, 0x00202c36, 0x001e2a34, 0x0019252e, 0x0018242c, 0x0019242c, 0x001a242c, 0x0019232a, 0x0018242b, 0x001d2930, 0x00212e36, 0x0028343d, 0x002f3b45, 0x002f3b47, 0x00303c48, 0x002f3b48, 0x002f3a48, 0x002f3a48, 0x002f3a47, 0x00303a46, 0x00303a44, 0x002f3944, 0x002c3741, 0x002b343e, 0x0028323b, 0x00272f38, 0x00232933, 0x00202630, 0x00202731, 0x00222833, 0x00232934, 0x00222832, 0x00222832, 0x00232a34, 0x00232c35, 0x00222a34, 0x00242c35, 0x0028303a, 0x002b313c, 0x002c333e, 0x002e3440, 0x002f3641, 0x002d3540, 0x002c3440, 0x002d3540, 0x002d3541, 0x002e3642, 0x002f3742, 0x00303843, 0x00313944, 0x00323a44, 0x00333b46, 0x00333c47, 0x00343c49, 0x00363d4a, 0x00343c49, 0x00343c49, 0x00343c4a, 0x00353c49, 0x00343b48, 0x00333946, 0x00323844, 0x00323844, 0x00333944, 0x00343a46, 0x00353b47, 0x00343b47, 0x00353c47, 0x00363d48, 0x00373d48, 0x00363d48, 0x00363c48, 0x00343a46, 0x00343a46, 0x00353a46, 0x00353a46, 0x00343844, 0x00343944, 0x00343844, 0x00343844, 0x00343944, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00343844, 0x00333743, 0x00333841, 0x00343944, 0x00383c46, 0x00383c48, 0x00383c48, 0x00383d48, 0x00383d48, 0x00373d49, 0x00383d4a, 0x00383d4a, 0x00353c48, 0x00353a48, 0x00343846, 0x00343945, 0x00343945, 0x00353945, 0x00363b47, 0x00383c49, 0x00383c4a, 0x00383c4a, 0x00393e4a, 0x00393e4a, 0x00383c48, 0x00353b48, 0x00343b48, 0x00343c49, 0x00343c48, 0x00343c48, 0x00343c47, 0x00333b46, 0x00303944, 0x002f3843, 0x002e3641, 0x002e3641, 0x002e3641, 0x002d3540, 0x002c343f, 0x0028303c, 0x00272d39, 0x00252c36, 0x00242b34, 0x00252c35, 0x00282d37, 0x00282e38, 0x00282c38, 0x00272c37, 0x00252b37, 0x00262c37, 0x00252c35, 0x00242b34, 0x00242b34, 0x00242a33, 0x00202730, 0x0020262e, 0x001f252e, 0x00202830, 0x00232c35, 0x0027313a, 0x0025313a, 0x0025313b, 0x0026313c, 0x0027313c, 0x0028313c, 0x0028303c, 0x0029313c, 0x002a323d, 0x002c343f, 0x002c3741, 0x002c3640, 0x002c3641, 0x002d3842, 0x002c3741, 0x002c3540, 0x002c3440, 0x0029303c, 0x00232b37, 0x00202834, 0x00202832, 0x001c242e, 0x001c252e, 0x00202831, 0x00202b34, 0x00212e37, 0x00212e38, 0x00212e38, 0x0024323c, 0x0023303a, 0x001d2b34, 0x001d2c35, 0x0017242d, 0x00162028, 0x00161e24, 0x00151c23, 0x00141a20, 0x00131920, 0x00141b22, 0x00171e25, 0x00182027, 0x00192129, 0x001b222c, 0x001b222c, 0x001b232c, 0x0019242c, 0x0019252d, 0x001c2832, 0x00202c36, 0x00202e38, 0x00223039, 0x0024323d, 0x00283642, 0x002b3945, 0x002c3b49, 0x002d3e4c, 0x002c3e4c, 0x002c3e4d, 0x002a3d4d, 0x002a3e4e, 0x002a3f4f, 0x002b3f4f, 0x002c4151, 0x00304455, 0x00314658, 0x00304556, 0x002e4454, 0x002b4152, 0x00243a49, 0x001d3140, 0x00182b3b, 0x00182838, 0x00182736, 0x00142230, 0x000f1c28, 0x000c1924, 0x000c1824, 0x000c1824, 0x000c1824, 0x000d1922, 0x000d1921, 0x000d1921, 0x000d1921, 0x000d1922, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000e1820, 0x000c1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b151e, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00122229, 0x000f2229, 0x0013242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00142e34, 0x00153338, 0x00143439, 0x0017383c, 0x00183a3e, 0x00183c40, 0x00183d41, 0x00183f43, 0x00194044, 0x001a4245, 0x001a4245, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4245, 0x001a4245, 0x001a4245, 0x001a4245, 0x001a4245, 0x001a4245, 0x001a4245, 0x001a4245, 0x001a4245, 0x001a4245, 0x00194245, 0x001a4245, 0x00194044, 0x00183f43, 0x00183f43, 0x00183d41, 0x00183c40, 0x0017383c, 0x0016363b, 0x00143338, 0x00143036, 0x00142e34, 0x00112a30, 0x0010282e, 0x0013242c, 0x00102229, 0x00102229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000e1d27, 0x00101d28, 0x00101d28, 0x000f1d28, 0x000e1e28, 0x000e1e28, 0x000f1f29, 0x000f1e29, 0x000d1d28, 0x000c1d28, 0x000c1c28, 0x000d1c28, 0x000d1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c27, 0x000f1c27, 0x000f1c27, 0x000f1c27, 0x000f1d28, 0x000e1f29, 0x000e1f29, 0x000e1e2a, 0x000e1e2a, 0x000f1d28, 0x000f1c27, 0x000f1c26, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000d1c27, 0x000e1c27, 0x000e1c28, 0x000e1c28, 0x000e1c28, 0x000f1c2a, 0x000f1c2a, 0x000f1c2a, 0x000f1c2a, 0x000f1c29, 0x000e1c28, 0x000d1a27, 0x000d1a26, 0x000d1b27, 0x000d1b27, 0x000c1c27, 0x000f1f2a, 0x00142431, 0x0022303d, 0x002f3a48, 0x00303a45, 0x00242e38, 0x001c242d, 0x0019212b, 0x001c242d, 0x001c2731, 0x001d2833, 0x001c2832, 0x001e2a34, 0x001d2933, 0x001c2832, 0x0018252e, 0x0018242c, 0x0018242d, 0x0019242d, 0x0019242c, 0x001a262d, 0x001e2a31, 0x00202d36, 0x0026323c, 0x002d3944, 0x002f3b47, 0x00303c48, 0x00303c48, 0x00303c49, 0x00303c48, 0x00303b47, 0x00303a45, 0x002f3843, 0x002e3842, 0x002c3440, 0x002a343d, 0x0027313a, 0x00262e37, 0x00242a34, 0x00202730, 0x00222833, 0x00232934, 0x00232834, 0x00212831, 0x00212831, 0x00222933, 0x00232a34, 0x00222933, 0x00242b34, 0x00272e38, 0x002c323d, 0x002c333e, 0x002d343f, 0x002e3540, 0x002d3540, 0x002e3641, 0x002e3641, 0x002d3541, 0x002d3541, 0x002e3642, 0x00303844, 0x00313a45, 0x00323b46, 0x00333c48, 0x00343c48, 0x00353e4a, 0x00383f4c, 0x00373f4c, 0x00363e4c, 0x0037404e, 0x00373f4c, 0x00383f4c, 0x00383f4c, 0x00353c48, 0x00333945, 0x00323844, 0x00343a45, 0x00353c47, 0x00353b48, 0x00363c49, 0x00383f4b, 0x00393f4c, 0x00393f4c, 0x00393f4c, 0x00383e4a, 0x00383e4a, 0x00383d49, 0x00383c48, 0x00353a46, 0x00343944, 0x00343945, 0x00353a46, 0x00363b47, 0x00373b48, 0x00363b47, 0x00343a46, 0x00353a46, 0x00343946, 0x00343944, 0x00343844, 0x00343944, 0x00363b44, 0x00373c47, 0x00383c48, 0x003a3f4b, 0x003c404c, 0x003a3f4c, 0x003a404c, 0x003a404d, 0x003a404d, 0x00383f4c, 0x00373d4b, 0x00363c4a, 0x00353b48, 0x00353b49, 0x00373c49, 0x00383e4a, 0x00383e4b, 0x00393e4c, 0x00383e4b, 0x00383e4b, 0x00373d4a, 0x00353c49, 0x00353d4a, 0x00383f4c, 0x00383f4c, 0x00353c49, 0x00343b48, 0x00333a47, 0x00333a46, 0x00313944, 0x002f3742, 0x002d3540, 0x002d3540, 0x002e3642, 0x002d3441, 0x002b333f, 0x0029313e, 0x002a303c, 0x00282e38, 0x00282e38, 0x00282e38, 0x00282f38, 0x00292e38, 0x00282c37, 0x00282c38, 0x00262c37, 0x00252c36, 0x00252c35, 0x00242c35, 0x00242c34, 0x00252c34, 0x00232931, 0x0020272e, 0x0020262e, 0x001f252f, 0x00202831, 0x00242e37, 0x00242e37, 0x0024303b, 0x0026303b, 0x0026303a, 0x00262f38, 0x00252e38, 0x00252e38, 0x0028303b, 0x002a343e, 0x002c3540, 0x002b343f, 0x002c3540, 0x002d3742, 0x002d3741, 0x002c3540, 0x002b333e, 0x0028303c, 0x00242c36, 0x00222932, 0x0020282f, 0x001c222a, 0x001a212a, 0x00202730, 0x00202c34, 0x00202c35, 0x00202c35, 0x00202c35, 0x00212f38, 0x0024333c, 0x00222f39, 0x00202c36, 0x001b2831, 0x0018232c, 0x00161d25, 0x00151c24, 0x00151c24, 0x00161c24, 0x00171d24, 0x00181f26, 0x00182027, 0x00182129, 0x0019222c, 0x001a232d, 0x001b242f, 0x001a242f, 0x00192530, 0x001f2a36, 0x0024303b, 0x0025323c, 0x0026343e, 0x00273440, 0x00293743, 0x002b3845, 0x002b3a48, 0x002c3c4c, 0x002c3c4c, 0x002b3c4d, 0x002b3d4f, 0x002b4050, 0x002c4052, 0x002c4052, 0x002e4354, 0x00304456, 0x00304557, 0x002c4152, 0x00283d4c, 0x00263b4a, 0x00203544, 0x001c2f3d, 0x00152634, 0x00132230, 0x0013212f, 0x00111f2c, 0x000f1c28, 0x000d1a25, 0x000c1924, 0x000c1824, 0x000d1924, 0x000e1923, 0x000e1922, 0x000e1923, 0x000e1923, 0x000e1a24, 0x000f1a24, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x000f1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000d1720, 0x000d1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b151e, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x000f2229, 0x0012242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00142e34, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183c40, 0x00183f43, 0x00194044, 0x001a4347, 0x001b4448, 0x001c4649, 0x001c474b, 0x001c474b, 0x001d484c, 0x001d484c, 0x001d484c, 0x001d484c, 0x001d484c, 0x001d484c, 0x001c484c, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c4649, 0x001c4649, 0x001b4448, 0x001a4347, 0x001a4245, 0x00183f43, 0x00183d41, 0x00183a3e, 0x0017383c, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000e1d27, 0x00101e29, 0x00101e29, 0x00101f29, 0x000f1f29, 0x000f1f29, 0x0010202b, 0x0010202b, 0x000f1f29, 0x000e1d28, 0x000e1d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101e28, 0x000f1f29, 0x000f1f29, 0x000f1e2c, 0x000f1e2c, 0x000f1e2a, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000c1c2a, 0x000d1c2b, 0x000d1c2b, 0x000f1c2b, 0x000f1c2b, 0x000f1c2a, 0x000d1a27, 0x000d1a26, 0x000d1a26, 0x000d1b26, 0x000c1a26, 0x000c1b25, 0x000d1e29, 0x00122430, 0x00202f3c, 0x002f3b48, 0x00303945, 0x00242c38, 0x001c232d, 0x001b212b, 0x001b222c, 0x0019222c, 0x0016202b, 0x0015212c, 0x001a2530, 0x0018242e, 0x0018242f, 0x0018242f, 0x0017242f, 0x0018242f, 0x00192530, 0x001a2630, 0x001c2831, 0x001e2a33, 0x00202c37, 0x0026303c, 0x002d3844, 0x002f3b47, 0x002f3b47, 0x00303c48, 0x00303c48, 0x00303c47, 0x00313b46, 0x00303944, 0x002e3842, 0x002e3641, 0x002b333e, 0x0028323c, 0x0027303b, 0x00272e38, 0x00242b36, 0x00242a34, 0x00252c34, 0x00242b35, 0x00232933, 0x00222831, 0x00222831, 0x00232933, 0x00242a34, 0x00242a34, 0x00242a35, 0x00272d38, 0x002b313c, 0x002c323d, 0x002c333e, 0x002c333e, 0x002c343e, 0x002b333e, 0x002c343f, 0x002b333e, 0x002a323e, 0x002c3440, 0x00303844, 0x00303a47, 0x00313c48, 0x00323d49, 0x00333f4b, 0x00343f4b, 0x0037404d, 0x0038414e, 0x0038404d, 0x0038424e, 0x0038424f, 0x003a424f, 0x003a424f, 0x0039404d, 0x00383e4a, 0x00343b44, 0x00343a44, 0x00383f4a, 0x00383e4a, 0x0038404c, 0x0038404c, 0x0039404c, 0x0039414e, 0x003b424f, 0x003b424e, 0x003b424f, 0x003b404d, 0x00383c4a, 0x00353a48, 0x00353a47, 0x00373c48, 0x00383c48, 0x00383d4b, 0x00383d4b, 0x00373c4a, 0x00363c49, 0x00373b48, 0x00373b48, 0x00353a47, 0x00353a45, 0x00353a46, 0x00363c46, 0x00373d48, 0x00353c47, 0x00393e4b, 0x003c404d, 0x003a3f4c, 0x003b404e, 0x00394150, 0x0039404f, 0x0039404f, 0x0038404f, 0x0038404e, 0x00383f4d, 0x0038404f, 0x003a414f, 0x003a424f, 0x0038404c, 0x00373e4b, 0x00383f4c, 0x003a414e, 0x0038404e, 0x00353e4b, 0x00363d4a, 0x00373d4a, 0x00363c49, 0x00353b48, 0x00343947, 0x00323846, 0x00313845, 0x00303844, 0x002d3540, 0x002c3440, 0x002d3440, 0x00303540, 0x002c333e, 0x002b313d, 0x002b313c, 0x002a313d, 0x002a303c, 0x002a303c, 0x002a303b, 0x0029303a, 0x00282e38, 0x00272c36, 0x00252a36, 0x00242935, 0x00222a33, 0x00222a33, 0x00212933, 0x00212931, 0x00242a32, 0x00242a31, 0x00212830, 0x0020272f, 0x001e242e, 0x001f252e, 0x00222932, 0x00212b34, 0x0025303a, 0x0028323c, 0x00263039, 0x00242e36, 0x00212c34, 0x00232c35, 0x00263039, 0x0028333d, 0x002a343e, 0x002b323d, 0x002b333d, 0x002d3540, 0x002e3540, 0x002c343f, 0x0029313d, 0x0028303c, 0x00252c37, 0x00232933, 0x001f252c, 0x001a2027, 0x00181f26, 0x001d242c, 0x00222b35, 0x00222e38, 0x00202c35, 0x001f2c36, 0x001d2b34, 0x0024313b, 0x0024313b, 0x001c2832, 0x0018252f, 0x0018232c, 0x00171f26, 0x00171f26, 0x00181f26, 0x00192026, 0x00181f27, 0x00181f26, 0x00161d24, 0x00141c25, 0x00151d27, 0x00162029, 0x0018212c, 0x0019242f, 0x001c2731, 0x00212d39, 0x0027333f, 0x00283440, 0x00263440, 0x00263440, 0x00283543, 0x00283845, 0x00283947, 0x00283a48, 0x002a3c4b, 0x002c3f4f, 0x002d4152, 0x002d4253, 0x002e4354, 0x002d4354, 0x002e4454, 0x002f4556, 0x002d4455, 0x00273c4c, 0x001f3442, 0x001b303c, 0x001c2f3c, 0x001a2c39, 0x00142431, 0x0010202c, 0x000f1e2a, 0x00101d28, 0x000e1c26, 0x000d1b24, 0x000d1a23, 0x000d1922, 0x000e1923, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101b25, 0x00101c26, 0x00101b25, 0x000f1a24, 0x000d1924, 0x000d1924, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000d1720, 0x000d1720, 0x000d1720, 0x000c1720, 0x000c161f, 0x000b151e, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00142e34, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183d41, 0x00194044, 0x001a4347, 0x001b4649, 0x001c474b, 0x001c4a4d, 0x001d4b4e, 0x001d4c50, 0x001d4c50, 0x001e4d50, 0x001e4d50, 0x001d4d50, 0x001e4d50, 0x001e4d50, 0x001e4d50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4b4e, 0x001d4b4e, 0x001c4a4d, 0x001d4a4d, 0x001c484c, 0x001b4649, 0x001b4448, 0x001a4245, 0x00183f43, 0x00183c40, 0x0017383c, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0013282e, 0x0012242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000e1d28, 0x00101e29, 0x00101e29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x0010202b, 0x0010202b, 0x000f1f29, 0x000e1e28, 0x000e1e28, 0x000f1d28, 0x000f1d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101f2a, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010202c, 0x00101e2b, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000c1c2a, 0x000d1c2b, 0x000d1c2b, 0x000e1c2b, 0x000f1c2b, 0x000f1c2a, 0x000d1a27, 0x000d1a26, 0x000d1a26, 0x000d1b26, 0x000c1a26, 0x000b1a25, 0x000d1d28, 0x0011222f, 0x001e2d3a, 0x002d3a48, 0x00303944, 0x00242c38, 0x001c232d, 0x001a202a, 0x0019202a, 0x00171f2a, 0x00131c27, 0x00121e28, 0x0017222c, 0x0017232c, 0x0018242e, 0x0018242f, 0x00182630, 0x001b2831, 0x001c2832, 0x001b2831, 0x001b2832, 0x001d2932, 0x00212c35, 0x0026303a, 0x002d3843, 0x002f3a46, 0x002f3b47, 0x00303c48, 0x00303c48, 0x00303c47, 0x00303a45, 0x002e3843, 0x002c3640, 0x002a323d, 0x0029313c, 0x0027303c, 0x0026303a, 0x00272d38, 0x00242b36, 0x00242b36, 0x00272d37, 0x00262c36, 0x00232933, 0x00222831, 0x00222831, 0x00222832, 0x00242a34, 0x00242b34, 0x00252c36, 0x00282e3a, 0x002c323d, 0x002c323d, 0x002a313c, 0x0028303b, 0x0028303c, 0x0028303c, 0x002b333e, 0x002c333e, 0x002a323c, 0x002c333e, 0x00303844, 0x00303a47, 0x00313b48, 0x00303c48, 0x00333e4a, 0x00343f4b, 0x0037404c, 0x0038414e, 0x0037414e, 0x0038424f, 0x0039434f, 0x003c4450, 0x003c4451, 0x003c4350, 0x003b414f, 0x0039404c, 0x00383e49, 0x003a404c, 0x003b414d, 0x003c434f, 0x003a424d, 0x0039414d, 0x003a424f, 0x003c4451, 0x003c4451, 0x003c4450, 0x003c4250, 0x003a404d, 0x00373c4a, 0x00363b48, 0x00373b48, 0x00383d49, 0x0039404c, 0x003a404d, 0x00393f4c, 0x00383e4b, 0x00393d4b, 0x00393d4b, 0x00383c48, 0x00383c48, 0x00383c48, 0x00373d48, 0x00383e48, 0x00363c48, 0x00393e4c, 0x003b404d, 0x003c404d, 0x003d4350, 0x003b4351, 0x003a4250, 0x003a4250, 0x003a4250, 0x003a4250, 0x00394250, 0x003a4250, 0x0039414f, 0x0038404c, 0x00373f4c, 0x00383f4c, 0x003a404d, 0x003b424f, 0x0038414e, 0x00353f4c, 0x00343c49, 0x00363c49, 0x00353b48, 0x00353b48, 0x00343a48, 0x00343947, 0x00333947, 0x00313844, 0x002e3641, 0x002c3440, 0x002c343f, 0x002e343f, 0x002d343f, 0x002e343f, 0x002c323d, 0x0028303b, 0x00282f3b, 0x002a303c, 0x002a303c, 0x002a303b, 0x00282e38, 0x00252c36, 0x00242934, 0x00222834, 0x00212831, 0x00202830, 0x001e2730, 0x001e2730, 0x00202830, 0x00212830, 0x0020282f, 0x0020262e, 0x001e242d, 0x001d242c, 0x00202630, 0x00212933, 0x00242f39, 0x0025303a, 0x00242d37, 0x00212c34, 0x00222c34, 0x00242d36, 0x00263039, 0x0028323c, 0x0029333d, 0x0029313c, 0x0029313c, 0x002c343f, 0x002c343f, 0x002a323d, 0x0029313d, 0x0028303c, 0x00252c37, 0x00242a33, 0x001f252c, 0x00192027, 0x00151c24, 0x00181f27, 0x00212a34, 0x0024303a, 0x00212d37, 0x001e2a34, 0x001c2933, 0x001e2c35, 0x00202d37, 0x0017242e, 0x00101e28, 0x00141f28, 0x00141e26, 0x00141c24, 0x00161c23, 0x00161c23, 0x00161c24, 0x00151c23, 0x00141c23, 0x00101822, 0x00111922, 0x00131c25, 0x00152029, 0x001b2530, 0x001f2b34, 0x0025313d, 0x00283440, 0x0025323e, 0x0023303c, 0x0024333e, 0x00283643, 0x00293947, 0x00283a47, 0x00283c4a, 0x002c404d, 0x00304454, 0x00314555, 0x00304455, 0x002f4455, 0x002f4455, 0x002e4455, 0x002d4555, 0x002c4353, 0x00253b4a, 0x001b2f3d, 0x00152935, 0x00162936, 0x00152834, 0x0012222f, 0x000f1f2b, 0x000e1d28, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000d1a23, 0x000d1921, 0x000e1a23, 0x00101b25, 0x00111c26, 0x00111c26, 0x00111c26, 0x00111c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x000f1a24, 0x000d1924, 0x000d1924, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000d1720, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b151e, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00143036, 0x00143439, 0x00183a3e, 0x00183d41, 0x001a4245, 0x001b4448, 0x001c474b, 0x001d4b4e, 0x001d4c50, 0x001e4f51, 0x001f5053, 0x00205154, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x001f5154, 0x001f5154, 0x00205154, 0x001f5053, 0x001e5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001e5053, 0x001e4f51, 0x001e4f51, 0x001d4d50, 0x001d4c50, 0x001c4a4d, 0x001c474b, 0x001b4649, 0x001a4245, 0x00183f43, 0x00183c40, 0x0016363b, 0x00143338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x000f1f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x00101f2a, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1e29, 0x00101e29, 0x00101e29, 0x00101e29, 0x00101f2b, 0x00101f2b, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x0011202b, 0x0011202c, 0x0011202c, 0x0011202d, 0x0011202d, 0x0010202c, 0x00101e2c, 0x00101e2b, 0x00101d28, 0x00101d28, 0x000f1d28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e2b, 0x000c1e2c, 0x000c1d2c, 0x000e1d2c, 0x000e1d2c, 0x000e1c2a, 0x000d1a27, 0x000d1a26, 0x000d1a26, 0x000d1b26, 0x000c1a26, 0x000b1a25, 0x000c1d28, 0x0011212e, 0x001b2a37, 0x002a3644, 0x002f3843, 0x00252d38, 0x001c232d, 0x00192029, 0x0019202a, 0x0018202c, 0x0016202b, 0x0014202a, 0x0015212b, 0x0018242d, 0x001b2731, 0x001b2831, 0x001b2832, 0x001d2a34, 0x001c2832, 0x001b2630, 0x001b2730, 0x001c2730, 0x00202b34, 0x00252e38, 0x002c3641, 0x002e3844, 0x002e3945, 0x002f3b47, 0x002f3c48, 0x00303b47, 0x00303944, 0x002d3842, 0x002b3540, 0x0028303b, 0x0028303c, 0x0027303b, 0x0026303a, 0x00272c38, 0x00222834, 0x00232934, 0x00242b34, 0x00242b34, 0x00232932, 0x00212831, 0x00212831, 0x00232933, 0x00252c35, 0x00272c37, 0x00282e39, 0x002a303c, 0x002d333e, 0x002e343f, 0x002d343f, 0x002b333e, 0x002a323d, 0x002c343e, 0x002c3440, 0x002d343f, 0x002d343c, 0x002e343f, 0x00313844, 0x00313a46, 0x00303a47, 0x00313c48, 0x00333d49, 0x00343f4b, 0x0036404c, 0x0038414e, 0x0038434f, 0x0038434f, 0x00394350, 0x003c4452, 0x003c4453, 0x003c4452, 0x003c4251, 0x003c424f, 0x003b414e, 0x003a404d, 0x003b414f, 0x003d4452, 0x003c4451, 0x003a4250, 0x003c4450, 0x003d4552, 0x003d4553, 0x003e4454, 0x003e4454, 0x003b4150, 0x00393f4d, 0x00383d4b, 0x00363c49, 0x00373d49, 0x00383f4b, 0x00393f4c, 0x003a404d, 0x0039404d, 0x00393f4c, 0x00393f4c, 0x003a3f4c, 0x003a3f4a, 0x003a3f4b, 0x0039404b, 0x003a414c, 0x0039404c, 0x003d4250, 0x003f4351, 0x00404452, 0x003f4554, 0x003b4351, 0x00394050, 0x00394150, 0x003a4250, 0x003a4250, 0x003a4250, 0x003a4250, 0x003b4351, 0x003b4351, 0x003a4250, 0x003b424f, 0x00393f4c, 0x00373e4b, 0x0037404c, 0x0036404c, 0x00363e4b, 0x00363c49, 0x00353b48, 0x00343a48, 0x00353b48, 0x00343a48, 0x00343a48, 0x00323a45, 0x00303843, 0x002d3540, 0x002c343f, 0x002c333e, 0x002f3540, 0x00303742, 0x002f3440, 0x002a303c, 0x00292f3c, 0x002a303d, 0x002b313d, 0x002c323d, 0x00292f3b, 0x00262c38, 0x00242935, 0x00232934, 0x00222832, 0x001f2730, 0x001c242f, 0x001c242f, 0x001e252f, 0x0020262f, 0x001f252e, 0x001f252e, 0x001e242d, 0x001c232c, 0x001f252e, 0x00222a33, 0x00222c36, 0x00212b35, 0x00202a34, 0x00202c34, 0x00222c35, 0x00232d36, 0x00242e37, 0x0027303b, 0x0029333d, 0x002a343e, 0x002b333e, 0x002a323e, 0x0029313e, 0x0029323e, 0x002a323e, 0x0028303c, 0x00252c37, 0x00242a33, 0x001f262d, 0x00192028, 0x00141b23, 0x00161c24, 0x00212a33, 0x00243039, 0x00222e38, 0x001e2b35, 0x001c2934, 0x001a2831, 0x001a2832, 0x0018242e, 0x00131e28, 0x00141f28, 0x00172029, 0x00141c24, 0x000f161c, 0x000c1319, 0x000d141c, 0x000f171c, 0x00111920, 0x00101821, 0x00101821, 0x00131c25, 0x0017212b, 0x001d2933, 0x00222e38, 0x0024303c, 0x0024303c, 0x00212e3a, 0x00202e39, 0x00253440, 0x002b3a47, 0x002c3c4a, 0x002b3e4b, 0x002c404e, 0x002e4250, 0x00304554, 0x00314556, 0x002f4454, 0x002d4454, 0x002c4354, 0x002c4354, 0x002c4354, 0x002c4251, 0x00243a48, 0x00192d3b, 0x00132734, 0x00142534, 0x00142432, 0x0011202d, 0x000e1d29, 0x000d1c27, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1b24, 0x000e1a24, 0x00101b25, 0x00111c26, 0x00111c26, 0x00111c26, 0x00111c26, 0x00111c27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00101c26, 0x00101b25, 0x000f1a24, 0x000e1a24, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000c161f, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000a141d, 0x0009141c, 0x0009141c, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x00102229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x00143439, 0x0017383c, 0x00183d41, 0x00194044, 0x001b4649, 0x001c484c, 0x001d4c50, 0x001e4f51, 0x001f5154, 0x00205356, 0x00205457, 0x00205558, 0x00205558, 0x00215659, 0x00215659, 0x00215659, 0x00215659, 0x00205558, 0x00205558, 0x00205558, 0x00205457, 0x00205457, 0x00205457, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205254, 0x00205154, 0x001e5053, 0x001d4d50, 0x001d4b4e, 0x001c484c, 0x001b4649, 0x001a4245, 0x00183d41, 0x00183a3e, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x00101f2a, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x00101f2a, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x00101e29, 0x00101e29, 0x00101f2a, 0x0010202b, 0x0010202b, 0x0011202c, 0x0011202c, 0x0012202c, 0x0013202c, 0x0013202c, 0x0013202c, 0x0013202c, 0x0012202c, 0x0012212c, 0x0012212c, 0x0012212d, 0x0012212e, 0x0011202d, 0x0010202c, 0x0010202c, 0x00101e29, 0x00101e29, 0x00101d28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e2b, 0x000c1e2c, 0x000c1e2c, 0x000e1d2c, 0x000e1d2c, 0x000e1c2a, 0x000d1a27, 0x000d1a26, 0x000d1a26, 0x000d1b26, 0x000c1a26, 0x000b1a25, 0x000c1c27, 0x0010202c, 0x00182633, 0x0026323f, 0x002e3743, 0x00262e39, 0x001c232d, 0x00192029, 0x0019202a, 0x001b242e, 0x001c2530, 0x001a2630, 0x0019242f, 0x001b2731, 0x001d2933, 0x001c2a34, 0x001e2c35, 0x001f2b35, 0x001b2731, 0x0019252f, 0x001c2830, 0x001c2730, 0x001e2832, 0x00232c36, 0x002b343f, 0x002d3844, 0x002d3945, 0x002e3a46, 0x002f3b47, 0x00303b46, 0x00303944, 0x002d3842, 0x002c3540, 0x0028303b, 0x0028303b, 0x0029323c, 0x0027303a, 0x00242b36, 0x00202732, 0x00222832, 0x00222831, 0x00222830, 0x00232931, 0x00242a33, 0x00242a34, 0x00252c35, 0x00272d37, 0x00282f3a, 0x002a303c, 0x002a303c, 0x002d3440, 0x002f3441, 0x002f3743, 0x002d3541, 0x002c343f, 0x002b333e, 0x002b323c, 0x002b313d, 0x002c333c, 0x002e343e, 0x00303742, 0x00303844, 0x00303845, 0x00303a47, 0x00323c48, 0x00353e4b, 0x0037404c, 0x0038414e, 0x00394450, 0x0038434f, 0x003b4450, 0x003c4452, 0x003c4454, 0x003c4453, 0x003c4352, 0x003c4350, 0x003c424f, 0x003b404e, 0x003b414e, 0x003c4350, 0x003c4451, 0x003d4553, 0x003e4554, 0x003e4654, 0x003d4454, 0x00404556, 0x00404556, 0x003e4454, 0x003c4252, 0x003b404f, 0x00393f4d, 0x00373d4b, 0x00383f4c, 0x003b404e, 0x003c414f, 0x003c424f, 0x003c4350, 0x003c4350, 0x003d424e, 0x003e424e, 0x003d424e, 0x003c434e, 0x003c444f, 0x003c4450, 0x00404554, 0x00414655, 0x00404655, 0x003f4554, 0x003c4454, 0x003c4454, 0x003c4454, 0x003c4455, 0x003c4455, 0x003c4455, 0x003c4454, 0x003c4454, 0x003d4454, 0x003c4452, 0x003b424f, 0x00383f4c, 0x00373d4a, 0x0037404c, 0x0037404d, 0x0038404c, 0x00363c49, 0x00343a48, 0x00333945, 0x00343a47, 0x00353b48, 0x00343a48, 0x00333a46, 0x00303843, 0x002e3641, 0x002d3540, 0x002d343f, 0x002e3440, 0x00303641, 0x00303742, 0x002c323e, 0x002a303d, 0x002b313f, 0x002d3440, 0x002e3440, 0x002c323d, 0x00292f3a, 0x00272c38, 0x00252b34, 0x00232933, 0x00202830, 0x001d2530, 0x001c242f, 0x001d2430, 0x001e2430, 0x001f252f, 0x001f252f, 0x0020242e, 0x001e242c, 0x001f252d, 0x00212831, 0x00202932, 0x001d2730, 0x001e2831, 0x00202c34, 0x00212c36, 0x00222c36, 0x00232d37, 0x0026303c, 0x0028313d, 0x0028323d, 0x002a323e, 0x0029313d, 0x0028303d, 0x0029313e, 0x002a323f, 0x0028303c, 0x00252c37, 0x00242a33, 0x0020272e, 0x001b2128, 0x00181c24, 0x00161b23, 0x00202830, 0x00242f38, 0x00212e37, 0x00202d37, 0x001d2b35, 0x001b2832, 0x00182630, 0x0018242e, 0x00151f2a, 0x00131c27, 0x00162029, 0x00151e26, 0x0010181f, 0x000c131a, 0x000d151c, 0x0010181e, 0x0010181f, 0x00101822, 0x00131b24, 0x0018212b, 0x001f2833, 0x00242f39, 0x00232e38, 0x00202a37, 0x001f2935, 0x001f2a36, 0x00212e3a, 0x00273541, 0x002c3a47, 0x002e3d4c, 0x002d3f4d, 0x002e404f, 0x002d4250, 0x002f4453, 0x00304454, 0x002e4253, 0x002c4252, 0x002c4252, 0x002c4252, 0x002c4353, 0x002b4151, 0x00243a48, 0x00182c3a, 0x00122433, 0x00112331, 0x00112230, 0x0010202c, 0x000d1c28, 0x000d1c27, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000f1b25, 0x00101b25, 0x00101c25, 0x00101c26, 0x00101c26, 0x00101c26, 0x00101c26, 0x00111d27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00111d27, 0x00101c26, 0x00101b25, 0x000f1a24, 0x000f1921, 0x000f1921, 0x000e1820, 0x000e1820, 0x000c161f, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000a141c, 0x0009141c, 0x0009141c, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0013282e, 0x00112a30, 0x00142e34, 0x00153338, 0x0015363b, 0x00183c40, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4c50, 0x00216371, 0x00267f9a, 0x0027819b, 0x0028819c, 0x0028829c, 0x0028829c, 0x0028839c, 0x0028839c, 0x0028839c, 0x0028839c, 0x0028839c, 0x0028839c, 0x0028839c, 0x0028829c, 0x0028829c, 0x0028829c, 0x0028829c, 0x0028829c, 0x0028819c, 0x0028819c, 0x0028819c, 0x0028819c, 0x0028819c, 0x0028819c, 0x0028829c, 0x0028819c, 0x0028819c, 0x0027819c, 0x0027819b, 0x0027809b, 0x0026809b, 0x00257e99, 0x001f5d6b, 0x001c484c, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010202e, 0x0010202d, 0x0010202d, 0x0010202d, 0x0010202c, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202c, 0x0011202c, 0x0011202c, 0x0012212c, 0x0012212c, 0x0013212c, 0x0014212c, 0x0014212c, 0x0014212c, 0x0014212c, 0x0013212e, 0x0012212f, 0x0012212f, 0x0012212f, 0x0012212f, 0x0011212e, 0x0010202e, 0x0010202d, 0x00101f2c, 0x00101f2b, 0x00101f2a, 0x00101e29, 0x00101e29, 0x000f1d28, 0x000f1d28, 0x000f1d2a, 0x000e1d2c, 0x000e1c2c, 0x000e1c2c, 0x000e1c2c, 0x000e1c29, 0x000d1a27, 0x000d1a26, 0x000d1a26, 0x000d1b26, 0x000d1a26, 0x000c1a24, 0x000c1b26, 0x000f1d29, 0x0014222f, 0x00222d3a, 0x002c3541, 0x00252e39, 0x001d242f, 0x001a202b, 0x001b212c, 0x001f2530, 0x00202834, 0x001f2934, 0x001c2831, 0x001c2730, 0x001c2831, 0x001e2a34, 0x001e2c34, 0x001d2933, 0x001a252f, 0x001a252f, 0x001c2830, 0x001c262f, 0x001b2530, 0x00202934, 0x002a323e, 0x002e3844, 0x002e3945, 0x002e3a46, 0x002f3b47, 0x002f3b46, 0x002e3a44, 0x002c3842, 0x002b3540, 0x0027303a, 0x00262f38, 0x00272f39, 0x00232b36, 0x00212833, 0x00212833, 0x00212831, 0x00202730, 0x0020262f, 0x00222830, 0x00242b34, 0x00252c36, 0x00262d38, 0x00283039, 0x0029303c, 0x002a303c, 0x0029303c, 0x002c323f, 0x002f3542, 0x00303844, 0x002d3541, 0x002b333d, 0x0028303b, 0x00282f3a, 0x00282f3b, 0x0029303a, 0x002b313b, 0x002c343f, 0x002e3642, 0x002f3744, 0x00303844, 0x00313a47, 0x00343c49, 0x0038404c, 0x0038424f, 0x0038434f, 0x0038424e, 0x00394450, 0x003b4553, 0x003c4654, 0x003c4755, 0x003c4554, 0x003c4451, 0x003a424f, 0x003a4250, 0x003c4451, 0x003c4553, 0x003d4754, 0x003f4857, 0x003f4858, 0x00404858, 0x00404858, 0x00404858, 0x003f4756, 0x003d4454, 0x003e4454, 0x003d4453, 0x003c4351, 0x003c4250, 0x003c4350, 0x003e4451, 0x003d4451, 0x003d4451, 0x003e4552, 0x003d4452, 0x003e4450, 0x003f4450, 0x003e4450, 0x003d4450, 0x003c4450, 0x003c4451, 0x00424858, 0x00444b59, 0x00414857, 0x00404857, 0x003f4757, 0x003f4758, 0x00404858, 0x00404858, 0x00404858, 0x00404858, 0x00404757, 0x003e4454, 0x003d4454, 0x003d4454, 0x003c4452, 0x003a404f, 0x0039404d, 0x0039404d, 0x0038414e, 0x0038404c, 0x00353c49, 0x00323945, 0x00313944, 0x00333a45, 0x00353b48, 0x00363c49, 0x00353b48, 0x00333b46, 0x00303844, 0x002f3742, 0x002f3441, 0x002e3440, 0x002f3440, 0x00303742, 0x002f3540, 0x002c333f, 0x002c333f, 0x002c333f, 0x002c3440, 0x002b333e, 0x0029303c, 0x00282f3b, 0x00282e38, 0x00242c34, 0x00212933, 0x00202a34, 0x00202934, 0x00212834, 0x00202833, 0x00212832, 0x00212832, 0x00202730, 0x001f262f, 0x0020262f, 0x00202730, 0x001f2730, 0x001e2730, 0x00212b34, 0x00242e38, 0x00242e38, 0x00222c36, 0x00232d38, 0x00252f3b, 0x00252f3c, 0x0027303d, 0x0028313e, 0x0028303d, 0x0028303d, 0x0029323e, 0x002a323e, 0x0028303b, 0x00252c37, 0x00242a33, 0x0021282f, 0x001d242c, 0x00191f27, 0x00141b22, 0x001c242c, 0x00253239, 0x00202f37, 0x001e2c35, 0x001f2d38, 0x001e2c35, 0x001b2832, 0x001c2832, 0x00141e28, 0x000c1620, 0x000d1820, 0x00111b22, 0x00141c24, 0x00141c23, 0x00151d24, 0x00151e24, 0x00141d24, 0x00161e27, 0x0019222b, 0x001f2831, 0x00242d38, 0x00242f39, 0x00202b35, 0x001e2833, 0x001d2833, 0x00202b37, 0x0024303c, 0x00283542, 0x002b3846, 0x002c3a4a, 0x002c3c4c, 0x002c3d4c, 0x002c3e4c, 0x002c3f4e, 0x00304252, 0x00304454, 0x002f4454, 0x002f4555, 0x00304655, 0x00304556, 0x002d4252, 0x00243848, 0x00182b39, 0x00122331, 0x00122130, 0x0011202c, 0x000f1d2a, 0x000d1c28, 0x000e1b27, 0x000e1b25, 0x000e1c25, 0x000d1c25, 0x000f1c25, 0x00101c26, 0x00101c26, 0x00101d27, 0x00101d27, 0x00111d27, 0x00111d27, 0x00121e28, 0x00131f28, 0x00131f28, 0x00131f28, 0x00131f28, 0x00121e28, 0x00121e28, 0x00121e28, 0x00111c27, 0x00101c26, 0x00101b25, 0x000f1a23, 0x000e1922, 0x000e1822, 0x000d1821, 0x000c1720, 0x000b151e, 0x000b151e, 0x000b151e, 0x000a141d, 0x000a141d, 0x000b151e, 0x000b151e, 0x000a141d, 0x0009141c, 0x0009141c, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4245, 0x001b4649, 0x001d4b4e, 0x0020616f, 0x002c9bc0, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002fa3ca, 0x0030a3ca, 0x0030a4ca, 0x0030a4ca, 0x0030a4ca, 0x0030a4ca, 0x0030a4ca, 0x0030a3ca, 0x0030a3ca, 0x0030a3ca, 0x002fa3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002ea3ca, 0x002da2ca, 0x002da2ca, 0x002ca1ca, 0x002ca2cb, 0x002994b8, 0x001d4c50, 0x001b4649, 0x001a4245, 0x00183d41, 0x0017383c, 0x00153439, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010212c, 0x0010202c, 0x0010202f, 0x00102130, 0x0010202f, 0x0010202f, 0x0010202f, 0x0010202d, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x000f202b, 0x000e202b, 0x000e202b, 0x000e202b, 0x000e202b, 0x0011212c, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0014222d, 0x0014222d, 0x0014222d, 0x0014222d, 0x0014222d, 0x00142230, 0x00132231, 0x00132231, 0x00132231, 0x00132231, 0x00122230, 0x00102130, 0x0010212f, 0x0010202c, 0x0010202c, 0x0010202b, 0x00111f2b, 0x00111f2b, 0x00101e29, 0x00101e29, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a25, 0x000d1b24, 0x000d1b24, 0x000e1c26, 0x0012202b, 0x001c2835, 0x0028333f, 0x00242f39, 0x001c2630, 0x0019212c, 0x001c232e, 0x00212833, 0x00212934, 0x00202934, 0x001c2630, 0x0019232e, 0x001a242f, 0x001e2a33, 0x001e2a33, 0x001c272f, 0x001b252e, 0x001c2730, 0x001c2730, 0x001a242d, 0x0019222c, 0x00202833, 0x0028323d, 0x002e3844, 0x00303945, 0x002f3b47, 0x00303c48, 0x002f3b47, 0x002c3a44, 0x002c3842, 0x002a3540, 0x0025303a, 0x00263038, 0x00262e38, 0x00202832, 0x00202730, 0x00212832, 0x00222832, 0x00202830, 0x001f2730, 0x00202830, 0x00222a33, 0x00242c35, 0x00242c37, 0x00272f3a, 0x0028303c, 0x00292f3b, 0x00272d39, 0x00272d39, 0x002c313d, 0x002f3641, 0x002f3741, 0x002c343e, 0x00272f3a, 0x00252d38, 0x00252d38, 0x00252d36, 0x00282f38, 0x002b313c, 0x002e3440, 0x00303543, 0x00303644, 0x00313845, 0x00343c48, 0x00373f4c, 0x0038404c, 0x0037404d, 0x0038414e, 0x00394350, 0x003c4553, 0x003e4856, 0x003f4957, 0x003f4957, 0x003d4654, 0x003c4453, 0x003c4553, 0x003d4755, 0x003e4856, 0x003e4957, 0x00404b5a, 0x00424c5d, 0x00444c5e, 0x00434c5d, 0x00424b5b, 0x003e4754, 0x003d4553, 0x003d4552, 0x003d4551, 0x003d4551, 0x003f4753, 0x003f4654, 0x00404754, 0x00404755, 0x003f4754, 0x003e4653, 0x003d4552, 0x003d4451, 0x003e4452, 0x00404654, 0x00404854, 0x003f4654, 0x003c4452, 0x00444c5a, 0x00464e5c, 0x00414a58, 0x00404a58, 0x00404958, 0x00404858, 0x0041495a, 0x00424a58, 0x00424b59, 0x00404857, 0x00404756, 0x003f4454, 0x003e4654, 0x00404755, 0x003f4554, 0x003c4251, 0x003c4250, 0x003c424f, 0x003a424f, 0x0038404d, 0x00353d4a, 0x00333b47, 0x00323a45, 0x00333b46, 0x00363c49, 0x00363c49, 0x00363c49, 0x00343c47, 0x00313a44, 0x00303843, 0x00303643, 0x002f3440, 0x002e3440, 0x00303541, 0x00303540, 0x002d333e, 0x002b333e, 0x0028333d, 0x0027323c, 0x0028323c, 0x0027313c, 0x0028313c, 0x0028313a, 0x00252f37, 0x00222c35, 0x00222c37, 0x00242d38, 0x00242e39, 0x00252e39, 0x00252d38, 0x00242c37, 0x00212a33, 0x00202830, 0x0020262f, 0x001e242e, 0x001d242e, 0x00202831, 0x00242d36, 0x00242d36, 0x0027303a, 0x00242e38, 0x00242e39, 0x00252f3c, 0x00242e3b, 0x0027303c, 0x0028323f, 0x0027303c, 0x0025303c, 0x0028323c, 0x0029313c, 0x00272f3a, 0x00242b36, 0x00242a33, 0x00222930, 0x0020262e, 0x001a2128, 0x00131c21, 0x00152025, 0x00233137, 0x0024343b, 0x001a2c33, 0x001d2c36, 0x00202e38, 0x001f2b34, 0x001f2a34, 0x0016202a, 0x000d1720, 0x000a141d, 0x000c161e, 0x00101a21, 0x00151f26, 0x00182229, 0x00182229, 0x0018222a, 0x001a242d, 0x001e2831, 0x00202a34, 0x00202b34, 0x001e2833, 0x001d2733, 0x001f2834, 0x00202a36, 0x00242d3a, 0x00283240, 0x00283544, 0x002b3846, 0x002b3848, 0x002b3a48, 0x002b3a48, 0x002b3a49, 0x002c3d4c, 0x00304152, 0x00304455, 0x00304758, 0x00324a5a, 0x00324a5a, 0x00314858, 0x002c4150, 0x00243746, 0x00172837, 0x0012212f, 0x0011202c, 0x00101e2a, 0x000f1c28, 0x000e1b27, 0x000e1a26, 0x000d1a25, 0x000c1b24, 0x000c1b24, 0x000d1c25, 0x000f1c26, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101e28, 0x00121e28, 0x00121e28, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f28, 0x00121e28, 0x00111d27, 0x00101c26, 0x000f1a24, 0x000e1a24, 0x000e1a24, 0x000c1822, 0x000c1821, 0x000c161f, 0x000b151e, 0x000b151e, 0x0009141c, 0x0009141d, 0x000a141d, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00132c32, 0x00143036, 0x00153439, 0x00183a3e, 0x00183f43, 0x001a4347, 0x001c484c, 0x001e4d50, 0x00237085, 0x002da3cb, 0x0028819c, 0x00267081, 0x00277282, 0x00277383, 0x00277484, 0x00277484, 0x00287484, 0x00287484, 0x00277484, 0x00277484, 0x00287484, 0x00277484, 0x00267383, 0x00277383, 0x00277282, 0x00267181, 0x00257181, 0x00267081, 0x00267081, 0x00267081, 0x00267081, 0x00267081, 0x00267081, 0x00267081, 0x00267181, 0x00267081, 0x00257081, 0x00257080, 0x00256e80, 0x00246d7f, 0x002991b2, 0x002a9ac0, 0x001d4d51, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00143439, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010212c, 0x0010212c, 0x0010212f, 0x00102130, 0x00102030, 0x0010202f, 0x0010202f, 0x0010202d, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x000f202b, 0x000d202b, 0x000d202b, 0x000d202b, 0x000e202b, 0x0011212c, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0014232e, 0x0014232e, 0x0015232e, 0x0015232e, 0x00142331, 0x00142433, 0x00142433, 0x00142433, 0x00142333, 0x00132331, 0x000f2230, 0x000f222f, 0x0010202c, 0x0010202c, 0x0011202b, 0x00111f2b, 0x00111f2b, 0x00101e29, 0x00101e29, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000d1a26, 0x000d1a26, 0x000c1a26, 0x000c1925, 0x000d1a25, 0x000d1b24, 0x000d1b24, 0x000e1c26, 0x00111f2a, 0x00182532, 0x0025303c, 0x0028303a, 0x001f2731, 0x001c212d, 0x001e2430, 0x00212833, 0x00212833, 0x001c262f, 0x001b242d, 0x0018222c, 0x0018222c, 0x001c2730, 0x001c2830, 0x001a252d, 0x001c262f, 0x001d2830, 0x001f2831, 0x001b252e, 0x0019232c, 0x00202830, 0x0029323c, 0x002e3844, 0x002f3a46, 0x002f3b48, 0x00303c48, 0x002f3c48, 0x002c3a45, 0x002b3944, 0x002a3641, 0x0025313c, 0x0028333c, 0x00273038, 0x00202832, 0x00202932, 0x00202830, 0x0020282f, 0x00202831, 0x00222c34, 0x00242e37, 0x00252d37, 0x00262e38, 0x00262f38, 0x0028313c, 0x002a333d, 0x0029313c, 0x00262f39, 0x00252e38, 0x00272f38, 0x002a323b, 0x002c353e, 0x002c343e, 0x0028303b, 0x00262e38, 0x00252e38, 0x00252d36, 0x00282d38, 0x002a303a, 0x002d333e, 0x002e3440, 0x002f3442, 0x00313845, 0x00343c48, 0x00343c49, 0x00353d4a, 0x00363e4b, 0x0036404c, 0x00384250, 0x003c4654, 0x003f4958, 0x003f4a58, 0x00404b59, 0x00404958, 0x003f4858, 0x003e4857, 0x00404958, 0x00404a59, 0x00404c5a, 0x00414e5d, 0x00445061, 0x00465062, 0x00485163, 0x00444d5d, 0x003d4754, 0x003e4754, 0x003e4652, 0x003c4550, 0x003d4652, 0x00414a57, 0x00414957, 0x00404857, 0x00414958, 0x00414958, 0x00404854, 0x003f4754, 0x00404754, 0x00404754, 0x00414855, 0x00444b59, 0x00434b59, 0x003d4554, 0x00434b59, 0x00454c5c, 0x00414b59, 0x00434c5b, 0x00424b5b, 0x00404858, 0x00424a5b, 0x00444c5b, 0x00424c5a, 0x00404a58, 0x00414958, 0x00414857, 0x00404856, 0x00404856, 0x003f4655, 0x003c4251, 0x003c4250, 0x003c4350, 0x003b4350, 0x003a424f, 0x0038404c, 0x00353d49, 0x00343c47, 0x00343c48, 0x00363c49, 0x00353c48, 0x00353c48, 0x00333a46, 0x00303844, 0x00303742, 0x00303643, 0x002f3441, 0x002e343f, 0x002f3540, 0x002f3540, 0x002c333e, 0x002b343e, 0x0028343d, 0x0024303b, 0x0024303a, 0x0027323c, 0x0028323c, 0x0027313b, 0x0027313a, 0x0028333c, 0x002a3440, 0x002a3440, 0x00293440, 0x00293340, 0x0027313c, 0x0026303a, 0x00232c36, 0x00212834, 0x00212832, 0x00202831, 0x001e2630, 0x00232b34, 0x0028303a, 0x00263039, 0x0028323d, 0x0026303a, 0x0026303b, 0x0028313e, 0x0027303d, 0x0028323e, 0x0029333f, 0x0026303c, 0x00242e39, 0x0026303b, 0x0028303b, 0x00262e38, 0x00242a35, 0x00232932, 0x00222830, 0x0020272e, 0x001a2028, 0x00141c22, 0x00121d23, 0x00202d34, 0x00283940, 0x001b2c34, 0x001a2933, 0x00202d37, 0x00202c36, 0x001e2833, 0x001b242f, 0x00151f28, 0x00121c24, 0x00111c22, 0x00111c23, 0x00141f27, 0x0019232c, 0x001b252f, 0x001b2530, 0x001b2530, 0x001e2833, 0x001e2833, 0x001b2630, 0x001b2530, 0x001d2833, 0x00202a37, 0x00242d39, 0x0026303c, 0x002b3542, 0x002d3947, 0x002d3b49, 0x002c3948, 0x002a3846, 0x00293845, 0x00293946, 0x002c3c4c, 0x002f4051, 0x002f4354, 0x002f4858, 0x00304a5a, 0x00344b5c, 0x00304656, 0x00293c4c, 0x001f313f, 0x00152533, 0x0010202c, 0x00101f2a, 0x000f1c28, 0x000e1c27, 0x000e1b26, 0x000d1925, 0x000d1925, 0x000c1b24, 0x000c1b24, 0x000d1c25, 0x000f1c26, 0x00101d27, 0x00101e28, 0x00101e28, 0x00111e28, 0x00121e28, 0x00121e28, 0x0014202a, 0x0014202a, 0x0014202a, 0x0014202a, 0x0014202a, 0x00131f29, 0x00131f29, 0x00121e28, 0x00111d27, 0x00111c27, 0x00101b25, 0x000e1a24, 0x000e1a24, 0x000c1823, 0x000c1822, 0x000c1720, 0x000b161f, 0x000b151e, 0x0009141c, 0x0009141d, 0x000a141d, 0x000b151e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00122c32, 0x00143036, 0x0015363b, 0x00173a3e, 0x00194044, 0x001b4448, 0x001c4a4d, 0x001e4f51, 0x00247286, 0x002ea3ca, 0x0026768a, 0x00245c5f, 0x00245e60, 0x00245f61, 0x00256163, 0x00256163, 0x00266264, 0x00266264, 0x00256163, 0x00256163, 0x00256163, 0x00246062, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x00235a5c, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0022585b, 0x00215659, 0x00288baa, 0x002a9ac0, 0x001d4f53, 0x001c484c, 0x001b4448, 0x00183f43, 0x00183a3e, 0x0015363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010202c, 0x0010202c, 0x0010202f, 0x0010202f, 0x0010202f, 0x00102130, 0x00102130, 0x0010202e, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202c, 0x000e212c, 0x000e212c, 0x000f222c, 0x000f222c, 0x0011222c, 0x0011232d, 0x0012232d, 0x0014232e, 0x0014232e, 0x0014232e, 0x0014232e, 0x0014232e, 0x0015232e, 0x0015232e, 0x00142331, 0x00142433, 0x00142433, 0x00142433, 0x00142433, 0x00132332, 0x00102330, 0x00102330, 0x0010212e, 0x0010212e, 0x0012202d, 0x0013202d, 0x0013202c, 0x00111f2c, 0x00111f2c, 0x00101e2a, 0x000e1d28, 0x000e1d28, 0x000f1d28, 0x000f1c28, 0x000e1c28, 0x000c1b26, 0x000c1a26, 0x000c1924, 0x000b1824, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1b25, 0x00101e28, 0x00182430, 0x00242f3b, 0x002a313c, 0x00242a34, 0x00202630, 0x00202732, 0x00222833, 0x00222832, 0x001e2830, 0x001c242f, 0x001a232d, 0x0019232c, 0x001b252e, 0x001b262f, 0x0019242c, 0x001c262f, 0x001e2830, 0x00202a33, 0x001d2730, 0x001a232c, 0x00202932, 0x0028333d, 0x002d3844, 0x002f3b47, 0x00303c48, 0x00313c48, 0x00303c48, 0x002c3a46, 0x002b3844, 0x00283440, 0x0025313c, 0x0026313b, 0x00252e37, 0x00202831, 0x00232c34, 0x001e2630, 0x001d252e, 0x001d2730, 0x00232c35, 0x0028323b, 0x0029343c, 0x0029333c, 0x0028323b, 0x0029343c, 0x002b343e, 0x002b333d, 0x0028313c, 0x00272f39, 0x00272f38, 0x00283039, 0x0028303a, 0x002a323c, 0x0029313c, 0x0028303b, 0x0028303a, 0x00272f38, 0x00282e39, 0x00293039, 0x002c323c, 0x002c323d, 0x002c333f, 0x002d3540, 0x002f3844, 0x00323a47, 0x00343c49, 0x00353d4a, 0x0037404c, 0x00394351, 0x003c4655, 0x003e4858, 0x00404a5a, 0x00414c5c, 0x00434c5d, 0x00454f5f, 0x00434c5d, 0x00444d5f, 0x00455060, 0x00445060, 0x00445162, 0x00485364, 0x00485365, 0x00495364, 0x00444e5e, 0x00404957, 0x00404855, 0x00404854, 0x003e4653, 0x003f4854, 0x00434c59, 0x00444c5b, 0x00434b5a, 0x00444c5b, 0x00434a59, 0x00404857, 0x00414857, 0x00434958, 0x00404857, 0x00424a58, 0x00444c5b, 0x00474f5d, 0x00414958, 0x00424a5a, 0x00444c5c, 0x00424c5c, 0x00444d5c, 0x00444c5c, 0x00444c5c, 0x00454d5e, 0x00475060, 0x00444e5d, 0x00444d5c, 0x0048505f, 0x00495160, 0x00444d5c, 0x00404958, 0x00404755, 0x003c4351, 0x003c4251, 0x003c4250, 0x003b4350, 0x003b4350, 0x003b4350, 0x0039414e, 0x00373f4b, 0x00343c48, 0x00343b48, 0x00333947, 0x00313844, 0x00303742, 0x002e3641, 0x002e3641, 0x00303542, 0x002f3441, 0x002d343f, 0x002f3440, 0x002f3540, 0x002c333e, 0x002c3440, 0x002b3640, 0x00293540, 0x0026323c, 0x0028343d, 0x0028343d, 0x002a353f, 0x002c3841, 0x002b3641, 0x002c3844, 0x002c3844, 0x002c3844, 0x002c3743, 0x00293440, 0x0026303b, 0x00242d38, 0x00232c37, 0x00272e39, 0x0028303b, 0x00242c37, 0x00242c37, 0x00262e3a, 0x0027303c, 0x00293440, 0x0028323d, 0x0028333d, 0x002b3441, 0x002b3441, 0x002b3441, 0x002a3440, 0x0026303c, 0x00222c38, 0x00242e38, 0x00272f39, 0x00262e38, 0x00242b35, 0x00232933, 0x00222831, 0x001f262e, 0x00192028, 0x00141c23, 0x00121d23, 0x001f2c33, 0x00293a40, 0x001e2f36, 0x00182730, 0x001a2731, 0x001e2a34, 0x001e2833, 0x001e2731, 0x001c242f, 0x0019222b, 0x00182228, 0x00162028, 0x00162028, 0x0018212c, 0x001a242e, 0x0018242e, 0x0018232d, 0x001c2731, 0x001c2831, 0x001b2630, 0x001d2833, 0x00202936, 0x00232c38, 0x0026303c, 0x0029323f, 0x002d3844, 0x00303c4a, 0x00303d4c, 0x002e3b4a, 0x002b3846, 0x00293845, 0x00293846, 0x002b3c4b, 0x002e4050, 0x002d4354, 0x002e4758, 0x00304858, 0x00324a5a, 0x002f4454, 0x00233745, 0x00182a38, 0x0011212e, 0x000f1f2a, 0x000e1d28, 0x000f1c28, 0x000e1c27, 0x000d1a26, 0x000d1925, 0x000d1a25, 0x000c1b24, 0x000c1c25, 0x000e1c26, 0x00101d27, 0x00101e28, 0x00101e28, 0x00111f28, 0x00111f29, 0x00111f29, 0x00122029, 0x0014202c, 0x0014202c, 0x0014202c, 0x0015202c, 0x0015202c, 0x0014202c, 0x0014202b, 0x00131f2a, 0x00121e29, 0x00111d28, 0x00101c27, 0x00101b27, 0x000f1a26, 0x000e1a25, 0x000d1924, 0x000c1821, 0x000c1720, 0x000b161f, 0x000b151e, 0x000b151e, 0x000a151f, 0x000a161e, 0x000a151d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00122c32, 0x00153036, 0x0016363b, 0x00173c40, 0x00194044, 0x001b4649, 0x001d4b4e, 0x001e4f51, 0x00247286, 0x002ea3ca, 0x0027778a, 0x00245d60, 0x00245f61, 0x00256163, 0x00256264, 0x00256364, 0x00256364, 0x00256364, 0x00256364, 0x00256364, 0x00256264, 0x00256163, 0x00246062, 0x00245f61, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00245c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x0021585b, 0x0021575a, 0x00298dac, 0x002a9ac0, 0x001d4f53, 0x001c484c, 0x001b4448, 0x00183f43, 0x00183a3e, 0x0015363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010202c, 0x0010202c, 0x0010202e, 0x0010202f, 0x0010202f, 0x00102130, 0x00102130, 0x0010202e, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010212c, 0x000f222c, 0x000f222c, 0x0010232d, 0x0010232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0014242e, 0x0014242f, 0x0014242e, 0x0014232e, 0x0013232e, 0x0014232e, 0x0014232e, 0x00142331, 0x00142433, 0x00142433, 0x00142433, 0x00142433, 0x00142433, 0x00112432, 0x00112432, 0x0011232f, 0x0011232f, 0x0013212e, 0x0014202e, 0x0014202e, 0x0013202d, 0x0013202d, 0x00101f2b, 0x000e1e28, 0x000e1d28, 0x00101d28, 0x00101d28, 0x000e1c28, 0x000c1b26, 0x000c1b26, 0x000b1824, 0x000b1824, 0x000b1824, 0x000c1924, 0x000c1924, 0x000d1b24, 0x00111e28, 0x00182530, 0x0025303c, 0x002c3541, 0x002b323d, 0x00272c38, 0x00242a35, 0x00242a34, 0x00242c34, 0x00222a34, 0x001d2530, 0x001b2430, 0x0019232f, 0x001b252f, 0x001b252e, 0x0019242c, 0x001e2830, 0x001f2831, 0x00202a32, 0x001c262e, 0x0018232c, 0x00212c34, 0x0029343f, 0x002d3844, 0x002f3c48, 0x00313d49, 0x00323d49, 0x00303d48, 0x002e3c47, 0x002c3945, 0x00283440, 0x0025313c, 0x00243039, 0x00222c34, 0x00212a33, 0x00232c34, 0x001f2730, 0x001d252f, 0x001b242d, 0x001f2831, 0x00212c34, 0x00242d37, 0x0027313a, 0x0028323b, 0x0029333c, 0x0028333c, 0x0029323c, 0x0029323c, 0x0029323c, 0x0028303a, 0x00283038, 0x00273038, 0x00283039, 0x0028313c, 0x00262f39, 0x00242d38, 0x00272e38, 0x00292f3a, 0x00282f39, 0x0029303b, 0x00282e3a, 0x0028303b, 0x002a323c, 0x002c3440, 0x00303845, 0x00343c49, 0x00353d4a, 0x00353e4b, 0x0036404e, 0x003a4453, 0x003c4757, 0x00404a5a, 0x00424d5d, 0x00445060, 0x00465061, 0x00445061, 0x00465062, 0x00455163, 0x00455263, 0x00475465, 0x004a5468, 0x004a5568, 0x004a5568, 0x00455060, 0x00424d5c, 0x00434c59, 0x00424b58, 0x00404a58, 0x00424c5a, 0x00475060, 0x00485261, 0x00464f5f, 0x00485060, 0x00424a5a, 0x00404859, 0x00444b5c, 0x00454c5c, 0x00434a5b, 0x00434b5b, 0x00454d5c, 0x00485060, 0x00485060, 0x00444c5e, 0x00464e5f, 0x00444e5f, 0x00454e5f, 0x00454e5f, 0x00485061, 0x00485263, 0x00485262, 0x00465060, 0x00444e5e, 0x00485060, 0x00495261, 0x00485160, 0x00454f5e, 0x00444c5b, 0x00414757, 0x00404654, 0x003e4554, 0x003c4451, 0x003c4450, 0x003c4451, 0x0039414e, 0x00373f4c, 0x00343c48, 0x00343b48, 0x00323846, 0x00313844, 0x002f3742, 0x002e3641, 0x002f3641, 0x00303542, 0x00303542, 0x002f3540, 0x002f3540, 0x002e3440, 0x002c333e, 0x002c333e, 0x002a343f, 0x002a343f, 0x0027313c, 0x0026303b, 0x0027313c, 0x0028353f, 0x002c3842, 0x002b3843, 0x002a3844, 0x002a3844, 0x002c3844, 0x002b3843, 0x0026313c, 0x00242f39, 0x00222d38, 0x00212b35, 0x00232c36, 0x00262e39, 0x0028303c, 0x0029313d, 0x002a313f, 0x002b3441, 0x002b3441, 0x0028323e, 0x002a343e, 0x002c3542, 0x002c3542, 0x002c3542, 0x002b3441, 0x002a3440, 0x0026303c, 0x00232e38, 0x00242d38, 0x00242d38, 0x00242b36, 0x00232933, 0x00232933, 0x00202730, 0x001c222a, 0x00141d23, 0x00141f24, 0x001e292f, 0x002c383f, 0x0024333a, 0x001a2831, 0x0016222c, 0x0019252f, 0x001c2731, 0x001f2832, 0x001f2730, 0x001c252d, 0x001a232a, 0x00182028, 0x00162028, 0x00172029, 0x0018202c, 0x0018212c, 0x0018242e, 0x001c2831, 0x001c2832, 0x00202a34, 0x00202a36, 0x00222c38, 0x00252f3c, 0x0029323f, 0x002e3643, 0x00313c48, 0x0034404d, 0x0033404e, 0x00303d4c, 0x002c3947, 0x00293845, 0x00293947, 0x002b3c4c, 0x002d4050, 0x002c4253, 0x002c4454, 0x002d4656, 0x002f4657, 0x002b4050, 0x001e3140, 0x00132432, 0x000e1f2c, 0x000d1d29, 0x000e1c28, 0x000f1c28, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1a25, 0x000c1c25, 0x000d1c26, 0x000f1d27, 0x00101d27, 0x00101e28, 0x00111f29, 0x00111f29, 0x00111f29, 0x00122029, 0x0013202a, 0x0014212c, 0x0014222d, 0x0015212d, 0x0016212d, 0x0016212d, 0x0015202c, 0x0015202c, 0x0014202c, 0x00131f2b, 0x00121e2a, 0x00111c28, 0x00101c28, 0x00101b27, 0x000e1a26, 0x000d1925, 0x000c1822, 0x000c1820, 0x000c1720, 0x000c161f, 0x000c161f, 0x000a151f, 0x000a161e, 0x000a151d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x000f2229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00153036, 0x0016363b, 0x00183c40, 0x001a4044, 0x001b4649, 0x001d4b4e, 0x001f5053, 0x00247286, 0x002ea3ca, 0x0027778a, 0x00245d60, 0x00245f61, 0x00266163, 0x00256264, 0x00256364, 0x00276466, 0x00276466, 0x00276466, 0x00266466, 0x00256364, 0x00256264, 0x00256163, 0x00246062, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0022595c, 0x00277c94, 0x002ca0c8, 0x00288eaf, 0x001d4c50, 0x001c484c, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00143439, 0x00143036, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010202c, 0x0010202c, 0x0010202e, 0x0010202f, 0x0010212f, 0x00112130, 0x00112130, 0x0011202d, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010212c, 0x0010232d, 0x0010232d, 0x0011232d, 0x0011232d, 0x0012232d, 0x0012232d, 0x0012232e, 0x0014242e, 0x0014242f, 0x0014242f, 0x0014242f, 0x0014242f, 0x00142430, 0x00142430, 0x00142433, 0x00152434, 0x00152434, 0x00152434, 0x00152434, 0x00142433, 0x00112432, 0x00112432, 0x00122430, 0x00122430, 0x0013222f, 0x0014212e, 0x0014212e, 0x0013202e, 0x0013202d, 0x00101f2c, 0x000e1e29, 0x000e1d29, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000c1b27, 0x000c1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1924, 0x000c1924, 0x000d1b25, 0x00101e28, 0x00182530, 0x00263340, 0x00303a48, 0x00303946, 0x002c333f, 0x00262c38, 0x00252c35, 0x00262c36, 0x00242c34, 0x001e2631, 0x001c2430, 0x001b2431, 0x001c2630, 0x001c2630, 0x001c2630, 0x00202b34, 0x00202b34, 0x001f2931, 0x001a242c, 0x0019242c, 0x00222c37, 0x002a3441, 0x002e3945, 0x00303c48, 0x00333e4a, 0x00343f4b, 0x00323f4a, 0x00303e49, 0x002f3c48, 0x002a3743, 0x0025323d, 0x00222e39, 0x00202b34, 0x00242d36, 0x00242d36, 0x00222a33, 0x00202932, 0x00202a32, 0x00232c34, 0x00242d36, 0x00242d36, 0x00263038, 0x00263039, 0x00263038, 0x00263038, 0x00263039, 0x0029333c, 0x0029333c, 0x0028323b, 0x00283039, 0x00283038, 0x00283039, 0x00273039, 0x00242c37, 0x00232c36, 0x00232c34, 0x00242c36, 0x00242c35, 0x00252d38, 0x00242c37, 0x00252d38, 0x0028303b, 0x002c343f, 0x00303643, 0x00333a46, 0x00343c48, 0x00353e4b, 0x0038414f, 0x003b4453, 0x003e4858, 0x00404b5a, 0x00424d5c, 0x0044505f, 0x00445060, 0x00445061, 0x00465264, 0x00485466, 0x00485667, 0x00485567, 0x004b586a, 0x004c596c, 0x004c5869, 0x00455060, 0x00444f5c, 0x0044505c, 0x00444f5c, 0x00434e5d, 0x00444f5f, 0x00485364, 0x004a5566, 0x004a5465, 0x00485062, 0x0041495a, 0x00464e5e, 0x00495061, 0x00495061, 0x00474e5f, 0x00464d5e, 0x00475060, 0x00495161, 0x004b5464, 0x00495264, 0x00495264, 0x00485264, 0x00475163, 0x00465062, 0x00485364, 0x00495364, 0x00485262, 0x00454f5f, 0x00434d5c, 0x00465060, 0x00485363, 0x00485464, 0x00475261, 0x00454f5f, 0x00444c5b, 0x00424b5a, 0x00414a58, 0x003f4755, 0x003c4452, 0x003a414e, 0x00373e4b, 0x00343c48, 0x00313946, 0x00303844, 0x00313845, 0x00313845, 0x00303844, 0x002f3843, 0x002f3743, 0x00303642, 0x00303743, 0x00303743, 0x00303742, 0x002e3541, 0x002d3440, 0x002a313c, 0x0027303c, 0x0025303a, 0x00242f38, 0x0026303a, 0x0027323c, 0x002b3740, 0x002f3c46, 0x002f3c47, 0x002b3a44, 0x00293843, 0x002b3a44, 0x002a3842, 0x0027343e, 0x0027343f, 0x00232e3a, 0x00222c38, 0x00262f39, 0x002c343f, 0x00303844, 0x00313b47, 0x00303a46, 0x002e3844, 0x002a3441, 0x0028313d, 0x0029333e, 0x002b3441, 0x002c3542, 0x002c3543, 0x002c3643, 0x002c3542, 0x00293440, 0x0024303a, 0x00242d38, 0x00242c38, 0x00242a35, 0x00242934, 0x00242934, 0x00232833, 0x001f252e, 0x00171f26, 0x00141e24, 0x0019232b, 0x0028333b, 0x0029363f, 0x001e2a34, 0x0016222c, 0x0014202a, 0x001a242e, 0x0019222c, 0x001a232c, 0x001a232a, 0x00182027, 0x00141c24, 0x00141c24, 0x00161d26, 0x00181f29, 0x001b232d, 0x001c2630, 0x001d2831, 0x001f2934, 0x00212b35, 0x00232b37, 0x00242c38, 0x00262e39, 0x002b323e, 0x00303644, 0x00333c49, 0x00364250, 0x00344250, 0x00303e4e, 0x002c3a48, 0x00293847, 0x002a3a48, 0x002c3c4c, 0x002c4050, 0x002a4051, 0x002a4252, 0x002c4454, 0x002d4454, 0x00283c4c, 0x001b2c3b, 0x00122330, 0x000d1e2a, 0x000d1d28, 0x000d1c27, 0x000e1c27, 0x000c1a26, 0x000c1925, 0x000c1925, 0x000c1a25, 0x000c1c26, 0x000d1d27, 0x000f1d27, 0x00101e28, 0x00111f29, 0x0012202a, 0x0012202a, 0x0013212b, 0x0013212b, 0x0014212b, 0x0014222d, 0x0014222d, 0x0015222d, 0x0016212d, 0x0016212d, 0x0015212c, 0x0014202c, 0x0014202b, 0x00131f2b, 0x00131f2a, 0x00111d28, 0x00101c28, 0x00101b26, 0x000e1a25, 0x000d1924, 0x000c1822, 0x000c1820, 0x000c1720, 0x000c1620, 0x000c161f, 0x000b151f, 0x000a151e, 0x000a141e, 0x000a141e, 0x000a141e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00122c32, 0x00143036, 0x0015363b, 0x00183c40, 0x00194044, 0x001b4649, 0x001d4b4e, 0x001e4f51, 0x00247286, 0x002ea3ca, 0x0027778a, 0x00245c5f, 0x00245f61, 0x00256163, 0x00256264, 0x00256364, 0x00276466, 0x00276466, 0x00276466, 0x00276466, 0x00266466, 0x00256364, 0x00256264, 0x00266163, 0x00246062, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x00235a5c, 0x00225b60, 0x0028839c, 0x002da0c8, 0x00288cab, 0x001f575f, 0x001d4b4e, 0x001c474b, 0x001a4245, 0x00183d41, 0x0017383c, 0x00153439, 0x00142e34, 0x00122c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010212c, 0x0010212c, 0x0010212c, 0x0010212d, 0x0010212d, 0x0012212d, 0x0012212c, 0x0011202c, 0x0010202b, 0x0010202b, 0x0010202b, 0x0011202c, 0x0011222c, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0013232e, 0x0014232e, 0x0014232e, 0x0014242e, 0x0014242f, 0x00142430, 0x00142431, 0x00142431, 0x00142532, 0x00152633, 0x00142634, 0x00142634, 0x00142634, 0x00142634, 0x00142634, 0x00132534, 0x00122433, 0x00122433, 0x00132431, 0x00132430, 0x00132430, 0x0012222f, 0x0012222f, 0x0011222f, 0x0010212e, 0x0010202c, 0x00101f2c, 0x000f1e2c, 0x00101e29, 0x00101e29, 0x00101d28, 0x000e1c28, 0x000e1b28, 0x000d1a28, 0x000c1a28, 0x000c1a28, 0x000c1926, 0x000c1925, 0x000c1a25, 0x00101e29, 0x00182531, 0x00273442, 0x00313e4c, 0x00343e4c, 0x00303644, 0x00282d3a, 0x00262a35, 0x00282c35, 0x00262c34, 0x001f2831, 0x001d2732, 0x001f2834, 0x001e2833, 0x001c2731, 0x001d2833, 0x00212c37, 0x00212c35, 0x001e2831, 0x0018232a, 0x0018232c, 0x00222c38, 0x002b3441, 0x00303a46, 0x00323d49, 0x0034404c, 0x0034404c, 0x0033404b, 0x00303e49, 0x00303c48, 0x002e3945, 0x00283440, 0x00222d38, 0x00222c36, 0x00242e37, 0x00252f38, 0x00202b34, 0x00242d36, 0x00242c34, 0x00262e37, 0x002b313b, 0x00283039, 0x00262d36, 0x00242c35, 0x00242c36, 0x00272f38, 0x0028313a, 0x0028333c, 0x0028343c, 0x0028333b, 0x00273139, 0x0027313a, 0x00263038, 0x00242d36, 0x00272f38, 0x0028303a, 0x0029313b, 0x00242c36, 0x00212a33, 0x00262e38, 0x00262d38, 0x00242c38, 0x00272f3a, 0x002a323d, 0x002f3641, 0x00303844, 0x00323a46, 0x0037404c, 0x003a4450, 0x003b4451, 0x003c4755, 0x003c4856, 0x003e4b58, 0x0044505e, 0x0044505f, 0x00455061, 0x00465364, 0x00495868, 0x004a5a6a, 0x00495868, 0x004c5b6c, 0x004e5c6d, 0x00495666, 0x00434f5d, 0x00424d5b, 0x0044505f, 0x00465060, 0x00485163, 0x00495566, 0x00495667, 0x004a5567, 0x00495465, 0x00495264, 0x00485063, 0x004b5464, 0x004d5667, 0x004c5667, 0x004b5466, 0x00485363, 0x004b5565, 0x004b5565, 0x00495464, 0x004d586a, 0x004e586c, 0x004c5868, 0x004a5768, 0x00475566, 0x00485466, 0x00485364, 0x00445060, 0x00455261, 0x00465260, 0x00485161, 0x00485362, 0x00485563, 0x00465460, 0x0043505d, 0x00414e5c, 0x00414c5c, 0x003e4856, 0x003c4554, 0x003a4350, 0x0038404c, 0x00383e4a, 0x00343c49, 0x00323a47, 0x00303844, 0x00303844, 0x00303844, 0x002f3744, 0x002f3744, 0x002f3744, 0x002f3743, 0x00303844, 0x00323a47, 0x00333b48, 0x002f3845, 0x002b3541, 0x0029323d, 0x0026313c, 0x0025303a, 0x00263039, 0x0028343c, 0x00293540, 0x002a3740, 0x002b3842, 0x002a3842, 0x00283640, 0x0025333c, 0x0025333c, 0x00283640, 0x002c3a44, 0x00303d48, 0x002f3a47, 0x002d3844, 0x002f3844, 0x002e3843, 0x00303b47, 0x00323d49, 0x00323d49, 0x002f3a46, 0x002a3440, 0x0027313c, 0x0029333d, 0x002b3440, 0x002c3543, 0x002c3643, 0x002d3844, 0x002c3644, 0x002b3441, 0x0027313c, 0x00262f39, 0x00252d38, 0x00242c37, 0x00242b36, 0x00242b36, 0x00242a34, 0x00202730, 0x001b212b, 0x00161e26, 0x00171e28, 0x00212b34, 0x002b3440, 0x00202a35, 0x0018232c, 0x00152028, 0x00182128, 0x00171f28, 0x00161e27, 0x00151f25, 0x00131c24, 0x00111a21, 0x00141a23, 0x00161c26, 0x001a212b, 0x001d262f, 0x001d2830, 0x001e2830, 0x00212934, 0x00242b36, 0x00272c37, 0x00262b35, 0x00262b34, 0x002a2f3a, 0x00303643, 0x00353e4b, 0x00364250, 0x00324250, 0x002f3f4f, 0x002a3b49, 0x00283a49, 0x002b3d4d, 0x002d4051, 0x002c4051, 0x00283e4e, 0x0029404e, 0x002a4150, 0x002b4150, 0x00263947, 0x00182a37, 0x0011222f, 0x000d1e29, 0x000e1d28, 0x000e1c27, 0x000e1c27, 0x000d1b26, 0x000d1b26, 0x000c1a26, 0x000c1a26, 0x000c1c27, 0x000d1c28, 0x000e1d28, 0x000f1f28, 0x00102029, 0x0011202a, 0x0011202a, 0x0012212b, 0x0012212b, 0x0012212b, 0x0014222d, 0x0014222d, 0x0014222d, 0x0015212d, 0x0014212d, 0x0014222c, 0x0014212b, 0x0014202b, 0x0014202a, 0x00131f28, 0x00111d27, 0x00101c26, 0x00101b25, 0x000e1a24, 0x000d1924, 0x000c1822, 0x000c1820, 0x000c1720, 0x000c1620, 0x000b151f, 0x000a141f, 0x000a141f, 0x000a141f, 0x000a141f, 0x000a141f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00132c32, 0x00143036, 0x0015363b, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001c484c, 0x001d4d50, 0x00247186, 0x002ea3ca, 0x0026778b, 0x00245c60, 0x00246063, 0x00246164, 0x00256366, 0x00266468, 0x00266568, 0x00276568, 0x00276669, 0x00276669, 0x00276569, 0x00266468, 0x00256468, 0x00266467, 0x00256163, 0x00246062, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00245c5e, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x00235a5c, 0x0022595c, 0x00225d62, 0x002988a6, 0x002da1c8, 0x002785a1, 0x001f555b, 0x001d4d50, 0x001c4a4d, 0x001b4649, 0x00194044, 0x00183c40, 0x0016363b, 0x00143338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010212c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0012212c, 0x0012212c, 0x0011202c, 0x0010202b, 0x0010202b, 0x0010202b, 0x0011202c, 0x0011222c, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0013232e, 0x0014232e, 0x0014232e, 0x0014242e, 0x0014242f, 0x00142430, 0x00142431, 0x00142431, 0x00142532, 0x00152633, 0x00142634, 0x00142734, 0x00142734, 0x00142734, 0x00142734, 0x00132534, 0x00122433, 0x00122433, 0x00132431, 0x00142431, 0x00132430, 0x0011232f, 0x0011232f, 0x0011232f, 0x0010222e, 0x0010202c, 0x00101f2c, 0x000f1e2c, 0x00101e29, 0x00101e29, 0x00101d29, 0x000e1c28, 0x000e1b28, 0x000d1a28, 0x000d1a28, 0x000d1a28, 0x000c1926, 0x000c1925, 0x000c1a25, 0x00101e29, 0x00182531, 0x00283542, 0x00344050, 0x00384252, 0x00343c4b, 0x002c303e, 0x00242733, 0x00272833, 0x00282c34, 0x00222a34, 0x00212c35, 0x00242c38, 0x00232c37, 0x001d2a34, 0x001e2b34, 0x00222d38, 0x00212c35, 0x001c272f, 0x00162028, 0x0018232c, 0x00222c38, 0x002b3440, 0x002f3945, 0x00323c49, 0x0034404c, 0x0034404c, 0x0032404b, 0x00303e49, 0x00303d48, 0x00303c48, 0x002d3844, 0x0026323d, 0x0028323d, 0x002b3640, 0x002b353f, 0x00242f38, 0x002c343e, 0x00262e38, 0x00272f39, 0x002a303a, 0x00272d37, 0x00242b34, 0x00232b34, 0x00242c35, 0x00272f38, 0x0028313a, 0x00263039, 0x00253139, 0x00253139, 0x00243038, 0x0028333c, 0x0028333c, 0x002a333c, 0x0029333c, 0x0029343c, 0x0029343c, 0x0028323b, 0x00242f38, 0x002a343d, 0x002e3741, 0x002e3641, 0x002d3540, 0x002e3640, 0x00313944, 0x00343c49, 0x00323c48, 0x00323c49, 0x003a4450, 0x003b4453, 0x003e4857, 0x003e4b58, 0x00414e5b, 0x00455260, 0x00475261, 0x00465162, 0x00485465, 0x00485768, 0x00485869, 0x00485868, 0x004c5b6c, 0x004a586a, 0x00465364, 0x00465161, 0x00455060, 0x00475262, 0x004a5565, 0x004d586a, 0x00505c6e, 0x004e5b6c, 0x004a5568, 0x00495467, 0x004c5869, 0x004c5768, 0x004c5666, 0x004e5868, 0x004c5768, 0x004b5667, 0x004a5767, 0x004d5969, 0x004d5868, 0x00495565, 0x004f5c6d, 0x00505c70, 0x004e5c6d, 0x004c5b6c, 0x004b5a6b, 0x004c5a6b, 0x004a5668, 0x00465364, 0x00485667, 0x00495465, 0x004a5464, 0x00485363, 0x00465361, 0x00414f5c, 0x003c4b58, 0x003d4b59, 0x003c4857, 0x00384250, 0x003a4452, 0x003b4451, 0x0038404b, 0x0038404b, 0x00343d4a, 0x00323b48, 0x00313a47, 0x00313a46, 0x00303946, 0x00323a47, 0x00313a46, 0x00303844, 0x00303845, 0x00303945, 0x00303946, 0x00303a46, 0x002e3945, 0x002b3642, 0x002a3440, 0x0029343e, 0x002a343f, 0x002a3640, 0x002b3740, 0x00293640, 0x0028353f, 0x00293741, 0x002b3844, 0x002f3c48, 0x00303e49, 0x0032404a, 0x00313f4b, 0x00303e49, 0x0032404c, 0x00303c49, 0x002e3947, 0x002f3b47, 0x00303c48, 0x00323e4b, 0x00323f4b, 0x00343f4c, 0x00303c48, 0x002b3643, 0x0029343f, 0x002b3440, 0x002c3541, 0x002c3743, 0x002d3844, 0x002d3844, 0x002c3644, 0x002b3442, 0x0028313c, 0x0028303c, 0x00272f3a, 0x00262d38, 0x00262d38, 0x00262c38, 0x00252c36, 0x00232932, 0x001e252e, 0x00182029, 0x00161e27, 0x001c242e, 0x0028303c, 0x00212c35, 0x001b252d, 0x00152027, 0x00141d24, 0x00151d24, 0x00141c24, 0x00121c23, 0x00101a21, 0x00111920, 0x00141a23, 0x00181e28, 0x001d2630, 0x00202a34, 0x00202a33, 0x00202933, 0x00242c37, 0x00293039, 0x002b303a, 0x00272c35, 0x00242831, 0x00282d37, 0x00303742, 0x00363e4b, 0x00354250, 0x00314250, 0x002d404f, 0x002a3d4c, 0x00293d4c, 0x002b404f, 0x002c4152, 0x00293f50, 0x00273d4c, 0x00263c4b, 0x00283e4b, 0x00273c4a, 0x00203340, 0x00162733, 0x0010202d, 0x000c1e29, 0x000e1d28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000d1b26, 0x000d1a26, 0x000d1a26, 0x000c1c27, 0x000d1c28, 0x000e1d28, 0x000f1f28, 0x00102029, 0x0011202a, 0x0011202a, 0x0012212b, 0x0012212b, 0x0012212b, 0x0013222d, 0x0013222d, 0x0014222d, 0x0014222d, 0x0014222d, 0x0014222c, 0x0014212b, 0x0014202b, 0x0014202a, 0x00131f28, 0x00111d27, 0x00101c26, 0x00101b25, 0x000e1a24, 0x000d1924, 0x000c1821, 0x000c1820, 0x000c1720, 0x000c161f, 0x000b161f, 0x000a141f, 0x000a141f, 0x000a141f, 0x000a141f, 0x000a141f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00153439, 0x0017383c, 0x00183d41, 0x001a4347, 0x001c474b, 0x001d4c50, 0x00226b7d, 0x002da0c8, 0x002c99bd, 0x002c95b7, 0x002c96b7, 0x002d97b8, 0x002e98b8, 0x002f98b8, 0x002f99b9, 0x002f99b9, 0x003099ba, 0x003099ba, 0x002f9aba, 0x002f9aba, 0x002f9abb, 0x002f97b7, 0x0026666c, 0x00256163, 0x00246062, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x00235a5c, 0x0022595c, 0x00236068, 0x002a8eae, 0x002da0c8, 0x00267e98, 0x00205458, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x0016363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010202c, 0x0010202c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0012212c, 0x0012212c, 0x0011202c, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0011222c, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0013232e, 0x0014232e, 0x0014232f, 0x00142430, 0x00142430, 0x00142532, 0x00132533, 0x00142534, 0x00152634, 0x00152634, 0x00142634, 0x00132734, 0x00122734, 0x00142734, 0x00142734, 0x00132534, 0x00122433, 0x00122433, 0x00132432, 0x00142432, 0x00132432, 0x00112230, 0x00112230, 0x00112230, 0x00102230, 0x0010202d, 0x000e1f2a, 0x000e1e29, 0x000f1e29, 0x000f1e29, 0x000e1d29, 0x000d1c28, 0x000d1b28, 0x000d1a28, 0x000d1a28, 0x000d1a28, 0x000c1926, 0x000c1925, 0x000d1a26, 0x00101e29, 0x00182632, 0x00263442, 0x00344150, 0x003a4555, 0x00384050, 0x00313544, 0x00272936, 0x00242530, 0x00282a34, 0x00252c35, 0x00242c36, 0x00272f39, 0x00242e38, 0x00202c36, 0x001f2b35, 0x00232e38, 0x00232c36, 0x001b252d, 0x00172028, 0x001b232c, 0x00242c38, 0x002b3340, 0x00303844, 0x00333c48, 0x0035404c, 0x0035404c, 0x00343f4c, 0x00303d4a, 0x00303c49, 0x00313d4a, 0x00303c48, 0x002c3844, 0x002d3945, 0x00303c48, 0x002f3b45, 0x002a333f, 0x002b333f, 0x00272f3b, 0x00262e39, 0x00282e39, 0x00242b34, 0x00242a32, 0x00232b34, 0x00232b34, 0x00242c35, 0x0027303a, 0x00253039, 0x00233038, 0x00243139, 0x0024323b, 0x0025333c, 0x0026333c, 0x0028333c, 0x0028343c, 0x0029353e, 0x0029373f, 0x0029373f, 0x002a363f, 0x002c3841, 0x00303843, 0x00323a44, 0x00343c47, 0x00343c48, 0x00333c47, 0x00343d4a, 0x00394350, 0x0036404e, 0x00384250, 0x003e4857, 0x00404b5b, 0x00404c5b, 0x0044525e, 0x00485564, 0x00485465, 0x00485466, 0x00485568, 0x0049576a, 0x0049596c, 0x004a5a6e, 0x004c5b6f, 0x0048576c, 0x00485669, 0x00495668, 0x00495567, 0x00495567, 0x004c596a, 0x00525e70, 0x00556275, 0x00546074, 0x004b576a, 0x004c566a, 0x004d596c, 0x004c5869, 0x004c5768, 0x004c5868, 0x004b5768, 0x004a5768, 0x004a5769, 0x004b586a, 0x004c586a, 0x00485566, 0x004c596b, 0x00505d70, 0x004f5d70, 0x004e5d70, 0x004e5e70, 0x004d5c6e, 0x004a586a, 0x00485568, 0x004b586a, 0x004c586b, 0x004c576a, 0x004a5568, 0x00455263, 0x003e4c5b, 0x003a4957, 0x003b4958, 0x003a4557, 0x003a4454, 0x003b4453, 0x003a4450, 0x0038424c, 0x0037404c, 0x00343f49, 0x00323d48, 0x00333e48, 0x00323d49, 0x00303c48, 0x002f3b47, 0x00303b47, 0x00303c48, 0x00303c48, 0x002c3844, 0x0026333f, 0x0025313d, 0x0026333f, 0x002a3541, 0x002c3844, 0x002f3b45, 0x00303c46, 0x002d3944, 0x002a3842, 0x00283641, 0x002c3944, 0x00303e49, 0x00313f4b, 0x00313f4a, 0x002e3c48, 0x00303d48, 0x0033404d, 0x0033424f, 0x00303e4c, 0x00313c4c, 0x00374250, 0x00384452, 0x00384453, 0x00313e4c, 0x002f3c4a, 0x002f3c49, 0x002e3a48, 0x002c3846, 0x002d3844, 0x002e3944, 0x002f3a45, 0x002e3945, 0x002e3844, 0x002c3844, 0x002c3644, 0x002b3442, 0x0028323d, 0x0029333d, 0x0028323c, 0x0027303b, 0x00272f3a, 0x00262e39, 0x00262d38, 0x00232b34, 0x00202830, 0x001b242c, 0x00171f28, 0x0018202a, 0x00242c38, 0x00222c35, 0x001c262d, 0x00162027, 0x00141c23, 0x00141b22, 0x00141c24, 0x00111b22, 0x00111b22, 0x00141c23, 0x00181f26, 0x001d242e, 0x00202934, 0x00212c36, 0x00202b35, 0x00232c36, 0x00282f3a, 0x002c333c, 0x002c313c, 0x00262b34, 0x0022272f, 0x00262b34, 0x00303641, 0x00373f4c, 0x0034414f, 0x00304050, 0x002d4050, 0x002b404e, 0x0029404e, 0x0029404e, 0x00283f4f, 0x00273d4e, 0x00253c4a, 0x00243a48, 0x00223845, 0x00203441, 0x001a2c3a, 0x00122430, 0x000e1f2b, 0x000c1d28, 0x000e1d28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000d1b26, 0x000d1b27, 0x000d1c27, 0x000d1c28, 0x000e1d28, 0x000f1e28, 0x0010202b, 0x0011202b, 0x0011202b, 0x0012212c, 0x0012212c, 0x0012212c, 0x0013222d, 0x0013222d, 0x0014222d, 0x0014222d, 0x0014222d, 0x0013222c, 0x0013212b, 0x0013212b, 0x0013202a, 0x00111f28, 0x00101d27, 0x000f1c26, 0x000e1c25, 0x000d1a24, 0x000c1924, 0x000b1821, 0x000a1820, 0x000b1720, 0x000b161f, 0x000b161f, 0x0009141f, 0x0008141f, 0x0009141f, 0x000a141f, 0x000a141f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0013282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0016363b, 0x00183c40, 0x00194044, 0x001c4649, 0x001c4a4d, 0x001e4f53, 0x0024768d, 0x002c9abe, 0x002c9cc0, 0x002d9dc0, 0x002f9dc1, 0x00309ec1, 0x00309fc2, 0x00309fc2, 0x00309fc3, 0x0031a0c3, 0x0030a0c3, 0x0031a1c4, 0x0031a1c4, 0x0031a3c6, 0x0031a4ca, 0x00276970, 0x00256163, 0x00256062, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0023646e, 0x002b94b5, 0x002da0c6, 0x0025768c, 0x00205457, 0x001e4f51, 0x001d4c50, 0x001c484c, 0x001b4448, 0x00194044, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00122c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202b, 0x0010202c, 0x0010202c, 0x0010212c, 0x0010222c, 0x0010222c, 0x0012212c, 0x0012212c, 0x0011202c, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x0011222c, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0013232e, 0x0014232e, 0x00142330, 0x00142430, 0x00142431, 0x00142533, 0x00142734, 0x00142734, 0x00152634, 0x00152634, 0x00142634, 0x00122734, 0x00122734, 0x00142734, 0x00142734, 0x00132534, 0x00122433, 0x00122433, 0x00132433, 0x00142433, 0x00132432, 0x00112331, 0x00112230, 0x00112230, 0x00112230, 0x0010202e, 0x000e1f2a, 0x000e1f29, 0x000f1f29, 0x000f1f29, 0x000e1d29, 0x000c1c28, 0x000c1b28, 0x000d1a28, 0x000d1a28, 0x000d1a28, 0x000d1a27, 0x000d1a26, 0x000d1a26, 0x00101d29, 0x00182734, 0x00253544, 0x00324150, 0x003c4857, 0x003d4454, 0x00373b49, 0x002b2c39, 0x00242530, 0x00282a34, 0x00282c36, 0x00232b34, 0x00242d38, 0x00242c38, 0x00212c38, 0x001e2a36, 0x00212c38, 0x00232d37, 0x001e2830, 0x00182129, 0x001c252e, 0x00262d39, 0x002b3340, 0x002f3744, 0x00333c48, 0x0036404c, 0x0036404d, 0x00343f4d, 0x00303c4a, 0x00303c49, 0x00323e4c, 0x00323d49, 0x002f3a48, 0x0034404c, 0x003a4551, 0x0034404c, 0x002d3643, 0x0029313e, 0x00262e3b, 0x0028303b, 0x0029303a, 0x00272e36, 0x00272d34, 0x00252d35, 0x00242c35, 0x00242c35, 0x00273039, 0x0028333c, 0x0028343e, 0x002b3841, 0x002a3842, 0x002a3842, 0x002a3842, 0x002c3842, 0x002c3842, 0x002c3842, 0x002a3842, 0x002c3b44, 0x002d3b44, 0x002a3641, 0x00303844, 0x002d3741, 0x00303944, 0x00323c46, 0x00343e49, 0x00323c48, 0x0038424e, 0x003f4856, 0x003e4856, 0x003e4858, 0x00404c5d, 0x00414e5e, 0x00455260, 0x00495767, 0x00495669, 0x00495669, 0x004a576c, 0x004c5a6f, 0x004f5e74, 0x004f5f75, 0x004c5c71, 0x0049586d, 0x004a586d, 0x004c596c, 0x004b586b, 0x004c5a6c, 0x00505f70, 0x00566376, 0x00586578, 0x00546275, 0x004b586b, 0x004a5769, 0x004c586b, 0x004b586b, 0x004e5b6c, 0x004f5c6e, 0x004e5b6e, 0x004d5b6e, 0x004c5a6d, 0x004b586b, 0x004a576a, 0x00475465, 0x004a5768, 0x00505e70, 0x00526074, 0x00526275, 0x00506274, 0x00506074, 0x004c5a6e, 0x004c5a6f, 0x004b596e, 0x004c596c, 0x004c596c, 0x004b586b, 0x00465466, 0x003e4d5c, 0x003d4c5c, 0x003c4b5b, 0x003e4a5c, 0x00404859, 0x003e4757, 0x003b4452, 0x0038424e, 0x00343f4a, 0x0035414d, 0x00384450, 0x00384450, 0x0036434e, 0x00323f4b, 0x0032404c, 0x0034414c, 0x0034414d, 0x00313f4b, 0x002e3a46, 0x002f3a46, 0x00303c48, 0x002e3a46, 0x002c3844, 0x00303c48, 0x0033404b, 0x0034414c, 0x00313f4b, 0x00303d4a, 0x002e3c49, 0x00303e4b, 0x0035434f, 0x0034424e, 0x00374450, 0x00384552, 0x00384654, 0x00364452, 0x00334150, 0x00334251, 0x00364254, 0x00434f5f, 0x0043505f, 0x00414e5d, 0x00394755, 0x00334150, 0x002e3c4b, 0x00303c4b, 0x00303c4a, 0x00303c4b, 0x00323e4b, 0x00323d49, 0x002f3a46, 0x002c3844, 0x002c3643, 0x002c3544, 0x002b3442, 0x0029333e, 0x002a343e, 0x0029333e, 0x0028323c, 0x0027313c, 0x0027303b, 0x00272f39, 0x00242c35, 0x00222933, 0x001d242f, 0x00181f28, 0x00171f28, 0x00202934, 0x00212c34, 0x0019242b, 0x00141f25, 0x00131b22, 0x00131a22, 0x00141c25, 0x00141e25, 0x00161f26, 0x00182028, 0x001e242c, 0x00222934, 0x00222c36, 0x00232c37, 0x00232d38, 0x00262f39, 0x0029313c, 0x002c333c, 0x002c303b, 0x00262b34, 0x0022262f, 0x00262a34, 0x00303641, 0x00363e4c, 0x0032404d, 0x0030404f, 0x002e4150, 0x002c414f, 0x002a404f, 0x00283f4c, 0x00263d4c, 0x00253b4a, 0x00243947, 0x00233644, 0x001f3340, 0x001b2e3c, 0x00152835, 0x0010212c, 0x000c1e28, 0x000c1d28, 0x000f1d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000d1c28, 0x000d1c28, 0x000e1d28, 0x000f1e29, 0x0010202b, 0x0011202c, 0x0011202c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0013222d, 0x0013222d, 0x0014222d, 0x0014222d, 0x0014222d, 0x0013222c, 0x0012212b, 0x0012212b, 0x0013202a, 0x00111f28, 0x00101d27, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000c1924, 0x000b1822, 0x000a1820, 0x000a1820, 0x000b171f, 0x000b161f, 0x0009141f, 0x0008141f, 0x0009141f, 0x000a141f, 0x000a141f, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00143036, 0x00143439, 0x00173a3e, 0x00183d41, 0x001a4347, 0x001c474b, 0x001c4a4d, 0x001e4f51, 0x00205357, 0x0020565a, 0x0022595c, 0x00235b5f, 0x00245d60, 0x00245f62, 0x00246064, 0x00256164, 0x00266366, 0x00256468, 0x00276568, 0x00276568, 0x002a7f92, 0x0031a4c9, 0x00276970, 0x00256364, 0x00266264, 0x00256062, 0x00245f61, 0x00245e60, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x00246876, 0x002c98bc, 0x002c9cc2, 0x00246f81, 0x00205254, 0x001e4f51, 0x001d4c50, 0x001c4a4d, 0x001b4649, 0x001a4245, 0x00183d41, 0x00183a3e, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0013282e, 0x0013242c, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000e1f2a, 0x000e1f2a, 0x000f202b, 0x0010212c, 0x0010212c, 0x0010212c, 0x0011202c, 0x0011202c, 0x0011202c, 0x0010202b, 0x0010202b, 0x0010202b, 0x0011202c, 0x0011222d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0013232e, 0x0013232e, 0x0013232f, 0x00142330, 0x00142430, 0x00142532, 0x00142634, 0x00142634, 0x00142534, 0x00142534, 0x00142634, 0x00122634, 0x00122634, 0x00132634, 0x00132634, 0x00132533, 0x00122432, 0x00122432, 0x00132432, 0x00132432, 0x00132432, 0x00112331, 0x00112230, 0x00102230, 0x00102130, 0x0010202e, 0x000f202c, 0x000e1f2c, 0x000e1e2b, 0x000e1e2b, 0x000e1d2a, 0x000d1c28, 0x000d1c28, 0x000d1b28, 0x000d1a28, 0x000d1a28, 0x000d1a28, 0x000d1a27, 0x000d1a28, 0x00101d2b, 0x00182634, 0x00223241, 0x002c3c4c, 0x00354454, 0x003c4656, 0x00393e4d, 0x00303340, 0x002a2b37, 0x002a2d38, 0x002a2d38, 0x00242934, 0x00212934, 0x00232c37, 0x00212c37, 0x001c2733, 0x001d2834, 0x00212c35, 0x001f2831, 0x001a222a, 0x001e2630, 0x0028303a, 0x002b3340, 0x002f3844, 0x00313c48, 0x00343f4b, 0x0036404d, 0x0034404d, 0x00303c4a, 0x002f3c4a, 0x00313f4c, 0x00313e4c, 0x00303d4c, 0x00343f4d, 0x003a4653, 0x00384450, 0x00343d4a, 0x002e3744, 0x002a323f, 0x002b323e, 0x002b313d, 0x002a313a, 0x002b333a, 0x002c343c, 0x002c343d, 0x002f3740, 0x00313942, 0x00313c45, 0x00343e48, 0x00333f4a, 0x00303d48, 0x00303d49, 0x00303d49, 0x00303c48, 0x00303c48, 0x00303d49, 0x00303e48, 0x002e3c45, 0x002e3b46, 0x002c3744, 0x00293340, 0x0029323f, 0x002b3440, 0x002c3742, 0x002f3a44, 0x00323e4a, 0x0037434f, 0x003b4652, 0x003c4856, 0x003d4958, 0x003e4b5c, 0x00404e60, 0x00465464, 0x00485668, 0x00485669, 0x0049576b, 0x004c596e, 0x004d5c71, 0x00506075, 0x004d5d74, 0x004d5d73, 0x004c5c72, 0x004d5c72, 0x004f5d72, 0x00505e73, 0x00526075, 0x0056657a, 0x0058667b, 0x00586579, 0x00536174, 0x004b586b, 0x004a576a, 0x004c596c, 0x004c5a6d, 0x00505d70, 0x00505e70, 0x00505d70, 0x004e5c70, 0x004b596c, 0x004a586b, 0x004b586a, 0x00475465, 0x00485568, 0x00536074, 0x00546276, 0x00536377, 0x00516478, 0x00526478, 0x00516177, 0x00506076, 0x004d5c72, 0x004b5a6e, 0x004c5a6d, 0x004a586c, 0x00485669, 0x00425162, 0x00425162, 0x00425061, 0x00414e5f, 0x00404b5c, 0x003f485a, 0x003c4655, 0x003b4453, 0x00364250, 0x00374450, 0x00394753, 0x003b4854, 0x00364450, 0x0033404c, 0x00394753, 0x00384550, 0x0034414c, 0x00313e4a, 0x00303c48, 0x00303c48, 0x00313d48, 0x00323f4a, 0x0034404c, 0x0035424e, 0x0036434f, 0x00384450, 0x00384552, 0x00384653, 0x00354350, 0x0032404d, 0x00344251, 0x00334050, 0x00344351, 0x00384655, 0x00384856, 0x00374656, 0x00374657, 0x003b4a5b, 0x003f4d5e, 0x00425060, 0x00404f5e, 0x0041505f, 0x00415060, 0x003f4e5d, 0x003c4959, 0x00384454, 0x00333f4e, 0x00344050, 0x00364150, 0x00343f4b, 0x002f3a46, 0x002c3843, 0x002c3643, 0x002c3643, 0x002c3542, 0x002a343f, 0x002b343f, 0x002a3440, 0x0029333e, 0x0028323c, 0x0028323c, 0x0028303a, 0x00242c35, 0x00242934, 0x00212530, 0x00191f28, 0x00161d25, 0x001e262e, 0x00242d34, 0x0018232a, 0x00141d24, 0x00131c23, 0x00131b24, 0x00171e27, 0x00182129, 0x001c252c, 0x00212830, 0x00242b34, 0x00242b35, 0x00242c37, 0x00252f39, 0x0028313c, 0x0028313c, 0x0028313c, 0x002b313c, 0x002c303a, 0x00282c36, 0x00242731, 0x00262a34, 0x002e3440, 0x00343c49, 0x00303e4b, 0x002e404d, 0x002d4150, 0x002c4250, 0x002a404e, 0x00273d4b, 0x00243a48, 0x00233745, 0x00223542, 0x001e313f, 0x001b2e3c, 0x00172937, 0x00132431, 0x000f202b, 0x000d1e29, 0x000d1e29, 0x000f1e29, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000e1c28, 0x000d1c28, 0x000d1c28, 0x000e1d28, 0x000e1e28, 0x00101f2a, 0x0011202c, 0x0011202c, 0x0012212c, 0x0012212c, 0x0013212c, 0x0013222d, 0x0013222d, 0x0014222d, 0x0014222d, 0x0014222d, 0x0013222c, 0x0012212b, 0x0012202b, 0x00122029, 0x00101e28, 0x00101d27, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000c1924, 0x000b1822, 0x000a1820, 0x000b181f, 0x000b171e, 0x000b161e, 0x0009151f, 0x0008141e, 0x0009141e, 0x000a141e, 0x000a141e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0016363b, 0x00183c40, 0x00183f43, 0x001a4347, 0x001c474b, 0x001d4b4e, 0x001e4f51, 0x001f5154, 0x00205457, 0x00215659, 0x0022595c, 0x00235c5e, 0x00245d60, 0x00245f61, 0x00246062, 0x00256264, 0x00256364, 0x00276466, 0x002a7f91, 0x0032a4c9, 0x00276a70, 0x00266466, 0x00256364, 0x00266264, 0x00246062, 0x00245e60, 0x00245d60, 0x00235c5e, 0x00256e7d, 0x002c9cc0, 0x002c99bd, 0x00236877, 0x00205254, 0x001e5053, 0x001d4c50, 0x001c4a4d, 0x001c4649, 0x001a4347, 0x00183f43, 0x00183c40, 0x0016363b, 0x00143338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1d28, 0x000d1e28, 0x000e2028, 0x000f2029, 0x0010202a, 0x0010202a, 0x0010202a, 0x0010202b, 0x0011202c, 0x0012212c, 0x0012212c, 0x0013222d, 0x0013222d, 0x0012222d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0012242e, 0x0012242e, 0x0012242e, 0x0013242f, 0x00142430, 0x00142532, 0x00142532, 0x00142534, 0x00142534, 0x00142533, 0x00132632, 0x00132632, 0x00132632, 0x00132632, 0x00132532, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x0011232f, 0x0011232f, 0x0010222e, 0x0010212e, 0x0010202d, 0x0010202d, 0x000f202e, 0x000e1f2d, 0x000e1f2d, 0x000d1e2c, 0x000d1c28, 0x000d1c28, 0x000d1c26, 0x000e1c26, 0x000e1b27, 0x000e1b28, 0x000e1b28, 0x000e1b28, 0x00101e2b, 0x00142431, 0x001c2f3c, 0x00243846, 0x002d404e, 0x00384554, 0x00374050, 0x00333948, 0x002d313e, 0x002d303b, 0x002d313c, 0x00262c38, 0x00212934, 0x00232c37, 0x00212c35, 0x001b252e, 0x001b262f, 0x001f2b34, 0x001e2932, 0x001b242d, 0x001f2833, 0x0027303b, 0x002a343f, 0x002d3843, 0x00303c45, 0x00323d4a, 0x0034404d, 0x0034404e, 0x00303e4b, 0x00303f4c, 0x0033414f, 0x00344351, 0x00374554, 0x00384655, 0x003a4958, 0x00364552, 0x0034414f, 0x00364150, 0x0034404e, 0x00323c49, 0x00303946, 0x00303844, 0x00303841, 0x00303941, 0x00303842, 0x00333c44, 0x00353f48, 0x0036404a, 0x0038414c, 0x0037424c, 0x0034404c, 0x0033404c, 0x00303f4c, 0x002f3c4b, 0x002f3d4a, 0x00313f4c, 0x0031414c, 0x00314049, 0x00313e48, 0x00313c48, 0x00303844, 0x002d3543, 0x002d3643, 0x002c3743, 0x002c3842, 0x002f3c47, 0x00323f4a, 0x0036434f, 0x003b4755, 0x003d4a5b, 0x00414f60, 0x00445364, 0x00465568, 0x0049586b, 0x004a586c, 0x004a586d, 0x004c5b70, 0x004d5d71, 0x004e5f74, 0x004c5c73, 0x004d5e74, 0x004f5f75, 0x00506076, 0x00526278, 0x00536378, 0x00546479, 0x0057677c, 0x0056667c, 0x00546579, 0x004f5f71, 0x004c5a6c, 0x004a586c, 0x004d5c6e, 0x004d5c70, 0x004c5c6e, 0x004f5d70, 0x00526074, 0x00505f71, 0x004d5c6e, 0x004c5c6e, 0x004c5b6e, 0x0049586a, 0x00495768, 0x00546175, 0x00556478, 0x00546478, 0x00536578, 0x0054667a, 0x00546479, 0x00546479, 0x00506076, 0x004f5d73, 0x004c5b70, 0x0048586c, 0x0048586c, 0x00475769, 0x00475868, 0x00455466, 0x00435063, 0x003e4b5c, 0x003c4859, 0x003c4857, 0x003a4553, 0x00374350, 0x00364350, 0x003a4754, 0x003c4a57, 0x0033404c, 0x00313f4a, 0x0034424d, 0x0033404c, 0x0034404c, 0x0032404b, 0x002e3c47, 0x002c3944, 0x00303d48, 0x00364450, 0x00384551, 0x00384551, 0x003a4853, 0x003b4955, 0x003a4956, 0x00394856, 0x00394856, 0x003a4856, 0x003e4c5c, 0x003b495b, 0x00394859, 0x003e4d5e, 0x00415261, 0x00435565, 0x00415464, 0x00405261, 0x00435464, 0x00425363, 0x00405060, 0x00405061, 0x00435361, 0x00425261, 0x00425162, 0x003e4c5c, 0x00394555, 0x00394454, 0x00384452, 0x00313d4a, 0x002c3844, 0x002b3742, 0x002b3741, 0x002c3643, 0x002c3542, 0x002b3441, 0x002b3541, 0x002b343f, 0x002a343e, 0x0029333c, 0x0029333c, 0x00272f38, 0x00232933, 0x00232832, 0x00212730, 0x001a2028, 0x00151c24, 0x001b232a, 0x00242e35, 0x001f2831, 0x00141e27, 0x00131c24, 0x00111a23, 0x00151e27, 0x001a232c, 0x00202831, 0x00242c34, 0x00262c34, 0x00242b35, 0x00222c36, 0x0026303b, 0x0029343e, 0x0028333d, 0x0028303c, 0x0029313c, 0x002c303b, 0x00282d38, 0x00252934, 0x00262c36, 0x002d3440, 0x00313c48, 0x002e3c49, 0x002c404c, 0x002c414f, 0x002c414f, 0x002a3f4c, 0x00263b48, 0x00233845, 0x00213442, 0x001f313f, 0x001b2e3b, 0x00182a38, 0x00142533, 0x00122430, 0x0010212d, 0x000f202c, 0x000e1f2c, 0x000f1f2c, 0x000f1e2b, 0x000f1d28, 0x000f1d28, 0x000e1c28, 0x000e1c28, 0x000e1c28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000f1f29, 0x0010202b, 0x0010202b, 0x0012202c, 0x0014212c, 0x0014212c, 0x0013222e, 0x0012212e, 0x0013222f, 0x0013222f, 0x0013222f, 0x0014212d, 0x0013202c, 0x00121f2a, 0x00121e28, 0x00121e28, 0x00101d27, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000c1924, 0x000c1a21, 0x000b1820, 0x000b181e, 0x000b171d, 0x000b171c, 0x000a161d, 0x000a161e, 0x000a151e, 0x000b151e, 0x000b151e, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00112a30, 0x00132c32, 0x00143036, 0x00143439, 0x0017383c, 0x00173c40, 0x00194044, 0x001a4347, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205356, 0x00215659, 0x0022585b, 0x00235a5c, 0x00245d60, 0x00245f61, 0x00256163, 0x00256364, 0x00276466, 0x002b7f91, 0x0032a4c9, 0x00276c72, 0x00266467, 0x00266466, 0x00266364, 0x00256163, 0x00245f61, 0x00245e60, 0x00277486, 0x002d9ec3, 0x002c95b8, 0x0022646f, 0x00205254, 0x001f5053, 0x001d4d50, 0x001c4a4d, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0017383c, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0011242c, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1d28, 0x000c1e28, 0x000d1f27, 0x000e1f27, 0x000f1f28, 0x00102029, 0x00102029, 0x0010202a, 0x0011202c, 0x0011202c, 0x0011212c, 0x0013222d, 0x0013222d, 0x0012222d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0012242e, 0x0012242e, 0x00132430, 0x00142431, 0x00142532, 0x00142534, 0x00142534, 0x00142533, 0x00132632, 0x00132632, 0x00132632, 0x00132632, 0x00122532, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x0011232f, 0x0011232f, 0x0010212e, 0x0010202d, 0x0010202d, 0x0010202d, 0x000f202e, 0x000e1f2d, 0x000e1f2d, 0x000d1e2c, 0x000d1c28, 0x000d1c28, 0x000d1c25, 0x000e1c25, 0x000e1b27, 0x000e1b28, 0x000e1b28, 0x000e1b28, 0x00101d2a, 0x00142330, 0x001c2d3a, 0x00243745, 0x002b3d4c, 0x00344351, 0x0035404f, 0x00343c4b, 0x00313644, 0x00313440, 0x00303541, 0x002a313c, 0x00232c37, 0x00232c37, 0x00212b34, 0x001a242b, 0x001b262d, 0x001f2b34, 0x001e2932, 0x001d2730, 0x00212c36, 0x0028323c, 0x002b3540, 0x002d3943, 0x00303c46, 0x00313c48, 0x0034404d, 0x0034404d, 0x002f3d4a, 0x0030404d, 0x00344552, 0x00374756, 0x003b4c5a, 0x003c4e5d, 0x00405160, 0x00405160, 0x003a4a58, 0x00394858, 0x003d4b5a, 0x003e4958, 0x00394553, 0x0037404e, 0x00363f4a, 0x00363f49, 0x0037404a, 0x00323c47, 0x00303b45, 0x00343f49, 0x0038434d, 0x003b4651, 0x00394652, 0x00394753, 0x00394855, 0x00394857, 0x00394857, 0x00384855, 0x00364551, 0x0034434d, 0x0034424c, 0x0035424d, 0x0036404c, 0x00343d4a, 0x00343e4c, 0x0034404c, 0x0034404b, 0x0034424c, 0x0036444f, 0x003a4754, 0x003e4b58, 0x00404d5c, 0x00424f60, 0x00425062, 0x00455667, 0x004c5c6e, 0x004e5d70, 0x004d5c70, 0x004c5c70, 0x004e5f72, 0x004f6074, 0x004d5e72, 0x004e5f74, 0x00516177, 0x00546478, 0x00546478, 0x00546478, 0x00546479, 0x0056667c, 0x0055657b, 0x00546478, 0x00506072, 0x004e5c70, 0x004c5a6d, 0x004d5c70, 0x004c5c70, 0x004c5a6e, 0x00505e72, 0x00546377, 0x00546376, 0x00505f71, 0x00505e71, 0x004e5c6f, 0x004c596c, 0x004a5769, 0x00525f74, 0x0058667b, 0x0058677c, 0x0055687b, 0x0055677c, 0x0054647a, 0x0054657b, 0x0054647a, 0x00506076, 0x004c5c72, 0x0048596e, 0x004b5c70, 0x004c5c70, 0x004c5c70, 0x004b5b6d, 0x00485668, 0x00414f61, 0x003f4b5c, 0x003f4a5a, 0x003e4958, 0x003d4857, 0x003a4754, 0x00354350, 0x00303e4b, 0x00303e4b, 0x00313f4b, 0x0034404c, 0x00313e4a, 0x00303d48, 0x00303d48, 0x00303d48, 0x0032404c, 0x0032404b, 0x00303e49, 0x0033404c, 0x00384652, 0x003e4d58, 0x003d4c59, 0x003a4b58, 0x00364754, 0x00334350, 0x003b4a58, 0x00445363, 0x00445464, 0x00435364, 0x00435464, 0x00455866, 0x00445666, 0x00415464, 0x003e5060, 0x00405262, 0x00415363, 0x00415263, 0x00425363, 0x00435463, 0x00445463, 0x00435464, 0x00425161, 0x003f4c5c, 0x003c4857, 0x00384454, 0x00323e4c, 0x002d3845, 0x002b3742, 0x002a3641, 0x002b3541, 0x002c3542, 0x002b3442, 0x002c3542, 0x002c3540, 0x002a343e, 0x0029333c, 0x0029333c, 0x00252d36, 0x00202730, 0x00232831, 0x00222830, 0x001c2229, 0x00141d24, 0x00161f24, 0x00202b31, 0x00242f37, 0x0019242c, 0x00131d25, 0x00111a24, 0x00151d26, 0x0018202a, 0x001c242e, 0x00202730, 0x00212831, 0x001e2530, 0x001e2833, 0x00232e38, 0x0026323c, 0x0025313c, 0x0028303d, 0x002a313c, 0x002c313c, 0x002a2f39, 0x00272b37, 0x00262c37, 0x002c3440, 0x00303c47, 0x002c3c48, 0x002b3f4c, 0x002c414f, 0x002b404d, 0x00283d4b, 0x00243846, 0x00213643, 0x001f3240, 0x001c2f3c, 0x00182c38, 0x00152834, 0x00132430, 0x00112330, 0x0010212e, 0x0010202d, 0x000f202c, 0x0010202c, 0x00101f2c, 0x000e1e28, 0x000e1d28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1e28, 0x0010202a, 0x0010202b, 0x0011202c, 0x0014212c, 0x0013212c, 0x0013212e, 0x0012212e, 0x0012212e, 0x0012212e, 0x0012212e, 0x0013212c, 0x0013202c, 0x00111e29, 0x00121e28, 0x00121e28, 0x00101d27, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000c1924, 0x000c1a21, 0x000b1920, 0x000b181e, 0x000b171d, 0x000b171c, 0x000a161d, 0x000a161e, 0x000a151e, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00143036, 0x00153439, 0x0017383c, 0x00183d41, 0x001a4044, 0x001a4347, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205356, 0x00215659, 0x0022595c, 0x00245c5e, 0x00245e60, 0x00256062, 0x00256264, 0x00266466, 0x002b7f91, 0x0032a4c9, 0x00286c73, 0x00276668, 0x00266568, 0x00266466, 0x00256264, 0x00256164, 0x00287c91, 0x002fa0c5, 0x002b90b0, 0x00226068, 0x00205457, 0x001f5154, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00183d41, 0x00183a3e, 0x0015363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1d28, 0x000c1d28, 0x000c1e26, 0x000d1e27, 0x000e1f28, 0x00101f28, 0x00101f28, 0x00101f28, 0x0010202b, 0x0010202b, 0x0010202c, 0x0011212c, 0x0012212c, 0x0011222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0012242e, 0x0013242f, 0x00142430, 0x00142430, 0x00142432, 0x00142432, 0x00132531, 0x00132631, 0x00132631, 0x00132632, 0x00132632, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x0010232f, 0x0010232f, 0x0010212e, 0x0010202d, 0x0010202d, 0x0010202d, 0x000f202c, 0x000e1f2c, 0x000e1f2c, 0x000d1e2a, 0x000c1d27, 0x000c1c26, 0x000c1c25, 0x000d1c25, 0x000d1c27, 0x000d1c29, 0x000d1c29, 0x000d1c28, 0x000f1d2a, 0x00132330, 0x001b2c38, 0x00233543, 0x00283b49, 0x0030404f, 0x0034404e, 0x00343e4c, 0x00333a47, 0x00323844, 0x00303845, 0x002c3541, 0x00242e39, 0x00212c36, 0x001e2831, 0x001a242c, 0x001d2830, 0x00202b33, 0x001c2830, 0x001d2830, 0x00242e37, 0x0028323c, 0x002b3640, 0x002e3a44, 0x00303c46, 0x00303c48, 0x00333e4c, 0x00323e4b, 0x002f3c4a, 0x0031404e, 0x00354452, 0x00374755, 0x003a4c5b, 0x003b4e5e, 0x003d5160, 0x003f5160, 0x003c4e5c, 0x003c4c5b, 0x00404d5d, 0x00404c5c, 0x003f4a59, 0x003d4856, 0x003c4654, 0x003c4653, 0x003c4754, 0x00394452, 0x0038434f, 0x0036414d, 0x003b4753, 0x003f4c58, 0x00414f5c, 0x00445160, 0x00455261, 0x00445363, 0x00445261, 0x00445362, 0x00435360, 0x0040505c, 0x00404f5b, 0x00404d5a, 0x00414e5b, 0x003f4c59, 0x003b4856, 0x00374451, 0x0035444f, 0x0034434e, 0x0036424e, 0x00394654, 0x003c4958, 0x00414e5f, 0x00445263, 0x00445465, 0x00475868, 0x004c5c6e, 0x00505f71, 0x004e5c70, 0x004c5c70, 0x004d5e71, 0x004f5f73, 0x004f5f73, 0x00516175, 0x00536378, 0x00546478, 0x00546478, 0x00546478, 0x00546478, 0x00546478, 0x00546478, 0x00536476, 0x00516074, 0x004f5e71, 0x004d5c70, 0x004f5d71, 0x00505f74, 0x00516074, 0x00546276, 0x00546377, 0x00546377, 0x00536275, 0x004f5e71, 0x004d5c6f, 0x004c586c, 0x004a576b, 0x00505c71, 0x00586479, 0x0058687c, 0x0055677b, 0x0054667a, 0x00546478, 0x00526278, 0x00536378, 0x00516277, 0x004e5f74, 0x004d5d73, 0x004c5d72, 0x004d5e71, 0x004d5d70, 0x004d5d70, 0x004c586c, 0x00475467, 0x00455264, 0x00434e60, 0x00424d5e, 0x003d4959, 0x00384453, 0x00364451, 0x00374551, 0x00374651, 0x0034434e, 0x00303e49, 0x002c3a45, 0x002d3b46, 0x00303d49, 0x0036424e, 0x0036414d, 0x00323e4a, 0x00303c48, 0x0034404d, 0x003b4855, 0x003d4c59, 0x003a4857, 0x00384856, 0x00374654, 0x00384857, 0x0041505f, 0x00465565, 0x00445564, 0x00435463, 0x00425363, 0x003f5161, 0x00405262, 0x00445565, 0x00445464, 0x00455668, 0x00455668, 0x00445667, 0x00445668, 0x00445565, 0x00445565, 0x00425364, 0x00405062, 0x003e4d5e, 0x003d4a5b, 0x00394556, 0x0034404f, 0x00303c49, 0x002d3844, 0x002a3641, 0x00293541, 0x00293441, 0x00283440, 0x002a3440, 0x002b3540, 0x002a343e, 0x0028323b, 0x0028333c, 0x00263038, 0x00232b34, 0x00232933, 0x00232931, 0x001e252c, 0x00171f26, 0x00141d23, 0x001c262c, 0x00252f38, 0x001c2730, 0x00121c25, 0x00111b24, 0x00131c25, 0x00151f28, 0x00172029, 0x00182029, 0x0018212a, 0x0019222c, 0x001a2630, 0x00202c36, 0x0024303b, 0x0025313c, 0x002a333f, 0x002c343f, 0x002e343e, 0x002c313c, 0x00292d39, 0x00282e39, 0x0029333e, 0x002c3945, 0x002a3b48, 0x002a3e4c, 0x002b404d, 0x00283d4b, 0x00243947, 0x00203643, 0x001d3240, 0x001c303e, 0x001a2c3a, 0x00152834, 0x00132632, 0x00122430, 0x00122430, 0x0010222e, 0x0010202d, 0x000f202c, 0x0010202c, 0x00101f2c, 0x000e1d28, 0x000e1d28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1e28, 0x000f1f29, 0x00101f2a, 0x00101f2a, 0x0013202c, 0x0013212c, 0x0012212e, 0x0012212e, 0x0012212e, 0x0011202d, 0x0012202d, 0x0013202d, 0x0013202c, 0x00121f2b, 0x00131f2a, 0x00121e29, 0x00101d27, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000c1924, 0x000c1a21, 0x000b1920, 0x000b181f, 0x000b171e, 0x000b171d, 0x0009161d, 0x000a161e, 0x0009141d, 0x0009141c, 0x0009141c, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0012242c, 0x0010282e, 0x00132c32, 0x00142e34, 0x00153338, 0x0015363b, 0x00183a3e, 0x00183d41, 0x001a4044, 0x001a4347, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205457, 0x0021585a, 0x00235a5c, 0x00245d60, 0x00246062, 0x00256264, 0x00266466, 0x002b7f91, 0x0033a4c9, 0x00286d74, 0x00286769, 0x00276668, 0x00266467, 0x00266568, 0x002b849b, 0x0030a2c7, 0x002b8ca8, 0x00235f64, 0x00215659, 0x00205356, 0x001e5053, 0x001d4c50, 0x001c484c, 0x001b4649, 0x001a4245, 0x00183f43, 0x00183a3e, 0x0016363b, 0x00143338, 0x00142e34, 0x00132c32, 0x00112a30, 0x0011242c, 0x0012242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1d28, 0x000c1d28, 0x000c1d26, 0x000c1e26, 0x000d1e27, 0x000f1f28, 0x000f1f28, 0x000f1f28, 0x00101f2a, 0x0010202b, 0x0010202b, 0x0011202c, 0x0012212c, 0x0011212c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0011232d, 0x0011232d, 0x0011232d, 0x0012242e, 0x0013242e, 0x0014242f, 0x0014242f, 0x00142431, 0x00142431, 0x00132430, 0x00132630, 0x00132630, 0x00132632, 0x00132632, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x0010232f, 0x0010232f, 0x0010212e, 0x0010202d, 0x0010202d, 0x0010202d, 0x000f202c, 0x000e1f2c, 0x000e1f2c, 0x000c1e2a, 0x000c1d27, 0x000c1d26, 0x000c1c25, 0x000c1c25, 0x000c1c27, 0x000d1c29, 0x000d1c29, 0x000c1c28, 0x000e1d2a, 0x0012222f, 0x00192b37, 0x00223341, 0x00263846, 0x002c3c4c, 0x00303f4c, 0x00333d4b, 0x00323b48, 0x00323a46, 0x00313a48, 0x002d3744, 0x0027303c, 0x00212c36, 0x001c2630, 0x0019242c, 0x001e2831, 0x001e2931, 0x001b252e, 0x001c272f, 0x00242e37, 0x0028333d, 0x002c3741, 0x002e3a44, 0x002f3b45, 0x00303c47, 0x00313d49, 0x00313d49, 0x00313e4b, 0x00354350, 0x00354452, 0x00374856, 0x003c4d5c, 0x003b4f5f, 0x003d5261, 0x00405363, 0x00405262, 0x00405162, 0x00415062, 0x00424f60, 0x00445061, 0x00424e5e, 0x00404c5c, 0x00404c5c, 0x00424e5e, 0x00455060, 0x00475260, 0x00485360, 0x004a5564, 0x004a5764, 0x004a5867, 0x004a5867, 0x004c5868, 0x004c5868, 0x004c5868, 0x004a5868, 0x00485866, 0x00455562, 0x0044515f, 0x00404f5d, 0x003e4d5c, 0x003e4c5a, 0x003d4a59, 0x003a4855, 0x0034444f, 0x003c4955, 0x00444f5c, 0x0044505e, 0x00435060, 0x00445163, 0x00445263, 0x00435365, 0x00445567, 0x00485869, 0x0049586b, 0x004a596c, 0x004c5c6e, 0x004c5d70, 0x004e5f71, 0x00506074, 0x00516074, 0x00516074, 0x00526175, 0x00536275, 0x00536376, 0x00536276, 0x00526175, 0x00536276, 0x00546476, 0x00516073, 0x004e5c70, 0x004d5c6f, 0x004c5b6d, 0x00516074, 0x00536276, 0x00546378, 0x00556478, 0x00546478, 0x00516074, 0x004c5c70, 0x004c5b70, 0x004c5b70, 0x004b596e, 0x004e5c70, 0x00556276, 0x0057657a, 0x0054667a, 0x0054667a, 0x00546478, 0x00526276, 0x00506074, 0x00506075, 0x00516177, 0x00506177, 0x00506074, 0x004f6073, 0x004c5c6e, 0x004b586c, 0x00485468, 0x00465266, 0x00445265, 0x00425063, 0x003f4c5d, 0x003c4859, 0x00404f5e, 0x00445361, 0x00455461, 0x0043525e, 0x00404d59, 0x003c4854, 0x003a4652, 0x00394551, 0x00384551, 0x003d4955, 0x003e4a56, 0x003f4b57, 0x00404c58, 0x003e4a57, 0x003a4755, 0x00384554, 0x003c4b5b, 0x00415061, 0x00404f60, 0x00445364, 0x00485768, 0x00475768, 0x00465768, 0x00485869, 0x0049586a, 0x00475868, 0x00455667, 0x00475868, 0x00485869, 0x0048596b, 0x0048596b, 0x0047596b, 0x00485a6c, 0x00485969, 0x00455666, 0x00425364, 0x003f5061, 0x003c4d5d, 0x003e4c5d, 0x003b4858, 0x00364251, 0x00323e4c, 0x002c3945, 0x002a3742, 0x00283440, 0x00283440, 0x0028333f, 0x002a3440, 0x002b3540, 0x002a343f, 0x0028313b, 0x00273039, 0x00262f38, 0x00242c35, 0x00242b34, 0x00222a31, 0x001e262d, 0x00192228, 0x00151d24, 0x00192228, 0x00222c34, 0x001e2831, 0x00151f28, 0x00121c24, 0x00101a23, 0x00111c24, 0x00131c24, 0x00141c25, 0x00171f28, 0x0019212c, 0x001a2530, 0x00202b35, 0x0024303a, 0x0029343f, 0x002f3843, 0x00303842, 0x00303741, 0x002e343d, 0x002c303b, 0x002a303c, 0x00293440, 0x002b3a46, 0x002a3c49, 0x002a3e4c, 0x00283e4c, 0x00243a48, 0x00213644, 0x001e3340, 0x001c303e, 0x001c2e3c, 0x00182b38, 0x00142834, 0x00132531, 0x00122430, 0x00122430, 0x0010222e, 0x0010202d, 0x000f202c, 0x0010202c, 0x000f1e2b, 0x000e1d28, 0x000e1d28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000f1f29, 0x000f1f29, 0x00101e29, 0x00111f2a, 0x0013202c, 0x0012212e, 0x0012212e, 0x0011202d, 0x0011202d, 0x0011202d, 0x0013202d, 0x0013202d, 0x00131f2c, 0x00131f2b, 0x00131f2a, 0x00101d27, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000c1924, 0x000c1a21, 0x000b1920, 0x000b1820, 0x000b171f, 0x000b171e, 0x0009161d, 0x000a161e, 0x0008141c, 0x0009141c, 0x0009141c, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00142e34, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183d41, 0x00194044, 0x001b4448, 0x001c474b, 0x001d4b4e, 0x001e4f51, 0x00205254, 0x00205558, 0x0022595c, 0x00245c5f, 0x00245f61, 0x00256264, 0x00266467, 0x002b7f91, 0x0033a5c9, 0x0029717a, 0x00286c70, 0x00286b70, 0x00276b70, 0x002c8ca6, 0x0031a3c8, 0x002b869f, 0x00245f63, 0x0022595c, 0x00215659, 0x001f5254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00183d41, 0x0017383c, 0x00143439, 0x00143036, 0x00142e34, 0x00112a30, 0x0010282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1c27, 0x000b1c27, 0x000b1d26, 0x000c1d26, 0x000d1e27, 0x000e1e27, 0x000e1e27, 0x000e1f28, 0x000f1f29, 0x0010202b, 0x0010202b, 0x0010202b, 0x0011202c, 0x0010202c, 0x0010212c, 0x0010212c, 0x0010212c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0011232d, 0x0013242e, 0x0014242f, 0x0014242f, 0x00142430, 0x00142431, 0x00122430, 0x00112530, 0x00112630, 0x00112631, 0x00112531, 0x00112431, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x0010232f, 0x0010232f, 0x0010212e, 0x0010202d, 0x000f202c, 0x000f202c, 0x000e1f2c, 0x000e1f2c, 0x000d1e2c, 0x000c1e2a, 0x000c1d28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c28, 0x000d1c29, 0x000d1c29, 0x000c1c28, 0x000f1e2b, 0x0012222f, 0x00182935, 0x0020313e, 0x00233443, 0x00283847, 0x002d3c49, 0x00303c49, 0x00303946, 0x00303a47, 0x00313b49, 0x002e3846, 0x00283140, 0x00212b38, 0x001a2430, 0x0019242e, 0x001f2932, 0x001e2830, 0x001a242d, 0x001c262f, 0x00232d38, 0x002a343f, 0x002d3842, 0x002e3944, 0x002f3a46, 0x00303c48, 0x00303c48, 0x00313d49, 0x00303d4b, 0x00354350, 0x00384754, 0x00394958, 0x003d4f5e, 0x003e5262, 0x00405464, 0x00435767, 0x00445869, 0x0044576a, 0x00445568, 0x00445468, 0x00465568, 0x00485668, 0x00475666, 0x00495867, 0x004c5868, 0x004b5764, 0x00495460, 0x004a5461, 0x0044515e, 0x00404f5c, 0x003c4d5b, 0x003b4a58, 0x00384654, 0x00384452, 0x00384452, 0x00354450, 0x0032404c, 0x00283440, 0x001d2834, 0x001a2630, 0x0018232e, 0x001c2833, 0x001e2936, 0x001c2935, 0x001c2934, 0x0025333e, 0x0036434e, 0x003f4c58, 0x0044505e, 0x00475361, 0x00485362, 0x00465363, 0x00455364, 0x00445465, 0x00445364, 0x00445364, 0x00465567, 0x0049586a, 0x004b5a6c, 0x004b5c6c, 0x004c5c6e, 0x004e5e70, 0x00506072, 0x00516173, 0x00526274, 0x00516073, 0x004f5f70, 0x00505f71, 0x00516070, 0x004e5c6d, 0x004b596b, 0x004a5869, 0x004a586a, 0x004e5c70, 0x00516074, 0x00556478, 0x00546478, 0x00546378, 0x00546276, 0x00506074, 0x004e5c70, 0x004c5b70, 0x004c5b70, 0x004f5c71, 0x00536074, 0x00546477, 0x00546579, 0x00546578, 0x00536477, 0x00516274, 0x00506174, 0x00506175, 0x00506076, 0x00506076, 0x004e5e73, 0x004c5c6f, 0x004a596b, 0x00485668, 0x00455365, 0x00455365, 0x00445466, 0x00465466, 0x00465565, 0x00435161, 0x003e4d5c, 0x003f4e5c, 0x0040505d, 0x0043525e, 0x0045535e, 0x0045525e, 0x0046525f, 0x0044515d, 0x0044525d, 0x0046535e, 0x0045535e, 0x0047545f, 0x00475460, 0x00465461, 0x00445361, 0x00425160, 0x00465666, 0x00475868, 0x0048586a, 0x00495b6c, 0x004a5c6e, 0x00495a6c, 0x00485a6c, 0x004a5a6c, 0x0048586b, 0x0047586a, 0x0047586a, 0x0048596c, 0x00485b6c, 0x00485a6d, 0x00485a6c, 0x00485b6d, 0x00495b6d, 0x00495b6d, 0x0047586a, 0x00425365, 0x00405162, 0x003e4f5f, 0x003f4c5d, 0x003b4858, 0x00364453, 0x00323f4e, 0x002c3a48, 0x002a3843, 0x00283440, 0x0028333f, 0x0028333f, 0x002a3440, 0x002c3540, 0x002c343f, 0x0029313c, 0x0028303a, 0x00272f38, 0x00262e38, 0x00262c36, 0x00232b33, 0x001f272e, 0x001c242c, 0x00182027, 0x001a2129, 0x001f2830, 0x00202a33, 0x0018232c, 0x00131d26, 0x00101b24, 0x00111c24, 0x00141c25, 0x00151d26, 0x00181f28, 0x001a222c, 0x001d2530, 0x00212934, 0x00262f39, 0x002c343f, 0x00303944, 0x00323a44, 0x00323944, 0x00303842, 0x002e3440, 0x002b323f, 0x00293440, 0x002a3844, 0x002a3b48, 0x00283d4b, 0x00263c49, 0x00223744, 0x001f3340, 0x001c3140, 0x001c2f3e, 0x001b2c3b, 0x00182937, 0x00162734, 0x00142533, 0x00132430, 0x00122430, 0x0010222e, 0x0010202d, 0x0010202d, 0x0010202c, 0x00101f2c, 0x000e1e28, 0x000e1d28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000e1c28, 0x000e1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000f1e28, 0x000f1e28, 0x00101e29, 0x00101e29, 0x00111f2b, 0x0011202d, 0x0012212d, 0x0011202d, 0x0011202d, 0x0011202d, 0x0012202c, 0x00121f2c, 0x00121f2c, 0x00121f2a, 0x00111e28, 0x00101d27, 0x000f1c26, 0x000e1b24, 0x000d1a24, 0x000c1923, 0x000b1822, 0x000b1821, 0x000b1720, 0x000a1620, 0x000a161e, 0x0009151e, 0x0009151e, 0x0008141d, 0x000a141d, 0x000a141d, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00132c32, 0x00153036, 0x00143439, 0x0016383c, 0x00183c40, 0x00183f43, 0x001a4245, 0x001b4649, 0x001d4a4d, 0x001d4d50, 0x001f5154, 0x00205457, 0x0022585b, 0x00245c5e, 0x00245f61, 0x00256264, 0x00266467, 0x002b7f91, 0x0034a6cb, 0x0032a0c2, 0x0031a0c1, 0x00319fc0, 0x0031a0c1, 0x0031a3c7, 0x002b8297, 0x00256164, 0x00245d60, 0x0022595c, 0x00215659, 0x001f5254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0017383c, 0x00153439, 0x00143036, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a1c24, 0x00091c25, 0x00091c25, 0x000b1d26, 0x000c1e27, 0x000e1e27, 0x000e1e27, 0x000e1e28, 0x000f1e29, 0x000f1f29, 0x000f1f29, 0x00101f2a, 0x00101f2a, 0x0010202a, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010212c, 0x0010212c, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232f, 0x0011232f, 0x0010242f, 0x0010252f, 0x00102630, 0x00102631, 0x00102631, 0x00102431, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010212e, 0x0010202d, 0x000f202c, 0x000d1e2b, 0x000c1e2a, 0x000c1e2c, 0x000c1e2c, 0x000c1d2b, 0x000c1c28, 0x000c1c28, 0x000d1b28, 0x000e1b28, 0x000e1b28, 0x000f1c29, 0x000e1c28, 0x000c1c28, 0x000f1e2b, 0x0012212e, 0x00152632, 0x001d2f3c, 0x0020323f, 0x00243643, 0x002a3947, 0x002c3a47, 0x002e3844, 0x002f3945, 0x00303947, 0x002d3745, 0x00283240, 0x00202a38, 0x001a2531, 0x001c2832, 0x00222c36, 0x001f2932, 0x001b252e, 0x001e2831, 0x00252f39, 0x002b3540, 0x002e3842, 0x002f3944, 0x00303945, 0x00313b48, 0x00313b48, 0x00303c48, 0x002f3b48, 0x0033404d, 0x003a4856, 0x003c4c5a, 0x003d5060, 0x00405463, 0x00415567, 0x00435768, 0x0044586a, 0x0044586b, 0x00475a6c, 0x00485a6c, 0x00485969, 0x00495868, 0x00485965, 0x00495864, 0x0045515c, 0x003d4750, 0x00333d45, 0x00333c48, 0x002c3a46, 0x002c3e4a, 0x002b3f4c, 0x00253746, 0x00172734, 0x0014242f, 0x00172630, 0x0013222b, 0x00091720, 0x00020c15, 0x00040d17, 0x00040f16, 0x00040e14, 0x000e1820, 0x0014202b, 0x00182631, 0x00182731, 0x00192834, 0x00283642, 0x002d3c47, 0x0035404c, 0x003b4653, 0x003d4855, 0x00414d5b, 0x00445161, 0x00445464, 0x00465465, 0x00455464, 0x00445163, 0x00445263, 0x00445362, 0x00455563, 0x00485967, 0x004c5c6c, 0x004d5f6f, 0x00506071, 0x00506071, 0x004f6070, 0x004f5e6f, 0x00505d6e, 0x004e5b6a, 0x004c5968, 0x004a5868, 0x00485566, 0x00485568, 0x004c5a6c, 0x00505f71, 0x00526074, 0x00516175, 0x00506175, 0x00516074, 0x004e5d70, 0x004a586b, 0x004b596c, 0x004d5b6d, 0x00505d70, 0x00515f72, 0x00526175, 0x00526476, 0x00516475, 0x00506374, 0x00506374, 0x00506274, 0x004e6073, 0x004c5e71, 0x00485b70, 0x0047586d, 0x00465769, 0x00455568, 0x00455466, 0x00465465, 0x00465464, 0x00465464, 0x00455464, 0x00435060, 0x00394858, 0x0031404e, 0x002e3c4a, 0x002b3b48, 0x0024323f, 0x0025323d, 0x002b3742, 0x0027333e, 0x0024303b, 0x002c3742, 0x00313e47, 0x0038454f, 0x003e4c56, 0x0041505a, 0x00445460, 0x00455663, 0x00415361, 0x00435464, 0x00445868, 0x00465969, 0x00485b6c, 0x004a5c6d, 0x004c5c6e, 0x004c5c6e, 0x004a5b6c, 0x0048586b, 0x0048596c, 0x00485a6d, 0x00485b6f, 0x00495c70, 0x00495b6f, 0x004b5c70, 0x004b5c70, 0x004a5c70, 0x00485b6f, 0x0047596c, 0x00425466, 0x00405263, 0x003e4f60, 0x003e4c5d, 0x003a4757, 0x00364452, 0x0032404d, 0x002e3b48, 0x002d3947, 0x002c3843, 0x002a3641, 0x002b3640, 0x002c3640, 0x002c3640, 0x002c343f, 0x0029313c, 0x0028303b, 0x0028303b, 0x0027303a, 0x00262e38, 0x00232b34, 0x001f2830, 0x001d252e, 0x001a232b, 0x0019212a, 0x001c242d, 0x001d2830, 0x0019242d, 0x00131e26, 0x00111c24, 0x00141d25, 0x00161f26, 0x00171f27, 0x00182029, 0x001c222c, 0x00202430, 0x00232834, 0x00272c38, 0x002b323d, 0x00303843, 0x00313a46, 0x00313a46, 0x00303844, 0x002e3644, 0x002c3341, 0x00293340, 0x002a3744, 0x002a3b48, 0x00283c4b, 0x00253a47, 0x001f3340, 0x001d303d, 0x001b2f3d, 0x001b2c3c, 0x00192a39, 0x00182837, 0x00162734, 0x00142633, 0x00132431, 0x00122430, 0x0011232f, 0x0010222e, 0x0010202d, 0x0010202d, 0x00101f2c, 0x000e1e29, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000d1c28, 0x000e1c27, 0x000e1c27, 0x000d1b26, 0x000d1b26, 0x000e1c27, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101e2a, 0x00111f2b, 0x0010202a, 0x0010202a, 0x0010202a, 0x00101f2a, 0x00101f2a, 0x00101f2a, 0x00101f2a, 0x00101e29, 0x00101d28, 0x000f1c26, 0x000f1c26, 0x000f1b25, 0x000d1924, 0x000c1922, 0x000b1821, 0x000b1821, 0x00091821, 0x00091620, 0x0009141f, 0x0008141f, 0x0009141e, 0x0009141e, 0x0009141e, 0x000a141f, 0x000b1520, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00142e34, 0x00153338, 0x0015363b, 0x00183a3e, 0x00183d41, 0x001a4044, 0x001b4448, 0x001c484c, 0x001d4c50, 0x001f5053, 0x00205457, 0x0021585a, 0x00245c5e, 0x00245e60, 0x00256163, 0x00266467, 0x0028737e, 0x002f90aa, 0x002f91ac, 0x002f92ac, 0x002f92ad, 0x002f92ad, 0x002a7c8c, 0x00266466, 0x00256062, 0x00245d60, 0x0022595c, 0x00215659, 0x001f5254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183c40, 0x0017383c, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081b24, 0x00081c24, 0x00091c24, 0x000b1c25, 0x000c1d26, 0x000c1d26, 0x000d1d26, 0x000d1d27, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1e28, 0x000f1e29, 0x000f1e29, 0x000f1e29, 0x000f1e29, 0x000f1f28, 0x00101f28, 0x0010202a, 0x0010202b, 0x0011202c, 0x0010212c, 0x0010222c, 0x0010222c, 0x0010222e, 0x0010222e, 0x0010242f, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222e, 0x0010212e, 0x0010202d, 0x000e1f2c, 0x000d1e2b, 0x000c1e2a, 0x000c1e2c, 0x000c1e2c, 0x000c1d2c, 0x000c1c28, 0x000c1c28, 0x000d1b28, 0x000e1b28, 0x000e1b28, 0x000f1c29, 0x000e1c28, 0x000c1c28, 0x000f1e2b, 0x0012212e, 0x00142531, 0x001c2e3b, 0x0020303e, 0x00233440, 0x00283844, 0x002b3946, 0x002d3844, 0x002e3844, 0x002f3846, 0x002d3745, 0x00283341, 0x00202b38, 0x001a2633, 0x001d2834, 0x00202c36, 0x001c2831, 0x0019252e, 0x001f2a33, 0x0026313a, 0x002b3540, 0x002e3842, 0x00303944, 0x00303946, 0x00303b48, 0x00303b48, 0x00313b48, 0x00313c4a, 0x00333f4c, 0x00394654, 0x003c4c5a, 0x003e505f, 0x00405363, 0x00425668, 0x00435768, 0x00435769, 0x0044586b, 0x00485c6d, 0x004a5c6d, 0x0048596b, 0x00485867, 0x00455660, 0x00414e56, 0x00313c43, 0x0022282f, 0x001c2228, 0x00222831, 0x002c3841, 0x0031424c, 0x00304450, 0x00283c49, 0x00172834, 0x0014242d, 0x0017262e, 0x00112129, 0x0007171f, 0x0007141d, 0x00101c24, 0x00121e25, 0x00101a21, 0x00111c23, 0x0014202b, 0x001a2b34, 0x00182832, 0x001c2b35, 0x002b3a45, 0x002c3b45, 0x002f3b45, 0x00303a44, 0x002f3944, 0x00323c49, 0x003a4454, 0x003c4958, 0x003e4c5c, 0x003f4c5c, 0x00404d5d, 0x00404e5d, 0x003f4d5b, 0x003d4c58, 0x0040505c, 0x00445463, 0x00475868, 0x004c5c6d, 0x004d5d6e, 0x004d5e6e, 0x004e5c6d, 0x004f5b6c, 0x004d5868, 0x004c5866, 0x004b5666, 0x004a5566, 0x004a5668, 0x004c586b, 0x004f5d70, 0x00536174, 0x00546476, 0x00536476, 0x00526074, 0x00505e70, 0x004c5a6c, 0x004c586b, 0x004c586c, 0x004c596c, 0x00505d70, 0x00526074, 0x00516375, 0x00506274, 0x004e6072, 0x004f6073, 0x004d5f71, 0x004a5c6f, 0x0046586b, 0x00445568, 0x00445466, 0x00435364, 0x00435263, 0x00445263, 0x00445060, 0x00414c5c, 0x003c4855, 0x00384350, 0x00303c4a, 0x002a3746, 0x002a3947, 0x002c3b48, 0x00293a46, 0x001c2c38, 0x001a2732, 0x001a2832, 0x0013212c, 0x000c1a25, 0x000c1824, 0x00101e29, 0x0010202a, 0x00102029, 0x0013232c, 0x00182935, 0x001d2f3c, 0x001d303d, 0x00243845, 0x002f4450, 0x00354957, 0x00374856, 0x003b4856, 0x00404b59, 0x00485261, 0x004c5868, 0x004c5c6d, 0x004b5d70, 0x004a5e70, 0x00495d70, 0x00485c6f, 0x00485a6e, 0x004a5c70, 0x004c5e71, 0x004c5e71, 0x004a5c70, 0x00485b6e, 0x0047596b, 0x00415466, 0x00405164, 0x00414f62, 0x003d4b5c, 0x00394757, 0x00344250, 0x00303d4b, 0x00303c4a, 0x002f3b48, 0x002e3a45, 0x002e3843, 0x002c3741, 0x002b3540, 0x002b333e, 0x0028303c, 0x0028303a, 0x0028303b, 0x0028303b, 0x00272f38, 0x00232c34, 0x00202831, 0x001e2630, 0x001a232c, 0x00172028, 0x0018202a, 0x0018242c, 0x0019252d, 0x00142028, 0x00141e27, 0x00162028, 0x00182329, 0x00192329, 0x001b232b, 0x001d242d, 0x00212630, 0x00242834, 0x00272c37, 0x00282e3a, 0x002c3440, 0x00303845, 0x00303945, 0x002e3945, 0x002d3745, 0x002b3342, 0x00283240, 0x00273441, 0x00293946, 0x00283c49, 0x00243845, 0x001c303c, 0x001c2f3b, 0x00192c3b, 0x00182a38, 0x00182837, 0x00162735, 0x00142534, 0x00132432, 0x00122431, 0x00122430, 0x0011232f, 0x0010212e, 0x0010202d, 0x0010202c, 0x00101f2c, 0x000e1e28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000d1c28, 0x000d1c27, 0x000d1b26, 0x000d1a26, 0x000d1a26, 0x000e1b26, 0x000f1c28, 0x000f1c28, 0x00101d28, 0x00101e2a, 0x00101e2a, 0x000f1e29, 0x000e1e28, 0x000e1e28, 0x000e1e28, 0x000e1e28, 0x000e1d28, 0x000e1d28, 0x000e1c28, 0x000f1c26, 0x000e1c25, 0x000e1b24, 0x000e1a24, 0x000d1924, 0x000b1921, 0x000a1820, 0x00091820, 0x00091720, 0x00081520, 0x0008141f, 0x0008141f, 0x0008131e, 0x0009131e, 0x0009141e, 0x000b1520, 0x000b1520, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f2229, 0x0012242c, 0x0012242c, 0x0010282e, 0x00132c32, 0x00132e34, 0x00153338, 0x00153439, 0x0016383c, 0x00183d41, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4c50, 0x001e5053, 0x00205356, 0x0022585a, 0x00235c5e, 0x00245e60, 0x00256163, 0x00276970, 0x002d8ca5, 0x002f92ac, 0x002f91ac, 0x003091ab, 0x002f90aa, 0x002e8fa8, 0x00286f78, 0x00266364, 0x00246062, 0x00245d60, 0x00235a5c, 0x00215659, 0x00205356, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00173c40, 0x0017383c, 0x00143439, 0x00153338, 0x00132e34, 0x00112a30, 0x0010282e, 0x0012242c, 0x00102229, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081a22, 0x00081b24, 0x00081c24, 0x000a1c24, 0x000b1c25, 0x000c1c25, 0x000c1c26, 0x000d1d26, 0x000d1c27, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1d27, 0x000e1e27, 0x000f1f28, 0x00101f2a, 0x0010202b, 0x0010202c, 0x0010212c, 0x0010212c, 0x0010212e, 0x0010212e, 0x0010222e, 0x000f242f, 0x000f242f, 0x000f242f, 0x000f242f, 0x000f232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222e, 0x000f222e, 0x000f222e, 0x0010202d, 0x000f202d, 0x000e1f2c, 0x000c1e2a, 0x000c1e2a, 0x000c1e2c, 0x000c1e2c, 0x000c1d2c, 0x000c1c28, 0x000c1c28, 0x000d1c28, 0x000d1c28, 0x000d1c29, 0x000e1c29, 0x000d1c28, 0x000c1c28, 0x000f1e2b, 0x0012212e, 0x00142431, 0x001c2d39, 0x0020303e, 0x0022333f, 0x00263542, 0x00293845, 0x002c3844, 0x002e3844, 0x002f3846, 0x002d3744, 0x00283341, 0x00202b38, 0x001a2634, 0x001c2834, 0x001f2a34, 0x001c2832, 0x001b272f, 0x001f2b33, 0x0027323c, 0x002c3640, 0x002d3842, 0x002f3843, 0x00303946, 0x00303a47, 0x00303a46, 0x00303a47, 0x00333e4c, 0x00364250, 0x00374552, 0x00394857, 0x003d4e5e, 0x00405364, 0x00425668, 0x00435768, 0x00435769, 0x0043586a, 0x00465a6b, 0x00485a6c, 0x00485869, 0x00455462, 0x00414f58, 0x00344046, 0x00252c33, 0x001c2024, 0x0017191d, 0x001a1c24, 0x00283038, 0x0031404a, 0x00334550, 0x002e424f, 0x001c2e39, 0x0015252e, 0x0017272e, 0x0014242c, 0x000e1f28, 0x00102029, 0x001a2a33, 0x0020313a, 0x00192830, 0x00132028, 0x0015242c, 0x001a2b34, 0x00192932, 0x0022323b, 0x002f3f48, 0x002c3c45, 0x002b3841, 0x0029343e, 0x0027303b, 0x002d3742, 0x002e3744, 0x00333e4b, 0x00364250, 0x00384451, 0x00384654, 0x003a4958, 0x003a4a58, 0x00394855, 0x003a4956, 0x003d4d5c, 0x00404e5e, 0x00435264, 0x00485868, 0x004a5a6a, 0x004c596a, 0x004c5868, 0x004a5565, 0x004a5563, 0x004a5564, 0x004a5565, 0x004a5566, 0x004c5769, 0x004e5b6d, 0x00505f71, 0x00516174, 0x00516274, 0x004f5e70, 0x004d5c6f, 0x004c5b6d, 0x004a576a, 0x00485467, 0x00485468, 0x00495669, 0x004d5c6e, 0x004e6071, 0x004c5e70, 0x004b5c6d, 0x00495a6c, 0x0048586b, 0x00455467, 0x00405062, 0x003d4d5f, 0x003d4d5c, 0x003d4c5c, 0x003c4a5a, 0x003c4858, 0x003b4554, 0x00363f4c, 0x00333c48, 0x00313a46, 0x00293240, 0x00293544, 0x002d3c49, 0x0031404d, 0x002f404c, 0x0023333e, 0x00162530, 0x00182831, 0x0014242f, 0x0011202b, 0x00172430, 0x00202f3a, 0x00182832, 0x0010222a, 0x000e212c, 0x00122431, 0x00142734, 0x00142835, 0x001b2f3c, 0x002c414d, 0x00314450, 0x00303d49, 0x0028303b, 0x001f242f, 0x00232833, 0x002f3642, 0x003a4654, 0x00475868, 0x004b5e70, 0x004a5e70, 0x00485c70, 0x0046596c, 0x0046586c, 0x0046586c, 0x00485a6e, 0x00485a6e, 0x00485b6e, 0x00485c6d, 0x0046586a, 0x00465769, 0x00465467, 0x00414e60, 0x003b4858, 0x00364453, 0x00323e4d, 0x00303c4b, 0x00303c49, 0x00303c48, 0x00303a44, 0x002d3842, 0x002b3540, 0x002a333e, 0x0028303c, 0x0028303b, 0x0028303b, 0x0028303b, 0x00272f38, 0x00242c35, 0x00222a34, 0x00202831, 0x001c242d, 0x00171f28, 0x00161f28, 0x0016212a, 0x0018242c, 0x00162029, 0x00152028, 0x0018232c, 0x001b252c, 0x001c262d, 0x001c242c, 0x001c242c, 0x001f242d, 0x00212632, 0x00242934, 0x00252c37, 0x0029303c, 0x002f3743, 0x00303a46, 0x00303a47, 0x002e3846, 0x002b3341, 0x0028313e, 0x0024303d, 0x00243441, 0x00253844, 0x00213541, 0x001d303c, 0x001c2d3a, 0x00182c39, 0x00172837, 0x00162735, 0x00142534, 0x00142433, 0x00122430, 0x00112430, 0x00112330, 0x0010212e, 0x0010202d, 0x000f202c, 0x000f1f2c, 0x000e1e2b, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000c1c27, 0x000c1a26, 0x000c1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000e1c27, 0x000e1c27, 0x000f1c28, 0x000f1d28, 0x000f1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000e1d28, 0x000e1c28, 0x000d1c28, 0x000d1c28, 0x000d1c27, 0x000e1c25, 0x000d1b24, 0x000d1a24, 0x000d1924, 0x000c1823, 0x000b1820, 0x0009171f, 0x0008161f, 0x0008151e, 0x0008151e, 0x0008141e, 0x0009141e, 0x000a141e, 0x000b131e, 0x000b141f, 0x000c1420, 0x000c1420, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f2229, 0x0012242c, 0x0012242c, 0x0010282e, 0x00112a30, 0x00142e34, 0x00153338, 0x00143439, 0x00183a3e, 0x00183d41, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4c50, 0x001f5053, 0x00205457, 0x0021585a, 0x00235a5c, 0x00245e60, 0x00276b74, 0x002f98b6, 0x0031a4c7, 0x003099b8, 0x003099b8, 0x00309ab8, 0x00319cbd, 0x0034a6cb, 0x00297886, 0x00266466, 0x00256163, 0x00245e60, 0x00245c5e, 0x0021585a, 0x00205457, 0x001f5053, 0x001d4c50, 0x001c484c, 0x001b4649, 0x001a4245, 0x00183d41, 0x00183a3e, 0x0016363b, 0x00143338, 0x00143036, 0x00132c32, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091921, 0x00091b24, 0x00091b24, 0x000a1c24, 0x000a1c24, 0x000b1c25, 0x000c1c25, 0x000c1c25, 0x000c1c26, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c26, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c26, 0x000d1d26, 0x000e1d28, 0x000f1e28, 0x00101f29, 0x0010202b, 0x0010202c, 0x0010202c, 0x0010202d, 0x0010202d, 0x000f212d, 0x000e222e, 0x000e222e, 0x000e222e, 0x000e222e, 0x000e222e, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000f202d, 0x000f202c, 0x000e1f2c, 0x000c1e2a, 0x000c1e2a, 0x000c1e2c, 0x000c1e2c, 0x000c1e2c, 0x000c1d28, 0x000c1d28, 0x000c1c28, 0x000d1c29, 0x000d1c29, 0x000d1c29, 0x000c1c28, 0x000c1c28, 0x000f1e2b, 0x0012212e, 0x00152431, 0x001c2c39, 0x0021303e, 0x00223340, 0x00253541, 0x00293744, 0x002c3844, 0x002e3844, 0x002f3846, 0x002c3644, 0x00293340, 0x00232d3c, 0x001e2836, 0x001d2833, 0x001e2934, 0x001f2b35, 0x001d2933, 0x00202c35, 0x0028343e, 0x002a3640, 0x002b3741, 0x002d3842, 0x002f3843, 0x00303944, 0x002f3844, 0x00303946, 0x00333d4c, 0x00374452, 0x00394755, 0x003c4b59, 0x003c4e5e, 0x00405264, 0x00425668, 0x00425668, 0x00425668, 0x0044586b, 0x0047596b, 0x00485869, 0x00455464, 0x00404d5b, 0x003a4750, 0x002b343c, 0x0021272d, 0x001d2026, 0x001a1c1f, 0x001a181f, 0x001e222a, 0x002b3740, 0x0032444f, 0x00344954, 0x00263944, 0x00172831, 0x00182931, 0x0020333b, 0x00223740, 0x001f333c, 0x00223742, 0x002b414c, 0x0020353e, 0x001c2e38, 0x001c2e37, 0x00182830, 0x001b2b34, 0x002d3c46, 0x0033434c, 0x00303f46, 0x002c3840, 0x00283039, 0x00242a34, 0x00242a34, 0x00222832, 0x00283039, 0x00343c48, 0x0038414d, 0x00384350, 0x00374451, 0x00364451, 0x00354450, 0x00354350, 0x00384654, 0x003b4857, 0x003c4959, 0x00414f5d, 0x00445361, 0x00475464, 0x00485463, 0x00485461, 0x00485361, 0x00485363, 0x00485464, 0x00495465, 0x004c5869, 0x00505c6f, 0x00516073, 0x00506073, 0x00506072, 0x0049586b, 0x00475668, 0x00485769, 0x00485467, 0x00455364, 0x00445164, 0x00465365, 0x00455465, 0x00475768, 0x00475768, 0x00475768, 0x00475668, 0x00425063, 0x003c4859, 0x003c4858, 0x003a4858, 0x00394655, 0x00394655, 0x00394353, 0x0038404d, 0x00343944, 0x002a2f39, 0x002a2f39, 0x002c313c, 0x00252c38, 0x002a3440, 0x00303c49, 0x0034434f, 0x00344550, 0x002c3c47, 0x00182732, 0x00192833, 0x0020313c, 0x0020303c, 0x0022333d, 0x002a3c46, 0x0020343d, 0x00192f38, 0x001c323c, 0x00182c38, 0x00142734, 0x00142634, 0x00233642, 0x0031444f, 0x00303e4a, 0x0028303b, 0x001e2029, 0x001b1a21, 0x001c1c22, 0x0021222a, 0x00232934, 0x0032404d, 0x00425262, 0x0048596b, 0x004c5f71, 0x004c5f73, 0x004a5d70, 0x00485b6e, 0x00485a6e, 0x00485b6f, 0x00485b6e, 0x00475a6c, 0x0047596b, 0x00465769, 0x00435264, 0x00404c5e, 0x003c4959, 0x00394655, 0x00354150, 0x00343e4e, 0x00313b4a, 0x00303a47, 0x002e3844, 0x002c3640, 0x0029333e, 0x0029323e, 0x0029313e, 0x0028303d, 0x0028303b, 0x0028303b, 0x00272f38, 0x00252e37, 0x00242c34, 0x00212a33, 0x001d262f, 0x00171f28, 0x00161e28, 0x00162029, 0x0018222b, 0x00172029, 0x00162029, 0x001a242c, 0x001c272f, 0x001c262f, 0x001c242c, 0x001c242c, 0x001c232c, 0x001d242d, 0x00202730, 0x00242a35, 0x0028303b, 0x002e3641, 0x00313a47, 0x00303a47, 0x002f3948, 0x002c3444, 0x00283240, 0x00212d3b, 0x00202e3c, 0x00213240, 0x0020323f, 0x001c2f3a, 0x001c2c38, 0x00192c38, 0x00162834, 0x00142534, 0x00142433, 0x00132432, 0x00112330, 0x0010222e, 0x0010212e, 0x0010202d, 0x000f202c, 0x000e1f2c, 0x000e1e2c, 0x000e1d2a, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000c1c27, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000d1a26, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000d1c27, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1c27, 0x000d1c28, 0x000c1c27, 0x000c1a26, 0x000c1a26, 0x000d1a24, 0x000c1a24, 0x000c1924, 0x000c1823, 0x000c1822, 0x000a1820, 0x0009171f, 0x0008161e, 0x0008151d, 0x0008141d, 0x0008141d, 0x0009141d, 0x000b141e, 0x000c141f, 0x000c141f, 0x000c1420, 0x000c1420, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00143036, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183f43, 0x001a4245, 0x001b4649, 0x001c4a4d, 0x001d4d50, 0x00205154, 0x00205457, 0x0021585a, 0x00245c5e, 0x00266c78, 0x002f9bbc, 0x0030a0c4, 0x00297b8b, 0x0027686b, 0x0028686c, 0x0028696c, 0x002b7886, 0x0033a4c8, 0x00297886, 0x00266466, 0x00256163, 0x00245f61, 0x00245c5e, 0x0022585b, 0x00205558, 0x00205254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4448, 0x001a4044, 0x00183d41, 0x00183a3e, 0x0015363b, 0x00153338, 0x00142e34, 0x00132c32, 0x00112a30, 0x0011242c, 0x0012242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091921, 0x00091a23, 0x00091a23, 0x00091b24, 0x000a1c24, 0x000b1c24, 0x000c1b24, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c27, 0x000c1c27, 0x000c1b25, 0x000c1b24, 0x000c1b24, 0x000c1b26, 0x000c1b26, 0x000c1c25, 0x000c1c25, 0x000f1d26, 0x00101d27, 0x00101d27, 0x000f1f29, 0x000f202b, 0x000f202b, 0x000f202c, 0x000f202c, 0x000f202c, 0x000f202c, 0x000f202c, 0x000f202d, 0x000f202d, 0x000f202d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000d202c, 0x0010202d, 0x000f202c, 0x000e1f2c, 0x000c1e2a, 0x000c1e2a, 0x000c1e2c, 0x000c1e2c, 0x000c1e2b, 0x000c1d28, 0x000c1d28, 0x000c1c29, 0x000d1c29, 0x000d1c29, 0x000d1c29, 0x000c1c28, 0x000c1c28, 0x000e1d2a, 0x0011202d, 0x00142430, 0x001c2c38, 0x0022313e, 0x00233440, 0x00253542, 0x00293744, 0x002c3844, 0x002d3844, 0x002e3745, 0x002c3544, 0x0027303e, 0x00232c39, 0x00202935, 0x001e2833, 0x00212b35, 0x00212c36, 0x001e2a34, 0x00212d37, 0x0028343e, 0x00293540, 0x002a3640, 0x002c3842, 0x002f3843, 0x002f3844, 0x00303a48, 0x00313b49, 0x00323d4c, 0x00344150, 0x00384655, 0x003e4d5c, 0x003f5060, 0x00405465, 0x00425668, 0x00435668, 0x00435568, 0x00445668, 0x00455567, 0x00445363, 0x00404d5c, 0x003b4654, 0x00344048, 0x00262f37, 0x0022282e, 0x00202429, 0x001f2024, 0x001d1c22, 0x001b1e24, 0x00202931, 0x002d3b45, 0x00384954, 0x00344752, 0x0020343d, 0x00283d47, 0x002e454f, 0x00253e48, 0x00203943, 0x0027424e, 0x003c5864, 0x002e4652, 0x001d323d, 0x00192b34, 0x00192a34, 0x00283842, 0x0034444d, 0x0034424c, 0x00303c44, 0x00283138, 0x0022262f, 0x001e2129, 0x001b1d27, 0x001c1f28, 0x0020252e, 0x00282c37, 0x002d333e, 0x00333a46, 0x00394350, 0x00374350, 0x0032404d, 0x00303c4a, 0x00303c4b, 0x00374350, 0x00384452, 0x00384451, 0x003c4855, 0x00404c58, 0x00404c59, 0x00404c58, 0x00434c5a, 0x00434d5c, 0x00444e5f, 0x00465263, 0x004b5668, 0x004e5b6c, 0x00536073, 0x00526073, 0x004f5e70, 0x004a596b, 0x00485768, 0x00485668, 0x00455264, 0x00435060, 0x00435060, 0x00435060, 0x00425060, 0x00415060, 0x00404f5e, 0x00404e5e, 0x003f4c5c, 0x00374353, 0x0034404e, 0x00384351, 0x00384453, 0x00394453, 0x00384250, 0x00333948, 0x002d313d, 0x00262933, 0x0021232c, 0x001f2029, 0x001f202a, 0x0021242f, 0x00272e39, 0x002d3843, 0x0034414c, 0x00364650, 0x0034444f, 0x0022313c, 0x00162732, 0x001e2f3b, 0x00243540, 0x00273a44, 0x00394f59, 0x0029404b, 0x001b343f, 0x00203844, 0x00253b48, 0x001d303d, 0x001e303c, 0x0030404b, 0x0032404a, 0x0028323c, 0x001e232c, 0x001b1c25, 0x001e1d24, 0x00212128, 0x00222229, 0x0020242d, 0x0027323e, 0x00364351, 0x003f4e5d, 0x00465768, 0x00475a6c, 0x0045596c, 0x0044586c, 0x0045596c, 0x00465a6d, 0x00465a6c, 0x00475b6c, 0x00485a6c, 0x00455769, 0x00445465, 0x00404f60, 0x003c4c5a, 0x003c4a58, 0x003a4654, 0x0036404e, 0x00303a48, 0x002d3844, 0x002b3540, 0x002b343f, 0x0029333d, 0x002a323e, 0x0029313e, 0x0029313e, 0x0028303c, 0x0028303b, 0x00272f39, 0x00272f38, 0x00262e37, 0x00242c35, 0x00202831, 0x0018202a, 0x00171f28, 0x00172029, 0x0018212a, 0x0018212a, 0x0018222b, 0x001a262e, 0x001c2830, 0x001d2730, 0x001c242e, 0x001c242e, 0x001c242c, 0x001d242d, 0x001f2530, 0x00222834, 0x00272e39, 0x002d3440, 0x00313945, 0x00303a47, 0x00303948, 0x002c3544, 0x00283140, 0x00222c3b, 0x001e2b38, 0x001e2d3b, 0x001d2f3c, 0x001c2e38, 0x001b2c38, 0x00182b37, 0x00162733, 0x00142433, 0x00142433, 0x00132432, 0x00112330, 0x0010212e, 0x0010212e, 0x0010202d, 0x000f202c, 0x000e1f2c, 0x000d1d2a, 0x000d1c29, 0x000d1c28, 0x000d1c28, 0x000c1c27, 0x000c1c27, 0x000c1b26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000d1a26, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000d1b27, 0x000c1b26, 0x000c1a26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000b1823, 0x000b1822, 0x000c1822, 0x000c1821, 0x000c1821, 0x000c1820, 0x000a161f, 0x0008161e, 0x0009151e, 0x0008141d, 0x0008141d, 0x0009141d, 0x000b141f, 0x000c141f, 0x000c141f, 0x000c1420, 0x000c1420, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x000f2229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00153338, 0x00143439, 0x00183a3e, 0x00183d41, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4b4e, 0x001e4f51, 0x00205254, 0x00205558, 0x0022595c, 0x00267080, 0x002f9ec0, 0x00309dc0, 0x00287482, 0x00266467, 0x00276668, 0x00276769, 0x00286769, 0x002a7784, 0x0033a4c8, 0x00297886, 0x00266466, 0x00256264, 0x00246062, 0x00245d60, 0x00235a5c, 0x0021585a, 0x00205457, 0x001f5154, 0x001d4d50, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183d41, 0x00173a3e, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0012242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091820, 0x00081821, 0x00081821, 0x00081a23, 0x00091b24, 0x000a1b24, 0x000b1a24, 0x000b1a24, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b26, 0x000c1b26, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000c1b26, 0x000c1b26, 0x000c1b25, 0x000c1b24, 0x000e1c25, 0x000f1c26, 0x000f1c26, 0x000e1e28, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x000f1f2b, 0x000f202b, 0x000f202b, 0x000f202c, 0x000f202c, 0x000f202c, 0x000f202c, 0x000e202c, 0x000d202c, 0x000d202c, 0x000c202c, 0x000c202c, 0x000c1f2c, 0x000e1f2c, 0x000e1f2c, 0x000d1e2a, 0x000c1e28, 0x000c1e28, 0x000c1e29, 0x000c1e29, 0x000d1e29, 0x000c1d28, 0x000c1e28, 0x000c1e29, 0x000c1e2a, 0x000c1d29, 0x000d1c29, 0x000d1c29, 0x000d1c29, 0x000e1d2a, 0x0010202c, 0x00142331, 0x001c2c3a, 0x00223241, 0x00243444, 0x00273645, 0x00293644, 0x002b3644, 0x002c3544, 0x002d3544, 0x002c3442, 0x00252d3a, 0x00202934, 0x001e2831, 0x001f2831, 0x00232d36, 0x00242d38, 0x00202a34, 0x00222c37, 0x0028323d, 0x002a343e, 0x002b343f, 0x002c3741, 0x002d3842, 0x002f3944, 0x00323c48, 0x00343e4b, 0x00313c4a, 0x00333f4c, 0x00384553, 0x00404e5c, 0x00415162, 0x00425564, 0x00415565, 0x00415465, 0x00425466, 0x00445667, 0x00445464, 0x00404e5d, 0x003b4755, 0x00343e4b, 0x002e3440, 0x00282c37, 0x00272b33, 0x00272830, 0x0026262d, 0x00242329, 0x00202027, 0x001d2028, 0x00222832, 0x002e3945, 0x00384854, 0x003c4f5c, 0x00384d5a, 0x00263d49, 0x00243c48, 0x001c3541, 0x0027434f, 0x003a5662, 0x00344c58, 0x00182c39, 0x00182a35, 0x00283844, 0x0033434e, 0x0032404c, 0x002e3a44, 0x00283038, 0x0022262e, 0x001e1f27, 0x001b1b23, 0x001a1b23, 0x0020212a, 0x0023252e, 0x0024252d, 0x0021222c, 0x00252832, 0x002d333f, 0x00353f4b, 0x00323d49, 0x002a3542, 0x00283140, 0x00333c4a, 0x00343d4b, 0x00313c49, 0x0035414e, 0x00394451, 0x003b4653, 0x003c4854, 0x003d4855, 0x003d4857, 0x003c4856, 0x003e4958, 0x00404c5b, 0x00455060, 0x004d5968, 0x00505e6e, 0x004d5c6c, 0x004b596b, 0x004a5868, 0x00485565, 0x00465261, 0x00424d5c, 0x003f4a58, 0x003b4854, 0x003a4754, 0x00394654, 0x00394554, 0x00384454, 0x0034404f, 0x002a3444, 0x002a3441, 0x00343d4b, 0x003a4451, 0x00343e4c, 0x00282f3c, 0x00202430, 0x0021232c, 0x0024242b, 0x00212027, 0x001d1c20, 0x001c1b21, 0x001e1f27, 0x00242831, 0x0029303a, 0x002f3843, 0x00333f4a, 0x0035434d, 0x0030404a, 0x001e2e38, 0x00152730, 0x00192d37, 0x00294048, 0x0039515b, 0x002e4853, 0x001b3440, 0x00203844, 0x00233844, 0x002a3b47, 0x00303e48, 0x00313c46, 0x00262e38, 0x001d232e, 0x001c2029, 0x00202029, 0x0022212b, 0x0024242c, 0x0023242e, 0x0020242e, 0x00232b35, 0x002d3743, 0x003a4551, 0x00455260, 0x00485867, 0x00445768, 0x00405467, 0x00405467, 0x0044566a, 0x0046586c, 0x00485b6e, 0x00485a6c, 0x00425466, 0x00405163, 0x00404f60, 0x003c4c58, 0x003b4b56, 0x003a4854, 0x0034404c, 0x002f3845, 0x002c3744, 0x002b3642, 0x002b3540, 0x0029333d, 0x002a343e, 0x002a343f, 0x002a343f, 0x0029333e, 0x0028323c, 0x0028303c, 0x0028303c, 0x0028303a, 0x00262e38, 0x00242a35, 0x001c222e, 0x00171f29, 0x00162029, 0x0019232c, 0x001a242c, 0x0019252d, 0x001b272f, 0x001c2830, 0x001d2730, 0x001d2630, 0x001c242e, 0x001c242c, 0x001c242d, 0x001e252f, 0x00202831, 0x00242b36, 0x002a323d, 0x00303843, 0x00313945, 0x00303845, 0x002c3542, 0x0028303d, 0x00222c39, 0x001d2836, 0x001c2b37, 0x001c2c38, 0x001a2c38, 0x00192b38, 0x00162834, 0x00152633, 0x00142431, 0x00122430, 0x00112330, 0x0012212f, 0x0011202d, 0x0011202c, 0x0010202c, 0x00101f2b, 0x000f1e2a, 0x000e1d29, 0x000d1c28, 0x000e1b27, 0x000d1b26, 0x000c1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000d1a26, 0x000c1a27, 0x000c1b28, 0x000c1a27, 0x000b1824, 0x000b1824, 0x000b1924, 0x000b1a24, 0x000b1a24, 0x000b1823, 0x000a1821, 0x000a1821, 0x00091720, 0x000a1720, 0x000c1821, 0x000c1620, 0x000c1620, 0x000c1620, 0x000d1520, 0x000b1620, 0x000b1520, 0x000b151e, 0x000b151e, 0x000b1520, 0x000a1520, 0x000a1520, 0x000a1520, 0x000a1520, 0x000a1520, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x000f2229, 0x0012242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00153036, 0x00143439, 0x0017383c, 0x00183c40, 0x00194044, 0x001b4448, 0x001c474b, 0x001d4b4e, 0x001e4f51, 0x001f5154, 0x00205457, 0x0021575a, 0x00267588, 0x00309fc4, 0x002e99bb, 0x00276e79, 0x00256264, 0x00266466, 0x00266568, 0x00276668, 0x00286769, 0x002a7784, 0x0032a4c8, 0x00297886, 0x00266467, 0x00266364, 0x00256163, 0x00245e60, 0x00245c5f, 0x0022595c, 0x00215659, 0x00205457, 0x001f5154, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x001a4245, 0x00183d41, 0x0017383c, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081820, 0x00081821, 0x00071821, 0x00081922, 0x00091922, 0x00091922, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1823, 0x000c1924, 0x000c1924, 0x000b1924, 0x000b1a24, 0x000b1a24, 0x000c1b26, 0x000c1b26, 0x000c1a24, 0x000c1a24, 0x000d1b24, 0x000e1c25, 0x000f1c26, 0x000e1d28, 0x000d1e28, 0x000d1e28, 0x000e1f29, 0x000e1f29, 0x000e1f2a, 0x000f1f29, 0x000f1f29, 0x000f1e2b, 0x000f1e2c, 0x000e1e2c, 0x000e1f2c, 0x000e1f2c, 0x000c1f2c, 0x000c1f2c, 0x000c1e2a, 0x000a1e28, 0x000b1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000d1e28, 0x000c1d28, 0x000c1e28, 0x000c1e29, 0x000c1e2a, 0x000c1d29, 0x000d1c29, 0x000d1c29, 0x000e1d2a, 0x000e1d2a, 0x00101f2c, 0x00132230, 0x001c2b39, 0x00233342, 0x00243544, 0x00283645, 0x00293644, 0x002b3644, 0x002c3544, 0x002d3544, 0x002c3442, 0x00242c38, 0x001f2831, 0x001c2730, 0x001f2932, 0x00232d36, 0x00232d38, 0x00202934, 0x00222c37, 0x0028323c, 0x0029333e, 0x002b343f, 0x002c3741, 0x002d3842, 0x002f3843, 0x00303a46, 0x00333c48, 0x00343d4b, 0x00343f4d, 0x00384553, 0x003d4a59, 0x00404f5f, 0x00405362, 0x00405363, 0x00405363, 0x00425464, 0x00455767, 0x00445362, 0x003d4958, 0x0035404c, 0x002c343f, 0x00272c37, 0x00292c35, 0x002b2f35, 0x002a2c33, 0x002b2b32, 0x002a2830, 0x0027262c, 0x0024242a, 0x0020232b, 0x00222832, 0x00283340, 0x00374452, 0x00374653, 0x002a3c48, 0x00223540, 0x00192d38, 0x00243a45, 0x002f4651, 0x002e434f, 0x0022323e, 0x0025343f, 0x002e3c48, 0x002c3944, 0x0025313c, 0x001f2832, 0x001c2029, 0x001c1d24, 0x001a1820, 0x0019171e, 0x0019181f, 0x001b1a22, 0x00191920, 0x0019181f, 0x001a1921, 0x001e1d27, 0x001f212c, 0x00282e39, 0x002f3844, 0x0028323e, 0x00252d39, 0x002d3541, 0x002e3642, 0x002d3744, 0x00333d49, 0x0037404d, 0x0039424f, 0x003a4450, 0x003b4451, 0x003b4453, 0x00394351, 0x003c4554, 0x00404856, 0x00404a59, 0x00404959, 0x00404c5c, 0x00414e5f, 0x00414e5f, 0x00404d5d, 0x00414c5c, 0x003f4958, 0x003d4755, 0x003b4552, 0x0038434f, 0x0035414d, 0x0035404d, 0x0035404d, 0x00343e4c, 0x00303947, 0x0028303d, 0x00252d3a, 0x00303844, 0x002f3641, 0x001f2430, 0x00171a26, 0x00181823, 0x001b1a22, 0x001d1b22, 0x001c191f, 0x001b171b, 0x001c181c, 0x001c1a22, 0x001e1e27, 0x001f212c, 0x00202430, 0x00242c37, 0x002a3440, 0x00313d48, 0x002c3a43, 0x001d2c33, 0x00182830, 0x00243840, 0x002d414a, 0x00263a45, 0x001b2e3a, 0x00213440, 0x0023323e, 0x00293540, 0x002d353f, 0x00232831, 0x001c202a, 0x001f202b, 0x0022242c, 0x0026262f, 0x0027272f, 0x00252630, 0x00262732, 0x00252731, 0x00242831, 0x00272c36, 0x00313842, 0x00404a56, 0x00485764, 0x00465869, 0x0043576a, 0x00405468, 0x00415468, 0x00435569, 0x0044576a, 0x00445768, 0x00405365, 0x00405164, 0x003e4e5f, 0x003b4a58, 0x00384753, 0x0034424d, 0x00303b47, 0x002d3744, 0x002c3644, 0x002b3642, 0x002c3640, 0x002a343e, 0x002a343f, 0x002c3640, 0x002c3741, 0x002b3540, 0x002a343e, 0x002a333d, 0x0029313c, 0x0028313c, 0x0028303c, 0x00252c37, 0x001c222e, 0x00171f29, 0x00172029, 0x001a242c, 0x001c2730, 0x001d2830, 0x001b272f, 0x001c272f, 0x001d2730, 0x001d2730, 0x001d252f, 0x001c242e, 0x001c242e, 0x001d252f, 0x00202831, 0x00252b37, 0x002a313c, 0x002e3641, 0x002e3642, 0x002d3542, 0x002a323e, 0x00262f3a, 0x00212c38, 0x001c2834, 0x001c2a35, 0x001b2b37, 0x00192c38, 0x00172936, 0x00142733, 0x00142632, 0x00132430, 0x0011222e, 0x0010212e, 0x0011202d, 0x0010202c, 0x0010202b, 0x000f1f29, 0x000e1e28, 0x000e1d28, 0x000e1d28, 0x000d1c27, 0x000d1b26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000b1926, 0x000b1a27, 0x000b1826, 0x000a1824, 0x000a1823, 0x00091822, 0x00081821, 0x00091822, 0x000a1822, 0x000a1821, 0x000a1821, 0x00091720, 0x000a1620, 0x000c1721, 0x000c1620, 0x000c1620, 0x000c1620, 0x000d1520, 0x000b1620, 0x000b1520, 0x000b151e, 0x000b151e, 0x000b1520, 0x000a1520, 0x000a1520, 0x000a1520, 0x000a1520, 0x000a1520, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00142e34, 0x00143338, 0x0016363b, 0x00183c40, 0x00183f43, 0x001a4347, 0x001c474b, 0x001d4b4e, 0x001e4f51, 0x001f5154, 0x00205356, 0x0021585b, 0x00277c92, 0x002ea0c7, 0x002c95b5, 0x00256870, 0x00256062, 0x00256264, 0x00266466, 0x00266467, 0x00266568, 0x00286668, 0x00297684, 0x0032a4c8, 0x00297886, 0x00266568, 0x00266466, 0x00256264, 0x00256163, 0x00245e60, 0x00245c5f, 0x00235a5c, 0x0021585a, 0x00205558, 0x00205254, 0x001e4f51, 0x001d4c50, 0x001c484c, 0x001b4448, 0x001a4245, 0x00183d41, 0x0017383c, 0x00153439, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091820, 0x00081821, 0x00081821, 0x00081821, 0x00081821, 0x00091821, 0x000a1821, 0x000a1821, 0x000a1820, 0x000b1820, 0x000b1820, 0x000b1820, 0x000b1820, 0x000b1820, 0x000b1921, 0x000b1922, 0x000c1a24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000e1c25, 0x000d1c27, 0x000c1c28, 0x000c1c28, 0x000c1c28, 0x000c1d28, 0x000c1e28, 0x000d1e28, 0x000d1e28, 0x000e1e2b, 0x000e1e2b, 0x000d1e2b, 0x000c1e2a, 0x000c1e2a, 0x000c1e2a, 0x000c1e2a, 0x000b1d28, 0x000a1d26, 0x000a1e26, 0x000c1e27, 0x000c1e27, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000d1e28, 0x000c1d28, 0x000c1e28, 0x000c1e29, 0x000c1e2a, 0x000c1e2a, 0x000c1d29, 0x000c1d29, 0x000e1d2a, 0x000e1d2a, 0x00101f2c, 0x00132230, 0x001b2a38, 0x00223240, 0x00253444, 0x00283645, 0x002a3544, 0x002a3544, 0x002b3544, 0x002c3544, 0x002b3442, 0x00252f3b, 0x00202832, 0x001c262f, 0x001f2931, 0x00212c35, 0x00202a34, 0x001d2832, 0x00232c38, 0x0028333d, 0x002a343f, 0x002c3540, 0x002c3741, 0x002d3842, 0x002d3842, 0x002c3642, 0x002d3744, 0x00333c49, 0x0036414f, 0x00354350, 0x00364452, 0x003a4959, 0x003d4d5e, 0x003f5060, 0x00425363, 0x00425464, 0x00425261, 0x003e4c5a, 0x00384150, 0x002f3644, 0x00282c38, 0x00272b35, 0x002a2f36, 0x002f333b, 0x002d3038, 0x002d2e37, 0x002e2f36, 0x002d2d33, 0x002c2c32, 0x00282830, 0x0024262f, 0x00242630, 0x00262934, 0x00282c37, 0x00282c36, 0x00232933, 0x001f252e, 0x00202831, 0x00212b35, 0x00212b36, 0x00222a35, 0x00242a35, 0x00212834, 0x001f2730, 0x001e242f, 0x001f232c, 0x001f2028, 0x001f1c22, 0x001e1a20, 0x001c181f, 0x001a171d, 0x0018171d, 0x0019181e, 0x001b1b20, 0x001e1e24, 0x00202028, 0x0020212b, 0x00202430, 0x00282e3a, 0x0029303c, 0x00262d38, 0x0029303c, 0x002a323d, 0x002c343f, 0x00303a46, 0x00343d49, 0x00353d49, 0x00353d48, 0x00353d4a, 0x00363e4c, 0x0039404e, 0x003d4553, 0x003f4754, 0x003f4855, 0x003f4856, 0x003d4756, 0x00394454, 0x00394354, 0x00394353, 0x00394351, 0x00394350, 0x00384250, 0x0038414e, 0x0038414e, 0x0036404c, 0x00343d4a, 0x00333a47, 0x00303844, 0x002e3642, 0x002a313c, 0x00272d38, 0x00282d38, 0x0021252f, 0x001a1d26, 0x001c1c24, 0x001c1c24, 0x001b1a22, 0x001c1920, 0x001c181e, 0x001b171c, 0x001d191e, 0x00201c22, 0x00201e26, 0x0020202a, 0x0020212b, 0x001f222d, 0x0020242f, 0x00212830, 0x00232b32, 0x00212a30, 0x001b242c, 0x001b252c, 0x001c272f, 0x001a242e, 0x0019202c, 0x001d242f, 0x00202730, 0x0020272f, 0x0020242c, 0x0020232a, 0x0020222b, 0x0024262f, 0x00272830, 0x0027282f, 0x0026272f, 0x00272830, 0x00292a35, 0x002a2b35, 0x00282a34, 0x00262933, 0x00282d38, 0x00343c48, 0x0043505c, 0x00465667, 0x00445869, 0x00445769, 0x00445568, 0x00425468, 0x00415466, 0x00415465, 0x00425467, 0x00425465, 0x003d4c5d, 0x00384654, 0x0034404c, 0x002f3c47, 0x002d3844, 0x002c3644, 0x002c3643, 0x002a3641, 0x002c3640, 0x002a343f, 0x002b343f, 0x002c3640, 0x002c3640, 0x002b343f, 0x002a343f, 0x002b343e, 0x002a323d, 0x002a323d, 0x0029313c, 0x00272e39, 0x001c242f, 0x0016202a, 0x0017222a, 0x0019242d, 0x001c2830, 0x001e2931, 0x001b272f, 0x0019242c, 0x0019232c, 0x001b242d, 0x001d252f, 0x001e2630, 0x001e2730, 0x00202832, 0x00242c35, 0x0029303b, 0x002b323d, 0x002b323d, 0x00272e39, 0x00262c38, 0x00262d38, 0x00242d38, 0x00212c37, 0x001c2a35, 0x001b2a35, 0x001a2a36, 0x00182a37, 0x00162834, 0x00112531, 0x00122430, 0x0012232f, 0x0010222d, 0x0010212c, 0x0010202b, 0x00101f2b, 0x000e1e29, 0x000e1d28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000c1b26, 0x000c1925, 0x000c1924, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1924, 0x000b1823, 0x000a1824, 0x000a1824, 0x000a1824, 0x000a1822, 0x000a1821, 0x00091821, 0x00091821, 0x00091821, 0x000a1821, 0x00091720, 0x00091720, 0x00091720, 0x000a1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1520, 0x000a1620, 0x000a1520, 0x000a151f, 0x000a151f, 0x000b1520, 0x000a1520, 0x000a1520, 0x000a1520, 0x000b1620, 0x000b1620, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153338, 0x0015363b, 0x00183a3e, 0x00183f43, 0x001a4347, 0x001b4649, 0x001d4b4e, 0x001e4f51, 0x001f5154, 0x00205457, 0x0021585c, 0x0028829c, 0x002fa1c8, 0x002c8fad, 0x0024646b, 0x00245f61, 0x00246062, 0x00266264, 0x00266364, 0x00276467, 0x00266568, 0x00276668, 0x00297684, 0x0032a4c8, 0x002a7887, 0x00276668, 0x00266568, 0x00266466, 0x00266364, 0x00256163, 0x00245f61, 0x00245d60, 0x00245c5e, 0x0022585b, 0x00215659, 0x00205356, 0x001f5053, 0x001d4c50, 0x001c484c, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00143338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1820, 0x00091821, 0x00091821, 0x00081821, 0x00081821, 0x00081821, 0x00091821, 0x000a1821, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1923, 0x000c1923, 0x000c1924, 0x000c1a24, 0x000d1b25, 0x000d1a26, 0x000c1b26, 0x000c1b26, 0x000c1c26, 0x000b1c26, 0x000c1d28, 0x000d1c28, 0x000e1c28, 0x000d1c28, 0x000c1c29, 0x000d1c29, 0x000c1c29, 0x000c1d29, 0x000b1d29, 0x000b1d28, 0x000c1d26, 0x000c1d26, 0x000c1e27, 0x000c1e27, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000d1e28, 0x000c1d28, 0x000c1e28, 0x000c1e29, 0x000c1e2a, 0x000c1e2a, 0x000c1e2a, 0x000c1e2a, 0x000e1d2a, 0x000e1d2a, 0x00101f2c, 0x00132230, 0x00192838, 0x0020303e, 0x00253443, 0x00283545, 0x002a3545, 0x002a3545, 0x002b3544, 0x002c3544, 0x002a3442, 0x0026303c, 0x001f2932, 0x001c262f, 0x00202932, 0x00202a33, 0x001c2630, 0x001c2630, 0x00242e38, 0x002b343f, 0x002c3640, 0x002c3640, 0x002c3741, 0x002d3842, 0x002d3842, 0x002c3642, 0x002b3441, 0x002d3744, 0x00343e4b, 0x0034404e, 0x00354250, 0x003a4857, 0x003c4c5c, 0x003f5060, 0x00425363, 0x00415161, 0x003c4b5a, 0x00384451, 0x00303a48, 0x0028303d, 0x00282d39, 0x002a2e38, 0x002c3139, 0x0032373f, 0x00323740, 0x0031343d, 0x0030333c, 0x00303239, 0x0030313a, 0x002e2f38, 0x002f2f3a, 0x002c2c38, 0x002a2a37, 0x00272733, 0x00272633, 0x00262531, 0x0024232d, 0x0022232b, 0x0022242d, 0x0021242e, 0x0021232f, 0x00222430, 0x00222430, 0x00222530, 0x00232630, 0x0022242d, 0x00232229, 0x00201e24, 0x00211d24, 0x00211d24, 0x00201d23, 0x001e1d23, 0x00202026, 0x00222328, 0x0024272f, 0x00262830, 0x00252831, 0x00242831, 0x00242b34, 0x00272d37, 0x00272c37, 0x00292f39, 0x0028303b, 0x0028303c, 0x002e3741, 0x00313944, 0x00333a45, 0x00343b45, 0x00343c48, 0x00343c48, 0x00353c49, 0x0038404d, 0x0039414d, 0x0038424e, 0x003b4451, 0x003c4554, 0x00394352, 0x00384152, 0x00384050, 0x00373f4d, 0x00353e4c, 0x00343d4a, 0x00343e4b, 0x0035404c, 0x00343c49, 0x00333a48, 0x002f3543, 0x002d3440, 0x002d3541, 0x002c323e, 0x00272c37, 0x00242833, 0x0022242e, 0x0022252d, 0x0025272e, 0x0025252c, 0x0024232b, 0x00232028, 0x00211d24, 0x00201d23, 0x00211d24, 0x00201d23, 0x00202026, 0x00232229, 0x0024242d, 0x0025252f, 0x0024252e, 0x0020242c, 0x001f2329, 0x001e2328, 0x001e242a, 0x001d222a, 0x001c2029, 0x001c2029, 0x001f212c, 0x0021232d, 0x0020242c, 0x0021262d, 0x00242830, 0x00282b33, 0x00282b34, 0x00292b34, 0x00292b34, 0x00272931, 0x00272932, 0x00282b34, 0x002a2c37, 0x002b2d38, 0x00292c35, 0x00282b34, 0x00282c37, 0x0029303c, 0x00343d4a, 0x003d4a5a, 0x003e4f5f, 0x00405061, 0x00415364, 0x00425366, 0x003f5062, 0x003c4e5f, 0x003d4f60, 0x003e4f60, 0x003c4a5a, 0x00374452, 0x00333f4b, 0x002f3a46, 0x002d3843, 0x002c3742, 0x002b3641, 0x002a3640, 0x002c3640, 0x002c3640, 0x002c3640, 0x002c3741, 0x002c3540, 0x002a343e, 0x0029333e, 0x002a333d, 0x002a323d, 0x002a323d, 0x002a323d, 0x00272f3a, 0x001d2530, 0x0015202a, 0x0017232b, 0x0019252e, 0x001c2830, 0x001f2b34, 0x001d2933, 0x001a242e, 0x001a232d, 0x001c242f, 0x001f2731, 0x00212932, 0x00232b34, 0x00272f38, 0x0029313b, 0x002b313c, 0x002b303c, 0x00272c38, 0x00232834, 0x00242834, 0x00242c36, 0x00242d37, 0x00222c37, 0x001c2a36, 0x001b2a35, 0x00192a35, 0x00182a37, 0x00152834, 0x00102430, 0x0010232f, 0x0011222e, 0x0010212c, 0x0010202c, 0x0010202a, 0x000e1e29, 0x000d1c28, 0x000c1c27, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000c1b26, 0x000b1824, 0x000b1824, 0x000c1924, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000b1823, 0x000b1822, 0x000a1822, 0x000a1823, 0x00091722, 0x00091720, 0x00091720, 0x00091720, 0x00091720, 0x00091720, 0x00091821, 0x00091720, 0x00091720, 0x00091720, 0x000a1620, 0x000b1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x00091720, 0x000a1620, 0x000a1520, 0x000a1520, 0x000b1620, 0x000b1620, 0x000a1520, 0x000a1520, 0x000b1720, 0x000c1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00143036, 0x00153439, 0x00183a3e, 0x00183d41, 0x001a4347, 0x001b4649, 0x001d4b4e, 0x001e4f51, 0x001f5154, 0x00205457, 0x00225c61, 0x002a88a5, 0x002fa2c9, 0x002b8ba6, 0x00246167, 0x00245f61, 0x00246062, 0x00266163, 0x00256264, 0x00256364, 0x00276467, 0x00266568, 0x00276668, 0x00297684, 0x0033a4c8, 0x002b8194, 0x0028727c, 0x0028727c, 0x0028717b, 0x0028707a, 0x00287079, 0x00286d78, 0x00276c76, 0x00266b75, 0x00256873, 0x00246670, 0x0023646f, 0x00215e68, 0x001f5054, 0x001d4c50, 0x001c484c, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00143036, 0x00132c32, 0x0010282e, 0x0012242c, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a171f, 0x00091720, 0x00091720, 0x00081821, 0x00081821, 0x00081821, 0x00081821, 0x00091821, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1823, 0x000c1823, 0x000c1822, 0x000c1822, 0x000c1822, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1925, 0x000c1a25, 0x000c1a24, 0x000c1b24, 0x000c1c25, 0x000c1c26, 0x000e1c27, 0x000e1c27, 0x000d1c28, 0x000d1c28, 0x000e1c28, 0x000d1c28, 0x000c1c28, 0x000b1c28, 0x000c1d28, 0x000c1d26, 0x000c1d26, 0x000c1e27, 0x000c1e27, 0x000c1e28, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000d1d28, 0x000d1c28, 0x000d1c28, 0x000d1c29, 0x000d1c29, 0x000d1d29, 0x000c1d29, 0x000c1d2a, 0x000e1d2a, 0x000e1d2b, 0x00101f2c, 0x00122130, 0x00182836, 0x001f2e3d, 0x00243341, 0x00273544, 0x00293545, 0x002a3545, 0x002b3544, 0x002b3443, 0x002a3442, 0x0028323d, 0x00212c35, 0x001f2831, 0x001f2932, 0x001d2830, 0x001a2430, 0x001b242f, 0x00242e38, 0x002c3640, 0x002c3741, 0x002c3640, 0x002c3741, 0x002d3842, 0x002c3842, 0x002c3642, 0x002c3542, 0x002c3643, 0x002f3a46, 0x0034404c, 0x00374451, 0x003b4856, 0x003c4b5a, 0x003e4d5c, 0x00404e5d, 0x003c4b59, 0x00384754, 0x0033404e, 0x00303949, 0x002c3442, 0x002c333f, 0x002c323d, 0x002c333c, 0x00303842, 0x00303843, 0x00323944, 0x00303742, 0x00303640, 0x00303540, 0x00313541, 0x00343846, 0x00383c4b, 0x00363a49, 0x00313544, 0x00313444, 0x00303340, 0x002e313c, 0x002c2f39, 0x002c2e38, 0x002c2f39, 0x002a2d38, 0x002a2d39, 0x00282c38, 0x00242a35, 0x00232831, 0x0022262e, 0x0023242c, 0x0022222a, 0x00242129, 0x00242128, 0x00222128, 0x00202229, 0x0022242c, 0x0024272e, 0x00252831, 0x00262931, 0x00262932, 0x00242932, 0x00232932, 0x00232933, 0x00252b34, 0x00282c37, 0x00282d38, 0x00272d38, 0x002c343e, 0x00303842, 0x00313842, 0x00323843, 0x00333944, 0x00333845, 0x00333946, 0x00343c48, 0x00353d49, 0x0037404c, 0x0038404d, 0x00363e4c, 0x00343c4b, 0x00343b4b, 0x00333a48, 0x00323947, 0x00313946, 0x00313845, 0x00313946, 0x00323a47, 0x00323946, 0x00323845, 0x002d323f, 0x002b303c, 0x002b313c, 0x002a303b, 0x00282d38, 0x00262b34, 0x00242831, 0x00242830, 0x00262830, 0x0026282f, 0x0025262f, 0x0024242c, 0x00232129, 0x00232128, 0x00222028, 0x00212026, 0x00212028, 0x00222129, 0x0023232c, 0x0024252e, 0x00262730, 0x00272932, 0x00282c34, 0x00292d36, 0x002b3038, 0x002a303a, 0x00292e39, 0x00282d38, 0x00282d39, 0x00282d38, 0x00282e38, 0x00293038, 0x002c313b, 0x002e333d, 0x002c303c, 0x002c303b, 0x002c303b, 0x002c303a, 0x002c303b, 0x002d313c, 0x002c303c, 0x002c303b, 0x002c2f39, 0x002c2f39, 0x002c303b, 0x00272e39, 0x00272f3c, 0x00303c4b, 0x00354251, 0x00364454, 0x00384656, 0x00394859, 0x00394959, 0x00394858, 0x003c4c5c, 0x003d4d5d, 0x003c4a5a, 0x00384451, 0x00333f4a, 0x00303a45, 0x002d3841, 0x002c3640, 0x002b3640, 0x0029353f, 0x002b3540, 0x002c3640, 0x002c3540, 0x002c3540, 0x002c3540, 0x002a343f, 0x0029333d, 0x0029323d, 0x0029323d, 0x0029323d, 0x0029313c, 0x00262e39, 0x001f2530, 0x00161f29, 0x0018222a, 0x001c272f, 0x001e2831, 0x001f2b34, 0x00202d37, 0x001f2b34, 0x001d2832, 0x001f2833, 0x00222b36, 0x00242d37, 0x00252e37, 0x0029313a, 0x002b313b, 0x00282d38, 0x00252a34, 0x00232630, 0x00212530, 0x00232833, 0x00262b36, 0x00252d38, 0x00232d38, 0x001d2b37, 0x001b2b36, 0x00182a35, 0x00172936, 0x00152834, 0x00112430, 0x0010222e, 0x0010202d, 0x0010202b, 0x000f1f2a, 0x000e1d28, 0x000d1c28, 0x000c1c28, 0x000c1c27, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1a25, 0x000c1925, 0x000b1824, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1924, 0x000c1924, 0x000b1823, 0x000b1822, 0x000a1822, 0x000a1822, 0x000a1822, 0x00091720, 0x00091720, 0x00091720, 0x00091720, 0x000a1821, 0x000a1821, 0x000a1620, 0x000a1620, 0x000a1620, 0x000b1620, 0x000b1620, 0x000b1520, 0x000c1520, 0x000c1520, 0x000c1520, 0x00091620, 0x000a1620, 0x000a1520, 0x000a1520, 0x000b1620, 0x000b1620, 0x000a1520, 0x000b1620, 0x000c1821, 0x000c1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4245, 0x001c4649, 0x001d4b4e, 0x001e4f51, 0x00205254, 0x00205558, 0x00235f67, 0x002b8fae, 0x0030a2c8, 0x0029859d, 0x00246164, 0x00246062, 0x00256163, 0x00256163, 0x00256264, 0x00256364, 0x00266466, 0x00266467, 0x00266568, 0x00276668, 0x002a7784, 0x0033a4c9, 0x0033a4c8, 0x0032a4c7, 0x0032a4c7, 0x0032a4c7, 0x0032a4c7, 0x0032a4c7, 0x0031a3c7, 0x0031a3c6, 0x0030a3c6, 0x0030a2c6, 0x0030a0c6, 0x002fa0c6, 0x002d9ec3, 0x0025788e, 0x001f5054, 0x001d4c50, 0x001c474b, 0x00194245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0013282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0009171f, 0x00091720, 0x00091720, 0x00091820, 0x00091821, 0x00091821, 0x00091821, 0x00091821, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1821, 0x000c1822, 0x000c1822, 0x000c1823, 0x000c1923, 0x000c1823, 0x000b1824, 0x000c1824, 0x000c1923, 0x000c1923, 0x000c1924, 0x000c1a24, 0x000d1a25, 0x000c1a25, 0x000c1b25, 0x000c1b27, 0x000e1c27, 0x000c1c27, 0x000c1c28, 0x000b1c28, 0x000b1c28, 0x000c1d27, 0x000c1d27, 0x000c1e28, 0x000c1e28, 0x000c1d28, 0x000d1c28, 0x000d1c28, 0x000e1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000d1c29, 0x000d1c29, 0x000f1e2b, 0x00101f2c, 0x0010202c, 0x0010202d, 0x00142432, 0x001b2c3a, 0x00203140, 0x00243442, 0x00283544, 0x00283644, 0x002a3443, 0x002b3340, 0x002a323f, 0x0028303c, 0x00232c38, 0x00202a34, 0x001e2832, 0x001c2630, 0x001a242f, 0x001b242f, 0x00232d37, 0x002c3640, 0x002c3741, 0x002c3741, 0x002c3741, 0x002d3842, 0x002c3741, 0x002c3640, 0x002c3641, 0x002c3742, 0x002d3844, 0x00303c47, 0x0034414d, 0x00394654, 0x003c4854, 0x003c4855, 0x00394653, 0x0034414f, 0x0032404c, 0x00303d4a, 0x00303c49, 0x00303948, 0x00303844, 0x002e3641, 0x002e3640, 0x002f3843, 0x00303945, 0x00343c48, 0x00343c4a, 0x00323b49, 0x00313948, 0x00303845, 0x00313a48, 0x0038404f, 0x003b4454, 0x00394454, 0x00394453, 0x00394250, 0x0038414e, 0x0038404d, 0x0037404c, 0x00363d49, 0x00323844, 0x002d343f, 0x0029303c, 0x00262d38, 0x00242934, 0x00232831, 0x0024262f, 0x0024252f, 0x0024252f, 0x0023242e, 0x0021242c, 0x0021242d, 0x0023242d, 0x0024262e, 0x0024262f, 0x0023252e, 0x0023272f, 0x00232730, 0x0021262e, 0x0020262f, 0x00222730, 0x00242934, 0x00252a34, 0x00252c35, 0x002b313b, 0x00303740, 0x00303741, 0x00303841, 0x00303843, 0x00303742, 0x00303742, 0x00303843, 0x00303844, 0x00313946, 0x00303846, 0x00313848, 0x00303847, 0x00303847, 0x00303844, 0x002f3744, 0x002f3744, 0x00303744, 0x00313844, 0x00313844, 0x00323844, 0x00313743, 0x002c323c, 0x00282d37, 0x00252c36, 0x00252c36, 0x00242c34, 0x00242c34, 0x00242830, 0x00232830, 0x00242830, 0x00242730, 0x00252730, 0x0025262f, 0x0024242d, 0x0024242d, 0x0023232c, 0x0022222a, 0x0022232b, 0x0022242c, 0x0022242d, 0x0024272f, 0x00252830, 0x00282c35, 0x002c313b, 0x00333843, 0x003a3f4b, 0x003a404e, 0x00383e4c, 0x00343c49, 0x00333a48, 0x00303845, 0x002f3643, 0x002e3541, 0x00303641, 0x00313843, 0x00303641, 0x002f3540, 0x00303643, 0x00303743, 0x00303643, 0x00303541, 0x002c3340, 0x002c333e, 0x002d343f, 0x002d333e, 0x002e343f, 0x002c333f, 0x0028303c, 0x002b3542, 0x00313d4b, 0x00323f4c, 0x00303d4a, 0x00344250, 0x00384654, 0x00384755, 0x00394857, 0x003a4857, 0x00384554, 0x00374350, 0x0034404c, 0x00303b46, 0x002d3842, 0x002c3640, 0x002b343f, 0x0028323c, 0x0029333d, 0x002b343f, 0x002b343f, 0x002a343e, 0x002a343f, 0x002b343f, 0x002a343e, 0x0029333e, 0x0029333d, 0x0029333d, 0x0029313c, 0x00272f3a, 0x001e2631, 0x00161e27, 0x00182028, 0x001d282f, 0x00202b32, 0x001f2c34, 0x00202f38, 0x00212f38, 0x001f2c35, 0x001e2a34, 0x00222e38, 0x00232f39, 0x00242e38, 0x00272e38, 0x00252b34, 0x00222630, 0x0020232b, 0x001e2129, 0x0020232b, 0x00242731, 0x00272c37, 0x00262e3b, 0x00232e3c, 0x001d2c39, 0x001a2b38, 0x00182936, 0x00162834, 0x00142734, 0x00132430, 0x0011212e, 0x0010202c, 0x00101e2c, 0x000f1d2a, 0x000e1c28, 0x000d1b27, 0x000d1b26, 0x000d1a26, 0x000c1a25, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1925, 0x000d1925, 0x000d1a26, 0x000e1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1924, 0x000c1924, 0x000c1924, 0x000b1823, 0x000b1823, 0x000b1822, 0x000a1822, 0x000a1822, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1720, 0x000b1620, 0x000b1720, 0x000c1821, 0x000c1721, 0x000b151e, 0x000b151d, 0x000c151d, 0x000d161e, 0x000c161f, 0x000c1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000c1821, 0x000c1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0016363b, 0x00173a3e, 0x00194044, 0x001b4448, 0x001c4a4d, 0x001e4f51, 0x00205254, 0x00215659, 0x0024646e, 0x002c95b5, 0x0030a1c7, 0x00298095, 0x00256164, 0x00256264, 0x00256264, 0x00266364, 0x00266364, 0x00266466, 0x00276467, 0x00266568, 0x00276568, 0x00276668, 0x00286769, 0x0029717b, 0x002f90a9, 0x003091ab, 0x003091ab, 0x003091ab, 0x003091ab, 0x003091ab, 0x003091ab, 0x002f90ab, 0x002f90aa, 0x002e90aa, 0x002e90aa, 0x002d8ea9, 0x002c8da9, 0x002f9dc1, 0x002c9cc0, 0x00205559, 0x001f5053, 0x001d4a4d, 0x001b4448, 0x00194044, 0x00173a3e, 0x00153439, 0x00143036, 0x00122c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0009151e, 0x0009151f, 0x0009151f, 0x000a161f, 0x000a161f, 0x000a171f, 0x000a171f, 0x000a171f, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1720, 0x000c1620, 0x000c1720, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1721, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1821, 0x000b1921, 0x000b1923, 0x000b1a23, 0x00091a23, 0x000b1b24, 0x000c1a24, 0x000c1b25, 0x000b1b27, 0x000a1b28, 0x000a1c28, 0x000b1c27, 0x000c1d28, 0x000c1d28, 0x000c1e28, 0x000c1c28, 0x000c1c27, 0x000c1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000d1c28, 0x000d1c29, 0x000d1c29, 0x000f1e2c, 0x00101f2c, 0x00101f2c, 0x0010202c, 0x00142430, 0x00182a38, 0x001e313f, 0x00223442, 0x00273544, 0x00283544, 0x00283341, 0x0028303d, 0x0028303c, 0x0027303c, 0x00232c37, 0x00202b35, 0x001e2833, 0x001b2530, 0x0019232d, 0x001a242c, 0x00232c36, 0x002c3640, 0x002c3741, 0x002c3741, 0x002c3741, 0x002d3842, 0x002c3741, 0x002c3640, 0x002c3640, 0x002c3842, 0x002e3a44, 0x00303c46, 0x00303d48, 0x00323f49, 0x00343f4a, 0x00313c47, 0x002c3844, 0x002e3a44, 0x00303c48, 0x00303d49, 0x00303d4a, 0x00323e4b, 0x00323c49, 0x00313a45, 0x00303944, 0x00303a45, 0x00323c48, 0x0038414f, 0x00394252, 0x00384252, 0x00374050, 0x00354050, 0x00374050, 0x00374252, 0x00374453, 0x00364353, 0x00354151, 0x00374352, 0x00384350, 0x0035404d, 0x00323d4a, 0x00313a47, 0x002e3642, 0x002c343f, 0x002c343f, 0x002b333e, 0x002a2f3a, 0x00282c36, 0x00262934, 0x00242732, 0x00242630, 0x00242630, 0x00232530, 0x00232530, 0x00242530, 0x00242630, 0x0022252e, 0x0021242d, 0x0020252e, 0x0020262e, 0x0020252d, 0x0020242d, 0x0020252f, 0x0020252f, 0x00232731, 0x00252b34, 0x002b313b, 0x00303640, 0x00303740, 0x00303740, 0x002f3742, 0x002e3642, 0x002f3742, 0x002f3742, 0x002f3743, 0x002f3743, 0x002f3744, 0x002f3745, 0x002f3745, 0x002f3745, 0x002e3643, 0x002e3642, 0x002d3542, 0x00303643, 0x00303744, 0x00313843, 0x00323743, 0x00303440, 0x002c313b, 0x00262c35, 0x00222a34, 0x00212932, 0x00222a33, 0x00232a34, 0x00242832, 0x00232831, 0x00232830, 0x00242830, 0x00252830, 0x00272932, 0x00282a33, 0x00282a32, 0x00262831, 0x00242830, 0x00262831, 0x00282b34, 0x00282c36, 0x00292d37, 0x00292e38, 0x00292f39, 0x002b303d, 0x002c323f, 0x002e3544, 0x00323948, 0x00323b49, 0x00343d4b, 0x00333c4a, 0x00313a48, 0x002f3846, 0x002f3745, 0x00303844, 0x00313945, 0x00333b47, 0x00343d49, 0x0038404d, 0x00373f4c, 0x00363e4b, 0x00323a47, 0x002d3543, 0x002d3542, 0x002f3743, 0x002f3742, 0x00303743, 0x00313844, 0x00303944, 0x002c3642, 0x002a3642, 0x002c3944, 0x002b3844, 0x002c3945, 0x002f3c48, 0x0033404d, 0x00354350, 0x00364250, 0x0035414e, 0x0035414d, 0x0034404c, 0x00333d48, 0x00313c46, 0x002f3844, 0x002c3640, 0x0028333d, 0x0028333d, 0x002b3540, 0x002b3540, 0x0029343e, 0x0029333e, 0x002b3540, 0x002b3540, 0x002a343f, 0x002a343e, 0x002a343e, 0x002a333e, 0x0028303c, 0x001f2832, 0x00151e27, 0x00151e25, 0x001a242a, 0x001f2a30, 0x001f2c34, 0x00202f38, 0x00203038, 0x001e2c35, 0x001c2731, 0x001f2a34, 0x00212c36, 0x00212a34, 0x001f2730, 0x001c222b, 0x001c1f28, 0x001a1d24, 0x001c2026, 0x0020232a, 0x00242831, 0x00282c38, 0x00272f3c, 0x00242f3d, 0x001e2d3a, 0x00192b38, 0x00172935, 0x00152834, 0x00142733, 0x00122330, 0x0011202d, 0x00101f2c, 0x000f1c2a, 0x000e1c28, 0x000d1b27, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1925, 0x000d1925, 0x000e1a26, 0x000e1a26, 0x000e1a26, 0x000c1925, 0x000c1925, 0x000c1924, 0x000c1924, 0x000c1924, 0x000b1822, 0x000b1822, 0x000a1821, 0x000a1821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1720, 0x000b1620, 0x000b1720, 0x000c1821, 0x000c1721, 0x000b151e, 0x000b151c, 0x000c151c, 0x000d161d, 0x000d161e, 0x000c1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1720, 0x000c1821, 0x000c1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0013282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4347, 0x001c484c, 0x001d4d50, 0x00205254, 0x00215659, 0x00246976, 0x002e99bc, 0x0030a0c4, 0x00297b8d, 0x00266466, 0x00266466, 0x00276467, 0x00276568, 0x00276568, 0x00266568, 0x00276668, 0x00276668, 0x00286769, 0x00286769, 0x0028686a, 0x0028686b, 0x0028696c, 0x00286a6c, 0x00296b6d, 0x00296c6e, 0x00296c6e, 0x00296c6e, 0x00296c6e, 0x00296c6e, 0x00296b6d, 0x00286a6c, 0x0028696c, 0x00286769, 0x00276568, 0x00266467, 0x002e94b4, 0x002e9dc0, 0x0021585c, 0x001f5254, 0x001d4d50, 0x001c474b, 0x001a4245, 0x00183c40, 0x0016363b, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a161e, 0x000a161e, 0x0009151e, 0x0009151d, 0x0008141d, 0x000a161e, 0x000a161e, 0x000b171f, 0x000b171f, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c171f, 0x000c161f, 0x000c161f, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1820, 0x000b1920, 0x000a1920, 0x00091920, 0x000a1a21, 0x000b1b23, 0x000c1b24, 0x000c1b25, 0x000a1b26, 0x000a1b28, 0x000a1b27, 0x000a1c27, 0x000b1c27, 0x000b1c27, 0x000c1d28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000d1c27, 0x000d1c27, 0x000d1c27, 0x000d1c27, 0x000d1c27, 0x000d1c27, 0x000d1c27, 0x000d1c27, 0x000d1c28, 0x000d1c28, 0x000e1d2b, 0x000f1e2b, 0x000f1e2c, 0x00101f2c, 0x00132330, 0x00182937, 0x001d303e, 0x00213442, 0x00273444, 0x00283543, 0x00283240, 0x00262e3b, 0x00262e3b, 0x00262f3a, 0x00232c37, 0x00202b35, 0x001e2833, 0x001b2530, 0x0019232e, 0x001a242d, 0x00232d35, 0x002c3640, 0x002c3741, 0x002c3741, 0x002c3741, 0x002c3742, 0x002c3741, 0x002c3640, 0x002c3540, 0x002c3744, 0x002e3a45, 0x00303c47, 0x00303d47, 0x00313c48, 0x00303b47, 0x00303945, 0x002c3843, 0x002d3844, 0x00303b47, 0x00323e4a, 0x0034424d, 0x0035434e, 0x0037414d, 0x00353e4b, 0x00343d49, 0x00343e4a, 0x0036404d, 0x00394352, 0x00384353, 0x00384554, 0x003c4958, 0x003e4b5a, 0x003e4b5a, 0x003d4b5b, 0x003d4b5c, 0x003a4858, 0x00384655, 0x00364453, 0x0034414f, 0x00323f4b, 0x00313d49, 0x00303a47, 0x002e3744, 0x00303844, 0x00313844, 0x00303843, 0x002e3440, 0x002b303b, 0x00282d37, 0x00262a34, 0x00242832, 0x00242731, 0x00242831, 0x00252934, 0x00272a34, 0x00272a34, 0x00242832, 0x00242831, 0x00232832, 0x00212830, 0x0020262e, 0x001f242c, 0x001e232b, 0x001d212a, 0x0020232d, 0x00252a34, 0x002c313b, 0x00313540, 0x00313641, 0x00303640, 0x00303641, 0x002f3641, 0x00303741, 0x00303741, 0x002f3742, 0x002e3641, 0x002e3642, 0x002e3644, 0x002e3644, 0x002e3644, 0x002e3641, 0x002c3440, 0x002d3440, 0x002f3440, 0x00303641, 0x00313742, 0x00303541, 0x002e323e, 0x002c303a, 0x00262c35, 0x00212831, 0x00202730, 0x00222833, 0x00242b35, 0x00262c36, 0x00262b36, 0x00262b35, 0x00272c35, 0x00282c36, 0x002a2e37, 0x002c2f38, 0x002b2f38, 0x002b2e38, 0x00292d36, 0x00292d37, 0x002a2f38, 0x002c3139, 0x002e333c, 0x00303440, 0x00303643, 0x002f3644, 0x002e3644, 0x00303846, 0x00313a48, 0x00333d4c, 0x0035404e, 0x00343f4c, 0x00323c4b, 0x00323c4b, 0x00303b4a, 0x00313c4b, 0x00313c4b, 0x00323d4a, 0x00374350, 0x003c4854, 0x003e4856, 0x003d4754, 0x00394250, 0x00343d4c, 0x00313a47, 0x002f3845, 0x00303845, 0x00303946, 0x00323b48, 0x00323c48, 0x00303c46, 0x002a3843, 0x00283440, 0x0026333e, 0x0027313c, 0x0028333e, 0x00293440, 0x002d3843, 0x002f3844, 0x00303845, 0x00303844, 0x002f3844, 0x002e3843, 0x002e3843, 0x002c3640, 0x0029343e, 0x0028323c, 0x0029333d, 0x002a343f, 0x0029333d, 0x0028313c, 0x0028323c, 0x002b3540, 0x002c3741, 0x002c3741, 0x002c3641, 0x002c3641, 0x002c3540, 0x0028313c, 0x001f2832, 0x00161f27, 0x00141c24, 0x00151f25, 0x0019242b, 0x001d2a33, 0x00202e38, 0x00203038, 0x001e2c35, 0x001c2630, 0x00202934, 0x00202833, 0x001d242d, 0x00181d27, 0x00171b24, 0x00181a24, 0x00181c23, 0x001c1f25, 0x0020242b, 0x00262933, 0x002a2d39, 0x0028303c, 0x0024303d, 0x001f2e3b, 0x001b2c38, 0x00172936, 0x00152834, 0x00122531, 0x0011222f, 0x0010202c, 0x000e1c29, 0x000e1c28, 0x000d1a28, 0x000c1a27, 0x000c1926, 0x000c1926, 0x000c1926, 0x000c1926, 0x000c1926, 0x000c1926, 0x000c1926, 0x000d1925, 0x000d1925, 0x000e1a26, 0x000e1a26, 0x000e1a26, 0x000c1a26, 0x000b1926, 0x000c1925, 0x000c1924, 0x000c1924, 0x000c1923, 0x000c1923, 0x000b1822, 0x000b1822, 0x000b1822, 0x000c1822, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1822, 0x000c1722, 0x000c1722, 0x000c1722, 0x000c1722, 0x000c1722, 0x000b161f, 0x000b161e, 0x000c161e, 0x000c161e, 0x000c161f, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1720, 0x000c1721, 0x000c1721, 0x000c1721, 0x000c1821, 0x000c1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00132c32, 0x00143036, 0x0015363b, 0x00183c40, 0x001a4044, 0x001c4649, 0x001d4b4e, 0x001f5154, 0x00205558, 0x00256e7e, 0x002f9dc0, 0x00309fc2, 0x00287786, 0x00276568, 0x00276668, 0x00286769, 0x0028686a, 0x0028686a, 0x0028686a, 0x0028686a, 0x0028686a, 0x0028686a, 0x0028686b, 0x0028696c, 0x00286a6c, 0x00286a6c, 0x00296b6d, 0x00296c6f, 0x00296c6f, 0x002a6d6f, 0x002a6e70, 0x002a6e70, 0x002a6e70, 0x002a6e70, 0x002a6e70, 0x002a6d6f, 0x002a6c6e, 0x00286a6c, 0x0028686a, 0x00276669, 0x002f95b4, 0x002f9ec0, 0x00235c5f, 0x00205558, 0x001e5053, 0x001c4a4d, 0x001b4448, 0x00183f43, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0012242c, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a161e, 0x000a161e, 0x0009151e, 0x0008141d, 0x0008141c, 0x0008141d, 0x000a161e, 0x000b171f, 0x000b171f, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c171f, 0x000c161f, 0x000c161f, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1820, 0x000c1820, 0x000b1820, 0x000a1920, 0x000a1920, 0x000b1a22, 0x000c1a23, 0x000c1a24, 0x000c1b26, 0x000b1b27, 0x000b1b27, 0x000a1b26, 0x000b1c26, 0x000a1c26, 0x000b1c27, 0x000b1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000d1c28, 0x000d1c28, 0x000e1d29, 0x000e1d2a, 0x000e1d2b, 0x000f1e2c, 0x0012222f, 0x00152735, 0x001c2f3d, 0x00213341, 0x00263444, 0x00283443, 0x00283240, 0x00272e3c, 0x00272e3b, 0x00262f3b, 0x00232c37, 0x00202b35, 0x001d2731, 0x001a242f, 0x0019232d, 0x001b252e, 0x00232d35, 0x002c3640, 0x002c3741, 0x002c3741, 0x002c3741, 0x002c3741, 0x002c3741, 0x002c3640, 0x002c3641, 0x002d3844, 0x002f3b47, 0x002f3b44, 0x002f3b45, 0x00303c46, 0x00303b46, 0x00303944, 0x002c3540, 0x002c3540, 0x002e3945, 0x0034404c, 0x00384552, 0x00384552, 0x00394451, 0x0038404e, 0x0037404d, 0x00384250, 0x00394351, 0x00394454, 0x00384454, 0x00384856, 0x003d4c5b, 0x00404f5d, 0x00404f5d, 0x003f4d5d, 0x003e4c5c, 0x003e4c5c, 0x003f4c5c, 0x003d4a59, 0x003b4856, 0x00394754, 0x00374450, 0x0038424f, 0x0037404d, 0x00353f4a, 0x00343d48, 0x00323a44, 0x002e3540, 0x002c323c, 0x002a2f39, 0x00282d38, 0x00282c36, 0x00262b34, 0x00272b35, 0x00282d37, 0x002a2e38, 0x002b2f39, 0x00282d38, 0x00282c36, 0x00262b34, 0x00242932, 0x0020252d, 0x001e222a, 0x001c1f27, 0x001b1e26, 0x001e212b, 0x00242833, 0x002c313c, 0x00303541, 0x00303441, 0x00303440, 0x00303540, 0x00303640, 0x00303740, 0x00303740, 0x00303740, 0x002e3640, 0x002e3641, 0x002e3642, 0x002e3643, 0x002e3642, 0x002c3540, 0x002c343f, 0x002d3440, 0x00303440, 0x00303440, 0x00303440, 0x002e323e, 0x002c303c, 0x002c303b, 0x00282c36, 0x00232831, 0x0020252f, 0x00222631, 0x00262b36, 0x00282d39, 0x00282d38, 0x00282d38, 0x00282d38, 0x00293039, 0x002a303a, 0x002b303a, 0x002a2f39, 0x002a3039, 0x00292f38, 0x00292f38, 0x002b303a, 0x002d323c, 0x0030343f, 0x00323844, 0x00343c49, 0x00343e4c, 0x00353f4d, 0x00384150, 0x00394452, 0x00394553, 0x003b4754, 0x003b4754, 0x003a4654, 0x003c4756, 0x003c4958, 0x003d4b5a, 0x003c4b5a, 0x003a4858, 0x003c4a58, 0x003b4957, 0x00394855, 0x003c4855, 0x003a4654, 0x00384453, 0x0034404f, 0x00313c4b, 0x002f3b48, 0x00303c49, 0x00323d4c, 0x00303d4b, 0x002e3d48, 0x002c3943, 0x0029353f, 0x0026313c, 0x00253039, 0x00262f38, 0x00272f39, 0x00282f3a, 0x0028303c, 0x0028303d, 0x0028313c, 0x0028313c, 0x0028323c, 0x0028323c, 0x0028323c, 0x0027313c, 0x0028323c, 0x0029333d, 0x002a343e, 0x0028323c, 0x0026303c, 0x0028323c, 0x002c3640, 0x002d3842, 0x002d3842, 0x002d3842, 0x002d3742, 0x002b3540, 0x0026303a, 0x001d2730, 0x00182028, 0x00141d24, 0x00141d24, 0x00162028, 0x001b2830, 0x001f2c36, 0x00202f38, 0x00202c37, 0x00202934, 0x00202832, 0x001e242d, 0x00181c26, 0x00141720, 0x00151822, 0x00191c24, 0x001c1e26, 0x001f2229, 0x0023252e, 0x00272a35, 0x002a2e3c, 0x0028303d, 0x0025303e, 0x001f2e3b, 0x001a2b38, 0x00172835, 0x00142632, 0x00112330, 0x0010212d, 0x000d1e2b, 0x000c1c29, 0x000c1b28, 0x000c1a28, 0x000b1927, 0x000b1826, 0x000b1826, 0x000c1927, 0x000c1927, 0x000c1927, 0x000c1927, 0x000c1926, 0x000d1925, 0x000d1925, 0x000e1a26, 0x000e1a26, 0x000e1a26, 0x000c1a27, 0x000b1a27, 0x000b1926, 0x000c1925, 0x000c1925, 0x000c1924, 0x000c1924, 0x000b1823, 0x000b1822, 0x000b1822, 0x000c1824, 0x000c1824, 0x000c1824, 0x000c1824, 0x000c1824, 0x000c1723, 0x000c1723, 0x000c1723, 0x000c1723, 0x000c1723, 0x000b1620, 0x000b171f, 0x000b161f, 0x000c161f, 0x000c161f, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1721, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00153338, 0x0016383c, 0x00183d41, 0x001a4347, 0x001c484c, 0x001e4f51, 0x00205457, 0x00236068, 0x00309ec2, 0x002f9cbe, 0x0028737e, 0x00276668, 0x0028686a, 0x0028696c, 0x00286a6c, 0x00296b6d, 0x00286b6d, 0x00296b6d, 0x00296b6d, 0x00296b6d, 0x00296b6d, 0x00296b6d, 0x002a6c6e, 0x00296c6e, 0x00296c6f, 0x002a6d6f, 0x002a6e70, 0x002b6f70, 0x002b7071, 0x002b7072, 0x002b7072, 0x002b7072, 0x002b7072, 0x002b7072, 0x002c7071, 0x002a6e70, 0x00296c6f, 0x00286a6c, 0x0028686c, 0x003096b4, 0x00309ec0, 0x00245d60, 0x0021585a, 0x00205254, 0x001d4b4e, 0x001c4649, 0x00194044, 0x00183a3e, 0x00153439, 0x00142e34, 0x00112a30, 0x0011242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a1620, 0x000a1620, 0x000a1620, 0x0009151e, 0x0008141d, 0x0009151e, 0x000a161e, 0x000a171f, 0x000b1720, 0x000c1820, 0x000c1820, 0x000c1821, 0x000c1821, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c171f, 0x000c161f, 0x000c161f, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1720, 0x000c1820, 0x000c1820, 0x000b1820, 0x000b1920, 0x000b1920, 0x000c1a21, 0x000c1a23, 0x000c1a24, 0x000c1b26, 0x000b1a25, 0x000b1a25, 0x000b1a25, 0x000b1b26, 0x000c1c26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000d1c27, 0x000d1c27, 0x000d1c28, 0x000d1c29, 0x000d1c29, 0x000f1e2b, 0x0010202d, 0x00142433, 0x001c2c3a, 0x00223140, 0x00263443, 0x00283543, 0x00293442, 0x0028303e, 0x0028303c, 0x0027303c, 0x00232d38, 0x00202934, 0x001c2530, 0x0019232d, 0x0019232d, 0x001b252e, 0x00232d35, 0x002c3640, 0x002e3843, 0x002e3843, 0x002d3842, 0x002c3741, 0x002c3641, 0x002c3741, 0x002d3843, 0x002e3a45, 0x002f3a46, 0x002e3a44, 0x002f3944, 0x00303b45, 0x00313a44, 0x002e3641, 0x002c343e, 0x002c343e, 0x002e3844, 0x0034404c, 0x00384553, 0x00384654, 0x003b4654, 0x003c4454, 0x00394451, 0x00394452, 0x003a4754, 0x003b4857, 0x003b4958, 0x003c4b59, 0x003e4c5a, 0x00404e5c, 0x00404e5c, 0x003e4c5b, 0x003e4c5b, 0x00404d5c, 0x00404d5c, 0x003e4b5a, 0x003c4958, 0x003c4855, 0x00394652, 0x00394450, 0x0038424e, 0x00363e4a, 0x00353c48, 0x00313843, 0x002c323e, 0x002c303c, 0x002c303b, 0x002c303a, 0x002a2f39, 0x00292e38, 0x00292e38, 0x002a2f39, 0x002b303a, 0x002c303b, 0x002b303a, 0x00282e37, 0x00272b34, 0x00242830, 0x0020232b, 0x001c1f26, 0x00191c24, 0x001b1f27, 0x0020242d, 0x00282c36, 0x002c323c, 0x002f343f, 0x002f343f, 0x002f343f, 0x0030343f, 0x00303540, 0x00303740, 0x00303740, 0x00303740, 0x002f3740, 0x002f3741, 0x002e3642, 0x002e3643, 0x002e3441, 0x002d343f, 0x002c333d, 0x002c313c, 0x002c303c, 0x002b303c, 0x002c303c, 0x002c303c, 0x002d303c, 0x002c303c, 0x00292d38, 0x00242832, 0x0020242e, 0x00222530, 0x00252934, 0x00282c38, 0x00282e39, 0x00282e3a, 0x0029303c, 0x002c323c, 0x002c323c, 0x002c323c, 0x002b313b, 0x002b313b, 0x002a303b, 0x002b303b, 0x002c313c, 0x002e343f, 0x00303641, 0x00333a47, 0x00363f4d, 0x00384350, 0x003b4553, 0x003c4854, 0x003c4856, 0x003c4958, 0x003c4a58, 0x00404c5a, 0x00404c5a, 0x003f4b5b, 0x00404d5c, 0x0041505f, 0x00445362, 0x00445260, 0x0041505e, 0x003b4a58, 0x00374654, 0x00374454, 0x00364453, 0x00374454, 0x00354452, 0x0031404f, 0x00303f4e, 0x0031404f, 0x00334150, 0x00303f4c, 0x002e3c47, 0x002c3842, 0x0029343e, 0x0026303b, 0x00262e38, 0x00262e37, 0x00282f38, 0x00282f38, 0x0028303b, 0x0028303c, 0x0028303c, 0x0029313c, 0x0029323d, 0x0029323d, 0x0028323c, 0x0028323c, 0x0028323c, 0x0028323d, 0x0029333d, 0x0028323d, 0x0027313c, 0x0029343e, 0x002c3741, 0x002f3843, 0x002f3843, 0x002f3843, 0x002f3843, 0x002c3640, 0x0027303a, 0x001e2630, 0x00182028, 0x00151d24, 0x00141d24, 0x00172128, 0x001c2730, 0x001f2c35, 0x001e2a34, 0x001e2833, 0x001f2630, 0x001c212c, 0x00181d25, 0x00141820, 0x0013151e, 0x00171a22, 0x001c1e27, 0x0020232b, 0x00242830, 0x00282c35, 0x002b2f3b, 0x002c313f, 0x002b3340, 0x00263140, 0x001f2e3c, 0x00192a38, 0x00172834, 0x00142532, 0x0011232f, 0x0010202d, 0x000e1e2b, 0x000c1c28, 0x000d1b28, 0x000c1a27, 0x000c1927, 0x000c1926, 0x000c1926, 0x000c1927, 0x000c1927, 0x000c1927, 0x000c1927, 0x000c1926, 0x000d1925, 0x000d1925, 0x000d1925, 0x000d1925, 0x000d1a26, 0x000c1a27, 0x000c1a27, 0x000c1926, 0x000c1925, 0x000c1925, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1923, 0x000c1923, 0x000c1824, 0x000c1824, 0x000c1824, 0x000c1824, 0x000c1824, 0x000c1823, 0x000c1823, 0x000c1723, 0x000c1723, 0x000c1723, 0x000b1720, 0x000b1720, 0x000b171f, 0x000c161f, 0x000c161f, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000c1721, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012242c, 0x00112a30, 0x00142e34, 0x00153439, 0x00173a3e, 0x00193f43, 0x001b4448, 0x001d4b4e, 0x001f5154, 0x00215659, 0x0024646d, 0x0031a3c8, 0x002c879e, 0x00286769, 0x0028696c, 0x00296b6d, 0x00296c6f, 0x00296d6f, 0x002a6d6f, 0x002a6e70, 0x002a6d6f, 0x002a6d6f, 0x002a6d6f, 0x002a6d6f, 0x002a6e70, 0x002a6e70, 0x002b6e70, 0x002b6f70, 0x002b7071, 0x002b7072, 0x002c7173, 0x002b7173, 0x002c7274, 0x002c7374, 0x002c7374, 0x002c7374, 0x002c7374, 0x002c7274, 0x002b7072, 0x002b6f70, 0x00296c6f, 0x00296b6e, 0x003097b4, 0x00309fc1, 0x00246062, 0x0022595c, 0x00205356, 0x001d4d50, 0x001c474b, 0x00194044, 0x00173a3e, 0x00153439, 0x00143036, 0x00112a30, 0x0012282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091722, 0x00081721, 0x00081721, 0x000a1520, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a151f, 0x00091620, 0x00081722, 0x00081722, 0x00091823, 0x00091823, 0x00091821, 0x00091820, 0x00091820, 0x00091820, 0x00091820, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000b1720, 0x000b1720, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b171f, 0x000b171f, 0x000a1820, 0x000a1820, 0x000b1920, 0x000c1a21, 0x000c1a23, 0x000c1a24, 0x000c1a25, 0x000b1924, 0x000b1923, 0x000b1924, 0x000b1a24, 0x000b1a25, 0x000b1a25, 0x000b1a25, 0x000b1a25, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1c26, 0x000c1c25, 0x000c1c25, 0x000c1c27, 0x000c1c27, 0x000d1c28, 0x000e1d28, 0x000f1f2a, 0x00122330, 0x00172836, 0x001e2f3d, 0x00243442, 0x00283644, 0x002b3644, 0x002a3240, 0x0028303e, 0x0028303c, 0x00242d38, 0x001e2832, 0x001a242e, 0x0018222b, 0x0019232c, 0x001c252e, 0x00242d37, 0x002d3741, 0x00303944, 0x00303a44, 0x002d3843, 0x002b3741, 0x002b3541, 0x002c3642, 0x002e3844, 0x002f3a46, 0x002f3b45, 0x00303a44, 0x00303843, 0x00303843, 0x00303843, 0x002e3641, 0x002b333e, 0x002c343e, 0x002d3742, 0x00323d49, 0x00364350, 0x00384754, 0x003b4858, 0x003c4958, 0x003b4858, 0x00394858, 0x003b4958, 0x003c4a5a, 0x003c4a59, 0x003d4a58, 0x003d4a57, 0x003d4957, 0x00404c59, 0x00414d5b, 0x00424e5c, 0x00414d5b, 0x00404c59, 0x003d4857, 0x003c4856, 0x003c4755, 0x003a4451, 0x0038414e, 0x00363d4b, 0x00343a47, 0x00333843, 0x002f333e, 0x002a2e3a, 0x002b2f3b, 0x002c303c, 0x002c303c, 0x002c303c, 0x002c303c, 0x002c303c, 0x002b2f3b, 0x002a2f3b, 0x002b303a, 0x002b303a, 0x00292e38, 0x00272b34, 0x0022252d, 0x001d2027, 0x001a1d23, 0x001a1d24, 0x001e2129, 0x00242a32, 0x00283038, 0x002a323a, 0x002c323b, 0x002c323b, 0x002e333c, 0x002f343e, 0x0030343f, 0x00303540, 0x00303640, 0x00303741, 0x002e3842, 0x002e3843, 0x002e3842, 0x002d3641, 0x002c333e, 0x002b313b, 0x002a303a, 0x00292e38, 0x00292e38, 0x00282e39, 0x002a303b, 0x002c303c, 0x002c313d, 0x002c303c, 0x00292e39, 0x00242832, 0x0020242c, 0x0020242c, 0x00232831, 0x00282c37, 0x002a2f3b, 0x002b303c, 0x002c323f, 0x002f3441, 0x00303540, 0x002f3540, 0x002e3440, 0x002d343f, 0x002c333e, 0x002c323d, 0x002e3440, 0x00303541, 0x00303643, 0x00333846, 0x00343d4c, 0x00384250, 0x003c4754, 0x003e4a56, 0x003d4b57, 0x003e4c5a, 0x003f4c5c, 0x00414f5e, 0x00445260, 0x00435160, 0x00445060, 0x00445160, 0x00435060, 0x00404d5c, 0x003f4c5a, 0x003b4b58, 0x00384855, 0x00384755, 0x00374453, 0x00374453, 0x00344452, 0x00344351, 0x00344553, 0x00344552, 0x00354350, 0x00333e4b, 0x002f3944, 0x002b343f, 0x0028313b, 0x00252d37, 0x00252d36, 0x00252d36, 0x00272e37, 0x00272f38, 0x00273039, 0x0028303b, 0x0028303d, 0x002a323e, 0x002c333f, 0x002b333f, 0x002a333e, 0x0029333e, 0x0029333d, 0x0028323c, 0x0028323c, 0x0028323c, 0x0028333d, 0x00293540, 0x002c3843, 0x00303945, 0x00303944, 0x002f3944, 0x002f3844, 0x002c3440, 0x00272e38, 0x001e242e, 0x00192027, 0x00151e24, 0x00141c24, 0x00162029, 0x001c2731, 0x00222c36, 0x00202832, 0x001c242c, 0x001b2029, 0x00141921, 0x0013171f, 0x0012141c, 0x0014161f, 0x001a1c24, 0x001d202a, 0x0020242e, 0x00262a35, 0x002b303c, 0x002c3340, 0x002c3442, 0x002b3444, 0x00273341, 0x001e2d3c, 0x00182937, 0x00152634, 0x00142431, 0x0011232f, 0x0010202d, 0x000e1d2a, 0x000c1b28, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1925, 0x000d1925, 0x000c1924, 0x000b1824, 0x000b1824, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000c1a24, 0x000c1924, 0x000b1823, 0x000b1824, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1a25, 0x000d1a25, 0x000c1924, 0x000c1924, 0x000b1823, 0x000b1822, 0x000b1821, 0x000b1821, 0x000a1821, 0x000b1821, 0x000c1822, 0x000c1822, 0x000c1721, 0x000b1622, 0x000c1723, 0x000b1821, 0x000b1821, 0x000b1820, 0x000b1820, 0x000b1820, 0x000b1821, 0x000b1820, 0x000c1820, 0x000c1720, 0x000a1720, 0x00091720, 0x00091720, 0x00091720, 0x000a1821, 0x000a1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012282e, 0x00112a30, 0x00142e34, 0x00143439, 0x00183c40, 0x00194044, 0x001c474b, 0x001e4d50, 0x00205356, 0x0022585b, 0x0025666f, 0x0031a4c8, 0x002c889e, 0x0028696c, 0x00296c6f, 0x002a6e70, 0x002b7071, 0x002b7072, 0x002b7072, 0x002b7072, 0x002b7072, 0x002b7072, 0x002c7072, 0x002b7072, 0x002b7072, 0x002b7072, 0x002b7173, 0x002b7173, 0x002c7274, 0x002c7274, 0x002c7374, 0x002c7475, 0x002c7476, 0x002c7476, 0x002c7476, 0x002c7476, 0x002c7476, 0x002c7475, 0x002c7374, 0x002c7173, 0x002b6f70, 0x00296c6f, 0x003098b4, 0x00309fc1, 0x00256164, 0x00235a5c, 0x00205457, 0x001e4f51, 0x001c484c, 0x00194245, 0x00183c40, 0x00153439, 0x00143036, 0x00132c32, 0x0012282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081722, 0x00081722, 0x00081722, 0x000a1620, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a151f, 0x00091621, 0x00081722, 0x00081722, 0x00081823, 0x00081823, 0x00081821, 0x00081820, 0x00081820, 0x00081820, 0x00081820, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1821, 0x000c1821, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b171f, 0x000b171f, 0x000b171f, 0x0009171f, 0x000a1820, 0x000a1820, 0x000c1a21, 0x000c1a21, 0x000b1922, 0x000b1823, 0x000b1822, 0x000b1822, 0x000b1822, 0x00091924, 0x000a1924, 0x000a1a24, 0x000b1a25, 0x000b1a25, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1b26, 0x000c1c25, 0x000c1c25, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000d1d27, 0x000e1f28, 0x0011222f, 0x00152634, 0x001c2d3c, 0x00233442, 0x00283745, 0x002c3847, 0x002c3444, 0x0029313f, 0x0028303c, 0x00242c38, 0x001c2530, 0x0018222c, 0x0017212a, 0x0019232c, 0x001c252e, 0x00232d36, 0x002e3843, 0x00323c48, 0x00333d48, 0x00303c45, 0x002d3943, 0x002c3643, 0x002c3542, 0x002c3844, 0x002e3a44, 0x002e3a44, 0x002e3843, 0x002c3540, 0x002d3540, 0x002d3540, 0x002c3440, 0x002b333d, 0x002b333e, 0x002b343f, 0x002d3843, 0x00323e4a, 0x00364551, 0x003a4957, 0x003c4c5b, 0x003c4c5a, 0x003c4b5b, 0x003c4a5b, 0x003c4959, 0x003a4856, 0x003c4755, 0x003b4654, 0x00394453, 0x003d4856, 0x003d4857, 0x003d4857, 0x003e4a58, 0x003d4957, 0x003c4855, 0x003c4755, 0x003c4554, 0x003b4350, 0x00383f4c, 0x00353a48, 0x00323642, 0x0030343e, 0x002e313c, 0x002c2f3b, 0x002c313d, 0x002e343f, 0x002f3440, 0x002f3440, 0x00303541, 0x00303641, 0x002e343f, 0x002c323e, 0x002b313c, 0x002a303a, 0x00282d37, 0x00252832, 0x0020242c, 0x001c1f25, 0x001c1f25, 0x001c2027, 0x0021252d, 0x00282d35, 0x00293139, 0x00293239, 0x00293038, 0x002b3039, 0x002c313b, 0x002e333c, 0x002f343d, 0x0030353f, 0x00303640, 0x00303641, 0x002f3843, 0x002f3843, 0x002e3842, 0x002c3540, 0x002c333d, 0x002a303a, 0x00292f38, 0x00282e38, 0x00282d38, 0x00282d38, 0x00292f39, 0x002a303b, 0x002a303c, 0x002b313c, 0x002a303b, 0x00262b34, 0x0021262f, 0x001d222a, 0x0020242c, 0x00252a34, 0x002a2f3a, 0x002c303c, 0x002d3340, 0x002f3542, 0x00303742, 0x00303843, 0x00303843, 0x00303843, 0x00303742, 0x00303642, 0x00303744, 0x00313845, 0x00333947, 0x00343b49, 0x00353d4d, 0x00374250, 0x003a4553, 0x003b4854, 0x003b4857, 0x003b4a59, 0x003d4c5c, 0x00404f5e, 0x0041505f, 0x00425060, 0x00435060, 0x00404e5d, 0x003c4958, 0x003b4857, 0x00394756, 0x00384755, 0x00364854, 0x00374854, 0x00384854, 0x00384655, 0x00354453, 0x00364454, 0x00384857, 0x00384856, 0x00364451, 0x00333e4c, 0x002d3844, 0x0029313c, 0x00262e38, 0x00242d36, 0x00262e37, 0x00262e37, 0x00262e37, 0x00262e37, 0x00272f38, 0x00272f39, 0x0028303c, 0x002b3240, 0x002c3340, 0x002c3340, 0x002c3340, 0x002b3440, 0x002b343f, 0x002a343e, 0x0028323c, 0x0028323c, 0x0029343e, 0x002a3641, 0x002d3844, 0x00303a46, 0x00303a46, 0x00303945, 0x002f3844, 0x002c3440, 0x00262c38, 0x001d242c, 0x00192026, 0x00161e24, 0x00141c24, 0x0017202a, 0x001c2730, 0x00232c37, 0x00222a34, 0x001c232b, 0x00171c24, 0x0010151c, 0x000f141a, 0x0011151c, 0x00171a22, 0x001d1f28, 0x001f222c, 0x00212530, 0x00262c36, 0x002b313d, 0x002c3441, 0x002c3443, 0x002c3544, 0x00273341, 0x001e2d3c, 0x00172836, 0x00152534, 0x00132430, 0x0010212e, 0x000f1f2c, 0x000d1c29, 0x000c1a27, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1925, 0x000d1925, 0x000c1923, 0x000b1822, 0x000b1823, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000c1a24, 0x000b1923, 0x000b1822, 0x000b1823, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000d1a26, 0x000c1924, 0x000c1924, 0x000b1823, 0x000b1920, 0x000b1920, 0x000a1820, 0x000a1820, 0x000b1820, 0x000c1821, 0x000c1822, 0x000c1721, 0x000b1622, 0x000b1622, 0x000b1822, 0x000b1822, 0x000a1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000b1820, 0x000c1820, 0x000c1820, 0x000a1720, 0x00091720, 0x00091720, 0x00091720, 0x000a1821, 0x000a1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00122c32, 0x00143036, 0x0016363b, 0x00183c40, 0x001a4245, 0x001c484c, 0x001e4f51, 0x00205558, 0x00235a5c, 0x00266870, 0x0032a4c8, 0x003096b4, 0x002f899e, 0x002f8b9f, 0x00308ca0, 0x00308da0, 0x00308da0, 0x00318da0, 0x00318da0, 0x00318da0, 0x00318da0, 0x00308da0, 0x00308da0, 0x00308da0, 0x00308da0, 0x00308da0, 0x00318da0, 0x00318ea1, 0x00318ea1, 0x00318fa1, 0x00318fa1, 0x00318fa1, 0x003190a2, 0x003190a2, 0x003190a2, 0x003190a2, 0x00318fa1, 0x00318ea1, 0x00308da0, 0x00308ca0, 0x002f8b9f, 0x00329ebf, 0x0031a0c1, 0x00256264, 0x00235c5e, 0x00205558, 0x001f5053, 0x001c484c, 0x001a4245, 0x00183c40, 0x0015363b, 0x00143036, 0x00132c32, 0x0012282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081722, 0x00081722, 0x00081722, 0x000a1620, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a151f, 0x00091621, 0x00081722, 0x00081722, 0x00081823, 0x00081823, 0x00081821, 0x00081820, 0x00081820, 0x00081820, 0x00081820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000b1821, 0x000b1821, 0x000b1720, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x0009171f, 0x0009171f, 0x000a1820, 0x000b1920, 0x000c1a21, 0x000b1920, 0x000b1920, 0x000b1821, 0x000b1822, 0x000b1822, 0x00091924, 0x00091924, 0x000a1924, 0x000b1924, 0x000b1924, 0x000c1a25, 0x000c1a26, 0x000c1a26, 0x000c1a26, 0x000c1a26, 0x000c1a26, 0x000c1a26, 0x000c1b26, 0x000c1c25, 0x000c1c25, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000d1c26, 0x000e1d27, 0x0010202d, 0x00142433, 0x001a2b39, 0x00203140, 0x00263644, 0x002c3a49, 0x002f3847, 0x002b3340, 0x0028303c, 0x00202a35, 0x0019242e, 0x0017212b, 0x0018212a, 0x001a242c, 0x001c262f, 0x00232d37, 0x002f3844, 0x00343e4a, 0x00353f49, 0x00333e48, 0x00303b45, 0x002d3844, 0x002c3542, 0x002c3643, 0x002a3641, 0x002a3640, 0x002b3540, 0x002b343f, 0x002c333e, 0x002c343f, 0x002c343f, 0x002b333e, 0x002c343e, 0x002b343f, 0x002b3640, 0x002e3b46, 0x0034424e, 0x003a4855, 0x003c4b58, 0x003c4a58, 0x003b4958, 0x003d4c5b, 0x003e4c5b, 0x003d4a58, 0x003c4856, 0x003b4754, 0x00394452, 0x00394453, 0x00394452, 0x00384451, 0x00394452, 0x003a4654, 0x003a4654, 0x003a4554, 0x003b4453, 0x0039404f, 0x00363d4a, 0x00333946, 0x00313542, 0x0030353f, 0x00323640, 0x00323642, 0x00333844, 0x00323844, 0x00323844, 0x00313843, 0x00323844, 0x00313844, 0x00303742, 0x002f3440, 0x002c323c, 0x00282f38, 0x00252934, 0x0022242f, 0x001f222a, 0x001e2128, 0x00202328, 0x0020242a, 0x00242830, 0x002a2f37, 0x002a3139, 0x00293139, 0x00293038, 0x00292f38, 0x002c303a, 0x002c313c, 0x002e333c, 0x002f343d, 0x002f353e, 0x00303640, 0x002f3843, 0x00303a44, 0x00303944, 0x002f3742, 0x002e3440, 0x002a303b, 0x002b303a, 0x002a2f39, 0x00292e39, 0x00282d38, 0x00272c37, 0x00282d38, 0x00282e3a, 0x002a303c, 0x002b303c, 0x00282d37, 0x00232830, 0x001f232b, 0x001d212a, 0x00202530, 0x00282c38, 0x002c303d, 0x002c323f, 0x002d3440, 0x00303642, 0x00303843, 0x00303843, 0x00323a45, 0x00343c48, 0x00343c48, 0x00363c4a, 0x00373c4b, 0x00383e4c, 0x00383f4e, 0x00384051, 0x00384352, 0x003a4554, 0x003b4755, 0x003a4858, 0x003c4b5c, 0x003c4c5d, 0x003e4f5e, 0x003f4e5e, 0x003d4c5c, 0x003d4a5b, 0x003c4959, 0x003c4858, 0x003c4858, 0x00394757, 0x00394756, 0x00374755, 0x00384855, 0x00394857, 0x00394858, 0x00394857, 0x00394857, 0x00394958, 0x00374856, 0x0034424f, 0x00303b48, 0x002b3441, 0x0028313c, 0x00262e38, 0x00252d38, 0x00262f38, 0x00272f38, 0x00273038, 0x00283038, 0x00272f38, 0x0028303a, 0x0029313d, 0x002b333f, 0x002c333f, 0x002c333f, 0x002c333f, 0x002c3540, 0x002c3641, 0x002b3540, 0x002a343e, 0x0029333d, 0x002a343f, 0x002c3843, 0x002e3a45, 0x002f3b47, 0x002f3946, 0x002f3945, 0x002f3844, 0x002c3440, 0x00262c38, 0x001c222c, 0x00181f25, 0x00151d23, 0x00131c24, 0x0017202a, 0x001c2630, 0x00212b35, 0x00202832, 0x001c222a, 0x00161c23, 0x0013181e, 0x0012171d, 0x00151a20, 0x00181c24, 0x001c1f28, 0x001e202c, 0x0020252f, 0x00252b35, 0x0029303c, 0x002c3440, 0x002c3443, 0x002c3544, 0x00263241, 0x001c2c3a, 0x00162635, 0x00142433, 0x0011232f, 0x0010202d, 0x000e1e2b, 0x000c1c28, 0x000b1a27, 0x000b1925, 0x000b1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1924, 0x000b1823, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1b24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1925, 0x000c1925, 0x000d1a26, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1923, 0x000b1920, 0x000b1920, 0x000b1820, 0x000a1820, 0x000b1820, 0x000c1821, 0x000c1821, 0x000b1821, 0x000b1721, 0x000c1722, 0x000b1822, 0x000b1822, 0x000a1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000b1821, 0x000c1820, 0x000c1820, 0x000b1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0016363b, 0x00183d41, 0x001a4347, 0x001c4a4d, 0x001e5053, 0x00215659, 0x00245c5f, 0x0026676d, 0x00319ebf, 0x0034a8cc, 0x0035a8cc, 0x0036a9cc, 0x0037aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038aacc, 0x0038abcc, 0x0038abcc, 0x0038abcc, 0x0038abcc, 0x0038abcc, 0x0038abcc, 0x0038aacc, 0x0037aacc, 0x0037a9cc, 0x0036a8cc, 0x0034a8cc, 0x003096b3, 0x00256264, 0x00235c5e, 0x00215659, 0x001f5053, 0x001c484c, 0x001b4347, 0x00183c40, 0x0015363b, 0x00143036, 0x00132c32, 0x0012282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081722, 0x00081722, 0x00081722, 0x000a1620, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a151f, 0x00091621, 0x00081722, 0x00081722, 0x00081823, 0x00081823, 0x00081821, 0x00081820, 0x00081820, 0x00081820, 0x00081820, 0x00081820, 0x00081820, 0x00091820, 0x000a1821, 0x000a1821, 0x000a1720, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b1820, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1820, 0x000b1821, 0x000b1821, 0x000b1823, 0x000b1823, 0x000b1824, 0x000c1924, 0x000c1924, 0x000c1a25, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000c1a25, 0x000c1c25, 0x000c1c25, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000d1b25, 0x000e1c26, 0x000f1e2a, 0x00102030, 0x00172836, 0x001d2e3c, 0x00253544, 0x002e3b4a, 0x00303a49, 0x002c3340, 0x00262e3b, 0x001e2832, 0x0019232d, 0x0018222c, 0x0018222b, 0x001b252d, 0x001e2830, 0x00232d37, 0x002f3845, 0x00343e4b, 0x00353f4b, 0x00343f4a, 0x00313c48, 0x002f3945, 0x002c3643, 0x002c3744, 0x002c3844, 0x002c3844, 0x002c3542, 0x002b3440, 0x002c3340, 0x002c343f, 0x002c343f, 0x002b333e, 0x002c343e, 0x002c343f, 0x002b3540, 0x002c3842, 0x00313d48, 0x00384450, 0x003c4753, 0x003b4754, 0x003d4857, 0x003f4c59, 0x00404c5a, 0x003f4c5a, 0x00404c59, 0x00404b59, 0x003d4957, 0x003c4755, 0x00394554, 0x00384452, 0x00384452, 0x00384352, 0x00384352, 0x00374252, 0x00384150, 0x00373e4e, 0x00363c4b, 0x00343a48, 0x00343a46, 0x00363c48, 0x00383d48, 0x00373d48, 0x00373d48, 0x00363e48, 0x00363d48, 0x00353d48, 0x00353d48, 0x00343c47, 0x00313944, 0x00303641, 0x002c323c, 0x00272d36, 0x00222731, 0x0020242e, 0x0020222b, 0x0020232a, 0x0021242b, 0x0024272d, 0x00272b33, 0x00292f37, 0x00293037, 0x00293038, 0x00293037, 0x002a3038, 0x002c303b, 0x002d323c, 0x002e333c, 0x002e343c, 0x002e343d, 0x002e3440, 0x002f3842, 0x002f3944, 0x002f3843, 0x002f3742, 0x002d3440, 0x002a303a, 0x002a303a, 0x002c303a, 0x002a2f39, 0x00282d38, 0x00272b35, 0x00272b35, 0x00282c36, 0x002a2f39, 0x00293039, 0x00282d35, 0x00242831, 0x0021242d, 0x001f222b, 0x0020232e, 0x00272936, 0x002c303d, 0x002e3440, 0x00303643, 0x00313844, 0x00323a45, 0x00323a46, 0x00333b48, 0x00343c49, 0x00383e4c, 0x003a4050, 0x003b4150, 0x003c4151, 0x003d4454, 0x003c4556, 0x003b4656, 0x003c4757, 0x003d4858, 0x003d4c5c, 0x003e4c5e, 0x003d4c5f, 0x003e4f5f, 0x003f4f5f, 0x003f4c5d, 0x003f4c5d, 0x003d4b5c, 0x003d4a5c, 0x003d4a5c, 0x003c495b, 0x003b4859, 0x00394959, 0x003b4b5a, 0x003c4c5b, 0x003c4c5b, 0x003d4c5c, 0x003c4b5a, 0x00394856, 0x00344250, 0x002e3a48, 0x002a3440, 0x0028303c, 0x0028303a, 0x00262e38, 0x00252d38, 0x00262e37, 0x00272f38, 0x0029323b, 0x0029323b, 0x0029313a, 0x002a333c, 0x002b333e, 0x002c343e, 0x002c343e, 0x002c343f, 0x002d3540, 0x002d3641, 0x002d3842, 0x002c3741, 0x002b3540, 0x002a343e, 0x002a343f, 0x002d3944, 0x002e3a46, 0x002f3b47, 0x002e3a46, 0x002f3945, 0x002f3844, 0x002b3440, 0x00252c38, 0x001c232c, 0x00181e24, 0x00141c22, 0x00121b22, 0x00162029, 0x001c2630, 0x00202934, 0x00202832, 0x001c232c, 0x00181c25, 0x00161b23, 0x00181c24, 0x001a1f27, 0x001b2028, 0x001c2028, 0x001e212c, 0x00202430, 0x00242a35, 0x00282f3b, 0x002c3340, 0x002c3443, 0x002b3544, 0x00243040, 0x001a2938, 0x00152434, 0x00142432, 0x0010222e, 0x000f202c, 0x000d1d2a, 0x000c1b28, 0x000b1a26, 0x000b1a25, 0x000b1a25, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000c1924, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000d1b24, 0x000d1b24, 0x000d1a25, 0x000d1a26, 0x000d1a26, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000c1a21, 0x000c1a21, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1820, 0x000c1821, 0x000c1821, 0x000b1822, 0x000b1822, 0x000a1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000b1821, 0x000c1821, 0x000c1821, 0x000c1822, 0x000b1823, 0x000c1924, 0x000b1823, 0x000b1822, 0x000b1822, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0016383c, 0x00183d41, 0x001b4448, 0x001d4b4e, 0x00205154, 0x0021585a, 0x00245d60, 0x00256264, 0x0029737e, 0x002d8496, 0x002e8698, 0x002f8898, 0x0030899a, 0x00308a9a, 0x00318a9b, 0x00318b9b, 0x00318b9b, 0x00318b9b, 0x00318b9b, 0x00318a9b, 0x00308a9b, 0x00308a9b, 0x00308a9a, 0x00308a9a, 0x00308a9a, 0x00308a9a, 0x00308a9b, 0x00308a9b, 0x00318b9b, 0x00318b9b, 0x00318b9b, 0x00318b9b, 0x00318b9b, 0x00318b9b, 0x00318b9b, 0x00308a9a, 0x0030899a, 0x002f8898, 0x002e8697, 0x002c8394, 0x00286c72, 0x00256163, 0x00235c5e, 0x00205558, 0x001f5053, 0x001c484c, 0x001a4245, 0x00183c40, 0x0015363b, 0x00143036, 0x00132c32, 0x0012282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081720, 0x00081721, 0x00081721, 0x000a1620, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a151f, 0x00091621, 0x00081722, 0x00081722, 0x00091823, 0x00091823, 0x00081821, 0x00081820, 0x00081820, 0x00081820, 0x00081820, 0x00081820, 0x00081820, 0x00091820, 0x00091820, 0x000a1821, 0x000a1720, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b161f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b181f, 0x000a1820, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1823, 0x000b1823, 0x000c1924, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1a25, 0x000c1c25, 0x000c1c25, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000d1b25, 0x000d1c25, 0x000d1c28, 0x000e1e2c, 0x00142433, 0x001b2c3a, 0x00233442, 0x002c3949, 0x002e3948, 0x00283240, 0x00242c39, 0x001d2733, 0x0019232e, 0x0019222c, 0x0019222b, 0x001c242d, 0x001e2830, 0x00242c38, 0x002e3844, 0x00343e4b, 0x00343f4b, 0x00333e4a, 0x00313d49, 0x00303c48, 0x002e3946, 0x002d3845, 0x002d3844, 0x002d3844, 0x002c3542, 0x002b3440, 0x002c3340, 0x002c333f, 0x002c343f, 0x002c343e, 0x002c343e, 0x002c343e, 0x002a323d, 0x002a343e, 0x00303844, 0x00363f4b, 0x003a4450, 0x003b4451, 0x003c4754, 0x003e4956, 0x003f4a58, 0x003e4a58, 0x003d4856, 0x003c4855, 0x003c4856, 0x003c4957, 0x003a4656, 0x00384454, 0x00384352, 0x00374251, 0x00364251, 0x00374252, 0x00384151, 0x0037404f, 0x00353e4c, 0x00353d4c, 0x00383e4c, 0x0039404d, 0x003b404d, 0x003b404d, 0x003a404d, 0x0038404c, 0x0038404c, 0x0038404c, 0x0038404c, 0x0038404b, 0x00363e48, 0x00333945, 0x002d343f, 0x00282e38, 0x00222831, 0x0020252f, 0x0020242e, 0x0022252c, 0x0024272e, 0x00272931, 0x00282c35, 0x00282e36, 0x00282f36, 0x00293037, 0x002a3038, 0x002b3039, 0x002d313c, 0x002d323c, 0x002e333c, 0x002e343d, 0x002e343d, 0x002f3440, 0x002c3641, 0x002c3741, 0x002c3640, 0x002c3440, 0x002c333e, 0x0029303a, 0x00292f38, 0x002a2e38, 0x00292e38, 0x00282c37, 0x00262a34, 0x00252a34, 0x00272c35, 0x00292e38, 0x00292f38, 0x00282d35, 0x00262b33, 0x0024272f, 0x0020242c, 0x001f222d, 0x00232632, 0x00292c3a, 0x002e3341, 0x00303644, 0x00323946, 0x00353d4a, 0x00353e4b, 0x00353e4c, 0x0037404e, 0x00384050, 0x00384051, 0x00384152, 0x00394253, 0x003c4455, 0x003d4556, 0x003a4454, 0x00394454, 0x003b4757, 0x003c495b, 0x003d4b5c, 0x003c4a5c, 0x003c4b5c, 0x003d4b5c, 0x003e4c5c, 0x003e4c5d, 0x003d4c5c, 0x003c4a5c, 0x003c4a5c, 0x003d4c5c, 0x003f4d5e, 0x003e4e5e, 0x003e4e5d, 0x003f4e5c, 0x003e4c5c, 0x003c4b59, 0x00394654, 0x0034404d, 0x002d3a48, 0x002b3643, 0x0027303c, 0x00262e39, 0x00262e38, 0x00272e38, 0x00262e37, 0x00262e37, 0x00272f38, 0x00283038, 0x0028313a, 0x0029323b, 0x002b343c, 0x002c343f, 0x002c343f, 0x002c3440, 0x002c3440, 0x002d3541, 0x002e3842, 0x00303944, 0x002f3843, 0x002e3843, 0x002c3741, 0x002a3640, 0x002e3a44, 0x002e3b46, 0x002f3b47, 0x002e3a46, 0x002e3945, 0x002e3844, 0x002c3441, 0x00262c39, 0x001c232c, 0x00181f24, 0x00161e24, 0x00121b23, 0x00141d27, 0x001c2630, 0x00202833, 0x00202832, 0x001d252e, 0x001b2029, 0x00191d27, 0x001c2029, 0x001e232c, 0x001f232d, 0x001e232d, 0x001f232f, 0x00202632, 0x00242a37, 0x00282e3c, 0x002b3341, 0x002c3444, 0x002b3443, 0x00212c3c, 0x00182836, 0x00142432, 0x00132330, 0x0011212d, 0x000f1f2c, 0x000d1c29, 0x000c1a27, 0x000a1926, 0x000b1a25, 0x000b1a25, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1a25, 0x000d1a26, 0x000d1a26, 0x000d1b24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1923, 0x000c1922, 0x000c1921, 0x000b1920, 0x000c1a21, 0x000b1920, 0x000b1920, 0x000b1820, 0x000c1821, 0x000c1821, 0x000b1822, 0x000b1822, 0x000a1821, 0x000a1821, 0x000b1822, 0x000b1822, 0x000c1822, 0x000c1822, 0x000c1822, 0x000c1822, 0x000b1923, 0x000c1924, 0x000b1823, 0x000b1822, 0x000b1822, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0017383c, 0x00183f43, 0x001c4448, 0x001d4b4e, 0x00205154, 0x0021585a, 0x00245d60, 0x00266466, 0x002c8093, 0x003198b5, 0x00339ab6, 0x00349bb7, 0x00349cb7, 0x00349cb8, 0x00359db8, 0x00359db8, 0x00359db8, 0x00359db8, 0x00359db8, 0x00359db8, 0x00359cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00359cb8, 0x00349cb8, 0x00349cb8, 0x00349cb8, 0x00349cb7, 0x00339bb7, 0x00329ab6, 0x003198b5, 0x002a7c8d, 0x00256163, 0x00245c5e, 0x00205558, 0x001e4f51, 0x001c484c, 0x00194245, 0x00183c40, 0x00153439, 0x00143036, 0x00112a30, 0x0012282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0009151d, 0x000a161d, 0x000a161d, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a151f, 0x000a151f, 0x000b1620, 0x000b1620, 0x000a1620, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161f, 0x000b1621, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1620, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b1820, 0x000b1820, 0x000b1820, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000b1823, 0x000b1824, 0x000b1824, 0x000b1822, 0x000b1822, 0x000b1924, 0x000b1a25, 0x000b1925, 0x000c1925, 0x000c1a26, 0x000d1b26, 0x000e1b27, 0x000d1b26, 0x000c1a26, 0x000d1b26, 0x000c1c27, 0x000c1c29, 0x0010212e, 0x00152735, 0x001e2f3f, 0x00273747, 0x002a3947, 0x0025313f, 0x00202a38, 0x001d2734, 0x001c2431, 0x001b222e, 0x001b232e, 0x001c2530, 0x00202834, 0x00242c39, 0x002c3644, 0x00343e4c, 0x00333f4c, 0x00313f4c, 0x00303d4b, 0x00303d4b, 0x00303c4a, 0x002e3a48, 0x002d3844, 0x002e3844, 0x002d3643, 0x002c3441, 0x002c3440, 0x002c343f, 0x002c343f, 0x002c343f, 0x002c343f, 0x002c343f, 0x002c323c, 0x002c323c, 0x002e343e, 0x00333a44, 0x0038404c, 0x00394450, 0x00394652, 0x003c4854, 0x003e4a57, 0x003c4855, 0x003a4653, 0x003b4754, 0x003b4855, 0x003b4855, 0x00394855, 0x00384755, 0x00384655, 0x00384655, 0x00384655, 0x00384655, 0x00394454, 0x00374351, 0x00364050, 0x00384251, 0x00384353, 0x00384352, 0x00394351, 0x003b4451, 0x003b4554, 0x00394654, 0x00384553, 0x00394452, 0x00384451, 0x0038414f, 0x00343d49, 0x00303641, 0x002b313a, 0x00262d34, 0x00222931, 0x0022272f, 0x0022262f, 0x00242830, 0x00272a31, 0x00282b34, 0x002a2c35, 0x00292e37, 0x00292e37, 0x002a2f38, 0x002c313a, 0x002e333c, 0x002e333c, 0x002e333c, 0x002e333c, 0x002e343d, 0x002f353e, 0x00303640, 0x002e3641, 0x002e3742, 0x002f3742, 0x002e3540, 0x002c343e, 0x0028303b, 0x00282e39, 0x002a2f3a, 0x002a2f3b, 0x00292d39, 0x00262b36, 0x00262a34, 0x00272c35, 0x00282d37, 0x00282d37, 0x00282e37, 0x00272c36, 0x00242b34, 0x00212730, 0x001f242f, 0x0020242d, 0x00242933, 0x002a303c, 0x002f3542, 0x00353e4b, 0x00384250, 0x00374350, 0x00374352, 0x00394454, 0x003a4454, 0x003a4454, 0x003b4656, 0x003b4656, 0x003c4656, 0x003c4456, 0x003b4454, 0x00394454, 0x00394457, 0x00384558, 0x00394757, 0x003a4858, 0x003c4959, 0x003e4c5b, 0x003e4b5b, 0x003d4c5b, 0x003c4c5c, 0x003b4b5a, 0x003b4b5a, 0x003e4c5d, 0x003f4d5e, 0x003e4d5e, 0x003c4c5b, 0x003c4c59, 0x003c4a58, 0x003a4554, 0x00343e4c, 0x002f3846, 0x002b3442, 0x0029343f, 0x0026303c, 0x00262f3a, 0x00272f3a, 0x00272f39, 0x00272f39, 0x00272f3a, 0x00272f39, 0x00262e38, 0x00272f39, 0x0028303b, 0x0029323c, 0x002b343e, 0x002b3540, 0x002c3640, 0x002c3640, 0x002d3642, 0x00303844, 0x00303a45, 0x00303a45, 0x00303a45, 0x002c3844, 0x002c3744, 0x002e3945, 0x002e3b47, 0x002f3b47, 0x002f3b47, 0x002e3945, 0x002f3844, 0x002e3540, 0x00262c38, 0x001d232c, 0x00181d25, 0x00181e25, 0x00151c24, 0x00141c25, 0x001c242d, 0x00202831, 0x00202831, 0x001d252e, 0x001c212b, 0x001b2028, 0x001e242c, 0x00222830, 0x00222831, 0x00222630, 0x00212530, 0x00222734, 0x00252a38, 0x00282e3c, 0x002c3341, 0x002c3543, 0x00283440, 0x001f2c39, 0x00182733, 0x0014242e, 0x0014212c, 0x0014202c, 0x00121f2b, 0x00101c28, 0x000d1925, 0x000d1a24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000b1823, 0x000c1924, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000d1a25, 0x000d1b25, 0x000d1b24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000d1a25, 0x000d1a26, 0x000d1a26, 0x000d1b24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1925, 0x000d1a26, 0x000d1a26, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000b1824, 0x000b1824, 0x000b1824, 0x000c1924, 0x000c1a23, 0x000c1a23, 0x000c1a23, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00142e34, 0x00143036, 0x0017383c, 0x00183f43, 0x001c4448, 0x001d4b4e, 0x00205154, 0x0021585a, 0x00245d60, 0x00287584, 0x0033a4c8, 0x0034a4c6, 0x0034a3c3, 0x0035a4c3, 0x0036a4c4, 0x0037a4c4, 0x0037a5c4, 0x0037a5c4, 0x0037a5c4, 0x0037a5c4, 0x0037a5c4, 0x0037a5c4, 0x0037a4c4, 0x0037a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c4, 0x0036a4c3, 0x0035a4c3, 0x0034a3c3, 0x0034a2c3, 0x0034a4c8, 0x00319ebf, 0x00246063, 0x00235a5c, 0x00205457, 0x001e4f51, 0x001c474b, 0x001a4245, 0x00173c40, 0x00153439, 0x00143036, 0x00112a30, 0x0012282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0008141a, 0x0008151b, 0x0008151b, 0x000a161d, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000b171f, 0x000b171f, 0x000a171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a1520, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1620, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b1820, 0x000c1820, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000b1823, 0x000b1824, 0x000b1823, 0x000b1822, 0x000b1822, 0x000b1924, 0x000b1a25, 0x000b1925, 0x000b1824, 0x000b1824, 0x000c1924, 0x000c1925, 0x000c1924, 0x000b1924, 0x000c1925, 0x000c1a26, 0x000a1a28, 0x000c1e2b, 0x00102230, 0x00192b3a, 0x00243444, 0x00283745, 0x0022303c, 0x001e2938, 0x001e2837, 0x001d2634, 0x001c2430, 0x001d2530, 0x001d2630, 0x00202934, 0x00242e3a, 0x002c3643, 0x00343f4c, 0x0032404c, 0x00313f4c, 0x002f3e4b, 0x002f3d4b, 0x00313e4c, 0x00303c49, 0x002d3845, 0x002f3844, 0x002f3744, 0x002d3542, 0x002d3541, 0x002c343f, 0x002c343f, 0x002c343f, 0x002c343f, 0x002d343f, 0x002c333d, 0x002c333c, 0x002c333c, 0x002f353e, 0x00343c45, 0x0038434f, 0x00384652, 0x003a4753, 0x003d4856, 0x003c4755, 0x003a4553, 0x003b4753, 0x003c4856, 0x003c4856, 0x003a4956, 0x00394857, 0x003c4858, 0x003c4858, 0x003c4858, 0x003b4857, 0x003a4655, 0x00384453, 0x00384453, 0x00394454, 0x003b4656, 0x003a4656, 0x003c4654, 0x003d4855, 0x003d4958, 0x003c4b59, 0x003b4a58, 0x003b4855, 0x00384452, 0x0036404e, 0x00333c48, 0x002f3540, 0x002b3139, 0x00282f36, 0x00252c34, 0x00242830, 0x00242831, 0x00282b34, 0x002a2d35, 0x002a2d34, 0x002a2d35, 0x00292e34, 0x00282d35, 0x00292e36, 0x002c3139, 0x002e333c, 0x002e343d, 0x002e343d, 0x002e343d, 0x002f353f, 0x00303640, 0x00303640, 0x002e3641, 0x002e3642, 0x002e3641, 0x002d3540, 0x002c343f, 0x0028303c, 0x00292f3b, 0x002c303c, 0x002c303c, 0x002b303c, 0x00282c37, 0x00272c35, 0x00282c36, 0x00282c36, 0x00272c36, 0x00282e37, 0x00282f38, 0x00282e37, 0x00242b34, 0x00222830, 0x0020272f, 0x00212831, 0x00262c38, 0x002b313e, 0x00313a47, 0x0034404e, 0x00354250, 0x00374453, 0x003c4757, 0x003d4758, 0x003c4755, 0x003c4755, 0x003b4755, 0x003b4655, 0x003c4557, 0x003c4455, 0x003a4455, 0x00394456, 0x00384457, 0x00384454, 0x00384656, 0x003c4959, 0x00404d5c, 0x00414f5e, 0x0041505f, 0x0040505f, 0x003e505f, 0x0040505f, 0x00425162, 0x00404f60, 0x003d4c5d, 0x003a4958, 0x00384754, 0x00374553, 0x0035414f, 0x00313b49, 0x002c3644, 0x00293340, 0x0028323d, 0x0027313c, 0x0028303b, 0x0028303a, 0x0028303a, 0x0028303b, 0x0028303c, 0x0028303c, 0x0028303c, 0x0027303a, 0x00272f39, 0x0028303b, 0x0028313c, 0x002b343f, 0x002d3842, 0x002f3843, 0x002f3844, 0x00303844, 0x00313b48, 0x00303b48, 0x00303b47, 0x002e3945, 0x002d3844, 0x002e3945, 0x002f3b47, 0x002f3b47, 0x002f3b47, 0x002e3945, 0x002d3844, 0x002e3440, 0x00272c38, 0x001c212c, 0x00181d25, 0x00181e25, 0x00161c24, 0x00141c24, 0x001a232c, 0x001f2831, 0x00202830, 0x001d252e, 0x001c232c, 0x001c232c, 0x0020272f, 0x00242c35, 0x00282d37, 0x00262b35, 0x00232833, 0x00222733, 0x00252937, 0x00282d3a, 0x002c3340, 0x002c3441, 0x0025313d, 0x001c2b36, 0x00162630, 0x0013222d, 0x0014202c, 0x0014202c, 0x0014202b, 0x00111c28, 0x000d1924, 0x000d1a24, 0x000c1a24, 0x000c1924, 0x000b1823, 0x000b1822, 0x000c1924, 0x000c1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000e1c25, 0x000d1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000d1b24, 0x000d1a25, 0x000d1a26, 0x000d1a26, 0x000d1b24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1925, 0x000d1a26, 0x000d1a26, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000d1b24, 0x000c1924, 0x000b1824, 0x000b1824, 0x000c1a24, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1b24, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0017383c, 0x00183d41, 0x001c4448, 0x001d4b4e, 0x00205154, 0x00205659, 0x00245c5f, 0x00297b8c, 0x0033a6ca, 0x002c8496, 0x002b7378, 0x002c747b, 0x002c787c, 0x002d787d, 0x002d797e, 0x002d7a7e, 0x002e7a7f, 0x002d7a7e, 0x002d7a7e, 0x002d797e, 0x002e787e, 0x002d787d, 0x002d787d, 0x002c787c, 0x002c777c, 0x002c777c, 0x002c757b, 0x002c757b, 0x002c757b, 0x002c777c, 0x002c777c, 0x002c777c, 0x002c777c, 0x002c777c, 0x002c757b, 0x002c747b, 0x002b747a, 0x002a7278, 0x00297076, 0x003094b0, 0x00309fc0, 0x00245e61, 0x0022585b, 0x00205356, 0x001d4c50, 0x001c4649, 0x00194044, 0x00173a3e, 0x00153439, 0x00142e34, 0x00112a30, 0x0011242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0008141a, 0x0008151b, 0x0008151b, 0x000a151c, 0x000a151c, 0x000a151c, 0x0009151d, 0x0009151d, 0x000a161e, 0x000a161e, 0x000b171f, 0x000b171f, 0x000b171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161f, 0x000a1620, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1620, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b1720, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x00091720, 0x00091720, 0x00091720, 0x000b1821, 0x000b1821, 0x000b1823, 0x000c1824, 0x000b1823, 0x000a1821, 0x000a1820, 0x00091822, 0x00091822, 0x00091822, 0x000a1821, 0x000a1821, 0x00091821, 0x000c1822, 0x000c1822, 0x00091821, 0x000b1822, 0x000c1823, 0x000b1924, 0x000c1c28, 0x000f202c, 0x00172835, 0x00213240, 0x00263542, 0x00222e3c, 0x001f2b39, 0x00212b39, 0x00202936, 0x001f2733, 0x001e2731, 0x001d2530, 0x001f2834, 0x00222c38, 0x002b3542, 0x00333e4c, 0x0033404d, 0x0032404c, 0x00303f4b, 0x00303e4a, 0x00303e4a, 0x00303c48, 0x002e3946, 0x002f3844, 0x002f3744, 0x002e3643, 0x002d3542, 0x002d3540, 0x002d3540, 0x002d3540, 0x002c3440, 0x002d3440, 0x002e343e, 0x002e343d, 0x002c333c, 0x002c323c, 0x00303640, 0x00333c48, 0x0036424e, 0x00374450, 0x003a4654, 0x003c4855, 0x003c4854, 0x003e4956, 0x003f4c59, 0x003f4c5a, 0x003d4b58, 0x003a4a58, 0x003a4958, 0x003c4a58, 0x003c4a59, 0x003c4a59, 0x003d4858, 0x003b4655, 0x003b4657, 0x003c4858, 0x003d495a, 0x003d4b5b, 0x003f4b59, 0x003f4b58, 0x00404c5b, 0x003d4c5b, 0x003d4c5b, 0x003c4b59, 0x00394654, 0x00343f4c, 0x00323b48, 0x002f3540, 0x002c333a, 0x00282f37, 0x00262d34, 0x00262b33, 0x00262a34, 0x002a2d37, 0x002b2e37, 0x002a2d34, 0x00292c33, 0x00282c34, 0x00282c34, 0x00282d35, 0x002c3038, 0x002d323c, 0x002e333c, 0x002e343e, 0x00303640, 0x002f3640, 0x00303740, 0x00303741, 0x00303742, 0x002e3641, 0x002e3641, 0x002d3540, 0x002d3540, 0x002a323d, 0x002a303c, 0x002c303c, 0x002c303c, 0x002c303c, 0x00292e38, 0x00282d37, 0x00282c36, 0x00282c36, 0x00262c36, 0x00282e37, 0x00282f38, 0x00282e38, 0x00262c36, 0x00252a34, 0x00242a32, 0x00242b34, 0x00242b37, 0x00272e3b, 0x002c3442, 0x00303c4a, 0x0034414f, 0x00384453, 0x003d4858, 0x00404a5a, 0x00404a58, 0x003f4a58, 0x003e4958, 0x003d4858, 0x003e4859, 0x003c4658, 0x003b4456, 0x003a4457, 0x00384355, 0x00394554, 0x003c4958, 0x00414d5c, 0x00414f5e, 0x00435060, 0x00445261, 0x00425260, 0x00435261, 0x00445362, 0x00445364, 0x00415061, 0x003c4c5c, 0x00384756, 0x00344350, 0x0032404d, 0x00343f4c, 0x00323c49, 0x002c3644, 0x00283240, 0x0027313c, 0x0027303b, 0x00273039, 0x00283039, 0x0028303c, 0x002a313d, 0x002a313d, 0x002a323d, 0x002a313d, 0x0029303c, 0x0028303c, 0x0029303c, 0x0028303c, 0x0029333d, 0x002c3741, 0x00303a44, 0x00303845, 0x00313846, 0x00323c48, 0x00313c49, 0x00303c48, 0x002f3b47, 0x002e3945, 0x002f3b47, 0x00303c48, 0x00303c48, 0x002f3c48, 0x002d3844, 0x002c3643, 0x002c3440, 0x00242b38, 0x001e232d, 0x00191e26, 0x00181e25, 0x00181e25, 0x00151d26, 0x001b232c, 0x001e2830, 0x00202830, 0x001d262d, 0x001d242c, 0x0020262f, 0x00232c34, 0x0028303b, 0x002b333d, 0x002a313c, 0x00262c39, 0x00242937, 0x00242a37, 0x00282e3c, 0x002c3340, 0x002a323f, 0x00212d38, 0x00192833, 0x0014242f, 0x0012212c, 0x00121f2b, 0x00121e2a, 0x00121e2a, 0x00101c28, 0x000d1924, 0x000d1924, 0x000c1924, 0x000b1823, 0x000b1822, 0x000b1822, 0x000c1924, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000d1a25, 0x000d1a26, 0x000d1b26, 0x000d1b24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000d1a25, 0x000d1b26, 0x000d1b26, 0x000c1a25, 0x000c1924, 0x000c1924, 0x000d1a24, 0x000d1a24, 0x000c1924, 0x000b1824, 0x000b1824, 0x000c1a24, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0016363b, 0x00183d41, 0x001a4347, 0x001c4a4d, 0x001e5053, 0x00215659, 0x00235c5e, 0x00287a8c, 0x0033a6ca, 0x002c8091, 0x00296c6e, 0x002a6e70, 0x002b7072, 0x002c7274, 0x002c7374, 0x002c7475, 0x002c7475, 0x002c7475, 0x002c7475, 0x002c7374, 0x002c7374, 0x002c7274, 0x002b7173, 0x002b7072, 0x002b7071, 0x002c7071, 0x002b6f70, 0x002b6f70, 0x002b6f70, 0x002b6f70, 0x002b6f70, 0x002b6f70, 0x002b6f70, 0x002b6f70, 0x002a6e70, 0x002a6d6f, 0x00296c6e, 0x00286a6c, 0x0028686a, 0x002e91ad, 0x00309ec0, 0x00245c60, 0x00215659, 0x00205154, 0x001d4b4e, 0x001b4448, 0x00183f43, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0012242c, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081319, 0x0009141a, 0x0009141a, 0x000a141b, 0x000a141b, 0x0009141c, 0x0008141d, 0x0008141d, 0x0009151d, 0x000a161e, 0x000b171f, 0x000b171f, 0x000b171f, 0x000a171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b1621, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1620, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000c161f, 0x000c161f, 0x000b1620, 0x000b1620, 0x000c1620, 0x000c1620, 0x000c1620, 0x000b1620, 0x000b1620, 0x000b1720, 0x000c1821, 0x000c1821, 0x000c1823, 0x000c1824, 0x000c1823, 0x000a1820, 0x000a1820, 0x00091720, 0x00091720, 0x00091720, 0x00091720, 0x00091720, 0x00091720, 0x000a1821, 0x000b1821, 0x00091720, 0x000a1821, 0x000c1821, 0x000c1823, 0x000b1b25, 0x000f1e2a, 0x00142431, 0x001f2e3c, 0x00243340, 0x00232f3d, 0x00202c3a, 0x00242d3c, 0x00242d3a, 0x00232b37, 0x00212934, 0x001e2731, 0x001f2834, 0x00232c39, 0x00293340, 0x00323e4a, 0x0034414e, 0x0032404c, 0x0030404b, 0x00303f4a, 0x002f3c48, 0x002f3b47, 0x002f3b47, 0x002f3945, 0x00303845, 0x00303844, 0x002f3744, 0x002e3642, 0x002e3641, 0x002d3540, 0x002d3540, 0x002d3440, 0x002e343f, 0x002c333c, 0x002a303a, 0x002a313b, 0x002c323c, 0x002b333e, 0x00303b47, 0x00313d4b, 0x0034404e, 0x00384451, 0x003b4753, 0x003d4855, 0x003e4a58, 0x00404c5a, 0x0043505f, 0x0040505e, 0x003d4d5c, 0x003f4e5d, 0x0040505e, 0x00404e5d, 0x00404b59, 0x003d4858, 0x003d485a, 0x00404a5c, 0x00404d5e, 0x00404e5f, 0x00414d5d, 0x003f4c5a, 0x003d4a59, 0x003c4a59, 0x003b4b59, 0x003c4b59, 0x003b4858, 0x0034404c, 0x00313a47, 0x002e3440, 0x002c333b, 0x00292f37, 0x00272d35, 0x00282d35, 0x00292e38, 0x002c303a, 0x002c2f37, 0x00292c34, 0x00272b32, 0x00262b32, 0x00282c34, 0x00282d35, 0x002c313a, 0x002e333c, 0x002f343d, 0x002f3540, 0x00303640, 0x002f3640, 0x00303740, 0x00303741, 0x002f3642, 0x002d3540, 0x002d3540, 0x002d3540, 0x002d3540, 0x002c343f, 0x002c323e, 0x002d313d, 0x002c303c, 0x002c303c, 0x002b2f3a, 0x002a2f38, 0x00282c37, 0x00282c36, 0x00272c36, 0x00272d37, 0x00272d37, 0x00282e37, 0x00282e37, 0x00282d37, 0x00262d34, 0x00262c34, 0x00252c37, 0x00282e39, 0x002b323f, 0x002f3846, 0x00343e4b, 0x00364250, 0x003b4656, 0x003f4858, 0x00404a59, 0x00404b5b, 0x00404c5c, 0x00414c5c, 0x00414c5e, 0x00404b5c, 0x003e495b, 0x003d485a, 0x003b4657, 0x003c4857, 0x00414c5c, 0x0044505f, 0x00424e5d, 0x003f4c5b, 0x003d4b5a, 0x003e4c5c, 0x00404f5d, 0x00404e5e, 0x00404d5d, 0x003e4c5c, 0x003a4858, 0x00374453, 0x0034414f, 0x00313d4b, 0x00333c4b, 0x00323c49, 0x00303847, 0x002c3542, 0x0028313d, 0x00273039, 0x00272f38, 0x00283039, 0x0029313c, 0x002c323f, 0x002d3340, 0x002d3440, 0x002d3340, 0x002c3340, 0x002c333e, 0x002d333f, 0x002d343f, 0x002c343f, 0x002c3640, 0x002f3843, 0x00323a47, 0x00333b48, 0x00333d49, 0x00323d49, 0x00313d49, 0x00303c48, 0x002f3b47, 0x00303c48, 0x00303c48, 0x00303c48, 0x00303c48, 0x002d3844, 0x002c3642, 0x002a313e, 0x00232936, 0x001e232e, 0x001a1f27, 0x00181e26, 0x00181f27, 0x00182028, 0x001c242d, 0x001f2830, 0x00212a31, 0x00202830, 0x001e2730, 0x00232b35, 0x0028303b, 0x002c3641, 0x002f3844, 0x002f3844, 0x002b3440, 0x00262e3c, 0x00262d3b, 0x002b323f, 0x002c3440, 0x0028303c, 0x001c2834, 0x00152430, 0x0013232d, 0x0011202c, 0x00111e2a, 0x00111d29, 0x00111c28, 0x00101c28, 0x000d1925, 0x000c1924, 0x000c1923, 0x000b1822, 0x000b1822, 0x000b1822, 0x000c1924, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1a25, 0x000d1a26, 0x000e1b26, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c26, 0x000e1c27, 0x000e1c27, 0x000d1b26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1b24, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1a24, 0x000b1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00122c32, 0x00143036, 0x0015363b, 0x00183c40, 0x001a4245, 0x001c484c, 0x001e4f51, 0x00205457, 0x0022595c, 0x0028788b, 0x0032a5ca, 0x002b7f90, 0x00286a6c, 0x00296c6f, 0x002a6e70, 0x002b7071, 0x002c7173, 0x002c7173, 0x002c7173, 0x002c7173, 0x002c7173, 0x002b7173, 0x002b7072, 0x002b7071, 0x002b6f70, 0x002a6e70, 0x002a6d6f, 0x002a6d6f, 0x00296c6f, 0x002a6c6e, 0x002a6c6e, 0x002a6c6e, 0x002a6c6e, 0x002a6c6e, 0x002a6c6e, 0x002a6c6e, 0x00296c6e, 0x00296b6d, 0x0028696c, 0x00286769, 0x0026676c, 0x002f95b4, 0x002f9dc0, 0x00235a5e, 0x00205457, 0x001e4f51, 0x001c484c, 0x001a4347, 0x00183d41, 0x0015363b, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081319, 0x0009141a, 0x0009141a, 0x000a141a, 0x000a141b, 0x0009141b, 0x0008141c, 0x0008141d, 0x0009151d, 0x000a161e, 0x000b171f, 0x000b171f, 0x000b171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x000a171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b1620, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1622, 0x000b1620, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000c161d, 0x000c161d, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000b1620, 0x000b1620, 0x000b1720, 0x000b1820, 0x000c1821, 0x000c1823, 0x000c1824, 0x000c1823, 0x000a1820, 0x000a1820, 0x00091720, 0x00091720, 0x00091620, 0x000b1620, 0x000a1620, 0x00091620, 0x000a1720, 0x000b1720, 0x00091720, 0x00091720, 0x000b1821, 0x000b1821, 0x000a1923, 0x000d1c27, 0x0012202d, 0x001c2b38, 0x00243340, 0x00253240, 0x00232e3c, 0x00242e3c, 0x0028313d, 0x0028303d, 0x00262e39, 0x00222a35, 0x00202a35, 0x00212c38, 0x0026303d, 0x00323d4c, 0x00344150, 0x00344150, 0x0033414d, 0x00313f4c, 0x00303c49, 0x002f3b48, 0x00303b48, 0x00303b48, 0x00323a48, 0x00333947, 0x00303845, 0x002f3743, 0x002e3641, 0x002d3541, 0x002d3540, 0x002e3440, 0x002f3540, 0x002c323c, 0x002a303b, 0x002c323c, 0x002c333d, 0x002b343f, 0x002e3744, 0x00313b48, 0x00343f4c, 0x0037414e, 0x0038434f, 0x003b4551, 0x003c4755, 0x003e4958, 0x00404d5c, 0x0041505f, 0x0040505e, 0x0040505e, 0x0041505f, 0x00404e5d, 0x003f4b59, 0x003f4a59, 0x00404c5d, 0x00424d5f, 0x00424f60, 0x00405060, 0x00414e5e, 0x00404d5c, 0x003d4c5b, 0x003c4a58, 0x003b4958, 0x003a4857, 0x00364351, 0x00313c49, 0x002f3844, 0x002c333e, 0x002c313a, 0x002a2f37, 0x00282d35, 0x002b3038, 0x002d313b, 0x002d323c, 0x002b3038, 0x00282c34, 0x00252a32, 0x00262b31, 0x00282c34, 0x002a2f37, 0x002d323b, 0x002e333c, 0x002f343e, 0x00303640, 0x00303640, 0x002f3740, 0x00303740, 0x00303741, 0x002f3641, 0x002c3440, 0x002c3440, 0x002c3440, 0x002d3440, 0x002d3540, 0x002f3440, 0x00303440, 0x002e323e, 0x002d323d, 0x002c303c, 0x002c303b, 0x00282d38, 0x00282c37, 0x00272c37, 0x00262c37, 0x00272c37, 0x00282e38, 0x00282f38, 0x00282e38, 0x00282f36, 0x00293037, 0x00292f38, 0x00292e38, 0x002a303b, 0x002c3440, 0x00303946, 0x00343d4a, 0x00384250, 0x003c4554, 0x003e4857, 0x003f4b5a, 0x00404c5c, 0x00414d5e, 0x00414e5f, 0x00404d5e, 0x00404c5d, 0x00404c5d, 0x00414c5d, 0x00404c5b, 0x00414e5c, 0x00404d5c, 0x003e4a58, 0x003c4857, 0x003c4957, 0x003d4a58, 0x003d4b58, 0x003c4857, 0x003b4856, 0x003b4755, 0x00394453, 0x0035414f, 0x00333e4c, 0x00313c49, 0x00303847, 0x002e3644, 0x002e3644, 0x002d3542, 0x002b333d, 0x002b333c, 0x002a323c, 0x002a323c, 0x002c3440, 0x002e3442, 0x002f3442, 0x00303643, 0x00303643, 0x002f3442, 0x002e3440, 0x002f3540, 0x002f3642, 0x002e3742, 0x002d3741, 0x002e3842, 0x00333b47, 0x00343c49, 0x00343e4a, 0x00323e4a, 0x00323e4a, 0x00323d49, 0x00313c49, 0x00313d49, 0x00323e4a, 0x00323d49, 0x00303c48, 0x002d3844, 0x002c3542, 0x002a313e, 0x00232936, 0x001f232f, 0x001b1f28, 0x00192028, 0x00192028, 0x00182028, 0x001b232c, 0x001c2730, 0x00202a33, 0x00212b34, 0x00222a34, 0x0028303b, 0x002e3742, 0x00343d49, 0x00343e4c, 0x00343d4b, 0x00303a48, 0x002c3443, 0x002a3240, 0x002c3442, 0x002c3440, 0x00232c38, 0x00192531, 0x0014232e, 0x0013222d, 0x00101f2a, 0x00101e29, 0x00111c28, 0x00111c28, 0x00101c28, 0x000d1925, 0x000d1a25, 0x000c1a24, 0x000c1923, 0x000c1923, 0x000c1923, 0x000c1924, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1925, 0x000c1a25, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x000e1b27, 0x000e1c27, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x000e1c27, 0x000e1c27, 0x000d1b26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000d1a26, 0x000c1925, 0x000c1925, 0x000c1925, 0x000d1b24, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00132c32, 0x00143036, 0x00143439, 0x00183c40, 0x00194044, 0x001c474b, 0x001d4c50, 0x00205254, 0x0021585a, 0x0027788a, 0x0031a5ca, 0x002a7d8f, 0x0028686a, 0x00286a6c, 0x00296c6e, 0x002a6d6f, 0x002b6e70, 0x002b6f70, 0x002b7071, 0x002b7071, 0x002b7071, 0x002b6f70, 0x002b6f70, 0x002a6e70, 0x002a6d6f, 0x00296c6f, 0x00296c6e, 0x00296b6d, 0x00286a6c, 0x0028696c, 0x0028696c, 0x0028696c, 0x0028696c, 0x0028696c, 0x0028686b, 0x0028686b, 0x0028686b, 0x00286769, 0x00276668, 0x0027686e, 0x002d90ac, 0x0030a4c9, 0x002985a0, 0x00205659, 0x001f5154, 0x001d4c50, 0x001b4649, 0x00194044, 0x00173a3e, 0x00143439, 0x00143036, 0x00122c32, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0008121a, 0x0009141a, 0x0009141a, 0x000a131a, 0x000a131a, 0x000a131a, 0x0008141b, 0x0009141b, 0x0009141c, 0x000a141d, 0x000a161e, 0x000a161e, 0x000a161e, 0x000b171f, 0x000b171f, 0x000a1820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000b1820, 0x000a1820, 0x000a1820, 0x000a1720, 0x000a1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000a1620, 0x0009171f, 0x0009171f, 0x0009171f, 0x0009171f, 0x000b171f, 0x000c161e, 0x000c161e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000b1620, 0x000b1620, 0x000b1620, 0x000a171f, 0x00091720, 0x000a1821, 0x000a1823, 0x000b1822, 0x000c1820, 0x000c1820, 0x00091720, 0x00091720, 0x00091620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000a1620, 0x00081720, 0x00081720, 0x00091820, 0x00091821, 0x000a1923, 0x000d1b27, 0x0012202d, 0x001b2a37, 0x0023323f, 0x00243240, 0x00232f3c, 0x00242e3b, 0x0028323e, 0x0029313e, 0x00272f3b, 0x00222c35, 0x00202933, 0x00202b35, 0x00242f3a, 0x00323c4a, 0x00374250, 0x00364350, 0x00344350, 0x0033404e, 0x00303e4b, 0x00303d4a, 0x00303c4a, 0x00323c4a, 0x00343d4b, 0x00343c4b, 0x00343948, 0x00313845, 0x00303744, 0x002f3542, 0x002d3440, 0x002e3441, 0x00303540, 0x002c333e, 0x002c323d, 0x002f3440, 0x002f3540, 0x002f3542, 0x002f3643, 0x00303946, 0x00363e4b, 0x0039424e, 0x0039444f, 0x003a4552, 0x003c4855, 0x003e4958, 0x003f4c59, 0x00404e5c, 0x0042505f, 0x00435160, 0x0043505f, 0x00404e5d, 0x003f4c5b, 0x003f4c5b, 0x00424f5f, 0x00445060, 0x00415060, 0x003f505e, 0x003e4e5d, 0x003f4f5d, 0x00404f5d, 0x003e4c5a, 0x003c4855, 0x00384451, 0x00333e4b, 0x00303845, 0x002d3541, 0x002c323c, 0x002b313b, 0x002b3038, 0x002a2f37, 0x002c3038, 0x002d323b, 0x002d323c, 0x002c303b, 0x002a2e37, 0x00272c34, 0x00272c34, 0x00282d36, 0x002b3039, 0x002c313c, 0x002d333c, 0x002f343f, 0x00303742, 0x00313842, 0x00303843, 0x00313843, 0x00303742, 0x00303641, 0x002d343f, 0x002c343e, 0x002c343f, 0x002d3440, 0x002f3540, 0x00303541, 0x00303440, 0x002f343f, 0x002e323e, 0x002b303b, 0x002a303a, 0x00292f38, 0x00282e38, 0x00262c36, 0x00262c36, 0x00272c36, 0x00282d36, 0x00292e37, 0x00292e37, 0x00292e36, 0x002b3038, 0x002b2f3a, 0x002c303c, 0x002c303c, 0x002b313d, 0x002d343f, 0x00323944, 0x00373f4b, 0x003a4350, 0x003c4654, 0x003d4a59, 0x003f4d5c, 0x00404e5c, 0x003f4e5d, 0x003f4d5d, 0x00404d5c, 0x00404d5c, 0x00424f5e, 0x0042505d, 0x00414f5c, 0x00404e5c, 0x00404d5c, 0x003e4c5a, 0x00404e5b, 0x00404d5b, 0x003f4c59, 0x003c4957, 0x003c4856, 0x003a4553, 0x00384150, 0x00343e4c, 0x00333c4a, 0x00323a48, 0x002e3643, 0x002a323f, 0x002b333e, 0x002c343e, 0x002c343d, 0x002d353f, 0x002d3640, 0x002e3742, 0x002f3743, 0x002f3744, 0x00303643, 0x00303643, 0x00303744, 0x00303643, 0x002f3641, 0x00303742, 0x00303843, 0x00303944, 0x002f3843, 0x002e3842, 0x00303a46, 0x00333c49, 0x00333e4a, 0x00333e4a, 0x00343f4c, 0x00343f4c, 0x00333f4c, 0x00333f4c, 0x00333e4c, 0x00323d4a, 0x00303c48, 0x002f3844, 0x002c3641, 0x002b323d, 0x00242b37, 0x001f2430, 0x001c212b, 0x001a2029, 0x001a202a, 0x00182029, 0x0018222c, 0x00192530, 0x001c2832, 0x00222c36, 0x00262f39, 0x002a3340, 0x00303947, 0x00353e4d, 0x00353f4f, 0x00364050, 0x00343d4c, 0x00303947, 0x002d3644, 0x002e3644, 0x0028303e, 0x001c2533, 0x0016212d, 0x0014212d, 0x0012212c, 0x000f1e29, 0x000e1c28, 0x000f1c28, 0x000f1c28, 0x000e1c27, 0x000c1925, 0x000d1a25, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1925, 0x000c1924, 0x000c1925, 0x000c1925, 0x000c1a25, 0x000e1c26, 0x000e1c27, 0x000e1c26, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x000e1c27, 0x000e1c27, 0x000c1c24, 0x000c1c24, 0x000c1c24, 0x000c1c24, 0x000c1c24, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1c25, 0x000d1c25, 0x000e1c25, 0x000d1b25, 0x000d1b26, 0x000d1b26, 0x000e1c25, 0x000e1c25, 0x000e1c24, 0x000e1c24, 0x000e1c24, 0x000d1c24, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153439, 0x00173a3e, 0x00183f43, 0x001b4448, 0x001d4b4e, 0x001f5053, 0x00205558, 0x00267689, 0x0030a4ca, 0x00297b8e, 0x00266467, 0x00286769, 0x0028696c, 0x00296b6d, 0x00296c6e, 0x00296c6f, 0x002a6d6f, 0x002a6d6f, 0x002a6d6f, 0x00296c6f, 0x00296c6f, 0x002a6c6e, 0x00296b6d, 0x00286a6c, 0x0028696c, 0x0028686b, 0x0028686a, 0x00286769, 0x00286769, 0x00276668, 0x00276668, 0x00276668, 0x00276668, 0x00266568, 0x00266467, 0x00266466, 0x00276a71, 0x002d94b2, 0x0030a2c8, 0x00288098, 0x0021595c, 0x001f5254, 0x001d4d50, 0x001c484c, 0x001a4347, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0013282e, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0008121a, 0x0009141a, 0x0009141a, 0x000a1319, 0x000a1219, 0x00091219, 0x00081319, 0x0009141a, 0x0009141c, 0x000a141d, 0x000a151e, 0x000a161e, 0x000a161e, 0x000b171f, 0x000b171f, 0x000b1820, 0x000b1820, 0x000a1820, 0x000b1920, 0x000b1920, 0x000b1920, 0x000a1820, 0x000a1820, 0x000a1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x00091620, 0x0008181f, 0x0008181f, 0x0008181f, 0x0008171f, 0x0009171f, 0x000a151e, 0x000a151e, 0x000a151e, 0x000a151e, 0x000b161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000b161f, 0x000a171f, 0x00091720, 0x00081821, 0x00081823, 0x000a1822, 0x000c1820, 0x000c1820, 0x00091720, 0x00091720, 0x00091620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000a1620, 0x00081720, 0x00081820, 0x00081820, 0x00081821, 0x000a1923, 0x000d1b27, 0x0013202d, 0x001b2a37, 0x0023323f, 0x00243240, 0x00222f3c, 0x0024303c, 0x002a3440, 0x002a3440, 0x0028303c, 0x00242d37, 0x00202a33, 0x00202a33, 0x00242d39, 0x00303947, 0x00384250, 0x00384452, 0x00344451, 0x00344350, 0x0034404e, 0x00323f4c, 0x00323d4b, 0x00333e4c, 0x0036404d, 0x00373f4d, 0x00343c4b, 0x00343b48, 0x00333947, 0x00313845, 0x002d3441, 0x002f3542, 0x00303742, 0x002f3540, 0x00303640, 0x00303742, 0x00313844, 0x00313845, 0x00313845, 0x00313946, 0x00353d4a, 0x003b4350, 0x003b4550, 0x003b4652, 0x003d4955, 0x003f4c59, 0x00404d5b, 0x00414f5c, 0x0043515f, 0x00455261, 0x00445160, 0x00435060, 0x00404f5f, 0x003f4e5d, 0x00415060, 0x00435160, 0x0040505e, 0x003e505c, 0x003d4e5c, 0x003c4d5b, 0x003d4d5b, 0x003d4956, 0x003c4551, 0x0038404c, 0x00333a46, 0x00313743, 0x002f3440, 0x002b313c, 0x002a303b, 0x002c3039, 0x002a2f37, 0x002c3038, 0x002d303a, 0x002e303b, 0x002d303b, 0x002c3038, 0x00282d35, 0x00282d36, 0x00293039, 0x002c323c, 0x002e343e, 0x002e343e, 0x002f3540, 0x00313843, 0x00313843, 0x00313843, 0x00313843, 0x00303742, 0x00303641, 0x002d343f, 0x002c343e, 0x002c343f, 0x002e3440, 0x002f3541, 0x00303541, 0x002f3440, 0x002f343f, 0x002d323d, 0x002a313b, 0x002a303a, 0x002a303a, 0x00282f38, 0x00272e37, 0x00252c35, 0x00272c36, 0x00282d36, 0x00292e36, 0x00292e36, 0x00292e36, 0x002a2f38, 0x002b303a, 0x002c303c, 0x002c303c, 0x002b313c, 0x002c323d, 0x002f3540, 0x00323844, 0x00373e4a, 0x00394450, 0x003b4756, 0x003d4c5b, 0x003e4d5c, 0x003d4d5c, 0x003f4d5c, 0x003e4d5c, 0x003f4c5c, 0x00445060, 0x00455362, 0x00425160, 0x003f4e5c, 0x003d4c5b, 0x003c4c5a, 0x003d4b58, 0x003e4a58, 0x003d4957, 0x003d4856, 0x003c4754, 0x00384250, 0x00343c4b, 0x00333a48, 0x00323a45, 0x00303843, 0x002d3540, 0x002a323d, 0x0029313c, 0x002a333c, 0x002b343d, 0x002d3540, 0x002e3742, 0x00303945, 0x00303a46, 0x00303946, 0x00303845, 0x00303844, 0x00303844, 0x00303844, 0x00303843, 0x00303844, 0x00303944, 0x00303944, 0x00303a44, 0x00303944, 0x00303a46, 0x00323c48, 0x00333e4a, 0x00343f4c, 0x0034404d, 0x0034404e, 0x00343f4c, 0x00343f4c, 0x00333f4c, 0x00323d4a, 0x00303c48, 0x002f3944, 0x002c3741, 0x002b333e, 0x00272d38, 0x00202732, 0x001d232e, 0x001b212b, 0x001c232c, 0x001b232b, 0x0018232c, 0x001b2630, 0x001d2a34, 0x00222d38, 0x002a333e, 0x002f3845, 0x00333c4b, 0x0035404e, 0x00364150, 0x00394452, 0x00384151, 0x00333c4b, 0x00303947, 0x002c3543, 0x00212b38, 0x0016202e, 0x00131f2b, 0x0014202c, 0x0011202c, 0x000e1d28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000b1a25, 0x000c1b25, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1924, 0x000b1824, 0x000b1824, 0x000b1824, 0x000c1925, 0x000c1925, 0x000e1c27, 0x000e1c27, 0x000e1c26, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x000e1c27, 0x000e1c27, 0x000c1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000c1c24, 0x000e1c25, 0x000e1c25, 0x000e1c26, 0x000e1c27, 0x000e1c27, 0x000e1c25, 0x000e1c25, 0x000e1c24, 0x000e1c24, 0x000e1c24, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012242c, 0x00112a30, 0x00142e34, 0x00153338, 0x0017383c, 0x00183d41, 0x001a4347, 0x001c484c, 0x001d4d50, 0x00205254, 0x00257488, 0x0030a4ca, 0x00297f94, 0x00276a73, 0x00286c75, 0x00286f77, 0x00297078, 0x00297179, 0x002a737b, 0x002a737b, 0x002a737b, 0x002b747c, 0x002a747c, 0x002a737b, 0x002a737b, 0x00297179, 0x0028696c, 0x0028686a, 0x00286769, 0x00276668, 0x00266568, 0x00266467, 0x00266466, 0x00266466, 0x00266466, 0x00266364, 0x00266364, 0x00256264, 0x00266c75, 0x002d97b8, 0x0030a0c5, 0x0027788c, 0x0021585b, 0x00205356, 0x001e4f51, 0x001c4a4d, 0x001b4649, 0x001a4044, 0x00183c40, 0x0016363b, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0009121b, 0x000a141b, 0x000a141b, 0x000a1219, 0x000a1219, 0x00091219, 0x00081319, 0x0009141a, 0x000a141c, 0x000b141c, 0x000b151e, 0x000a161e, 0x000a161e, 0x000b171f, 0x000c171f, 0x000b1820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000b1820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000a1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x00091620, 0x0008181f, 0x0008181f, 0x0008181f, 0x0008171f, 0x0009171f, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000b151e, 0x000c161f, 0x000d1720, 0x000c161d, 0x000c161d, 0x000b161e, 0x000a171f, 0x0009171f, 0x00091821, 0x00091822, 0x000b1822, 0x000c1820, 0x000c1820, 0x000a1720, 0x000a1720, 0x000a1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000a1620, 0x00081720, 0x00081820, 0x00081820, 0x00081821, 0x000a1923, 0x000e1c27, 0x0013212e, 0x001b2a37, 0x0020303d, 0x0023303f, 0x0023303d, 0x0027333f, 0x002c3744, 0x002c3643, 0x0028333f, 0x0025303a, 0x00212c35, 0x001f2933, 0x00242d38, 0x002c3644, 0x0035404e, 0x00384554, 0x00364553, 0x00364452, 0x00354352, 0x0033404f, 0x00333e4c, 0x0035404f, 0x00384250, 0x00384050, 0x00363e4c, 0x00353c4a, 0x00353c49, 0x00343b48, 0x00303543, 0x00303744, 0x00323844, 0x00323843, 0x00333944, 0x00333944, 0x00333945, 0x00333b47, 0x00323a46, 0x00313844, 0x00323a46, 0x00353d49, 0x0037414c, 0x00394450, 0x003d4854, 0x00404c5a, 0x00414f5d, 0x00404f5d, 0x00404f5d, 0x00404f5e, 0x003d4b5a, 0x003e4c5b, 0x00404f5e, 0x0040505f, 0x003f4f5d, 0x0040505d, 0x0040505d, 0x003e505c, 0x003c4f5b, 0x003b4c58, 0x00384854, 0x0037424e, 0x00373f4c, 0x00343c48, 0x00333a45, 0x00323741, 0x0030343f, 0x002c313b, 0x002b303a, 0x002c3038, 0x002a2f37, 0x002b3038, 0x002c303a, 0x002c303a, 0x002c303a, 0x002c3039, 0x002c3039, 0x002c323b, 0x002e343e, 0x00303640, 0x00303640, 0x002f3440, 0x002f3440, 0x00303742, 0x00313844, 0x00313843, 0x00313843, 0x00303742, 0x00303641, 0x002d343f, 0x002c343e, 0x002c343f, 0x002e3440, 0x002f3440, 0x002f3440, 0x002f3440, 0x002f3440, 0x002f3440, 0x002c343e, 0x002e343e, 0x002d343d, 0x002c333d, 0x002c323c, 0x00293039, 0x00282c37, 0x00282d37, 0x00292e37, 0x00292e37, 0x00292e37, 0x00292e38, 0x00292e38, 0x002a2f3a, 0x002c303c, 0x002b303c, 0x002c323d, 0x002f3540, 0x00323844, 0x00353c48, 0x0036404c, 0x00364150, 0x00384655, 0x00394857, 0x003b4a58, 0x003c4b59, 0x003b4a58, 0x003b4858, 0x003f4c5c, 0x00404f5e, 0x003e4e5c, 0x003b4c5a, 0x00384958, 0x003a4a58, 0x00394856, 0x00384452, 0x00374350, 0x00364250, 0x0035404d, 0x00343c4a, 0x00323948, 0x00303844, 0x00303843, 0x002f3742, 0x002c3440, 0x002b333d, 0x002b333d, 0x002b343c, 0x002b333c, 0x002c343f, 0x002e3742, 0x00303946, 0x00323c48, 0x00333c49, 0x00323c48, 0x00303a48, 0x00303947, 0x00303845, 0x00303844, 0x00313945, 0x00313a46, 0x00303a46, 0x00313b48, 0x00313b48, 0x00303a47, 0x00323c48, 0x00343f4b, 0x0034404c, 0x0034404e, 0x0034404e, 0x00343f4c, 0x00343f4c, 0x00333f4c, 0x00323d4a, 0x00303c48, 0x002f3944, 0x002c3741, 0x002b343f, 0x00282f3a, 0x00212834, 0x001f2430, 0x001c212c, 0x001c232c, 0x001c252d, 0x001c2630, 0x001e2833, 0x00202c37, 0x0025313b, 0x002b3641, 0x00313c48, 0x00343e4c, 0x0037414f, 0x00384451, 0x003a4654, 0x003b4554, 0x0037404f, 0x00323c4a, 0x00293341, 0x001b2433, 0x00121c2a, 0x00121e2a, 0x0014202c, 0x0011202b, 0x000e1d28, 0x000d1c28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1b26, 0x000c1b25, 0x000c1b24, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000b1824, 0x000b1824, 0x000c1925, 0x000c1925, 0x000d1b26, 0x000e1c27, 0x000f1c28, 0x000e1c27, 0x000e1c26, 0x000e1c26, 0x000e1c26, 0x000e1c26, 0x000e1c27, 0x000e1c27, 0x000e1c27, 0x000c1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000c1c24, 0x000d1c24, 0x000e1c25, 0x000e1c25, 0x000e1c27, 0x000e1c27, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c24, 0x000e1c24, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0016363b, 0x00183c40, 0x00194044, 0x001c4649, 0x001c4a4d, 0x001e4f51, 0x00226674, 0x002c9dc3, 0x002ea1c7, 0x0030a0c5, 0x0030a1c5, 0x0031a1c5, 0x0031a2c6, 0x0032a3c6, 0x0032a3c6, 0x0033a3c6, 0x0033a4c6, 0x0033a4c6, 0x0033a4c7, 0x0033a4c7, 0x0033a4c7, 0x0032a2c4, 0x00286d73, 0x00286769, 0x00266568, 0x00266467, 0x00266466, 0x00256364, 0x00256264, 0x00256264, 0x00256163, 0x00246062, 0x00246062, 0x00266e7b, 0x002e9bbd, 0x002f9dc2, 0x00257183, 0x00215659, 0x00205356, 0x001e5053, 0x001d4b4e, 0x001c474b, 0x001a4245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a121b, 0x000b131c, 0x000b131c, 0x000b121a, 0x000a1219, 0x000a1219, 0x00091219, 0x000a131a, 0x000b141a, 0x000c141b, 0x000b151d, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000b171f, 0x000b171f, 0x000b171f, 0x0009171f, 0x000a1820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000c1821, 0x000c1821, 0x00091620, 0x0008181f, 0x0008181f, 0x0008181f, 0x0008171f, 0x0009171f, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b161e, 0x000a171f, 0x0009171f, 0x000a1820, 0x000a1821, 0x000c1820, 0x000d1720, 0x000d1720, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000a1620, 0x00081720, 0x00081820, 0x00081820, 0x00081821, 0x000b1924, 0x000f1c28, 0x0014222f, 0x001b2a37, 0x001e2d3b, 0x0021303d, 0x0023303d, 0x00283540, 0x002c3844, 0x002c3844, 0x002b3541, 0x0028323d, 0x00232e38, 0x001f2a34, 0x00212c37, 0x00273240, 0x00323e4c, 0x00384553, 0x00364552, 0x00374553, 0x00374453, 0x00354251, 0x00354050, 0x00384451, 0x00394452, 0x00384150, 0x00353f4d, 0x00353f4c, 0x0037404c, 0x00373f4c, 0x00323946, 0x00313845, 0x00353c48, 0x00363d48, 0x00353c48, 0x00343b47, 0x00333a45, 0x00333c47, 0x00323b45, 0x00303742, 0x00303641, 0x00303742, 0x00313944, 0x00343c49, 0x00363f4c, 0x00384251, 0x003b4857, 0x003b4858, 0x003b4958, 0x003b4a58, 0x003b4a58, 0x003c4958, 0x003e4c5b, 0x003f4c5c, 0x003c4b5a, 0x003d4b5a, 0x003d4b58, 0x003a4956, 0x00384754, 0x00344451, 0x0034404c, 0x00313c48, 0x00313844, 0x00313844, 0x00323841, 0x00313540, 0x0030343f, 0x002f343c, 0x002d323a, 0x002c3139, 0x002b3038, 0x002b3038, 0x002c303a, 0x002c2f3a, 0x002c2f39, 0x002c303a, 0x002f333d, 0x00313640, 0x00313841, 0x00313841, 0x00303742, 0x002e343f, 0x002d333f, 0x00303541, 0x00313843, 0x00313843, 0x00303843, 0x00303742, 0x00303641, 0x002d343f, 0x002c333e, 0x002d343f, 0x002e343f, 0x002e343f, 0x002e3440, 0x002f3440, 0x00303541, 0x00303742, 0x00303843, 0x00313842, 0x00303742, 0x00303541, 0x002d343f, 0x002b313c, 0x00282e38, 0x00282d37, 0x00282d37, 0x00282d37, 0x00282d37, 0x00282d37, 0x00282d38, 0x00292e39, 0x002b2f3b, 0x002b303c, 0x002c323d, 0x002e3440, 0x00303541, 0x00303844, 0x00303947, 0x00303c4b, 0x00344050, 0x00374251, 0x00384554, 0x003b4857, 0x003c4958, 0x003b4857, 0x003b4858, 0x003d4c5b, 0x003d4e5c, 0x003c4d5c, 0x003a4b59, 0x00384857, 0x00384856, 0x00364250, 0x00323e4c, 0x00323c4b, 0x00323c48, 0x00323b48, 0x00313946, 0x00303744, 0x002f3742, 0x00303842, 0x002f3742, 0x002e3640, 0x002d353f, 0x002d353f, 0x002d353f, 0x002d3540, 0x002f3843, 0x00303946, 0x00313b48, 0x00343e4a, 0x00343e4c, 0x00333c4b, 0x00323c4a, 0x00313b48, 0x00333b48, 0x00343b48, 0x00343c49, 0x00343d49, 0x00343e4a, 0x00343e4a, 0x00323c49, 0x00343e4a, 0x0035414d, 0x0035414e, 0x0035404f, 0x0034404e, 0x00343f4c, 0x00343f4c, 0x00333f4c, 0x00323d4b, 0x00303c4a, 0x002e3945, 0x002b3743, 0x002a3440, 0x0027303a, 0x00212934, 0x001f2832, 0x001c2430, 0x001c2430, 0x001f2730, 0x00202832, 0x00202b35, 0x00232f38, 0x0026323c, 0x002c3743, 0x00303b48, 0x00343d4b, 0x0037404f, 0x003a4452, 0x003d4856, 0x003d4856, 0x003a4452, 0x00343d4c, 0x00283140, 0x0018202f, 0x00101b28, 0x00131e2b, 0x0013202c, 0x0010202b, 0x000e1d28, 0x000d1c28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1b25, 0x000c1a24, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000c1924, 0x000c1924, 0x000c1a25, 0x000d1b26, 0x000e1c27, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000c1d25, 0x000c1d24, 0x000c1d24, 0x000c1d24, 0x000c1d24, 0x000c1d24, 0x000c1d24, 0x000c1d24, 0x000c1d24, 0x000c1d24, 0x000d1d24, 0x000d1d24, 0x000e1c25, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00111f27, 0x00102229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4245, 0x001c474b, 0x001d4c50, 0x001e5053, 0x00236877, 0x00298ba8, 0x002b8dab, 0x002c8eab, 0x002c8fac, 0x002d90ad, 0x002d91ad, 0x002e92ae, 0x002e92af, 0x002f93af, 0x003093b0, 0x003094b0, 0x003094b0, 0x00319bba, 0x0033a5c9, 0x00286c73, 0x00276668, 0x00266467, 0x00266466, 0x00256364, 0x00256264, 0x00256163, 0x00246062, 0x00245f61, 0x00245e60, 0x00277484, 0x002f9dc1, 0x002c99bc, 0x00246b78, 0x00205558, 0x00205254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0009121b, 0x000a131b, 0x000a131b, 0x000b121a, 0x000b1219, 0x000b1219, 0x000a1219, 0x000b131a, 0x000b141a, 0x000c141b, 0x000b151d, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000b171f, 0x000b171f, 0x000b1820, 0x000a1820, 0x000a1820, 0x000a1820, 0x000b1820, 0x000a1820, 0x000a1820, 0x000b1920, 0x000b1920, 0x000c1821, 0x000c1821, 0x000a1620, 0x0008171f, 0x0008181f, 0x0008181f, 0x0008171f, 0x0009171f, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a141d, 0x000a141d, 0x000a141d, 0x000b151e, 0x000b151e, 0x000b151f, 0x000a1720, 0x00091720, 0x000a1820, 0x000a1821, 0x000c1820, 0x000d1720, 0x000d1720, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000b1620, 0x000a1620, 0x00091720, 0x00081820, 0x00081821, 0x00081821, 0x000c1b24, 0x00101c28, 0x00142330, 0x001b2a37, 0x001d2c3a, 0x0020303d, 0x0023323f, 0x00293844, 0x002c3946, 0x002d3a47, 0x002d3846, 0x002a3643, 0x0024303b, 0x001f2b34, 0x00202b36, 0x0025303d, 0x002f3b48, 0x00384452, 0x00384654, 0x00384654, 0x00384554, 0x00384454, 0x00384452, 0x00384452, 0x00384350, 0x00374250, 0x0037404f, 0x0038424f, 0x00384350, 0x00394350, 0x0036404c, 0x00353d4b, 0x0037404c, 0x0038414c, 0x00363f4a, 0x00333c47, 0x00323b45, 0x00333b46, 0x00333b45, 0x00313844, 0x00303642, 0x002f3440, 0x002f3641, 0x00313944, 0x00343c48, 0x00373f4c, 0x00384250, 0x00374351, 0x00384452, 0x00394654, 0x003b4856, 0x003c4857, 0x003c4857, 0x003a4755, 0x00384454, 0x00384453, 0x00394452, 0x00384450, 0x0034404d, 0x00313d4a, 0x00303b47, 0x002f3844, 0x00303743, 0x00303641, 0x00313540, 0x00323640, 0x00333640, 0x0031363e, 0x0030353d, 0x0030343c, 0x0030343c, 0x002f343c, 0x002d313c, 0x002c303b, 0x002c303b, 0x002d323c, 0x0030343f, 0x00333842, 0x00323843, 0x00323843, 0x00313843, 0x00303641, 0x002f3440, 0x00303641, 0x00313843, 0x00313843, 0x00303742, 0x00303742, 0x00303641, 0x002d343f, 0x002d333e, 0x002e343f, 0x002e3440, 0x002f3440, 0x002e3440, 0x002f3440, 0x00303641, 0x00313844, 0x00343c46, 0x00343a46, 0x00313844, 0x00303641, 0x002e3440, 0x002b313c, 0x00282d38, 0x00282d38, 0x00282d37, 0x00282d37, 0x00282d37, 0x00292e38, 0x002a2f39, 0x002b2f3b, 0x002b2f3b, 0x002a303c, 0x002c323d, 0x002c333e, 0x002e343f, 0x002f3541, 0x00303844, 0x00313a48, 0x00353f4e, 0x00384150, 0x00394453, 0x003b4754, 0x003c4855, 0x003c4856, 0x003a4754, 0x003a4856, 0x00394957, 0x00394957, 0x00384855, 0x00374754, 0x00354451, 0x00333f4c, 0x00323c4b, 0x00313a48, 0x00303845, 0x00313946, 0x00303845, 0x00303844, 0x00313944, 0x00333b46, 0x00333b46, 0x00313944, 0x002f3742, 0x002f3742, 0x002f3842, 0x00303944, 0x00303a44, 0x00313b47, 0x00313b48, 0x00333c49, 0x00343d4c, 0x00343e4c, 0x00343e4c, 0x00343d4b, 0x00343c4a, 0x00363e4c, 0x0037404d, 0x0037404d, 0x0036404e, 0x0036404d, 0x00353f4c, 0x00353f4c, 0x0036414e, 0x0036424e, 0x0035414e, 0x0034404d, 0x00343f4c, 0x00343f4c, 0x00333f4c, 0x00323d4b, 0x00303c4a, 0x002e3945, 0x002b3742, 0x002a3440, 0x0027303a, 0x00212a34, 0x00202833, 0x001e2631, 0x001d2530, 0x00202831, 0x00202933, 0x00202b35, 0x00202d37, 0x0024313c, 0x00283440, 0x002d3844, 0x00303a48, 0x00343f4c, 0x003a4453, 0x003e4958, 0x003f4958, 0x003d4655, 0x00353e4d, 0x0026303e, 0x00151d2c, 0x00111a28, 0x00141d2a, 0x0013202c, 0x0010202b, 0x000e1e28, 0x000d1c28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1b26, 0x000c1a24, 0x000c1924, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1a24, 0x000d1b25, 0x000e1c27, 0x000e1c27, 0x00101d28, 0x00101d28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1c28, 0x000c1d26, 0x000c1d25, 0x000c1d25, 0x000c1d25, 0x000c1d25, 0x000c1d25, 0x000c1d25, 0x000c1d25, 0x000c1d25, 0x000c1d25, 0x000c1d25, 0x000d1d25, 0x000e1c25, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000e1c26, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00143036, 0x0015363b, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001c474b, 0x001d4c50, 0x001f5053, 0x00205457, 0x0021575a, 0x0022595c, 0x00245c5f, 0x00245e60, 0x00246062, 0x00256164, 0x00266466, 0x00266568, 0x00266668, 0x00276668, 0x00286769, 0x002b8093, 0x0033a4c9, 0x00286c73, 0x00266568, 0x00266467, 0x00266466, 0x00256364, 0x00256163, 0x00246062, 0x00245e60, 0x00245e60, 0x0027788c, 0x002ea0c5, 0x002c95b7, 0x0023636e, 0x00205457, 0x00205254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081118, 0x00081219, 0x00081219, 0x00091118, 0x000b1219, 0x000b1219, 0x000a1219, 0x000a1219, 0x000a131a, 0x0009141a, 0x000a141c, 0x000a141c, 0x000a151d, 0x000a161e, 0x000b171f, 0x000a1820, 0x000a1820, 0x000a1820, 0x000a1821, 0x000a1821, 0x000b1821, 0x000b1923, 0x000c1923, 0x000b1821, 0x000b1821, 0x000b1821, 0x000a1821, 0x000a1821, 0x000a1720, 0x000a171f, 0x000a171f, 0x000a171f, 0x000a171f, 0x000a171f, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a161e, 0x000a151e, 0x0009141c, 0x0009141c, 0x000b141d, 0x000c141d, 0x000c1520, 0x000b1622, 0x000b1622, 0x00091721, 0x00091721, 0x000a1721, 0x000c1720, 0x000c1720, 0x000a1720, 0x00091720, 0x000a1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000b1720, 0x000a1620, 0x00091720, 0x00091822, 0x00091924, 0x000e1c27, 0x00101e29, 0x0014232f, 0x001a2936, 0x001d2c3a, 0x0020303e, 0x00243341, 0x00283845, 0x002c3b48, 0x00303d4b, 0x00303c4b, 0x002d3847, 0x0026323d, 0x00202c36, 0x001f2b34, 0x00242f3b, 0x002d3947, 0x00374452, 0x00384854, 0x00384654, 0x00374655, 0x00384554, 0x00384453, 0x00384452, 0x00374350, 0x00364250, 0x00384250, 0x003a4451, 0x003b4452, 0x003b4451, 0x003a4450, 0x0038414e, 0x0037404c, 0x0037414c, 0x00343e4b, 0x00333c48, 0x00333b46, 0x00333b46, 0x00333b46, 0x00343a46, 0x00333846, 0x00313844, 0x00313844, 0x00323944, 0x00343c47, 0x00373e48, 0x00363e49, 0x00353e49, 0x00353d48, 0x0038404c, 0x0039434e, 0x003c4551, 0x003a4451, 0x0037414e, 0x0037404e, 0x0036404d, 0x0038404c, 0x00383f4b, 0x00343c48, 0x00313946, 0x00303844, 0x00303844, 0x00303843, 0x00303843, 0x00303742, 0x00303842, 0x00313742, 0x00313740, 0x00303640, 0x0030343f, 0x0030343f, 0x002f343e, 0x002e333c, 0x002e333c, 0x002f343d, 0x002f343e, 0x00303540, 0x00323742, 0x00303843, 0x00313843, 0x00313843, 0x00303743, 0x00303742, 0x00303741, 0x00313841, 0x00303640, 0x00303741, 0x00303641, 0x002f3540, 0x002e343f, 0x002d333f, 0x002f3440, 0x002f3440, 0x002f3440, 0x002f3440, 0x002f3440, 0x002f3540, 0x00313845, 0x00323c48, 0x00343c48, 0x00323a47, 0x00303844, 0x002f3542, 0x002c323f, 0x00272c38, 0x00282c38, 0x00292e38, 0x00282d38, 0x00282d37, 0x00292e38, 0x002c303a, 0x002c303b, 0x002b303c, 0x002a303c, 0x002a303c, 0x002b313c, 0x002d333f, 0x002f3540, 0x002f3743, 0x00303944, 0x00343c49, 0x0037404d, 0x00394250, 0x00384350, 0x00384450, 0x00384450, 0x00384450, 0x00384551, 0x00384752, 0x00384752, 0x00374652, 0x00354450, 0x0033404c, 0x00323e4a, 0x00323c49, 0x00303946, 0x00303844, 0x00303844, 0x00303844, 0x00303845, 0x00333b47, 0x00343c48, 0x00353c4a, 0x00343c49, 0x00323a47, 0x00323947, 0x00323a47, 0x00333b46, 0x00323b46, 0x00333c49, 0x00343d49, 0x00353f4c, 0x00353f4d, 0x00343e4c, 0x00343e4c, 0x00353e4c, 0x00353d4c, 0x00373e4d, 0x00384150, 0x00374350, 0x0036414f, 0x0035404d, 0x00353f4d, 0x0035404e, 0x0035414d, 0x0035414d, 0x0034404c, 0x00333e4a, 0x00323d4a, 0x00323d4a, 0x00333e4a, 0x00333d4a, 0x00313c48, 0x00303944, 0x002c3640, 0x0028333d, 0x00242e38, 0x00212a34, 0x00212934, 0x00202833, 0x001f2732, 0x00202834, 0x00202b35, 0x00212c36, 0x00222e38, 0x0026323c, 0x00283440, 0x002c3845, 0x00303b49, 0x0036404e, 0x003b4553, 0x003d4958, 0x00404a5b, 0x003e4858, 0x00343d4d, 0x00242c3b, 0x00121a26, 0x000e1824, 0x00111d29, 0x0011202b, 0x000f202a, 0x000c1e28, 0x000c1d28, 0x000d1c28, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000c1c27, 0x000d1a26, 0x000d1a25, 0x000d1b25, 0x000d1b24, 0x000d1b24, 0x000c1b24, 0x000c1b24, 0x000c1c26, 0x000d1c27, 0x000d1c28, 0x000f1e28, 0x000f1e29, 0x000f1d28, 0x000f1c28, 0x000f1d28, 0x000d1d28, 0x000d1d28, 0x000d1d28, 0x000d1d28, 0x000d1d28, 0x000c1d28, 0x000c1d28, 0x000c1d27, 0x000c1d26, 0x000c1d26, 0x000c1e27, 0x000c1d26, 0x000c1d26, 0x000c1d26, 0x000c1d26, 0x000c1e26, 0x000c1e26, 0x000c1e26, 0x000c1d26, 0x000c1d26, 0x000e1d26, 0x000d1c26, 0x000d1c26, 0x000d1c26, 0x000d1c26, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0016363b, 0x00183c40, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4c50, 0x001e5053, 0x00205254, 0x00205558, 0x0021585a, 0x00235a5c, 0x00245c5f, 0x00245e60, 0x00246062, 0x00256264, 0x00266466, 0x00266467, 0x00276568, 0x002b8092, 0x0032a4c9, 0x00286c73, 0x00266568, 0x00266467, 0x00266466, 0x00256364, 0x00256163, 0x00245f61, 0x00245e61, 0x00287e94, 0x002ea1c7, 0x002a90af, 0x00215e67, 0x00205356, 0x001f5154, 0x001d4d50, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0017383c, 0x00143338, 0x00143036, 0x00122c32, 0x0010282e, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00061017, 0x00071118, 0x00081018, 0x00081018, 0x000a1018, 0x00091018, 0x00081118, 0x00091119, 0x00091319, 0x00091419, 0x000a141a, 0x000a141a, 0x000a151c, 0x0009161e, 0x0009171f, 0x00081820, 0x00091920, 0x00091820, 0x000b1822, 0x000b1822, 0x000b1822, 0x000c1a24, 0x000c1a24, 0x000b1823, 0x000b1822, 0x000b1822, 0x000a1821, 0x000a1821, 0x000a1720, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000a151e, 0x0009141c, 0x0009141c, 0x000c141d, 0x000c141d, 0x000c1520, 0x000c1622, 0x000c1723, 0x00091722, 0x00091722, 0x00091722, 0x000a1820, 0x000a1820, 0x00081820, 0x00081821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1720, 0x000b1620, 0x00091720, 0x00091822, 0x000a1924, 0x000e1d28, 0x00101f2a, 0x0014242f, 0x00192834, 0x001c2b38, 0x001f2f3d, 0x00243442, 0x00283847, 0x002c3b49, 0x00333e4e, 0x00323e4d, 0x002d3948, 0x0026323e, 0x00202c36, 0x001f2b34, 0x00232f3b, 0x002c3846, 0x00354250, 0x00384854, 0x00374754, 0x00374655, 0x00384554, 0x00384453, 0x00384351, 0x00384350, 0x00384451, 0x00394451, 0x003b4452, 0x003b4452, 0x003c4452, 0x003c4451, 0x003b4350, 0x0038414e, 0x0036404c, 0x00343e4b, 0x00343d4a, 0x00363e4a, 0x00373f4a, 0x00373f4b, 0x0038404c, 0x00383e4b, 0x00353c49, 0x00353c48, 0x00333944, 0x00343a45, 0x00353c46, 0x00363c46, 0x00353c46, 0x00343c45, 0x00384049, 0x003a434d, 0x003b4450, 0x0038424f, 0x0038414e, 0x0038404c, 0x00383e4b, 0x00363d48, 0x00343b47, 0x00343945, 0x00333944, 0x00333844, 0x00323945, 0x00313944, 0x00303843, 0x00303844, 0x00303844, 0x00313842, 0x00303840, 0x0030353f, 0x002d333c, 0x002d323c, 0x002e333c, 0x002e333c, 0x002e333c, 0x002f343d, 0x002f343e, 0x00303540, 0x00313542, 0x00303642, 0x00303742, 0x00313843, 0x00323844, 0x00313843, 0x00313841, 0x00303740, 0x00303640, 0x00303640, 0x00303641, 0x002f3440, 0x002d343f, 0x002c333e, 0x002e3440, 0x002f3440, 0x002f3440, 0x002f3541, 0x00303541, 0x00303642, 0x00303844, 0x00303a46, 0x00313a47, 0x00303845, 0x002f3744, 0x002f3543, 0x002a303d, 0x00242a34, 0x00272c36, 0x00282d38, 0x00282c36, 0x00282d37, 0x00292e38, 0x002c303a, 0x002c303b, 0x002c303c, 0x002a303c, 0x002a303c, 0x0029303c, 0x002c323d, 0x002d3440, 0x002f3742, 0x00303843, 0x00323a44, 0x00343c48, 0x0037404c, 0x0035404c, 0x0035414d, 0x0037434f, 0x0036424e, 0x0037434f, 0x0035434f, 0x0035434e, 0x0034424d, 0x00343f4b, 0x00313d49, 0x00303c48, 0x00313c48, 0x00303a47, 0x00303845, 0x00303845, 0x00323946, 0x00333b48, 0x00343c49, 0x00363e4c, 0x00383f4d, 0x0038404f, 0x0038404e, 0x00373e4c, 0x00363e4b, 0x00363e4a, 0x00353e4a, 0x00353f4b, 0x0037404d, 0x00384250, 0x00384150, 0x0037404f, 0x0037404f, 0x0038404e, 0x00373f4d, 0x0038404f, 0x00394452, 0x003a4553, 0x00374250, 0x00353f4d, 0x0036404e, 0x0035414e, 0x0035424e, 0x0034404c, 0x00343f4a, 0x00313d4a, 0x00313c49, 0x00303c48, 0x00303c48, 0x00313c48, 0x00313b48, 0x00303944, 0x002c3540, 0x0028333d, 0x00242d38, 0x00212b35, 0x00242c38, 0x00232c37, 0x00202a34, 0x00202a34, 0x00202c36, 0x00202c37, 0x00232e38, 0x0028333d, 0x002c3844, 0x002e3a48, 0x00323e4c, 0x00374350, 0x003b4754, 0x003c4857, 0x003f495c, 0x003e485a, 0x00303a49, 0x00202835, 0x000e1620, 0x000c1722, 0x00101c28, 0x0010202b, 0x000d202a, 0x000b1e28, 0x000c1d28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000d1c27, 0x000e1c27, 0x000e1c26, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000d1c26, 0x000d1d26, 0x000d1c27, 0x000d1c28, 0x000e1d28, 0x000f1f29, 0x000f1f29, 0x00101e28, 0x00101d28, 0x000e1d28, 0x000d1d28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000c1f27, 0x000c1f27, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00143036, 0x00153439, 0x0017383c, 0x00183c40, 0x00194044, 0x001b4448, 0x001c474b, 0x001d4b4e, 0x001e4f51, 0x001f5154, 0x00205457, 0x00215659, 0x0022595c, 0x00245c5f, 0x00245e60, 0x00246062, 0x00256264, 0x00266466, 0x00266568, 0x002b8092, 0x0033a4c9, 0x00286c73, 0x00286668, 0x00266568, 0x00276467, 0x00256364, 0x00256163, 0x00246164, 0x0029849c, 0x0030a2c8, 0x00298aa6, 0x00215b60, 0x00205356, 0x001f5154, 0x001d4d50, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183d41, 0x0017383c, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00041017, 0x00061017, 0x00071018, 0x00081018, 0x000a1018, 0x00091018, 0x00081118, 0x00091118, 0x00091318, 0x00091418, 0x000a1419, 0x000a1419, 0x000a151c, 0x0009161e, 0x0009171f, 0x00081820, 0x00091920, 0x000a1920, 0x000b1923, 0x000b1923, 0x000b1923, 0x000b1924, 0x000c1923, 0x000b1822, 0x000b1822, 0x000b1822, 0x000a1821, 0x000a1821, 0x000a1720, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000a161e, 0x0009141d, 0x0009141c, 0x000b141d, 0x000b141d, 0x000c1520, 0x000b1622, 0x000b1722, 0x00091722, 0x00091722, 0x00091722, 0x000a1820, 0x000a1820, 0x00081820, 0x00081821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1720, 0x000b1620, 0x00091720, 0x00091821, 0x000a1924, 0x000e1d27, 0x00101f29, 0x0012222c, 0x00172632, 0x001a2937, 0x00202f3d, 0x00243442, 0x00283846, 0x002c3a49, 0x00333e4e, 0x00333e4e, 0x002d3948, 0x0026313d, 0x00202c37, 0x001e2a34, 0x00222e39, 0x002b3644, 0x0033404d, 0x00374553, 0x00364654, 0x00364655, 0x00374554, 0x00384454, 0x00384453, 0x00394452, 0x003a4553, 0x003b4453, 0x003b4453, 0x003b4453, 0x003c4453, 0x003c4552, 0x003c4451, 0x0039424f, 0x0037404d, 0x0037404e, 0x0037414d, 0x0039424f, 0x003a424f, 0x003b4450, 0x003c4451, 0x003d4450, 0x003c424f, 0x003b414d, 0x00383e4a, 0x00363c48, 0x00373d48, 0x00383e48, 0x00383e48, 0x00353c46, 0x00383e48, 0x003b424d, 0x0038404d, 0x00363e4b, 0x00343f4b, 0x00353d4a, 0x00343c48, 0x00343b46, 0x00343a44, 0x00333a44, 0x00343a44, 0x00333a44, 0x00323944, 0x00313845, 0x00303843, 0x00303844, 0x00303842, 0x002e3640, 0x002e353f, 0x002d343d, 0x002c323c, 0x002c323c, 0x002c333c, 0x002d333c, 0x002d333c, 0x002e333c, 0x002f343e, 0x00303540, 0x00303541, 0x00303641, 0x00303641, 0x00303742, 0x00323844, 0x00313843, 0x00313841, 0x00303740, 0x002f353f, 0x00303640, 0x00303641, 0x002e3440, 0x002c333e, 0x002c333e, 0x002d333f, 0x002e343f, 0x002e343f, 0x002f3540, 0x00303742, 0x00303742, 0x00303843, 0x002e3743, 0x002d3542, 0x002e3643, 0x002f3743, 0x002f3641, 0x0029303b, 0x00252c36, 0x00272c36, 0x00282d37, 0x00282d37, 0x00282d37, 0x00292e38, 0x002a2f39, 0x002b303b, 0x002c303c, 0x002a303c, 0x002a303c, 0x002c323d, 0x002f3440, 0x00303742, 0x00303843, 0x00303843, 0x00303843, 0x00323a45, 0x00333c48, 0x00323d49, 0x0034404c, 0x0036424e, 0x0038434f, 0x0038434f, 0x0036424e, 0x0034404c, 0x00323e4a, 0x00333d49, 0x00323c48, 0x00313b48, 0x00323c48, 0x00323b48, 0x00333b48, 0x00343c48, 0x00363e4a, 0x00383f4c, 0x0038404d, 0x00394150, 0x003b4351, 0x003c4352, 0x003c4352, 0x003a4250, 0x00394150, 0x0039414f, 0x0038404d, 0x0038414e, 0x00394350, 0x003b4453, 0x003b4453, 0x003b4452, 0x003b4452, 0x003c4453, 0x003b4452, 0x003b4452, 0x003b4654, 0x003b4754, 0x00394451, 0x00374150, 0x00384150, 0x00374250, 0x0035414d, 0x00333f4b, 0x00333e4a, 0x00323d4b, 0x00323d4c, 0x002e3947, 0x002d3844, 0x00313b48, 0x00313b48, 0x00303944, 0x002c3640, 0x0028323c, 0x00222c37, 0x00212a34, 0x00242f39, 0x0024303a, 0x00202c36, 0x001f2b34, 0x001f2c35, 0x00202c37, 0x00232e38, 0x0027333d, 0x002c3844, 0x00303c49, 0x0034404e, 0x00394453, 0x003c4855, 0x003d4856, 0x003f485b, 0x003c4557, 0x002c3543, 0x0018202c, 0x000c141c, 0x000c1721, 0x00101d28, 0x0010202b, 0x000d202b, 0x000c1f28, 0x000c1e28, 0x000e1e28, 0x000d1d28, 0x000d1c28, 0x000d1c28, 0x000e1c28, 0x000e1c27, 0x000e1c27, 0x000e1c26, 0x000e1c26, 0x000e1c26, 0x000d1d27, 0x000d1d27, 0x000d1d28, 0x000e1e28, 0x000e1e28, 0x000f1f29, 0x000f1f2a, 0x000f1e28, 0x000f1e28, 0x000e1e28, 0x000d1e28, 0x000d1e28, 0x000d1e28, 0x000d1e28, 0x000d1e28, 0x000d1e28, 0x000d1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e27, 0x000c1f27, 0x000c1f27, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00143036, 0x00143439, 0x0017383c, 0x00183c40, 0x00194044, 0x001b4448, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205457, 0x00215659, 0x0022595c, 0x00245c5f, 0x00245e60, 0x00256163, 0x00266364, 0x00266467, 0x002b8092, 0x0033a4c9, 0x00286d74, 0x00286769, 0x00276668, 0x00266467, 0x00266466, 0x0026656a, 0x002c8ca6, 0x0030a2c8, 0x0029849c, 0x00225a5f, 0x00205457, 0x00205254, 0x001e4f51, 0x001d4b4e, 0x001c484c, 0x001b4448, 0x001a4245, 0x00183d41, 0x00183a3e, 0x00153439, 0x00153338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00040f16, 0x00041017, 0x00061017, 0x00081018, 0x000a1018, 0x000a1018, 0x00091018, 0x000a1118, 0x000a1318, 0x00091418, 0x000a1419, 0x000a1419, 0x000a151c, 0x0009161e, 0x0009171f, 0x00081820, 0x00091920, 0x000b1a21, 0x000b1a24, 0x000c1b24, 0x000b1a24, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1820, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000a161e, 0x000a161e, 0x0009151e, 0x000b151e, 0x000b151e, 0x000b1520, 0x00091622, 0x00091722, 0x00091722, 0x00091722, 0x00091722, 0x000a1820, 0x000a1820, 0x00081820, 0x00081821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1720, 0x000b171f, 0x0009171f, 0x000a1820, 0x000c1923, 0x000e1c25, 0x000f1d28, 0x0010202b, 0x00142430, 0x00182835, 0x001e2d3c, 0x00233241, 0x00283846, 0x002b3948, 0x00303d4c, 0x00323e4d, 0x002d3848, 0x0025303e, 0x00202b37, 0x001d2934, 0x00202c38, 0x00293443, 0x00313f4c, 0x00344250, 0x00334451, 0x00354554, 0x00374554, 0x00394555, 0x003a4554, 0x003a4654, 0x003b4754, 0x003c4654, 0x003c4455, 0x003c4555, 0x003c4655, 0x003c4654, 0x003c4654, 0x003c4552, 0x003b4451, 0x003b4451, 0x00394450, 0x0039434f, 0x003b4450, 0x003d4653, 0x00404855, 0x00414856, 0x00404754, 0x003e4451, 0x003c424d, 0x003a404c, 0x00383f4a, 0x00373d48, 0x00373d48, 0x00373d48, 0x00383f48, 0x0039404b, 0x00363d4a, 0x00343c48, 0x00333c48, 0x00343c48, 0x00323a46, 0x00323a44, 0x00323a43, 0x00303840, 0x00303840, 0x00323843, 0x00313844, 0x00303844, 0x00303744, 0x002f3742, 0x002e3640, 0x002c343d, 0x002c333c, 0x002d333c, 0x002c333c, 0x002d333c, 0x002c323c, 0x002c323c, 0x002c323c, 0x002d323c, 0x0030343e, 0x00313640, 0x00313642, 0x00303641, 0x00303641, 0x00303641, 0x00303742, 0x00303741, 0x002f3740, 0x00313841, 0x00303740, 0x00303740, 0x00303641, 0x002e343f, 0x002c333e, 0x002c323d, 0x002c323d, 0x002c323d, 0x002c323d, 0x002e3440, 0x00303742, 0x00303742, 0x00303641, 0x002c343f, 0x002c343f, 0x002e3641, 0x002f3742, 0x00303742, 0x002d333f, 0x002b313c, 0x00293039, 0x00282f38, 0x00282e37, 0x00292e38, 0x00292e38, 0x002a2f38, 0x002b303b, 0x002c303c, 0x002a303c, 0x002a303c, 0x002a303c, 0x002d333e, 0x002f3641, 0x002f3742, 0x002f3742, 0x002f3742, 0x00303844, 0x00323b45, 0x00323c48, 0x00333e4a, 0x0036414d, 0x0037424e, 0x0037424e, 0x0038414e, 0x0037404c, 0x00343c49, 0x00343d4a, 0x00353e4b, 0x00343e4b, 0x00353e4b, 0x00353e4b, 0x00363e4b, 0x0038404c, 0x003a424f, 0x003a424f, 0x003b4350, 0x003c4453, 0x003e4554, 0x003f4655, 0x003f4655, 0x003d4554, 0x003c4453, 0x003c4452, 0x00394350, 0x0038434f, 0x003a4451, 0x003c4654, 0x003d4755, 0x003d4755, 0x003d4755, 0x003d4755, 0x003d4755, 0x003d4755, 0x003c4855, 0x003b4754, 0x003b4554, 0x003a4452, 0x003a4452, 0x00384350, 0x0035414d, 0x00333e4a, 0x00313c48, 0x00313c4a, 0x00313c49, 0x002e3846, 0x002e3844, 0x00313b48, 0x00313b48, 0x00303944, 0x002c3741, 0x0028323c, 0x00212c36, 0x00212a34, 0x00242f39, 0x0025303b, 0x00212c37, 0x001e2a34, 0x001f2c36, 0x00222e38, 0x00232f38, 0x0026313c, 0x002b3744, 0x00303c49, 0x0034404d, 0x00384451, 0x003c4754, 0x003c4856, 0x003e4858, 0x00374051, 0x00282f3c, 0x00111823, 0x000b111b, 0x000e1823, 0x00101d29, 0x0010202c, 0x000e202b, 0x000c2029, 0x000c2029, 0x000e1f29, 0x000d1f29, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000d1c28, 0x000d1c28, 0x000f1c28, 0x000f1c28, 0x000f1c28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000f1f29, 0x000f1f29, 0x000f202b, 0x000f202b, 0x000f1f2a, 0x000f1f29, 0x000f1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000d1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1f27, 0x000c1f27, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00153338, 0x00143439, 0x0017383c, 0x00183d41, 0x00194044, 0x001b4448, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205457, 0x0021585a, 0x00235a5c, 0x00245d60, 0x00246062, 0x00266364, 0x00266467, 0x002b8092, 0x0033a4c9, 0x00286d74, 0x0028686a, 0x00286769, 0x00266568, 0x00276a70, 0x002e92af, 0x0030a2c6, 0x00287d93, 0x00225b5e, 0x0021585a, 0x00205356, 0x001f5154, 0x001d4c50, 0x001d4a4d, 0x001b4649, 0x001a4245, 0x00183f43, 0x00183c40, 0x0016363b, 0x00143338, 0x00143036, 0x00132c32, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00040f16, 0x00041017, 0x00061017, 0x00081018, 0x000a1018, 0x000a1018, 0x000a1018, 0x000a1118, 0x000a1318, 0x00091418, 0x000a1419, 0x000a1419, 0x000a151c, 0x0009161e, 0x0009171f, 0x00081820, 0x00091920, 0x000b1a21, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1823, 0x000b1823, 0x000b1822, 0x000b1822, 0x000b1820, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000a161e, 0x000a161e, 0x000a161e, 0x000b151e, 0x000b151e, 0x000b1520, 0x000a1622, 0x00091722, 0x00091722, 0x00091722, 0x00091722, 0x000a1820, 0x000a1820, 0x00081820, 0x00081821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1720, 0x000b171f, 0x0009171f, 0x000a1820, 0x000c1923, 0x000d1b24, 0x000e1c26, 0x00101e28, 0x0012212c, 0x00172634, 0x001c2c3a, 0x00213140, 0x00263645, 0x00283847, 0x002d3b4a, 0x00313e4d, 0x002e3949, 0x0026313f, 0x00202c38, 0x001d2935, 0x00202c38, 0x00283441, 0x00303d4b, 0x0032404e, 0x00334350, 0x00344452, 0x00384454, 0x00394454, 0x003a4655, 0x003b4754, 0x003c4855, 0x003c4655, 0x003c4656, 0x003c4657, 0x003c4656, 0x003d4755, 0x003c4654, 0x003d4754, 0x003d4754, 0x003c4554, 0x003c4452, 0x003b4350, 0x003b4350, 0x003c4452, 0x003f4754, 0x003f4754, 0x003f4754, 0x003e4450, 0x003b404c, 0x003a404c, 0x00393f4b, 0x00383f4b, 0x003a414c, 0x003c424d, 0x003b424d, 0x0038404c, 0x00353d49, 0x00343c49, 0x00343c48, 0x00343c48, 0x00323a47, 0x00323a44, 0x00313943, 0x002f3740, 0x002f3640, 0x00313843, 0x00313845, 0x00313845, 0x00303844, 0x002f3742, 0x002d3540, 0x002c323c, 0x002c313b, 0x002c323c, 0x002d313c, 0x002e313c, 0x002d323c, 0x002c323c, 0x002c323c, 0x002d323c, 0x0030343e, 0x00323742, 0x00343844, 0x00303743, 0x00303641, 0x00303541, 0x00303541, 0x002f3540, 0x002e353f, 0x00303740, 0x00303841, 0x00303640, 0x00303541, 0x002e3440, 0x002d333e, 0x002c323d, 0x002b313c, 0x002a303c, 0x002b313c, 0x002d343f, 0x00303642, 0x00303742, 0x002f3541, 0x002c343f, 0x002c333d, 0x002c3540, 0x002f3742, 0x002f3742, 0x002e3540, 0x002c333d, 0x002c323c, 0x002b313b, 0x00293039, 0x00292e38, 0x00292e38, 0x00292e38, 0x002b2f3b, 0x002c303c, 0x0029303c, 0x002a303c, 0x002a303c, 0x002b313c, 0x002c343f, 0x002d3541, 0x002e3641, 0x002f3742, 0x00303843, 0x00333a45, 0x00343c48, 0x00343c48, 0x0036404c, 0x0037404d, 0x0038404d, 0x0038404c, 0x00373f4c, 0x00353d4a, 0x00363e4b, 0x0038404d, 0x0038414e, 0x0038404d, 0x0039414e, 0x0039414e, 0x003a424f, 0x003b4351, 0x003c4452, 0x003d4453, 0x003e4655, 0x00404857, 0x00404858, 0x00404858, 0x00404857, 0x00404857, 0x00404755, 0x003d4654, 0x003c4553, 0x003c4654, 0x003d4755, 0x003e4856, 0x003e4856, 0x003e4856, 0x003e4856, 0x003e4857, 0x003f4857, 0x003e4857, 0x003c4856, 0x003b4754, 0x003c4654, 0x003a4554, 0x00384450, 0x0036414d, 0x00343f4b, 0x00333d4a, 0x00313b49, 0x00303a48, 0x00303a47, 0x00303a47, 0x00313b48, 0x00303a47, 0x002f3944, 0x002c3842, 0x0028323c, 0x00212c36, 0x00232c38, 0x0027313c, 0x0025313c, 0x00212c38, 0x001f2b36, 0x00212e38, 0x0026333d, 0x0025313c, 0x0025323d, 0x00293644, 0x002e3947, 0x00313c4b, 0x00364250, 0x003c4754, 0x003e4957, 0x003c4554, 0x00313848, 0x001f2531, 0x000d141d, 0x00091019, 0x000e1722, 0x00111e2a, 0x0011212c, 0x000f212c, 0x000d202b, 0x000e202b, 0x000f202b, 0x000f202b, 0x0010202b, 0x0010202b, 0x00101f2a, 0x000e1e28, 0x000e1e28, 0x00101d28, 0x00101d28, 0x00101d28, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x0010202a, 0x0010202b, 0x000f202b, 0x000f202b, 0x000f1f2a, 0x000f1f29, 0x00101f2a, 0x000e1f2a, 0x000e1f2a, 0x000e1f2a, 0x000e1f2a, 0x000e1f2a, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000c1e28, 0x000c1e28, 0x000d1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000d1f28, 0x000c1f27, 0x000c1f27, 0x000c1e27, 0x000c1e27, 0x000c1e27, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x000f2229, 0x0012242c, 0x0011242c, 0x00112a30, 0x00132c32, 0x00142e34, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183d41, 0x00194044, 0x001b4448, 0x001c474b, 0x001d4b4e, 0x001e4f51, 0x00205254, 0x00205558, 0x0022595c, 0x00245c5f, 0x00245f61, 0x00256264, 0x00266467, 0x002b8092, 0x0033a5c9, 0x002c7c8a, 0x002b7884, 0x002a7784, 0x00297885, 0x003098b7, 0x0030a0c4, 0x0028788a, 0x00245e60, 0x0022595c, 0x00215659, 0x00205356, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00183d41, 0x0017383c, 0x00143439, 0x00153338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00060f14, 0x00051017, 0x00051017, 0x00081018, 0x00091018, 0x000a1018, 0x000a1018, 0x000a1118, 0x00091319, 0x0008141a, 0x0008141a, 0x0008151b, 0x0008151c, 0x000a161c, 0x000a171d, 0x0009181e, 0x00091820, 0x00091920, 0x00091921, 0x000a1921, 0x000a1920, 0x000b1920, 0x000b1920, 0x000c1923, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000b1822, 0x000b1821, 0x000b1821, 0x000a1820, 0x000a1820, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000b171f, 0x000a161e, 0x000a161e, 0x000b151e, 0x000b151e, 0x000b151f, 0x000b1620, 0x000a1620, 0x00091722, 0x00091722, 0x000b1722, 0x000c1821, 0x000b1821, 0x00091821, 0x00081821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1821, 0x000a1820, 0x00081820, 0x00091922, 0x000c1a24, 0x000d1b24, 0x000e1a24, 0x000e1c24, 0x00101f29, 0x00152431, 0x00192a37, 0x001d303c, 0x00233543, 0x00253845, 0x00293a48, 0x002f3d4c, 0x002c3a48, 0x0024303f, 0x00202c39, 0x001e2a35, 0x00212d39, 0x0027333f, 0x002f3c48, 0x0032414d, 0x00344350, 0x00344351, 0x00364454, 0x00394655, 0x003b4857, 0x003d4958, 0x003e4959, 0x003c4858, 0x003c4656, 0x003b4656, 0x003c4757, 0x003c4756, 0x003c4656, 0x003c4655, 0x003d4654, 0x003d4554, 0x003d4454, 0x003c4453, 0x003c4451, 0x003b4350, 0x003a424e, 0x0038404c, 0x0039414d, 0x0039404d, 0x00383f4c, 0x0039404d, 0x003b414f, 0x003d4451, 0x003d4551, 0x003c4450, 0x003a424e, 0x0038404c, 0x00383e4b, 0x00363e4b, 0x00343c49, 0x00333c48, 0x00333b48, 0x00323a47, 0x00333a45, 0x00313843, 0x00303742, 0x00313843, 0x00323844, 0x00343944, 0x00333844, 0x00313641, 0x002f343f, 0x002c313c, 0x002b303b, 0x002b303a, 0x002c303b, 0x002c303b, 0x002d313b, 0x002d313b, 0x002d323c, 0x002e343e, 0x00303641, 0x00333944, 0x00343a45, 0x00313842, 0x00303540, 0x002f343d, 0x002f343d, 0x002e343d, 0x002f343e, 0x0030343e, 0x0030343f, 0x0030343f, 0x002e343f, 0x002d333f, 0x002c333e, 0x002c323d, 0x002c303c, 0x002a2f3b, 0x0029303a, 0x002c333c, 0x00303640, 0x00303640, 0x002e3440, 0x002d333e, 0x002c323d, 0x002c343f, 0x002e3642, 0x002f3742, 0x002e3642, 0x002f3641, 0x002e3440, 0x002c333d, 0x002a313c, 0x002a303c, 0x00292f3b, 0x00292f3b, 0x00292f3b, 0x00292e39, 0x00292e39, 0x002a2f3b, 0x002b313c, 0x002c323d, 0x002c323d, 0x002d343f, 0x002e3440, 0x00303641, 0x00303843, 0x00343945, 0x00343b46, 0x00333b46, 0x00343d49, 0x00343f4b, 0x0036404c, 0x00363e4b, 0x00353d4a, 0x00353d4a, 0x00383f4c, 0x003a424f, 0x003a424f, 0x003a424f, 0x003b4350, 0x003c4450, 0x003c4453, 0x003c4453, 0x003d4554, 0x003e4755, 0x003f4857, 0x00404958, 0x00404a59, 0x003f4a59, 0x003f4958, 0x0040495a, 0x00404959, 0x003f4858, 0x003d4857, 0x003d4757, 0x003e4858, 0x003f4858, 0x00404a59, 0x00404b5a, 0x003e4a59, 0x003e4959, 0x003f4a5a, 0x003e4959, 0x003d4858, 0x003b4756, 0x003c4856, 0x003c4754, 0x00394452, 0x00364250, 0x0037404e, 0x00353f4b, 0x00323c4a, 0x00323c4a, 0x00313c49, 0x00323c48, 0x00313b48, 0x00303a46, 0x002e3844, 0x002c3541, 0x0028313c, 0x00222c37, 0x0024303b, 0x00293742, 0x0024323d, 0x00202e3a, 0x00202d38, 0x0023303c, 0x00273542, 0x00263441, 0x00253340, 0x00283644, 0x002c3848, 0x00313d4b, 0x00384350, 0x003c4855, 0x003e4957, 0x0038414f, 0x00272d3c, 0x00151c28, 0x000b111b, 0x000a101a, 0x000f1823, 0x00111f2a, 0x0011212c, 0x000f222c, 0x000e212c, 0x000e212c, 0x000f202c, 0x000f202c, 0x0010202b, 0x000f2029, 0x000e1f28, 0x000e1f28, 0x000e1f28, 0x000f1f28, 0x000f1f28, 0x000f1f28, 0x000e1f28, 0x000e1f28, 0x000f202a, 0x0010202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000e202b, 0x000e202b, 0x000e202b, 0x000e202b, 0x000e202b, 0x000f202b, 0x000f202b, 0x000e1f2a, 0x000e1f29, 0x000e1f2a, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000e1e2a, 0x000d1d29, 0x000d1d29, 0x000d1d29, 0x000d1d29, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1c25, 0x000b1c25, 0x000b1c25, 0x000b1c25, 0x000c1c25, 0x000c1b24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00132c32, 0x00143036, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183f43, 0x001a4245, 0x001b4649, 0x001d4a4d, 0x001d4d50, 0x00205154, 0x00205457, 0x0022585b, 0x00245c5e, 0x00245f61, 0x00256264, 0x00266467, 0x002b7f91, 0x0034a6cb, 0x0033a6c9, 0x0033a5c9, 0x0033a4c9, 0x0033a4c9, 0x00309fc0, 0x00287482, 0x00246062, 0x00245d60, 0x0022595c, 0x00215659, 0x001f5254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0017383c, 0x00153439, 0x00143036, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00060e14, 0x00061017, 0x00051017, 0x00080f17, 0x00090f17, 0x00090f17, 0x000a1018, 0x000a1018, 0x00091319, 0x0008141a, 0x0008141a, 0x0008151b, 0x0008151c, 0x0009161c, 0x000a161c, 0x000a171d, 0x00091820, 0x00091920, 0x00091920, 0x00091920, 0x00091920, 0x000b1920, 0x000b1a21, 0x000c1a23, 0x000d1b24, 0x000d1b24, 0x000c1924, 0x000c1924, 0x000b1823, 0x000b1822, 0x000b1822, 0x000a1821, 0x000a1821, 0x000b1821, 0x000c1821, 0x000c1821, 0x000c1820, 0x000c1820, 0x000b171f, 0x000a161e, 0x000a161e, 0x000b151e, 0x000b151e, 0x000b151f, 0x000b1620, 0x000b1620, 0x00091722, 0x00091722, 0x000b1722, 0x000c1821, 0x000b1821, 0x00091821, 0x00081821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1821, 0x00091821, 0x00081821, 0x000a1923, 0x000c1b24, 0x000d1b24, 0x000d1924, 0x000d1b23, 0x000e1d26, 0x0014232e, 0x00172934, 0x00192e38, 0x00203542, 0x00223744, 0x00253846, 0x002c3c4b, 0x002c3a48, 0x00243240, 0x00202e3b, 0x001f2c38, 0x00222f3b, 0x0026343f, 0x002c3b46, 0x0032414c, 0x00344350, 0x00344452, 0x00364454, 0x00394756, 0x003c4958, 0x003e4b5a, 0x00404b5b, 0x003e485a, 0x003d4858, 0x003c4858, 0x003c4857, 0x003d4858, 0x003d4757, 0x003c4655, 0x003c4654, 0x003d4654, 0x003f4755, 0x003f4755, 0x00404854, 0x003f4754, 0x003c4451, 0x0039424f, 0x0038404d, 0x0038404d, 0x0038404d, 0x00394250, 0x003c4453, 0x003d4654, 0x003b4451, 0x0038424f, 0x0038404d, 0x0038404c, 0x00383f4c, 0x00383e4c, 0x00353c49, 0x00333b48, 0x00323a47, 0x00333b48, 0x00343a47, 0x00333944, 0x00313843, 0x00313843, 0x00323844, 0x00323944, 0x00333844, 0x00313640, 0x002f343e, 0x002c313b, 0x002b313b, 0x002c323c, 0x002e333c, 0x002e323c, 0x002e303b, 0x002e303b, 0x002f333d, 0x00303640, 0x00313843, 0x00343a45, 0x00343a45, 0x00313842, 0x002e343d, 0x002c303b, 0x002c303b, 0x002c303b, 0x002c303b, 0x002c303b, 0x002c303b, 0x002c303b, 0x002c303c, 0x002c323d, 0x002c333e, 0x002c323d, 0x002c303c, 0x002a2f3b, 0x00282e38, 0x00293039, 0x002b313b, 0x002c323b, 0x002b313c, 0x002b303c, 0x002a303c, 0x002a313d, 0x002d3340, 0x00303643, 0x00303844, 0x00303844, 0x002f3742, 0x002d3540, 0x002c3440, 0x002b333e, 0x002b323d, 0x002b313c, 0x002a2f3b, 0x00292e38, 0x00282d37, 0x002a2f38, 0x002c323c, 0x002c333e, 0x002c333e, 0x002c323d, 0x002e343f, 0x00303541, 0x00303742, 0x00333945, 0x00333b46, 0x00323a45, 0x00323c48, 0x00333e4a, 0x00343e4a, 0x00343e4a, 0x00343e4b, 0x00363f4c, 0x0038404d, 0x0039424f, 0x0039434f, 0x003a4450, 0x003c4551, 0x003d4653, 0x003e4756, 0x003d4755, 0x003d4755, 0x00404a58, 0x00434c5b, 0x00414b58, 0x003f4957, 0x003d4857, 0x003d4958, 0x00404b5b, 0x00414c5c, 0x00404b5b, 0x003f4a5a, 0x003e4959, 0x003e4959, 0x00404b5a, 0x00414e5d, 0x00414f5e, 0x003f4c5c, 0x003e4b5c, 0x003e4b5c, 0x003d495b, 0x003d4858, 0x003c4858, 0x003e4958, 0x003c4755, 0x00394453, 0x00374250, 0x0037414f, 0x00353f4c, 0x00323c4a, 0x00323c4a, 0x00333c4a, 0x00323c48, 0x00303b47, 0x00303945, 0x002d3743, 0x002b3441, 0x0027313c, 0x00212c37, 0x0025323d, 0x002a3944, 0x0023323d, 0x0022313c, 0x0021303c, 0x0023323d, 0x00273643, 0x00263643, 0x00273644, 0x00293845, 0x002e3b49, 0x0034404e, 0x00394553, 0x003c4855, 0x003a4553, 0x002f3844, 0x001b212d, 0x000d141e, 0x00080f18, 0x000b111c, 0x00101926, 0x0012202b, 0x0011212c, 0x000f222c, 0x000f222c, 0x000f222c, 0x0010232d, 0x0010222c, 0x000f212c, 0x000f2028, 0x000e2028, 0x000e2028, 0x000e1f28, 0x000f1f26, 0x000f1f26, 0x000f1f26, 0x000e1f28, 0x000e1f28, 0x000f202a, 0x0010202c, 0x0010202c, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000f202b, 0x000f202b, 0x000e1f2a, 0x000e1f29, 0x000e1f2a, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f1e29, 0x000e1d28, 0x000d1d28, 0x000c1e28, 0x000c1e28, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000b1c25, 0x000b1c25, 0x000b1c25, 0x000b1c25, 0x000c1c25, 0x000c1a24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0012242c, 0x0010282e, 0x00132c32, 0x00142e34, 0x00153338, 0x0015363b, 0x00183a3e, 0x00183d41, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4c50, 0x001e5053, 0x00205457, 0x0021585a, 0x00245c5e, 0x00245e60, 0x00256163, 0x00266466, 0x00286e76, 0x002c8194, 0x002c8396, 0x002c8497, 0x002c8497, 0x002c8497, 0x0028707b, 0x00266364, 0x00246062, 0x00245d60, 0x0022595c, 0x00215659, 0x001f5254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0017383c, 0x00153439, 0x00143036, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00080e14, 0x00071017, 0x00071017, 0x00080f17, 0x00080f17, 0x00080f17, 0x00091018, 0x00091018, 0x00091319, 0x0008141a, 0x0008141a, 0x0008151b, 0x0008151c, 0x000a151c, 0x000b151c, 0x000b171d, 0x000b1820, 0x000b1920, 0x000b1920, 0x000a1920, 0x000a1920, 0x000b1a21, 0x000b1a21, 0x000c1a23, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1a24, 0x000c1923, 0x000b1823, 0x000b1822, 0x000a1821, 0x000a1821, 0x000b1821, 0x000b1821, 0x000c1821, 0x000c1820, 0x000c1820, 0x000b171f, 0x000a161e, 0x000a161e, 0x000b151e, 0x000b151e, 0x000b151f, 0x000b1620, 0x000b1620, 0x000a1721, 0x000a1821, 0x000b1721, 0x000c1821, 0x000b1821, 0x00091821, 0x00091821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000b1821, 0x00091821, 0x00091922, 0x000a1923, 0x000b1a24, 0x000c1a24, 0x000c1923, 0x000c1a22, 0x000e1d26, 0x0013222c, 0x00162833, 0x00182c38, 0x00203441, 0x00223644, 0x00243745, 0x00293a49, 0x002a3948, 0x00243440, 0x0022303c, 0x00212f3b, 0x00212f3b, 0x0026343f, 0x002b3945, 0x0030404b, 0x00344350, 0x00344453, 0x00364554, 0x00384655, 0x003b4858, 0x003c4958, 0x003e4959, 0x003e495b, 0x003f4c5c, 0x003e4b5a, 0x003c4958, 0x003e4958, 0x003e4858, 0x003c4755, 0x003c4654, 0x003c4655, 0x003f4858, 0x00404858, 0x00434a59, 0x00434a59, 0x00414957, 0x003f4754, 0x003c4452, 0x003c4452, 0x003b4351, 0x003a4451, 0x003c4554, 0x003b4453, 0x0038424f, 0x0038404d, 0x0037404c, 0x00373e4b, 0x00373e4b, 0x00373e4a, 0x00353d49, 0x00343c48, 0x00343c48, 0x00343b47, 0x00343a47, 0x00343945, 0x00313843, 0x00313843, 0x00323844, 0x00323844, 0x00333843, 0x00303540, 0x002e333d, 0x002d313c, 0x002c323c, 0x002e343d, 0x002f343d, 0x0030333d, 0x002f313c, 0x0030333d, 0x00313540, 0x00323842, 0x00333945, 0x00343946, 0x00323944, 0x002f3740, 0x002c323c, 0x002a2f39, 0x002a2e38, 0x00292e38, 0x002a2f38, 0x002a2f39, 0x002c303a, 0x002c303b, 0x002c303c, 0x002c323d, 0x002c323d, 0x002c313d, 0x002c303c, 0x00292e39, 0x00262c36, 0x00272d37, 0x00272d37, 0x00272d37, 0x00282e38, 0x00282e39, 0x00282e39, 0x00292f3b, 0x002b313c, 0x002f3440, 0x00303843, 0x00313944, 0x00313944, 0x00303843, 0x00303843, 0x002f3742, 0x002e3641, 0x002e3540, 0x002e333f, 0x002d313c, 0x002b2f39, 0x002b303a, 0x002c323c, 0x002d343f, 0x002c333e, 0x002c333e, 0x002e3440, 0x00303541, 0x00303742, 0x00333945, 0x00333a45, 0x00323a45, 0x00303a46, 0x00303a47, 0x00333d49, 0x0036404c, 0x0038414e, 0x0038424f, 0x0039424e, 0x0039424f, 0x003a4450, 0x003b4451, 0x003c4552, 0x003c4653, 0x003d4755, 0x003d4755, 0x003d4755, 0x00414b59, 0x00454f5c, 0x00424c5a, 0x003e4856, 0x003c4856, 0x003e4958, 0x00424d5d, 0x0044505f, 0x00444f5f, 0x00434e5d, 0x00414c5c, 0x00414c5c, 0x00424e5d, 0x0043505f, 0x00435060, 0x00424f5f, 0x00424f60, 0x00404d5e, 0x00404d5e, 0x00404d5e, 0x00404c5c, 0x003f4b5b, 0x003c4858, 0x00394454, 0x00364250, 0x00374150, 0x00353f4c, 0x00323c4a, 0x00333c4b, 0x00333d4a, 0x00323c48, 0x00303a47, 0x002e3844, 0x002c3642, 0x002a3440, 0x0027313c, 0x00242e39, 0x0027343f, 0x00273640, 0x0021303c, 0x0022313c, 0x0023323d, 0x0024333f, 0x00273643, 0x00283844, 0x002b3a47, 0x002d3c49, 0x00323f4c, 0x00384451, 0x003b4754, 0x003a4553, 0x00313c4a, 0x00222c37, 0x00111823, 0x000a101a, 0x00091018, 0x000c131e, 0x00111b27, 0x0013202c, 0x0012222d, 0x0010232d, 0x0010242d, 0x0010232d, 0x0010232e, 0x0010232d, 0x000f222c, 0x000e202b, 0x000e202a, 0x000e202a, 0x000e202a, 0x000f2028, 0x000f2028, 0x000f2028, 0x000e2029, 0x000e202a, 0x000f202b, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e202b, 0x000e202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f1f29, 0x000e1e28, 0x000d1e28, 0x000d1e28, 0x000d1e28, 0x000d1d27, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1c26, 0x000b1c25, 0x000b1c25, 0x000a1c24, 0x000a1c24, 0x000b1b24, 0x000c1a24, 0x000d1924, 0x000d1924, 0x000d1924, 0x000d1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f2229, 0x0012242c, 0x0012242c, 0x0010282e, 0x00132c32, 0x00132e34, 0x00153338, 0x00153439, 0x0017383c, 0x00183d41, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4c50, 0x001e5053, 0x00205356, 0x0022585a, 0x00235a5c, 0x00245e60, 0x00256163, 0x0028737f, 0x00309ab8, 0x00319dbe, 0x00319ebe, 0x00319dbd, 0x00319cbc, 0x00309bbb, 0x0028737e, 0x00256364, 0x00246062, 0x00245d60, 0x00235a5c, 0x00215659, 0x00205356, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00173c40, 0x0017383c, 0x00143439, 0x00153338, 0x00142e34, 0x00132c32, 0x0010282e, 0x0012242c, 0x00102229, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00080e14, 0x00080f17, 0x00080f17, 0x00080f16, 0x00080f16, 0x00080f16, 0x00091018, 0x000a1018, 0x000b1219, 0x0009141a, 0x0009141a, 0x0008151b, 0x0009151c, 0x000b151c, 0x000c151c, 0x000c171d, 0x000c1820, 0x000c1820, 0x000c1820, 0x000b1920, 0x000b1920, 0x000b1a21, 0x000c1a21, 0x000c1a22, 0x000d1b23, 0x000d1b23, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1924, 0x000b1823, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000c1822, 0x000c1822, 0x000b1720, 0x000a161e, 0x000a161e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1822, 0x000a1923, 0x000a1923, 0x000b1a24, 0x000b1a24, 0x000c1924, 0x000c1822, 0x000c1a22, 0x000f1c26, 0x0011202c, 0x00142630, 0x00182c37, 0x001e3340, 0x00223744, 0x00243845, 0x00283847, 0x00283744, 0x0024333f, 0x0024323d, 0x0023303c, 0x0023303c, 0x0025333e, 0x002a3944, 0x002f3e49, 0x0033424f, 0x00344453, 0x00364454, 0x00384655, 0x00394756, 0x00394656, 0x003c4857, 0x003f4a5c, 0x00404c5c, 0x003f4c5c, 0x003d4b5a, 0x003e4b5a, 0x003f4a5a, 0x003d4857, 0x003d4755, 0x003d4756, 0x003d4757, 0x003f4858, 0x00434c5a, 0x00444c5b, 0x00434a59, 0x00404857, 0x00404855, 0x003f4655, 0x003e4654, 0x003d4754, 0x003c4654, 0x003a4452, 0x0037404d, 0x00373f4c, 0x00363e4b, 0x00373e4b, 0x00363d49, 0x00363d48, 0x00353d48, 0x00343c48, 0x00343c48, 0x00343c47, 0x00343b47, 0x00343945, 0x00323844, 0x00313843, 0x00313843, 0x00313844, 0x00313642, 0x00303540, 0x002f343e, 0x002e333d, 0x002d333c, 0x0030343e, 0x0030343e, 0x0030343e, 0x0030343f, 0x00313540, 0x00343844, 0x00353c48, 0x00353b49, 0x00333947, 0x00313844, 0x002e343f, 0x002c303b, 0x00292e38, 0x00282d36, 0x00282c34, 0x00282d36, 0x002a2f39, 0x002c303b, 0x002d323c, 0x002d323d, 0x002c323d, 0x002c323d, 0x002c313c, 0x002b2f3a, 0x00282c37, 0x00262b35, 0x00272c36, 0x00272c36, 0x00272c35, 0x00262b35, 0x00262c37, 0x00282d39, 0x00292f3a, 0x002a303c, 0x002e3440, 0x00313844, 0x00343c47, 0x00353d48, 0x00343c48, 0x00343c48, 0x00333b45, 0x00313944, 0x00313844, 0x00303743, 0x00303540, 0x002e333d, 0x002d343d, 0x002e343e, 0x002d343f, 0x002d343f, 0x002d343f, 0x002f3440, 0x00303540, 0x00303742, 0x00333944, 0x00343a45, 0x00343a45, 0x00323a46, 0x00313b47, 0x00343d4a, 0x0038404d, 0x003b4350, 0x003c4450, 0x003c4450, 0x003b4450, 0x003a4450, 0x003b4451, 0x003c4552, 0x003c4551, 0x003c4654, 0x003c4554, 0x003c4654, 0x00404a58, 0x00444d5c, 0x00424c5a, 0x003f4958, 0x003f4b58, 0x00404c5b, 0x00434e5e, 0x00455060, 0x00455060, 0x00455060, 0x00455060, 0x00455060, 0x00455160, 0x00445261, 0x00445160, 0x00445262, 0x00455263, 0x00445062, 0x00435061, 0x00445062, 0x00424f60, 0x00404c5c, 0x003c4858, 0x00394454, 0x00364251, 0x00354150, 0x00333f4d, 0x00313c4a, 0x00323c4b, 0x00343d4a, 0x00323c48, 0x00303a47, 0x002e3844, 0x002c3542, 0x00293340, 0x0028323e, 0x0027313d, 0x00283440, 0x0024333e, 0x00202f3a, 0x0024333e, 0x00243440, 0x00253541, 0x00283744, 0x002c3a48, 0x002f3e4c, 0x0032404e, 0x00364450, 0x00394554, 0x00384654, 0x00313d4b, 0x00242f3c, 0x00151e2a, 0x000b121d, 0x00091019, 0x00091019, 0x000d1520, 0x00141e2a, 0x0015222d, 0x00142430, 0x00122530, 0x00122530, 0x0011242f, 0x0010232f, 0x0010232f, 0x000f222e, 0x000e212c, 0x000e212c, 0x000e202c, 0x000d202c, 0x000e202b, 0x000f202a, 0x000f202b, 0x000e212c, 0x000e212c, 0x000f202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f202b, 0x000f202b, 0x000f202c, 0x000f212c, 0x000f222c, 0x000f222c, 0x000f222c, 0x000f222c, 0x000e212c, 0x000e212c, 0x000f212c, 0x0010212c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f202b, 0x000e1f2a, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1e27, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1c25, 0x000b1c25, 0x000a1c24, 0x000a1c24, 0x00091b24, 0x000a1b24, 0x000c1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f2229, 0x0012242c, 0x0012242c, 0x0010282e, 0x00132c32, 0x00142e34, 0x00153338, 0x0015363b, 0x00183a3e, 0x00183d41, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4c50, 0x001f5053, 0x00205457, 0x0021585a, 0x00235a5c, 0x00245e60, 0x00287686, 0x0030a0c2, 0x00319ec0, 0x002d8ba3, 0x002e8ca3, 0x002f8ca4, 0x003093ae, 0x0033a5ca, 0x00297886, 0x00266466, 0x00256163, 0x00245e60, 0x00235a5c, 0x0021585a, 0x00205457, 0x001f5053, 0x001d4c50, 0x001c484c, 0x001b4649, 0x001a4245, 0x00183f43, 0x00183c40, 0x0016363b, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00080e14, 0x00080f17, 0x00080f17, 0x00080f15, 0x00080f15, 0x00080f16, 0x00091018, 0x000a1018, 0x000b1219, 0x0009141a, 0x0009141a, 0x0008151b, 0x0009151b, 0x000b151c, 0x000c151c, 0x000c161d, 0x000c1820, 0x000c1820, 0x000c1820, 0x000b1820, 0x000b1920, 0x000c1921, 0x000c1a21, 0x000c1a22, 0x000d1b23, 0x000d1b23, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000b1822, 0x000c1822, 0x000c1822, 0x000b1720, 0x000a161e, 0x000a161e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c1821, 0x000c1822, 0x000c1821, 0x000c1821, 0x000c1821, 0x000a1821, 0x000a1821, 0x000a1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1821, 0x000c1822, 0x000b1924, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000b1924, 0x000c1822, 0x000c1a24, 0x000f1d27, 0x0011202b, 0x00142430, 0x00172a35, 0x001c303e, 0x00213644, 0x00243846, 0x00273847, 0x00273644, 0x00243440, 0x00263440, 0x0024323d, 0x0023303c, 0x0026323e, 0x00293742, 0x002f3c47, 0x0034404d, 0x00374351, 0x00374454, 0x00384655, 0x00394755, 0x00384555, 0x003b4757, 0x00404b5c, 0x00414d5d, 0x00404d5c, 0x00404c5c, 0x003f4c5c, 0x00404c5c, 0x00404c5b, 0x00424c5b, 0x003f4958, 0x003d4857, 0x003e4857, 0x00424b59, 0x00444c5b, 0x00424a59, 0x00414958, 0x00424a59, 0x00424a5a, 0x00414958, 0x00404958, 0x00404957, 0x003c4454, 0x0038404e, 0x00363e4b, 0x00373e4b, 0x00373f4c, 0x00383e4a, 0x00373e49, 0x00363e49, 0x00353d48, 0x00343c48, 0x00343c48, 0x00343b47, 0x00343a45, 0x00323844, 0x00313843, 0x00313843, 0x00313843, 0x00323743, 0x00313541, 0x00303540, 0x00303540, 0x00303640, 0x00323741, 0x00323741, 0x00333843, 0x00343a45, 0x00353c48, 0x0038404c, 0x003a4350, 0x0038404e, 0x00333948, 0x00303644, 0x002c323d, 0x002b3039, 0x00282c36, 0x00262b34, 0x00262a33, 0x00282c34, 0x002a2e38, 0x002c303b, 0x002e323c, 0x002e333e, 0x002c333e, 0x002c333e, 0x002c313d, 0x002c2f3b, 0x00292c37, 0x00252934, 0x00262a34, 0x00262b34, 0x00262a34, 0x00242833, 0x00252a35, 0x00282c38, 0x00282e3a, 0x002b303c, 0x002e343f, 0x00313844, 0x00363d49, 0x0038404c, 0x0038414d, 0x0038414c, 0x0037404c, 0x0037404c, 0x00363d4b, 0x00343b48, 0x00333846, 0x00313742, 0x00303640, 0x002f3540, 0x002e3440, 0x002e343f, 0x002e343f, 0x002f3440, 0x002f3440, 0x00303541, 0x00333844, 0x00343b46, 0x00353c47, 0x00343b48, 0x00343c48, 0x00363d4a, 0x0038404d, 0x003b4350, 0x003c4450, 0x003c4451, 0x003c4450, 0x003b4450, 0x003b4451, 0x003c4551, 0x003b4451, 0x003a4451, 0x003b4453, 0x003c4654, 0x003f4857, 0x00404a59, 0x0040495a, 0x00414b5c, 0x00444f5f, 0x00445060, 0x00445061, 0x00475363, 0x00485363, 0x00485364, 0x00485364, 0x00485464, 0x00485465, 0x00485465, 0x00485465, 0x00485566, 0x00485567, 0x00475465, 0x00445264, 0x00445062, 0x00424e60, 0x00404c5d, 0x003c4858, 0x00394454, 0x00364251, 0x00354150, 0x00333f4d, 0x00313c4a, 0x00323c4b, 0x00343e4a, 0x00323c48, 0x00303a47, 0x00303945, 0x002e3844, 0x002c3541, 0x0028323f, 0x0028333f, 0x00293440, 0x0025333f, 0x001e2d38, 0x0024343e, 0x00283742, 0x00283744, 0x002a3947, 0x002f3e4c, 0x0032414f, 0x00354450, 0x00384553, 0x00374350, 0x0033404d, 0x00283441, 0x00182330, 0x000f1824, 0x0009111e, 0x000a101b, 0x000c121c, 0x00101a24, 0x0016212c, 0x00162430, 0x00142530, 0x00132630, 0x00122630, 0x00122430, 0x0010232f, 0x0010232f, 0x000f222e, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000f202c, 0x000f202b, 0x000f202c, 0x000f222c, 0x000f222c, 0x0010212c, 0x0010212c, 0x0010212c, 0x0010212c, 0x0010212c, 0x0010212c, 0x0010212c, 0x0010212c, 0x000f222c, 0x000f222c, 0x000f222c, 0x000f222c, 0x000f222c, 0x000e212c, 0x000e212c, 0x000f212c, 0x0010222c, 0x0010212c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f202b, 0x000e1f2b, 0x000e1f2a, 0x000e1f2a, 0x000e1f2a, 0x000e1f2a, 0x000e1e27, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1c25, 0x000c1c25, 0x000b1c24, 0x000a1b24, 0x000a1b24, 0x000a1a24, 0x000c1924, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000e1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0013282e, 0x00102a30, 0x00132c32, 0x00153036, 0x00143439, 0x0016363b, 0x00183c40, 0x00183f43, 0x001a4347, 0x001b4649, 0x001d4a4d, 0x001d4d50, 0x001f5154, 0x00205457, 0x0021585a, 0x00235b5e, 0x00287a8e, 0x0030a0c5, 0x003099b9, 0x00287079, 0x00276668, 0x00286769, 0x00286769, 0x002a7784, 0x0033a4c8, 0x00297886, 0x00266466, 0x00256163, 0x00245e60, 0x00245c5e, 0x0022585b, 0x00205558, 0x00205254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x001a4245, 0x00183d41, 0x00183a3e, 0x0015363b, 0x00143338, 0x00142e34, 0x00132c32, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00080f14, 0x00071015, 0x00080f15, 0x00090f15, 0x00090f15, 0x00090f16, 0x000a1018, 0x000a1018, 0x000a1219, 0x0009141a, 0x0009141a, 0x0008151b, 0x0008151b, 0x0009151c, 0x000a161c, 0x000b171d, 0x000a1820, 0x000a1820, 0x000b1820, 0x000b1821, 0x000b1822, 0x000c1923, 0x000c1923, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000b1823, 0x000b1823, 0x000c1821, 0x000b1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000b1720, 0x000b171f, 0x000b171f, 0x000b161e, 0x000b161e, 0x000c1720, 0x000d1720, 0x000d1720, 0x000c1821, 0x000c1822, 0x000c1821, 0x000b1821, 0x000b1821, 0x00091821, 0x00091822, 0x000a1823, 0x000c1923, 0x000c1923, 0x000c1823, 0x000c1823, 0x000c1823, 0x000b1924, 0x000b1924, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000b1a24, 0x000c1c24, 0x000f1e28, 0x0013222d, 0x00152530, 0x00172834, 0x001c2e3b, 0x00203440, 0x00243744, 0x00273846, 0x00283745, 0x00253442, 0x00273542, 0x0024323d, 0x00232f3b, 0x0026323e, 0x002a3642, 0x002f3946, 0x00343e4c, 0x00364150, 0x00384452, 0x00384654, 0x00394754, 0x00384654, 0x003b4856, 0x00414c5c, 0x00435060, 0x00425060, 0x00414f60, 0x00414f60, 0x00435061, 0x00445060, 0x00445060, 0x00414d5c, 0x003f4b58, 0x003e4956, 0x00404b58, 0x00424c58, 0x00414a58, 0x00414958, 0x00424a58, 0x00424a59, 0x00414b59, 0x00404b58, 0x003f4857, 0x003c4554, 0x003a4350, 0x0039424d, 0x0039414d, 0x0039404c, 0x0039404c, 0x0039404c, 0x0038404c, 0x00363e49, 0x00353d48, 0x00353c48, 0x00353c47, 0x00343b46, 0x00333944, 0x00323844, 0x00323843, 0x00323842, 0x00313741, 0x00313741, 0x00313740, 0x00313741, 0x00313843, 0x00343a45, 0x00363d48, 0x0038404c, 0x003a424f, 0x003a4450, 0x003a4550, 0x003c4551, 0x0038414e, 0x00333b48, 0x00313744, 0x002d323e, 0x00292e38, 0x00272b35, 0x00272a34, 0x00272a34, 0x00282b34, 0x002b2d38, 0x002d303b, 0x002f313c, 0x0030333f, 0x002d333e, 0x002c323e, 0x002d303c, 0x002b2e39, 0x00282b35, 0x00252833, 0x00262934, 0x00262934, 0x00252934, 0x00242832, 0x00242834, 0x00272b35, 0x00282c37, 0x002a3039, 0x002e343d, 0x00313843, 0x00343c48, 0x0035404c, 0x0037414e, 0x00384450, 0x00394452, 0x003b4453, 0x003a4351, 0x0038404f, 0x00353c4c, 0x00343b48, 0x00323845, 0x00303743, 0x002f3542, 0x002f3440, 0x002e343f, 0x002f3440, 0x002e3440, 0x002f3540, 0x00313742, 0x00343944, 0x00353b46, 0x00353c48, 0x00343c48, 0x00363d4a, 0x0038404d, 0x003a424f, 0x003c4450, 0x003c4451, 0x003c4450, 0x003c4450, 0x003c4551, 0x003d4653, 0x003e4653, 0x003d4554, 0x003d4655, 0x003e4856, 0x003f4957, 0x0040495a, 0x00414b5c, 0x00444e60, 0x00485363, 0x00475363, 0x00465363, 0x00485464, 0x00485465, 0x00495568, 0x00495568, 0x00485668, 0x00485769, 0x00485768, 0x00485668, 0x00485566, 0x00485464, 0x00475464, 0x00455364, 0x00425060, 0x003f4b5c, 0x003f4a5b, 0x003c4857, 0x00394454, 0x00374250, 0x0036404f, 0x00343d4c, 0x00313b49, 0x00323c4a, 0x00333d4a, 0x00313c48, 0x00303a46, 0x00303945, 0x002f3945, 0x002d3744, 0x00293340, 0x0029333f, 0x00283440, 0x0025343f, 0x001f2e39, 0x0024343f, 0x00293844, 0x00283845, 0x002b3b48, 0x0030404c, 0x00334450, 0x00354450, 0x00374350, 0x00313d4b, 0x002a3644, 0x001d2834, 0x00101a26, 0x000b1520, 0x0008111c, 0x00081018, 0x000a131b, 0x00101c25, 0x0014222d, 0x00142430, 0x00122530, 0x00102630, 0x00102631, 0x00102530, 0x00112430, 0x0010232f, 0x0010232f, 0x000f222e, 0x000f222e, 0x000f222c, 0x000e212c, 0x000f212b, 0x0010202a, 0x0010212c, 0x000f222d, 0x000f222d, 0x000f222d, 0x0010222d, 0x0010222d, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x000f222c, 0x0010232e, 0x0010232e, 0x0010232e, 0x0010232e, 0x000f222e, 0x000e212c, 0x000e212c, 0x000f212c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f202b, 0x000f202b, 0x000e202b, 0x000e1f2a, 0x000e1f28, 0x000d1f28, 0x000c1e27, 0x000c1e27, 0x000c1d26, 0x000c1d26, 0x000c1c26, 0x000c1c24, 0x000c1c24, 0x000c1c24, 0x000b1a23, 0x000b1a23, 0x000c1923, 0x000c1924, 0x000c1924, 0x000d1924, 0x000d1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00153338, 0x0015363b, 0x00183a3e, 0x00183d41, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4b4e, 0x001e4f51, 0x00205254, 0x00205558, 0x0022595c, 0x00287f96, 0x0030a2c8, 0x002c94b3, 0x00266970, 0x00266466, 0x00266467, 0x00276668, 0x00276668, 0x00297684, 0x0032a4c8, 0x00297886, 0x00266466, 0x00256264, 0x00245f61, 0x00245c5f, 0x00235a5c, 0x0021585a, 0x00205457, 0x001f5154, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00183d41, 0x00183a3e, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0010282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00061013, 0x00041013, 0x00051014, 0x00080f17, 0x00080f17, 0x00080f17, 0x00091018, 0x000a1018, 0x000a1219, 0x0009141a, 0x0009141a, 0x0008151b, 0x0008151b, 0x0008151c, 0x0008161c, 0x0008171d, 0x00081820, 0x00081820, 0x00091820, 0x000b1822, 0x000b1822, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1821, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000b171f, 0x000b171f, 0x000b171f, 0x000a161e, 0x000a161e, 0x000c1720, 0x000e1820, 0x000e1820, 0x000c1822, 0x000c1822, 0x000c1822, 0x00091822, 0x00091922, 0x00081922, 0x00081922, 0x000b1923, 0x000d1b24, 0x000d1b24, 0x000d1a24, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000b1924, 0x000b1a24, 0x000b1a24, 0x00091b24, 0x000b1c25, 0x000e1f28, 0x0012232e, 0x00142430, 0x00162532, 0x001a2c38, 0x001d303c, 0x00203440, 0x00233643, 0x00253845, 0x00253644, 0x00263543, 0x0024313e, 0x0022303b, 0x0026323e, 0x002a3642, 0x002d3845, 0x00323e4c, 0x00354150, 0x00374351, 0x00384552, 0x00384654, 0x00384654, 0x003a4855, 0x00404d5c, 0x00425060, 0x00435163, 0x00445264, 0x00445264, 0x00455466, 0x00475464, 0x00465363, 0x00445060, 0x00424e5c, 0x00404c59, 0x00404a58, 0x00404a58, 0x00404957, 0x00404957, 0x00404a58, 0x00404b59, 0x00404b59, 0x00404b58, 0x003d4856, 0x003b4654, 0x003c4553, 0x003c4551, 0x003c4451, 0x003d4450, 0x003c434e, 0x003c4350, 0x0039414e, 0x00373e4a, 0x00353d48, 0x00353c48, 0x00353c47, 0x00353b47, 0x00343945, 0x00323844, 0x00323843, 0x00313840, 0x0030373f, 0x00313841, 0x00323843, 0x00333944, 0x00333b46, 0x00353d49, 0x003a4250, 0x003d4654, 0x003d4854, 0x003c4754, 0x00394550, 0x0039444f, 0x0037404c, 0x00323c48, 0x00303844, 0x002c313d, 0x00272c36, 0x00252934, 0x00262934, 0x00272a34, 0x00282a34, 0x002b2d38, 0x002c303a, 0x002f313c, 0x0030323e, 0x002e333c, 0x002d323c, 0x002d303a, 0x002b2d38, 0x00282b35, 0x00272a34, 0x00272a34, 0x00272a34, 0x00262934, 0x00252832, 0x00242832, 0x00262934, 0x00282c35, 0x00292f38, 0x002c333c, 0x002f3740, 0x00303944, 0x00313d48, 0x0034404c, 0x003a4653, 0x003e4958, 0x003f4b5b, 0x003e4a5a, 0x003c4857, 0x00384453, 0x0037404e, 0x00343c4a, 0x00323946, 0x00313845, 0x00313844, 0x00303541, 0x002e3440, 0x002e3440, 0x002f3540, 0x00313642, 0x00333743, 0x00343844, 0x00343b46, 0x00363c48, 0x00353d4a, 0x00373f4c, 0x0039414e, 0x003a424f, 0x003b4350, 0x003b4350, 0x003b444f, 0x003c4451, 0x003d4552, 0x003e4653, 0x003f4754, 0x003f4856, 0x00404957, 0x00414b59, 0x00424c5c, 0x00434c5d, 0x00454e60, 0x00485364, 0x00485466, 0x00475466, 0x00485466, 0x00485668, 0x00495669, 0x004a586b, 0x0049586c, 0x0048586b, 0x00485868, 0x00485768, 0x00475565, 0x00475463, 0x00465363, 0x00465364, 0x00414e5f, 0x003d4859, 0x003d4859, 0x003a4555, 0x00384452, 0x0038424e, 0x00353f4c, 0x00333c48, 0x00303a47, 0x00323c48, 0x00333c49, 0x00313b48, 0x00303b48, 0x00303a47, 0x00303a46, 0x002f3844, 0x002a3441, 0x00283440, 0x00273440, 0x00263440, 0x0020303b, 0x0024343f, 0x00283a47, 0x00283a48, 0x002b3c4a, 0x0030414e, 0x00334450, 0x0032404e, 0x002f3c49, 0x0026343f, 0x00212e39, 0x0016212c, 0x000b161f, 0x0009141c, 0x00081019, 0x00071017, 0x0009141b, 0x000e1d26, 0x0011242d, 0x0010252f, 0x0010262f, 0x000e2630, 0x000d2631, 0x000f2531, 0x00112430, 0x00102430, 0x0010232f, 0x0010232f, 0x0010232e, 0x000f222c, 0x000f222c, 0x0010212b, 0x0010212a, 0x0010222c, 0x000f222e, 0x000f222e, 0x000f222e, 0x0010232f, 0x0010232e, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222c, 0x000f222c, 0x000f212c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f202b, 0x000f202b, 0x000e1f29, 0x000e1f28, 0x000d1f28, 0x000c1e27, 0x000c1e27, 0x000c1d26, 0x000c1d26, 0x000c1d26, 0x000c1c24, 0x000c1c24, 0x000c1c24, 0x000c1b23, 0x000c1b23, 0x000c1a21, 0x000b1920, 0x000c1920, 0x000d1921, 0x000d1921, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00143036, 0x00143439, 0x0017383c, 0x00183c40, 0x00194044, 0x001a4347, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205356, 0x0021595e, 0x002884a0, 0x0030a2c8, 0x002c8eab, 0x0025646b, 0x00256163, 0x00256364, 0x00266466, 0x00266467, 0x00266568, 0x00297684, 0x0032a4c8, 0x00297786, 0x00266466, 0x00256264, 0x00246062, 0x00245e60, 0x00245c5e, 0x0022595c, 0x0021585a, 0x00205457, 0x001f5154, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00183d41, 0x00183a3e, 0x00143439, 0x00143036, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00061013, 0x00051013, 0x00061014, 0x00080f17, 0x00080f17, 0x00090f17, 0x00091018, 0x000a1018, 0x000a1219, 0x0009141a, 0x0009141a, 0x0008151b, 0x0008151b, 0x0008151c, 0x0008171c, 0x0008171d, 0x00081820, 0x00081820, 0x00091820, 0x000b1822, 0x000b1822, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1821, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000b171f, 0x000b171f, 0x000b171f, 0x000a161e, 0x000a161e, 0x000c1720, 0x000d1820, 0x000d1820, 0x000c1821, 0x000c1822, 0x000c1822, 0x00091822, 0x00091922, 0x00081922, 0x00081922, 0x000a1923, 0x000c1a24, 0x000c1b24, 0x000d1924, 0x000d1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000c1a24, 0x000b1a24, 0x000a1b24, 0x000b1c25, 0x000c1e28, 0x000f222c, 0x0012232e, 0x0014242f, 0x00172834, 0x001a2e38, 0x001c313c, 0x001f3340, 0x00243744, 0x00263846, 0x00263644, 0x00243340, 0x0022303c, 0x0025323e, 0x00283440, 0x002c3844, 0x00323d4c, 0x00354150, 0x00374351, 0x00374451, 0x00374451, 0x00384552, 0x00394754, 0x00404d5c, 0x00425061, 0x00445264, 0x00455467, 0x00465468, 0x00465468, 0x00465466, 0x00465464, 0x00455363, 0x00455060, 0x00444e5c, 0x00414a59, 0x00404957, 0x003f4857, 0x00404a58, 0x00424c5a, 0x00414c5a, 0x00404c59, 0x00404b59, 0x003e4957, 0x003c4754, 0x003e4855, 0x003e4854, 0x003e4754, 0x003e4451, 0x003d4350, 0x003c4350, 0x0039404e, 0x00373d49, 0x00353c48, 0x00353c47, 0x00363c48, 0x00353c48, 0x00343b46, 0x00343945, 0x00333943, 0x00313840, 0x00313840, 0x00333941, 0x00353b46, 0x00383e4b, 0x0038404d, 0x003b4450, 0x003e4754, 0x00404957, 0x003d4855, 0x003b4653, 0x0038434f, 0x00343f4b, 0x00323c47, 0x002f3843, 0x002e3641, 0x002b303b, 0x00272c36, 0x00262a34, 0x00262a34, 0x00262934, 0x00272a34, 0x002a2c37, 0x002c2f39, 0x002d303b, 0x002f323d, 0x002e333c, 0x002c303b, 0x002c303a, 0x002a2d38, 0x00292c36, 0x00282b35, 0x00262833, 0x00252832, 0x00252832, 0x00242731, 0x00242831, 0x00262833, 0x00282c35, 0x00292e38, 0x002b313b, 0x002b333c, 0x002c3540, 0x002d3944, 0x00303c48, 0x0035404e, 0x003b4654, 0x003c4858, 0x003e4b5b, 0x00404c5c, 0x003e4a59, 0x003b4553, 0x00384250, 0x00363e4c, 0x00343c48, 0x00343a47, 0x00323844, 0x00303743, 0x00303743, 0x00313743, 0x00333843, 0x00343844, 0x00333743, 0x00333844, 0x00343c47, 0x00343c49, 0x00353c49, 0x0038404c, 0x003a424f, 0x003a424f, 0x003b4350, 0x003a434f, 0x003a4350, 0x003b4350, 0x003d4552, 0x00404854, 0x00404958, 0x00404a58, 0x00414b59, 0x00434c5c, 0x00444d5f, 0x00454f61, 0x00485264, 0x00485567, 0x00475667, 0x00485667, 0x00485769, 0x004a586b, 0x004a5a6c, 0x004a5b6e, 0x0049596d, 0x0048586a, 0x00485768, 0x00475566, 0x00475464, 0x00465463, 0x00455263, 0x00404d5e, 0x003a4658, 0x003a4557, 0x00394455, 0x00384352, 0x0038414e, 0x00353f4b, 0x00323c48, 0x00303a47, 0x00313b48, 0x00323c48, 0x00323c48, 0x00313b48, 0x00303a47, 0x00303945, 0x002e3844, 0x002a3541, 0x00283440, 0x00283642, 0x00283642, 0x0023323d, 0x0023333f, 0x00293b48, 0x00293c4b, 0x002b3d4b, 0x002f404c, 0x002f404c, 0x00283844, 0x00202e3b, 0x00182630, 0x001a2630, 0x00131d27, 0x0009131c, 0x0009131a, 0x00081118, 0x00081018, 0x000b161d, 0x00101f28, 0x0013242f, 0x0011252f, 0x0010262f, 0x000e2630, 0x000d2631, 0x000f2531, 0x00102430, 0x00102430, 0x0010232f, 0x0010232f, 0x0010232e, 0x000f222c, 0x000f222c, 0x0010222b, 0x0010212b, 0x0010222c, 0x000f222e, 0x000f222e, 0x0010232f, 0x0010232f, 0x0010232e, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222c, 0x000f222c, 0x000f212c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f202b, 0x000f202b, 0x000e1f29, 0x000e1f28, 0x000d1f28, 0x000c1e27, 0x000c1e27, 0x000c1d27, 0x000c1d27, 0x000c1d26, 0x000c1c24, 0x000c1c24, 0x000c1c24, 0x000c1b23, 0x000c1b23, 0x000c1a22, 0x000b1921, 0x000c1921, 0x000d1922, 0x000d1922, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00142e34, 0x00143338, 0x0016363b, 0x00183c40, 0x00183f43, 0x001a4347, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5053, 0x00205356, 0x00215b61, 0x00298aa8, 0x002ea3c9, 0x002a88a2, 0x00246064, 0x00245f61, 0x00246062, 0x00266264, 0x00256364, 0x00266466, 0x00266467, 0x00287583, 0x0032a4c8, 0x00297786, 0x00266466, 0x00256364, 0x00256163, 0x00245f61, 0x00245d60, 0x00245c5e, 0x0022595c, 0x0021585a, 0x00205457, 0x001f5154, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00183c40, 0x0017383c, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00041013, 0x00041013, 0x00051014, 0x00070f17, 0x00080f17, 0x00081017, 0x00091018, 0x00091018, 0x000a1118, 0x0009141a, 0x0009141a, 0x0008151b, 0x0008151b, 0x0008151c, 0x0008171c, 0x0008181d, 0x00081820, 0x00081820, 0x00091820, 0x000b1822, 0x000b1822, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1821, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000b171f, 0x000c1820, 0x000c1820, 0x000c1821, 0x000c1822, 0x000c1822, 0x00091822, 0x00091922, 0x00091922, 0x00091922, 0x00091922, 0x000b1a24, 0x000b1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000b1b24, 0x000b1c25, 0x000c1e27, 0x000d202b, 0x0010212c, 0x0011232d, 0x00142731, 0x00182c37, 0x001c303c, 0x001e333f, 0x00233744, 0x00253946, 0x00273845, 0x00263743, 0x0023333e, 0x0023323d, 0x0025333e, 0x00293742, 0x00303c4a, 0x0034414f, 0x00354350, 0x00364450, 0x00374450, 0x00374451, 0x003a4754, 0x00404c5b, 0x00425061, 0x00445264, 0x00455466, 0x00465468, 0x00465568, 0x00465566, 0x00465565, 0x00475465, 0x00485464, 0x00465160, 0x00444c5d, 0x00414a5a, 0x00414b5a, 0x00424c5b, 0x00444d5c, 0x00444e5c, 0x00414d5b, 0x00404c5a, 0x00404b59, 0x00404958, 0x00404958, 0x003f4754, 0x003c4451, 0x003a404d, 0x00383d4b, 0x00373c4a, 0x00383f4c, 0x00363c49, 0x00343b48, 0x00353c48, 0x00373d48, 0x00363c48, 0x00353c47, 0x00353b47, 0x00343b44, 0x00323941, 0x00323840, 0x00343b44, 0x00373d49, 0x003c4250, 0x003e4654, 0x003d4755, 0x00414b59, 0x003f4958, 0x003b4452, 0x00373f4c, 0x00343c47, 0x002c343e, 0x0028303a, 0x0028303a, 0x002b323c, 0x002a3039, 0x00282c36, 0x00262a34, 0x00252833, 0x00252833, 0x00262934, 0x00282b35, 0x002a2c37, 0x002b2e39, 0x002e303c, 0x002d323c, 0x002d313b, 0x002d303a, 0x002c2f39, 0x00292c37, 0x00282b35, 0x00262934, 0x00262833, 0x00262934, 0x00252833, 0x00252832, 0x00262931, 0x00272b34, 0x00282d37, 0x002b3039, 0x00293039, 0x00283039, 0x0028313c, 0x002b343f, 0x002e3643, 0x00333b48, 0x00384150, 0x003e4858, 0x00424e5c, 0x00424f5e, 0x00404b59, 0x003c4754, 0x003a4250, 0x00383f4c, 0x00363c48, 0x00343a45, 0x00323844, 0x00313843, 0x00313843, 0x00333843, 0x00333843, 0x00343844, 0x00343944, 0x00343b47, 0x00343c48, 0x00343c49, 0x00373f4c, 0x0039414e, 0x003b4350, 0x003b4350, 0x003a444f, 0x003a4450, 0x003c4450, 0x003f4754, 0x00404856, 0x00424b59, 0x00424c5a, 0x00404a58, 0x00424c5c, 0x00454e60, 0x00464f62, 0x00465264, 0x00485567, 0x00485668, 0x00485868, 0x004a586a, 0x004b596c, 0x004b5b6e, 0x004b5c70, 0x004a5b6f, 0x0048586c, 0x00475769, 0x00455568, 0x00455464, 0x00455464, 0x00445263, 0x003f4c5d, 0x003b4758, 0x00394457, 0x00384454, 0x00384351, 0x0037404d, 0x00343e4a, 0x00323c48, 0x00313b48, 0x00323c48, 0x00323c48, 0x00313b48, 0x00303a47, 0x00303945, 0x002e3844, 0x002c3542, 0x00293440, 0x00293541, 0x002a3844, 0x002b3944, 0x0024343f, 0x00243440, 0x00293b49, 0x002b3e4c, 0x002c3f4c, 0x002d404c, 0x00283946, 0x00192835, 0x00101d2a, 0x00121e29, 0x0018232d, 0x00121c25, 0x0008121b, 0x00091319, 0x00091118, 0x000a1219, 0x000f1920, 0x0012212b, 0x00142530, 0x00112630, 0x00102630, 0x000f2530, 0x000e2430, 0x000f2430, 0x00102430, 0x00102430, 0x0010232f, 0x0010232f, 0x0010232e, 0x0010232d, 0x0010232d, 0x0010222c, 0x0010222c, 0x0010222d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232e, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232d, 0x0010232d, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010212c, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000d1f29, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000d1d26, 0x000d1d24, 0x000d1d24, 0x000c1c24, 0x000c1c24, 0x000c1b24, 0x000b1a24, 0x000b1924, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153338, 0x0016363b, 0x00183a3e, 0x00183f43, 0x001a4347, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205254, 0x00225e67, 0x002a90b0, 0x002ea1c8, 0x00288099, 0x00245e61, 0x00245c5f, 0x00245e60, 0x00245f61, 0x00256163, 0x00256264, 0x00256364, 0x00276466, 0x00297482, 0x0032a4c8, 0x00297786, 0x00276466, 0x00256364, 0x00256264, 0x00256163, 0x00245f61, 0x00245d60, 0x00245c5e, 0x0022595c, 0x0021585a, 0x00205558, 0x00205254, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00051013, 0x00051013, 0x00051014, 0x00071017, 0x00071017, 0x00071017, 0x00080f17, 0x00091018, 0x000a1118, 0x0009141a, 0x0009141a, 0x0008151b, 0x0008151b, 0x0008151c, 0x0008171c, 0x0008181d, 0x00081820, 0x00081820, 0x00091820, 0x000b1822, 0x000b1822, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1822, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1821, 0x000c1822, 0x000c1822, 0x00091822, 0x00091922, 0x00091922, 0x00091922, 0x00091922, 0x000b1a24, 0x000b1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000b1b24, 0x000b1c25, 0x000c1e27, 0x000e202a, 0x0010202c, 0x0011212c, 0x00132430, 0x00172a36, 0x001c303c, 0x00203440, 0x00243846, 0x00273a48, 0x00283b48, 0x00283946, 0x00263643, 0x00243340, 0x0024313d, 0x00293742, 0x002f3c48, 0x0033404e, 0x0034414f, 0x0034424e, 0x00364350, 0x00374551, 0x00394754, 0x003e4b59, 0x00425060, 0x00435264, 0x00455466, 0x00475668, 0x00475668, 0x00465567, 0x00465566, 0x00465566, 0x00485567, 0x00485464, 0x00475163, 0x00444f60, 0x00444e60, 0x00454e5e, 0x0046505e, 0x0046505f, 0x0044505d, 0x00424e5c, 0x00404c5a, 0x00404a58, 0x00404857, 0x003d4552, 0x003a404e, 0x00353a48, 0x00343845, 0x00363c49, 0x00383e4b, 0x00363c49, 0x00353c48, 0x00363c48, 0x00373d48, 0x00373d48, 0x00353c47, 0x00353c47, 0x00353c45, 0x00343a42, 0x00343b43, 0x00383e48, 0x003b414f, 0x003f4654, 0x003f4857, 0x003f4858, 0x00404959, 0x003b4454, 0x00343c49, 0x002e3441, 0x002a303a, 0x00252c34, 0x00232932, 0x00252b34, 0x00292f38, 0x00292e38, 0x00282c36, 0x00262a34, 0x00262934, 0x00262934, 0x00282a34, 0x00282b35, 0x002a2c37, 0x002a2c38, 0x002c2f3b, 0x002c303b, 0x002c303b, 0x002e303b, 0x002c303a, 0x002a2c37, 0x00282b35, 0x00272a34, 0x00272a34, 0x00262934, 0x00262934, 0x00262932, 0x00262931, 0x00262932, 0x00282c36, 0x00292e38, 0x00282e37, 0x00242b34, 0x00232833, 0x00232933, 0x00242b35, 0x00292f3a, 0x002d3441, 0x0038404f, 0x00414c59, 0x00434e5e, 0x00404d5c, 0x00404a58, 0x003d4654, 0x003b4250, 0x00383f4c, 0x00353b47, 0x00333945, 0x00323844, 0x00313843, 0x00323642, 0x00333743, 0x00343844, 0x00343945, 0x00363c48, 0x00373e4b, 0x00373f4c, 0x0038404d, 0x003a424f, 0x003b4350, 0x003c4452, 0x003c4552, 0x003c4451, 0x003c4453, 0x003f4756, 0x00414958, 0x00434c5b, 0x00444d5c, 0x00434c5c, 0x00424b5c, 0x00454e60, 0x00465061, 0x00465264, 0x00485567, 0x00485768, 0x00495869, 0x004b596c, 0x004c5b6d, 0x004b5b6e, 0x004b5c6f, 0x004b5c70, 0x0048596c, 0x00475769, 0x00465568, 0x00465465, 0x00455464, 0x00435162, 0x003e4c5d, 0x003c485a, 0x003b4658, 0x003a4453, 0x00384350, 0x0037404d, 0x00343e4a, 0x00333c49, 0x00323c48, 0x00333d49, 0x00313c48, 0x00303a47, 0x00303a46, 0x00303945, 0x002d3743, 0x002b3441, 0x00293440, 0x00293542, 0x002c3a46, 0x00303f4a, 0x00283844, 0x00243641, 0x002c3e4c, 0x002c404d, 0x002c404c, 0x002c3e4b, 0x00263643, 0x0014222e, 0x000c1824, 0x00131c28, 0x0018212c, 0x00111924, 0x0009111b, 0x000b131c, 0x000a131b, 0x000c161e, 0x00131e26, 0x0015242e, 0x00142630, 0x00122630, 0x00112630, 0x000f2530, 0x000e2430, 0x000f2430, 0x00102430, 0x00102430, 0x0010242f, 0x0010232f, 0x0010232e, 0x0010232d, 0x0010232d, 0x0010222c, 0x0010222c, 0x0010222d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232d, 0x0010232d, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010212c, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000d1f29, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000d1e28, 0x000d1d28, 0x000d1d26, 0x000d1d24, 0x000d1d24, 0x000c1c24, 0x000c1c24, 0x000c1b24, 0x000b1a24, 0x000b1924, 0x000c1a24, 0x000c1a24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012242c, 0x0010282e, 0x00132c32, 0x00143036, 0x00143439, 0x0017383c, 0x00183d41, 0x001a4245, 0x001b4649, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205356, 0x0022626d, 0x002b95b7, 0x002ea0c6, 0x00287a90, 0x00235c5f, 0x00245c5f, 0x00245d60, 0x00245e60, 0x00245f61, 0x00246062, 0x00256163, 0x00256264, 0x00256364, 0x00287481, 0x0031a4c8, 0x002c89a2, 0x002b7f93, 0x002b7f92, 0x002a7f91, 0x002a7d90, 0x00297c90, 0x00287c8f, 0x0028798d, 0x0028798c, 0x0027788c, 0x0026758a, 0x00257488, 0x00236d80, 0x001f5257, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183d41, 0x00183a3e, 0x00153439, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00080f14, 0x00080f14, 0x00080f14, 0x00080f16, 0x00071017, 0x00081017, 0x00091018, 0x000a1018, 0x000a1118, 0x000a131a, 0x0009141a, 0x0008141b, 0x0008151b, 0x0008151c, 0x0008171c, 0x0008171d, 0x00081820, 0x00081820, 0x00091820, 0x000b1822, 0x000b1823, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1923, 0x000c1923, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1823, 0x000c1923, 0x00091a23, 0x00091a23, 0x00091a23, 0x00091a23, 0x00091a23, 0x000b1a24, 0x000b1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000c1b24, 0x000c1c25, 0x000c1d27, 0x000e1f2a, 0x0010202c, 0x0011202c, 0x0012232f, 0x00172834, 0x001c303c, 0x00223644, 0x00263a49, 0x00293c4c, 0x002b3c4b, 0x002a3848, 0x00283645, 0x00263342, 0x00253340, 0x002a3844, 0x002f3c49, 0x0032404c, 0x0032404c, 0x0033414c, 0x00354350, 0x00374451, 0x00394755, 0x003c4958, 0x00404e5d, 0x00435061, 0x00445364, 0x00455466, 0x00475568, 0x00455668, 0x00465568, 0x00475568, 0x00475668, 0x00475667, 0x00475464, 0x00445062, 0x00445062, 0x00455062, 0x00465161, 0x00465261, 0x00455160, 0x00444e5c, 0x00414c5a, 0x00404857, 0x003f4554, 0x003c4250, 0x003a3f4c, 0x00363a48, 0x00353947, 0x00363c48, 0x00373d49, 0x00373d49, 0x00373d4a, 0x00373d48, 0x00373d48, 0x00363d48, 0x00353c47, 0x00353c47, 0x00353b46, 0x00353c45, 0x00373e49, 0x003c4350, 0x00404858, 0x00444c5c, 0x00404959, 0x003b4352, 0x0039404f, 0x00333947, 0x002d323e, 0x00262b36, 0x00232831, 0x00212530, 0x0020242d, 0x0022252e, 0x00262b34, 0x00282c36, 0x00272b35, 0x00282b35, 0x00282b35, 0x00282b35, 0x00282c37, 0x00282c37, 0x00282c37, 0x00292d38, 0x002a2e39, 0x002c303a, 0x002c303a, 0x002c303a, 0x002c2f39, 0x002a2c37, 0x00282b35, 0x00272a34, 0x00272a34, 0x00262a34, 0x00262932, 0x00252a32, 0x00242831, 0x00262a34, 0x00282c36, 0x00282d37, 0x00262b34, 0x00212630, 0x001e222c, 0x001f232c, 0x0020242d, 0x00252831, 0x00282c37, 0x002f3440, 0x003b4350, 0x003f4856, 0x00404c5c, 0x00414d5c, 0x003f4a59, 0x003d4655, 0x003a4250, 0x00383f4d, 0x00353c4a, 0x00343a48, 0x00343844, 0x00303542, 0x00303642, 0x00333943, 0x00343b45, 0x00363c48, 0x00383e4b, 0x0039404c, 0x003a404c, 0x003b434e, 0x003c4450, 0x003d4654, 0x003e4655, 0x003d4554, 0x003e4556, 0x00404858, 0x00414a59, 0x00434c5b, 0x00434c5c, 0x00444d5d, 0x00434c5d, 0x00465060, 0x00475364, 0x00485467, 0x00485668, 0x00485869, 0x0049586a, 0x0049596b, 0x004a5a6c, 0x004a5a6c, 0x004a5b6d, 0x004a5b6d, 0x0048596b, 0x0048586a, 0x0046566a, 0x00455568, 0x00455466, 0x00445061, 0x00404d5d, 0x00404b5b, 0x003d4756, 0x003b4452, 0x00384250, 0x0037404f, 0x00353f4c, 0x00343e4a, 0x00343c49, 0x00343c48, 0x00323b46, 0x00303944, 0x00303944, 0x00303944, 0x002d3844, 0x00293440, 0x00283441, 0x00273443, 0x002e3d4c, 0x00334452, 0x002e424f, 0x00263a48, 0x002c404d, 0x002c404d, 0x002c3e4c, 0x002b3c48, 0x00253440, 0x00192630, 0x000f1a25, 0x00131d28, 0x00161f2a, 0x000c161f, 0x0008131c, 0x000a141e, 0x000a161e, 0x000c1a23, 0x0013212b, 0x00142631, 0x00162733, 0x00142632, 0x00142631, 0x00112531, 0x00102530, 0x00102430, 0x00102531, 0x00102531, 0x00112430, 0x00112430, 0x0011242f, 0x0010242d, 0x0010242d, 0x0010232d, 0x0010222c, 0x0010232d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232e, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010242f, 0x0010242f, 0x000f242f, 0x000f232f, 0x000f232f, 0x000f232d, 0x000e232d, 0x000f232d, 0x0010232d, 0x0010232d, 0x000f222d, 0x000e212c, 0x000f202c, 0x000f202b, 0x0010202c, 0x000f212c, 0x000f212c, 0x000e202b, 0x000c1f29, 0x000c1f28, 0x000c1e28, 0x000c1e28, 0x000d1d28, 0x000e1d28, 0x000e1d28, 0x000d1d26, 0x000d1d24, 0x000d1d24, 0x000c1c24, 0x000c1c24, 0x000c1b26, 0x000b1a25, 0x000c1a25, 0x000d1b25, 0x000d1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153338, 0x0016363b, 0x00183c40, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4d50, 0x001f5154, 0x00205356, 0x00236877, 0x002c99bc, 0x002d9ec3, 0x00267588, 0x00245c5f, 0x00245c5f, 0x00245d60, 0x00245d60, 0x00245e60, 0x00245f61, 0x00245f61, 0x00246062, 0x00256163, 0x00256264, 0x00287481, 0x0031a4c8, 0x0032a5cb, 0x0032a5cb, 0x0032a5cb, 0x0032a5cb, 0x0032a5cb, 0x0032a5cb, 0x0032a5cb, 0x0031a4cb, 0x0031a4cb, 0x0030a4cb, 0x0030a4cb, 0x002fa4cb, 0x002da2c9, 0x002885a3, 0x001d4e51, 0x001c4a4d, 0x001a4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a0f15, 0x000a0f15, 0x000a0f15, 0x00080f17, 0x00071017, 0x00081017, 0x00091018, 0x000a1018, 0x000a1118, 0x000a131a, 0x000a141a, 0x0009141b, 0x0008151b, 0x0008151c, 0x0008161c, 0x0008171d, 0x00081820, 0x00081820, 0x000a1821, 0x000b1822, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000c1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000d1a24, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000c1924, 0x00091a24, 0x00091b24, 0x00091b24, 0x00091b24, 0x00091a24, 0x000b1a24, 0x000b1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000c1b24, 0x000c1c25, 0x000c1d27, 0x000e1f2a, 0x0010202b, 0x0011202c, 0x0012232e, 0x00152834, 0x001c303c, 0x00233847, 0x00283c4c, 0x002b3e4d, 0x002c3c4c, 0x002b394a, 0x002a3848, 0x00283546, 0x00283544, 0x002b3845, 0x00303d49, 0x00313f4a, 0x0032404b, 0x0033404c, 0x00354250, 0x00374451, 0x00394755, 0x003c4958, 0x00404d5c, 0x00415060, 0x00435263, 0x00465466, 0x00465468, 0x00465668, 0x00475668, 0x00475668, 0x00485768, 0x00485768, 0x00485465, 0x00445162, 0x00445062, 0x00455062, 0x00465163, 0x00475362, 0x00465160, 0x00444e5c, 0x00424b59, 0x00414756, 0x003f4452, 0x003c404e, 0x003b3f4d, 0x00393e4c, 0x00383c4a, 0x00373c48, 0x00383e49, 0x0039404b, 0x003a404c, 0x00383f4a, 0x00383d48, 0x00373c48, 0x00363c47, 0x00363c47, 0x00373c48, 0x00383f4c, 0x003a4250, 0x00414a5a, 0x00475062, 0x00495364, 0x00434b5a, 0x00393f4e, 0x00343847, 0x002f333f, 0x002a2d38, 0x00252832, 0x0021252e, 0x0020242c, 0x001f232b, 0x0020232b, 0x00252831, 0x00272b35, 0x00272c35, 0x00282c36, 0x00292c36, 0x00292c36, 0x00282d37, 0x00292e38, 0x00292e38, 0x00292e38, 0x002b303a, 0x002c303a, 0x002c303a, 0x002b2f39, 0x00292e38, 0x00282c35, 0x00272b35, 0x00272b35, 0x00272c34, 0x00272c34, 0x00262b33, 0x00252a32, 0x00242933, 0x00262a35, 0x00282c36, 0x00282c36, 0x00242730, 0x001d2029, 0x001c1f28, 0x001c2028, 0x001e212a, 0x0021242b, 0x00242830, 0x00282c36, 0x00303642, 0x0038404d, 0x003d4757, 0x00444f5f, 0x00434d5d, 0x00424b5b, 0x003d4755, 0x003c4452, 0x003a404f, 0x00383f4d, 0x00363c48, 0x00303642, 0x00303641, 0x00333943, 0x00353c46, 0x00363c48, 0x00373d4a, 0x00383e49, 0x003a404c, 0x003a424d, 0x003c4450, 0x003c4654, 0x003e4856, 0x00404958, 0x00414a5a, 0x00444c5c, 0x00434d5c, 0x00444d5c, 0x00434f5c, 0x0044505f, 0x00445060, 0x00465262, 0x00485768, 0x0049576a, 0x0048586a, 0x0048586a, 0x0048586a, 0x0048586b, 0x00495a6c, 0x0048596b, 0x0048596b, 0x0048596b, 0x0048596b, 0x0049596c, 0x0048586c, 0x0046566a, 0x00465467, 0x00435060, 0x00404d5c, 0x00404c5b, 0x003e4856, 0x003b4453, 0x00384250, 0x0037404f, 0x00353f4c, 0x00353f4b, 0x00343d49, 0x00333c46, 0x00323a44, 0x00313944, 0x00313944, 0x002f3844, 0x002c3643, 0x002a3440, 0x00283441, 0x00283544, 0x002e3e4d, 0x00314452, 0x00304653, 0x002b404e, 0x002a3e4c, 0x002b3d4c, 0x002a3c48, 0x00283844, 0x0023313c, 0x0016222b, 0x000d1922, 0x00121c27, 0x00141d27, 0x000b141c, 0x000b141d, 0x000b1821, 0x000c1823, 0x000c1c27, 0x0013242e, 0x00152834, 0x00152834, 0x00152633, 0x00142633, 0x00122531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00112430, 0x00112430, 0x0011242f, 0x0011242e, 0x0011242e, 0x0011232d, 0x0011232d, 0x0011232d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232e, 0x0010242d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x00102430, 0x00102430, 0x000f242f, 0x000f242f, 0x000f242f, 0x000e242d, 0x000d242d, 0x000e242d, 0x000f242d, 0x000f232d, 0x000f222d, 0x000e212d, 0x000f202c, 0x0010202c, 0x0010212c, 0x0010222c, 0x0010232d, 0x000e212c, 0x000c2029, 0x000c2029, 0x000c1e28, 0x000c1e28, 0x000d1d28, 0x000e1d28, 0x000e1d28, 0x000d1d26, 0x000d1d24, 0x000d1d24, 0x000d1d24, 0x000c1c25, 0x000c1c26, 0x000c1b26, 0x000c1a26, 0x000e1c25, 0x000e1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x00153439, 0x00183a3e, 0x00183f43, 0x001a4347, 0x001c484c, 0x001d4c50, 0x001f5154, 0x00205457, 0x00246f80, 0x002d9cc1, 0x002d9cc0, 0x0026707e, 0x00245d60, 0x00245d60, 0x00245d60, 0x00245e60, 0x00245e60, 0x00245e60, 0x00245f61, 0x00245f61, 0x00246062, 0x00256163, 0x00266264, 0x0026686f, 0x00297d90, 0x002a7f92, 0x002a7f92, 0x002a7f93, 0x002a7f92, 0x002a7f92, 0x002a7f92, 0x002a7e91, 0x00297e91, 0x00297d91, 0x00287c90, 0x00287b90, 0x00277a90, 0x002c98bc, 0x002c9bc0, 0x001f5054, 0x001d4c50, 0x001c474b, 0x00194245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0013282e, 0x00102229, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091016, 0x00091016, 0x00091016, 0x00081017, 0x00071017, 0x00081017, 0x00091018, 0x000a1018, 0x000a1118, 0x000b131a, 0x000a131a, 0x000a141b, 0x0009141b, 0x000a151c, 0x000a161c, 0x000a171d, 0x00091820, 0x00091820, 0x000a1821, 0x000b1822, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000c1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1a24, 0x000e1a24, 0x000d1924, 0x000d1924, 0x000c1924, 0x00091b24, 0x00091b24, 0x00091b24, 0x00091b24, 0x00091b24, 0x000b1a24, 0x000b1a24, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000c1b24, 0x000c1c25, 0x000c1d27, 0x000e1f2a, 0x0010202b, 0x0011202c, 0x0012222d, 0x00142733, 0x00192c38, 0x00213544, 0x00273c4b, 0x002c3e4e, 0x002c3c4c, 0x002c3a4b, 0x002c394a, 0x002b3849, 0x002c3949, 0x002c3a47, 0x00303e4a, 0x0032404b, 0x0032404b, 0x0032404c, 0x0034414f, 0x00364350, 0x00384654, 0x003c4958, 0x003f4c5b, 0x00404f5e, 0x00445262, 0x00465466, 0x00465468, 0x00475668, 0x00475668, 0x00475668, 0x00485769, 0x00485768, 0x00485466, 0x00455263, 0x00445162, 0x00465163, 0x00455062, 0x00445060, 0x00434e5d, 0x00414b5a, 0x00414958, 0x00414756, 0x00404453, 0x003c414f, 0x003b404d, 0x003b404d, 0x003a3f4c, 0x00383e4b, 0x0039404c, 0x003b404c, 0x003b414c, 0x0039404b, 0x00383d49, 0x00383c48, 0x00383c48, 0x00373c48, 0x00383e4b, 0x003b4250, 0x003f4756, 0x00454f5f, 0x00495465, 0x004b5566, 0x00424958, 0x00383d4b, 0x00323442, 0x002c2e3a, 0x00282a34, 0x00242630, 0x0021242d, 0x0020242c, 0x0020232b, 0x0020222b, 0x00252831, 0x00272b35, 0x00272c35, 0x00282c36, 0x00292c36, 0x00292c37, 0x00282d37, 0x00292e38, 0x002a2f38, 0x002c303a, 0x002c303b, 0x002c303b, 0x002c303a, 0x002b303a, 0x00292e38, 0x00282c37, 0x00282c36, 0x00282c36, 0x00282c35, 0x00282c36, 0x00272b34, 0x00272b34, 0x00252a34, 0x00272b36, 0x00282c38, 0x00282c36, 0x0022252d, 0x001c1f28, 0x001c1f27, 0x001c1f28, 0x001c2028, 0x001d2027, 0x0020232a, 0x00242830, 0x002a2f3a, 0x00343a47, 0x00394150, 0x00404b5b, 0x00465060, 0x0046505f, 0x00414b59, 0x003f4655, 0x003b4351, 0x003a404f, 0x00383e4a, 0x00363c48, 0x00333a45, 0x00333a44, 0x00353c46, 0x00363d49, 0x00373d4a, 0x00383e4a, 0x003a404c, 0x003a424d, 0x003b4350, 0x003c4654, 0x00404a58, 0x00434c5b, 0x00434c5c, 0x00444e5e, 0x00444e5e, 0x00444e5c, 0x0044505e, 0x00465362, 0x00475463, 0x00465463, 0x00485768, 0x0049586a, 0x0048586a, 0x0048586a, 0x0048586a, 0x0048596c, 0x004a5b6c, 0x00495a6c, 0x0048596c, 0x0048596b, 0x0048596b, 0x00495a6c, 0x0047576b, 0x0046556a, 0x00455467, 0x00414f5f, 0x00404c5c, 0x003f4a59, 0x003d4755, 0x003b4452, 0x00394350, 0x0037404f, 0x00353f4d, 0x00343e4b, 0x00333c48, 0x00323944, 0x00303843, 0x00303844, 0x00313944, 0x002f3844, 0x002c3743, 0x00293340, 0x00273340, 0x002a3846, 0x002e3f4d, 0x002d404e, 0x002b414e, 0x002d4450, 0x0029404c, 0x002a3e4c, 0x00283c48, 0x00263642, 0x00202e38, 0x00111e27, 0x000b171f, 0x00101a23, 0x00101a22, 0x000c161d, 0x000e1820, 0x000e1b24, 0x000d1c27, 0x0010202c, 0x00142532, 0x00152834, 0x00142834, 0x00142733, 0x00132633, 0x00122532, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00112430, 0x00112430, 0x0011242f, 0x0011242e, 0x0011242e, 0x0010232d, 0x0010222c, 0x0010232d, 0x0010232e, 0x000f232e, 0x0010232f, 0x0010232f, 0x0010232e, 0x0010242d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x00102430, 0x00102430, 0x000f242f, 0x000f242f, 0x000f242f, 0x000e242d, 0x000d242d, 0x000e242d, 0x000f242d, 0x000f242d, 0x000f222e, 0x000e212d, 0x000f212c, 0x000f202c, 0x0010212c, 0x000f222d, 0x000f222d, 0x000e212c, 0x000d202a, 0x000c202a, 0x000c1e29, 0x000c1e28, 0x000c1d28, 0x000d1d28, 0x000d1d28, 0x000d1d26, 0x000d1d24, 0x000d1d24, 0x000d1d24, 0x000c1c25, 0x000c1c26, 0x000c1b26, 0x000c1b26, 0x000e1c25, 0x000e1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4245, 0x001b4649, 0x001d4b4e, 0x001f5053, 0x00205457, 0x0025758a, 0x002ea0c4, 0x002d98bb, 0x00256c78, 0x00245e60, 0x00245f61, 0x00245f61, 0x00245f61, 0x00245f61, 0x00245f61, 0x00245f61, 0x00245f61, 0x00245f61, 0x00246062, 0x00256163, 0x00256163, 0x00256264, 0x00256364, 0x00276466, 0x00266466, 0x00266467, 0x00266467, 0x00266467, 0x00266467, 0x00266466, 0x00266364, 0x00256264, 0x00246062, 0x00245e60, 0x00245d60, 0x002b93b2, 0x002c9bc0, 0x00205457, 0x001d4d50, 0x001c484c, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00142e34, 0x00132c32, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091016, 0x00091016, 0x00091016, 0x00081017, 0x00081018, 0x00081018, 0x000a1018, 0x000a1018, 0x000a1118, 0x000c131a, 0x000c131a, 0x000b141b, 0x000b141b, 0x000b141c, 0x000c151c, 0x000c161d, 0x000c1820, 0x000b1820, 0x000b1821, 0x000b1822, 0x000c1924, 0x000c1924, 0x000c1924, 0x000c1b24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000c1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1a24, 0x000e1a24, 0x000c1b24, 0x000a1b24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000a1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000d1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000d1b24, 0x000e1c25, 0x000d1c27, 0x00101f2a, 0x0010202b, 0x0012202c, 0x0011202c, 0x00142430, 0x00182936, 0x001e313e, 0x00283c4a, 0x002c3f4d, 0x00283a49, 0x002a3a49, 0x002c3c4b, 0x002c3c4b, 0x002c3c4a, 0x002b3946, 0x002e3c49, 0x0032404c, 0x0031404b, 0x0031404c, 0x0034414f, 0x00364350, 0x00384654, 0x003c4858, 0x003d4b59, 0x003f4c5b, 0x00445160, 0x00475465, 0x00485468, 0x00475668, 0x00485769, 0x00475668, 0x00485769, 0x00485768, 0x00485567, 0x00475465, 0x00465364, 0x00465163, 0x00455062, 0x00424e5e, 0x00404c5c, 0x00404b5b, 0x00414a5a, 0x00414857, 0x003f4454, 0x003c4150, 0x003b4050, 0x003b4050, 0x003a404e, 0x003b404e, 0x003b414e, 0x003c424e, 0x003c424d, 0x003b414c, 0x003b404c, 0x003b3f4b, 0x003a3e4a, 0x00393e4b, 0x003b404f, 0x003f4757, 0x00464f5f, 0x00485263, 0x00475364, 0x00465262, 0x003c4452, 0x00373b49, 0x00313441, 0x002a2c38, 0x00262833, 0x00232530, 0x0021242c, 0x0020232b, 0x0020232b, 0x0023242c, 0x00272932, 0x00282c36, 0x00282c36, 0x00282c36, 0x00292c36, 0x00292c37, 0x00282d37, 0x00292e38, 0x002c303b, 0x002d323c, 0x002d323c, 0x002d323c, 0x002d313c, 0x002c303b, 0x002a2f39, 0x00292e38, 0x00292e38, 0x00292e38, 0x00282d37, 0x00282d37, 0x00282c36, 0x00282c36, 0x00272b35, 0x00282c37, 0x00292e39, 0x00282c37, 0x0022242e, 0x001c1f28, 0x001c1f27, 0x001c2028, 0x001d2028, 0x001d2028, 0x00202329, 0x00242630, 0x002a2d38, 0x00343845, 0x00383e4d, 0x003e4654, 0x00485160, 0x00485361, 0x0046505e, 0x00414a59, 0x003e4654, 0x003b4250, 0x003b414e, 0x003a414d, 0x0039414d, 0x0038404c, 0x00363e4a, 0x00373f4c, 0x00383f4c, 0x00383f4c, 0x003a404d, 0x003a424d, 0x003b4350, 0x003e4654, 0x00424b59, 0x00444e5c, 0x00444e5d, 0x00444d5e, 0x00444d5d, 0x00444e5d, 0x00475260, 0x00485564, 0x00485566, 0x00485566, 0x00485769, 0x0048586a, 0x00485769, 0x0048586a, 0x0048596c, 0x004b5c6e, 0x004c5c6f, 0x004c5c6e, 0x004a5b6d, 0x00495a6c, 0x00495a6c, 0x0048586b, 0x0047576b, 0x00455468, 0x00445265, 0x00414e5e, 0x003e4b5a, 0x003d4858, 0x003c4755, 0x003c4553, 0x003b4452, 0x00384250, 0x0036404e, 0x00343e4c, 0x00323b49, 0x00303844, 0x002f3742, 0x00303843, 0x00313944, 0x00303944, 0x00303945, 0x002a3440, 0x00222e3b, 0x00283444, 0x002c3c4b, 0x002a3d4b, 0x00273d4b, 0x002c4350, 0x002c4350, 0x002c414e, 0x00283b47, 0x0021333e, 0x001c2c36, 0x00131e28, 0x000c1620, 0x000d1720, 0x000c171f, 0x000d1820, 0x00101c25, 0x00101e28, 0x000f1f2a, 0x0012232f, 0x00152834, 0x00142936, 0x00142835, 0x00132734, 0x00122734, 0x00102533, 0x00102533, 0x00102532, 0x00102531, 0x00102530, 0x00102430, 0x0010232f, 0x0010242f, 0x0011242e, 0x0010242d, 0x0010222d, 0x0010222c, 0x0010222c, 0x000f232d, 0x000f242d, 0x000f232e, 0x0010232f, 0x0010232e, 0x0010242d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x000e242d, 0x000d242d, 0x000e242d, 0x000f242d, 0x000f242d, 0x000f242f, 0x000f232f, 0x000f222e, 0x000f222e, 0x000f222e, 0x000e222e, 0x000e222e, 0x000e212d, 0x000e212c, 0x000d202c, 0x000c1e2b, 0x000c1e2a, 0x000c1e2a, 0x000c1e2a, 0x000c1e28, 0x000d1d26, 0x000d1d24, 0x000d1d24, 0x000d1d24, 0x000d1d24, 0x000c1c24, 0x000c1c25, 0x000d1c25, 0x000e1c25, 0x000e1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153439, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001d4a4d, 0x001e4d50, 0x00205458, 0x00267c94, 0x002fa1c8, 0x002c94b4, 0x00266871, 0x00246062, 0x00256163, 0x00256163, 0x00256163, 0x00256163, 0x00256163, 0x00246062, 0x00246062, 0x00246062, 0x00246062, 0x00246062, 0x00256163, 0x00256163, 0x00256264, 0x00256364, 0x00266466, 0x00266466, 0x00266467, 0x00266467, 0x00266467, 0x00266467, 0x00266467, 0x00266466, 0x00256364, 0x00266264, 0x00245f61, 0x00245e61, 0x002c93b3, 0x002c9cc0, 0x00205458, 0x001e4f51, 0x001d4a4d, 0x001a4448, 0x00183f43, 0x00173a3e, 0x00153439, 0x00142e34, 0x00122c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091016, 0x00091016, 0x00091016, 0x00081017, 0x00081018, 0x00081018, 0x000a1018, 0x000a1018, 0x000a1118, 0x000c131a, 0x000c131a, 0x000c141b, 0x000c141b, 0x000c141c, 0x000c151c, 0x000c161d, 0x000c1720, 0x000c1820, 0x000b1821, 0x000b1822, 0x000b1924, 0x000b1924, 0x000c1a24, 0x000c1b24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000c1b24, 0x000d1b24, 0x000d1b24, 0x000d1a24, 0x000d1a24, 0x000d1b25, 0x000d1c25, 0x000d1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1a24, 0x000e1a24, 0x000c1b24, 0x000b1b24, 0x000a1c24, 0x000a1c24, 0x000a1c24, 0x000a1b24, 0x000c1b24, 0x000c1b24, 0x000d1b24, 0x000d1b24, 0x000c1a24, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000d1b24, 0x000e1c25, 0x000d1c27, 0x000f1f29, 0x0010202b, 0x00111f2b, 0x0010202b, 0x0012232f, 0x00152734, 0x001a2d3a, 0x00273a48, 0x002c3f4f, 0x00283b4a, 0x00283949, 0x002a3b4a, 0x002b3c4a, 0x00293a48, 0x00283844, 0x002a3845, 0x00303f4b, 0x00303f49, 0x0031404c, 0x0034414f, 0x00354250, 0x00384453, 0x003a4756, 0x003c4957, 0x003e4c59, 0x00424f5f, 0x00445263, 0x00475467, 0x00475568, 0x00465668, 0x00465668, 0x00475668, 0x00475667, 0x00475667, 0x00475566, 0x00475464, 0x00485364, 0x00465163, 0x00445060, 0x00434e5d, 0x00424d5c, 0x00414b5b, 0x00414858, 0x003f4454, 0x003c4150, 0x003c4150, 0x003c4150, 0x003c4150, 0x003c4250, 0x003c424f, 0x003c424f, 0x003c424e, 0x003c424f, 0x003c404e, 0x003d414f, 0x003c404e, 0x003d4250, 0x003f4454, 0x00434b5c, 0x00495465, 0x004b5769, 0x00485467, 0x00434d5e, 0x003c4250, 0x00373a48, 0x00323440, 0x002a2c38, 0x00262833, 0x00232530, 0x0021242c, 0x001f222b, 0x0020222b, 0x0023252e, 0x00272a33, 0x00282c36, 0x00282c36, 0x00292c36, 0x00292c36, 0x00292c37, 0x00282d37, 0x002a2f38, 0x002c313b, 0x002d323c, 0x002d323c, 0x002d313c, 0x002d313c, 0x002d313c, 0x002c303a, 0x002a2f39, 0x002b303a, 0x002b3039, 0x00292e38, 0x00282d38, 0x00282d38, 0x00292e38, 0x00292e38, 0x00292f39, 0x002b2f3b, 0x002a2d39, 0x00232630, 0x001d202a, 0x001c1f28, 0x001d2028, 0x001d2028, 0x001e2128, 0x0020242a, 0x0024262e, 0x00292c36, 0x00303440, 0x00363b48, 0x003c4452, 0x00454d5c, 0x00485261, 0x00485362, 0x00444e5e, 0x00424a5a, 0x003e4655, 0x00404654, 0x003f4654, 0x003e4653, 0x003c4453, 0x003b4350, 0x003a4250, 0x003a414e, 0x003b404e, 0x003b404e, 0x003b424e, 0x003c4451, 0x003f4755, 0x00404958, 0x00434c5b, 0x00444e5e, 0x00444e5e, 0x00444d5d, 0x00454f5e, 0x00485461, 0x00485665, 0x00495768, 0x004a5868, 0x004a5869, 0x0049586a, 0x004a586b, 0x00495a6c, 0x004a5b6d, 0x004c5c6f, 0x004c5d70, 0x004c5c6f, 0x004b5c6e, 0x004a5b6c, 0x0048586a, 0x00465668, 0x00455568, 0x00455467, 0x00445063, 0x00404c5c, 0x003e4a59, 0x003c4856, 0x003c4654, 0x003c4553, 0x003b4452, 0x00384250, 0x0036404f, 0x00343e4c, 0x00323b49, 0x00303844, 0x002f3742, 0x00303843, 0x00313944, 0x00303945, 0x00303b48, 0x002d3844, 0x0024303c, 0x00243240, 0x00283948, 0x00283c4a, 0x00273c4a, 0x0029404d, 0x002c4250, 0x002f4350, 0x002b3d4b, 0x0020303d, 0x001b2834, 0x00121c28, 0x000c1620, 0x000c161e, 0x000e1820, 0x00121c25, 0x0015202c, 0x0014232e, 0x0012232f, 0x00142532, 0x00162936, 0x00142937, 0x00132836, 0x00132734, 0x00122734, 0x00112634, 0x00102533, 0x00102532, 0x00102531, 0x00102530, 0x00102430, 0x0010232f, 0x0010242e, 0x0011242e, 0x0010242d, 0x0010232c, 0x0010222c, 0x0010222c, 0x000f232d, 0x000f242d, 0x000f232e, 0x0010232f, 0x0010232e, 0x0010242d, 0x0010232d, 0x0010232d, 0x0010232d, 0x0010232d, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x000e242d, 0x000d242d, 0x000e242d, 0x000f242d, 0x000f242d, 0x000f242f, 0x000f242f, 0x000f232e, 0x000f222e, 0x000f222e, 0x000e222e, 0x000e222e, 0x000e212d, 0x000e212d, 0x000d202c, 0x000c1f2c, 0x000c1e2a, 0x000c1e2a, 0x000c1e2a, 0x000c1e28, 0x000d1d26, 0x000d1d24, 0x000d1d24, 0x000d1d24, 0x000d1d24, 0x000c1c24, 0x000c1c25, 0x000d1c25, 0x000e1c25, 0x000e1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00132c32, 0x00143036, 0x0015363b, 0x00183c40, 0x00194044, 0x001b4649, 0x001d4b4e, 0x001f5154, 0x00225e68, 0x002da0c6, 0x002c94b3, 0x0025656c, 0x00256163, 0x00266364, 0x00266466, 0x00266466, 0x00266466, 0x00256364, 0x00256364, 0x00256264, 0x00256163, 0x00256163, 0x00256163, 0x00256163, 0x00266163, 0x00256163, 0x00256264, 0x00256364, 0x00266466, 0x00276466, 0x00266467, 0x00266467, 0x00266467, 0x00266467, 0x00266467, 0x00266466, 0x00266466, 0x00256264, 0x00246062, 0x00246062, 0x002c93b3, 0x002c9cc0, 0x00205458, 0x001e4f51, 0x001c4a4d, 0x001a4448, 0x001a4044, 0x00183a3e, 0x00153439, 0x00142e34, 0x00122c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091016, 0x00091016, 0x00091016, 0x00081017, 0x00081018, 0x00081018, 0x00091018, 0x00091018, 0x00091118, 0x000b131a, 0x000b131a, 0x000b141b, 0x000b141b, 0x000b141c, 0x000c151d, 0x000b151e, 0x000c171f, 0x000c1820, 0x000b1820, 0x00091921, 0x000a1921, 0x000a1a22, 0x000a1b23, 0x000c1b24, 0x000b1b24, 0x000b1b24, 0x000a1c24, 0x000a1c24, 0x000c1c26, 0x000d1c27, 0x000d1c27, 0x000d1b27, 0x000e1b27, 0x000d1c27, 0x000c1c27, 0x000c1c27, 0x000c1c25, 0x000c1c25, 0x000d1c25, 0x000d1c25, 0x000d1c25, 0x000e1c25, 0x000f1b25, 0x000e1b24, 0x000d1b24, 0x000d1b23, 0x000d1b23, 0x000d1b23, 0x000d1b24, 0x000d1c24, 0x000e1c24, 0x000c1c24, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b23, 0x000c1a23, 0x000c1a23, 0x000c1924, 0x000c1924, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c26, 0x000f1d28, 0x00101e28, 0x00101e29, 0x0010202b, 0x0011232e, 0x00142632, 0x00182a37, 0x00243744, 0x002c404e, 0x002a3d4c, 0x00263848, 0x00283948, 0x002b3a4a, 0x00293847, 0x00283644, 0x00293744, 0x00303d48, 0x00303e49, 0x0034404d, 0x0035414f, 0x0035414f, 0x00374350, 0x003b4654, 0x003c4855, 0x003e4c59, 0x00414f5e, 0x00445161, 0x00465464, 0x00445465, 0x00445565, 0x00445565, 0x00465667, 0x00475667, 0x00455667, 0x00465566, 0x00465565, 0x00485465, 0x00475264, 0x00424e5f, 0x00414c5c, 0x00424c5c, 0x00424a5b, 0x00414859, 0x003f4655, 0x003c4452, 0x003c4352, 0x003c4452, 0x003c4452, 0x003c4350, 0x003b424f, 0x003c4350, 0x003c4450, 0x003e4451, 0x003f4452, 0x00404553, 0x003f4452, 0x00414756, 0x00454c5c, 0x00495263, 0x004b5768, 0x004c586a, 0x00495465, 0x00414b5c, 0x003b4250, 0x00363c48, 0x00313540, 0x002a2c37, 0x00262934, 0x00242730, 0x0023252e, 0x0020232c, 0x0020232c, 0x0024252f, 0x00282c34, 0x002a2d38, 0x00292d38, 0x002b2e38, 0x002a2e39, 0x002a2e39, 0x00292e38, 0x002c303b, 0x002d323c, 0x002f343e, 0x002e333e, 0x002d323c, 0x002d323c, 0x002d323c, 0x002c303b, 0x002c303b, 0x002c313b, 0x002c303b, 0x002b2f3a, 0x00292e3a, 0x002a303c, 0x002b313c, 0x002b323d, 0x002c313d, 0x002c303c, 0x002b2e39, 0x00252832, 0x001e202a, 0x001c1f28, 0x001e2028, 0x0020212a, 0x0020242b, 0x0021242c, 0x0024262e, 0x00272a34, 0x002c303c, 0x00333844, 0x0038404d, 0x00424a58, 0x00485160, 0x00495262, 0x00475060, 0x00444c5c, 0x00414959, 0x00404858, 0x00404755, 0x003e4554, 0x003c4453, 0x003c4351, 0x003c4251, 0x003b4150, 0x003c414f, 0x003c4250, 0x003c4450, 0x003e4653, 0x00404856, 0x003f4857, 0x00404a59, 0x00434c5c, 0x00454e5f, 0x00444e5f, 0x00455060, 0x00485565, 0x004a5868, 0x0049586a, 0x00485869, 0x0049586b, 0x0049596c, 0x00495a6d, 0x00495b6e, 0x00495b6d, 0x00495c6e, 0x00495c6e, 0x004a5c6e, 0x004a5b6d, 0x0048596b, 0x00465868, 0x00445565, 0x00455465, 0x00455363, 0x00434f60, 0x00414c5c, 0x003e4858, 0x003c4654, 0x003b4452, 0x003b4452, 0x003a4450, 0x00384250, 0x0037404e, 0x00353f4c, 0x00323c49, 0x00313a48, 0x00303944, 0x00303844, 0x00303846, 0x00303946, 0x002f3b48, 0x002d3b48, 0x00263543, 0x00243444, 0x00283948, 0x00293c4b, 0x00283d4b, 0x00293d4c, 0x002c404e, 0x00324553, 0x0030414e, 0x00243441, 0x001b2834, 0x000d1924, 0x000a1520, 0x000c1720, 0x00101b23, 0x00141f28, 0x0016232e, 0x00152431, 0x00142432, 0x00142633, 0x00142835, 0x00142835, 0x00132834, 0x00132734, 0x00122733, 0x00112633, 0x00112632, 0x00112632, 0x00112632, 0x00102531, 0x00102430, 0x00102430, 0x0010242f, 0x0010242f, 0x0010242f, 0x0010232f, 0x0010232f, 0x0010242f, 0x0010242f, 0x0010242f, 0x0010242f, 0x00102430, 0x0010242f, 0x000f232e, 0x000f222e, 0x000f232e, 0x000f242e, 0x000f242e, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x000f242f, 0x000f242f, 0x000f242e, 0x0010242e, 0x0010242e, 0x0010242f, 0x00102430, 0x0010242f, 0x0010232f, 0x0010232f, 0x000f232f, 0x000f222e, 0x000e222e, 0x000e212d, 0x000e212d, 0x000c202a, 0x000c2029, 0x000d1f28, 0x000d1f28, 0x000d1e28, 0x000d1d26, 0x000d1d24, 0x000d1d25, 0x000d1d25, 0x000d1d25, 0x000d1c26, 0x000d1c26, 0x000d1c26, 0x000d1c26, 0x000d1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00153338, 0x0016363b, 0x00183d41, 0x001a4347, 0x001c484c, 0x001d4d50, 0x00205356, 0x0023616b, 0x0030a2c8, 0x002a849c, 0x00256163, 0x00266466, 0x00266467, 0x00276568, 0x00276568, 0x00276568, 0x00266467, 0x00266467, 0x00266466, 0x00256364, 0x00256264, 0x00266264, 0x00256163, 0x00256163, 0x00256264, 0x00256264, 0x00256364, 0x00256364, 0x00276466, 0x00276466, 0x00266467, 0x00266467, 0x00266467, 0x00266467, 0x00276466, 0x00256364, 0x00266264, 0x00246062, 0x00245e61, 0x002c93b3, 0x002c9cc0, 0x00205458, 0x001e4f51, 0x001c4a4d, 0x001a4448, 0x00183f43, 0x00173a3e, 0x00153439, 0x00142e34, 0x00122c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081016, 0x00081017, 0x00081017, 0x00081018, 0x00081018, 0x00081018, 0x00081016, 0x00081016, 0x00081218, 0x0009131a, 0x0009141a, 0x0008151b, 0x0008151b, 0x0009141c, 0x000a141d, 0x000b151e, 0x000c161f, 0x000b171f, 0x000a1820, 0x00081920, 0x00081a20, 0x00081b21, 0x00091b22, 0x000a1c24, 0x000c1b24, 0x000c1b24, 0x000a1c24, 0x000a1c24, 0x000c1c27, 0x000d1c28, 0x000d1c28, 0x000e1c27, 0x000d1c27, 0x000c1c27, 0x000a1d28, 0x000a1d27, 0x000b1d26, 0x000c1d26, 0x000c1c26, 0x000d1c26, 0x000d1c26, 0x000f1c26, 0x00101c26, 0x000f1b24, 0x000c1b21, 0x000c1c20, 0x000c1c20, 0x000c1b20, 0x000d1b21, 0x000e1c24, 0x000f1c24, 0x000c1c24, 0x000c1c25, 0x000c1c24, 0x000c1c24, 0x000c1c23, 0x000b1a22, 0x000b1a21, 0x000b1a22, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000f1c26, 0x000f1c26, 0x000f1d28, 0x0010212c, 0x0010232e, 0x00122430, 0x00162935, 0x0020323d, 0x002a3f4b, 0x002c404f, 0x00273949, 0x00263747, 0x00293948, 0x00293947, 0x00293744, 0x00293743, 0x002f3c47, 0x00303d48, 0x0034404e, 0x0035414f, 0x0035414f, 0x0035404f, 0x00384451, 0x003b4654, 0x003d4958, 0x00414e5c, 0x0043505f, 0x00445263, 0x00445364, 0x00445364, 0x00445464, 0x00455565, 0x00465465, 0x00445464, 0x00445464, 0x00455464, 0x00475464, 0x00465264, 0x00404c5d, 0x00404b5b, 0x00414c5c, 0x00414a5b, 0x00404958, 0x00404857, 0x003e4856, 0x003d4755, 0x003c4654, 0x003c4554, 0x003c4453, 0x003b4350, 0x003c4451, 0x003e4754, 0x00404855, 0x00404855, 0x00404855, 0x00434b58, 0x00444d5c, 0x00485060, 0x004d5767, 0x004e5868, 0x004b5565, 0x00485060, 0x00404757, 0x0039404f, 0x00373d4b, 0x00323743, 0x00292e39, 0x00262a34, 0x00252830, 0x0024272c, 0x0021242a, 0x0022242b, 0x00262730, 0x002b2d36, 0x002c303a, 0x002c303b, 0x002d323c, 0x002c313c, 0x002c303c, 0x002c303b, 0x002e333c, 0x0030343e, 0x00303440, 0x002f3440, 0x002e333f, 0x002d323e, 0x002e333d, 0x002d323c, 0x002d313c, 0x002c313b, 0x002c303a, 0x002a2f39, 0x002a2f3b, 0x002b303c, 0x002c333e, 0x002c343f, 0x002c333e, 0x002c303c, 0x002c2f39, 0x00262833, 0x001f222b, 0x001d2028, 0x001f2129, 0x0021222c, 0x0022242d, 0x0023252e, 0x00252730, 0x00272934, 0x002b2f39, 0x00303641, 0x00363e49, 0x003f4754, 0x00454e5c, 0x004a5162, 0x00495363, 0x00454f5f, 0x00444b5c, 0x00414959, 0x00404757, 0x003c4352, 0x003c4150, 0x003c4150, 0x003c4150, 0x003c4150, 0x003c4251, 0x003d4451, 0x003e4653, 0x003f4754, 0x00404856, 0x003e4856, 0x003d4756, 0x00404959, 0x00444d5f, 0x00454f60, 0x00465163, 0x00485667, 0x004a5869, 0x00485969, 0x00485868, 0x0048586a, 0x0048586b, 0x0048596c, 0x00485a6c, 0x00485b6d, 0x00485a6c, 0x0047596c, 0x0047596b, 0x0048586b, 0x00455768, 0x00435564, 0x00445462, 0x00455463, 0x00445260, 0x00434e5d, 0x0040495a, 0x003e4758, 0x003a4453, 0x00394350, 0x00384250, 0x003a4450, 0x003a4450, 0x0038414e, 0x0035404c, 0x00343d4b, 0x00343d4a, 0x00323c48, 0x00303a47, 0x00303946, 0x002f3948, 0x002e3b49, 0x002c3c49, 0x00283a47, 0x00283a49, 0x002a3d4c, 0x002b3e4c, 0x002a3e4c, 0x00283d4b, 0x00283b4b, 0x00304352, 0x0030424f, 0x00273744, 0x001f2c38, 0x000e1924, 0x000b1620, 0x000c1922, 0x00101e25, 0x0013212a, 0x00142430, 0x00152532, 0x00142532, 0x00142532, 0x00132734, 0x00132835, 0x00132734, 0x00112631, 0x00112630, 0x00112630, 0x00112630, 0x00112631, 0x00112632, 0x00102531, 0x00102531, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x000f242f, 0x000e232e, 0x000e222e, 0x000f232f, 0x000f242f, 0x000f242f, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x0010242f, 0x0010242e, 0x0010242e, 0x00102430, 0x00102430, 0x0010242f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222e, 0x000e212d, 0x000e212d, 0x000d202a, 0x000d2029, 0x000d2028, 0x000e1f28, 0x000e1f28, 0x000d1e26, 0x000d1d24, 0x000d1d25, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012242c, 0x00112a30, 0x00142e34, 0x00153338, 0x0017383c, 0x00183f43, 0x001b4448, 0x001c4a4d, 0x001e5053, 0x00205457, 0x0023636c, 0x0030a2c8, 0x002b859c, 0x00266467, 0x00276668, 0x0028686a, 0x0028686b, 0x0028686b, 0x0028686b, 0x0028686a, 0x00276769, 0x00276668, 0x00276568, 0x00256466, 0x00256466, 0x00256264, 0x00256264, 0x00256264, 0x00256264, 0x00256264, 0x00256466, 0x00256466, 0x00266467, 0x00276467, 0x00276467, 0x00276467, 0x00276467, 0x00256466, 0x00256264, 0x00256164, 0x00246062, 0x00245e61, 0x002c93b3, 0x002c9bc0, 0x001f5457, 0x001e4f51, 0x001d4a4d, 0x001b4448, 0x00183f43, 0x00183a3e, 0x00153439, 0x00142e34, 0x00132c32, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081016, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00081118, 0x00081117, 0x00081117, 0x00081218, 0x0008141a, 0x0009141a, 0x0008151b, 0x0008151b, 0x0009141c, 0x000a141d, 0x000b151e, 0x000c161f, 0x000b171f, 0x000a1820, 0x00081920, 0x00081a20, 0x00081b21, 0x00091b22, 0x000b1b24, 0x000c1b24, 0x000c1b24, 0x000a1c24, 0x000b1c25, 0x000c1c27, 0x000d1c28, 0x000d1c28, 0x000e1c27, 0x000e1c27, 0x000c1c27, 0x000a1d28, 0x000a1d28, 0x000b1d27, 0x000c1d26, 0x000c1d26, 0x000d1d26, 0x000e1c26, 0x000f1c26, 0x00101c26, 0x000f1b24, 0x000c1c22, 0x000c1c21, 0x000c1c21, 0x000c1c21, 0x000d1c22, 0x000e1c24, 0x000f1c24, 0x000d1c24, 0x000c1c25, 0x000c1c24, 0x000c1b23, 0x000c1b23, 0x000b1a22, 0x000b1a21, 0x000b1a22, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000f1c26, 0x000f1c26, 0x000f1d28, 0x000f202b, 0x0010222d, 0x00112430, 0x00142834, 0x001b2e38, 0x00263a46, 0x002c404e, 0x00293c4b, 0x00283848, 0x002b3a4b, 0x002b3a4a, 0x002b3947, 0x002a3844, 0x002f3c48, 0x00303e49, 0x0034404e, 0x00354250, 0x0034404f, 0x00343f4d, 0x0036414f, 0x00394552, 0x003e4a57, 0x00434f5c, 0x0043505e, 0x00435061, 0x00445263, 0x00445363, 0x00445464, 0x00445464, 0x00445464, 0x00445363, 0x00445363, 0x00445363, 0x00455363, 0x00445162, 0x00404d5d, 0x00404c5b, 0x00414c5b, 0x00414b59, 0x00404a58, 0x00404c59, 0x00404c5a, 0x00404a58, 0x00404856, 0x003d4654, 0x003c4454, 0x003d4454, 0x003f4755, 0x00404a58, 0x00424c5a, 0x00434d59, 0x00444d5a, 0x0046505c, 0x0046505d, 0x004a5463, 0x00505869, 0x004f5868, 0x004a5263, 0x00464c5d, 0x003f4555, 0x00383f4e, 0x00383f4c, 0x00313743, 0x002c303c, 0x00292e37, 0x00282c34, 0x0025292f, 0x0024272c, 0x0026272d, 0x00282932, 0x002d2e38, 0x002e303b, 0x002e333d, 0x002f343d, 0x002e333d, 0x002d313d, 0x002e323d, 0x0030353f, 0x00323640, 0x00323642, 0x00313541, 0x00303440, 0x00303440, 0x00303440, 0x002f343f, 0x002f343f, 0x002e333d, 0x002a2f39, 0x002a2f39, 0x002c303c, 0x002c323d, 0x002d343f, 0x002c3440, 0x002c343f, 0x002c333d, 0x002c303a, 0x00262934, 0x0020242c, 0x0020232a, 0x0021242c, 0x0024252f, 0x00242630, 0x00252831, 0x00292b34, 0x00292c37, 0x002c303a, 0x00313640, 0x00383f4a, 0x003c4451, 0x00424c5a, 0x00464e5f, 0x00485060, 0x00485161, 0x00465060, 0x00434c5c, 0x00414a5a, 0x003f4655, 0x003e4453, 0x003e4453, 0x00404454, 0x003f4453, 0x003d4452, 0x003d4553, 0x00404854, 0x00404854, 0x00404855, 0x003f4856, 0x003f4857, 0x0040495a, 0x00444d5e, 0x00454f61, 0x00445061, 0x00455364, 0x00475667, 0x00475868, 0x00475868, 0x00485868, 0x0048586a, 0x0048586b, 0x0048596b, 0x0048596c, 0x0048596b, 0x00465869, 0x00455668, 0x00465668, 0x00445566, 0x00425463, 0x00435462, 0x00455362, 0x00445260, 0x00424e5d, 0x00404959, 0x003d4757, 0x00394352, 0x00384250, 0x00384250, 0x003a4450, 0x0038434f, 0x0037404d, 0x0035404c, 0x00343e4c, 0x00343d4a, 0x00323c48, 0x00313b48, 0x00303947, 0x002f3947, 0x002e3c4a, 0x002f404c, 0x002c3e4b, 0x002c3f4c, 0x002d414f, 0x002d404e, 0x002b3f4c, 0x00293d4b, 0x00273948, 0x00293b4a, 0x00293a47, 0x00243441, 0x001f2c38, 0x00111c27, 0x000c1822, 0x000d1a24, 0x00122028, 0x0015242e, 0x00152632, 0x00152834, 0x00142734, 0x00142733, 0x00132734, 0x00122734, 0x00122734, 0x00112631, 0x00112630, 0x00112630, 0x00112630, 0x00112631, 0x00112632, 0x00102531, 0x00102531, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x000f242f, 0x000e232e, 0x000e222e, 0x000f232f, 0x000f242f, 0x000f242f, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x0010242f, 0x0010242f, 0x0010242f, 0x00102430, 0x00102430, 0x00102430, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222e, 0x000e212d, 0x000e212d, 0x000d202a, 0x000d2029, 0x000d2028, 0x000e1f28, 0x000e1f28, 0x000d1e26, 0x000d1d24, 0x000d1d25, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000d1d26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0013282e, 0x00102a30, 0x00142e34, 0x00153439, 0x00183a3e, 0x00183f43, 0x001c4649, 0x001d4b4e, 0x001f5154, 0x00215659, 0x0024646d, 0x0031a3c8, 0x00309cbe, 0x002f95b2, 0x002f96b3, 0x003097b3, 0x003097b3, 0x003096b3, 0x003097b3, 0x003097b3, 0x002f96b3, 0x002f96b3, 0x002f94b2, 0x002f94b2, 0x002e94b2, 0x002e94b2, 0x002d94b2, 0x002d94b2, 0x002d94b2, 0x002d94b2, 0x002d94b2, 0x002d94b2, 0x002e94b2, 0x002e94b2, 0x002e94b2, 0x002e94b2, 0x002d94b2, 0x002d94b2, 0x002d94b2, 0x002d93b1, 0x002c92b1, 0x002c91b1, 0x002e9fc4, 0x002c9bc0, 0x00205256, 0x001d4c50, 0x001c484c, 0x001a4347, 0x00183d41, 0x00183a3e, 0x00153439, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081016, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00081118, 0x00081117, 0x00081117, 0x00081218, 0x0008141a, 0x0008141a, 0x0008151b, 0x0008151b, 0x0009141c, 0x000a141d, 0x000b151e, 0x000c161f, 0x000b171f, 0x000a181f, 0x0009191f, 0x0009191f, 0x000a1a20, 0x000b1b21, 0x000c1b23, 0x000c1b23, 0x000c1b24, 0x000c1b24, 0x000c1c26, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000e1c28, 0x000e1c28, 0x000c1c28, 0x000a1d29, 0x000a1d28, 0x000b1d28, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000c1c28, 0x000e1c28, 0x000f1c28, 0x000d1c26, 0x000c1c24, 0x000b1c24, 0x000c1c24, 0x000c1c24, 0x000d1c24, 0x000e1c24, 0x000e1c24, 0x000e1c24, 0x000e1c25, 0x000d1b24, 0x000c1a22, 0x000b1a21, 0x000b1a21, 0x000b1a21, 0x000b1a22, 0x000c1924, 0x000c1924, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000e1c25, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000e1c28, 0x000d1e29, 0x000e202c, 0x00102430, 0x00132632, 0x00182b35, 0x00203541, 0x00293e4c, 0x002c3e4c, 0x002c3d4c, 0x002d3c4c, 0x002c3b4a, 0x002b3a49, 0x002b3947, 0x002e3c48, 0x00303e4b, 0x0033404e, 0x0034414f, 0x0034404f, 0x00343f4d, 0x0034404e, 0x00384450, 0x003d4955, 0x00424e5a, 0x00404e5c, 0x00404d5c, 0x00404f5e, 0x00425160, 0x00435260, 0x00415160, 0x00435261, 0x00445261, 0x00445261, 0x00445261, 0x00445261, 0x00445160, 0x00414f5e, 0x003f4c5b, 0x00404b59, 0x00414b59, 0x00424c5a, 0x00424c5b, 0x00424d5b, 0x00424c5a, 0x00424a58, 0x003e4756, 0x003e4554, 0x003e4554, 0x00414958, 0x00444c5a, 0x00444d5c, 0x0046505c, 0x00454f5c, 0x0048515f, 0x004c5664, 0x00505a6a, 0x004f5969, 0x004d5767, 0x00485060, 0x0042495a, 0x003c4253, 0x003c4251, 0x003c4350, 0x00333945, 0x002f333f, 0x002c303b, 0x002b2e38, 0x00282a32, 0x0025282e, 0x00272830, 0x002a2c34, 0x002d3038, 0x002e303a, 0x002e323c, 0x002e333d, 0x002f343e, 0x002f3440, 0x00303440, 0x00333741, 0x00343843, 0x00343944, 0x00333843, 0x00333743, 0x00333843, 0x00333743, 0x00323642, 0x00323742, 0x0030343f, 0x002c303a, 0x002c303b, 0x002e333e, 0x00303540, 0x00303742, 0x002f3742, 0x002e3641, 0x002f3440, 0x002e313c, 0x00282c36, 0x00242730, 0x0023262e, 0x00242830, 0x00282934, 0x00282a35, 0x002a2d38, 0x002d2f3a, 0x002d303b, 0x002e323d, 0x00343844, 0x0038404b, 0x003b4350, 0x003f4856, 0x00444c5c, 0x00454f5d, 0x00475260, 0x00485363, 0x00455060, 0x00444c5d, 0x00434b5a, 0x00414857, 0x00404756, 0x00414756, 0x003f4454, 0x003c4352, 0x003d4453, 0x00404854, 0x003f4754, 0x00404854, 0x00414a58, 0x00424c5b, 0x00414b5c, 0x00424c5d, 0x00455062, 0x00485364, 0x00465464, 0x00445364, 0x00455465, 0x00445465, 0x00465668, 0x00475769, 0x0048586a, 0x0047586a, 0x0048596b, 0x0049596b, 0x0047576a, 0x00465668, 0x00475668, 0x00445566, 0x00435462, 0x00425260, 0x00445261, 0x0044515f, 0x00424d5c, 0x00404959, 0x003c4656, 0x003a4452, 0x00394350, 0x00394351, 0x003a4450, 0x0035404c, 0x00343e4b, 0x00343e4a, 0x00343d4b, 0x00323c4a, 0x00313c48, 0x00313b48, 0x00303947, 0x002d3845, 0x002c3a48, 0x0030404d, 0x002f404e, 0x002f4150, 0x00304452, 0x002d404d, 0x00263a48, 0x00283b49, 0x00283847, 0x00243443, 0x00223340, 0x0020303c, 0x001d2b36, 0x00121e28, 0x000c1822, 0x000d1a24, 0x00122029, 0x0016242f, 0x00172733, 0x00152836, 0x00142836, 0x00142835, 0x00132734, 0x00112634, 0x00112633, 0x00112630, 0x00112630, 0x00122831, 0x00132831, 0x00132832, 0x00112632, 0x00102531, 0x00102531, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x000f242f, 0x000f242f, 0x000f242f, 0x000f242f, 0x000f242f, 0x000f2430, 0x00102430, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102430, 0x00112430, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222e, 0x000e212d, 0x000e212d, 0x000d202a, 0x000d2029, 0x000d2028, 0x000e1f28, 0x000e1f28, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153439, 0x00173a3e, 0x00194044, 0x001c4649, 0x001d4c50, 0x00205254, 0x0021585a, 0x00246066, 0x002e94b4, 0x0032a5c9, 0x0033a5c9, 0x0034a6c9, 0x0034a6c9, 0x0034a7c9, 0x0034a7c9, 0x0034a7c9, 0x0034a6c9, 0x0034a6c9, 0x0033a6c9, 0x0033a5c9, 0x0032a5c9, 0x0032a5c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0031a4c9, 0x0030a4c9, 0x0030a4c9, 0x0030a4c9, 0x002ea3c9, 0x002da1c9, 0x0027839f, 0x001f5054, 0x001d4b4e, 0x001b4649, 0x00194245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00102a30, 0x0013282e, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00071018, 0x00081018, 0x00081018, 0x00081118, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00081218, 0x0008141a, 0x0008141a, 0x0008151b, 0x0008151b, 0x0009141c, 0x000a141d, 0x000b151e, 0x000c161f, 0x000b171f, 0x000b1820, 0x000a191f, 0x000a1920, 0x000a1a20, 0x000b1b21, 0x000c1b23, 0x000d1b23, 0x000c1b24, 0x000c1b24, 0x000c1c26, 0x000d1c28, 0x000d1c28, 0x000d1c28, 0x000f1c28, 0x000e1c28, 0x000c1c28, 0x000b1d29, 0x000b1d29, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000c1d28, 0x000c1c28, 0x000e1c28, 0x000f1c28, 0x000e1c27, 0x000c1c24, 0x000c1c24, 0x000c1c24, 0x000c1c24, 0x000d1c24, 0x000e1c24, 0x000e1c24, 0x000e1c24, 0x000e1c25, 0x000d1b24, 0x000c1a22, 0x000b1a21, 0x000b1a21, 0x000b1a21, 0x000b1a22, 0x000c1a24, 0x000c1a24, 0x000d1b24, 0x000d1b24, 0x000e1c25, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000f1c26, 0x000e1c28, 0x000d1e28, 0x000e202c, 0x0010232f, 0x00122531, 0x00152834, 0x001c313d, 0x00273c49, 0x002b3f4c, 0x002c3e4c, 0x002c3c4c, 0x002a3948, 0x00293847, 0x002c3a48, 0x002c3b48, 0x002e3d4a, 0x00313f4c, 0x0033404e, 0x0033404e, 0x0034404e, 0x0034404e, 0x00384450, 0x003c4854, 0x003d4955, 0x003c4a58, 0x003e4c5b, 0x003f4d5c, 0x003f4d5c, 0x00404f5d, 0x00404f5d, 0x00415060, 0x00435160, 0x00445260, 0x00445160, 0x00445160, 0x00445160, 0x0043505f, 0x00404d5b, 0x00404c5a, 0x00414c5a, 0x00434c5b, 0x00434d5c, 0x00414d5c, 0x00434d5c, 0x00444c5c, 0x003f4858, 0x003e4655, 0x00404857, 0x00444c5b, 0x00464f5d, 0x00464f5e, 0x0045505e, 0x0047515f, 0x00495462, 0x004f5969, 0x00515c6c, 0x004c5868, 0x00495363, 0x00434c5c, 0x003e4657, 0x003c4454, 0x003e4655, 0x003f4654, 0x00363c4a, 0x00323744, 0x00303541, 0x002f323e, 0x002c3038, 0x002a2d36, 0x002b2e38, 0x002c3039, 0x002d303b, 0x002e323c, 0x002f343d, 0x0030343f, 0x00303540, 0x00323743, 0x00343945, 0x00373c48, 0x00373c48, 0x00383c49, 0x00363b48, 0x00363a46, 0x00353a46, 0x00343945, 0x00343944, 0x00343a45, 0x00333844, 0x002f3440, 0x002e3340, 0x00303542, 0x00323845, 0x00323946, 0x00303844, 0x002e3643, 0x00303542, 0x002f333f, 0x002c303a, 0x00292c36, 0x00292c35, 0x002b2e37, 0x002c303d, 0x002d3140, 0x002e3341, 0x00303442, 0x00303543, 0x00303744, 0x00353c48, 0x0038404c, 0x003a424f, 0x003c4453, 0x00414859, 0x00434c5c, 0x0044505d, 0x00485362, 0x00485464, 0x00485160, 0x00464f5e, 0x00434b59, 0x00434a58, 0x00444958, 0x00404655, 0x003c4454, 0x003b4452, 0x003d4654, 0x00404756, 0x00414855, 0x00444b59, 0x00474f5e, 0x00434c5c, 0x00404a5c, 0x00444f60, 0x00485465, 0x00475465, 0x00445162, 0x00435162, 0x00445263, 0x00445466, 0x00455668, 0x00465769, 0x00475769, 0x00485769, 0x0048576a, 0x00485669, 0x00475568, 0x00485468, 0x00455465, 0x00425262, 0x0040505f, 0x00435261, 0x0044515f, 0x00414d5c, 0x00404959, 0x003d4656, 0x003b4453, 0x003a4451, 0x003a4451, 0x0038434f, 0x00343d49, 0x00333d49, 0x00343d49, 0x00343e4b, 0x00323c49, 0x00313b48, 0x00313b48, 0x00303948, 0x002b3644, 0x00283643, 0x002f3f4c, 0x0030414f, 0x002e414f, 0x00324654, 0x002e414f, 0x00213443, 0x00223442, 0x00263544, 0x00212f3d, 0x00202d39, 0x00202d39, 0x001d2a35, 0x00131f29, 0x000d1823, 0x000d1a24, 0x00122029, 0x0016242f, 0x00172733, 0x00152936, 0x00152937, 0x00142836, 0x00132834, 0x00122734, 0x00122734, 0x00122731, 0x00122731, 0x00132831, 0x00142832, 0x00132832, 0x00122733, 0x00102531, 0x00102531, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x000f242f, 0x000f242f, 0x000f242f, 0x000f242f, 0x00102430, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00112430, 0x00112430, 0x00112430, 0x0010232f, 0x0010232f, 0x000f222e, 0x000e212d, 0x000e212d, 0x000d202a, 0x000d2029, 0x000d2028, 0x000e1f28, 0x000e1f28, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012282e, 0x00132c32, 0x00142e34, 0x00153439, 0x00183c40, 0x00194044, 0x001b474b, 0x001d4d50, 0x00205356, 0x0022585b, 0x00245d60, 0x0026666b, 0x00287078, 0x0029727b, 0x002a747c, 0x002b757e, 0x002b767e, 0x002b767e, 0x002a757e, 0x002b757d, 0x002a747c, 0x002a737c, 0x0029727b, 0x00287079, 0x00287078, 0x00286e77, 0x00276d76, 0x00276c76, 0x00276c75, 0x00266c75, 0x00266b74, 0x00266b74, 0x00276b74, 0x00276b74, 0x00266b74, 0x00266b74, 0x00256a74, 0x00256973, 0x00256872, 0x00246771, 0x00236670, 0x0023646f, 0x0021606c, 0x00205458, 0x001d4d50, 0x001c4a4d, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00071018, 0x00081018, 0x00081018, 0x00081118, 0x00081118, 0x00081118, 0x00091118, 0x00091118, 0x00081218, 0x0008141a, 0x0008141a, 0x0008141a, 0x0009141b, 0x000a141c, 0x000a141d, 0x000b151e, 0x000c161f, 0x000c171f, 0x000c1820, 0x000c1821, 0x000b1821, 0x000b1922, 0x000c1a22, 0x000c1b23, 0x000d1b24, 0x000c1b25, 0x000b1c26, 0x000c1c27, 0x000c1c28, 0x000c1c28, 0x000c1c28, 0x000d1c28, 0x000e1d27, 0x000d1d28, 0x000c1e29, 0x000c1e29, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1d27, 0x000c1d27, 0x000e1d27, 0x000f1c27, 0x000f1d27, 0x000d1d26, 0x000d1d25, 0x000d1d24, 0x000d1d24, 0x000d1c24, 0x000e1c24, 0x000e1c24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000c1b24, 0x000c1c23, 0x000c1c23, 0x000c1b24, 0x000c1b24, 0x000c1c24, 0x000d1c25, 0x000e1c26, 0x000e1c26, 0x000e1d26, 0x000e1d26, 0x000f1c26, 0x000f1c26, 0x000f1c27, 0x000e1d28, 0x000e1f29, 0x000f202c, 0x00102330, 0x00132632, 0x00142834, 0x001a2f3c, 0x00243847, 0x00293d4c, 0x002b3f4d, 0x002c3d4e, 0x00283848, 0x00293948, 0x002c3c4a, 0x002a3a47, 0x002c3c48, 0x00303e4a, 0x0032404c, 0x0033404d, 0x0033404e, 0x0034414f, 0x00364450, 0x003c4955, 0x003c4a57, 0x003c4b58, 0x003e4c5a, 0x003f4c5c, 0x003f4d5c, 0x00404e5d, 0x00404d5c, 0x00414f5e, 0x0042505f, 0x0043505e, 0x0042505f, 0x0043505f, 0x0043505f, 0x0043505d, 0x00414d5b, 0x00404c5a, 0x00404c5a, 0x00404c5a, 0x00404c5a, 0x00404c5b, 0x00434e5c, 0x00434c5c, 0x003e4857, 0x003f4858, 0x00444c5b, 0x0048505f, 0x00485160, 0x00485161, 0x00475261, 0x00485463, 0x004c5766, 0x004f5a6a, 0x004f596a, 0x004b5566, 0x00464f60, 0x003f4858, 0x003d4554, 0x003e4756, 0x003d4655, 0x003c4453, 0x00373f4c, 0x00343c4a, 0x00343a48, 0x00343946, 0x00333843, 0x00303641, 0x002f3540, 0x002f343f, 0x002f3540, 0x00303640, 0x00323843, 0x00343845, 0x00343948, 0x00373c4a, 0x00393f4c, 0x003b414e, 0x003b414f, 0x003c424f, 0x003b404d, 0x003b404d, 0x003a404c, 0x00393e4b, 0x00383d4a, 0x00373d4a, 0x00363c49, 0x00343a47, 0x00333846, 0x00333947, 0x00343948, 0x00333a49, 0x00303847, 0x00303844, 0x002f3644, 0x002f3441, 0x002d323e, 0x002b303c, 0x002c313c, 0x00303440, 0x00323846, 0x00313948, 0x00333a48, 0x00343a49, 0x00343a49, 0x00343a48, 0x00363e4b, 0x003a424e, 0x003b4350, 0x003d4554, 0x00404858, 0x00434c5a, 0x00444e5c, 0x00485161, 0x00495464, 0x00495463, 0x00475160, 0x00444c5c, 0x00444c5c, 0x00444b5c, 0x00434a5b, 0x00404a5a, 0x00404959, 0x00424c5c, 0x00444d5d, 0x00434b5b, 0x00424a59, 0x00444c5a, 0x00424c5b, 0x00404a5b, 0x00434d5e, 0x00455061, 0x00435060, 0x00424f5f, 0x00424f5f, 0x00425061, 0x00435264, 0x00445465, 0x00445465, 0x00445364, 0x00455465, 0x00455467, 0x00465467, 0x00465467, 0x00475366, 0x00465264, 0x00445061, 0x0041505f, 0x00425060, 0x0042505e, 0x00404d5c, 0x00404b5b, 0x003e4958, 0x003c4554, 0x003b4452, 0x003b4451, 0x00384250, 0x00333c4a, 0x00333d4a, 0x00343e4b, 0x00343e4b, 0x00333c49, 0x00313b48, 0x00303a47, 0x00303a47, 0x002c3744, 0x00263340, 0x002a3a47, 0x0030424e, 0x002f4350, 0x00344857, 0x002c4050, 0x00203442, 0x00233340, 0x00233240, 0x001f2d3b, 0x001e2c38, 0x00212f39, 0x001c2934, 0x00121f29, 0x000e1924, 0x000e1b24, 0x00122028, 0x0015242e, 0x00162633, 0x00152836, 0x00162a36, 0x00152a36, 0x00142935, 0x00142834, 0x00142834, 0x00132834, 0x00132833, 0x00132833, 0x00142833, 0x00132833, 0x00112733, 0x00112632, 0x00112531, 0x00112431, 0x00112430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x0011232f, 0x0011232f, 0x0011232f, 0x0011232f, 0x0010232f, 0x000f232f, 0x000f2330, 0x00102430, 0x00102430, 0x00102432, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00112431, 0x00112431, 0x00112431, 0x00112431, 0x00112430, 0x00112430, 0x00102430, 0x0010232e, 0x000f222d, 0x000f222c, 0x000e212c, 0x000e212c, 0x000d202a, 0x000d2029, 0x000d1f28, 0x000e1f28, 0x000e1f28, 0x000e1d28, 0x000e1d28, 0x000e1e28, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012282e, 0x00132c32, 0x00142e34, 0x00143439, 0x00183c40, 0x00194245, 0x001c474b, 0x001d4d50, 0x00205356, 0x0022595c, 0x00246064, 0x00286f7b, 0x0027686b, 0x0028696c, 0x00296c6e, 0x00296d6f, 0x002a6e70, 0x002b6f70, 0x002a6e70, 0x00296d6f, 0x002a6c6f, 0x00296b6d, 0x0028696c, 0x0028686a, 0x00276668, 0x00266467, 0x00256364, 0x00256264, 0x00256163, 0x00246062, 0x00245f61, 0x00245e60, 0x00245e60, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00245c5e, 0x00235a5c, 0x0022595c, 0x0021585a, 0x00205558, 0x00205356, 0x001e5053, 0x001c4b4e, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00143439, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081016, 0x00081015, 0x00081016, 0x00081118, 0x000a1219, 0x000a1219, 0x000b131a, 0x000b131a, 0x0009131a, 0x0009141a, 0x0009141a, 0x0009141a, 0x0009141b, 0x000a141d, 0x000a141d, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c1821, 0x000c1822, 0x000c1822, 0x000c1924, 0x000c1923, 0x000d1b23, 0x000d1c25, 0x000c1c27, 0x000b1c27, 0x000b1e28, 0x000c1f28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000e1f28, 0x000e1f28, 0x000e1f2a, 0x000e1f2a, 0x000e1f2a, 0x000e1f2a, 0x000e1f28, 0x000e2026, 0x000e1f26, 0x000f1e26, 0x00101e26, 0x00101e26, 0x000e1e27, 0x000e1e27, 0x000e1e25, 0x000e1e25, 0x000e1d24, 0x000f1c24, 0x000f1c24, 0x000d1b24, 0x000d1b24, 0x000d1b24, 0x000f1c26, 0x000f1c26, 0x000d1d24, 0x000d1d24, 0x000c1c24, 0x000b1c25, 0x000b1c25, 0x000c1d26, 0x000c1e27, 0x000c1e27, 0x000e1e27, 0x000e1e27, 0x000f1d27, 0x00101d27, 0x000f1d27, 0x000f1e28, 0x000f202a, 0x0010212d, 0x00112430, 0x00132632, 0x00142834, 0x00192e3c, 0x00223746, 0x00273c4b, 0x002b3f4e, 0x002c3f50, 0x00293c4c, 0x00293c4b, 0x002b3c4b, 0x00283a47, 0x00293a45, 0x002c3c47, 0x00303d4a, 0x00303e4b, 0x0032404c, 0x0034414f, 0x00364450, 0x003b4856, 0x003c4a57, 0x003c4a57, 0x003d4a58, 0x003d4b5a, 0x00404d5c, 0x00424f5e, 0x00404d5c, 0x00404d5c, 0x00404d5c, 0x00404c5a, 0x003f4c59, 0x00404b58, 0x00404b59, 0x00404c58, 0x003f4a57, 0x003f4a58, 0x003e4a58, 0x003e4958, 0x003f4a58, 0x00404c59, 0x00424e5c, 0x00404b58, 0x003c4855, 0x003f4857, 0x00444e5c, 0x0046505f, 0x00465160, 0x00455160, 0x00455362, 0x00485464, 0x004a5767, 0x004b5768, 0x004a5466, 0x00474f60, 0x00434b5a, 0x003d4553, 0x003c4451, 0x003c4553, 0x003c4554, 0x003a4351, 0x0037404e, 0x0038404f, 0x0039404f, 0x003b4150, 0x0039414e, 0x0038404d, 0x00343d4b, 0x00323c48, 0x00313b48, 0x00333c48, 0x00343d4a, 0x0039404e, 0x003a4050, 0x003b4150, 0x003c4250, 0x003c4451, 0x003e4654, 0x00404856, 0x00404854, 0x003e4654, 0x003c4451, 0x003c4450, 0x0039414e, 0x0039414e, 0x0039414e, 0x0038404d, 0x00373f4d, 0x00363e4d, 0x00363d4d, 0x00353c4c, 0x00313b49, 0x00303a47, 0x00303a48, 0x00313948, 0x00303844, 0x00303744, 0x00303844, 0x00353c48, 0x0038404d, 0x00384150, 0x003a4351, 0x003a4150, 0x0038404f, 0x00373f4d, 0x0038404d, 0x003c444f, 0x003c444f, 0x003e4752, 0x003f4754, 0x00424a58, 0x00464e5c, 0x00475060, 0x00485464, 0x004a5565, 0x00495465, 0x00455060, 0x00424c5c, 0x00424c5c, 0x00424c5c, 0x00414c5c, 0x00434d5d, 0x00455060, 0x00434e5e, 0x00404a5a, 0x003f4857, 0x00404a58, 0x00424b5a, 0x00424c5c, 0x00444d5d, 0x00434d5d, 0x00404d5c, 0x00414e5d, 0x00414e5d, 0x00404d5c, 0x00414f5e, 0x0040505e, 0x0040505e, 0x00415060, 0x00445362, 0x00445262, 0x00445363, 0x00445364, 0x00455263, 0x00465162, 0x00455060, 0x00424f5d, 0x00404e5d, 0x003f4c5c, 0x003f4c5c, 0x003f4c5c, 0x003e4c59, 0x003d4857, 0x003c4553, 0x003b4451, 0x00384150, 0x00343d4c, 0x00343e4c, 0x00353f4c, 0x00343f4c, 0x00333d49, 0x00303b48, 0x002f3a48, 0x002f3a48, 0x002d3947, 0x00283543, 0x00293845, 0x002e3f4c, 0x00304352, 0x00324656, 0x002d4250, 0x00243845, 0x00233440, 0x0020303c, 0x001c2b36, 0x001f2f38, 0x0023323c, 0x001a2832, 0x00121f29, 0x000f1b24, 0x000f1b24, 0x00111e27, 0x0014222d, 0x00172532, 0x00152834, 0x00162935, 0x00162b37, 0x00152b36, 0x00142c34, 0x00142b34, 0x00142a35, 0x00142a35, 0x00142934, 0x00142834, 0x00132733, 0x00112632, 0x00112632, 0x00122632, 0x00122431, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x0011232f, 0x0011232f, 0x0011232f, 0x0011232f, 0x0010222e, 0x000f222e, 0x000f242f, 0x00102430, 0x000f2432, 0x000f2534, 0x00102532, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00112632, 0x00102531, 0x00102531, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x0010232f, 0x0010232c, 0x000f232b, 0x000f222b, 0x000e212a, 0x000e212a, 0x000d202b, 0x000d202a, 0x000d1f28, 0x000e1f28, 0x000e1f28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012282e, 0x00132c32, 0x00142e34, 0x00143439, 0x00183c40, 0x00194245, 0x001c474b, 0x001d4d50, 0x00205356, 0x0022595c, 0x00256870, 0x0031a3c6, 0x003094b1, 0x002c7e8e, 0x002a6f72, 0x002b6f70, 0x002c7071, 0x002c7071, 0x002c7071, 0x002b6f70, 0x002a6e70, 0x00296c6f, 0x00296b6d, 0x0028686b, 0x00286769, 0x00276568, 0x00266466, 0x00266264, 0x00246062, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00245c5e, 0x00245c5e, 0x00235a5c, 0x0022595c, 0x0022585b, 0x0021585a, 0x00205558, 0x00205356, 0x001f5154, 0x001d4d50, 0x001c4a4d, 0x001b4649, 0x001a4245, 0x00183d41, 0x0017383c, 0x00153439, 0x00142e34, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081015, 0x00081014, 0x00081015, 0x00081118, 0x000a1219, 0x000a1219, 0x000b131a, 0x000b131a, 0x000a131a, 0x0009141a, 0x0009141a, 0x0009141a, 0x0009141b, 0x000a141d, 0x000a141d, 0x000b151e, 0x000c161f, 0x000c1720, 0x000c1821, 0x000c1822, 0x000c1822, 0x000c1924, 0x000c1923, 0x000d1b23, 0x000d1c25, 0x000c1c27, 0x000b1c27, 0x000c1e28, 0x000c1f28, 0x000d1e28, 0x000e1f29, 0x000e1f29, 0x000f1f29, 0x000e202b, 0x000e202c, 0x000e202c, 0x000e202c, 0x000e202c, 0x000e202b, 0x000f2028, 0x000f2027, 0x00102027, 0x00102027, 0x00101f27, 0x000f1f28, 0x000f1f28, 0x000f1f27, 0x000f1f26, 0x000e1d25, 0x000f1c24, 0x000f1c24, 0x000d1c24, 0x000d1b24, 0x000d1b24, 0x000f1c26, 0x000f1c26, 0x000e1d25, 0x000d1d24, 0x000c1d24, 0x000b1c25, 0x000b1c25, 0x000c1d26, 0x000c1e27, 0x000c1e27, 0x000e1e27, 0x000e1e27, 0x000f1e27, 0x00101d27, 0x00101d28, 0x000f1f29, 0x0010202a, 0x0010212d, 0x00112430, 0x00142632, 0x00142834, 0x00192e3c, 0x00213645, 0x00273c4b, 0x002b3f4e, 0x002c3f50, 0x002b3e4e, 0x002b3e4d, 0x002a3c4b, 0x00273845, 0x00273845, 0x002b3a46, 0x00303c4a, 0x002f3c4a, 0x0033404e, 0x0034414f, 0x00364350, 0x003a4754, 0x003c4856, 0x003c4956, 0x003c4857, 0x003c4958, 0x003f4c5b, 0x00404e5c, 0x00404d5c, 0x003f4c5b, 0x003d4a58, 0x003c4855, 0x003c4855, 0x003b4754, 0x003b4754, 0x003c4854, 0x003b4753, 0x003b4754, 0x003c4855, 0x003c4856, 0x003e4958, 0x00404b58, 0x003f4a58, 0x003e4957, 0x003e4a58, 0x00404c5a, 0x00444f5c, 0x0044505d, 0x00455060, 0x00475262, 0x00485464, 0x00485665, 0x00495766, 0x004a5567, 0x00475062, 0x00414959, 0x003f4755, 0x003c4450, 0x003b4350, 0x00394150, 0x0038404f, 0x0038404e, 0x0038404f, 0x003c4452, 0x003e4654, 0x00404a58, 0x00414a58, 0x00404958, 0x003c4554, 0x00384250, 0x0037404f, 0x0038414f, 0x00384250, 0x003d4554, 0x00404858, 0x00414858, 0x00404857, 0x003f4856, 0x00414a58, 0x00444c5b, 0x00444d5b, 0x00424a59, 0x00414857, 0x00404856, 0x003f4755, 0x003e4754, 0x003d4654, 0x003c4654, 0x003c4454, 0x003c4454, 0x003b4353, 0x00394152, 0x00384050, 0x0036404e, 0x00374050, 0x00384050, 0x00373f4d, 0x0037404c, 0x0039414e, 0x003d4653, 0x003f4858, 0x00404b5a, 0x00424c5b, 0x003f4757, 0x003b4353, 0x0038404f, 0x0038404d, 0x003a434f, 0x003a424e, 0x003c444f, 0x003c4450, 0x00404855, 0x00444c5a, 0x00444e5d, 0x00495464, 0x004a5567, 0x004a5567, 0x00485364, 0x00444e60, 0x00434c5e, 0x00444d5e, 0x00424d5d, 0x00424e5d, 0x00444f5f, 0x00445060, 0x00414c5c, 0x003f4858, 0x00404a58, 0x00414c5a, 0x00424c5c, 0x00434c5c, 0x00424c5c, 0x00414e5d, 0x00414e5d, 0x00404e5d, 0x00404c5c, 0x00404d5c, 0x003f4e5c, 0x00404f5d, 0x0040505f, 0x00404e5d, 0x00404f5e, 0x00415060, 0x00435261, 0x00435160, 0x00445060, 0x00445060, 0x00424f5d, 0x00404c5d, 0x003e4b5c, 0x003c495b, 0x003c4a5a, 0x003e4c59, 0x003e4a58, 0x003c4654, 0x003a4451, 0x0037404f, 0x0038414f, 0x00384150, 0x0036404d, 0x00353f4c, 0x00333c49, 0x00303a47, 0x002e3947, 0x002d3947, 0x002d3946, 0x002b3846, 0x002b3b48, 0x002c3e4c, 0x00304352, 0x00304454, 0x002d4250, 0x00283b48, 0x00233542, 0x001e2e39, 0x001b2b36, 0x0020303a, 0x0024343d, 0x00192831, 0x0013202a, 0x00111d26, 0x000f1b24, 0x00101d26, 0x0013202c, 0x00152431, 0x00142634, 0x00152834, 0x00162b37, 0x00162c37, 0x00142c35, 0x00142b35, 0x00142a35, 0x00142a35, 0x00142934, 0x00142834, 0x00132733, 0x00112632, 0x00112632, 0x00122632, 0x00122431, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x0011232f, 0x0011232f, 0x0011232f, 0x0011232f, 0x0010222e, 0x000f222e, 0x000f242f, 0x00102430, 0x000f2432, 0x000f2534, 0x00102532, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00112632, 0x00102531, 0x00102531, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x0010232f, 0x0010232c, 0x000f232b, 0x000f222b, 0x000e212a, 0x000e212a, 0x000d202b, 0x000d202a, 0x000d1f28, 0x000e1f28, 0x000e1f28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012282e, 0x00132c32, 0x00142e34, 0x00153439, 0x00183c40, 0x00194245, 0x001b474b, 0x001d4d50, 0x00205356, 0x0023595c, 0x00256871, 0x0033a6ca, 0x0031a0c1, 0x0034a6c8, 0x00339ebc, 0x002f889a, 0x002c767c, 0x002b7173, 0x002b7173, 0x002b7072, 0x002c7071, 0x00296d6f, 0x00296c6e, 0x0028696c, 0x0028686a, 0x00276668, 0x00266466, 0x00266264, 0x00256062, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0022595c, 0x0022585b, 0x0021585a, 0x00205558, 0x00205457, 0x00205154, 0x001e4f51, 0x001d4b4e, 0x001c484c, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081015, 0x00081015, 0x00081015, 0x00081118, 0x00081118, 0x000a1219, 0x000b141a, 0x000c141b, 0x000a141a, 0x0009141a, 0x0009141a, 0x0009141a, 0x0009141b, 0x000a141b, 0x000a141c, 0x000b151d, 0x000c161f, 0x000d1720, 0x000d1721, 0x000e1822, 0x000d1822, 0x000d1924, 0x000d1923, 0x000d1b23, 0x000d1c25, 0x000c1c27, 0x000b1c27, 0x000c1d28, 0x000c1e28, 0x000e1f29, 0x000e1f2a, 0x000f202b, 0x000f202b, 0x000f202c, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212d, 0x000e212c, 0x000e212b, 0x000e212a, 0x0010212a, 0x0010202a, 0x0010202a, 0x000f202b, 0x000f202b, 0x00102029, 0x00102029, 0x000f1f28, 0x000e1e27, 0x000e1e27, 0x000e1c26, 0x000d1b24, 0x000d1b24, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101d27, 0x000f1d27, 0x000c1d26, 0x000c1d26, 0x000c1d26, 0x000c1e27, 0x000e1f28, 0x000e1f28, 0x000e1f28, 0x000f1f28, 0x000f1f28, 0x00101f28, 0x00111f29, 0x0012202a, 0x0012222c, 0x0012242e, 0x00152631, 0x00152734, 0x00192d3a, 0x00223645, 0x00293d4d, 0x002c4050, 0x002b3f50, 0x002b3f4e, 0x002b3e4d, 0x00293a4a, 0x00263745, 0x00283845, 0x002b3a47, 0x002e3c49, 0x002e3c49, 0x0034414f, 0x0034414f, 0x00354350, 0x00394754, 0x003b4856, 0x003c4855, 0x003b4754, 0x003c4855, 0x003d4956, 0x003e4b58, 0x003f4a58, 0x003c4755, 0x00394552, 0x00394451, 0x00394450, 0x00384450, 0x00384450, 0x0038444f, 0x0039444f, 0x003a4652, 0x003c4854, 0x003d4957, 0x003d4957, 0x003e4a58, 0x003e4957, 0x003f4a58, 0x00404c5a, 0x00414d5b, 0x00414c5a, 0x00424d5c, 0x00455060, 0x00485464, 0x00485565, 0x00485565, 0x00495464, 0x00485163, 0x00444c5e, 0x00404656, 0x003c4250, 0x003a414d, 0x0039404c, 0x00373e4b, 0x00353c49, 0x00363d4a, 0x00383e4c, 0x003b4250, 0x00434b59, 0x00444f5c, 0x0044505e, 0x0044505d, 0x00424d5c, 0x003e4957, 0x003c4755, 0x003c4754, 0x003d4857, 0x00404a5a, 0x00434c5d, 0x00434d5d, 0x00434d5e, 0x00444e5f, 0x00454f60, 0x00465061, 0x00475061, 0x00465060, 0x00454e60, 0x00444d5e, 0x00434c5d, 0x00434d5e, 0x00424c5d, 0x00414b5c, 0x00404859, 0x003f4658, 0x003f4658, 0x003f4758, 0x003d4455, 0x003d4555, 0x003c4657, 0x003c4758, 0x003b4654, 0x003c4756, 0x003f4a58, 0x00414e5c, 0x00475463, 0x00485566, 0x00485464, 0x00444d5f, 0x003c4656, 0x00343e4d, 0x00333c4a, 0x00343f4b, 0x0037404d, 0x0038414c, 0x0039424d, 0x003d4552, 0x00414956, 0x00434c5b, 0x00475160, 0x00485364, 0x00495566, 0x004a5567, 0x00455062, 0x00444e60, 0x00444e5f, 0x00414e5d, 0x00404c5c, 0x003e4b5a, 0x00404e5d, 0x00404d5c, 0x00404b59, 0x003f4a58, 0x00404c5a, 0x00414c5c, 0x00404c5c, 0x00404c5c, 0x00414d5d, 0x00404c5c, 0x003e4b5b, 0x003f4b5b, 0x003f4c5b, 0x00404d5c, 0x00404e5d, 0x003e4c5c, 0x003d4c5c, 0x0040505e, 0x00404f5e, 0x0040505f, 0x0041505e, 0x00404d5c, 0x00414e5c, 0x00424f5e, 0x00404d5d, 0x003e4c5c, 0x003c495b, 0x003c4858, 0x003c4a58, 0x003e4a57, 0x003c4854, 0x00384350, 0x00384150, 0x00394350, 0x003a4451, 0x00384150, 0x00353f4c, 0x00303a47, 0x002f3845, 0x002e3947, 0x002c3846, 0x002b3845, 0x002b3a47, 0x002d3e4b, 0x002c3e4c, 0x002d404e, 0x002e4350, 0x002c404e, 0x00283c49, 0x00243642, 0x001f2e3a, 0x001e2d38, 0x0021313b, 0x0022323c, 0x00192832, 0x0016242f, 0x00132029, 0x00111c26, 0x00121e27, 0x0014202c, 0x00152430, 0x00142634, 0x00162935, 0x00172c38, 0x00172c38, 0x00152c36, 0x00142c36, 0x00142a35, 0x00142a35, 0x00132934, 0x00122834, 0x00112833, 0x00102732, 0x00102732, 0x00102632, 0x00102531, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00112430, 0x00112430, 0x0011232f, 0x0011232f, 0x0011232f, 0x0011232f, 0x0010232f, 0x000f242f, 0x000f242f, 0x00102430, 0x000f2432, 0x00102634, 0x00112633, 0x00112632, 0x00112632, 0x00112632, 0x00112632, 0x00112632, 0x00112632, 0x00112632, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x0010232f, 0x0010232c, 0x000f232b, 0x000f222b, 0x000e212a, 0x000e212b, 0x000d202c, 0x000d202c, 0x000d1f2a, 0x000e1f29, 0x000e1f29, 0x000c1e28, 0x000c1e28, 0x000d1e28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153439, 0x00173a3e, 0x00194044, 0x001b474b, 0x001d4d50, 0x00205356, 0x0022595c, 0x00256870, 0x0032a4c9, 0x002a7c8a, 0x002c7f8e, 0x003298b4, 0x0035a7c8, 0x0035a4c2, 0x003291a7, 0x002c787e, 0x002c7274, 0x002b7072, 0x002b6f70, 0x002a6d6f, 0x00296b6d, 0x0028686b, 0x00276668, 0x00266466, 0x00256264, 0x00256062, 0x00245e60, 0x00245d60, 0x00245c5e, 0x00235a5c, 0x0022595c, 0x0022595c, 0x0022585b, 0x0022585a, 0x00215659, 0x00205558, 0x00205457, 0x00205254, 0x001f5053, 0x001d4d50, 0x001c4a4d, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0013282e, 0x0013242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091016, 0x00091016, 0x00091016, 0x00081118, 0x00081118, 0x000a1219, 0x000b141a, 0x000c141b, 0x000b141b, 0x000a141b, 0x000a141b, 0x000a141b, 0x000a141b, 0x000a141b, 0x000b151c, 0x000b151d, 0x000c161f, 0x000d1720, 0x000d1721, 0x000e1822, 0x000c1822, 0x000c1924, 0x000c1923, 0x000d1b23, 0x000d1c26, 0x000c1c27, 0x000b1c27, 0x000c1e28, 0x000d1f29, 0x000e1f2a, 0x000f202b, 0x000f202c, 0x0010212c, 0x0010222d, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232e, 0x000f232c, 0x000f232b, 0x0010222b, 0x0010222b, 0x0010212b, 0x0010202c, 0x0010202c, 0x0010202a, 0x0010202a, 0x00102029, 0x00102028, 0x00101f28, 0x00101d27, 0x000e1c25, 0x000e1c25, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101d27, 0x000f1d27, 0x000c1d26, 0x000c1d26, 0x000c1d26, 0x000c1e27, 0x000e1f28, 0x000f2028, 0x000f2029, 0x00102029, 0x00102029, 0x00102029, 0x0012202a, 0x0013202b, 0x0012222c, 0x0013242e, 0x00152631, 0x00152734, 0x00182c39, 0x00213544, 0x002a3f4e, 0x002c4150, 0x002a3f50, 0x002a3f4e, 0x002a3d4c, 0x00283949, 0x00273846, 0x00283846, 0x002c3a47, 0x002c3947, 0x002b3845, 0x0032404d, 0x00313f4c, 0x0034424f, 0x003b4855, 0x003c4856, 0x003c4855, 0x003b4554, 0x003b4453, 0x003c4654, 0x003c4754, 0x003c4653, 0x003a4450, 0x00394450, 0x00384450, 0x0038434f, 0x0037424e, 0x0038434f, 0x0038434d, 0x0038434d, 0x00384450, 0x003a4652, 0x003b4754, 0x003c4855, 0x003e4957, 0x003f4b58, 0x00404c59, 0x00414c5b, 0x00434e5c, 0x00404b5a, 0x00404c5c, 0x00455160, 0x004a5565, 0x00485564, 0x00475463, 0x00485362, 0x00444e5e, 0x00404858, 0x003c4251, 0x00383f4b, 0x00363c48, 0x00353c48, 0x00353a48, 0x00343846, 0x00343a48, 0x00343a48, 0x00343948, 0x00404756, 0x0047505f, 0x00485260, 0x00485260, 0x0047505f, 0x00444e5c, 0x00434c5a, 0x00434c5c, 0x00444e5e, 0x00454f60, 0x00455062, 0x00475364, 0x00485466, 0x00475467, 0x00475466, 0x00485467, 0x004a5468, 0x004a5468, 0x004a5468, 0x00495467, 0x00485467, 0x00495568, 0x00495468, 0x00465164, 0x00444e61, 0x00434c60, 0x00444d60, 0x00444d60, 0x00424b5c, 0x00414a5b, 0x00434c5e, 0x00444e60, 0x00444f5e, 0x0044505f, 0x0044505e, 0x00465260, 0x004b5767, 0x004c5869, 0x004a5566, 0x00454e60, 0x00384052, 0x00303848, 0x002f3645, 0x00303845, 0x00333b48, 0x00343c48, 0x00363e49, 0x0038404c, 0x003c4451, 0x00404956, 0x00404a58, 0x00465060, 0x00485465, 0x004b5668, 0x004a5567, 0x00475164, 0x00455061, 0x00424f5e, 0x00414f5e, 0x00404c5c, 0x003f4c5c, 0x003f4b5b, 0x00414c5c, 0x00414c5c, 0x00404c5c, 0x00404b5b, 0x003e4a59, 0x003d4858, 0x003e4a59, 0x003f4a5a, 0x003f4a5a, 0x003e4958, 0x003d4858, 0x003e4a59, 0x003f4a5a, 0x003a4656, 0x003d4b59, 0x00404f5e, 0x00404f5d, 0x003f4d5c, 0x00404c5b, 0x003f4b5a, 0x003c4857, 0x003f4c5b, 0x00404d5d, 0x00404d5e, 0x003f4c5d, 0x003d4a5b, 0x003c4a58, 0x003d4a58, 0x003b4754, 0x00384451, 0x00394451, 0x003a4451, 0x00394350, 0x00384150, 0x00343e4c, 0x00303a46, 0x002e3946, 0x002f3c49, 0x002e3b48, 0x002c3b48, 0x002c3c48, 0x0030404c, 0x002f414e, 0x002b3f4c, 0x002b404d, 0x002a3f4c, 0x00283c49, 0x00243643, 0x0020303d, 0x0020303c, 0x0021303c, 0x00203039, 0x001b2a34, 0x00182732, 0x0013202b, 0x00101e28, 0x00132029, 0x0015232d, 0x00162431, 0x00162835, 0x00172a37, 0x00182c39, 0x00182c38, 0x00162d37, 0x00152c37, 0x00142a36, 0x00142a35, 0x00132934, 0x00122834, 0x00112833, 0x00102833, 0x00102732, 0x00102632, 0x00102531, 0x00102430, 0x00102430, 0x00102430, 0x00112430, 0x00112430, 0x00112430, 0x0011232f, 0x0011232f, 0x0011232f, 0x0011232f, 0x0010232f, 0x000f242f, 0x000f2430, 0x00102430, 0x000f2433, 0x00102634, 0x00122734, 0x00122733, 0x00112632, 0x00112632, 0x00112632, 0x00112632, 0x00112632, 0x00112632, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x0010232f, 0x0010232c, 0x000f232c, 0x000f222b, 0x000e212a, 0x000e212b, 0x000d202c, 0x000d202c, 0x000d1f2a, 0x000e1f29, 0x000e1f29, 0x000c1e28, 0x000c1e28, 0x000d1e28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000e1e27, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0011242c, 0x00102a30, 0x00142e34, 0x00153439, 0x00173a3e, 0x00194044, 0x001c4649, 0x001d4c50, 0x00205356, 0x0022585b, 0x0025676f, 0x0032a4c8, 0x002b7c8c, 0x00286b6d, 0x002a7071, 0x002d7d87, 0x003294aa, 0x0036a6c6, 0x003293a8, 0x002e7b81, 0x002e8390, 0x002b7274, 0x002a6e70, 0x00296c6e, 0x0028696c, 0x00286769, 0x00266467, 0x00256364, 0x00256062, 0x00245e60, 0x00245d60, 0x00235c5e, 0x00235a5c, 0x0021595c, 0x0022585b, 0x0022585a, 0x0021585a, 0x00215659, 0x00205558, 0x00205356, 0x00205254, 0x001e5053, 0x001e4c50, 0x001c4a4d, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x0016363b, 0x00153338, 0x00132e34, 0x00102a30, 0x0013282e, 0x0013242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081118, 0x00091117, 0x00091117, 0x00091118, 0x00091118, 0x000a1219, 0x000b131a, 0x000b141a, 0x000a141b, 0x000a141b, 0x000a141b, 0x000a141b, 0x000a141b, 0x0009151c, 0x000a161c, 0x000b161e, 0x000b171f, 0x000c1720, 0x000c1821, 0x000c1921, 0x000c1922, 0x000c1a24, 0x000c1a24, 0x000c1b24, 0x000c1c27, 0x000c1c28, 0x000c1e28, 0x000c1f29, 0x000d202a, 0x000e202b, 0x000f202c, 0x000f212d, 0x0010212e, 0x0010232f, 0x0010242f, 0x0010242f, 0x00102430, 0x00102430, 0x00102430, 0x0010242e, 0x0010242e, 0x0010232e, 0x0010232d, 0x000f222d, 0x000f202d, 0x000f202d, 0x0010202c, 0x0010202c, 0x0010202b, 0x00102029, 0x000f2028, 0x000f1e28, 0x000e1d26, 0x000d1c26, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000c1d27, 0x000c1e27, 0x000c1e28, 0x000d1e28, 0x000e1f28, 0x00102029, 0x0010202a, 0x0010202a, 0x0010202a, 0x0010202b, 0x0011202c, 0x0012212d, 0x00122330, 0x00122430, 0x00142633, 0x00152834, 0x00182c3a, 0x00203544, 0x002a3f4e, 0x002c4050, 0x00293e4d, 0x002a3e4c, 0x002c3d4c, 0x002a3b48, 0x00283744, 0x00293845, 0x002c3b48, 0x002c3a48, 0x00283644, 0x002e3b48, 0x002e3c49, 0x00374452, 0x003c4856, 0x003c4855, 0x003b4654, 0x00394351, 0x00384150, 0x00384250, 0x00384350, 0x0038434f, 0x0038434f, 0x0039434f, 0x0038434f, 0x0035414d, 0x00343f4b, 0x00353f4b, 0x00343f48, 0x00354049, 0x0037404c, 0x0038424e, 0x0038424f, 0x003b4653, 0x003d4a56, 0x00404d59, 0x00424e5b, 0x00434e5c, 0x00444f5f, 0x00444e5f, 0x00434d5e, 0x00465162, 0x00485464, 0x00485362, 0x00475160, 0x0046505e, 0x00424958, 0x003d4452, 0x00383d4b, 0x00343b46, 0x00323843, 0x00313843, 0x00323844, 0x00323744, 0x00303642, 0x002e3440, 0x002c323e, 0x00313744, 0x003c4350, 0x00454b58, 0x00464b59, 0x003f4452, 0x003d4452, 0x00404855, 0x00454c5b, 0x00484f5f, 0x00454e60, 0x00445064, 0x00465668, 0x00495a6c, 0x00495c6d, 0x00485b6d, 0x004c5b6f, 0x004d5b70, 0x004d5b6f, 0x004d5b70, 0x004c5a6f, 0x004c5b70, 0x004d5d71, 0x004d5c71, 0x004a596d, 0x004a576c, 0x004a566b, 0x00495569, 0x00485466, 0x00455061, 0x00455060, 0x0047505f, 0x0046505f, 0x00444d5c, 0x00414a58, 0x003d4654, 0x003f4856, 0x0047505e, 0x00495261, 0x00454d5c, 0x00383f4e, 0x002c3140, 0x002c3141, 0x002e3241, 0x002e3340, 0x002e3440, 0x00313842, 0x00343945, 0x00353c47, 0x0039404c, 0x003d4552, 0x003f4754, 0x00444c5b, 0x00485262, 0x004b5668, 0x004c5869, 0x00485466, 0x00445060, 0x00414d5e, 0x00434f60, 0x00445061, 0x00445060, 0x00424d5d, 0x00414c5c, 0x00414c5c, 0x00404b5b, 0x00404959, 0x003e4858, 0x003d4857, 0x003e4958, 0x003e4a58, 0x003c4756, 0x003b4554, 0x003b4654, 0x003c4856, 0x003b4654, 0x00384453, 0x003d4958, 0x00404d5c, 0x003f4c5c, 0x003c4958, 0x003c4857, 0x003c4959, 0x003a4756, 0x003b4858, 0x003e4b5c, 0x00404d5e, 0x00404d5e, 0x003f4c5d, 0x003d4a5b, 0x003c4958, 0x003a4654, 0x00384452, 0x00394452, 0x00394451, 0x0037404e, 0x00313b49, 0x00303a48, 0x00333d4a, 0x00303c49, 0x002f3c4a, 0x00303e4c, 0x00303e4c, 0x002d3d4b, 0x0030404e, 0x00304350, 0x002c404d, 0x002b3f4c, 0x002a3f4c, 0x002c3f4c, 0x00283a48, 0x00253544, 0x00233240, 0x00202f3c, 0x001e2d38, 0x001c2b36, 0x00182832, 0x0014222c, 0x0014202a, 0x0014212c, 0x0017242f, 0x00182633, 0x00182938, 0x00192c3b, 0x00192e3c, 0x00182e3b, 0x00162e3a, 0x00162d39, 0x00142c38, 0x00142b37, 0x00132a35, 0x00122834, 0x00122834, 0x00122834, 0x00112834, 0x00112632, 0x00102531, 0x00102531, 0x000f2531, 0x000f2531, 0x00102431, 0x00102431, 0x00102431, 0x00112430, 0x00112430, 0x0011232f, 0x0011232f, 0x0010232f, 0x000f2430, 0x000f2430, 0x000f2431, 0x00102532, 0x00102633, 0x00112733, 0x00112733, 0x00112732, 0x00112732, 0x00112732, 0x00112632, 0x00102531, 0x00102531, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x00102430, 0x0010232e, 0x000f222d, 0x000f222c, 0x000e212c, 0x000e212c, 0x000d202c, 0x000d202b, 0x000c202a, 0x000d202a, 0x000d202a, 0x000d1e28, 0x000d1e28, 0x000d1e28, 0x000e1e28, 0x000e1e28, 0x000e1e28, 0x000e1e28, 0x000e1e28, 0x000d1e28, 0x000d1e28, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012242c, 0x00112a30, 0x00142e34, 0x00153338, 0x00183a3e, 0x00183f43, 0x001c4649, 0x001d4b4e, 0x001f5254, 0x0022585b, 0x0024646c, 0x0030a0c4, 0x002c8598, 0x00296b6d, 0x002b6f70, 0x002b7173, 0x002c7375, 0x00349ab4, 0x00349db8, 0x00349cb7, 0x0037a8ca, 0x00349cb8, 0x002e8190, 0x002a6f72, 0x00286a6c, 0x0028686a, 0x00276568, 0x00266364, 0x00256163, 0x00245e60, 0x00245d60, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0022585b, 0x0022585a, 0x00215659, 0x00205558, 0x00205558, 0x00205356, 0x00205254, 0x001e5053, 0x001e4d50, 0x001c4a4d, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081319, 0x00091318, 0x00091318, 0x000a1219, 0x000a1219, 0x000a1219, 0x000b131a, 0x000b131a, 0x000a141c, 0x000b151d, 0x000b151d, 0x000b151d, 0x000a151d, 0x0009161c, 0x0009161c, 0x0009171e, 0x000a1820, 0x000b1820, 0x000b1a21, 0x000c1b22, 0x000c1b23, 0x000a1c24, 0x000b1c25, 0x000c1c27, 0x000c1d28, 0x000c1e28, 0x000c1f29, 0x000c202a, 0x000d202b, 0x000e212c, 0x000e212c, 0x000f222e, 0x0010232f, 0x0010242f, 0x00102430, 0x00102430, 0x00102531, 0x00112632, 0x00102531, 0x00102430, 0x00102430, 0x000f242f, 0x000f242f, 0x000f2230, 0x000f2230, 0x000f222f, 0x0010222f, 0x0010222e, 0x0010212c, 0x000f2029, 0x000f2028, 0x000e1f28, 0x000d1e27, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000c1e28, 0x000d1e28, 0x000d1f29, 0x000e1f29, 0x000e202a, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202d, 0x0011212f, 0x00112230, 0x00122431, 0x00122432, 0x00132534, 0x00142835, 0x00172c39, 0x001c313f, 0x00253c48, 0x002a404d, 0x00283f4c, 0x002b404d, 0x002d3f4c, 0x002a3b48, 0x00283643, 0x00283643, 0x002d3b47, 0x002d3b46, 0x00283441, 0x002a3844, 0x002c3947, 0x00384452, 0x003a4754, 0x003a4554, 0x003a4553, 0x00394451, 0x0036404d, 0x00343d4a, 0x00343f4a, 0x0037404c, 0x0037414c, 0x0038434e, 0x0038424f, 0x0034404c, 0x00323c48, 0x00323c48, 0x00313c45, 0x00323c45, 0x00343e48, 0x0036404a, 0x0037404d, 0x00394450, 0x003c4955, 0x00404d59, 0x00424d5c, 0x00414d5c, 0x00445060, 0x00445061, 0x00434e60, 0x00445061, 0x00455062, 0x00465060, 0x00444e5c, 0x00424958, 0x003c4350, 0x00373d4b, 0x00313743, 0x002f3540, 0x002e343e, 0x002e343e, 0x002e343f, 0x002d343e, 0x002b313b, 0x00292f38, 0x00292e38, 0x00282d37, 0x002a2d38, 0x002f313d, 0x00323440, 0x00343641, 0x00343843, 0x00353a45, 0x00343a46, 0x003c4452, 0x00414a5c, 0x00445060, 0x00475668, 0x004a5b6d, 0x00495d6f, 0x004b6072, 0x00506276, 0x00526377, 0x00536478, 0x00526377, 0x00516276, 0x00526278, 0x0054657a, 0x0054667b, 0x00506277, 0x00506075, 0x00506074, 0x004d5b6e, 0x00485667, 0x00475361, 0x00475160, 0x00434b59, 0x003c4350, 0x0038404c, 0x00383f4b, 0x00383f4a, 0x00383f4b, 0x003b404d, 0x003b404d, 0x00343845, 0x002b2f3c, 0x00262a38, 0x00282c3a, 0x002c303d, 0x002c313c, 0x002c323c, 0x00303640, 0x00323842, 0x00313843, 0x00343a46, 0x0038404c, 0x003c4452, 0x00404857, 0x00454d5d, 0x004a5364, 0x004c5869, 0x004a5668, 0x00465163, 0x00434d5f, 0x00434e5f, 0x00445061, 0x00434e60, 0x00424c5c, 0x00414a5a, 0x00404a58, 0x003e4856, 0x003c4654, 0x003d4756, 0x003d4856, 0x003d4856, 0x003c4855, 0x00384350, 0x0035404e, 0x0036424f, 0x00394451, 0x00384350, 0x00384451, 0x003c4756, 0x003d4a58, 0x003d4b58, 0x00394654, 0x00374452, 0x003c4858, 0x003a4757, 0x00394756, 0x003c4a5a, 0x003f4c5d, 0x003f4c5d, 0x003d4a5c, 0x003c495a, 0x003c4959, 0x00394755, 0x00394554, 0x003a4453, 0x003a4452, 0x00353f4d, 0x002d3745, 0x002c3644, 0x00343e4c, 0x0033404e, 0x00303e4b, 0x002f3e4d, 0x0031404f, 0x0030404f, 0x002d404e, 0x002c404e, 0x002c4250, 0x002c424f, 0x002c404e, 0x002c404d, 0x002c3f4d, 0x002a3c4a, 0x00253544, 0x0022323f, 0x0022313d, 0x001e2d38, 0x00182832, 0x00162430, 0x0014222d, 0x0014222d, 0x00172530, 0x00192834, 0x00192a39, 0x00192c3c, 0x001a2e3d, 0x00182f3c, 0x00162e3c, 0x00162d3b, 0x00162c39, 0x00152c38, 0x00142a35, 0x00122834, 0x00122834, 0x00122835, 0x00112834, 0x00112633, 0x00102531, 0x00102631, 0x000e2631, 0x000e2631, 0x000f2631, 0x000f2631, 0x00102531, 0x00102531, 0x00102430, 0x0010242f, 0x000f242f, 0x000f242f, 0x000f2530, 0x000f2530, 0x00102631, 0x00102632, 0x00112632, 0x00112833, 0x00112833, 0x00112833, 0x00112833, 0x00112833, 0x00112632, 0x00102531, 0x00102531, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x00112430, 0x0010232f, 0x000f222e, 0x000f222e, 0x000e212d, 0x000e212d, 0x000e212c, 0x000d202b, 0x000d202b, 0x000d202b, 0x000d202b, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00143338, 0x0017383c, 0x00183f43, 0x001b4448, 0x001d4b4e, 0x001f5154, 0x0021585a, 0x00245f63, 0x002f98b8, 0x002e93af, 0x00296c6e, 0x002b6e70, 0x002b7173, 0x002c7475, 0x003499b3, 0x00359db9, 0x0035a0bc, 0x0036a5c4, 0x0035a0be, 0x0036a8c8, 0x00339cb8, 0x002c808e, 0x00286b6f, 0x00276668, 0x00266466, 0x00256163, 0x00245f61, 0x00245d60, 0x00245c5e, 0x00235a5c, 0x0021595c, 0x0022585b, 0x0022585a, 0x0022585a, 0x00215659, 0x00205558, 0x00205457, 0x00205254, 0x001f5053, 0x001d4d50, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00081419, 0x00091418, 0x00091418, 0x00091319, 0x00091219, 0x00091219, 0x000a131a, 0x000b141a, 0x000b141c, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151d, 0x0009161c, 0x0008161c, 0x0009171e, 0x000a1820, 0x000b1920, 0x000b1a22, 0x000c1b23, 0x000c1c24, 0x000b1c25, 0x000b1c26, 0x000c1d28, 0x000c1d29, 0x000c1e29, 0x000d1f29, 0x000d202b, 0x000e212c, 0x000e212c, 0x000f222c, 0x000f222e, 0x0010232f, 0x00102430, 0x00102530, 0x00102531, 0x00112632, 0x00122733, 0x00122733, 0x00112632, 0x00102632, 0x00102530, 0x00102430, 0x00102432, 0x00102433, 0x00102332, 0x000f2331, 0x00102330, 0x0010222e, 0x000f212c, 0x000e212b, 0x000e202a, 0x000d202a, 0x000c2029, 0x000c1f29, 0x000c1f29, 0x000c1f29, 0x000c1f29, 0x000c1f29, 0x000d202a, 0x000d202b, 0x000d202b, 0x000e212c, 0x000f212c, 0x000f222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222e, 0x00112330, 0x00112331, 0x00122432, 0x00122433, 0x00132534, 0x00142734, 0x00152b38, 0x0019303d, 0x00243a47, 0x0029404c, 0x00293e4c, 0x002c414f, 0x002d3f4d, 0x00273745, 0x00233140, 0x00243340, 0x002b3944, 0x002d3b46, 0x00293742, 0x002a3844, 0x002a3845, 0x0034424f, 0x00384552, 0x00394452, 0x00384451, 0x00394451, 0x00343f4c, 0x00303a46, 0x00343d48, 0x00343f49, 0x00343e48, 0x0036404b, 0x00353f4c, 0x00323c48, 0x00303a47, 0x00313a46, 0x00313a44, 0x00323b44, 0x00333c47, 0x00343e4a, 0x0036404d, 0x00384450, 0x003b4854, 0x00404c58, 0x00404c5a, 0x00404c5b, 0x00444f5e, 0x00445060, 0x00444f60, 0x00444e5f, 0x00444e5f, 0x00444c5c, 0x00404857, 0x003c4251, 0x00363c49, 0x00303643, 0x002c313d, 0x002c303c, 0x002c313c, 0x002c333c, 0x002c323c, 0x002b313b, 0x00282f36, 0x00282c34, 0x00292d35, 0x00292d35, 0x00282b34, 0x00252730, 0x0024242e, 0x00272831, 0x002c2d37, 0x0030313b, 0x002c2f39, 0x002b303c, 0x00353c4b, 0x00414b5c, 0x00495668, 0x004c5a6c, 0x004c5c6f, 0x004c6072, 0x00506477, 0x00536579, 0x0057687c, 0x0057687c, 0x0056687d, 0x0056687f, 0x00566980, 0x00546980, 0x0054677e, 0x0054677c, 0x00526378, 0x004a5a6c, 0x00475565, 0x0044505e, 0x003c4453, 0x00323847, 0x00313543, 0x00313642, 0x00333842, 0x00333843, 0x00333641, 0x002f323d, 0x002b2e39, 0x00282834, 0x00272834, 0x00272834, 0x00282a34, 0x002a2d38, 0x00292e37, 0x002b3039, 0x002f343e, 0x00303540, 0x002f3440, 0x00303742, 0x00343c48, 0x0038404d, 0x003d4553, 0x00414958, 0x00465060, 0x004a5464, 0x00495666, 0x00485464, 0x00455062, 0x00444f60, 0x00444f60, 0x00455061, 0x00444d5f, 0x00404958, 0x00404957, 0x003c4654, 0x003c4553, 0x003b4453, 0x003a4453, 0x00394553, 0x00384452, 0x0035404e, 0x00333e4c, 0x0034404c, 0x0036424e, 0x0036414e, 0x00384350, 0x00384251, 0x00384453, 0x00384653, 0x00364350, 0x0033404e, 0x00384553, 0x00394654, 0x00394655, 0x003c4959, 0x003f4c5c, 0x003d4a5b, 0x003c4859, 0x003b4858, 0x003c4858, 0x00394755, 0x00394654, 0x003b4654, 0x00394452, 0x0036404e, 0x00303948, 0x002e3847, 0x00313d4b, 0x00344250, 0x0030404d, 0x002f404e, 0x00314250, 0x00304250, 0x002d404e, 0x002a3f4c, 0x002c404e, 0x002c4250, 0x002c424f, 0x002b404d, 0x002c3f4c, 0x002c3d4c, 0x00283948, 0x00253744, 0x00253642, 0x0020303a, 0x00192932, 0x00172530, 0x0014242f, 0x0014232e, 0x00172631, 0x001a2936, 0x00192b39, 0x00192c3c, 0x001a2e3c, 0x00182f3c, 0x00182f3c, 0x00172e3b, 0x00162d39, 0x00152c38, 0x00142a36, 0x00132935, 0x00132934, 0x00132936, 0x00122835, 0x00122734, 0x00112634, 0x00102633, 0x000e2631, 0x000e2631, 0x000f2631, 0x000f2631, 0x00102631, 0x00102531, 0x00102430, 0x00102430, 0x000f242f, 0x000f2430, 0x000f2530, 0x000f2531, 0x00102732, 0x00102732, 0x00112732, 0x00112833, 0x00112833, 0x00112833, 0x00112833, 0x00112833, 0x00112632, 0x00102531, 0x00102531, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x00112430, 0x0010232f, 0x000f222e, 0x000f222e, 0x000e212d, 0x000e212d, 0x000f222c, 0x000f222c, 0x000e212c, 0x000d202b, 0x000d202b, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00122c32, 0x00153338, 0x0016363b, 0x00183d41, 0x001b4347, 0x001c4a4d, 0x001f5053, 0x00205558, 0x00245c5f, 0x002c88a0, 0x0032a3c4, 0x002a757e, 0x002a6e70, 0x002b7072, 0x002c7475, 0x003499b3, 0x00359db9, 0x0035a0bc, 0x00349fbb, 0x002c767a, 0x002f8898, 0x00349ebc, 0x0034a6c9, 0x003099b7, 0x002b7d8e, 0x0027666a, 0x00256264, 0x00245f61, 0x00245e60, 0x00245c5f, 0x00235a5c, 0x0022595c, 0x0022595c, 0x0022585b, 0x0022585a, 0x0021585a, 0x00215659, 0x00205558, 0x00205356, 0x00205154, 0x001e4f51, 0x001d4c50, 0x001c484c, 0x001b4448, 0x001a4044, 0x00183d41, 0x0017383c, 0x00153439, 0x00142e34, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0007141a, 0x0008141a, 0x0008141a, 0x0008141a, 0x0008141a, 0x0008141a, 0x0009141a, 0x0009141a, 0x000a141c, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x0009161e, 0x0008161e, 0x0009171f, 0x000a1820, 0x000b1920, 0x000b1a22, 0x000c1b23, 0x000c1c24, 0x000c1d27, 0x000b1c26, 0x000b1c27, 0x000b1c28, 0x000c1d28, 0x000d1f29, 0x000d202b, 0x000f222c, 0x000f222c, 0x0010232d, 0x0010232f, 0x00112430, 0x00112431, 0x00102531, 0x00112632, 0x00122632, 0x00132733, 0x00132834, 0x00132833, 0x00132733, 0x00112632, 0x00112632, 0x00102533, 0x00102534, 0x00102434, 0x00102434, 0x00102432, 0x00102430, 0x0010232e, 0x000f232d, 0x000e222c, 0x000e212c, 0x000d212c, 0x000d202b, 0x000d202b, 0x000d202b, 0x000d202b, 0x000d202b, 0x000e202c, 0x000f202c, 0x000f212c, 0x0010212c, 0x0010222d, 0x000f222c, 0x000f222c, 0x000f222c, 0x0010232d, 0x0010232f, 0x00112431, 0x00112432, 0x00122433, 0x00122433, 0x00142734, 0x00142834, 0x00162b38, 0x001a303c, 0x00233946, 0x0029404c, 0x00293f4c, 0x002d414f, 0x002d3e4c, 0x00253544, 0x0022303f, 0x00243240, 0x00293843, 0x002c3944, 0x002c3945, 0x002f3c49, 0x002d3b48, 0x00303e4b, 0x0034414f, 0x00384350, 0x00384451, 0x00374350, 0x00303c48, 0x00303945, 0x00343e48, 0x00313c46, 0x00303944, 0x00333c47, 0x00313c46, 0x00303944, 0x00303844, 0x00303843, 0x00303841, 0x00303942, 0x00333b46, 0x00343e4a, 0x0037404f, 0x00384451, 0x003a4754, 0x003d4957, 0x00404b59, 0x00404b59, 0x00434e5c, 0x0044505f, 0x00444f5e, 0x00444d5d, 0x00414b5b, 0x003f4755, 0x003c4450, 0x00363c4a, 0x00303642, 0x002b303c, 0x002a2e39, 0x002a2e38, 0x002b2f38, 0x002b2f39, 0x002a2f39, 0x00292e38, 0x00282c34, 0x00272b32, 0x00282c33, 0x00292c33, 0x00282930, 0x0024242b, 0x00212129, 0x00212029, 0x00222129, 0x0024242d, 0x0024252e, 0x00262833, 0x00292c3a, 0x00323848, 0x00414c5d, 0x00485568, 0x0049596c, 0x004b5d70, 0x004c6073, 0x00506074, 0x00526276, 0x00546478, 0x0057667c, 0x0058687f, 0x0056687f, 0x0054667c, 0x0052647b, 0x00516379, 0x004c5b70, 0x00475568, 0x00434f60, 0x00363f4d, 0x002b3140, 0x002b303c, 0x002c303b, 0x002d313b, 0x002d303a, 0x002a2e37, 0x00282a34, 0x00242630, 0x00262630, 0x0027252f, 0x00282830, 0x00282831, 0x00282831, 0x00282a34, 0x00282c35, 0x002a2f38, 0x002d323c, 0x002e333c, 0x002e333d, 0x0030343f, 0x00323844, 0x00363d49, 0x003c4350, 0x003f4854, 0x00434c5b, 0x00475160, 0x00485464, 0x004a5566, 0x004a5566, 0x00465163, 0x00455062, 0x00444f60, 0x00424c5d, 0x003f4858, 0x003f4857, 0x003d4755, 0x003c4654, 0x003c4553, 0x00394452, 0x00374250, 0x0035404f, 0x00333e4c, 0x00323d4b, 0x00323d4a, 0x00343f4b, 0x00343e4b, 0x00343f4c, 0x00364050, 0x00384351, 0x00364350, 0x0034414f, 0x0032404c, 0x0034414f, 0x00384553, 0x00384553, 0x003c4a58, 0x003f4c5c, 0x003d4959, 0x003b4656, 0x00394454, 0x00394554, 0x00384554, 0x00384655, 0x003a4654, 0x003a4452, 0x0037404f, 0x00313b4b, 0x00313c4c, 0x00303c4b, 0x00324050, 0x00324150, 0x00334351, 0x00324351, 0x00304250, 0x002d414f, 0x002b404c, 0x002c404d, 0x002c4250, 0x002b414f, 0x002c404e, 0x002c404d, 0x002a3d4b, 0x00293c4a, 0x00283a46, 0x00243641, 0x001c2d38, 0x00182831, 0x00182530, 0x0015242f, 0x0014242f, 0x00172631, 0x001a2935, 0x001a2b39, 0x001a2c3b, 0x001b2e3c, 0x001a2e3c, 0x00192f3c, 0x00182e3c, 0x00182e3b, 0x00172d38, 0x00152c38, 0x00142b36, 0x00142a37, 0x00132936, 0x00132936, 0x00132835, 0x00122734, 0x00112734, 0x000f2732, 0x000f2732, 0x00102732, 0x00102732, 0x00102732, 0x000e2530, 0x000e2430, 0x00102530, 0x00102531, 0x00112531, 0x00102531, 0x00112632, 0x00112833, 0x00112833, 0x00112834, 0x00102934, 0x00112934, 0x00112834, 0x00122834, 0x00122834, 0x00122733, 0x00112632, 0x00112632, 0x00122632, 0x00122531, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x00112430, 0x0010232f, 0x000f222e, 0x000f222e, 0x000e212d, 0x000e212d, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00132c32, 0x00143036, 0x0016363b, 0x00183c40, 0x001a4245, 0x001c484c, 0x001e4f51, 0x00205457, 0x00235a5c, 0x00266c76, 0x0032a2c5, 0x003095b0, 0x002a7073, 0x002b7072, 0x002c7475, 0x003499b3, 0x00359db9, 0x0036a0bc, 0x00349fbb, 0x002c7476, 0x002c7274, 0x002c7276, 0x002d8394, 0x00329cba, 0x0033a5c8, 0x003098b8, 0x00297a8b, 0x00256368, 0x00245f61, 0x00245d60, 0x00235c5f, 0x00235b5e, 0x00225a5c, 0x00225a5c, 0x0022595c, 0x0022595c, 0x0022585b, 0x0021575a, 0x00205558, 0x00205457, 0x001f5054, 0x001e4e51, 0x001c4a4d, 0x001b4649, 0x001a4245, 0x00183d41, 0x00183a3e, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0007141a, 0x0008141a, 0x0008141a, 0x0008141a, 0x0008141a, 0x0008141a, 0x0009141a, 0x0009141a, 0x0009141c, 0x000a141d, 0x000b151e, 0x000b151e, 0x000b151e, 0x0009161e, 0x0009171f, 0x0009171f, 0x000a1820, 0x000b1920, 0x000c1b23, 0x000c1c23, 0x000c1c25, 0x000c1e28, 0x000c1e27, 0x000c1d28, 0x000c1d29, 0x000c1e29, 0x000e202a, 0x000e212c, 0x000f222c, 0x0010232d, 0x0010242e, 0x00112430, 0x00122431, 0x00122633, 0x00122734, 0x00132835, 0x00132936, 0x00142935, 0x00142a35, 0x00142a36, 0x00142936, 0x00142834, 0x00132834, 0x00122835, 0x00112737, 0x00102636, 0x00102634, 0x00102533, 0x00102534, 0x00102432, 0x00102430, 0x0010232e, 0x000f232c, 0x000f222c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000f212c, 0x000f222c, 0x0010222c, 0x0011222d, 0x0011232d, 0x0010232d, 0x0010242d, 0x0010242d, 0x0010242d, 0x00102430, 0x00122432, 0x00122433, 0x00122433, 0x00122433, 0x00142734, 0x00142834, 0x00162c37, 0x001a303c, 0x00223845, 0x00283f4c, 0x002c404f, 0x002d4251, 0x002c3e4e, 0x00273848, 0x00243241, 0x00263442, 0x00293844, 0x002c3b46, 0x002f3c48, 0x00303e4b, 0x002e3b48, 0x002d3a48, 0x00303e4b, 0x0034414f, 0x0035424f, 0x00333f4c, 0x002e3a46, 0x00303946, 0x00333d48, 0x00303a44, 0x002e3843, 0x00303a44, 0x00303944, 0x002e3842, 0x002e3641, 0x002e3640, 0x002d363f, 0x002f3741, 0x00323a46, 0x00353f4d, 0x00384250, 0x00394452, 0x003b4855, 0x003e4a58, 0x00404c59, 0x00404b59, 0x00424e5c, 0x0044505e, 0x00444f5e, 0x00414c5b, 0x003f4757, 0x003c4150, 0x00383e4b, 0x00323644, 0x002c2f3b, 0x00292c38, 0x00282b36, 0x00282b35, 0x00282b35, 0x00282c36, 0x00282c36, 0x00282c35, 0x00262930, 0x0025282f, 0x0025282f, 0x0025282f, 0x0024252c, 0x00222328, 0x00202027, 0x00202027, 0x001f1f27, 0x001e1e26, 0x001d1f25, 0x00202028, 0x0023242f, 0x00282c39, 0x00303949, 0x00404b5c, 0x00485566, 0x004a5a6c, 0x004c5c6f, 0x004e5c70, 0x004f5d72, 0x00505e72, 0x00526074, 0x00546378, 0x00526377, 0x00506074, 0x004e5e72, 0x004b586d, 0x00465368, 0x00414c5e, 0x00313b4a, 0x0029303e, 0x00272a38, 0x00272a34, 0x00262931, 0x00252830, 0x0024272e, 0x0022252c, 0x0020242a, 0x00212229, 0x00222229, 0x0024242c, 0x0027262f, 0x0027252f, 0x00272730, 0x00282932, 0x00282c35, 0x002a2f38, 0x002c303a, 0x002c303b, 0x002d313c, 0x002d323c, 0x002f343f, 0x00313843, 0x00383f4a, 0x003c4450, 0x00404854, 0x00444c5c, 0x00485060, 0x00495464, 0x004b5668, 0x00485364, 0x00444f60, 0x00414c5d, 0x00404a5b, 0x003f4858, 0x003e4856, 0x003d4755, 0x003d4755, 0x003c4554, 0x00394452, 0x00364250, 0x0034404d, 0x00323c4b, 0x00313c4a, 0x00313b48, 0x00313b47, 0x00323c48, 0x00343e4b, 0x00343e4d, 0x00374250, 0x0035404e, 0x00333f4c, 0x0034404e, 0x00303c4b, 0x00333f4c, 0x0035424f, 0x003a4654, 0x003c4858, 0x003a4555, 0x00384353, 0x00374251, 0x00374352, 0x00374453, 0x00374453, 0x00384453, 0x00384350, 0x0034404d, 0x00303b49, 0x00323c4c, 0x002e3a4a, 0x002e3c4b, 0x0031404f, 0x00344452, 0x00324452, 0x00314351, 0x00304451, 0x002c404e, 0x002b3f4e, 0x002c4050, 0x002b414f, 0x002c4250, 0x002c4250, 0x002a3e4c, 0x002a3d4b, 0x00273a46, 0x0020313d, 0x001a2b35, 0x00172730, 0x0016242f, 0x0015242f, 0x0014242f, 0x00162530, 0x001a2934, 0x001a2c38, 0x001a2c3a, 0x001b2e3c, 0x001a2e3c, 0x00192e3c, 0x00192e3c, 0x00182f3c, 0x00182f3a, 0x00172d38, 0x00142c37, 0x00142b37, 0x00142a37, 0x00132936, 0x00142835, 0x00142835, 0x00132734, 0x00102833, 0x00102833, 0x00112833, 0x00112833, 0x00102732, 0x000f2631, 0x000e2530, 0x00102531, 0x00112632, 0x00122632, 0x00112632, 0x00122733, 0x00122834, 0x00122834, 0x00122834, 0x00112a34, 0x00112a34, 0x00112934, 0x00122834, 0x00122834, 0x00122733, 0x00122733, 0x00112632, 0x00132632, 0x00132632, 0x00122431, 0x00122431, 0x00112430, 0x00112430, 0x00112430, 0x0010232f, 0x000f222e, 0x000f222e, 0x000e212d, 0x000e212d, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00143036, 0x00153439, 0x00183a3e, 0x00194044, 0x001b4649, 0x001d4c50, 0x00205356, 0x0022585b, 0x00245f61, 0x002c859c, 0x0033a6c9, 0x003090a7, 0x002b7175, 0x002c7374, 0x003499b3, 0x00359db9, 0x0036a0bc, 0x00349fbb, 0x002c7476, 0x002c7274, 0x002b7071, 0x002a6d6f, 0x00296d71, 0x002c7e8f, 0x003099b8, 0x0031a3c8, 0x002f99ba, 0x002d92b1, 0x002c92b0, 0x002c91b0, 0x002c91b0, 0x002c91b0, 0x002b90b0, 0x002b90b0, 0x002b90b0, 0x002b90b0, 0x002a90b0, 0x002a90b0, 0x00298fb0, 0x00288eaf, 0x002787a5, 0x001d4c50, 0x001c484c, 0x001a4347, 0x00183f43, 0x00173a3e, 0x0015363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0008141b, 0x0008141b, 0x0008141b, 0x0008141a, 0x0008141a, 0x0008141a, 0x0009141a, 0x0009141a, 0x0009141c, 0x000a141d, 0x000b151e, 0x000b151e, 0x000b151e, 0x000a161e, 0x000a171f, 0x000a1820, 0x000b1920, 0x000c1a21, 0x000c1b23, 0x000d1c23, 0x000d1c25, 0x000c1d28, 0x000c1e28, 0x000c1e28, 0x000c1f2b, 0x000d202c, 0x000e212c, 0x000f222d, 0x00102430, 0x00102430, 0x00112431, 0x00112532, 0x00122633, 0x00132734, 0x00122837, 0x00132a39, 0x00142c3a, 0x00142c39, 0x00142c39, 0x00142c39, 0x00142c39, 0x00142b38, 0x00142b38, 0x00132b38, 0x00122937, 0x00112836, 0x00122835, 0x00122734, 0x00112634, 0x00112633, 0x00112633, 0x00112430, 0x00102430, 0x0010242f, 0x000e222d, 0x000e212d, 0x000f222e, 0x000f222e, 0x000f222e, 0x000f222d, 0x000f232e, 0x0010232e, 0x0011242e, 0x0011242e, 0x0011242f, 0x00102430, 0x00102530, 0x00102530, 0x00102531, 0x00102532, 0x00112532, 0x00122533, 0x00132633, 0x00142834, 0x00162a36, 0x00182d39, 0x001a303d, 0x00213844, 0x00283f4e, 0x002c4150, 0x002d4350, 0x002c3f4e, 0x00283848, 0x00243443, 0x00243542, 0x00283744, 0x002b3a46, 0x002d3c48, 0x002f3d49, 0x002b3946, 0x00293844, 0x002c3a47, 0x00313f4b, 0x0035424f, 0x00303d49, 0x002e3a46, 0x002f3946, 0x00303b45, 0x00303a44, 0x00303c46, 0x00313b46, 0x00303944, 0x002c3540, 0x0028303b, 0x0029323c, 0x002c343d, 0x002f3642, 0x00323a47, 0x0036404c, 0x0038424f, 0x00394452, 0x003b4855, 0x003d4a58, 0x003e4b58, 0x003f4b59, 0x00404c5a, 0x00434e5b, 0x00434d5a, 0x00404957, 0x003c4351, 0x00383c4a, 0x00343844, 0x002c303c, 0x00282b34, 0x00272a34, 0x00282a34, 0x00282a34, 0x00272a34, 0x00262a34, 0x00262a34, 0x00262831, 0x0023262d, 0x0021242c, 0x0023262c, 0x0022252c, 0x0020232a, 0x00212329, 0x001d1f25, 0x001c1d24, 0x001c1d24, 0x001a1c22, 0x00191c22, 0x001b1d24, 0x001f2029, 0x00222530, 0x00252c38, 0x002c3542, 0x003b4453, 0x00465261, 0x004a5768, 0x00495769, 0x004a586b, 0x004a586c, 0x004d5c70, 0x004f5e70, 0x00505d6f, 0x004f5c6d, 0x004b5768, 0x00465061, 0x003e4758, 0x00303948, 0x00272d3b, 0x00272b38, 0x00242833, 0x0022242d, 0x001f2229, 0x001d2028, 0x001c1e25, 0x001d1f26, 0x00202028, 0x00202129, 0x00202128, 0x0023232a, 0x0024242d, 0x00262630, 0x00252730, 0x00262930, 0x00282c34, 0x00292d37, 0x002b2e38, 0x002c2f3a, 0x002c303a, 0x002c303a, 0x002c313b, 0x002c333c, 0x00323841, 0x00383e48, 0x003c424e, 0x00414956, 0x00444d5c, 0x00485160, 0x00485262, 0x00455060, 0x00434e5e, 0x00414c5c, 0x00404b5a, 0x003c4755, 0x003c4754, 0x003b4553, 0x003b4452, 0x00394451, 0x0037424f, 0x0034404d, 0x00333e4c, 0x00323d4a, 0x00323c49, 0x00313b47, 0x00303944, 0x00303944, 0x00313b46, 0x00323c48, 0x00353f4c, 0x00323c48, 0x002f3a46, 0x00323d49, 0x002f3946, 0x002d3844, 0x00323d49, 0x00384350, 0x00394452, 0x00384351, 0x0034404f, 0x00343f4e, 0x0034404f, 0x00354250, 0x00354250, 0x00354250, 0x0034414e, 0x00313e4b, 0x002d3847, 0x00303b49, 0x002d3a48, 0x002b3947, 0x00303e4c, 0x0030414f, 0x00304251, 0x00304252, 0x00314454, 0x002d4150, 0x002a3f4e, 0x002a404f, 0x002c4250, 0x002d4350, 0x002e4350, 0x002c404d, 0x002c3e4c, 0x00273846, 0x001e2f3b, 0x00192834, 0x00182732, 0x00172631, 0x00162531, 0x00152531, 0x00172733, 0x001a2a37, 0x001a2c39, 0x001a2d3b, 0x001a2d3b, 0x00182d3b, 0x00182c3b, 0x00182d3b, 0x00182e3c, 0x00182f3c, 0x00182e3b, 0x00162c39, 0x00142b38, 0x00142a37, 0x00142a37, 0x00142836, 0x00142836, 0x00132834, 0x00112834, 0x00112834, 0x00112833, 0x00112833, 0x00112833, 0x00102732, 0x00102732, 0x00112733, 0x00112733, 0x00122733, 0x00122834, 0x00122834, 0x00122834, 0x00122834, 0x00122834, 0x00122935, 0x00122935, 0x00122834, 0x00122834, 0x00122834, 0x00142834, 0x00142834, 0x00132732, 0x00132632, 0x00132631, 0x00122531, 0x00112531, 0x00102430, 0x00112430, 0x00102430, 0x0010232f, 0x0010232f, 0x000f222e, 0x000e212d, 0x000e212d, 0x000f212c, 0x000f212c, 0x000f212c, 0x000f212c, 0x000f202c, 0x000f202b, 0x000f202b, 0x0010202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000f202b, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013282e, 0x00112a30, 0x00142e34, 0x00153439, 0x00183a3e, 0x00183f43, 0x001c4649, 0x001d4b4e, 0x001f5154, 0x0021585a, 0x00245d60, 0x00266469, 0x002f90aa, 0x0035a8ca, 0x00339ab6, 0x002e8390, 0x00349ab4, 0x00359db9, 0x0035a0bc, 0x00349fbb, 0x002c7476, 0x002c7274, 0x002b7071, 0x002a6e70, 0x00296b6d, 0x0028686b, 0x0027686c, 0x00297c8c, 0x002e94b3, 0x002f99bb, 0x002e99ba, 0x002d98ba, 0x002d98ba, 0x002d98ba, 0x002c98ba, 0x002c98ba, 0x002c98ba, 0x002c98ba, 0x002c98ba, 0x002b98ba, 0x002b96b9, 0x002c9dc4, 0x002b9ac0, 0x001e4f53, 0x001c4a4d, 0x001b4649, 0x001a4044, 0x00183c40, 0x0017383c, 0x00143338, 0x00142e34, 0x00102a30, 0x0012282e, 0x00102229, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0008141a, 0x0008141a, 0x0008141a, 0x0009141a, 0x0009141a, 0x0009141a, 0x0009141a, 0x0009141a, 0x0009141c, 0x000a141d, 0x000a141d, 0x000b151e, 0x000b161e, 0x000b171f, 0x000c1820, 0x000b1820, 0x000b1920, 0x000c1a22, 0x000d1b23, 0x000d1b23, 0x000d1c25, 0x000c1d27, 0x000c1e28, 0x000c1f2a, 0x000d202c, 0x000e212d, 0x000f222e, 0x000f2430, 0x00102432, 0x00102433, 0x00102533, 0x00112634, 0x00122734, 0x00132835, 0x00132937, 0x00142b3a, 0x00142c3b, 0x00132c3b, 0x00132c3b, 0x00142c3b, 0x00142c3b, 0x00142c3b, 0x00142c3b, 0x00132c3a, 0x00122b36, 0x00122934, 0x00132834, 0x00132834, 0x00132733, 0x00132733, 0x00132733, 0x00112632, 0x00102531, 0x00102430, 0x000f232f, 0x000e222e, 0x000f232e, 0x000f232e, 0x000f232f, 0x000f242f, 0x00102430, 0x00102430, 0x00112430, 0x00122430, 0x00112430, 0x00102632, 0x00102732, 0x00112733, 0x00102632, 0x00102631, 0x00102632, 0x00122632, 0x00142834, 0x00152a38, 0x00182e3b, 0x0018303c, 0x0019303c, 0x001f3543, 0x00283e4d, 0x002b4150, 0x002c4350, 0x002b3f4c, 0x00273845, 0x00243441, 0x00233440, 0x00253643, 0x00293a46, 0x002c3b48, 0x002c3b49, 0x00283744, 0x00283844, 0x00263540, 0x002d3b47, 0x0033404c, 0x00303e49, 0x00303c48, 0x002d3844, 0x002e3844, 0x002f3944, 0x00323c47, 0x00323c46, 0x002e3641, 0x00273039, 0x00242c35, 0x00242d36, 0x002a323c, 0x002f3742, 0x00343c48, 0x0037404c, 0x0038424e, 0x00384450, 0x00394653, 0x003a4854, 0x003d4856, 0x00404a58, 0x00414c58, 0x00414b58, 0x00404855, 0x003d4552, 0x00383e4c, 0x00333744, 0x002f323c, 0x00282c34, 0x0024282f, 0x0024262f, 0x00242730, 0x00242730, 0x0024262e, 0x0023262d, 0x0023262d, 0x0021252c, 0x001f242a, 0x001d2128, 0x0020242c, 0x0020222c, 0x001e212a, 0x001c2026, 0x00181b20, 0x00181b20, 0x00191c21, 0x00191c22, 0x00181c23, 0x00191d24, 0x001a1e25, 0x001d2229, 0x0020242d, 0x00242834, 0x00292f3b, 0x00343947, 0x003e4756, 0x00434d5e, 0x00455062, 0x00485264, 0x00485465, 0x00495464, 0x00495462, 0x0047505f, 0x003e4654, 0x00373d4c, 0x002b313f, 0x00232836, 0x00222732, 0x00212630, 0x001f222c, 0x001c2028, 0x001a1d24, 0x00181b22, 0x00181921, 0x00191a23, 0x001d1e28, 0x00202029, 0x001e2027, 0x001e2028, 0x0020242c, 0x0024262f, 0x0024272f, 0x0024272f, 0x00252831, 0x00262934, 0x00282b35, 0x00292c37, 0x002c2f38, 0x002c3038, 0x002b3038, 0x002b3038, 0x002c323a, 0x00323740, 0x00373d47, 0x003c444e, 0x003f4753, 0x00444e5b, 0x00444f5d, 0x00404d5b, 0x00404c5b, 0x00404c5a, 0x003f4b58, 0x003b4653, 0x00384450, 0x00384450, 0x00394350, 0x0036424e, 0x0034404c, 0x00333e4a, 0x00323d49, 0x00313c48, 0x00313c48, 0x00303a45, 0x002c3740, 0x002c3740, 0x002e3841, 0x002f3843, 0x00303b45, 0x002f3843, 0x002c3540, 0x002f3843, 0x002e3843, 0x002b3540, 0x002d3742, 0x00353f4b, 0x0035414e, 0x0034404c, 0x00303c48, 0x002f3b47, 0x00303c49, 0x0032404c, 0x0032404d, 0x0031404c, 0x0031404e, 0x0032404d, 0x002f3c48, 0x002c3947, 0x002c3947, 0x002b3947, 0x002f3e4b, 0x002d3f4c, 0x002c3f4e, 0x002c404f, 0x002e4352, 0x002e4352, 0x002c4152, 0x002b4152, 0x002c4352, 0x002e4451, 0x002d4450, 0x002c4250, 0x002c404d, 0x00273846, 0x001e2e3c, 0x00192836, 0x00182834, 0x00182734, 0x00162634, 0x00162735, 0x00182a38, 0x001b2c3a, 0x001b2d3b, 0x001b2e3c, 0x001a2c3b, 0x00182b39, 0x00182c39, 0x00182c3a, 0x00182d3b, 0x00182e3b, 0x00182e3c, 0x00172d3b, 0x00142b38, 0x00142a37, 0x00142937, 0x00142836, 0x00142836, 0x00142835, 0x00132734, 0x00132734, 0x00122834, 0x00122834, 0x00122834, 0x00122834, 0x00112833, 0x00122834, 0x00122834, 0x00122834, 0x00122835, 0x00122835, 0x00122835, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00122835, 0x00122835, 0x00132835, 0x00142834, 0x00142834, 0x00142732, 0x00142731, 0x00142731, 0x00122631, 0x00102531, 0x00102430, 0x00102430, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222e, 0x000f222e, 0x000f222e, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f212c, 0x0010212c, 0x0010212c, 0x0010212c, 0x0010202c, 0x000e202c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x00102229, 0x0012242c, 0x00102a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001b4448, 0x001c4a4d, 0x001e5053, 0x00215659, 0x00235c5e, 0x00256163, 0x0027686c, 0x002e889c, 0x0034a3c3, 0x0036a8c9, 0x0036a8ca, 0x00349db8, 0x0035a0bc, 0x00359fbc, 0x002c7578, 0x002c7274, 0x002b7071, 0x002a6d6f, 0x00296b6d, 0x0028686b, 0x00276668, 0x00266466, 0x00256366, 0x00256267, 0x00246166, 0x00246064, 0x00246064, 0x00245f64, 0x00245e63, 0x00235e63, 0x00235e63, 0x00235d62, 0x00225c61, 0x00225c60, 0x00225a60, 0x002889a7, 0x002b9ac0, 0x001e5054, 0x001d4b4e, 0x001c474b, 0x001a4245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0008141a, 0x0008141a, 0x0008141a, 0x0009141a, 0x0009141a, 0x0009141a, 0x0009141a, 0x0009141a, 0x000a141c, 0x000a141d, 0x000b151e, 0x000b151e, 0x000b161e, 0x000b171f, 0x000c1820, 0x000c1820, 0x000c1a21, 0x000d1b23, 0x000d1b23, 0x000e1b23, 0x000d1c25, 0x000c1d27, 0x000c1e28, 0x000d1f2a, 0x000e212c, 0x000f222e, 0x000f232f, 0x00102430, 0x00102432, 0x00102533, 0x00102533, 0x00112634, 0x00132734, 0x00132836, 0x00132a38, 0x00142c3a, 0x00142c3b, 0x00142d3c, 0x00142d3c, 0x00162e3c, 0x00162e3c, 0x00152e3c, 0x00152e3c, 0x00142c3b, 0x00132c37, 0x00122a34, 0x00132934, 0x00142834, 0x00142834, 0x00142834, 0x00132834, 0x00112733, 0x00112632, 0x00102531, 0x00102430, 0x000f242f, 0x000f2430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00122431, 0x00122431, 0x00122532, 0x00122734, 0x00122834, 0x00132835, 0x00112833, 0x00102833, 0x00102733, 0x00132733, 0x00142935, 0x00182d3b, 0x0019303d, 0x0019303c, 0x00182e3b, 0x001c323f, 0x00253c49, 0x002a414f, 0x002c4350, 0x002b3f4c, 0x00273846, 0x00243542, 0x00243542, 0x00283845, 0x00283a46, 0x002b3a48, 0x002a3a48, 0x00283745, 0x00283742, 0x00273641, 0x002b3844, 0x0032404b, 0x0033404c, 0x0034404c, 0x002f3945, 0x002d3842, 0x00303944, 0x00313a45, 0x002f3741, 0x0028303b, 0x00232b34, 0x00232b34, 0x00252e36, 0x002b343d, 0x002f3843, 0x00333c46, 0x00353f49, 0x0036414c, 0x00384450, 0x003b4753, 0x003c4854, 0x003d4856, 0x00404957, 0x00404957, 0x003f4754, 0x003c4450, 0x00383e4b, 0x00323744, 0x002d313c, 0x00282a34, 0x0022252e, 0x0021242b, 0x0020232a, 0x001e2129, 0x001f2129, 0x001e2128, 0x001f2228, 0x001d2027, 0x001b1f25, 0x001a1e24, 0x001a1f24, 0x001c2027, 0x001c1f28, 0x001a1d26, 0x00171a1f, 0x00191c20, 0x001c1f24, 0x001d2025, 0x001c2025, 0x001a1f25, 0x001b2026, 0x001c1f26, 0x001c2026, 0x001d2026, 0x001e2129, 0x0020242d, 0x00222630, 0x00252b38, 0x002b303f, 0x00303645, 0x00343c4a, 0x00343c4a, 0x00313946, 0x002d343f, 0x002a313c, 0x002a303a, 0x00292c38, 0x00242832, 0x0020242d, 0x001e222a, 0x0020232a, 0x001a1d24, 0x00191c23, 0x00181c22, 0x00181921, 0x00171820, 0x00181921, 0x001c1d26, 0x001e1f28, 0x001e2027, 0x001c1f26, 0x001c2028, 0x001f222a, 0x0020232b, 0x0020222c, 0x0020232d, 0x0021242f, 0x00232530, 0x00242630, 0x00272a33, 0x00282c34, 0x00282c34, 0x00282c34, 0x00282e36, 0x002d323b, 0x00343a43, 0x00384048, 0x003c444f, 0x00404a57, 0x00444f5c, 0x00424f5c, 0x00414e5c, 0x00424d5b, 0x00414c59, 0x003d4955, 0x00394551, 0x00384450, 0x0038424e, 0x0035414d, 0x00343f4b, 0x00313c48, 0x002f3b47, 0x002e3a46, 0x00303946, 0x002e3843, 0x002b343d, 0x0029343c, 0x002b343d, 0x002a343e, 0x002c3640, 0x002c3640, 0x002a343f, 0x002c3741, 0x002f3843, 0x002c3640, 0x0029333d, 0x002e3843, 0x00333e48, 0x00323d48, 0x002d3945, 0x002c3844, 0x002d3946, 0x002e3948, 0x00303c4a, 0x00303e4c, 0x0031404d, 0x0033404e, 0x00313f4c, 0x002c3a48, 0x00293844, 0x00283845, 0x002d3c49, 0x002c3e4b, 0x002d3f4e, 0x002c3e4e, 0x002c3f4e, 0x002f4453, 0x00314556, 0x00304455, 0x002f4654, 0x002f4553, 0x002c4450, 0x002c414f, 0x002b3f4c, 0x00253744, 0x001f2f3c, 0x001a2937, 0x00192834, 0x00182835, 0x00172836, 0x00182938, 0x001b2c3b, 0x001c2e3c, 0x001c303d, 0x001c303e, 0x001b2e3c, 0x00192c3a, 0x00182c3a, 0x00182c3a, 0x00182c3b, 0x00182e3b, 0x00182e3c, 0x00182e3b, 0x00142b38, 0x00142a37, 0x00142937, 0x00142836, 0x00142836, 0x00142836, 0x00142835, 0x00142835, 0x00132834, 0x00122834, 0x00122834, 0x00122834, 0x00122834, 0x00122834, 0x00122834, 0x00122834, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00142834, 0x00142834, 0x00142732, 0x00142731, 0x00142731, 0x00122631, 0x00102531, 0x00102430, 0x00102430, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222e, 0x000f222e, 0x000f222e, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x000f222c, 0x0010222c, 0x0010222c, 0x0010212c, 0x0010202c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x00102229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00153338, 0x0016363b, 0x00183d41, 0x001a4347, 0x001c484c, 0x001e4f51, 0x00205457, 0x00235a5c, 0x00246062, 0x00266467, 0x0028686b, 0x002b747b, 0x0030899c, 0x00349bb6, 0x003397b0, 0x00349eba, 0x0037a8c9, 0x00349fbc, 0x00308ea3, 0x002c7982, 0x002a6f71, 0x00296b6d, 0x0028686a, 0x00276668, 0x00266466, 0x00266264, 0x00246062, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0022585b, 0x002888a6, 0x002b9bc0, 0x001e5054, 0x001d4c50, 0x001c474b, 0x001a4347, 0x00183d41, 0x00183a3e, 0x00153439, 0x00142e34, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0009141b, 0x0009141b, 0x0009141b, 0x000a141b, 0x000a141b, 0x000a141b, 0x000a141b, 0x000a141b, 0x000a141c, 0x000b151c, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c1720, 0x000d1720, 0x000c1820, 0x000d1921, 0x000e1a23, 0x000e1a23, 0x000f1b24, 0x000f1c24, 0x000e1c26, 0x000e1e27, 0x000f1f29, 0x000f212c, 0x0010232d, 0x0010242e, 0x00102430, 0x000f2432, 0x000f2533, 0x00102634, 0x00112834, 0x00122835, 0x00122a36, 0x00132b38, 0x00142c39, 0x00142d3b, 0x00142e3c, 0x00152e3c, 0x00162e3c, 0x00172e3c, 0x00142e3c, 0x00142e3c, 0x00142d3b, 0x00122c38, 0x00112b35, 0x00122a34, 0x00132934, 0x00122834, 0x00132934, 0x00132834, 0x00112833, 0x00112733, 0x00102732, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00122531, 0x00132632, 0x00132632, 0x00132834, 0x00122834, 0x00122836, 0x00122834, 0x00122834, 0x00122834, 0x00142834, 0x00162a37, 0x001a303c, 0x001b313f, 0x0019303d, 0x00172d3a, 0x001a303e, 0x00253c49, 0x002b4250, 0x002c4250, 0x002b3f4c, 0x00283b48, 0x00253846, 0x00283947, 0x002c3e4a, 0x00293a47, 0x002b3a48, 0x002a3948, 0x00293846, 0x00283843, 0x00293844, 0x002d3c47, 0x0034404c, 0x0034414d, 0x0038434e, 0x00303b45, 0x002e3843, 0x00303a45, 0x00303944, 0x0028303c, 0x00242c37, 0x00222a34, 0x00252d37, 0x0028313a, 0x002d3640, 0x00303944, 0x00313c46, 0x0035404a, 0x0036424c, 0x00394450, 0x003c4854, 0x003c4854, 0x003d4854, 0x003d4854, 0x003d4754, 0x0038404d, 0x00343c48, 0x002f3542, 0x00292e3b, 0x00252934, 0x0023252e, 0x001f2128, 0x001e2127, 0x001e2128, 0x001c1f27, 0x001a1d24, 0x001a1d23, 0x001b1e23, 0x00191c21, 0x0015191e, 0x00171c20, 0x00181d22, 0x00181d23, 0x00181b23, 0x00161920, 0x00171a1f, 0x001c2023, 0x00202328, 0x001f2227, 0x001a1d22, 0x00181c21, 0x00181c20, 0x00191c21, 0x001a1d22, 0x001b1e21, 0x001a1d22, 0x001c2026, 0x001d2128, 0x001e2129, 0x001c2028, 0x001b1d28, 0x001c1e28, 0x001c1f28, 0x001d222a, 0x001f242c, 0x001f242b, 0x0020242c, 0x001f222a, 0x001c1e27, 0x001c2028, 0x001e2128, 0x001c1f26, 0x00161920, 0x00181b21, 0x00191c23, 0x001a1c23, 0x00181920, 0x0016181f, 0x0014161f, 0x00171820, 0x001c1f26, 0x001c2027, 0x001c1f27, 0x001c1f28, 0x001c1f28, 0x001d2029, 0x001d202a, 0x001e212b, 0x001d202a, 0x001e212b, 0x0021242c, 0x0024262f, 0x00242830, 0x00232830, 0x00252a32, 0x00282d35, 0x002f343c, 0x00343b44, 0x0039424e, 0x003f4854, 0x00404b59, 0x00404d5a, 0x00404c5a, 0x00404c59, 0x00404c58, 0x003c4854, 0x00384450, 0x0036424e, 0x0037404d, 0x0034404c, 0x00333e4b, 0x00303c48, 0x002c3844, 0x002b3642, 0x002c3541, 0x002c353f, 0x0028333c, 0x0028313a, 0x0029333c, 0x002a333d, 0x002b343f, 0x002b343f, 0x002a343e, 0x002a343f, 0x002d3741, 0x002e3842, 0x0029343e, 0x0028323c, 0x00303b45, 0x00323d48, 0x002e3a45, 0x002d3844, 0x002c3844, 0x002a3442, 0x002b3644, 0x002c3a48, 0x00303f4c, 0x0033404e, 0x0033404e, 0x002f3c4a, 0x002b3a47, 0x00283844, 0x002b3c48, 0x002d3d4c, 0x002f3f4f, 0x002f3f50, 0x002b3d4d, 0x002c4050, 0x00334858, 0x00324858, 0x00314856, 0x002e4552, 0x0029404d, 0x00283d4a, 0x00273b48, 0x00243544, 0x0020303d, 0x001c2b38, 0x00182834, 0x00182835, 0x00182837, 0x00192b39, 0x001a2d3c, 0x001c2f3d, 0x001d3040, 0x001e3140, 0x001d303f, 0x001b2e3c, 0x00192d3b, 0x00192c3c, 0x001a2d3c, 0x00192e3c, 0x00182f3c, 0x00182f3c, 0x00152c38, 0x00132936, 0x00142836, 0x00142836, 0x00142836, 0x00142836, 0x00142836, 0x00142835, 0x00132935, 0x00132935, 0x00132935, 0x00132935, 0x00132935, 0x00132935, 0x00132935, 0x00132936, 0x00132a37, 0x00132a37, 0x00132a37, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132935, 0x00122833, 0x00112833, 0x00132833, 0x00142833, 0x00142833, 0x00122733, 0x00102531, 0x00102430, 0x00102430, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x000f222e, 0x000f222e, 0x000f222e, 0x000f222d, 0x0010212d, 0x0010212d, 0x0010212d, 0x0010222e, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010222c, 0x000f212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000e212c, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00153338, 0x0016363b, 0x00183c40, 0x001a4245, 0x001c484c, 0x001e4f51, 0x00205457, 0x0022595c, 0x00245e60, 0x00256364, 0x00286769, 0x00296b6d, 0x002a6d6f, 0x002b7073, 0x002b7375, 0x002d7b83, 0x00308c9f, 0x00349cb7, 0x0035a5c6, 0x0036a6c8, 0x003298b4, 0x00286b6e, 0x0028686a, 0x00276568, 0x00266466, 0x00256163, 0x00246062, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022585b, 0x002989a6, 0x002c9bc0, 0x001f5256, 0x001d4c50, 0x001c484c, 0x001b4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00142e34, 0x00122c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b151c, 0x000b151c, 0x000b151c, 0x000b151c, 0x000b151c, 0x000b151c, 0x000b151c, 0x000b151c, 0x000b151c, 0x000c161d, 0x000c161f, 0x000c161f, 0x000d1720, 0x000d1820, 0x000e1820, 0x000d1922, 0x000e1a23, 0x000f1c24, 0x000f1c24, 0x00101c24, 0x000f1c24, 0x000e1c26, 0x000e1e27, 0x000f1f29, 0x000f222c, 0x0010242e, 0x0010242f, 0x00102430, 0x00102533, 0x00102634, 0x00112834, 0x00122835, 0x00122836, 0x00132a37, 0x00142c38, 0x00142c39, 0x00142d3b, 0x00142f3c, 0x00162e3c, 0x00172f3d, 0x00172f3d, 0x00142f3c, 0x00142f3c, 0x00142e3c, 0x00132d38, 0x00122c37, 0x00132b36, 0x00142a35, 0x00132935, 0x00142a35, 0x00132934, 0x00122834, 0x00122834, 0x00112733, 0x00102531, 0x00102531, 0x00122531, 0x00122431, 0x00122531, 0x00102631, 0x00102531, 0x00102531, 0x00122632, 0x00132733, 0x00132733, 0x00132934, 0x00132935, 0x00132a36, 0x00132934, 0x00132934, 0x00132934, 0x00142934, 0x00162b38, 0x001a303d, 0x001a303e, 0x0019303c, 0x00182f3c, 0x001c3340, 0x00273d4c, 0x002c4150, 0x002c4250, 0x002a3f4c, 0x00283c49, 0x00273a48, 0x002a3c49, 0x002f404c, 0x00283a46, 0x00283845, 0x00293846, 0x00283845, 0x00283743, 0x00283843, 0x002d3c47, 0x00323f4b, 0x0034414d, 0x0037434e, 0x002f3844, 0x00303944, 0x00323c48, 0x00303945, 0x0026303b, 0x00252e39, 0x00242d37, 0x0028303a, 0x002a343e, 0x00303843, 0x00313b46, 0x00323c48, 0x0035414c, 0x00384450, 0x003a4551, 0x003b4753, 0x003c4753, 0x003d4854, 0x003c4854, 0x0038424e, 0x00303844, 0x002c343f, 0x00262c38, 0x00202731, 0x001e232d, 0x001e232a, 0x001e2128, 0x001b1e24, 0x001b1e24, 0x001a1d24, 0x00171920, 0x00181b20, 0x001a1d22, 0x00181c20, 0x0016191e, 0x00181c21, 0x00181d22, 0x00161b21, 0x00141820, 0x00171a21, 0x001c1f24, 0x001b1e22, 0x00191d21, 0x0016191e, 0x0013161a, 0x0011161a, 0x0011171b, 0x00171b20, 0x001a1d22, 0x00181c20, 0x00191c20, 0x001b1e22, 0x001c1f24, 0x00181b20, 0x0018191f, 0x00181a20, 0x001c1d23, 0x001d1f24, 0x001e2026, 0x001d2028, 0x001d2027, 0x001b1e24, 0x001c1d24, 0x00181920, 0x00191c21, 0x001d1f24, 0x001c1d24, 0x00181a1f, 0x0015181d, 0x00171a20, 0x001a1d24, 0x00191c23, 0x00151820, 0x0010141c, 0x0010131b, 0x0014171f, 0x00181c23, 0x001a1d26, 0x00191c24, 0x00191c24, 0x001c2028, 0x00191c25, 0x001c2028, 0x001a1d25, 0x001a1d26, 0x001c1f28, 0x0020232c, 0x0020232b, 0x001f232b, 0x0020252d, 0x00232830, 0x00272d36, 0x002e343e, 0x00323844, 0x0038404c, 0x003b4551, 0x003d4854, 0x003d4955, 0x003c4854, 0x003c4854, 0x003b4753, 0x00384450, 0x0036414d, 0x00343d4a, 0x00303b47, 0x00303c48, 0x002e3a46, 0x002b3541, 0x0028323e, 0x002b3440, 0x002c353f, 0x002c353e, 0x0029323b, 0x0029323b, 0x002c343e, 0x002c3540, 0x002b343f, 0x0029333d, 0x0026303b, 0x0027303c, 0x002a3440, 0x002a3440, 0x00252f3b, 0x002c3843, 0x00323d49, 0x002f3b46, 0x002f3b47, 0x002f3b48, 0x002a3543, 0x00273340, 0x00293644, 0x002c3947, 0x00303c4b, 0x0032404d, 0x00303d4c, 0x002f3e4c, 0x002c3c4a, 0x002c3c49, 0x002c3d4c, 0x00304050, 0x00304051, 0x002d404f, 0x002c4050, 0x00334758, 0x00344a5a, 0x00334957, 0x002f4552, 0x00293f4c, 0x00243948, 0x00243847, 0x00243744, 0x00213140, 0x001c2c39, 0x00182834, 0x00182835, 0x00192a38, 0x001b2c3b, 0x001b2f3d, 0x001d3040, 0x001e3242, 0x001e3341, 0x001d3240, 0x001c303f, 0x001b303d, 0x001b2e3d, 0x001b2e3d, 0x001a303d, 0x001b313f, 0x001a303f, 0x00172d3b, 0x00142a37, 0x00142937, 0x00142836, 0x00142937, 0x00142a37, 0x00152a37, 0x00152a37, 0x00142a37, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132936, 0x00132b38, 0x00132c38, 0x00132c38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142a37, 0x00122834, 0x00112833, 0x00122834, 0x00142934, 0x00142834, 0x00122733, 0x00102531, 0x00102430, 0x00112430, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010232f, 0x0010222f, 0x0011222f, 0x0010222f, 0x0010232e, 0x0010232d, 0x0011232d, 0x0010222c, 0x0010222c, 0x000f222c, 0x000f222c, 0x000f222c, 0x000f222c, 0x000f222c, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00153338, 0x0016363b, 0x00183c40, 0x00194245, 0x001c474b, 0x001e4d50, 0x00205356, 0x0022585b, 0x00245d60, 0x00256264, 0x00276668, 0x0028696c, 0x00296c6f, 0x002a6e70, 0x002b7072, 0x002b7072, 0x002b7173, 0x002c7174, 0x002c777e, 0x003296b0, 0x0034a4c5, 0x00286b6e, 0x00286769, 0x00276568, 0x00266364, 0x00256163, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x002989a6, 0x002c9bc0, 0x00205256, 0x001d4c50, 0x001c484c, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00142e34, 0x00122c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b161d, 0x000b161d, 0x000b161d, 0x000b161c, 0x000b161c, 0x000b161c, 0x000b161c, 0x000b161c, 0x000b161e, 0x000c1720, 0x000c1620, 0x000d1721, 0x000d1822, 0x000d1922, 0x000d1923, 0x000d1b24, 0x000e1c24, 0x000f1c24, 0x000e1c24, 0x000e1c24, 0x000f1d26, 0x000f1e27, 0x000f1f28, 0x0010202b, 0x000f212c, 0x0010232d, 0x0010242f, 0x00102531, 0x00102634, 0x00112834, 0x00112834, 0x00122836, 0x00142a37, 0x00142b38, 0x00142c39, 0x00142c39, 0x00142d3b, 0x00142f3c, 0x00152e3c, 0x00162f3d, 0x00162f3d, 0x00142f3c, 0x00142f3c, 0x00142f3c, 0x00142e3b, 0x00142d3a, 0x00142c39, 0x00142b38, 0x00142a37, 0x00142b37, 0x00142a37, 0x00132935, 0x00132934, 0x00122834, 0x00112632, 0x00112632, 0x00122631, 0x00132631, 0x00122631, 0x00112730, 0x00112731, 0x00112732, 0x00112733, 0x00132733, 0x00142834, 0x00142834, 0x00142a35, 0x00152a35, 0x00142a35, 0x00142a35, 0x00142a35, 0x00152a35, 0x00162b38, 0x001a303c, 0x001a303f, 0x0019303e, 0x001c3140, 0x00213745, 0x00294050, 0x002b4150, 0x002b4150, 0x002a3f4c, 0x00283c4a, 0x00283b49, 0x002a3c4a, 0x002f404d, 0x00273844, 0x00273643, 0x00293844, 0x00283643, 0x00263440, 0x00283540, 0x002c3945, 0x002f3c48, 0x00323f4b, 0x0034404c, 0x002c3743, 0x002f3945, 0x00313b48, 0x002c3541, 0x0026303b, 0x0029333c, 0x0028303b, 0x0027303a, 0x002b3540, 0x00323c48, 0x00343f4b, 0x0034404c, 0x0037444f, 0x00394551, 0x00394652, 0x00394551, 0x003a4551, 0x003c4552, 0x0038404c, 0x00313944, 0x002c333c, 0x00262e37, 0x00212730, 0x001e242c, 0x001c2028, 0x001b1f26, 0x001c2027, 0x00161a20, 0x0014181e, 0x0013161c, 0x0014181f, 0x00181c22, 0x00191d23, 0x00181c23, 0x00191d24, 0x001b1f25, 0x001c2028, 0x00181e25, 0x00181d24, 0x001b1e26, 0x001c1e25, 0x00181b21, 0x00181c22, 0x001a1c23, 0x00191c22, 0x00161a20, 0x00161b20, 0x001a1f24, 0x00181c22, 0x0014181d, 0x00191d20, 0x001c2024, 0x00181d21, 0x000e1217, 0x00101318, 0x0015181c, 0x00181c20, 0x001a1d21, 0x001a1d22, 0x00181c22, 0x00181c23, 0x001e2128, 0x00202229, 0x0016181f, 0x0013141c, 0x0014161c, 0x0015181c, 0x0014171c, 0x00121419, 0x00111319, 0x00161920, 0x001c1f26, 0x00181c23, 0x00141820, 0x0012151d, 0x00141820, 0x00171a21, 0x00161820, 0x0014171f, 0x001a1c25, 0x001b1f27, 0x00171c24, 0x001a1e26, 0x001b1e27, 0x001b1f27, 0x00191c25, 0x001c1f28, 0x001d212a, 0x001e232c, 0x0020252e, 0x0020262f, 0x00232832, 0x00282e38, 0x002d323c, 0x00313742, 0x00333b45, 0x0038414c, 0x003c4650, 0x003c4853, 0x003b4753, 0x003b4753, 0x0037434f, 0x0035404c, 0x00343e4a, 0x00303945, 0x002e3844, 0x002f3844, 0x002d3843, 0x0027303c, 0x0028313c, 0x002c353f, 0x002e3841, 0x002d3842, 0x002b343f, 0x002b3440, 0x002d3843, 0x002c3842, 0x002c3743, 0x002c3643, 0x00283440, 0x0026303d, 0x0028323f, 0x0024303c, 0x00283440, 0x00303c48, 0x002c3845, 0x002c3845, 0x00303c48, 0x002f3a48, 0x002a3544, 0x002c3947, 0x002b3947, 0x00283744, 0x002f3d4c, 0x002f3e4c, 0x00324250, 0x00324351, 0x002d3f4c, 0x002c3e4d, 0x00314352, 0x00334454, 0x002f4251, 0x002f4453, 0x00324858, 0x00324858, 0x00304855, 0x002e4451, 0x002b404e, 0x00283d4b, 0x00253a49, 0x00243845, 0x00213340, 0x001c2c39, 0x00182835, 0x001a2a38, 0x001c2d3c, 0x001c303e, 0x001c3040, 0x001c3243, 0x001e3343, 0x001e3340, 0x001d323f, 0x001d323f, 0x001c313f, 0x001c303e, 0x001b2f3d, 0x001b303e, 0x001c3340, 0x001c3340, 0x00182f3c, 0x00162c39, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142b38, 0x00142b38, 0x00132c38, 0x00132b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00132a37, 0x00122934, 0x00112834, 0x00122834, 0x00142934, 0x00142834, 0x00122733, 0x00102532, 0x00102431, 0x00112430, 0x00112430, 0x0010232e, 0x0010242e, 0x0010232e, 0x0010232e, 0x0010232e, 0x000f232e, 0x000f232e, 0x0010232e, 0x0010232e, 0x0010232e, 0x0010242e, 0x0010242d, 0x0011242d, 0x0010242d, 0x0010232d, 0x0010242d, 0x0010242d, 0x0010242d, 0x0010242d, 0x0010242d, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x00102229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00153338, 0x0016363b, 0x00183c40, 0x00194245, 0x001c474b, 0x001d4d50, 0x00205356, 0x0022585b, 0x00245d60, 0x00256163, 0x00276568, 0x0028686b, 0x00296b6d, 0x00296d6f, 0x002b6f70, 0x002c7071, 0x002b7071, 0x002c7378, 0x002e8494, 0x00329dbc, 0x0034a3c5, 0x00286a6d, 0x00276668, 0x00266467, 0x00256264, 0x00246062, 0x00245f61, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x0022585b, 0x002989a6, 0x002c9bc0, 0x001f5256, 0x001d4c50, 0x001c484c, 0x001b4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00142e34, 0x00122c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a171e, 0x000a171e, 0x000a181e, 0x000a181e, 0x000a181e, 0x000a181e, 0x000a181e, 0x000a181f, 0x000c1821, 0x000c1822, 0x000d1823, 0x000e1824, 0x000d1925, 0x000d1b25, 0x000c1c25, 0x000d1c25, 0x000d1d26, 0x000e1e27, 0x000e1e28, 0x000e1f28, 0x000e2028, 0x000f2029, 0x000f2029, 0x0010202c, 0x000f212c, 0x000f222c, 0x0010242e, 0x00112530, 0x00112734, 0x00122835, 0x00132936, 0x00142a37, 0x00142b38, 0x00142c38, 0x00142c39, 0x00142d39, 0x00132d3b, 0x00132f3c, 0x00142f3c, 0x0015303d, 0x0015303d, 0x0015303d, 0x0015303d, 0x00142f3c, 0x00142f3c, 0x00152d3c, 0x00152d3c, 0x00142c39, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142a36, 0x00142a35, 0x00132834, 0x00122733, 0x00112632, 0x00132631, 0x00132630, 0x00142732, 0x00132834, 0x00132934, 0x00132934, 0x00132934, 0x00132834, 0x00142834, 0x00142834, 0x00152934, 0x00162935, 0x00162935, 0x00152a35, 0x00152a35, 0x00152a36, 0x00162b38, 0x001a2f3c, 0x001b3140, 0x001c3241, 0x001d3444, 0x00223a49, 0x00294051, 0x00294050, 0x00283f4d, 0x00283d4c, 0x00283c4c, 0x002a3d4d, 0x002c404e, 0x002f414e, 0x00263844, 0x00273644, 0x002b3846, 0x00283542, 0x0024323e, 0x0024323d, 0x00283642, 0x002c3944, 0x002f3c48, 0x00303c48, 0x002a3642, 0x002e3945, 0x002f3a46, 0x00293440, 0x0026323c, 0x0028343c, 0x0028333c, 0x00252f38, 0x002e3843, 0x0037424e, 0x0036444f, 0x0034434f, 0x00384551, 0x00384652, 0x00384651, 0x00384450, 0x0037414d, 0x00363e4b, 0x00313844, 0x002c333d, 0x00293038, 0x00252b33, 0x0021262e, 0x001d222a, 0x001c2028, 0x00191d24, 0x001a1f25, 0x00181c21, 0x0014181e, 0x0014181f, 0x00151a20, 0x00161b21, 0x00171c23, 0x00181d25, 0x00181d24, 0x00161b21, 0x001e242a, 0x001d242a, 0x001b2026, 0x001a1f25, 0x00181c22, 0x0014181f, 0x00181c22, 0x001b1e24, 0x001b2026, 0x001b2025, 0x00191e24, 0x00181d24, 0x0014181f, 0x0014191d, 0x001b2024, 0x001c2025, 0x0014181c, 0x000d1116, 0x000f1216, 0x00121517, 0x0016191a, 0x00181b1d, 0x00171a1e, 0x00171b21, 0x001b2026, 0x001c2027, 0x001c2026, 0x0015181f, 0x000f1218, 0x000f1218, 0x00101418, 0x0013161b, 0x000c1014, 0x00101318, 0x0014191f, 0x00191e24, 0x001a1f25, 0x00181c24, 0x00181d24, 0x00181c23, 0x00181c22, 0x00161920, 0x0012151c, 0x00161a21, 0x00191e24, 0x00181e24, 0x00191f27, 0x00181c24, 0x00171b24, 0x00171c25, 0x00181c26, 0x00181d27, 0x001b202a, 0x00202730, 0x001f252d, 0x001f252d, 0x0020252f, 0x00242933, 0x002b2f39, 0x002d343f, 0x00313844, 0x0038414c, 0x003c4651, 0x003b4652, 0x003a4652, 0x0037434f, 0x0035404c, 0x00333d49, 0x00303a46, 0x002c3640, 0x002e3842, 0x00303944, 0x0029333d, 0x00242f39, 0x0026323c, 0x002b3741, 0x002f3b47, 0x002d3945, 0x002b3743, 0x002e3a46, 0x002b3844, 0x002b3843, 0x00303b48, 0x002f3b47, 0x002b3743, 0x0027333f, 0x00232f3c, 0x00242f3c, 0x002e3845, 0x002c3743, 0x00293440, 0x002d3945, 0x002d3948, 0x002c3848, 0x002e3c4a, 0x002c3d4a, 0x00283846, 0x002c3a49, 0x002e3d4c, 0x00334251, 0x00324351, 0x002c3f4d, 0x002c4050, 0x00304454, 0x00324755, 0x00304452, 0x00304555, 0x00314858, 0x002f4856, 0x002d4653, 0x002c4350, 0x002a404e, 0x0029404c, 0x00263d4a, 0x00243946, 0x001f333f, 0x001a2c38, 0x00192b38, 0x001b2d3a, 0x001c303d, 0x001d3340, 0x001d3341, 0x001c3442, 0x001e3442, 0x001d3340, 0x001d3240, 0x001d3240, 0x001c3240, 0x001c303e, 0x0019303c, 0x001a303e, 0x001b3340, 0x001b3340, 0x001a303e, 0x00182e3b, 0x00162c3a, 0x00152c39, 0x00162c3a, 0x00142c39, 0x00132c38, 0x00132c38, 0x00142b38, 0x00142a38, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142b38, 0x00142b38, 0x00142c38, 0x00132c38, 0x00132c38, 0x00132c38, 0x00132c38, 0x00132c38, 0x00132c38, 0x00122b37, 0x00122b35, 0x00112a34, 0x00122934, 0x00132934, 0x00132733, 0x00122733, 0x00102531, 0x00112431, 0x00122431, 0x00112430, 0x0011242d, 0x0011242c, 0x0010242c, 0x0010242c, 0x0010232c, 0x000f242d, 0x000f242d, 0x000f242d, 0x0010232d, 0x000f232d, 0x0010242e, 0x0010242e, 0x0010242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x00102229, 0x0012242c, 0x00112a30, 0x00142e34, 0x00153338, 0x0016363b, 0x00183d41, 0x001b4347, 0x001c484c, 0x001e4d50, 0x00205356, 0x0022585b, 0x00245c5f, 0x00256163, 0x00276467, 0x0028686a, 0x00286a6c, 0x002a6c6f, 0x002a7074, 0x002d7f8c, 0x003093aa, 0x0034a3c3, 0x0034a6c9, 0x00329dbd, 0x002e8aa0, 0x0028686b, 0x00276568, 0x00256364, 0x00256163, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00245c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0022585b, 0x002888a6, 0x002b9bc0, 0x001e5054, 0x001d4c50, 0x001c474b, 0x001a4347, 0x00183d41, 0x00183a3e, 0x00153439, 0x00142e34, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a1820, 0x000a1820, 0x000a1820, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1920, 0x000b1920, 0x000c1923, 0x000c1924, 0x000d1824, 0x000e1925, 0x000f1b27, 0x000e1c27, 0x000d1c27, 0x000d1d27, 0x000e1e28, 0x000f1f28, 0x000f2029, 0x000f202a, 0x000f202a, 0x000f202a, 0x000f202a, 0x0010202c, 0x000f212c, 0x000f222c, 0x0010242e, 0x00112530, 0x00112734, 0x00132936, 0x00132936, 0x00142a38, 0x00142b38, 0x00142c38, 0x00142c39, 0x00142d39, 0x00132d3b, 0x00132f3c, 0x00142f3c, 0x0015303d, 0x0015303d, 0x0015303d, 0x0015303d, 0x00152f3c, 0x00152e3c, 0x00152d3c, 0x00152c3c, 0x00142c3a, 0x00142b39, 0x00142b38, 0x00142b38, 0x00142a36, 0x00142a35, 0x00142934, 0x00142834, 0x00142834, 0x00142834, 0x00142834, 0x00142834, 0x00142934, 0x00132934, 0x00132934, 0x00132934, 0x00132934, 0x00142934, 0x00142934, 0x00142934, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a36, 0x00162b38, 0x001a303d, 0x001b3240, 0x001c3442, 0x001d3544, 0x00233b4a, 0x00284050, 0x00283f4e, 0x00273d4c, 0x00283e4d, 0x00293e4d, 0x002c4050, 0x002d4250, 0x00304451, 0x00283948, 0x00283846, 0x002b3946, 0x00283543, 0x0025333e, 0x0024313d, 0x00283642, 0x002b3844, 0x002c3b46, 0x002c3a44, 0x0027343e, 0x002c3844, 0x00303c48, 0x002b3742, 0x002b3740, 0x0029353d, 0x0028343c, 0x00263039, 0x00303b46, 0x00384450, 0x00384450, 0x00364550, 0x00394753, 0x00394753, 0x00384650, 0x0037434e, 0x00333d49, 0x00313946, 0x002f3540, 0x002c323c, 0x00282f37, 0x00242a32, 0x0020252d, 0x001d222a, 0x001d222a, 0x001a1f26, 0x00171c22, 0x0014191f, 0x0013171d, 0x0013181f, 0x0014191f, 0x00161b21, 0x00161a22, 0x00141921, 0x0012171e, 0x00161b21, 0x001c2128, 0x00192025, 0x00181c23, 0x00161b21, 0x00151a20, 0x00141920, 0x00181c23, 0x001b1e24, 0x00191e24, 0x00181c23, 0x00171c22, 0x0014181f, 0x00161b21, 0x00181d22, 0x00191f23, 0x00181d22, 0x00101519, 0x000d1115, 0x00101315, 0x00121516, 0x0015191a, 0x00161a1c, 0x0014181c, 0x00171b21, 0x001a1f25, 0x00191e24, 0x00181b22, 0x0014171e, 0x00101319, 0x000d1017, 0x000d1015, 0x00111419, 0x00101317, 0x00111419, 0x0013181d, 0x0014191f, 0x00171c23, 0x00171c24, 0x00191e26, 0x00181d24, 0x00161b21, 0x00161b21, 0x00161b20, 0x00181d24, 0x00181d24, 0x00151c22, 0x00181e24, 0x00161b23, 0x00131820, 0x00191d27, 0x001a1e28, 0x00181d27, 0x00191f28, 0x001f252f, 0x001e242c, 0x001b2129, 0x001c212b, 0x0020242f, 0x00262b34, 0x002a3039, 0x002d343e, 0x00333b44, 0x0038414c, 0x003b4450, 0x003a4450, 0x00394450, 0x0036414e, 0x00343e4b, 0x00303a46, 0x002c3640, 0x002c3640, 0x002d3842, 0x002a343f, 0x0026313b, 0x0024303a, 0x0028343f, 0x002e3a46, 0x002e3a46, 0x002a3642, 0x002e3a46, 0x002c3a45, 0x00293642, 0x00293642, 0x002c3844, 0x002f3b47, 0x002c3743, 0x0024303c, 0x00212c38, 0x0026303c, 0x002a3441, 0x00293440, 0x002a3642, 0x00293443, 0x00293544, 0x002c3948, 0x002c3d4a, 0x002c3c4a, 0x002c3c4b, 0x002d3c4c, 0x00334250, 0x00314250, 0x002a3d4b, 0x002c4050, 0x00304454, 0x00314655, 0x00314554, 0x00304655, 0x00304856, 0x002c4554, 0x002b4450, 0x002a414f, 0x002a404d, 0x0029404c, 0x00283f4c, 0x00263b48, 0x001e333f, 0x001a2c38, 0x001c2e3b, 0x001c303c, 0x001e333f, 0x001f3440, 0x001e3542, 0x001d3544, 0x001f3443, 0x001e3240, 0x001d3240, 0x001d3240, 0x001c3140, 0x001c313e, 0x0019303d, 0x001a313e, 0x001b3340, 0x001b3340, 0x001a303d, 0x00182e3c, 0x00172d3b, 0x00172d3a, 0x00172d3a, 0x00152d3a, 0x00142c39, 0x00142c39, 0x00142c39, 0x00142b38, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142b38, 0x00142b38, 0x00142c38, 0x00132c38, 0x00132c38, 0x00132c38, 0x00132c38, 0x00132c38, 0x00132c38, 0x00122b37, 0x00122b35, 0x00112a34, 0x00122934, 0x00132934, 0x00132834, 0x00122733, 0x00102531, 0x00112431, 0x00122431, 0x00112430, 0x0011242d, 0x0011242c, 0x0010242c, 0x0010242c, 0x0010232c, 0x000e252e, 0x000e252e, 0x000e242d, 0x000f242d, 0x000f242d, 0x0010242e, 0x0010242e, 0x0010242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013282e, 0x00102a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4347, 0x001c484c, 0x001d4d50, 0x00205356, 0x0021585b, 0x00245c5f, 0x00256163, 0x00266467, 0x0028696c, 0x002a757f, 0x002f8ca2, 0x00339fbe, 0x0034a6c9, 0x0034a4c5, 0x003094ae, 0x002c7c8a, 0x00286d71, 0x0028686a, 0x00276668, 0x00266466, 0x00256264, 0x00246062, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00235c5e, 0x00245c5e, 0x00235a5c, 0x00235a5c, 0x00235a5c, 0x00235a5c, 0x00235a5c, 0x0021595c, 0x0022585b, 0x0021575a, 0x002888a6, 0x002b9ac0, 0x001e5054, 0x001d4b4e, 0x001c4649, 0x001a4245, 0x00183d41, 0x0017383c, 0x00153439, 0x00142e34, 0x00122a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a1a21, 0x000a1a21, 0x000a1a21, 0x000a1b22, 0x000a1b22, 0x000a1b22, 0x000a1b22, 0x000a1b23, 0x000b1b25, 0x000c1a27, 0x000d1a26, 0x000e1a26, 0x000f1c28, 0x000f1d28, 0x000e1d28, 0x000e1e28, 0x000f1f29, 0x0010202b, 0x0010202b, 0x000f202b, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f212c, 0x000f222c, 0x0010242e, 0x00112530, 0x00112734, 0x00132936, 0x00132936, 0x00142a37, 0x00142a37, 0x00142b38, 0x00142c39, 0x00142c39, 0x00142d3b, 0x00142f3c, 0x00142f3c, 0x0015303d, 0x0015303d, 0x0015303d, 0x0015303d, 0x00162f3d, 0x00162e3c, 0x00172c3c, 0x00172c3c, 0x00152c3b, 0x00152c3b, 0x00152c3b, 0x00152c3b, 0x00142a38, 0x00142a37, 0x00142936, 0x00142934, 0x00142934, 0x00152834, 0x00162834, 0x00152834, 0x00142a35, 0x00142a36, 0x00142a35, 0x00142a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00162b37, 0x001a303c, 0x001c3341, 0x001d3544, 0x001f3745, 0x00243c4b, 0x00284050, 0x00273e4e, 0x00283e4d, 0x002a4050, 0x002b4050, 0x002c4152, 0x002d4252, 0x00304554, 0x00293c4b, 0x00293a48, 0x002a3946, 0x00283644, 0x0024333f, 0x0024313d, 0x00293842, 0x002a3843, 0x00293742, 0x0027343e, 0x0024323c, 0x002c3843, 0x00303c47, 0x002e3a44, 0x002f3b44, 0x002c3841, 0x0028343d, 0x0028343c, 0x00303c47, 0x0038434f, 0x00384450, 0x00384752, 0x00384652, 0x00384551, 0x0038444f, 0x00333d48, 0x002e3843, 0x002f3742, 0x002c343f, 0x002b313a, 0x00282e36, 0x00242931, 0x001f232b, 0x001b1f28, 0x00161b23, 0x0013181f, 0x0011171d, 0x0011161c, 0x0013181f, 0x0012181f, 0x00151c21, 0x00171d24, 0x00161d24, 0x00161c24, 0x00141920, 0x0010171c, 0x00141c21, 0x00161c23, 0x00181c23, 0x00171c22, 0x00161b21, 0x00181c23, 0x00191d24, 0x001a1d24, 0x0014181e, 0x0013181e, 0x00141920, 0x0013181e, 0x00161b20, 0x00151a20, 0x00141a1e, 0x0014181d, 0x0010151a, 0x0012161a, 0x00101418, 0x00111417, 0x00141819, 0x0015181c, 0x0014181c, 0x00181c22, 0x001b2025, 0x00191e24, 0x00191d24, 0x00171920, 0x0013151c, 0x000f1218, 0x000e1116, 0x0012151a, 0x00171a1f, 0x0012151a, 0x0011171c, 0x0014181f, 0x00171c23, 0x00181c24, 0x001a1e26, 0x001c2027, 0x00181c23, 0x0015181f, 0x001a1d24, 0x001c2026, 0x00181d24, 0x0013191f, 0x00151c22, 0x00181e24, 0x00171d24, 0x00181e25, 0x001a2028, 0x001c222a, 0x001c232b, 0x0020262e, 0x0021282f, 0x001f252c, 0x001f242c, 0x00212630, 0x00242933, 0x00262c36, 0x00283039, 0x002c343e, 0x00303a45, 0x00394350, 0x003a4452, 0x003a4553, 0x00384350, 0x00343e4c, 0x002f3846, 0x002d3842, 0x002c3741, 0x002c3640, 0x002a343e, 0x0028323c, 0x0025313c, 0x0028343d, 0x002c3843, 0x002d3844, 0x002b3743, 0x002d3945, 0x002e3a46, 0x00283440, 0x0026333e, 0x0026333f, 0x002c3945, 0x002e3b47, 0x00293441, 0x0026303c, 0x00232c39, 0x0028313e, 0x00293440, 0x00293541, 0x00283442, 0x00283443, 0x002a3846, 0x002c3c49, 0x002e3f4c, 0x002e3e4c, 0x002e3e4d, 0x00334353, 0x00304151, 0x00283c4c, 0x002c4050, 0x002d4153, 0x002f4454, 0x00304755, 0x00304756, 0x00304655, 0x002c4351, 0x0028414e, 0x00273f4c, 0x00273f4c, 0x0028404c, 0x00283f4c, 0x00253a46, 0x001e333e, 0x001b2f39, 0x001d303c, 0x001e313e, 0x001f3440, 0x001f3541, 0x00203644, 0x00203845, 0x00203544, 0x001e3340, 0x001d323e, 0x001c313e, 0x001c313d, 0x001c313d, 0x001b323d, 0x001b313e, 0x001b313f, 0x001b313f, 0x0019303d, 0x00182e3c, 0x00182e3b, 0x00182e3b, 0x00182e3b, 0x00162d3a, 0x00152d3a, 0x00142c39, 0x00152c39, 0x00152c39, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00162b38, 0x00162b38, 0x00152b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00132b37, 0x00122b35, 0x00112a34, 0x00122934, 0x00132934, 0x00122834, 0x00102733, 0x00102631, 0x00102531, 0x00102531, 0x00102430, 0x0010242d, 0x0010242c, 0x000f242c, 0x000f242c, 0x000f242c, 0x000e252e, 0x000e252e, 0x000e252d, 0x000e252c, 0x000e252c, 0x000f2630, 0x000f2631, 0x00102531, 0x00102531, 0x00102531, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0013282e, 0x00112a30, 0x00142e34, 0x00153439, 0x0017383c, 0x00183f43, 0x001b4448, 0x001c4a4d, 0x001e4f51, 0x00205457, 0x0022585b, 0x00245d60, 0x00266a72, 0x002b8398, 0x003098b7, 0x0034a4c8, 0x0034a5c9, 0x00329ab8, 0x002e869a, 0x002a727a, 0x00286b6d, 0x0028696c, 0x0028686a, 0x00276668, 0x00266467, 0x00256264, 0x00256163, 0x0025666e, 0x00298097, 0x002a86a1, 0x002886a0, 0x002885a0, 0x002885a0, 0x002885a0, 0x002885a0, 0x002885a0, 0x002885a0, 0x002885a0, 0x002885a0, 0x002884a0, 0x0027849f, 0x002b96ba, 0x002b9ac0, 0x001e4f53, 0x001c4a4d, 0x001b4649, 0x001a4044, 0x00183c40, 0x0017383c, 0x00143338, 0x00142e34, 0x00102a30, 0x0012282e, 0x00102229, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091c24, 0x00091c24, 0x00091c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c24, 0x000b1c25, 0x000b1c28, 0x000c1c28, 0x000d1c28, 0x000f1c28, 0x000f1c28, 0x000f1e28, 0x000e1e28, 0x000f1f29, 0x0010202a, 0x0010202b, 0x0010202b, 0x000f202b, 0x0010202c, 0x0010222c, 0x0010222c, 0x0010222c, 0x000f222c, 0x000f222c, 0x0010242e, 0x00112530, 0x00112734, 0x00132936, 0x00132936, 0x00142a37, 0x00142a37, 0x00142b38, 0x00142c39, 0x00142c39, 0x00142d3b, 0x00142f3c, 0x00142f3c, 0x0015303d, 0x0015303d, 0x0015303d, 0x0015303d, 0x00162f3d, 0x00162e3d, 0x00172c3c, 0x00172c3c, 0x00152c3b, 0x00152c3b, 0x00162c3c, 0x00162c3b, 0x00142a38, 0x00142a37, 0x00142a36, 0x00152a35, 0x00152a35, 0x00162935, 0x00172935, 0x00162936, 0x00152a38, 0x00152a37, 0x00152a36, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00172c38, 0x001b303d, 0x001c3342, 0x001e3644, 0x001f3745, 0x00243c4b, 0x0028404f, 0x00283f4f, 0x00283f4f, 0x002a4151, 0x002b4152, 0x002c4253, 0x002d4352, 0x00324654, 0x002c3d4c, 0x002a3b49, 0x00293845, 0x00253441, 0x0023323e, 0x0024333f, 0x002a3843, 0x00293742, 0x00283440, 0x0026323c, 0x0024303b, 0x00293541, 0x002c3844, 0x002f3b47, 0x00313d48, 0x002f3b43, 0x002a363f, 0x002a363f, 0x0034404a, 0x0038444f, 0x00384450, 0x00374450, 0x0036424e, 0x0036424e, 0x00343f4a, 0x002f3944, 0x002c3741, 0x002e3641, 0x002c333c, 0x00272e35, 0x00212830, 0x001e232a, 0x00181c24, 0x00161921, 0x000f141c, 0x000c131a, 0x0010161c, 0x00141b20, 0x00141a20, 0x0014191f, 0x00151c21, 0x00171d24, 0x001b2128, 0x00181f26, 0x000e131a, 0x000d1419, 0x00141a20, 0x00181f25, 0x00181e24, 0x0014191f, 0x0013181e, 0x00181d23, 0x00181d24, 0x00181c23, 0x000f141a, 0x00141920, 0x00151a20, 0x00151a20, 0x00151a20, 0x00171c22, 0x00161b20, 0x0012181d, 0x0012171c, 0x0014181d, 0x0014181d, 0x0014181c, 0x00181b1f, 0x0016191d, 0x00191c21, 0x001c2025, 0x001a1f25, 0x001c2027, 0x001c2026, 0x00181b22, 0x00171920, 0x0014181e, 0x0012151b, 0x0015181d, 0x00181b20, 0x0013161b, 0x0011161b, 0x0014191f, 0x00151a21, 0x00141921, 0x00131820, 0x00181d24, 0x001a1e24, 0x00181b21, 0x00191c23, 0x00171a21, 0x001b2026, 0x00192026, 0x001a2027, 0x001c2228, 0x001c2228, 0x001b2129, 0x001b2229, 0x001d242c, 0x0020272e, 0x0020272f, 0x00232930, 0x00242a31, 0x00242a31, 0x00242832, 0x00242934, 0x00242a34, 0x00252c36, 0x00272f39, 0x0028323e, 0x00303a48, 0x00374250, 0x00394452, 0x00384451, 0x00343e4c, 0x00303946, 0x002d3843, 0x002d3842, 0x002c3741, 0x0028333d, 0x0028323c, 0x0027323c, 0x0028333d, 0x002a3440, 0x002b3441, 0x002b3441, 0x002b3541, 0x002c3743, 0x002a3441, 0x0028323f, 0x0026323d, 0x002a3742, 0x002d3945, 0x002c3844, 0x002c3642, 0x00242d3a, 0x00242d3a, 0x00283440, 0x0028333f, 0x00283441, 0x002b3746, 0x002d3b4a, 0x002d3e4c, 0x0030404e, 0x00304050, 0x00304151, 0x00344555, 0x00304252, 0x00283c4c, 0x00293e4f, 0x002c4052, 0x002c4152, 0x002e4454, 0x00304756, 0x00304655, 0x002c4251, 0x0028404c, 0x00263e4b, 0x00273f4c, 0x00283f4c, 0x00283f4c, 0x00253a47, 0x001e343f, 0x001c303b, 0x001e313d, 0x001f3440, 0x00203543, 0x00203744, 0x00203745, 0x00203847, 0x00203646, 0x001f3442, 0x001d323e, 0x001c313d, 0x001c313d, 0x001c323e, 0x001c333e, 0x001b323e, 0x001a303e, 0x001a303e, 0x0019303d, 0x00182f3c, 0x00182e3b, 0x00182e3b, 0x00182e3b, 0x00172e3b, 0x00152d3a, 0x00152d3a, 0x00162d3a, 0x00152c39, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00162b38, 0x00162b38, 0x00152b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00132a37, 0x00122b35, 0x00112a34, 0x00122934, 0x00132934, 0x00122834, 0x00102833, 0x00102631, 0x00102531, 0x00102531, 0x00102430, 0x0010242d, 0x0010242c, 0x000f242c, 0x000f242c, 0x000f242c, 0x000e252e, 0x000f262f, 0x000f262e, 0x000e252e, 0x000e252e, 0x000f2630, 0x000f2631, 0x00102631, 0x00102531, 0x00102531, 0x0011242f, 0x0011242e, 0x0011242e, 0x0011242e, 0x0011242e, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00143036, 0x00143439, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001d4a4d, 0x001f5053, 0x0020575b, 0x00267689, 0x002c90ad, 0x0030a1c6, 0x0033a5ca, 0x00319fc0, 0x002e8ea8, 0x002a7883, 0x00286c6f, 0x0028696c, 0x0028686b, 0x0028686b, 0x00286769, 0x00276568, 0x00266467, 0x00256264, 0x00266971, 0x002a849c, 0x002f9dc1, 0x002f9fc4, 0x002c9bbf, 0x002c9bbf, 0x002c9bbf, 0x002c9bbf, 0x002c9bbf, 0x002c9bbf, 0x002c9bbf, 0x002c9abf, 0x002c9abf, 0x002c9abf, 0x002c9abf, 0x002b99be, 0x002b99be, 0x002990b4, 0x001d4c50, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x0015363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1e27, 0x000a1e26, 0x000b1e26, 0x000c1e27, 0x000d1e27, 0x000d1e27, 0x000e1d27, 0x000e1d27, 0x000d1d28, 0x000c1d28, 0x000e1d28, 0x000e1d27, 0x000f1e28, 0x000f1e29, 0x00101f2a, 0x00101f2a, 0x0010202c, 0x0010202c, 0x0010202c, 0x000f202b, 0x0010212c, 0x0010222c, 0x0010222c, 0x0010222c, 0x000f222c, 0x0010232d, 0x0010242e, 0x00112430, 0x00122734, 0x00132936, 0x00132936, 0x00142a37, 0x00142a37, 0x00142b38, 0x00142c38, 0x00142c39, 0x00152c3b, 0x00162d3c, 0x00152e3c, 0x00152f3c, 0x00152f3c, 0x00142f3c, 0x00142f3c, 0x00152e3c, 0x00162d3b, 0x00162c3b, 0x00152c3a, 0x00142b39, 0x00142a38, 0x00152b39, 0x00162b39, 0x00152a37, 0x00152a36, 0x00152a36, 0x00152a35, 0x00152a35, 0x00172935, 0x00172935, 0x00172936, 0x00162b38, 0x00152a38, 0x00152a35, 0x00142934, 0x00142934, 0x00152834, 0x00152834, 0x00152834, 0x00162834, 0x00162935, 0x00162934, 0x00162a34, 0x00162b35, 0x00182c38, 0x001c303c, 0x001c3340, 0x001d3542, 0x001f3744, 0x00243b48, 0x0028404f, 0x00283f50, 0x00284050, 0x00284150, 0x002b4251, 0x002c4251, 0x002c4150, 0x00314552, 0x002e404d, 0x002c3c49, 0x00283745, 0x00233340, 0x0020303d, 0x00243440, 0x00293844, 0x00293643, 0x0026333f, 0x0026333c, 0x0024303a, 0x0028343d, 0x0028343f, 0x002d3944, 0x00303c45, 0x002f3b43, 0x002a373f, 0x002a3640, 0x0034404a, 0x0035414d, 0x0035424d, 0x00323e49, 0x00313c48, 0x00323c48, 0x00323b48, 0x002e3844, 0x002d3741, 0x002c333d, 0x00282d38, 0x00212830, 0x00191f27, 0x00161a22, 0x0010141c, 0x0010141c, 0x000f151c, 0x00121920, 0x00161e24, 0x00171d23, 0x00141a20, 0x0013181e, 0x0013181e, 0x00161c22, 0x001b2128, 0x00131920, 0x0010151c, 0x0010161c, 0x00151c21, 0x00171c21, 0x00181c21, 0x00151b21, 0x00171c23, 0x00191e24, 0x00181c23, 0x00171c23, 0x00131820, 0x00181e25, 0x00181e25, 0x00171c24, 0x00151b22, 0x00181f26, 0x00161c24, 0x00171c24, 0x00181c24, 0x00181c24, 0x00191c25, 0x001a1d24, 0x001b1e26, 0x00181c23, 0x001a1e25, 0x001b2028, 0x001b2027, 0x001d2229, 0x001b1f25, 0x00171a20, 0x00171a20, 0x0012161c, 0x000f1318, 0x0014171c, 0x00161a1e, 0x0014181c, 0x0014181e, 0x00161b21, 0x00181c23, 0x00181c24, 0x00141921, 0x00181d24, 0x001c2128, 0x001a2026, 0x00151a21, 0x00131820, 0x00171c24, 0x001d242a, 0x001c2228, 0x001f262b, 0x0020272e, 0x001d242b, 0x001a2028, 0x001c222b, 0x001d242e, 0x001b222c, 0x001c242c, 0x001d252d, 0x00222931, 0x00242c34, 0x00222a34, 0x00202831, 0x00202832, 0x00222c36, 0x00232c38, 0x00252f3b, 0x002d3743, 0x00333d49, 0x0037404d, 0x0037404d, 0x00323c48, 0x002b3542, 0x00293541, 0x002a3542, 0x0028313e, 0x0027313c, 0x0026313c, 0x0026313c, 0x0028313c, 0x0028323d, 0x0029323e, 0x0028323d, 0x002b3440, 0x002c3641, 0x002b3440, 0x0029333e, 0x0028333d, 0x00283440, 0x002b3743, 0x00293540, 0x00222e39, 0x00202c37, 0x00283540, 0x00293843, 0x00293845, 0x002a3847, 0x002b3b4a, 0x002d3e4c, 0x0030404f, 0x00304150, 0x00314454, 0x00344757, 0x00304454, 0x002a3f4e, 0x002a3f4e, 0x002d4251, 0x002c4352, 0x002c4352, 0x00304755, 0x00304756, 0x002c4251, 0x00283f4d, 0x00283d4b, 0x00283f4c, 0x00283d4b, 0x00283c4a, 0x00243946, 0x00203440, 0x001d323d, 0x001e333f, 0x00203543, 0x00223745, 0x00213845, 0x00203847, 0x00203848, 0x00203847, 0x00203544, 0x001f3341, 0x001d3240, 0x001c313f, 0x001c323e, 0x001c333f, 0x001b313e, 0x001a303e, 0x001a303e, 0x001a303d, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182e3b, 0x00182e3b, 0x00162d3a, 0x00162d3a, 0x00152c39, 0x00142b38, 0x00162a38, 0x00162a38, 0x00152a37, 0x00152a37, 0x00152a37, 0x00152a37, 0x00152a37, 0x00152a37, 0x00142a37, 0x00142a38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142a38, 0x00142a36, 0x00142936, 0x00142836, 0x00132836, 0x00132834, 0x00122733, 0x00122633, 0x00122633, 0x00122633, 0x00112532, 0x00102530, 0x0010252f, 0x0010252f, 0x000f242f, 0x000f242f, 0x000f2530, 0x00102530, 0x00102530, 0x00102530, 0x00102530, 0x00102530, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00112430, 0x00122530, 0x00112430, 0x00102430, 0x00102430, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00132c32, 0x00143036, 0x0015363b, 0x00173a3e, 0x00194044, 0x001b4649, 0x001d4b4e, 0x001e5053, 0x0021606a, 0x002ea3c9, 0x0030a2c8, 0x002d94b2, 0x002a7b8d, 0x00276b70, 0x00286769, 0x00286769, 0x0028686a, 0x0028686a, 0x00286769, 0x00276668, 0x00266467, 0x00266466, 0x00276a72, 0x002b87a0, 0x00309ec2, 0x002f9fc4, 0x002986a0, 0x0024646f, 0x00225d64, 0x00225d64, 0x00215c63, 0x00225c63, 0x00225c63, 0x00225c63, 0x00215c62, 0x00215c62, 0x00215c62, 0x00205a61, 0x00205960, 0x00205860, 0x001f565e, 0x001e535a, 0x001c4a4d, 0x001b4649, 0x001a4245, 0x00183d41, 0x00183a3e, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1e28, 0x000c1f27, 0x000c1e27, 0x000e1f28, 0x000f1f28, 0x000f1e27, 0x00101d27, 0x00101d27, 0x000f1d27, 0x000e1d27, 0x000e1e27, 0x000d1e27, 0x000d1e27, 0x000f1f29, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010232d, 0x0010232d, 0x0010242f, 0x00112430, 0x00132734, 0x00132936, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142a38, 0x00142b38, 0x00142b38, 0x00152c3a, 0x00172c3c, 0x00162d3c, 0x00162e3a, 0x00162e3a, 0x00142f3a, 0x00142f3a, 0x00162d3a, 0x00152c39, 0x00142b38, 0x00142b38, 0x00142a37, 0x00142936, 0x00142834, 0x00152834, 0x00152935, 0x00162935, 0x00162935, 0x00152a35, 0x00152a35, 0x00172935, 0x00172935, 0x00172936, 0x00162b38, 0x00152a38, 0x00152a35, 0x00142934, 0x00142934, 0x00142834, 0x00142834, 0x00142834, 0x00152834, 0x00162834, 0x00172934, 0x00172934, 0x00182c35, 0x00192e38, 0x001c313c, 0x001c313e, 0x001c333f, 0x001e3440, 0x00233945, 0x00273d4a, 0x00283e4d, 0x0028404e, 0x00294350, 0x002c4451, 0x002c4350, 0x002c4350, 0x00314551, 0x002f424e, 0x002a3c48, 0x00283644, 0x00243442, 0x00223341, 0x00273744, 0x00283845, 0x00273542, 0x0024323e, 0x0025333d, 0x0024303a, 0x0027323c, 0x0027333d, 0x002a3640, 0x002d3843, 0x002c3842, 0x002a3640, 0x002a3640, 0x00313d47, 0x0034404a, 0x00344049, 0x00323e48, 0x00333d48, 0x00323c48, 0x00323a47, 0x002f3744, 0x002c333f, 0x00262c36, 0x00212630, 0x001b2028, 0x00151b21, 0x00141820, 0x000c1119, 0x000f141c, 0x00141a21, 0x001b2229, 0x00192128, 0x00151d23, 0x00141a20, 0x0014181e, 0x00151a20, 0x00191d25, 0x00181f26, 0x0010161e, 0x00141820, 0x00191f24, 0x001c2126, 0x00181c20, 0x00151a1f, 0x00141b20, 0x00181f24, 0x00192026, 0x00161d24, 0x00141b22, 0x00181f27, 0x001a2229, 0x001b232b, 0x00182027, 0x00171f26, 0x00181f27, 0x00182028, 0x00192028, 0x00181f27, 0x00181f27, 0x001c2229, 0x001e242b, 0x001c222a, 0x001b2028, 0x001b2028, 0x00181e25, 0x001c2328, 0x001c2028, 0x00181c22, 0x00161a20, 0x00171a20, 0x0012171c, 0x000d1317, 0x00101519, 0x0014181c, 0x00171a1f, 0x00171c22, 0x00191e24, 0x001a1f26, 0x001b2028, 0x001b2028, 0x001c222a, 0x001f282f, 0x001d242c, 0x00171d24, 0x00171d25, 0x00181f25, 0x001e242a, 0x001b2026, 0x00181d23, 0x00181e24, 0x00191e26, 0x00191f26, 0x001b212a, 0x001f2530, 0x001d2430, 0x001a232c, 0x0018222b, 0x001c262f, 0x00202b33, 0x00212b34, 0x00202932, 0x001e2830, 0x001e2832, 0x00222c35, 0x00202b34, 0x00212b34, 0x0029343d, 0x00323c47, 0x0035404b, 0x00323d49, 0x002b3743, 0x00283440, 0x00283440, 0x0028333f, 0x0027303d, 0x0026303c, 0x0028303c, 0x002b333e, 0x002c343f, 0x0028303b, 0x0026303a, 0x0028323c, 0x002b3540, 0x002a343f, 0x0028333d, 0x0025313b, 0x0023303c, 0x00263440, 0x0025333f, 0x0022303b, 0x00202e38, 0x0024323d, 0x002b3a45, 0x00303f4c, 0x002d3c4a, 0x002c3d4c, 0x002d404e, 0x002f404f, 0x00314452, 0x00334555, 0x00344757, 0x00314555, 0x002c4251, 0x002b4150, 0x002e4453, 0x002e4454, 0x002d4454, 0x002f4755, 0x002f4655, 0x002d4352, 0x00293e4d, 0x00283c4a, 0x002a3f4c, 0x00293c4b, 0x00283c49, 0x00243846, 0x00203541, 0x001e333f, 0x00203541, 0x00223745, 0x00213847, 0x00203847, 0x00203848, 0x00203848, 0x00203848, 0x00213746, 0x00203444, 0x001d3240, 0x001c313f, 0x001c313f, 0x001b313f, 0x001b313f, 0x001a303d, 0x001a303d, 0x0019303c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182e3b, 0x00182e3b, 0x00172d3a, 0x00172d3a, 0x00172d3a, 0x00162b38, 0x00182a37, 0x00182a37, 0x00172935, 0x00172935, 0x00162935, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a36, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00152a37, 0x00152a37, 0x00142937, 0x00142836, 0x00142835, 0x00142734, 0x00142734, 0x00142734, 0x00142734, 0x00142734, 0x00112631, 0x00112630, 0x00102630, 0x000f2631, 0x000f2631, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102531, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00122531, 0x00132632, 0x00122531, 0x00102531, 0x00102531, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0015363b, 0x00173c40, 0x001a4044, 0x001b4649, 0x001c4b4e, 0x001f5154, 0x0021606b, 0x002fa4cb, 0x002a88a3, 0x00256063, 0x00256264, 0x00276467, 0x00266568, 0x00276668, 0x00276668, 0x00276668, 0x00276568, 0x00266467, 0x00276c75, 0x002c88a1, 0x00309fc3, 0x0030a0c4, 0x002986a1, 0x00236670, 0x0022585b, 0x00215659, 0x00205558, 0x00205558, 0x00205457, 0x00205457, 0x00205457, 0x00205457, 0x00205457, 0x00205457, 0x00205356, 0x00205356, 0x00205154, 0x001f5053, 0x001d4d50, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x00194044, 0x00183d41, 0x0017383c, 0x00153439, 0x00142e34, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1e28, 0x000c1f27, 0x000c1e27, 0x000e1f28, 0x000f1f28, 0x000f1e28, 0x00101d27, 0x00101d27, 0x000f1e27, 0x000e1e27, 0x000e1e27, 0x000c1e27, 0x000d1e27, 0x000f1f28, 0x0010202a, 0x0010202a, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010202c, 0x0010222c, 0x0010222c, 0x0010222c, 0x0010232d, 0x0010242e, 0x00112430, 0x00122531, 0x00142734, 0x00132936, 0x00142a37, 0x00142a37, 0x00142a37, 0x00142b38, 0x00142b38, 0x00142b38, 0x00152c3b, 0x00172c3c, 0x00162d3c, 0x00162e39, 0x00162f39, 0x00142f39, 0x00142f39, 0x00162d39, 0x00162c39, 0x00152b38, 0x00142a37, 0x00142937, 0x00142835, 0x00142734, 0x00142733, 0x00142834, 0x00152834, 0x00162935, 0x00152a35, 0x00152a35, 0x00172935, 0x00172935, 0x00172936, 0x00162b38, 0x00152a38, 0x00152936, 0x00142835, 0x00142834, 0x00142834, 0x00142834, 0x00142834, 0x00142834, 0x00152834, 0x00162833, 0x00162934, 0x00172b35, 0x001a2f38, 0x001c313c, 0x001c313c, 0x001b313d, 0x001d343f, 0x00203541, 0x00243946, 0x00263c4a, 0x0028404d, 0x002a4450, 0x002c4451, 0x002c4450, 0x002d4350, 0x002f4450, 0x002c404c, 0x00283946, 0x00273745, 0x00263544, 0x00283847, 0x002a3b48, 0x002a3946, 0x00293844, 0x0024313e, 0x0024313c, 0x00243039, 0x0025303b, 0x0026323c, 0x0029353f, 0x002c3842, 0x002c3842, 0x0029353f, 0x002b3740, 0x002f3b45, 0x00303c45, 0x00323c47, 0x00343f49, 0x00353f4a, 0x00343d48, 0x00323a46, 0x002d3541, 0x0029303b, 0x00232831, 0x001c212a, 0x00171c24, 0x00161c22, 0x0014181f, 0x000e1419, 0x0011161c, 0x00171e25, 0x00182128, 0x00182027, 0x00151c21, 0x0013181e, 0x0012171c, 0x00171c23, 0x00181d24, 0x00171d24, 0x0010161e, 0x00161b22, 0x001e2328, 0x001d2226, 0x00181c20, 0x0014181d, 0x000d141a, 0x00151c22, 0x00181f24, 0x00181f26, 0x00182027, 0x001d262d, 0x001c262d, 0x001c242b, 0x00192229, 0x00182027, 0x00151e25, 0x00141c23, 0x00141b22, 0x00141c23, 0x00151c24, 0x00192028, 0x001a2028, 0x00181f27, 0x001a2028, 0x001b2129, 0x00181e25, 0x0020252c, 0x0020242b, 0x00181d24, 0x00171b21, 0x00181c22, 0x00161b20, 0x000e1317, 0x000f1418, 0x0012171b, 0x00171a1e, 0x00161b21, 0x00151a20, 0x00171c24, 0x001a1f27, 0x001c2028, 0x001c242b, 0x00202830, 0x0020282f, 0x00151c24, 0x00121820, 0x00141b21, 0x00181f25, 0x001b2026, 0x00181e24, 0x00161b22, 0x00151a21, 0x00161c24, 0x00181f28, 0x001e242f, 0x00222934, 0x001c252f, 0x00152028, 0x0019232c, 0x001c2730, 0x00202933, 0x00212b34, 0x00202b34, 0x00202b34, 0x00202b33, 0x00222c35, 0x00232c35, 0x00242e37, 0x002b3540, 0x00303a45, 0x00313c48, 0x002d3945, 0x002a3843, 0x002a3642, 0x002b3441, 0x0027313d, 0x00252f3a, 0x0028303c, 0x0029313c, 0x002b333e, 0x0028303b, 0x00252e38, 0x00242d38, 0x00252f39, 0x0027313c, 0x0027313c, 0x0025303a, 0x00202e38, 0x0024313c, 0x0024323e, 0x0024313c, 0x0023313b, 0x0022313c, 0x00283742, 0x0030404c, 0x0031404e, 0x002d3e4c, 0x002e404f, 0x002f4150, 0x00344755, 0x00334656, 0x00344757, 0x00324756, 0x002d4453, 0x002f4454, 0x00304856, 0x00304857, 0x002f4856, 0x002e4856, 0x002f4856, 0x002c4452, 0x00293f4d, 0x00283d4b, 0x002a3e4c, 0x00293c4b, 0x00283b48, 0x00243946, 0x00203742, 0x00213642, 0x00233844, 0x00233846, 0x00213847, 0x00203847, 0x00203848, 0x001f3848, 0x00203848, 0x00223847, 0x00203444, 0x001d3240, 0x001c313f, 0x001c313f, 0x001b313f, 0x001b313f, 0x0019303d, 0x0019303c, 0x0019303c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182e3b, 0x00182e3b, 0x00172d3a, 0x00172d3a, 0x00172d3a, 0x00162c38, 0x00182a37, 0x00182a37, 0x00172935, 0x00172935, 0x00162935, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a36, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00142b38, 0x00162b39, 0x00162b39, 0x00162b38, 0x00152a38, 0x00152937, 0x00152836, 0x00142835, 0x00142835, 0x00142835, 0x00142835, 0x00132733, 0x00122831, 0x00112832, 0x00102732, 0x00102732, 0x00122632, 0x00122632, 0x00112531, 0x00112531, 0x00112431, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00102430, 0x00122531, 0x00132632, 0x00122531, 0x00102531, 0x00102531, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00122c32, 0x00143036, 0x0016363b, 0x00183c40, 0x001a4044, 0x001c474b, 0x001d4c50, 0x001f5154, 0x0021606b, 0x002fa4cb, 0x002986a0, 0x00245f61, 0x00256163, 0x00256364, 0x00266466, 0x00266466, 0x00266466, 0x00266466, 0x00276d76, 0x002c88a2, 0x0030a0c4, 0x002fa0c4, 0x002a88a4, 0x00246670, 0x0022595c, 0x00215659, 0x00205558, 0x00205457, 0x00205356, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x00205254, 0x001f5154, 0x001f5053, 0x001d4f51, 0x001d4c50, 0x001c4a4d, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000e1f29, 0x000e1f29, 0x000e1f29, 0x000f1f2a, 0x000f202a, 0x0010202a, 0x00102029, 0x00102029, 0x00101f28, 0x000f1f28, 0x000f1f28, 0x000e1f28, 0x000e1f28, 0x00101f28, 0x00102029, 0x00102029, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010202c, 0x0010212c, 0x0011232d, 0x0011232d, 0x0010232d, 0x0010232d, 0x0011242e, 0x0012252f, 0x00132630, 0x00142834, 0x00132936, 0x00132936, 0x00142b38, 0x00142b38, 0x00152c39, 0x00152c39, 0x00152c39, 0x00172c3b, 0x00182e3c, 0x00182e3c, 0x00182e39, 0x00172e39, 0x00162f39, 0x00162f39, 0x00172d39, 0x00162c39, 0x00162b37, 0x00152a36, 0x00142936, 0x00142835, 0x00142733, 0x00142733, 0x00142834, 0x00152834, 0x00162834, 0x00172935, 0x00172935, 0x00172935, 0x00172935, 0x00172936, 0x00162b38, 0x00152a38, 0x00152937, 0x00142836, 0x00142835, 0x00142734, 0x00142734, 0x00142734, 0x00142734, 0x00142834, 0x00142833, 0x00142834, 0x00172a36, 0x001a2d39, 0x001c303c, 0x001c303c, 0x001c313d, 0x001c303c, 0x001c2f3c, 0x001e3240, 0x00213744, 0x00273e4b, 0x002c4450, 0x002c4450, 0x002c4450, 0x002c4350, 0x002c414d, 0x00293d48, 0x00243744, 0x00283847, 0x00283847, 0x00293a48, 0x002b3b48, 0x002c3b48, 0x002b3947, 0x0024313f, 0x0024323c, 0x00202d38, 0x00212e38, 0x0025323c, 0x0029353f, 0x0028343e, 0x0028343e, 0x0028343d, 0x002c3841, 0x002e3a44, 0x002d3843, 0x00303b45, 0x00353f49, 0x0036404a, 0x00343e48, 0x00313944, 0x002b333c, 0x00262d36, 0x0020262e, 0x001c2028, 0x00181d25, 0x00171c24, 0x0013181f, 0x0010151c, 0x0013181e, 0x00182025, 0x00172025, 0x00151e24, 0x0010181e, 0x0010161c, 0x000f141a, 0x00161b22, 0x00151921, 0x00181e25, 0x00181e26, 0x001a1f26, 0x001c2026, 0x001c2025, 0x00181c20, 0x0013181c, 0x000f151b, 0x0012181f, 0x00131920, 0x00141c23, 0x001c232a, 0x00202930, 0x001c262d, 0x001a232a, 0x00182128, 0x00182028, 0x00182028, 0x00182028, 0x00151d25, 0x00141b23, 0x00181f27, 0x00171d25, 0x001b2129, 0x001d242c, 0x001c222a, 0x001b2129, 0x001c232b, 0x0022282f, 0x00242a30, 0x001c2027, 0x00181d24, 0x00181d24, 0x00181c22, 0x0011161a, 0x000f1418, 0x0014181c, 0x00181b20, 0x0014181f, 0x0012171d, 0x0010151d, 0x0010151d, 0x0012171f, 0x00192028, 0x001f272e, 0x00192129, 0x00131b22, 0x000c141b, 0x000e151b, 0x00171d23, 0x001c2027, 0x00191e24, 0x00171d24, 0x00141a22, 0x0010171f, 0x00141a23, 0x00181e29, 0x001c242f, 0x001f2832, 0x001b242d, 0x0018232b, 0x001c262f, 0x001c2730, 0x001c2730, 0x001e2830, 0x001e2831, 0x00202a32, 0x00252f38, 0x00273039, 0x00232d36, 0x0026303a, 0x002f3844, 0x00333e4a, 0x00303c48, 0x002c3a45, 0x002d3944, 0x002c3643, 0x0028313e, 0x00242e39, 0x0027303a, 0x0028303b, 0x00272f39, 0x00262e39, 0x00252e38, 0x00242e39, 0x00222c36, 0x00222c36, 0x00242e39, 0x0024303b, 0x0023303a, 0x0024313c, 0x0025333e, 0x0025343f, 0x0025333c, 0x0023323c, 0x0024343f, 0x002c3c48, 0x00324150, 0x002c3e4c, 0x00293e4c, 0x002c404e, 0x00334755, 0x00344757, 0x00344858, 0x00344958, 0x002f4554, 0x00304856, 0x00344a59, 0x00324958, 0x002f4856, 0x002f4857, 0x00304857, 0x002c4453, 0x002a404f, 0x002a3f4c, 0x00293e4c, 0x00293c4b, 0x00283b49, 0x00253a47, 0x00233844, 0x00233844, 0x00243945, 0x00243947, 0x00223848, 0x00203847, 0x00203848, 0x00203848, 0x00213848, 0x00233847, 0x00203544, 0x001d3140, 0x001c303e, 0x001c303f, 0x001b313f, 0x001b313f, 0x0019303d, 0x0019303c, 0x0019303c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182e3b, 0x00182e3b, 0x00172d3a, 0x00172d3a, 0x00172d3a, 0x00152b38, 0x00172936, 0x00172935, 0x00162834, 0x00152834, 0x00152834, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152b37, 0x00162b38, 0x00162c39, 0x00162c39, 0x00162c39, 0x00162c39, 0x00172c3a, 0x00172c3a, 0x00162c39, 0x00162b38, 0x00162b38, 0x00172938, 0x00172937, 0x00172937, 0x00162836, 0x00162836, 0x00142834, 0x00142834, 0x00142834, 0x00132834, 0x00132834, 0x00132632, 0x00132632, 0x00132632, 0x00132632, 0x00132632, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x00112430, 0x00142431, 0x00142532, 0x00132431, 0x00122431, 0x00122431, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00153036, 0x0016363b, 0x00183c40, 0x001a4044, 0x001b4649, 0x001d4c50, 0x001e5053, 0x0021606a, 0x002fa4cb, 0x0029859f, 0x00245e60, 0x00256062, 0x00256163, 0x00256264, 0x00256264, 0x00276c76, 0x002c8ba5, 0x0030a0c4, 0x0030a1c5, 0x002b88a4, 0x00246771, 0x0022595c, 0x00215659, 0x00205558, 0x00205356, 0x00205254, 0x001f5154, 0x001f5154, 0x001e5053, 0x001e5053, 0x001e5053, 0x001f5154, 0x001f5154, 0x001f5154, 0x001f5154, 0x001f5154, 0x001f5053, 0x001d4f51, 0x001d4d50, 0x001d4b4e, 0x001c484c, 0x001b4649, 0x001a4245, 0x00183f43, 0x00183a3e, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f202a, 0x000f202a, 0x000f202a, 0x000f202b, 0x000f202b, 0x0010202b, 0x0011202a, 0x0011202a, 0x00102029, 0x000f1f28, 0x000f1f28, 0x000f1f28, 0x00101f28, 0x00102029, 0x00102029, 0x00102029, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010202c, 0x0010212c, 0x0011232d, 0x0012242e, 0x0010232d, 0x0010242e, 0x0011242e, 0x0012252f, 0x00132630, 0x00142834, 0x00132936, 0x00132936, 0x00142b38, 0x00152c39, 0x00162c39, 0x00162c3a, 0x00162d3a, 0x00182d3c, 0x00182e3d, 0x00182e3c, 0x00182e39, 0x00182e39, 0x00162e39, 0x00162f39, 0x00172d39, 0x00162c38, 0x00152a36, 0x00152935, 0x00142835, 0x00142734, 0x00142733, 0x00142632, 0x00142833, 0x00152834, 0x00162834, 0x00172935, 0x00172935, 0x00172935, 0x00172935, 0x00172936, 0x00162a38, 0x00152a38, 0x00152937, 0x00142836, 0x00142835, 0x00142734, 0x00142734, 0x00142734, 0x00142734, 0x00142734, 0x00142733, 0x00142733, 0x00152834, 0x00192c38, 0x001b2d3a, 0x001b2d3a, 0x001b2d39, 0x00182a37, 0x00152834, 0x00172938, 0x001a2e3c, 0x00233846, 0x002c4350, 0x002c4450, 0x002c4350, 0x002c414e, 0x00293e4a, 0x00283b47, 0x00243744, 0x002b3b4a, 0x002b3c4a, 0x00283948, 0x00283947, 0x002c3c4a, 0x002d3b49, 0x00253240, 0x0025333d, 0x001f2c36, 0x00202d38, 0x0024313c, 0x0027333d, 0x0024303a, 0x0026323c, 0x0026323c, 0x002b3741, 0x002e3a44, 0x002c3741, 0x002e3944, 0x00343e49, 0x0038424c, 0x00343e48, 0x00303640, 0x00282f38, 0x00202830, 0x001c222a, 0x001a2028, 0x001a2028, 0x00181e26, 0x00151b23, 0x00161b23, 0x00192027, 0x00192027, 0x00131c21, 0x00141c22, 0x0011181e, 0x0011171d, 0x0012171d, 0x00171c23, 0x00181c24, 0x00181f27, 0x001b2129, 0x001c2129, 0x001c2228, 0x001c2128, 0x00191d24, 0x0014191f, 0x0012181f, 0x0012191f, 0x00141c21, 0x00181f27, 0x00202830, 0x00232c33, 0x001f2830, 0x001d2730, 0x001b242d, 0x001d262f, 0x001e2830, 0x0018212a, 0x00141c25, 0x00181f28, 0x00192029, 0x00141c24, 0x001a212a, 0x001e262f, 0x001e252f, 0x001b222c, 0x00202831, 0x00242b33, 0x00272d34, 0x0021272e, 0x001a1e26, 0x00191e24, 0x00181f25, 0x00171c22, 0x00141a20, 0x00181c23, 0x00191d24, 0x00141920, 0x0013171f, 0x00141921, 0x0013171f, 0x0011171f, 0x00141a22, 0x001d252c, 0x001a232a, 0x001b242b, 0x00131b22, 0x00131b20, 0x00161d23, 0x00192026, 0x00141b21, 0x00181d25, 0x00181e25, 0x000f151c, 0x00111820, 0x00131923, 0x00141c26, 0x001f2831, 0x001f2931, 0x0019242c, 0x0019242c, 0x001c2730, 0x001b252f, 0x001a242d, 0x001a242e, 0x001d2730, 0x00232d36, 0x00263039, 0x00232d36, 0x00222c36, 0x0028323c, 0x002d3844, 0x00303c48, 0x002c3945, 0x002c3844, 0x002b3541, 0x0028323e, 0x00242d38, 0x00242c38, 0x00272f3a, 0x00262e38, 0x00242c38, 0x00252e38, 0x00242f39, 0x00222c37, 0x00202a34, 0x00212c36, 0x00242f3a, 0x0026333d, 0x0025333e, 0x00273440, 0x00263440, 0x0026343f, 0x0023323e, 0x0023323e, 0x002a3946, 0x00324150, 0x002e404e, 0x00273c49, 0x00283e4c, 0x00324856, 0x00334857, 0x00344858, 0x00364b5b, 0x00314856, 0x00304655, 0x00344b59, 0x00344b59, 0x002f4755, 0x002f4958, 0x00304a58, 0x002e4454, 0x002c4352, 0x002b404e, 0x00293e4c, 0x00283c4a, 0x00283c49, 0x00263b48, 0x00233945, 0x00243844, 0x00243945, 0x00253947, 0x00233948, 0x00203847, 0x00203848, 0x00203848, 0x00223848, 0x00233847, 0x00203543, 0x001c313f, 0x001c303e, 0x001c303e, 0x001b313f, 0x001b313f, 0x0019303d, 0x0019303c, 0x0019303c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182e3b, 0x00182e3b, 0x00172d3a, 0x00172d3a, 0x00172c3a, 0x00152b38, 0x00172936, 0x00172935, 0x00152834, 0x00152834, 0x00152834, 0x00152a35, 0x00152a35, 0x00152a35, 0x00152a35, 0x00162b37, 0x00172c39, 0x00172c39, 0x00172c39, 0x00172c39, 0x00172c39, 0x00172d3b, 0x00182e3b, 0x00172d3a, 0x00162c3a, 0x00162c39, 0x00182a38, 0x00182a38, 0x00182a38, 0x00172938, 0x00172937, 0x00142934, 0x00142834, 0x00142835, 0x00142836, 0x00142836, 0x00142733, 0x00132632, 0x00132632, 0x00132632, 0x00132632, 0x00122430, 0x00112430, 0x00112430, 0x00112430, 0x00122430, 0x00142431, 0x00142532, 0x00142431, 0x00122431, 0x00122431, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0012242c, 0x00112a30, 0x00122c32, 0x00143036, 0x0016363b, 0x00183c40, 0x00194044, 0x001b4649, 0x001d4b4e, 0x001f5053, 0x0021606a, 0x002ea3ca, 0x0028859f, 0x00245c5f, 0x00245e60, 0x00246062, 0x00266c77, 0x002c8aa5, 0x0030a0c4, 0x0030a1c5, 0x002a89a4, 0x00246874, 0x0022595c, 0x00215659, 0x00205558, 0x00205356, 0x00205254, 0x001f5053, 0x001e4f51, 0x001e4f51, 0x001d4d50, 0x001d4d50, 0x001d4f51, 0x001d4f51, 0x001e5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001d4f51, 0x001e4d50, 0x001c4b4e, 0x001c474b, 0x001b4649, 0x001a4245, 0x00183f43, 0x00183a3e, 0x00153439, 0x00143036, 0x00132c32, 0x00102a30, 0x0013282e, 0x0013242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010202c, 0x0010202b, 0x0011202b, 0x0011202b, 0x0011202a, 0x0010202a, 0x0010202a, 0x00102029, 0x00102029, 0x00102029, 0x00102029, 0x00102029, 0x0010202b, 0x0010202b, 0x0010202c, 0x0010222c, 0x0011232c, 0x0011232d, 0x0012242e, 0x0011242e, 0x0011242e, 0x0011242f, 0x00122530, 0x00132631, 0x00142834, 0x00142836, 0x00142936, 0x00142b38, 0x00142b38, 0x00152c39, 0x00162c39, 0x00162c39, 0x00172c3b, 0x00182d3c, 0x00182c3b, 0x00182c39, 0x00182c39, 0x00172d39, 0x00172d39, 0x00162c38, 0x00162a37, 0x00152835, 0x00152834, 0x00152734, 0x00152734, 0x00152632, 0x00142632, 0x00152732, 0x00162832, 0x00172833, 0x00162935, 0x00162935, 0x00162935, 0x00162936, 0x00172937, 0x00182a38, 0x00182a38, 0x00182938, 0x00172937, 0x00162836, 0x00142834, 0x00142834, 0x00142734, 0x00142734, 0x00142733, 0x00162632, 0x00152731, 0x00162832, 0x00182934, 0x00182834, 0x00182731, 0x00162430, 0x0012212e, 0x0010202d, 0x00132431, 0x00162836, 0x001f3340, 0x002c404f, 0x002e4451, 0x002c4450, 0x002b404c, 0x00283d49, 0x00283c48, 0x00253844, 0x002c3d4b, 0x002c3f4c, 0x00283a48, 0x00283a48, 0x002f3f4c, 0x002c3a48, 0x0025323f, 0x0023303a, 0x001f2c36, 0x0024303a, 0x0024303a, 0x0025313b, 0x00232f39, 0x0026313c, 0x0026323c, 0x002c3843, 0x002c3944, 0x002a3641, 0x002d3a44, 0x00343f4a, 0x00353f4a, 0x00333a45, 0x002c323c, 0x00222833, 0x00192028, 0x00181f26, 0x00192028, 0x00192128, 0x00151d24, 0x00141b23, 0x00151c24, 0x00181f26, 0x00131920, 0x000d151b, 0x00151d23, 0x00141c21, 0x00141b20, 0x00141920, 0x00141c22, 0x00182027, 0x001c242c, 0x001b232c, 0x001d242c, 0x001c222a, 0x001a2028, 0x001b2027, 0x001c2128, 0x00192028, 0x001a2128, 0x00212a31, 0x00232c34, 0x00242c35, 0x00242d36, 0x00222b34, 0x00212c35, 0x001e2830, 0x001f2932, 0x001e2830, 0x00141e26, 0x00131c24, 0x00161e27, 0x00171f28, 0x0018202a, 0x001c242d, 0x001c242e, 0x001e272f, 0x001c252d, 0x00222b33, 0x00252c34, 0x00272e35, 0x00282f37, 0x001f242c, 0x001c2128, 0x001b2128, 0x00181e25, 0x00181e25, 0x00191e25, 0x00191d24, 0x00171c23, 0x00131820, 0x00161c23, 0x00141a22, 0x00121820, 0x00131921, 0x001c242c, 0x001c242c, 0x001c262e, 0x001a232b, 0x00172026, 0x00182027, 0x00182127, 0x00131b21, 0x00131921, 0x00181f26, 0x0010161d, 0x0011181f, 0x0010171f, 0x0010161e, 0x00181f28, 0x00202a32, 0x00202a32, 0x001e2830, 0x001e2830, 0x001e2833, 0x001c2631, 0x001e2832, 0x001e2832, 0x001f2833, 0x00222c37, 0x00242e37, 0x00222c36, 0x0026303b, 0x002a3541, 0x002d3844, 0x002c3643, 0x002b3440, 0x002b3440, 0x0028313d, 0x00242d38, 0x00232b36, 0x00252d38, 0x0028303b, 0x0028303b, 0x00252f39, 0x00242d38, 0x00232c38, 0x00202a37, 0x00202b37, 0x00232d39, 0x0026333d, 0x0028343f, 0x00283440, 0x00263441, 0x00253441, 0x00243442, 0x00243341, 0x00273745, 0x002f3f4e, 0x002c3f4d, 0x00283d4b, 0x00273d4b, 0x002f4454, 0x00314655, 0x00314655, 0x00364c5b, 0x00334958, 0x00304655, 0x00334958, 0x00324a59, 0x00304858, 0x00304a5a, 0x00314c5c, 0x00314859, 0x00304656, 0x002c4150, 0x00283d4c, 0x00273c49, 0x00263b48, 0x00243946, 0x00223845, 0x00233845, 0x00243846, 0x00243846, 0x00233847, 0x00213846, 0x00213847, 0x00213847, 0x00223848, 0x00223847, 0x00203544, 0x001c3240, 0x001c303f, 0x001b303f, 0x001b303e, 0x001c303e, 0x001b303d, 0x001a303c, 0x001a303c, 0x001a2e3c, 0x001a2e3c, 0x00182f3c, 0x00182f3c, 0x00182d3b, 0x00182d3a, 0x00182c39, 0x00182c39, 0x00182c39, 0x00172b38, 0x00172936, 0x00172936, 0x00172935, 0x00172935, 0x00162935, 0x00162a36, 0x00162a37, 0x00162a37, 0x00162b37, 0x00162b38, 0x00162b39, 0x00172c39, 0x00172c39, 0x00172c39, 0x00182c3a, 0x00182e3b, 0x00182e3b, 0x00172e3b, 0x00172e3b, 0x00172c3a, 0x00182c3a, 0x00182c39, 0x00182b39, 0x00182b38, 0x00172b38, 0x00152a37, 0x00152a36, 0x00152a36, 0x00152a36, 0x00142936, 0x00142834, 0x00142733, 0x00142632, 0x00142532, 0x00132531, 0x00132431, 0x00122431, 0x00122430, 0x00122430, 0x00122430, 0x00142431, 0x00142532, 0x00142431, 0x00122431, 0x00122431, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0015363b, 0x00183a3e, 0x00194044, 0x001b4448, 0x001c4a4d, 0x001d4d50, 0x00215d68, 0x002ea3ca, 0x0028849f, 0x00235b5e, 0x00246a76, 0x002b8ba6, 0x0030a0c6, 0x002fa0c5, 0x002a8ba7, 0x00246772, 0x0022585c, 0x00215659, 0x00205558, 0x00205356, 0x00205154, 0x001f5053, 0x001d4d50, 0x001d4c50, 0x001d4c50, 0x001d4b4e, 0x001d4b4e, 0x001e4c50, 0x001e4c50, 0x001d4d50, 0x001d4f51, 0x001e4f51, 0x001f5053, 0x001f5053, 0x001f5053, 0x001f5053, 0x001d4f51, 0x001e4d50, 0x001d4b4e, 0x001c484c, 0x001b4649, 0x001a4245, 0x00183f43, 0x00183a3e, 0x00143439, 0x00153338, 0x00132c32, 0x00102a30, 0x0013282e, 0x0013242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0010212a, 0x0010212a, 0x0010212a, 0x0010222c, 0x0010222c, 0x0010212c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011202c, 0x0011202c, 0x0010212a, 0x0010212a, 0x00102029, 0x00102029, 0x00102029, 0x0010202b, 0x0010202b, 0x0010212b, 0x0010222b, 0x0012242c, 0x0012242c, 0x0012242e, 0x0012242e, 0x0012242f, 0x00122431, 0x00122431, 0x00132632, 0x00142734, 0x00142835, 0x00142936, 0x00142b38, 0x00142b38, 0x00152b38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00172b39, 0x00182b39, 0x00182b39, 0x00162a38, 0x00152a38, 0x00152936, 0x00142834, 0x00142834, 0x00162733, 0x00162732, 0x00162733, 0x00152631, 0x00152631, 0x00152731, 0x00162832, 0x00152832, 0x00142834, 0x00142834, 0x00142835, 0x00142836, 0x00152936, 0x00182a38, 0x00182a38, 0x00172a38, 0x00172a38, 0x00172936, 0x00152834, 0x00142832, 0x00142730, 0x0014262f, 0x00162530, 0x00182530, 0x0016242c, 0x0016242c, 0x0014232c, 0x0014202a, 0x00132029, 0x00121f29, 0x00101d27, 0x00101f2a, 0x00142430, 0x00182b37, 0x001e333f, 0x0028404c, 0x002c4552, 0x002c4451, 0x002b414c, 0x002c404c, 0x002b404b, 0x00263b47, 0x00293d4b, 0x002c404d, 0x00283c48, 0x002b3e4a, 0x0030404c, 0x002b3945, 0x0026343f, 0x00202e38, 0x00212e38, 0x0028343d, 0x0026303a, 0x0025303a, 0x00243039, 0x0025303b, 0x0026313d, 0x002a3743, 0x002b3844, 0x00283742, 0x002c3945, 0x00323e4a, 0x00333d49, 0x002f3843, 0x00283039, 0x0020272f, 0x00171f27, 0x00182028, 0x00192128, 0x00172027, 0x00121b22, 0x00111a21, 0x00141c23, 0x00151c24, 0x0010171e, 0x0011181d, 0x00192025, 0x00192025, 0x00181e26, 0x00171e25, 0x00151f26, 0x00182329, 0x00202830, 0x001e272e, 0x001f282f, 0x00182128, 0x001a2229, 0x00212830, 0x00242c34, 0x001c242b, 0x00252d36, 0x002c363f, 0x0027323c, 0x0027313c, 0x0028323c, 0x0027303b, 0x00232d38, 0x00202b34, 0x00212a33, 0x001f272e, 0x001b2429, 0x00182027, 0x00161e27, 0x0018212a, 0x001c242d, 0x00202933, 0x00202932, 0x00212c33, 0x001e282f, 0x00232c33, 0x00242d34, 0x00272f36, 0x002b323a, 0x0020272e, 0x001a2028, 0x00192027, 0x00192027, 0x00181d25, 0x00191e26, 0x001a1e27, 0x001a2028, 0x00181f26, 0x00171d24, 0x00171d26, 0x00151c25, 0x00182029, 0x00202831, 0x001d2730, 0x001c2730, 0x001c262f, 0x00182229, 0x001b242c, 0x001b242b, 0x00192128, 0x00121920, 0x001b2128, 0x0012181e, 0x0013191f, 0x0012191f, 0x0010171d, 0x00121920, 0x001d252c, 0x00202930, 0x00202a30, 0x00202a31, 0x00202b34, 0x00202b35, 0x00222c36, 0x00202a34, 0x00202933, 0x00202b34, 0x00253038, 0x00242f38, 0x00242e38, 0x0027303c, 0x0027303c, 0x0028323d, 0x002a323d, 0x0028303c, 0x0028303b, 0x00252e38, 0x00212b34, 0x00202a34, 0x00252f3a, 0x0029333d, 0x0029333d, 0x0028313c, 0x00252f39, 0x00232c38, 0x00202a37, 0x00202b36, 0x00232f39, 0x0028343d, 0x0028343f, 0x0027343f, 0x00253441, 0x00273844, 0x00263946, 0x00273847, 0x002e3f4e, 0x002e4050, 0x002b404f, 0x00283e4c, 0x002c4150, 0x00314655, 0x00304454, 0x00324858, 0x00334958, 0x00304757, 0x00304858, 0x00304959, 0x00304a5a, 0x00304c5e, 0x00334f60, 0x00344d5f, 0x0034495a, 0x002d4453, 0x00283e4c, 0x00263b47, 0x00243a46, 0x00223845, 0x00203744, 0x00203744, 0x00213744, 0x00213644, 0x00213643, 0x00223743, 0x00223844, 0x00223945, 0x00223847, 0x00213847, 0x00203544, 0x001c3241, 0x001b3040, 0x001b2f3f, 0x001b2e3c, 0x001b2e3c, 0x001a2e3c, 0x001a2d3c, 0x001a2e3c, 0x00192d3c, 0x00192e3c, 0x00182e3b, 0x00182e3b, 0x00182c39, 0x00182c38, 0x00182c38, 0x00182b38, 0x00182a37, 0x00182a37, 0x00172936, 0x00172936, 0x00172936, 0x00172936, 0x00172936, 0x00172937, 0x00172937, 0x00162a38, 0x00172c39, 0x00172c39, 0x00162b38, 0x00162b38, 0x00162c39, 0x00182c3a, 0x00182c3a, 0x00182e3b, 0x00182e3b, 0x00172e3b, 0x00162e3b, 0x00162e3b, 0x00182d3b, 0x00182d3b, 0x00172d39, 0x00162c38, 0x00162c38, 0x00162b39, 0x00162b38, 0x00162b38, 0x00162b37, 0x00152a36, 0x00152834, 0x00142834, 0x00142633, 0x00142431, 0x00132430, 0x00142431, 0x00142532, 0x00142532, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x00132431, 0x00122431, 0x00122431, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00122c32, 0x00143036, 0x00153439, 0x00183a3e, 0x00183f43, 0x001a4347, 0x001c474b, 0x001d4c50, 0x00205c68, 0x002da2ca, 0x00288caa, 0x00298ba8, 0x002ea0c5, 0x002ea0c6, 0x002989a6, 0x00246874, 0x0022595c, 0x00215659, 0x00205457, 0x00205356, 0x001f5154, 0x001e4f51, 0x001e4d50, 0x001d4b4e, 0x001c4a4d, 0x001d4a4d, 0x001d4a4d, 0x001d4a4d, 0x001d4a4d, 0x001c4b4e, 0x001d4b4e, 0x001e4c50, 0x001d4f51, 0x001e5053, 0x001f5053, 0x001f5154, 0x001f5154, 0x001f5154, 0x001f5053, 0x001e4f51, 0x001d4c50, 0x001d4a4d, 0x001b4649, 0x001a4347, 0x00183f43, 0x00183a3e, 0x0015363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0010212a, 0x0010212a, 0x0010212a, 0x0010222c, 0x0010222c, 0x0010222c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011202c, 0x0010212a, 0x00102029, 0x00102029, 0x00102029, 0x00102029, 0x0010202b, 0x0010202b, 0x0010212b, 0x0011232c, 0x0012242c, 0x0012242c, 0x0012242e, 0x0012242e, 0x0012242f, 0x00122431, 0x00122431, 0x00132632, 0x00142734, 0x00142834, 0x00152935, 0x00152b38, 0x00152b38, 0x00152b38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00172b38, 0x00182b39, 0x00182a39, 0x00152a37, 0x00142836, 0x00142835, 0x00142834, 0x00142834, 0x00152733, 0x00162732, 0x00152633, 0x00152631, 0x00152631, 0x00152732, 0x00162832, 0x00162832, 0x00142734, 0x00142734, 0x00142734, 0x00142835, 0x00142835, 0x00172935, 0x00172935, 0x00162935, 0x00162935, 0x00162834, 0x00162832, 0x00142732, 0x00142730, 0x0015262f, 0x0016242f, 0x0015232c, 0x00122028, 0x00101d25, 0x000f1c24, 0x00101c25, 0x00111e27, 0x0014212a, 0x0016242c, 0x00192831, 0x001c2c36, 0x001f303b, 0x00233843, 0x002b4350, 0x002f4854, 0x00304956, 0x00324854, 0x00324854, 0x002d434f, 0x00273c49, 0x00293f4c, 0x00293f4d, 0x00273c49, 0x002c404d, 0x002e404c, 0x002c3b48, 0x00293743, 0x0023303b, 0x0024313b, 0x0029343e, 0x0027313c, 0x0025303a, 0x00242e38, 0x00242e38, 0x0027323e, 0x002a3541, 0x002c3844, 0x00293843, 0x00283843, 0x002d3b46, 0x002f3a46, 0x002a3440, 0x00202931, 0x001b242b, 0x00182229, 0x001c242c, 0x00182128, 0x00161f28, 0x00141d25, 0x00131c23, 0x00131b22, 0x00141a22, 0x00141a21, 0x00171e24, 0x001c2329, 0x001b2228, 0x001a2028, 0x001a2129, 0x0018232a, 0x001c252c, 0x00212c32, 0x00202a31, 0x00212c33, 0x001d272d, 0x001f2830, 0x00283138, 0x00242d35, 0x001c252e, 0x00242e36, 0x00243038, 0x0028343e, 0x002a3540, 0x002b3540, 0x0028313c, 0x00242f39, 0x00222c37, 0x00232c35, 0x00212a31, 0x00212a30, 0x001e272c, 0x001c242c, 0x001d262f, 0x001f2830, 0x00232d36, 0x00263039, 0x0028333a, 0x00232c34, 0x00222932, 0x00262c35, 0x00293038, 0x00262d35, 0x001f252f, 0x001e242c, 0x00151c24, 0x001c2229, 0x001c232a, 0x001c212a, 0x001c212b, 0x001c232b, 0x001d242c, 0x00192028, 0x00182028, 0x001b212b, 0x001e2730, 0x00212a33, 0x001f2830, 0x001e2830, 0x001b242d, 0x00182329, 0x0019242a, 0x001a242b, 0x001c242b, 0x00151e25, 0x001b2228, 0x00141b21, 0x00161c22, 0x00151c22, 0x00141c21, 0x00121920, 0x001a2128, 0x00242c34, 0x00232c34, 0x00202b32, 0x001c2831, 0x001f2833, 0x00222c37, 0x00232c37, 0x00212c35, 0x00202b34, 0x00242e37, 0x00263039, 0x00242d37, 0x00222c37, 0x00212b35, 0x00252f3a, 0x0028303c, 0x0028303a, 0x00252d38, 0x00242e37, 0x00222c35, 0x00202a34, 0x0025303a, 0x0028323c, 0x0028323c, 0x0028333d, 0x0028323d, 0x00242e3b, 0x00222c38, 0x00202c37, 0x00212d37, 0x0024303a, 0x0029343f, 0x00293641, 0x00283643, 0x00283a46, 0x002a3d4b, 0x00293c4b, 0x00304152, 0x00314454, 0x002e4453, 0x002b4150, 0x002d4252, 0x00314655, 0x002f4454, 0x002d4454, 0x002e4454, 0x002f4554, 0x00304758, 0x002f4858, 0x00304a5a, 0x00335060, 0x00375465, 0x00385364, 0x00374f60, 0x00314858, 0x002a404f, 0x00263b48, 0x00253a47, 0x00233946, 0x00203643, 0x00203542, 0x00203442, 0x00203440, 0x00203440, 0x00223742, 0x00233944, 0x00243c46, 0x00243a48, 0x00223848, 0x001f3544, 0x001c3241, 0x001b3040, 0x001a2e3e, 0x00192c3b, 0x00192c3a, 0x00192c3a, 0x001a2d3b, 0x001a2d3b, 0x00182d3b, 0x00182d3b, 0x00182d3b, 0x00172d3a, 0x00182c39, 0x00182c38, 0x00182c38, 0x00182a37, 0x00182a37, 0x00182936, 0x00172935, 0x00172935, 0x00172935, 0x00172935, 0x00172935, 0x00172937, 0x00172938, 0x00162a38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00172c39, 0x00182c3a, 0x00182d3b, 0x00182e3b, 0x00182e3b, 0x00172e3b, 0x00162e3b, 0x00162e3b, 0x00182e3b, 0x00182e3b, 0x00172e3a, 0x00162c38, 0x00152c38, 0x00172c39, 0x00162b38, 0x00162b38, 0x00162b37, 0x00162b36, 0x00162834, 0x00142834, 0x00142633, 0x00142431, 0x00132430, 0x00142431, 0x00142532, 0x00142532, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x00132431, 0x00122431, 0x00122431, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00111f27, 0x00102229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4245, 0x001b4649, 0x001c4a4d, 0x00205964, 0x002ca1c9, 0x002da2cb, 0x002ca0c6, 0x002888a6, 0x00236674, 0x00215659, 0x00205558, 0x00205356, 0x00205254, 0x001f5154, 0x001e4f51, 0x001d4c50, 0x001d4b4e, 0x001c484c, 0x001c474b, 0x001c474b, 0x001c4649, 0x001c4649, 0x001c474b, 0x001c484c, 0x001d4a4d, 0x001c4b4e, 0x001e4c50, 0x001d4f51, 0x001f5053, 0x001f5154, 0x00205254, 0x00205254, 0x00205254, 0x001f5154, 0x001e5053, 0x001d4d50, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0010212a, 0x0010212a, 0x0010222b, 0x0010222c, 0x0010222d, 0x0011222c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011202c, 0x000f2029, 0x00102029, 0x00102029, 0x00102029, 0x00102029, 0x0011202c, 0x0011202c, 0x0011222c, 0x0011232c, 0x0012242c, 0x0012242c, 0x0013232e, 0x0014242e, 0x0014242f, 0x00142530, 0x00142530, 0x00142631, 0x00142732, 0x00152834, 0x00162834, 0x00162a37, 0x00162a37, 0x00162b38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00172a38, 0x00182a38, 0x00172938, 0x00152836, 0x00142835, 0x00142835, 0x00142835, 0x00142734, 0x00142633, 0x00142532, 0x00152632, 0x00162732, 0x00162832, 0x00162832, 0x00162832, 0x00152732, 0x00152633, 0x00152633, 0x00142734, 0x00142734, 0x00142734, 0x00172834, 0x00172834, 0x00162834, 0x00152834, 0x00152834, 0x00152731, 0x00152631, 0x00152630, 0x0015252e, 0x0014222c, 0x00131f29, 0x000f1b24, 0x000d1a22, 0x00101c25, 0x0015212c, 0x0018252f, 0x001c2b34, 0x00202f38, 0x0021313c, 0x0023343e, 0x00233742, 0x00253c48, 0x002c4452, 0x00314c59, 0x0036505e, 0x0038505d, 0x00354c59, 0x002d4451, 0x00283f4c, 0x002b414e, 0x0029404e, 0x00283e4c, 0x002d4150, 0x002f404d, 0x002f3c4a, 0x00283642, 0x0023303b, 0x0025333c, 0x002b3741, 0x0028333d, 0x0027313c, 0x00242e38, 0x00242f38, 0x0028333e, 0x00293541, 0x002c3844, 0x002a3844, 0x002b3b46, 0x002e3c47, 0x002e3945, 0x00242e3a, 0x001b242d, 0x00182329, 0x001a242b, 0x001c262d, 0x00182129, 0x00162029, 0x00172028, 0x00161f26, 0x00151e25, 0x00121921, 0x00131920, 0x00181f24, 0x001b2228, 0x001b2127, 0x001c232a, 0x00222931, 0x00232c34, 0x00212c33, 0x00202a31, 0x00263038, 0x002c373f, 0x00243038, 0x00242f38, 0x002e3841, 0x00232c36, 0x001d2830, 0x00232d36, 0x0026333b, 0x002c3741, 0x002c3841, 0x002e3843, 0x002c3741, 0x0029343e, 0x0028323c, 0x0028303a, 0x00252d34, 0x00222a30, 0x001f282e, 0x00212932, 0x00242c34, 0x00252e37, 0x0029343c, 0x002c363f, 0x0029333b, 0x00232a32, 0x00202830, 0x0020262e, 0x00212830, 0x00252c34, 0x00202730, 0x0020262f, 0x00161c24, 0x001a2028, 0x001d242c, 0x001d242d, 0x001e242d, 0x0020262e, 0x001f252c, 0x001b2129, 0x001b2129, 0x001d242c, 0x001c242c, 0x001e262f, 0x001e2730, 0x001e2830, 0x001c262e, 0x00182229, 0x0019242b, 0x001c262f, 0x001a232c, 0x001a222b, 0x001b232a, 0x00171d24, 0x00192026, 0x00192026, 0x00182025, 0x00141b22, 0x00161e25, 0x00222a31, 0x00273037, 0x00212c34, 0x001e2a34, 0x001c2731, 0x001f2934, 0x00232c37, 0x00202b34, 0x001d2830, 0x001c2730, 0x00212b34, 0x00242f39, 0x00232d38, 0x00202934, 0x00222b36, 0x00252d38, 0x00252e38, 0x00242c38, 0x00242d37, 0x00242e37, 0x00242f39, 0x0028323c, 0x002a343f, 0x0029343e, 0x0028333d, 0x0028323c, 0x00252f3b, 0x0026303c, 0x0025303b, 0x00232f39, 0x00222e3a, 0x0028343f, 0x002c3743, 0x002b3945, 0x00293b47, 0x002b3e4c, 0x00293b4b, 0x00324354, 0x0036495b, 0x00324758, 0x00304656, 0x00324657, 0x00324656, 0x002d4352, 0x002c4251, 0x002c4352, 0x00304656, 0x00314859, 0x002f485a, 0x002f4a5b, 0x00345163, 0x003a576a, 0x003c5668, 0x00395264, 0x00344c5c, 0x002e4654, 0x0029404d, 0x00283e4b, 0x00253c49, 0x00233844, 0x00203541, 0x001e3340, 0x001c323f, 0x001c313d, 0x00203440, 0x00233944, 0x00243c47, 0x00243b47, 0x00213845, 0x001e3442, 0x001b313f, 0x001b303d, 0x001a2e3c, 0x00182c39, 0x00182c39, 0x00182c3a, 0x00182c3a, 0x00192c3b, 0x00182d3b, 0x00182d3b, 0x00172d3a, 0x00172c3a, 0x00182c39, 0x00192b39, 0x00192a38, 0x00192a38, 0x00182938, 0x00182936, 0x00172935, 0x00172935, 0x00172935, 0x00172935, 0x00172935, 0x00162835, 0x00152835, 0x00152935, 0x00152a36, 0x00162b38, 0x00162b38, 0x00162b38, 0x00172c39, 0x00182c3a, 0x00182d3b, 0x00182e3c, 0x00182e3c, 0x00182e3c, 0x00182e3c, 0x00182e3c, 0x00182e3b, 0x00182e3b, 0x00182e3b, 0x00172d39, 0x00152c38, 0x00172c39, 0x00162b38, 0x00162b38, 0x00162b37, 0x00162b36, 0x00162834, 0x00152834, 0x00142733, 0x00142532, 0x00142431, 0x00142431, 0x00142431, 0x00132430, 0x00122430, 0x00122430, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00102a30, 0x00132c32, 0x00143036, 0x0016363b, 0x00183a3e, 0x00183f43, 0x001a4347, 0x001c474b, 0x001d4b50, 0x00216a7e, 0x0025809b, 0x00206270, 0x00205256, 0x00205254, 0x00205254, 0x001f5154, 0x001e5053, 0x001d4d50, 0x001d4c50, 0x001d4b4e, 0x001c484c, 0x001c474b, 0x001b4649, 0x001a4448, 0x001a4448, 0x001a4448, 0x001a4448, 0x001c4649, 0x001c474b, 0x001d484c, 0x001c4b4e, 0x001d4d50, 0x001e5053, 0x001f5154, 0x00205356, 0x00205457, 0x00205457, 0x00205457, 0x00205356, 0x00205254, 0x001e5053, 0x001d4c50, 0x001d4a4d, 0x001b4649, 0x001a4245, 0x00183d41, 0x0017383c, 0x00153439, 0x00143036, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0010222b, 0x0010222b, 0x0010222b, 0x0011232d, 0x0011232e, 0x0011222d, 0x0012212d, 0x0012212d, 0x0012212c, 0x0012212c, 0x0011202c, 0x0010202b, 0x0010202b, 0x0010202a, 0x00102029, 0x00102029, 0x0011202c, 0x0012212c, 0x0012222c, 0x0011232c, 0x0012242c, 0x0012242c, 0x0014232e, 0x0014242e, 0x00142430, 0x00142530, 0x00152631, 0x00152631, 0x00162832, 0x00172833, 0x00172834, 0x00182a36, 0x00182a37, 0x00172a38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00162b38, 0x00172a38, 0x00182a38, 0x00172938, 0x00152836, 0x00142835, 0x00142835, 0x00142835, 0x00142734, 0x00142633, 0x00142532, 0x00142532, 0x00152731, 0x00162832, 0x00162832, 0x00162732, 0x00152732, 0x00152633, 0x00142533, 0x00142734, 0x00142734, 0x00142734, 0x00172633, 0x00172633, 0x00162633, 0x00152733, 0x00162633, 0x00162631, 0x00162530, 0x0014232c, 0x00102029, 0x000f1c26, 0x000d1923, 0x00101c25, 0x00142029, 0x001c2830, 0x001f2c36, 0x001f2d38, 0x0022323d, 0x00253641, 0x00273a45, 0x00283c48, 0x00283d4b, 0x0028404e, 0x002d4856, 0x00334e5d, 0x00385363, 0x003c5766, 0x003a5260, 0x00324957, 0x002c4350, 0x00304654, 0x002d4453, 0x002c4250, 0x002f4351, 0x0030424f, 0x002e3c4a, 0x0024313c, 0x00202e38, 0x0024323c, 0x002c3842, 0x0028343e, 0x0027313c, 0x00242e38, 0x0026313c, 0x00283440, 0x00293642, 0x002b3844, 0x002c3a45, 0x002d3c48, 0x002f3d48, 0x002d3a46, 0x00202c38, 0x0018242c, 0x001a252c, 0x001d272e, 0x001c272e, 0x0018222b, 0x0017212a, 0x0018222b, 0x0018222b, 0x00151c26, 0x00121822, 0x00141a22, 0x00182027, 0x001d242b, 0x001e242c, 0x00242b34, 0x002c333c, 0x002a343d, 0x00232d37, 0x0027323c, 0x00333e48, 0x0037424d, 0x002c3843, 0x00303c47, 0x0035404c, 0x00242e3a, 0x00222e39, 0x00293540, 0x00303d48, 0x00333e49, 0x0036404c, 0x00363f4b, 0x00303844, 0x002a343f, 0x002b3440, 0x00212934, 0x00212833, 0x00212932, 0x00242c34, 0x00232933, 0x00242c35, 0x002b333c, 0x002c363f, 0x002a343c, 0x00202932, 0x00202831, 0x00232933, 0x00212830, 0x00252c34, 0x00242a32, 0x001f252f, 0x001f252e, 0x001c222b, 0x001a2029, 0x001e252d, 0x00202730, 0x001c242c, 0x00252c34, 0x00252c34, 0x00202730, 0x00202831, 0x00202831, 0x001b242c, 0x001e2730, 0x00202831, 0x00202a34, 0x00222c36, 0x001e2832, 0x001d2831, 0x00212b35, 0x001b242d, 0x001d2530, 0x001f272f, 0x00192028, 0x001b2228, 0x001c2228, 0x001b2228, 0x00182027, 0x00171d24, 0x00182027, 0x00232b32, 0x00212c34, 0x001b2830, 0x0017222c, 0x00142029, 0x001a242f, 0x001d2830, 0x001c2730, 0x001a242d, 0x001c2730, 0x0025303a, 0x0027313c, 0x00212b35, 0x00202833, 0x00202833, 0x00212934, 0x00202834, 0x00222b34, 0x00242d37, 0x00262f39, 0x0029323c, 0x002c3540, 0x002d3741, 0x002c3640, 0x002c3540, 0x0027313c, 0x0028333d, 0x002a3540, 0x0027333e, 0x0024303b, 0x0025313d, 0x002a3743, 0x002c3c48, 0x002c3e4a, 0x002b3d4c, 0x00273949, 0x00304254, 0x00374b5c, 0x0034495a, 0x00344a5b, 0x00354b5c, 0x00304555, 0x002b4150, 0x002c4252, 0x002e4454, 0x0033495b, 0x00364e60, 0x00355063, 0x00345063, 0x0038586b, 0x003d5e70, 0x003c5a6d, 0x003c5668, 0x00395364, 0x00365061, 0x00334c5c, 0x002f4754, 0x002b414f, 0x00283f4b, 0x00253b47, 0x00223744, 0x00203441, 0x001b303c, 0x00192e3a, 0x001d333e, 0x00223844, 0x00223844, 0x00203442, 0x001c323f, 0x001b303e, 0x001b2f3c, 0x00182d3b, 0x00172c38, 0x00162b38, 0x00172b39, 0x00172c39, 0x00182c3a, 0x00182c3a, 0x00182c3a, 0x00182c3a, 0x00172c3a, 0x00192c39, 0x00192b39, 0x00192a38, 0x00192a38, 0x00182937, 0x00182937, 0x00182a36, 0x00182a36, 0x00182a36, 0x00182a36, 0x00182a36, 0x00162935, 0x00162935, 0x00152a35, 0x00152a36, 0x00172c38, 0x00172c39, 0x00172c39, 0x00182c3a, 0x00182d3b, 0x00182d3b, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182f3c, 0x00182e3c, 0x00182e3b, 0x00182e3b, 0x00182e3b, 0x00172d3a, 0x00152c39, 0x00162c3a, 0x00152b38, 0x00152b38, 0x00152b38, 0x00152b38, 0x00162835, 0x00152834, 0x00152734, 0x00152633, 0x00142532, 0x00142431, 0x00142431, 0x00132430, 0x00122430, 0x00122430, 0x00122430, 0x00122431, 0x00122431, 0x00122431, 0x00122431, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x00102229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x00143439, 0x0017383c, 0x00183c40, 0x00194044, 0x001b4448, 0x001c474b, 0x001c4a4d, 0x001d4b4e, 0x001e4d50, 0x001e4d50, 0x001d4d50, 0x001e4d50, 0x001d4c50, 0x001d4b4e, 0x001c4a4d, 0x001c484c, 0x001c474b, 0x001b4448, 0x001a4347, 0x001a4245, 0x001a4245, 0x001a4245, 0x001b4245, 0x001a4347, 0x001a4448, 0x001c474b, 0x001d4a4d, 0x001d4c50, 0x001e4f51, 0x001f5154, 0x00205459, 0x0020585e, 0x0021595f, 0x00215a60, 0x00215a60, 0x0021595f, 0x0020585e, 0x0020555b, 0x001e4f53, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x0015363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0011232e, 0x0011232e, 0x0011232e, 0x0011232d, 0x0011232d, 0x0011222d, 0x0012212c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011202b, 0x0010202a, 0x0010202a, 0x00101f29, 0x00101f28, 0x00102029, 0x0011202c, 0x0011202c, 0x0012212c, 0x0012212c, 0x0013222c, 0x0012232c, 0x0014242d, 0x0014242f, 0x00142430, 0x00142530, 0x00152631, 0x00152731, 0x00162832, 0x00162833, 0x00172833, 0x00172935, 0x00172936, 0x00172a37, 0x00162a37, 0x00162b37, 0x00162b37, 0x00162b38, 0x00172a38, 0x00182a38, 0x00172938, 0x00172937, 0x00162936, 0x00172936, 0x00172835, 0x00162834, 0x00162834, 0x00152733, 0x00152733, 0x00152731, 0x00152731, 0x00152631, 0x00142530, 0x00142531, 0x00142532, 0x00142532, 0x00142734, 0x00142734, 0x00142633, 0x00142531, 0x00142531, 0x00142532, 0x00152632, 0x00162531, 0x0018242f, 0x0015212b, 0x00101c25, 0x000c1922, 0x000e1b25, 0x00101e28, 0x00182630, 0x001f2c38, 0x0024323f, 0x00273543, 0x00263743, 0x00273947, 0x00293c4a, 0x002c404e, 0x002e4452, 0x002d4453, 0x002d4655, 0x00314c5c, 0x00355263, 0x00385768, 0x003c5a6c, 0x003a5566, 0x00344c5d, 0x00304758, 0x00314859, 0x002f4555, 0x002f4452, 0x00304451, 0x0030414e, 0x002b3a47, 0x00202e3b, 0x00202c38, 0x0025333d, 0x002c3843, 0x00293540, 0x0026323c, 0x0026333c, 0x00283540, 0x00293743, 0x00293843, 0x00293844, 0x002b3b45, 0x002c3c46, 0x002b3944, 0x002a3742, 0x00202b35, 0x0019252c, 0x001c282e, 0x001f282f, 0x001c272e, 0x0019242b, 0x0018232b, 0x001a242c, 0x0018232b, 0x00161f28, 0x00151c26, 0x00131a23, 0x001a2128, 0x00222931, 0x00252c34, 0x002b323c, 0x002f3843, 0x002c3843, 0x002c3844, 0x0035424f, 0x00394654, 0x003b4755, 0x00323e4c, 0x00343f4c, 0x00323e4b, 0x00293440, 0x002e3945, 0x0034404c, 0x0035404c, 0x00384350, 0x003c4452, 0x0039414e, 0x00333b48, 0x002e3644, 0x002d3543, 0x00252d3b, 0x0029303d, 0x002f3842, 0x002f3741, 0x00282e39, 0x002e3540, 0x002d343f, 0x002c343e, 0x002c343e, 0x001d2631, 0x00252d37, 0x002a303b, 0x0028303a, 0x00323944, 0x002d343e, 0x00272e38, 0x00202732, 0x00202833, 0x00202832, 0x00202832, 0x00212a33, 0x001f2730, 0x00232b35, 0x002c333e, 0x002b333e, 0x0026303b, 0x0026303c, 0x00202b35, 0x001f2834, 0x00212b36, 0x002a343f, 0x0028343f, 0x00242f3b, 0x00242e3a, 0x0028333f, 0x00212a36, 0x001d2632, 0x00202832, 0x0019222a, 0x001a2329, 0x001c242b, 0x001a2229, 0x00192128, 0x00182028, 0x00161e25, 0x001a232a, 0x00202b32, 0x001e2a32, 0x001b2730, 0x0017232b, 0x00152029, 0x001a242d, 0x001d2830, 0x001c2730, 0x001d2831, 0x00242e38, 0x0029333d, 0x00242f39, 0x00202a34, 0x001e2731, 0x001c242f, 0x001a222d, 0x001c242f, 0x00202831, 0x00232b36, 0x00262e38, 0x00262f39, 0x0028303b, 0x002a333d, 0x002b3440, 0x0028313e, 0x0029333f, 0x002a3542, 0x002a3642, 0x00283440, 0x00273440, 0x00293744, 0x002e3d4b, 0x002f404d, 0x002b3e4b, 0x00273a4a, 0x00304454, 0x00344859, 0x00314858, 0x00324959, 0x00334959, 0x002f4454, 0x002b4151, 0x002c4353, 0x002f4555, 0x00344c5e, 0x00385367, 0x003d5d72, 0x00456a80, 0x004b7488, 0x004a7287, 0x0045697e, 0x00406176, 0x003e5e72, 0x003e5f74, 0x003c5b70, 0x00395468, 0x00344c5e, 0x00304858, 0x002d4453, 0x002c4050, 0x00293e4c, 0x00213643, 0x00182c38, 0x00152834, 0x00182a34, 0x001c2d39, 0x001c2e3b, 0x001c2f3c, 0x001c303d, 0x001c2f3c, 0x001a2d3b, 0x00172b37, 0x00162a37, 0x00162b38, 0x00172b39, 0x00172c39, 0x00182c39, 0x00182c39, 0x00182c39, 0x00182c39, 0x00182b38, 0x00182a38, 0x00182a38, 0x00182937, 0x00182937, 0x00182937, 0x00182a38, 0x00182b38, 0x00192c38, 0x00192c39, 0x001b2f3c, 0x001d323f, 0x001d3340, 0x001c3340, 0x0019303d, 0x00182f3c, 0x00182e3c, 0x00182d3b, 0x00182d3b, 0x00182d3b, 0x00182d3b, 0x00182e3c, 0x00182e3c, 0x00182e3c, 0x00182e3c, 0x00182e3c, 0x00182e3b, 0x00182e3b, 0x00182e3b, 0x00182d3b, 0x00172d3a, 0x00172c39, 0x00172c39, 0x00162b38, 0x00162a38, 0x00162a38, 0x00152934, 0x00142834, 0x00142734, 0x00142633, 0x00142532, 0x00142430, 0x00132430, 0x00132430, 0x0012242f, 0x0012242f, 0x00122430, 0x00122430, 0x00122430, 0x00122531, 0x00122531, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153338, 0x00153439, 0x00183a3e, 0x00183d41, 0x00194044, 0x001a4347, 0x001c4649, 0x001c484c, 0x001d4a4d, 0x001c4a4d, 0x001c4a4d, 0x001c4a4d, 0x001c484c, 0x001c484c, 0x001b4649, 0x001b4448, 0x001a4347, 0x001a4245, 0x00194044, 0x00194044, 0x00194044, 0x00184044, 0x00194044, 0x001b4347, 0x001a4448, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001e5053, 0x00205960, 0x00298cac, 0x002c99bd, 0x002c99bd, 0x002c9abd, 0x002c9abd, 0x002c99bd, 0x002b98bd, 0x002b98bc, 0x00247c94, 0x001e4e51, 0x001d4a4d, 0x001c4649, 0x001a4044, 0x00183c40, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0013282e, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00132430, 0x00132430, 0x00132430, 0x0012242f, 0x0011232d, 0x0011222d, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011202a, 0x00102029, 0x00102029, 0x00102029, 0x00101f28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x0012202a, 0x0013202a, 0x0013212b, 0x0013222c, 0x0014242c, 0x0014242e, 0x00152530, 0x00142530, 0x00152631, 0x00162832, 0x00162832, 0x00162832, 0x00162832, 0x00172834, 0x00162834, 0x00162836, 0x00162936, 0x00162b37, 0x00152a36, 0x00172c38, 0x00172b38, 0x00182a37, 0x00182b37, 0x00182c38, 0x00182c38, 0x00192c37, 0x00192a35, 0x00192a35, 0x00182934, 0x00182934, 0x00162832, 0x00152731, 0x00152631, 0x00142530, 0x0014242f, 0x00142430, 0x00142532, 0x00142532, 0x00142633, 0x00132633, 0x00132531, 0x00142531, 0x00142531, 0x00142632, 0x00142631, 0x0015242e, 0x00152029, 0x00101a22, 0x000c181f, 0x000f1b23, 0x0016242e, 0x001d2c39, 0x00223440, 0x00263845, 0x002b3c4b, 0x002c4050, 0x002c4151, 0x002c4353, 0x002e4656, 0x00304a5b, 0x00314c5c, 0x00304a5b, 0x00314b5c, 0x00355163, 0x0038586b, 0x003c6073, 0x00426579, 0x0039596c, 0x00355365, 0x00314c5e, 0x0030485a, 0x002e4657, 0x002d4453, 0x002d4451, 0x002d404c, 0x00283a46, 0x00202e3c, 0x00202c39, 0x0026343f, 0x002a3844, 0x00283742, 0x00263540, 0x00273541, 0x002a3844, 0x002a3a45, 0x002a3a45, 0x002a3944, 0x00293843, 0x002c3944, 0x002b3741, 0x0028343e, 0x00212a34, 0x001d2830, 0x001f292e, 0x001f292e, 0x001c262d, 0x001a242b, 0x0019242a, 0x001b252c, 0x00182329, 0x00141f25, 0x00141d24, 0x00111b23, 0x001c262d, 0x00242d35, 0x00252f38, 0x002d3641, 0x0037434f, 0x0034434e, 0x00384652, 0x003c4a59, 0x003e4a5b, 0x003d4a5a, 0x00384554, 0x0034404e, 0x00303b48, 0x00333e4c, 0x003b4452, 0x003a4450, 0x00394250, 0x003c4454, 0x003e4555, 0x003d4454, 0x003a4250, 0x0038404f, 0x00394150, 0x0038404f, 0x00394250, 0x003c4753, 0x003c4751, 0x0037404b, 0x0039414c, 0x003a404c, 0x00383f4a, 0x00303642, 0x0028303c, 0x002c3441, 0x00343c48, 0x00343c48, 0x003b434f, 0x00343c48, 0x00343c48, 0x002d3541, 0x002c343e, 0x00272f3a, 0x0027303b, 0x0028303d, 0x00252e3c, 0x0026303d, 0x002e3744, 0x00303a48, 0x00303c49, 0x002c3846, 0x00283340, 0x0025303c, 0x0028323f, 0x00293440, 0x00283440, 0x002a3743, 0x00293642, 0x002c3743, 0x002b3441, 0x001e2834, 0x00202934, 0x0019232c, 0x001b242c, 0x001c252d, 0x00162027, 0x00182229, 0x0018232a, 0x0018232a, 0x0018242a, 0x001c282f, 0x001d2932, 0x001c2830, 0x001b262f, 0x0018232c, 0x0018232c, 0x0018242c, 0x001d2a32, 0x001f2b34, 0x00202c36, 0x0027303b, 0x0026313c, 0x00202c36, 0x001e2832, 0x001c242e, 0x0018202c, 0x001b232e, 0x001d2630, 0x00202832, 0x00222b34, 0x00242d36, 0x00262e37, 0x00273039, 0x0027303b, 0x00262f3c, 0x0028333f, 0x00283441, 0x00273643, 0x00283844, 0x002a3948, 0x00283847, 0x002e404e, 0x002d414e, 0x00273c49, 0x00253a49, 0x00324656, 0x00334857, 0x002f4554, 0x002d4554, 0x002f4554, 0x002e4453, 0x002d4453, 0x002e4454, 0x002f4658, 0x00334e61, 0x003b5c71, 0x0048748b, 0x005f90a9, 0x00699cb4, 0x006597b0, 0x006492ac, 0x005c89a4, 0x00547f99, 0x004e7893, 0x004b728c, 0x00496c86, 0x0045677f, 0x003c5a71, 0x00365065, 0x00344c60, 0x0032485a, 0x002b404f, 0x00213340, 0x00162632, 0x000e1c27, 0x00101e28, 0x00162430, 0x001a2a37, 0x001c2c3a, 0x001c2d3b, 0x001b2c3a, 0x00182b37, 0x00172936, 0x00172938, 0x00182a38, 0x00182a38, 0x00182c38, 0x00182c38, 0x00182c38, 0x00182c38, 0x00182c38, 0x00172b37, 0x00172b37, 0x00162a36, 0x00162a36, 0x00172b38, 0x00182c3b, 0x00192f3c, 0x001e3541, 0x00233b47, 0x00263f4d, 0x00284250, 0x00294451, 0x00294451, 0x00284450, 0x0026414f, 0x00203847, 0x001b3342, 0x00193040, 0x00192f3e, 0x00192e3d, 0x001a2f3c, 0x001b2f3c, 0x00192e3c, 0x00182d3b, 0x00192d3c, 0x001a2e3c, 0x001a2e3c, 0x00192d3b, 0x00182d3b, 0x00182d3b, 0x00192d39, 0x00192c38, 0x00182c38, 0x00182a37, 0x00182a37, 0x00162934, 0x00142834, 0x00142834, 0x00142733, 0x00132631, 0x0013242f, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012252f, 0x00122530, 0x00132630, 0x00132630, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0012242c, 0x0010282e, 0x00132c32, 0x00143036, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183d41, 0x001a4044, 0x001b4347, 0x001b4448, 0x001b4649, 0x001b4649, 0x001b4649, 0x001b4649, 0x001b4649, 0x001a4448, 0x001a4347, 0x001a4245, 0x00194044, 0x00194044, 0x00193f43, 0x00193f43, 0x00193f43, 0x00193f43, 0x00194044, 0x001a4347, 0x001b4649, 0x001c484c, 0x001d4b4e, 0x001e4f51, 0x00205254, 0x00246d7f, 0x002ea3cb, 0x002c99bc, 0x002c94b5, 0x002c94b5, 0x002c94b5, 0x002c94b5, 0x002c94b4, 0x002d9ec4, 0x002c9bc0, 0x001f5054, 0x001e4c50, 0x001c474b, 0x001a4347, 0x00183d41, 0x0017383c, 0x00153439, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00142431, 0x00142431, 0x00142431, 0x0013242f, 0x0011232d, 0x0011222d, 0x0012212c, 0x0012212c, 0x0011202b, 0x00102029, 0x00102029, 0x00102029, 0x00102029, 0x00101f29, 0x00101e28, 0x00101e28, 0x00101d27, 0x00101d27, 0x00111f29, 0x0013202a, 0x0013212b, 0x0013222c, 0x0014242c, 0x0014242e, 0x00152530, 0x00142530, 0x00152631, 0x00162832, 0x00162832, 0x00162832, 0x00162832, 0x00162832, 0x00152834, 0x00152836, 0x00162836, 0x00162a36, 0x00162a36, 0x00172c38, 0x00182c38, 0x00192c38, 0x00192c38, 0x001a2d39, 0x001a2d39, 0x001a2c38, 0x001a2c37, 0x001a2b36, 0x00192a34, 0x00182934, 0x00172833, 0x00152731, 0x00152631, 0x00142530, 0x0014242f, 0x0014242f, 0x00132430, 0x00132430, 0x00122430, 0x0012242f, 0x0012242e, 0x0013242f, 0x0014242f, 0x00142430, 0x0014242d, 0x00132029, 0x00111b24, 0x000e1820, 0x00121c24, 0x001c2831, 0x0024323f, 0x00263948, 0x002b404e, 0x002f4453, 0x00334858, 0x0033495c, 0x00324c5e, 0x00344f61, 0x00385465, 0x00385668, 0x00365568, 0x00345265, 0x00375468, 0x00406176, 0x004c7186, 0x00588095, 0x00588095, 0x0043677c, 0x003c5c70, 0x00345264, 0x002e495a, 0x002d4756, 0x002c4553, 0x002c4350, 0x002b3e4b, 0x00283a47, 0x00243240, 0x00212f3c, 0x00283541, 0x002a3843, 0x00283844, 0x00293844, 0x002a3944, 0x002c3b46, 0x002c3c48, 0x002c3c48, 0x00283743, 0x00273540, 0x00293540, 0x0029353f, 0x0026313c, 0x00242d38, 0x00202b33, 0x001d282e, 0x001b252a, 0x001b252c, 0x0019242a, 0x001a242b, 0x001d282f, 0x00182329, 0x00152027, 0x00152027, 0x00172128, 0x00202b31, 0x001f2930, 0x002a343d, 0x00343f4a, 0x003c4853, 0x003b4a54, 0x003d4c58, 0x003f4c5a, 0x00404a5a, 0x003f4959, 0x003d4855, 0x00374150, 0x00343f4c, 0x003a4453, 0x003d4755, 0x003d4554, 0x003c4452, 0x003e4554, 0x003f4657, 0x00404757, 0x00404857, 0x00404857, 0x00444c5a, 0x00454d5c, 0x00474f5d, 0x0047505e, 0x0048515e, 0x00454e5b, 0x003f4754, 0x003c4250, 0x00383e4a, 0x00353c48, 0x00373e4b, 0x0039414e, 0x003d4553, 0x00404856, 0x00444c59, 0x00414957, 0x00414957, 0x003b4350, 0x00343c49, 0x00373f4c, 0x0038414e, 0x00353f4c, 0x00313b4a, 0x00333c4b, 0x00363f4e, 0x00384250, 0x00394453, 0x00384453, 0x002a3543, 0x00333e4b, 0x00384451, 0x0034404d, 0x00283542, 0x002b3844, 0x00303d48, 0x002c3844, 0x002f3845, 0x00222c38, 0x00222c36, 0x001c262f, 0x001a242d, 0x001f2830, 0x001a242c, 0x001c242c, 0x001c252e, 0x001c2730, 0x001d2830, 0x001c2830, 0x001c2830, 0x001c2830, 0x001c2730, 0x001c252e, 0x001b252e, 0x0019252e, 0x001d2931, 0x001f2b34, 0x001e2a34, 0x00242e38, 0x0028343e, 0x00232f38, 0x00202b35, 0x001e2631, 0x001c2530, 0x001f2731, 0x00202831, 0x001e2730, 0x00212932, 0x00242d36, 0x00273038, 0x00272f38, 0x00242c38, 0x00262d3a, 0x00283440, 0x00283542, 0x00243340, 0x00233440, 0x00283a48, 0x00283948, 0x002d404e, 0x002c414f, 0x00283c4a, 0x00283c4b, 0x00314655, 0x00334757, 0x002f4554, 0x002c4452, 0x002d4453, 0x002f4554, 0x00304656, 0x00304657, 0x0031495b, 0x00345265, 0x0040647c, 0x005c8ca4, 0x0079aec3, 0x0088bcc9, 0x0084b8c8, 0x0086b7c8, 0x0086b7c8, 0x0081b1c4, 0x007aa9bd, 0x0073a0b5, 0x006893aa, 0x005c869f, 0x0050758f, 0x0044667f, 0x00405c74, 0x00395468, 0x00304959, 0x00293d4c, 0x0021303d, 0x0014202c, 0x000c1824, 0x000c1a25, 0x0012202c, 0x00182633, 0x001a2a36, 0x001b2c38, 0x00182b37, 0x00172936, 0x00172937, 0x00182a38, 0x00182a38, 0x00182a37, 0x00182b37, 0x00182c38, 0x00182c38, 0x00182a37, 0x00172a37, 0x00162b37, 0x00152a36, 0x00162b37, 0x00192e3b, 0x001d3240, 0x00233946, 0x00273f4b, 0x002c4551, 0x002f4856, 0x002f4a58, 0x002f4b58, 0x00304c59, 0x00304c5a, 0x00304c5a, 0x002e4858, 0x00284250, 0x00213948, 0x001d3443, 0x001c3040, 0x001b303d, 0x001b303c, 0x00192e3c, 0x00182d3b, 0x00182d3b, 0x001a2e3c, 0x001a2e3c, 0x00192d3c, 0x00182d3b, 0x00182d3b, 0x001a2d39, 0x001a2d39, 0x00182c38, 0x00182a37, 0x00182a37, 0x00162834, 0x00152833, 0x00142833, 0x00142732, 0x00132631, 0x0013242f, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012252f, 0x00122530, 0x00132630, 0x00132630, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x000f2229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00142e34, 0x00143036, 0x00143439, 0x0017383c, 0x00183c40, 0x00183d41, 0x00194044, 0x001a4245, 0x001a4347, 0x001a4347, 0x001a4448, 0x001a4448, 0x001a4347, 0x001b4347, 0x001b4245, 0x00184044, 0x00183f43, 0x00193f43, 0x00193f43, 0x00193f43, 0x00193f43, 0x00194044, 0x001a4245, 0x001b4448, 0x001c474b, 0x001c4a4d, 0x001d4d50, 0x001f5154, 0x00205356, 0x00247081, 0x002fa4cb, 0x0027778a, 0x00245c60, 0x00245d60, 0x00245c60, 0x00245c5f, 0x00235c5f, 0x002b90af, 0x002c9bc0, 0x00205457, 0x001d4d50, 0x001c484c, 0x001b4448, 0x00183f43, 0x00183a3e, 0x00153439, 0x00143036, 0x00122c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00142430, 0x00142430, 0x00142430, 0x0013242f, 0x0011232d, 0x0012222d, 0x0013222e, 0x0012212d, 0x0011202c, 0x00102029, 0x00102029, 0x00102029, 0x00102029, 0x00102028, 0x00112027, 0x00111f27, 0x00111f28, 0x00111f29, 0x00122029, 0x00132028, 0x0014212a, 0x0014222c, 0x0014232c, 0x0015242e, 0x00162430, 0x00162530, 0x00172631, 0x00172732, 0x00182732, 0x00182732, 0x00182732, 0x00182732, 0x00172833, 0x00172834, 0x00172834, 0x00182a34, 0x00182b36, 0x00182c38, 0x00192c38, 0x00192c38, 0x00192c38, 0x00192c38, 0x00192c39, 0x001a2c38, 0x001a2b37, 0x001a2b36, 0x00192a34, 0x00182934, 0x00172833, 0x00152731, 0x00152631, 0x00142530, 0x0014242f, 0x0012242e, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011232d, 0x0012222c, 0x0013222c, 0x0013222c, 0x0012202a, 0x00101c26, 0x000c1822, 0x000d1821, 0x00131f28, 0x001e2c35, 0x00263642, 0x002b3d4c, 0x002f4557, 0x00344c5e, 0x00385062, 0x00395265, 0x003a556a, 0x003c5c70, 0x00406276, 0x00416579, 0x0042687b, 0x0041697d, 0x00436c82, 0x004b748c, 0x005c89a0, 0x006f9db3, 0x0078a5bc, 0x006b97ad, 0x00527b91, 0x003f6177, 0x0038576b, 0x00324e60, 0x002e4859, 0x002f4655, 0x002d4450, 0x00283c48, 0x00273945, 0x00253240, 0x0024303e, 0x00283644, 0x002b3844, 0x00293845, 0x00293845, 0x002b3a47, 0x002d3c49, 0x002e3e4b, 0x00283845, 0x0023323f, 0x00273440, 0x0025313c, 0x0028343d, 0x0025303b, 0x00242f39, 0x00202a33, 0x001a242b, 0x00182228, 0x001b252c, 0x001c262d, 0x001f2930, 0x00232d34, 0x001c262d, 0x001c262c, 0x001b252c, 0x001a242c, 0x001e282f, 0x001d282e, 0x002d3740, 0x00333c46, 0x00333e48, 0x0037434c, 0x0038444e, 0x003a4450, 0x003a4250, 0x003c4351, 0x003f4552, 0x003d4450, 0x003c434f, 0x003e4553, 0x00404856, 0x00404855, 0x003f4754, 0x00404856, 0x00404858, 0x00424959, 0x00444c5a, 0x00454d5c, 0x00464e5c, 0x00484f5e, 0x00484f5e, 0x00444d5d, 0x00444c5c, 0x00444c5c, 0x00414858, 0x003d4453, 0x003d4452, 0x00404653, 0x00404754, 0x00404856, 0x00424959, 0x00485060, 0x004b5363, 0x004a5262, 0x00495161, 0x00474f5d, 0x00404957, 0x00404956, 0x00424c59, 0x00414b59, 0x00404b5b, 0x00404c5c, 0x00414d5d, 0x00424f5f, 0x00414e5e, 0x00435060, 0x00354250, 0x00323f4c, 0x003a4754, 0x003b4855, 0x00323e4c, 0x002e3b47, 0x00303c48, 0x002d3844, 0x0029323f, 0x00262e3b, 0x0029323d, 0x00252d38, 0x001d2530, 0x00222b34, 0x00242c34, 0x001e262f, 0x001c242e, 0x00202831, 0x00232d36, 0x00202a33, 0x001c2730, 0x001e2931, 0x00202c34, 0x001c2830, 0x001a262f, 0x001c2830, 0x001c2a32, 0x001d2b34, 0x001d2a34, 0x001e2a34, 0x0028343d, 0x0024303a, 0x00222c37, 0x00202833, 0x001f2832, 0x00202833, 0x00212932, 0x001f2730, 0x00202831, 0x00242d36, 0x00273038, 0x00272f38, 0x00242c38, 0x0028303c, 0x002b3643, 0x002a3844, 0x00233340, 0x0021323f, 0x00283948, 0x002b3c4a, 0x002e404e, 0x002d4150, 0x002c4150, 0x002e4352, 0x00324756, 0x00324656, 0x00304655, 0x002d4554, 0x002d4353, 0x00304757, 0x00334a5a, 0x0031495b, 0x00344d60, 0x003d5c70, 0x00497288, 0x00679ab0, 0x008dc0ca, 0x00a1cbcc, 0x00a5cacc, 0x00a7c9cc, 0x00a8c9cc, 0x00a8cacc, 0x00a4c8cc, 0x009fc4cb, 0x0094bcc8, 0x0086b0c0, 0x0077a1b5, 0x00628ca1, 0x0050778e, 0x0044687f, 0x003a586c, 0x00314b5e, 0x002b3e4f, 0x001f2f3d, 0x0012202c, 0x000a1821, 0x00081620, 0x00101e28, 0x0016242f, 0x001a2936, 0x00182936, 0x00172834, 0x00172834, 0x00172835, 0x00182936, 0x00182a37, 0x00182a37, 0x00182b38, 0x00182c38, 0x00182a37, 0x00172936, 0x00152a35, 0x00152a36, 0x00192e39, 0x001e3340, 0x00243a48, 0x0029414e, 0x002d4753, 0x00304957, 0x00304b59, 0x00304c5a, 0x00314c5b, 0x00314c5b, 0x00314c5b, 0x00314c5b, 0x00324d5b, 0x00314c5a, 0x002c4554, 0x00263d4c, 0x00203644, 0x001c303e, 0x001b303c, 0x001a2e3c, 0x00182d3b, 0x00192e3c, 0x001b2f3c, 0x001b303c, 0x001a2f3c, 0x001a2e3c, 0x00192e3c, 0x00192c39, 0x00192c38, 0x00182c38, 0x00182a37, 0x00182a37, 0x00162834, 0x00152833, 0x00142832, 0x00142731, 0x00132630, 0x0013242d, 0x0012242c, 0x0012242d, 0x0012242e, 0x0012242e, 0x0013242e, 0x0014242f, 0x00142430, 0x00142530, 0x00142530, 0x000d1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00143036, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183c40, 0x00183d41, 0x00194044, 0x00194044, 0x001b4245, 0x001a4245, 0x001a4245, 0x001b4245, 0x001b4245, 0x00194044, 0x00184044, 0x00193f43, 0x00193f43, 0x00193f43, 0x00193f43, 0x00194044, 0x001a4245, 0x001a4347, 0x001b4649, 0x001c484c, 0x001d4c50, 0x001e5053, 0x00205254, 0x00205558, 0x00257082, 0x0030a4cb, 0x0028788a, 0x00245e60, 0x00245e60, 0x00245e60, 0x00245d60, 0x00245c5f, 0x002b90af, 0x002c9bc0, 0x00205458, 0x001e4f51, 0x001c4a4d, 0x001c4649, 0x00194044, 0x00183c40, 0x0015363b, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0012252f, 0x0012252f, 0x0013242f, 0x0014242f, 0x0013232e, 0x0013222e, 0x0013222f, 0x0012212e, 0x0011202c, 0x00102029, 0x00102029, 0x00102029, 0x00102029, 0x00102028, 0x00112027, 0x00112027, 0x00132029, 0x0013202a, 0x00132029, 0x00132028, 0x00142129, 0x0014222c, 0x0015232c, 0x0016242e, 0x00162430, 0x00162530, 0x00172631, 0x00182732, 0x00182732, 0x00182732, 0x00182732, 0x00182732, 0x00182733, 0x00172833, 0x00172833, 0x00182a34, 0x00182b36, 0x00192c38, 0x00192c39, 0x00192c38, 0x00192c38, 0x00192c38, 0x00192c38, 0x001a2c38, 0x001a2b37, 0x001a2b36, 0x00192a34, 0x00182934, 0x00172833, 0x00152732, 0x00152631, 0x00142530, 0x0014242f, 0x0012242e, 0x0011232d, 0x0011232d, 0x0011232e, 0x0011222d, 0x0012212c, 0x0013202b, 0x00111f27, 0x000e1b24, 0x000b1720, 0x000c1822, 0x0014212c, 0x00202f3a, 0x00283a46, 0x00304451, 0x00354c5d, 0x003a5467, 0x003d596d, 0x00405c71, 0x00436075, 0x0045667c, 0x004c7187, 0x00568095, 0x00608ba1, 0x006996ab, 0x0071a0b3, 0x0077a5b8, 0x0080afc0, 0x008abac8, 0x0090c0cb, 0x008cbcca, 0x0079a8bc, 0x00628ca2, 0x00446b81, 0x003d6074, 0x00395669, 0x00344f60, 0x00324858, 0x002c414f, 0x00263846, 0x00243542, 0x0023313e, 0x00263340, 0x002a3744, 0x002a3844, 0x00293845, 0x002a3946, 0x002e3e4b, 0x0030404c, 0x002e3f4c, 0x00253441, 0x00243340, 0x00283541, 0x0025313c, 0x0027333c, 0x0024303a, 0x00222d37, 0x001c262f, 0x00172128, 0x00172027, 0x001a242b, 0x00202930, 0x00263037, 0x00242e34, 0x00202930, 0x001c272e, 0x001c252c, 0x001c252d, 0x00212b32, 0x00212b31, 0x00262f36, 0x00283039, 0x00242b34, 0x00222932, 0x00202832, 0x00212833, 0x00242935, 0x002b2f3c, 0x00343843, 0x00383c45, 0x00383c46, 0x003b404a, 0x003e4450, 0x003f4451, 0x003f4552, 0x003f4552, 0x00404654, 0x00404754, 0x00424854, 0x00424855, 0x00444957, 0x00454858, 0x00444858, 0x00404756, 0x00404656, 0x00434858, 0x00434858, 0x00434857, 0x00434856, 0x00434855, 0x00444956, 0x00444958, 0x00444959, 0x00474c5c, 0x00484f5f, 0x00495060, 0x00484f5f, 0x00474d5c, 0x00464c5c, 0x00474e5c, 0x00474e5d, 0x00484f60, 0x00484f61, 0x00465062, 0x00475163, 0x00454f61, 0x00434d5f, 0x00434f60, 0x003f4a5a, 0x00344050, 0x00384352, 0x003c4657, 0x00394352, 0x0039424f, 0x0037404c, 0x00323b48, 0x002a323f, 0x002e3541, 0x00343c47, 0x002b323c, 0x00202832, 0x00232a34, 0x00242c35, 0x00262e38, 0x0018212a, 0x001c242d, 0x00202a32, 0x00242d36, 0x001b252e, 0x001a242d, 0x001c262f, 0x001c252e, 0x001a252e, 0x001c2931, 0x001d2b33, 0x001e2c35, 0x001d2b34, 0x001c2833, 0x00202c36, 0x00243039, 0x001f2a34, 0x001f2832, 0x00202832, 0x00202832, 0x00202831, 0x00202832, 0x00222b34, 0x00242c36, 0x00262e38, 0x0028303b, 0x00272f3b, 0x00262e3c, 0x00293542, 0x002c3a47, 0x00253542, 0x0021333f, 0x00283948, 0x002c3c4b, 0x002f414f, 0x002d4250, 0x002e4350, 0x00314655, 0x00334857, 0x00324757, 0x00304756, 0x00304858, 0x00314858, 0x00334a5b, 0x00384f60, 0x00375062, 0x00385468, 0x0043667b, 0x00578499, 0x0074a9bc, 0x009ac7cb, 0x00aecccc, 0x00b5cccc, 0x00b8cccc, 0x00b9cccc, 0x00b9cccc, 0x00b8cccc, 0x00b5cccc, 0x00b1cbcc, 0x00acc9cc, 0x00a1c6cb, 0x0090bac4, 0x0079a4b8, 0x00618ca1, 0x004e7288, 0x00405f75, 0x00344c61, 0x002a3d4f, 0x001d2d3a, 0x00101f28, 0x0008161e, 0x0008161e, 0x00101e27, 0x00172531, 0x00182734, 0x00182734, 0x00162734, 0x00162834, 0x00162834, 0x00162834, 0x00162834, 0x00172936, 0x00172936, 0x00172935, 0x00162834, 0x00162935, 0x00182c38, 0x001c313d, 0x00243946, 0x002a404e, 0x002d4552, 0x00304956, 0x00314c58, 0x00324c5c, 0x00314c5b, 0x00314c5b, 0x00314d5c, 0x00324e5c, 0x00324e5c, 0x00324e5c, 0x00324e5c, 0x00314c5a, 0x002d4554, 0x00253c4b, 0x001f3441, 0x001b303d, 0x001a2e3c, 0x00182d3b, 0x00192e3c, 0x001b303c, 0x001b303c, 0x001b303c, 0x001b303c, 0x001a2e3c, 0x00192c39, 0x00192c38, 0x00182c38, 0x00182a37, 0x00182a37, 0x00162834, 0x00152833, 0x00142832, 0x00142731, 0x00132530, 0x0012242d, 0x0012242c, 0x0012242d, 0x0012242e, 0x0012242e, 0x0013242e, 0x0014242f, 0x00142430, 0x00142530, 0x00142530, 0x000d1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f2229, 0x00102229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00142e34, 0x00153338, 0x00143439, 0x0017383c, 0x00183c40, 0x00183d41, 0x00193f43, 0x00184044, 0x001b4245, 0x001b4245, 0x001b4245, 0x001b4245, 0x001b4245, 0x001b4245, 0x001a4245, 0x00194044, 0x00194044, 0x00194044, 0x001a4245, 0x001a4245, 0x001a4347, 0x001b4649, 0x001c484c, 0x001d4b4e, 0x001e4f51, 0x001f5154, 0x00205457, 0x0021585a, 0x00277284, 0x0030a4cb, 0x0028788b, 0x00245f61, 0x00246062, 0x00245f61, 0x00245f61, 0x00245d60, 0x002c90af, 0x002c9cc0, 0x00205559, 0x001f5053, 0x001d4b4e, 0x001c4649, 0x001a4245, 0x00183c40, 0x0015363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0014242f, 0x0014242f, 0x0013242f, 0x0014232e, 0x0013222d, 0x0013222d, 0x0013222f, 0x0012212e, 0x0012202c, 0x00112029, 0x00112029, 0x00112029, 0x00112029, 0x00112028, 0x00112028, 0x00122028, 0x0013202a, 0x0013202a, 0x0014212a, 0x00142129, 0x0014212a, 0x0014222c, 0x0014222c, 0x0015232e, 0x00162430, 0x00162530, 0x00172631, 0x00182732, 0x00182732, 0x00182732, 0x00182732, 0x00182732, 0x00182733, 0x00172834, 0x00172935, 0x00192b37, 0x00182c38, 0x00182c38, 0x00192c39, 0x00192c38, 0x00192c38, 0x00192c38, 0x00192c38, 0x001a2c38, 0x001a2b37, 0x001a2b36, 0x00192a34, 0x00182934, 0x00172833, 0x00152732, 0x00152631, 0x00142530, 0x0014242f, 0x0012242e, 0x0011232d, 0x0011232d, 0x0012222c, 0x0012202a, 0x00121f29, 0x00111d26, 0x000d1820, 0x000a151d, 0x000b1720, 0x0014212e, 0x001f3040, 0x00283e50, 0x002f495b, 0x003b576b, 0x00436278, 0x0044657c, 0x0047687f, 0x004b6e85, 0x0054788f, 0x00648ca1, 0x0078a1b5, 0x008ab4c4, 0x0096bfc9, 0x009ec4cb, 0x00a4c8cc, 0x00a8c9cc, 0x00adcbcc, 0x00b0cccc, 0x00b0cccc, 0x00a8c8cc, 0x008eb8c4, 0x00709dae, 0x00507c91, 0x00446d83, 0x00406176, 0x00385265, 0x00324858, 0x00293c4a, 0x00223441, 0x0022333f, 0x00263542, 0x00273642, 0x00273542, 0x00273542, 0x002a3947, 0x002d3d4a, 0x00324450, 0x0031424f, 0x002c3b47, 0x0025333f, 0x00273340, 0x00283340, 0x0026303c, 0x0026313c, 0x00242f38, 0x00202b34, 0x001c262e, 0x0018232a, 0x00161f27, 0x00192329, 0x001f282e, 0x00283138, 0x00212b32, 0x001f2930, 0x001b242b, 0x001b222a, 0x001f262e, 0x00242c34, 0x00232b32, 0x00222931, 0x00222830, 0x001c232a, 0x00181c24, 0x00171921, 0x00141820, 0x00141620, 0x0014161f, 0x00171920, 0x00181b21, 0x001b1e24, 0x001f2129, 0x0024272f, 0x00282a32, 0x002c2f37, 0x002e3039, 0x002d303a, 0x002f313c, 0x0031343e, 0x00343640, 0x00363743, 0x00383844, 0x00383844, 0x00373844, 0x00383844, 0x00383944, 0x003a3b45, 0x003c3d48, 0x003e404c, 0x0040414d, 0x0040414d, 0x003f404c, 0x003c3e4b, 0x003c3e4a, 0x003d3f4c, 0x0040424e, 0x00424450, 0x00424552, 0x00434553, 0x00424553, 0x00424554, 0x00414454, 0x00404454, 0x00414757, 0x00424757, 0x00404455, 0x003f4352, 0x003e4351, 0x003c414f, 0x00383e4b, 0x00343947, 0x00343846, 0x00303541, 0x002e323d, 0x00282c38, 0x00252834, 0x0021242f, 0x0020232c, 0x0023262f, 0x0020242c, 0x001c2028, 0x001e232b, 0x001e242d, 0x00242b34, 0x0018202a, 0x001d262f, 0x001f2831, 0x00263038, 0x001e2830, 0x0018212a, 0x0019212a, 0x001b242c, 0x001c242d, 0x001c262e, 0x001a252d, 0x001b2630, 0x001c2832, 0x00202c36, 0x001c2832, 0x00243039, 0x00202c36, 0x00202a34, 0x00202832, 0x00212834, 0x00232934, 0x00242c37, 0x00252d38, 0x00242d38, 0x00242c38, 0x0028303c, 0x0028303e, 0x00242e3c, 0x0025323f, 0x002b3845, 0x002a3a46, 0x00243541, 0x00283847, 0x002f4050, 0x00304251, 0x002f4251, 0x002c4050, 0x002e4151, 0x00314655, 0x00334858, 0x00324958, 0x00344c5c, 0x00354c5d, 0x00384f60, 0x003c5468, 0x003c596d, 0x00426779, 0x00588695, 0x007cabb7, 0x009bc3ca, 0x00aecbcc, 0x00bbcccc, 0x00c0cccc, 0x00c3cccc, 0x00c4cccc, 0x00c4cccc, 0x00c4cccc, 0x00c2cccc, 0x00c0cccc, 0x00bfcccc, 0x00bacccc, 0x00b4cbcc, 0x00a7c6cb, 0x0090b4c1, 0x007299ac, 0x00598096, 0x0043647c, 0x00324d62, 0x00253a4a, 0x001a2b38, 0x00101c27, 0x0008141c, 0x000c161f, 0x00131f2a, 0x00162430, 0x00162532, 0x00152632, 0x00172633, 0x00162734, 0x00152834, 0x00152834, 0x00162834, 0x00162834, 0x00172834, 0x00162834, 0x00172936, 0x001a2e3a, 0x00203541, 0x00283d4b, 0x002c4451, 0x002f4855, 0x00304b58, 0x00304c5a, 0x00314c5c, 0x00304c5c, 0x00304c5c, 0x00324e5c, 0x00324f5c, 0x00334f5d, 0x00334f5d, 0x00344e5d, 0x00344e5d, 0x00314a59, 0x002a4150, 0x00243a48, 0x001e3440, 0x001b303d, 0x00192f3c, 0x001a2f3c, 0x001b303c, 0x001b303c, 0x001b303c, 0x001b303c, 0x001a2f3c, 0x001a2e3a, 0x00192d39, 0x00182c38, 0x00182c37, 0x00182b36, 0x00172934, 0x00152833, 0x00142832, 0x00142731, 0x00142630, 0x0014242e, 0x0014242e, 0x0013242e, 0x0013242e, 0x0013242e, 0x0013242f, 0x00132430, 0x00142430, 0x00142631, 0x00142631, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f2229, 0x00102229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00142e34, 0x00153338, 0x00143439, 0x0016383c, 0x00183c40, 0x00183d41, 0x00183f43, 0x001a4245, 0x001b4245, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001b4448, 0x001b4649, 0x001c474b, 0x001c484c, 0x001d4b4e, 0x001e4f51, 0x001f5154, 0x00205457, 0x0021585a, 0x0022595c, 0x00277384, 0x0030a4cb, 0x0028798c, 0x00256163, 0x00256163, 0x00256163, 0x00246062, 0x00245e60, 0x002c90b0, 0x002c9cc0, 0x0020565a, 0x001f5154, 0x001d4c50, 0x001c474b, 0x001a4245, 0x00183d41, 0x0017383c, 0x00153338, 0x00142e34, 0x00112a30, 0x0011242c, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0014242f, 0x00142430, 0x0013242e, 0x0013232e, 0x0014232e, 0x0013222e, 0x0013222f, 0x0013222f, 0x0014212c, 0x0013202a, 0x0013202a, 0x00132029, 0x00132029, 0x00132029, 0x0013202a, 0x0013202a, 0x0013202a, 0x0013202a, 0x0014212b, 0x0014212b, 0x0014212b, 0x0014222c, 0x0014222d, 0x0014232e, 0x0014242f, 0x00162530, 0x00172631, 0x00182732, 0x00182833, 0x00182833, 0x00182732, 0x00172633, 0x00172633, 0x00182834, 0x00182b37, 0x00192c38, 0x00182c38, 0x00182c38, 0x00182c39, 0x001a2d39, 0x001a2d39, 0x001a2c39, 0x001a2b38, 0x001a2b38, 0x001a2b37, 0x001a2b36, 0x00192a34, 0x00182934, 0x00172833, 0x00152731, 0x00152631, 0x00142530, 0x0014242f, 0x0014242d, 0x0013242d, 0x0013242c, 0x0013232b, 0x00112028, 0x00111c25, 0x000f1820, 0x000c141b, 0x000c141c, 0x0014202a, 0x00213140, 0x00284052, 0x00334e63, 0x00406078, 0x004f718c, 0x00547994, 0x00577f98, 0x006089a2, 0x00739cb2, 0x0084adbe, 0x0097bdc8, 0x00a7c7cb, 0x00b4cbcc, 0x00b9cccc, 0x00bccccc, 0x00bdcccc, 0x00c0cccc, 0x00c0cccc, 0x00c2cccc, 0x00c1cccc, 0x00bbcccc, 0x00a4c5ca, 0x0079a6b4, 0x0059899c, 0x004b778c, 0x0046697d, 0x00385465, 0x00304654, 0x00283a46, 0x0022343d, 0x0024353f, 0x002f3f4b, 0x00283944, 0x0024343f, 0x00273842, 0x002b3b48, 0x002f404d, 0x0030424f, 0x0030414d, 0x00293842, 0x0023303c, 0x0025323e, 0x0027323e, 0x0028343d, 0x0025303b, 0x00212c34, 0x001c2730, 0x001b252f, 0x001a242d, 0x00162028, 0x00182329, 0x001b252c, 0x00202930, 0x001c242b, 0x001c242a, 0x001c2429, 0x00171f26, 0x001b242c, 0x00202930, 0x001d272e, 0x001d262d, 0x001f252d, 0x0020242c, 0x001f222a, 0x00202029, 0x001d1d27, 0x00191a23, 0x0015171c, 0x00121418, 0x00101216, 0x00141418, 0x00131318, 0x00121218, 0x00121317, 0x00141419, 0x0014141a, 0x0013131a, 0x00121219, 0x00131219, 0x0013131a, 0x0016131b, 0x0017141c, 0x0017141b, 0x0018141a, 0x00171419, 0x0017141b, 0x0018161d, 0x001a181f, 0x001d1c23, 0x001d1d25, 0x001c1c24, 0x001a1b22, 0x001a1921, 0x001a1921, 0x001d1c24, 0x0023222b, 0x0025242e, 0x00272830, 0x00292933, 0x00282934, 0x00282833, 0x00242630, 0x0023242e, 0x00242630, 0x0021232d, 0x0020202a, 0x001f1e28, 0x001d1d27, 0x001d1e27, 0x001c1d26, 0x0014161f, 0x0013141c, 0x0012121a, 0x00111118, 0x000d0d14, 0x000c0d14, 0x00101017, 0x00101016, 0x00101117, 0x0014151a, 0x0015181d, 0x00151820, 0x00191f27, 0x001d242c, 0x001b232c, 0x00202831, 0x00202a32, 0x001f2931, 0x001d282e, 0x001a2329, 0x00192228, 0x00192127, 0x00182028, 0x001f262d, 0x001c242c, 0x00182029, 0x001c242e, 0x00212c35, 0x001f2c34, 0x00202f37, 0x00223038, 0x00222e38, 0x00202a34, 0x00232c36, 0x00242c37, 0x00242c38, 0x00242c39, 0x00242d3a, 0x00232d3a, 0x0025303c, 0x0028323e, 0x0026323e, 0x00293742, 0x00293743, 0x002a3a45, 0x00273844, 0x00293a48, 0x002e3f4f, 0x002e4050, 0x00304353, 0x002d4151, 0x002d4050, 0x00304454, 0x00354a58, 0x00344b5a, 0x00354d5d, 0x00385060, 0x003c5265, 0x0040586f, 0x00486c80, 0x006192a2, 0x0087bac2, 0x00a4c9cb, 0x00b3cccc, 0x00bacccc, 0x00c2cccc, 0x00c4cccc, 0x00c7cccc, 0x00c7cccb, 0x00c7cccc, 0x00c7cccc, 0x00c7cccc, 0x00c8cccc, 0x00c8cccc, 0x00c6cccc, 0x00c4cccc, 0x00bdcccc, 0x00b3c9cc, 0x009cbdc7, 0x0080a8b9, 0x00608aa0, 0x00486c82, 0x00304c5f, 0x00243a4c, 0x00192936, 0x000f1b24, 0x000b151d, 0x000d1820, 0x00121f29, 0x0014242e, 0x00152430, 0x00162531, 0x00152632, 0x00152832, 0x00142832, 0x00162833, 0x00172834, 0x00172934, 0x00152834, 0x00182b37, 0x001e333f, 0x00243b47, 0x002a414e, 0x002c4453, 0x002e4857, 0x002e4b59, 0x002f4b5a, 0x00304c5c, 0x00304c5e, 0x00304d5c, 0x00314f5d, 0x00314f5e, 0x00314f5e, 0x0032505f, 0x0033505f, 0x00334f5e, 0x00324d5d, 0x002d4856, 0x00263e4b, 0x00203642, 0x001c313f, 0x001a303f, 0x001a303f, 0x001c303e, 0x001c303e, 0x001c303d, 0x001c303c, 0x001b303c, 0x001b303b, 0x00192e3a, 0x00182d38, 0x00192c37, 0x00182c36, 0x00172a34, 0x00172934, 0x00152833, 0x00142832, 0x00152731, 0x00162630, 0x00162530, 0x00152530, 0x00142430, 0x00142430, 0x00122430, 0x00122431, 0x00122531, 0x00142733, 0x00142733, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0013282e, 0x00112a30, 0x00132c32, 0x00143036, 0x00143338, 0x0016363b, 0x00183a3e, 0x00183d41, 0x00183f43, 0x001a4245, 0x001a4347, 0x001a4448, 0x001b4649, 0x001b4649, 0x001c4649, 0x001c474b, 0x001c474b, 0x001c4649, 0x001b4649, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c484c, 0x001c4a4d, 0x001d4c50, 0x001e4f51, 0x001f5154, 0x00205457, 0x00215659, 0x0022595c, 0x00245c5e, 0x00287484, 0x0031a4cb, 0x00297a8c, 0x00266264, 0x00256264, 0x00256163, 0x00246062, 0x00245f61, 0x002c90b0, 0x002d9cc0, 0x0020565a, 0x00205254, 0x001e4d50, 0x001c474b, 0x001a4347, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0011242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0014242f, 0x00142430, 0x0013242e, 0x0013232e, 0x0014232e, 0x0014232e, 0x00142330, 0x00142330, 0x0014222c, 0x0013202a, 0x0013202a, 0x00132028, 0x00132028, 0x00132029, 0x0013202a, 0x0013202a, 0x0013202a, 0x0014212b, 0x0014212b, 0x0014212b, 0x0014212b, 0x0014212c, 0x0014222d, 0x0014222d, 0x0014242f, 0x00152430, 0x00172631, 0x00182732, 0x00182732, 0x00182732, 0x00182732, 0x00172633, 0x00172633, 0x00182834, 0x00182b38, 0x00192c38, 0x00182c38, 0x00182c38, 0x00182d39, 0x001b2e3a, 0x001b2e3a, 0x001a2c39, 0x001a2b38, 0x001a2b38, 0x001a2b37, 0x001a2b36, 0x00192a34, 0x00182934, 0x00172833, 0x00162832, 0x00152631, 0x00142530, 0x0014242f, 0x0014242c, 0x0014242c, 0x0014222c, 0x00132029, 0x00101d25, 0x000e181f, 0x000b1318, 0x000a131a, 0x00121c27, 0x001e2d3c, 0x00293e50, 0x00334f64, 0x0043667d, 0x0059809a, 0x006b96b1, 0x0072a0b7, 0x0081acc0, 0x0093bac7, 0x00a4c4cb, 0x00b0cacc, 0x00bacccc, 0x00c2cccc, 0x00c8cccb, 0x00c8ccc8, 0x00c9ccc9, 0x00c9ccc9, 0x00c8cccb, 0x00c8cccb, 0x00c9cccc, 0x00c8cccc, 0x00c4cccc, 0x00b3cbcc, 0x0088b0bb, 0x006c9bad, 0x00538095, 0x00486c81, 0x00385466, 0x00314755, 0x00293c48, 0x0024353e, 0x00263840, 0x002f404c, 0x00263742, 0x00243440, 0x00283944, 0x002b3c49, 0x002d3f4b, 0x002e404c, 0x002c3c48, 0x0024333c, 0x0022313c, 0x0025333e, 0x0026323e, 0x0026323c, 0x00222e38, 0x001f2a32, 0x001e2831, 0x001c262f, 0x001a242c, 0x0018242b, 0x00162027, 0x00152027, 0x00192228, 0x00182127, 0x00192127, 0x001b2328, 0x00182027, 0x00182229, 0x001d282f, 0x001e2830, 0x0020282f, 0x00222830, 0x00242931, 0x00252831, 0x00262730, 0x0024242c, 0x00202128, 0x001c1e23, 0x00191c20, 0x00191b1f, 0x001a1a1e, 0x001b191e, 0x0018181c, 0x0018181c, 0x0019191d, 0x001a181d, 0x0018151a, 0x00161418, 0x00161418, 0x00151318, 0x00141116, 0x00141014, 0x00141012, 0x00130f11, 0x00110d10, 0x00100c0f, 0x00100c10, 0x00100c10, 0x00100d10, 0x000f0d10, 0x000f0c10, 0x000e0c0f, 0x000f0b0d, 0x00100c0e, 0x00100c0f, 0x00110c11, 0x00110d12, 0x00100d12, 0x00100c11, 0x000f0c11, 0x00100c11, 0x000f0c10, 0x000d0c10, 0x000d0c10, 0x000c0a0e, 0x000d090e, 0x000d080d, 0x000d0a0e, 0x00100d10, 0x00111013, 0x00101011, 0x00100f11, 0x00111013, 0x00121014, 0x00100f13, 0x00121013, 0x00171315, 0x00181416, 0x00181517, 0x001a181a, 0x001c1c1f, 0x001d1f24, 0x001d2027, 0x001c2028, 0x001d242c, 0x00212932, 0x00202a33, 0x00202a32, 0x001e282f, 0x001c242c, 0x00192228, 0x00181f25, 0x00141b22, 0x001b2129, 0x00202830, 0x00171f28, 0x00141d26, 0x001d2830, 0x00202d35, 0x001f2c34, 0x00223038, 0x0024303a, 0x00222d38, 0x00242e38, 0x00242d38, 0x00242d38, 0x00242d3a, 0x00242e3a, 0x00232e3a, 0x0025313d, 0x0025313e, 0x00283440, 0x002e3c48, 0x002d3b47, 0x00293945, 0x00273844, 0x00293a49, 0x002d3e4e, 0x002c3e4e, 0x00304453, 0x002f4453, 0x002d4251, 0x00314656, 0x00354c5c, 0x00334b5c, 0x00364e60, 0x003b5465, 0x003f586c, 0x00446178, 0x00588599, 0x0085b6c2, 0x00aacbcc, 0x00bacccc, 0x00c1cccc, 0x00c4cccc, 0x00c6cccc, 0x00c9cccb, 0x00cacccb, 0x00cbcccb, 0x00cbcccb, 0x00cbcccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cbcccb, 0x00c8cccc, 0x00c3cccc, 0x00b8cccc, 0x00a9c7cb, 0x008db5c3, 0x006d97ab, 0x004c7084, 0x00314f63, 0x0024384a, 0x00182735, 0x00101a24, 0x0009141c, 0x000c1820, 0x00111f28, 0x0013222c, 0x0015242f, 0x00152531, 0x00142731, 0x00142731, 0x00172831, 0x00182932, 0x00172934, 0x00162935, 0x00192d39, 0x00203742, 0x00273f4a, 0x002b4350, 0x002c4654, 0x002e4a58, 0x002f4b5a, 0x00304c5b, 0x00304c5c, 0x00304c5e, 0x00304d5c, 0x00304f5e, 0x0030505e, 0x0031505e, 0x0032505f, 0x00314f5e, 0x00314f5e, 0x00314e5e, 0x002f4a58, 0x0029424f, 0x00233945, 0x001e3441, 0x001b3140, 0x001c3140, 0x001c303e, 0x001c303d, 0x001c303d, 0x001c303c, 0x001c303c, 0x001b303c, 0x001b303b, 0x00192d38, 0x00192c37, 0x00182c36, 0x00182a34, 0x00172934, 0x00152833, 0x00142832, 0x00142832, 0x00162631, 0x00162631, 0x00152631, 0x00142530, 0x00142530, 0x00122430, 0x00122431, 0x00122531, 0x00142733, 0x00142733, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00143036, 0x00143439, 0x0017383c, 0x00183c40, 0x00183f43, 0x001a4245, 0x001a4448, 0x001b4649, 0x001c474b, 0x001c484c, 0x001d4a4d, 0x001c4a4d, 0x001c4a4d, 0x001c4a4d, 0x001c4a4d, 0x001d4b4e, 0x001d4b4e, 0x001d4b4e, 0x001d4c50, 0x001e4d50, 0x001e4f51, 0x001e5053, 0x00205254, 0x00205457, 0x00215659, 0x0022585b, 0x00245c5e, 0x00245d60, 0x00287586, 0x0032a5cb, 0x00297b8c, 0x00256364, 0x00256364, 0x00256264, 0x00256163, 0x00245f61, 0x002c90b0, 0x002d9cc0, 0x0020585b, 0x00205254, 0x001e4d50, 0x001c474b, 0x001a4347, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00122a30, 0x0011242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00142430, 0x0014242f, 0x0013242f, 0x0014232e, 0x0014232e, 0x0014232e, 0x00142330, 0x00142330, 0x0014222c, 0x0013202a, 0x0013202a, 0x00132028, 0x00132028, 0x0012202a, 0x0012202a, 0x0012202a, 0x0014212b, 0x0014212b, 0x0014222b, 0x0014222b, 0x0014222b, 0x0014212c, 0x0014212c, 0x0014222c, 0x0014242e, 0x00152430, 0x00162530, 0x00172631, 0x00172631, 0x00182732, 0x00172632, 0x00172632, 0x00172632, 0x00182834, 0x00182a36, 0x00192b37, 0x00182b38, 0x00182c38, 0x00192c38, 0x001a2e3a, 0x001b2e3a, 0x001a2d39, 0x001a2c38, 0x001a2b38, 0x001a2b37, 0x001a2b36, 0x00192a34, 0x00182a34, 0x00172833, 0x00162832, 0x00152731, 0x00142530, 0x0014242f, 0x0014242c, 0x0014232c, 0x0015212c, 0x00121e27, 0x000c1820, 0x0009141b, 0x00081218, 0x000d1822, 0x001c2b37, 0x00293e4e, 0x00375365, 0x004c7085, 0x006890a5, 0x0082acbe, 0x0094bcc8, 0x00a2c4cb, 0x00aec9cc, 0x00b7cccc, 0x00bccccc, 0x00c1cccc, 0x00c6cccc, 0x00cacccb, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00caccca, 0x00caccca, 0x00cbcccb, 0x00cacccc, 0x00c7cccc, 0x00bacccc, 0x009dc0c6, 0x0078a6b8, 0x005b889c, 0x00496e83, 0x00375466, 0x00334858, 0x002c3f4a, 0x00273842, 0x00253740, 0x002c3e48, 0x00233440, 0x0021323d, 0x00283944, 0x002c3c49, 0x002c3d4a, 0x002b3d49, 0x00243541, 0x0020303a, 0x0025343e, 0x00273440, 0x00232f3b, 0x00222c37, 0x001d2832, 0x001e2831, 0x00212b34, 0x001d272f, 0x0019242a, 0x001a242b, 0x00152026, 0x00182128, 0x00182027, 0x00151d23, 0x00192127, 0x001c242a, 0x001c242b, 0x001c252c, 0x00202a30, 0x00202b32, 0x00212b33, 0x00242b33, 0x00262c34, 0x00282d35, 0x002b2d36, 0x00282b34, 0x00252830, 0x0022262c, 0x0021262c, 0x0020242a, 0x00202027, 0x00201f26, 0x001c1e24, 0x001b1c21, 0x001c1c21, 0x001c1c21, 0x001b191f, 0x001a191e, 0x001a191f, 0x001b191f, 0x001b181e, 0x001a171c, 0x001a171b, 0x001a1618, 0x00181417, 0x00181316, 0x00161214, 0x00141214, 0x00141114, 0x00141114, 0x00141114, 0x00141012, 0x00140f10, 0x00151011, 0x00150f12, 0x00140f12, 0x00140f12, 0x00140f12, 0x00140e11, 0x00140e11, 0x00140e11, 0x00130e11, 0x00110e10, 0x00141013, 0x00151114, 0x00161016, 0x00140f15, 0x00140f14, 0x00151115, 0x00181518, 0x00181619, 0x00181618, 0x00161316, 0x00171416, 0x00171417, 0x00181418, 0x001c181c, 0x001c1a1e, 0x001c1c20, 0x001f1f22, 0x00222428, 0x0024282c, 0x0024252d, 0x0022242c, 0x001e222b, 0x00202630, 0x00232c34, 0x00232d35, 0x00202a31, 0x001c242c, 0x00192228, 0x00171e24, 0x00141a21, 0x00151c23, 0x001d242c, 0x001b242c, 0x00141d26, 0x0017212a, 0x001b2830, 0x001f2c34, 0x00223038, 0x0026333c, 0x00242f39, 0x00232d38, 0x00232d38, 0x00242e38, 0x00242e3b, 0x0026313d, 0x0027343f, 0x002a3843, 0x00283441, 0x00273441, 0x002c3a47, 0x002e3d4a, 0x002b3c48, 0x002a3b48, 0x00283949, 0x002c3c4c, 0x002a3d4c, 0x002e4251, 0x00304554, 0x002d4152, 0x00314657, 0x00344c5c, 0x00304858, 0x00324a5c, 0x003b5365, 0x0040596f, 0x004a6c82, 0x0078a6b4, 0x00a1c8cb, 0x00b8cccc, 0x00c3cccc, 0x00c8cccc, 0x00c8cccc, 0x00cacccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccb, 0x00cccbcb, 0x00cbcccb, 0x00cacccc, 0x00c9cccc, 0x00c5cccc, 0x00bfcccc, 0x00b4cacc, 0x00a0bfc8, 0x0079a0b1, 0x00517488, 0x00344e63, 0x00223546, 0x00162430, 0x000c1820, 0x0008141c, 0x000d1921, 0x00121e27, 0x0015222d, 0x00152431, 0x00142731, 0x00142731, 0x00172831, 0x00172832, 0x00172834, 0x00162935, 0x001b303c, 0x00223944, 0x0028414c, 0x002c4552, 0x002d4856, 0x002e4a58, 0x002f4c5a, 0x00304c5b, 0x00304c5c, 0x00304c5e, 0x00304d5d, 0x00304f5e, 0x0030505e, 0x0030505e, 0x0032505f, 0x0032505f, 0x00314f5e, 0x00324e5d, 0x00304b59, 0x002b4451, 0x00243c48, 0x001f3542, 0x001c313f, 0x001c313f, 0x001c303d, 0x001c303c, 0x001b303c, 0x001b303c, 0x001b303c, 0x001b303c, 0x001b303c, 0x00192d39, 0x00192c38, 0x00192c38, 0x00182b36, 0x00182936, 0x00162934, 0x00152833, 0x00152833, 0x00152832, 0x00152731, 0x00152631, 0x00142530, 0x00142531, 0x00132531, 0x00122531, 0x00132632, 0x00142733, 0x00142734, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0012242c, 0x0010282e, 0x00132c32, 0x00143036, 0x00143338, 0x0016363b, 0x00183c40, 0x00183f43, 0x001a4245, 0x001b4448, 0x001c474b, 0x001c4a4d, 0x001d4b4e, 0x001d4c50, 0x001d4d50, 0x001e4d50, 0x001e4f51, 0x001e4f51, 0x001e4f51, 0x001e4f51, 0x001e5053, 0x001e5053, 0x001f5053, 0x001f5154, 0x00205254, 0x00205356, 0x00205558, 0x0021585a, 0x0022595c, 0x00245c5e, 0x00245d60, 0x00245f61, 0x00297686, 0x0032a5cb, 0x00297b8c, 0x00256364, 0x00256364, 0x00256264, 0x00256163, 0x00245f61, 0x002c90b0, 0x002d9cc0, 0x0020585b, 0x00205254, 0x001e4d50, 0x001c474b, 0x001a4347, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00122a30, 0x0011242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00142430, 0x0014242f, 0x0014242f, 0x0014242e, 0x0014232e, 0x0014232e, 0x00142330, 0x00142330, 0x0014222e, 0x0013202c, 0x0013202c, 0x0013202a, 0x0013202a, 0x0012202b, 0x0012212b, 0x0012212b, 0x0014212b, 0x0014212b, 0x0014222b, 0x0015232b, 0x0014222b, 0x0014212b, 0x0014212b, 0x0013212c, 0x0014232e, 0x0014242f, 0x00162530, 0x00162530, 0x00162530, 0x00162530, 0x00162530, 0x00162530, 0x00162530, 0x00172733, 0x00172834, 0x00182935, 0x00182a37, 0x00182c38, 0x00182c38, 0x00182c38, 0x00192c39, 0x001a2d39, 0x00192c38, 0x001a2b38, 0x001a2b37, 0x001a2b36, 0x00192a34, 0x00182a34, 0x00172833, 0x00162832, 0x00162832, 0x00152530, 0x00152430, 0x0014232c, 0x0015222c, 0x00131e28, 0x000f1922, 0x000b141d, 0x0008121a, 0x000b151e, 0x00182532, 0x00283c4a, 0x00365464, 0x0052788a, 0x0075a0b4, 0x0094bcc8, 0x00aac8cc, 0x00b7cccc, 0x00becccc, 0x00c4cccc, 0x00c7cccc, 0x00c8cccc, 0x00c8cccc, 0x00c9cccc, 0x00cbccca, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00ccccc9, 0x00cbcccb, 0x00cbcccb, 0x00cbcccb, 0x00cbcccb, 0x00c9cccc, 0x00becccc, 0x00acc9cb, 0x0085b0be, 0x00628ea1, 0x00496f84, 0x00345164, 0x00304655, 0x002c3f4a, 0x00283942, 0x00243740, 0x00293b46, 0x00243440, 0x001f303b, 0x00283944, 0x002b3c48, 0x00283b47, 0x00263945, 0x00233440, 0x0024333c, 0x0027343f, 0x0024313d, 0x001f2935, 0x001f2833, 0x001c242e, 0x001e252f, 0x00222933, 0x00202831, 0x00192329, 0x00172128, 0x00172027, 0x00171d25, 0x00181e25, 0x00181d24, 0x001c2329, 0x00222830, 0x00212830, 0x001f2830, 0x00202b32, 0x00222c34, 0x00222c34, 0x00242c34, 0x00272d35, 0x002a3038, 0x002e323c, 0x002e323b, 0x002b2f38, 0x002a2f36, 0x002b3037, 0x00292d34, 0x00272931, 0x00252730, 0x0022242d, 0x001f222a, 0x001f2128, 0x00202128, 0x00202027, 0x001e1e25, 0x001f1f25, 0x00202026, 0x00211f26, 0x00201e25, 0x00211d24, 0x00201c21, 0x00201b20, 0x001f191e, 0x001c171b, 0x001b1619, 0x00191518, 0x001a1619, 0x001a1519, 0x00191418, 0x001a1317, 0x001c1418, 0x001b1317, 0x001b1318, 0x001a1217, 0x001a1217, 0x001b1317, 0x001a1317, 0x00181117, 0x00181017, 0x00181118, 0x00181318, 0x001c161c, 0x001f1920, 0x001f1920, 0x001e1a20, 0x001e1a1f, 0x001c1a1e, 0x001c191e, 0x001b181c, 0x001b181b, 0x001c181c, 0x001d1a1f, 0x001d1a21, 0x00201d25, 0x00202129, 0x0022242a, 0x0024282f, 0x00272d34, 0x00272d34, 0x00282b33, 0x00292b34, 0x00262932, 0x00222830, 0x00242b34, 0x00232b34, 0x00212c33, 0x001d262d, 0x00192228, 0x00182026, 0x00141a21, 0x00141a22, 0x001b232a, 0x001d252e, 0x00172028, 0x00151f28, 0x0018232b, 0x001c2730, 0x001d2931, 0x00242f39, 0x0026303b, 0x00242d38, 0x00262f3a, 0x0028303c, 0x0028303d, 0x00293441, 0x00283643, 0x00293844, 0x002a3845, 0x00293844, 0x002b3a47, 0x002e3d4a, 0x002c3d4a, 0x002b3c49, 0x00283948, 0x002c3d4e, 0x002c4050, 0x00304554, 0x00344858, 0x00304454, 0x00304554, 0x00344b5a, 0x00304859, 0x00324a5c, 0x003a5467, 0x00425c72, 0x0054798e, 0x0090bac4, 0x00afcccc, 0x00bfcccc, 0x00c6cccc, 0x00cacccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00cbcccc, 0x00cacccc, 0x00c8cccc, 0x00c4cccc, 0x00bacbcc, 0x00a4c4c9, 0x0080a8b7, 0x00547a8f, 0x00304e62, 0x001c3140, 0x0011202d, 0x000a1421, 0x0008121c, 0x000f1922, 0x0014202b, 0x00162430, 0x00152530, 0x00152631, 0x00162832, 0x00162832, 0x00162833, 0x00152935, 0x001c313c, 0x00233b46, 0x0028424d, 0x002c4653, 0x002c4856, 0x002e4a58, 0x002f4c5a, 0x00304c5b, 0x00304c5c, 0x00304c5e, 0x00304c5d, 0x00304e5d, 0x0030505e, 0x0030505e, 0x00324f5f, 0x00334f5f, 0x00324e5e, 0x00314c5c, 0x00304a59, 0x002b4452, 0x00243c49, 0x00203643, 0x001c313d, 0x001c303c, 0x001c303a, 0x001b3039, 0x001a2f39, 0x001a2f3a, 0x001a2f3c, 0x001b303c, 0x001a2f3c, 0x001a2d3a, 0x00192c38, 0x00192c38, 0x00182b37, 0x00182a37, 0x00172935, 0x00172934, 0x00172934, 0x00152833, 0x00142832, 0x00142732, 0x00152631, 0x00152631, 0x00132631, 0x00132632, 0x00132632, 0x00142834, 0x00142834, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153338, 0x0015363b, 0x00183a3e, 0x00183f43, 0x001a4245, 0x001b4649, 0x001c484c, 0x001d4b4e, 0x001d4d50, 0x001e5053, 0x001f5154, 0x00205254, 0x001f5254, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205457, 0x00205457, 0x00205558, 0x00215659, 0x0021585a, 0x0022585b, 0x00235a5c, 0x00245c5f, 0x00245d60, 0x00245f61, 0x00256163, 0x00297787, 0x0032a5cb, 0x002a7c8d, 0x00276466, 0x00256364, 0x00256264, 0x00256163, 0x00245f61, 0x002c90b0, 0x002d9cc0, 0x0020565a, 0x00205254, 0x001e4d50, 0x001c474b, 0x001a4347, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0011242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00142430, 0x0014242f, 0x0014242f, 0x0014242e, 0x0014232e, 0x0014232e, 0x00142330, 0x00142330, 0x0014222e, 0x0013202c, 0x0013202c, 0x0012202a, 0x00122029, 0x0012202b, 0x0013212c, 0x0013212c, 0x0014202c, 0x0014212c, 0x0015222b, 0x0015232b, 0x0014222b, 0x0014212b, 0x0014212b, 0x0014222c, 0x0014222d, 0x0014222d, 0x0014232e, 0x0015242e, 0x0014242e, 0x0014242f, 0x0014242f, 0x0014242f, 0x0014242f, 0x00152531, 0x00162834, 0x00182834, 0x00182834, 0x00182935, 0x00182936, 0x00182a36, 0x00182b37, 0x00182c38, 0x00182b37, 0x001a2b38, 0x001a2b37, 0x001a2b36, 0x00192a34, 0x00182a34, 0x00182934, 0x00172832, 0x00162731, 0x00162530, 0x0015242e, 0x0015212c, 0x00141f28, 0x00101923, 0x000c141c, 0x00091219, 0x000b141c, 0x00131f2b, 0x00203444, 0x00345164, 0x00567c8e, 0x007ea7b6, 0x00a0c3ca, 0x00b1cbcc, 0x00becccc, 0x00c4cccc, 0x00c8cccc, 0x00c9cccc, 0x00cbcbcc, 0x00cbcbcb, 0x00cacccb, 0x00cbcccc, 0x00cbccca, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00cccbc9, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cacbcc, 0x00c0cccc, 0x00b3cbcc, 0x0090b8c4, 0x00638fa3, 0x00456b80, 0x00314e5f, 0x002e4452, 0x002c3e4b, 0x00283a44, 0x00273942, 0x00293a45, 0x00233441, 0x001f313c, 0x00273844, 0x00283945, 0x00283a46, 0x00283b47, 0x00283744, 0x0024343f, 0x0026343f, 0x00222e3a, 0x001e2834, 0x001d2530, 0x001a212b, 0x001c222c, 0x00202730, 0x00202830, 0x00182128, 0x00172026, 0x00192027, 0x00131920, 0x00161b21, 0x00181d24, 0x0020262d, 0x00252c34, 0x00232c34, 0x00242c35, 0x00242d36, 0x00242e36, 0x00242d36, 0x00262e38, 0x00293039, 0x002b313b, 0x002e343d, 0x00303440, 0x00303440, 0x00303640, 0x00323841, 0x00313740, 0x002e333c, 0x002b303a, 0x00282c37, 0x00252932, 0x00262931, 0x00272831, 0x0026272e, 0x0024242c, 0x0024242c, 0x0025252c, 0x0026242d, 0x0027242d, 0x0027242c, 0x00262329, 0x00272228, 0x00262027, 0x00231d24, 0x00211c22, 0x00201b20, 0x001f1b20, 0x001e1a1f, 0x001d191d, 0x001e181c, 0x001d171c, 0x001d181c, 0x001e181d, 0x001e181d, 0x001d171d, 0x001e181f, 0x00201920, 0x00201921, 0x001e1820, 0x001d1820, 0x001c1920, 0x001f1c24, 0x00242028, 0x00242028, 0x00222028, 0x00201f25, 0x001e1d24, 0x001d1c23, 0x001c1c23, 0x001e1d24, 0x001f1f26, 0x00212028, 0x0022222b, 0x0024242f, 0x00272a34, 0x002a2f37, 0x002c3239, 0x002b333b, 0x00293039, 0x002a3038, 0x002c3038, 0x002b3038, 0x00262b34, 0x00252c35, 0x00242c34, 0x00232c34, 0x00222c33, 0x001e272c, 0x001e262c, 0x00161c24, 0x00151c24, 0x001a2128, 0x001a222a, 0x00151d25, 0x00161e27, 0x0018222b, 0x001c262f, 0x001c2730, 0x001d2833, 0x00242e38, 0x00232c36, 0x00232c37, 0x0028303c, 0x0028303f, 0x002a3442, 0x002a3744, 0x00283844, 0x002a3946, 0x002e3d4a, 0x002d3d4a, 0x002e3d4a, 0x002c3d4a, 0x002d3e4c, 0x00293a4b, 0x002e3f50, 0x00304454, 0x00344858, 0x00344b5b, 0x00324859, 0x00304758, 0x00324a5a, 0x00344c5d, 0x00365063, 0x003e586c, 0x00446278, 0x0062899c, 0x009fc4c8, 0x00b7cccc, 0x00c4cccb, 0x00c8cccb, 0x00cacccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cacccb, 0x00c8cccc, 0x00c4cccc, 0x00b9cccc, 0x00a8c7cb, 0x0084acba, 0x00567a8d, 0x002f4a5c, 0x001a2e3e, 0x00101d2c, 0x0008131f, 0x000c141e, 0x00101c27, 0x0014202c, 0x0014232e, 0x00142530, 0x00152631, 0x00162732, 0x00152832, 0x00152935, 0x001c313c, 0x00243c47, 0x0029424d, 0x002c4753, 0x002c4856, 0x002e4a58, 0x00304c5a, 0x00304c5b, 0x00304c5c, 0x00304c5e, 0x00304d5d, 0x00304e5c, 0x00304e5c, 0x00314e5c, 0x00324d5f, 0x00334d5e, 0x00324d5c, 0x00304b59, 0x002f4958, 0x002c4452, 0x00253c4a, 0x00203543, 0x001c303d, 0x001a2e3b, 0x00192e39, 0x00182e38, 0x00192e39, 0x001a2f3a, 0x001a2e3b, 0x001a2e3c, 0x00192e3c, 0x00192d39, 0x00192c38, 0x00182c38, 0x00182b37, 0x00182a37, 0x00172935, 0x00172934, 0x00162833, 0x00152834, 0x00142834, 0x00152834, 0x00152734, 0x00152733, 0x00142734, 0x00142734, 0x00142734, 0x00142835, 0x00152835, 0x000d1d28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x00153439, 0x0017383c, 0x00183d41, 0x001a4245, 0x001c4649, 0x001c4a4d, 0x001d4c50, 0x001f5053, 0x00205254, 0x00205356, 0x00205558, 0x00215659, 0x0021585a, 0x0021585a, 0x0021585a, 0x0021585a, 0x0022585a, 0x0022585a, 0x0022585b, 0x0022585b, 0x0021585b, 0x0022595c, 0x00235a5c, 0x00245c5e, 0x00245d60, 0x00245e60, 0x00245f61, 0x00256163, 0x00256264, 0x00297888, 0x0032a5cb, 0x002a7c8d, 0x00276466, 0x00256364, 0x00256264, 0x00256062, 0x00245f61, 0x002c90b0, 0x002d9cc0, 0x0020565a, 0x001f5154, 0x001d4c50, 0x001c474b, 0x001a4245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0011242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00142532, 0x00142431, 0x00142431, 0x00142430, 0x00142430, 0x0013232f, 0x00142330, 0x00142330, 0x0014222f, 0x0013202d, 0x00111f2b, 0x00101e29, 0x00111f28, 0x0011202a, 0x0012212b, 0x0012212b, 0x0014212b, 0x0014212b, 0x0014212b, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014212b, 0x0013202a, 0x0014212b, 0x0014222c, 0x0014222c, 0x0014222c, 0x0015232e, 0x0014232e, 0x0014232e, 0x0014242e, 0x00152430, 0x00182732, 0x00182833, 0x00182732, 0x00182732, 0x00182833, 0x00172934, 0x00172a35, 0x00182a35, 0x00182a36, 0x00192a37, 0x00192a37, 0x00192a37, 0x00192a34, 0x00192a34, 0x00182a34, 0x00182932, 0x00172831, 0x0017262f, 0x0017232d, 0x0014202a, 0x00111c24, 0x000d141d, 0x000b1218, 0x000b1218, 0x000f1924, 0x001c2c3b, 0x002d495f, 0x00557c93, 0x0084aebd, 0x00a8c6cb, 0x00becccc, 0x00c5cccc, 0x00cacccc, 0x00cbcccc, 0x00cccbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cacccb, 0x00c4ccca, 0x00b6cccc, 0x0096bcc5, 0x00628da2, 0x00406478, 0x00304c5d, 0x002e4453, 0x002b404c, 0x00273b47, 0x00273944, 0x00283a46, 0x00223541, 0x00203340, 0x00263945, 0x00263945, 0x00283c48, 0x002a3d49, 0x00293a47, 0x00253440, 0x0024313e, 0x00202b38, 0x001f2934, 0x001c242d, 0x00182128, 0x00182028, 0x001d252c, 0x0020282f, 0x00182027, 0x00171f25, 0x00192025, 0x0012171d, 0x0013181d, 0x00181f24, 0x00242b32, 0x00293239, 0x00242c35, 0x00272e38, 0x00272f38, 0x00262e37, 0x00262e37, 0x00293039, 0x002b323c, 0x002c323c, 0x002c333c, 0x002e343d, 0x00303640, 0x00303843, 0x00313844, 0x00303843, 0x002f3641, 0x002b323d, 0x002b323d, 0x002d343d, 0x002c323b, 0x002c3038, 0x002a2d35, 0x00292a32, 0x00282830, 0x0028282f, 0x00282832, 0x00292833, 0x00292832, 0x00282630, 0x0028262f, 0x0028242d, 0x0026222c, 0x0024212a, 0x00242029, 0x00242028, 0x00231f27, 0x00201c24, 0x001f1c23, 0x001f1c23, 0x00201c24, 0x00201c24, 0x00201c24, 0x001f1c24, 0x00201c24, 0x00232028, 0x0024222a, 0x0024222a, 0x00212128, 0x00202028, 0x00202128, 0x0024242c, 0x0024242d, 0x0020222b, 0x00202229, 0x0020232a, 0x0022242c, 0x00242730, 0x00252834, 0x00252934, 0x00262c36, 0x00272c37, 0x00282c37, 0x00292e38, 0x002f343e, 0x002f363f, 0x002f3540, 0x002e343e, 0x002b323c, 0x00293138, 0x00283038, 0x00282e36, 0x00272d34, 0x00262e35, 0x00242d34, 0x00242d34, 0x00202930, 0x00212930, 0x001a2028, 0x00171d24, 0x00192025, 0x00181f25, 0x00131b21, 0x00141c24, 0x00182129, 0x001b252e, 0x001c262f, 0x001b252f, 0x001d2832, 0x001e2832, 0x00202b35, 0x0026303c, 0x0027303e, 0x002a3442, 0x002c3844, 0x002c3b47, 0x002c3c48, 0x002e3d4b, 0x002d3c49, 0x002c3a48, 0x002a3b48, 0x002c3e4b, 0x00293c4c, 0x002f4154, 0x00304657, 0x00344b5c, 0x00334c5d, 0x00324c5c, 0x00314b5c, 0x00344c5f, 0x00375064, 0x003c576c, 0x00405c74, 0x00446980, 0x006f9dac, 0x00acc9cb, 0x00c2cccc, 0x00c9cccb, 0x00cbccca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cacccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cacccb, 0x00cacccb, 0x00c5cccc, 0x00bfcccc, 0x00abc7cb, 0x0086acb8, 0x0055788a, 0x002b4558, 0x0017293b, 0x000d1925, 0x000a141c, 0x000f1822, 0x00121e28, 0x0014212c, 0x0014242d, 0x0014242f, 0x00142630, 0x00142630, 0x00152832, 0x001b3039, 0x00243a45, 0x002a414d, 0x002d4652, 0x002f4855, 0x002f4857, 0x00304a59, 0x00314b5b, 0x00314c5c, 0x00314c5c, 0x00314c5b, 0x00314c5b, 0x00324e5c, 0x00314d5c, 0x00304c5c, 0x00304c5c, 0x00304c5a, 0x002f4b58, 0x002e4856, 0x002a414f, 0x00243947, 0x001e3441, 0x001b303e, 0x00182d3a, 0x00182c39, 0x00182c38, 0x00182d39, 0x00182d39, 0x00182d39, 0x00182d38, 0x00182c38, 0x00172c38, 0x00172c35, 0x00172b35, 0x00182a37, 0x00182a37, 0x00172935, 0x00172934, 0x00152834, 0x00152836, 0x00152836, 0x00152836, 0x00152836, 0x00152836, 0x00142835, 0x00142835, 0x00142836, 0x00152937, 0x00162937, 0x000d1d28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00112a30, 0x00142e34, 0x00153338, 0x0016363b, 0x00183c40, 0x00194044, 0x001b4448, 0x001c484c, 0x001d4d50, 0x001f5256, 0x0020585f, 0x00215c61, 0x00225d63, 0x00235f64, 0x00246067, 0x00246168, 0x00246068, 0x00246268, 0x00246268, 0x00246269, 0x00246269, 0x0024636a, 0x0024636a, 0x0024646b, 0x0024646c, 0x0024656c, 0x0024666d, 0x0025676e, 0x0026686f, 0x00266870, 0x00266970, 0x00276c73, 0x002c89a1, 0x0032a5cb, 0x002a7b8c, 0x00276466, 0x00256364, 0x00256264, 0x00246062, 0x00245e60, 0x002c90b0, 0x002c9cc0, 0x00205559, 0x001f5154, 0x001d4c50, 0x001c474b, 0x001a4245, 0x00183d41, 0x0016363b, 0x00143036, 0x00142e34, 0x00112a30, 0x0012242c, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142430, 0x00142330, 0x00142330, 0x0014222f, 0x0013202d, 0x00111f2b, 0x00101e28, 0x00101e28, 0x00112029, 0x0012212b, 0x0012212b, 0x0014212b, 0x0014212b, 0x0014212b, 0x0014212c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014212b, 0x0013202a, 0x0013202a, 0x0014212b, 0x0014222c, 0x0014222c, 0x0014222d, 0x0014222d, 0x0014222d, 0x0013222e, 0x0014242e, 0x00152530, 0x00182732, 0x00182732, 0x00182732, 0x00182832, 0x00162932, 0x00172934, 0x00172934, 0x00182a35, 0x00192a37, 0x00192a37, 0x00192a37, 0x00192a34, 0x00192a34, 0x00192a34, 0x00182a34, 0x00182932, 0x0016252f, 0x0015212c, 0x00131c26, 0x000c141c, 0x000b1018, 0x000c1218, 0x000f151c, 0x0016232f, 0x00284053, 0x004b7084, 0x0083acbb, 0x00a9c8cc, 0x00b9cccc, 0x00c8cccc, 0x00cbcccc, 0x00cccbcc, 0x00cccbcc, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00c9cccb, 0x00c5ccca, 0x00b5cbcc, 0x0095bbc6, 0x00618ba0, 0x003b5f74, 0x00344f5f, 0x00304754, 0x002a3f4c, 0x00273c47, 0x00263a46, 0x00293c4a, 0x00243744, 0x00243844, 0x00283c48, 0x00283a46, 0x00293c48, 0x002c404b, 0x002a3c48, 0x00263643, 0x0024313f, 0x00202c39, 0x00202a35, 0x0019232b, 0x00171f25, 0x00161d24, 0x001e242b, 0x001e242c, 0x00161e25, 0x00151e24, 0x00161c24, 0x0010151c, 0x00141a1f, 0x001b2228, 0x00293138, 0x002c343c, 0x00252d36, 0x00283039, 0x00283039, 0x00272f38, 0x0028303a, 0x002c343c, 0x002e343d, 0x002d343c, 0x002c323c, 0x002d343c, 0x00303741, 0x00303843, 0x00303843, 0x002f3843, 0x002e3842, 0x002c3741, 0x00333c48, 0x00353d48, 0x00323943, 0x0030343e, 0x0030323c, 0x002f3038, 0x002c2e35, 0x002b2c34, 0x002b2c37, 0x002c2c38, 0x002b2c37, 0x00292a34, 0x002b2a34, 0x002a2933, 0x002a2832, 0x00292731, 0x00292730, 0x0028262f, 0x0028252e, 0x0025232c, 0x0025242c, 0x0025242c, 0x0027242e, 0x0028252e, 0x0027242e, 0x0025242c, 0x0024232c, 0x0026262e, 0x00282831, 0x00282832, 0x00262730, 0x0024262d, 0x0022242c, 0x0023262e, 0x00242730, 0x00242730, 0x00242830, 0x00272c33, 0x002b3038, 0x0030343f, 0x00303743, 0x00313844, 0x00313844, 0x00313843, 0x00303540, 0x002c333d, 0x002f343f, 0x00303841, 0x00303841, 0x00313841, 0x002c343d, 0x002a333b, 0x002a323b, 0x002b3139, 0x00282e36, 0x00272d35, 0x00262e35, 0x00242c33, 0x00222a31, 0x0020282f, 0x001c242b, 0x00171e24, 0x001c2328, 0x001b2127, 0x0011181e, 0x00121b21, 0x00151f26, 0x00182229, 0x001a242c, 0x001c2530, 0x001a242e, 0x0019242e, 0x001e2833, 0x00242e3b, 0x00293340, 0x002a3441, 0x002a3744, 0x00303f4b, 0x002f3e4a, 0x002c3b48, 0x002a3946, 0x002a3946, 0x00293b47, 0x00283b48, 0x00283a4b, 0x00304354, 0x0034495b, 0x00385060, 0x00344e5f, 0x00334c5e, 0x00344d60, 0x00365062, 0x003a5468, 0x003f5a6f, 0x00405c74, 0x00487086, 0x007babb8, 0x00b2cccc, 0x00c5cccc, 0x00cbccca, 0x00cccbc9, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cacccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccb, 0x00c9ccca, 0x00c4cccb, 0x00bbcccc, 0x00aac8cb, 0x0083a8b5, 0x004c6d7e, 0x00243c4e, 0x00142230, 0x000c151e, 0x000a141c, 0x000d1822, 0x00101d27, 0x0012202a, 0x0012232c, 0x0013242d, 0x0014252e, 0x00132630, 0x00182c36, 0x00233843, 0x002a404c, 0x002e4651, 0x002f4855, 0x002f4857, 0x00304a59, 0x00314b5b, 0x00314c5c, 0x00314c5a, 0x00304c5a, 0x00304c5a, 0x00304c5a, 0x00304c5a, 0x00304c5b, 0x00304b5a, 0x00304b59, 0x00304a58, 0x002c4654, 0x0028404d, 0x00243846, 0x001d3240, 0x001a2e3c, 0x00182c39, 0x00182c38, 0x00182c38, 0x00182d39, 0x00182d39, 0x00182c39, 0x00172c38, 0x00172c38, 0x00162b36, 0x00162b34, 0x00172b34, 0x00182a37, 0x00182a37, 0x00172935, 0x00172934, 0x00152834, 0x00152836, 0x00152836, 0x00152836, 0x00152836, 0x00152836, 0x00142937, 0x00152a37, 0x00162b38, 0x00162b38, 0x00162b38, 0x000e1e28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00132c32, 0x00142e34, 0x00153439, 0x00183a3e, 0x00183f43, 0x001a4347, 0x001c484c, 0x001d4c50, 0x00205458, 0x002786a2, 0x002ea0c7, 0x002fa2c8, 0x0030a2c8, 0x0030a2c8, 0x0030a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0031a3c8, 0x0032a4c8, 0x0032a4c8, 0x0032a4c8, 0x0032a4c8, 0x0032a4c8, 0x0032a6cb, 0x00309fc1, 0x00286d76, 0x00266466, 0x00256364, 0x00256163, 0x00245f61, 0x00245e61, 0x002c92b2, 0x002c9cc0, 0x00205559, 0x001e5053, 0x001d4b4e, 0x001c4649, 0x00194044, 0x00183c40, 0x0015363b, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00142532, 0x00142430, 0x00142330, 0x00142230, 0x0012212e, 0x0011202c, 0x00101e29, 0x00101e28, 0x00101f2a, 0x0010202b, 0x0011202b, 0x0013202b, 0x0013202b, 0x0014202c, 0x0014212c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0013202a, 0x00122029, 0x00122029, 0x00122029, 0x0013202a, 0x0014212b, 0x0014212c, 0x0014212c, 0x0014212c, 0x0014222d, 0x0014222d, 0x0014232e, 0x00172430, 0x00182631, 0x00182631, 0x00182731, 0x00172831, 0x00172932, 0x00172933, 0x00182a34, 0x00182a36, 0x00182934, 0x00182934, 0x00182934, 0x00182934, 0x00182934, 0x00182934, 0x00182832, 0x0016242e, 0x00141f28, 0x000e1720, 0x000a111a, 0x000a1018, 0x000c141a, 0x00141c24, 0x0020303e, 0x003a5a6f, 0x00739cac, 0x00a4c5ca, 0x00bccccc, 0x00c4cccc, 0x00cacccc, 0x00cccbcb, 0x00cbcccc, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00c9cccc, 0x00c3cccc, 0x00b0c9cb, 0x008cb0be, 0x00527b91, 0x00395b70, 0x00365061, 0x00304855, 0x002c414e, 0x00283c48, 0x00273b47, 0x00283b48, 0x00253844, 0x002b3e4a, 0x002c3f4b, 0x00283b47, 0x00283b46, 0x002a3e4a, 0x00273945, 0x00243542, 0x0024313f, 0x00232f3c, 0x00212c37, 0x001a242c, 0x00151d24, 0x00151c23, 0x0020272d, 0x001a2128, 0x00141b22, 0x00151c24, 0x00151c23, 0x0012181f, 0x00151c22, 0x001f262d, 0x00283239, 0x00283138, 0x00242d35, 0x00262e38, 0x00283039, 0x002c343c, 0x002c343e, 0x002e353f, 0x002f353e, 0x002d343c, 0x002c323c, 0x002d343d, 0x00303741, 0x00303944, 0x00303a44, 0x00303a45, 0x00303b45, 0x00333c48, 0x0037424c, 0x00363e49, 0x00313844, 0x00303541, 0x00313540, 0x0032343f, 0x0031343d, 0x0030333c, 0x0030333f, 0x00303340, 0x0030323e, 0x002d303c, 0x0030313d, 0x0030303d, 0x002f2f3c, 0x002e2e39, 0x0030303b, 0x0030303b, 0x002f2f3a, 0x002d2d3a, 0x002e2f3b, 0x002e2f3b, 0x002e2f3b, 0x002f2f3b, 0x002f2f3b, 0x002d2e39, 0x002c2c36, 0x002b2c36, 0x002c2d38, 0x002c2d38, 0x002c2c37, 0x00292c35, 0x00282c34, 0x002a2c36, 0x002c2f39, 0x002b303a, 0x002b313a, 0x002f353d, 0x00323842, 0x00363c48, 0x00373f4c, 0x00363f4c, 0x00353e4b, 0x00343c48, 0x00323945, 0x00303641, 0x002d333f, 0x002e3440, 0x002f3640, 0x00303842, 0x002f3841, 0x002c363f, 0x002c353e, 0x002c343c, 0x00283039, 0x00272f38, 0x00242d36, 0x00202931, 0x00222c34, 0x00212932, 0x001d242c, 0x001a2027, 0x00182025, 0x00192026, 0x00141b20, 0x00131a22, 0x00161e25, 0x00182028, 0x0019222a, 0x001d2630, 0x00202a34, 0x00202934, 0x001f2934, 0x00232e3a, 0x00283440, 0x002a3642, 0x00283742, 0x002b3b46, 0x002a3944, 0x002b3a48, 0x002c3c48, 0x002b3a47, 0x002b3c48, 0x00283b48, 0x00293c4c, 0x002f4153, 0x00334859, 0x00374f5f, 0x00354e60, 0x00354f60, 0x00364f61, 0x003a5467, 0x003d586b, 0x003f596e, 0x003f5c74, 0x004c748a, 0x0081b0bd, 0x00b2cccc, 0x00c4cccc, 0x00cbccca, 0x00cbcbca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccca, 0x00cacccb, 0x00c4cccc, 0x00bdcccc, 0x00aac5c8, 0x007b9caa, 0x003e5d70, 0x001a303e, 0x00101b26, 0x000b131c, 0x000a141e, 0x000d1823, 0x00121f28, 0x0012212a, 0x0013232c, 0x0013242d, 0x0012252d, 0x00152a33, 0x001e343c, 0x00283e48, 0x002c4450, 0x002d4855, 0x002e4957, 0x00304a59, 0x00304a5a, 0x00314b5a, 0x00304c59, 0x00304c59, 0x00304c59, 0x00304c59, 0x00304c59, 0x00304c5a, 0x002f4a5a, 0x00304959, 0x00304858, 0x002b4453, 0x00263c4a, 0x00213642, 0x001c313c, 0x00192e39, 0x00182c38, 0x00182c37, 0x00182c37, 0x00182c38, 0x00182c38, 0x00182c38, 0x00182c37, 0x00182c37, 0x00182c36, 0x00182b35, 0x00182b35, 0x00182a35, 0x00182a35, 0x00172934, 0x00172934, 0x00152834, 0x00152836, 0x00152836, 0x00152836, 0x00152836, 0x00162937, 0x00162a38, 0x00162b38, 0x00172c39, 0x00172c39, 0x00172c3a, 0x000e1e28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0015363b, 0x00183c40, 0x00194044, 0x001c4649, 0x001d4b4e, 0x001f5053, 0x00215f69, 0x002ea3c9, 0x002d9cc0, 0x002c95b5, 0x002d95b5, 0x002e95b5, 0x002e95b5, 0x002e96b4, 0x002e96b4, 0x002e95b4, 0x002e96b4, 0x002f96b4, 0x002f96b4, 0x002e95b4, 0x002e95b4, 0x002f95b4, 0x002e94b3, 0x002e94b3, 0x002e95b3, 0x002e95b3, 0x002e94b2, 0x002e94b2, 0x002e94b2, 0x002e94b2, 0x002e8fa9, 0x0028717d, 0x00276466, 0x00256364, 0x00256264, 0x00256163, 0x00245f61, 0x00246064, 0x002c9abd, 0x002c99bd, 0x00205458, 0x001e4f51, 0x001d4a4d, 0x001a4448, 0x00194044, 0x00173a3e, 0x00143439, 0x00143036, 0x00122c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152432, 0x00152431, 0x00142431, 0x0013222f, 0x0012202d, 0x00101e2a, 0x00101e29, 0x00101e29, 0x000f1f29, 0x0010202b, 0x0013202c, 0x0013202c, 0x0014202c, 0x0014212c, 0x0014222c, 0x0014222c, 0x0014212b, 0x0013202a, 0x00111f29, 0x00111f29, 0x00111f29, 0x00122029, 0x0013202a, 0x0014212b, 0x0014212b, 0x0014212c, 0x0014212c, 0x0014222d, 0x0014222d, 0x00172430, 0x00182531, 0x00182531, 0x00182530, 0x00172830, 0x00172830, 0x00172831, 0x00182933, 0x00182934, 0x00182934, 0x00182934, 0x00182934, 0x00182934, 0x00182934, 0x00172834, 0x00162531, 0x0014202b, 0x000f1923, 0x000a111a, 0x00080e17, 0x000a1017, 0x000e161e, 0x0019242e, 0x002b4052, 0x005c8095, 0x0098bdc5, 0x00b5cccc, 0x00c5cbcc, 0x00cacbcc, 0x00cccbcc, 0x00cccbca, 0x00cbcccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00c9cccc, 0x00c0cccc, 0x00a6c1c5, 0x006e92a1, 0x003a6078, 0x0037556b, 0x00385063, 0x00314856, 0x002e4350, 0x00293e4a, 0x00293c49, 0x00283a48, 0x00273a47, 0x002d404c, 0x002c3f4b, 0x00283b47, 0x00273a46, 0x00293c48, 0x00253844, 0x00233440, 0x0023323f, 0x0024303d, 0x00212d38, 0x001a242c, 0x00161e25, 0x00161d24, 0x001e252b, 0x00192028, 0x00161c24, 0x001b2128, 0x001b2129, 0x00171d24, 0x00181f25, 0x001e262c, 0x00242d34, 0x00253036, 0x00242d36, 0x00263038, 0x002c363f, 0x002f3841, 0x00303842, 0x00303842, 0x00303740, 0x002e343e, 0x002e343e, 0x002f353f, 0x00303742, 0x00303944, 0x00303a45, 0x00323c47, 0x00343d48, 0x0037404b, 0x0038444d, 0x00343f4b, 0x00343c49, 0x00353b48, 0x00343a46, 0x00363a44, 0x00343943, 0x00343944, 0x00373b48, 0x00393d4c, 0x00383d4c, 0x00373c4b, 0x003b404e, 0x003c404e, 0x00383c49, 0x00373947, 0x003b3e4b, 0x003d404c, 0x003b3e4b, 0x003b3e4c, 0x003c404d, 0x003c3f4d, 0x003b3e4c, 0x003b3e4c, 0x003b3d4b, 0x00383b48, 0x00343642, 0x00343642, 0x00343644, 0x00343644, 0x00333441, 0x0030343f, 0x00323540, 0x00343742, 0x00343845, 0x00343a46, 0x00343a45, 0x00333b44, 0x00343c47, 0x00383f4c, 0x00394250, 0x00384350, 0x0037414f, 0x00343d4c, 0x00333a48, 0x00303743, 0x002c323e, 0x002b313c, 0x002b323d, 0x002c343f, 0x002e3641, 0x002d3740, 0x002c3640, 0x002c343d, 0x0029323b, 0x00283039, 0x00242d36, 0x00202932, 0x001c2730, 0x001f2830, 0x001f252e, 0x001d242c, 0x00171d23, 0x00161c23, 0x00161d23, 0x00141c23, 0x00151e25, 0x00182028, 0x001a222b, 0x001f2731, 0x00242c38, 0x0026303a, 0x0025303b, 0x0025303c, 0x0026323e, 0x00283440, 0x00293843, 0x00263540, 0x0023323d, 0x002b3a46, 0x0030404c, 0x002b3b48, 0x00283b47, 0x00283b48, 0x002b3d4e, 0x002f4153, 0x00334859, 0x00344c5c, 0x00344c5e, 0x00375063, 0x00385063, 0x003e5769, 0x0040596c, 0x003f586d, 0x00405c74, 0x004f758c, 0x0080b0bd, 0x00b0cbcc, 0x00c2cccc, 0x00c9ccca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00c9cccc, 0x00c4cccc, 0x00bccccc, 0x00a0bec6, 0x00668a9c, 0x002b4858, 0x00142330, 0x000e1620, 0x000a131c, 0x000a141e, 0x00101c25, 0x00112027, 0x00122229, 0x0013242c, 0x0013242d, 0x00142730, 0x00192e37, 0x00243a44, 0x002a414d, 0x002c4754, 0x002d4957, 0x002f4958, 0x00304959, 0x00304a59, 0x00304c59, 0x00304c59, 0x00304c59, 0x00304c59, 0x00304c59, 0x002f4b59, 0x002f4a58, 0x00304857, 0x002f4654, 0x0029404e, 0x00223845, 0x001e333e, 0x001a2e39, 0x00182c37, 0x00182c36, 0x00182c36, 0x00182c36, 0x00192c38, 0x00192c38, 0x00192c38, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182b34, 0x00182b34, 0x00172a34, 0x00172934, 0x00152834, 0x00152836, 0x00152836, 0x00152836, 0x00152836, 0x00162937, 0x00162a38, 0x00172c39, 0x00172c39, 0x00172c3a, 0x00182c3a, 0x000e1e28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0012242c, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4347, 0x001c484c, 0x001d4d50, 0x00205356, 0x0023636c, 0x0030a4cb, 0x002a88a0, 0x00256264, 0x00266467, 0x00276568, 0x00276669, 0x0028676a, 0x0028676a, 0x0028686a, 0x00276769, 0x00276669, 0x00276668, 0x00276568, 0x00266568, 0x00266568, 0x00266568, 0x00276568, 0x00276568, 0x00276568, 0x00266568, 0x00266568, 0x00266568, 0x00266568, 0x00276568, 0x00276466, 0x00266466, 0x00256364, 0x00256163, 0x00246062, 0x00245e60, 0x00256c79, 0x002ea3c9, 0x00288cab, 0x00205254, 0x001d4d50, 0x001c484c, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00142e34, 0x00132c32, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00162633, 0x00162633, 0x00162633, 0x00152633, 0x00152632, 0x00152632, 0x00162531, 0x00162531, 0x00152432, 0x00142330, 0x0012212e, 0x00111f2a, 0x00101e2a, 0x00101f2a, 0x000f1f29, 0x00101f2a, 0x0013202c, 0x0014202c, 0x0014202c, 0x0014212b, 0x0014212b, 0x0014202a, 0x0013202a, 0x0013202a, 0x00121f29, 0x00121f29, 0x00111f29, 0x00111f29, 0x0013202a, 0x0013202a, 0x0013202a, 0x0013202c, 0x0013202c, 0x0014212c, 0x0014212c, 0x00162430, 0x00182430, 0x00182430, 0x00182530, 0x00172730, 0x00172830, 0x00172830, 0x00172832, 0x00182934, 0x00182934, 0x00182934, 0x00182934, 0x00172833, 0x00162833, 0x00162732, 0x0014222d, 0x00101b24, 0x000c141c, 0x00090e18, 0x00090d16, 0x000c121a, 0x00111c27, 0x001e303e, 0x003e5e70, 0x0080a9b5, 0x00adcacc, 0x00bfcccc, 0x00cacbcc, 0x00cccbcc, 0x00cccbcc, 0x00cccbca, 0x00cbcccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00c5cccc, 0x00bbcbcc, 0x0091aeb7, 0x004b6c7c, 0x002b4a5e, 0x00334e60, 0x00365060, 0x00324957, 0x00304553, 0x002b404d, 0x002b3f4c, 0x00283b49, 0x00273a48, 0x002c3f4b, 0x002a3d48, 0x00283a46, 0x00273844, 0x00283945, 0x00243641, 0x00243440, 0x0024313d, 0x0024303c, 0x00202c37, 0x0018222b, 0x00182027, 0x00172026, 0x001c2329, 0x001a2028, 0x00192027, 0x001d242b, 0x001c232a, 0x00192027, 0x00182026, 0x001c242a, 0x001f282e, 0x00222b32, 0x00242d35, 0x0027313a, 0x002c3740, 0x002f3841, 0x00313944, 0x00323944, 0x00333944, 0x00343a45, 0x00343a45, 0x00333944, 0x00333945, 0x00343c48, 0x00343e49, 0x0036404b, 0x0038434d, 0x003c4551, 0x0036424e, 0x0034404c, 0x00384250, 0x0039414f, 0x0038404c, 0x00383e4a, 0x00363c48, 0x00373d4a, 0x003c4350, 0x00424857, 0x00424858, 0x00404857, 0x00404958, 0x00404857, 0x003f4554, 0x003e4453, 0x00434858, 0x00464c5b, 0x00454b5a, 0x00454b5a, 0x00454b59, 0x00444958, 0x00434957, 0x00444a58, 0x00444a58, 0x00444958, 0x00404554, 0x003d4251, 0x003d4151, 0x003d4151, 0x003c4050, 0x003a404d, 0x003a404d, 0x0039404d, 0x00383f4d, 0x00383f4d, 0x00383f4c, 0x00363e4b, 0x0037404c, 0x0039424f, 0x003c4453, 0x003a4554, 0x00384453, 0x00343e4e, 0x00333b49, 0x00303845, 0x002c3440, 0x002c343f, 0x002c343e, 0x002c343f, 0x002d3540, 0x002d3540, 0x002d3540, 0x002c343e, 0x002a323b, 0x0028303a, 0x00262f38, 0x00242d36, 0x00202931, 0x00202832, 0x001f262f, 0x001f262e, 0x00181f27, 0x00151c24, 0x00161c24, 0x00171e25, 0x00182028, 0x00182128, 0x001b232b, 0x001d2630, 0x00202833, 0x00202b35, 0x00222e38, 0x0026313c, 0x0027323e, 0x00273440, 0x00283742, 0x0024333e, 0x0022313c, 0x00243440, 0x002c3c48, 0x00293a47, 0x00283b47, 0x002a3d4a, 0x002a3c4d, 0x002b3d4f, 0x00314758, 0x00354c5d, 0x00354f5e, 0x00385061, 0x00385162, 0x003d5668, 0x003d5568, 0x003c566b, 0x00405c74, 0x004d7088, 0x0074a3b2, 0x00a8c8cb, 0x00bdcccc, 0x00c6cccc, 0x00cbcccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00c9cccc, 0x00c3cccc, 0x00b7cbcc, 0x008fb1bc, 0x004c6d7e, 0x001e3040, 0x00101925, 0x000a131c, 0x0009111b, 0x000e1822, 0x00101d25, 0x00122029, 0x0013232c, 0x0013242c, 0x0014242f, 0x00152833, 0x001e323e, 0x00273d4a, 0x002b4453, 0x002c4857, 0x002f4958, 0x00304958, 0x00304958, 0x00304a58, 0x002f4a58, 0x00304b58, 0x00304b58, 0x002f4b57, 0x002f4956, 0x002f4855, 0x002e4654, 0x002c4250, 0x00263b48, 0x00203441, 0x001c2f3c, 0x001a2c38, 0x00182a35, 0x00182a34, 0x00182b35, 0x00182b35, 0x00182c37, 0x00182c38, 0x00182c38, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182b35, 0x00182b34, 0x00172a34, 0x00172934, 0x00152834, 0x00152834, 0x00152834, 0x00152834, 0x00152835, 0x00162935, 0x00162b38, 0x00172b39, 0x00172c39, 0x00182c3a, 0x00182d3b, 0x000e1e28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153439, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001d4b4e, 0x001f5053, 0x00205558, 0x0024646e, 0x0031a4ca, 0x002c88a1, 0x00266467, 0x00276668, 0x0028686a, 0x0028686b, 0x0028696c, 0x0028696c, 0x0028696c, 0x0028686b, 0x0028686b, 0x0028686a, 0x00286769, 0x00286769, 0x00276668, 0x00276668, 0x00266568, 0x00266568, 0x00266568, 0x00266568, 0x00266568, 0x00266467, 0x00266467, 0x00276467, 0x00276466, 0x00256364, 0x00256264, 0x00246062, 0x00245f61, 0x00245d60, 0x002a8ca8, 0x002da3c9, 0x00246d80, 0x001e5053, 0x001d4b4e, 0x001c474b, 0x001a4245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0013282e, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00172633, 0x00172633, 0x00172633, 0x00162632, 0x00152631, 0x00152631, 0x00162531, 0x00162530, 0x00152431, 0x00142330, 0x0013222f, 0x0012212c, 0x0011202c, 0x0012202b, 0x0012202a, 0x0013202a, 0x0014212b, 0x0014212c, 0x0014212b, 0x0014212b, 0x0014212b, 0x0013202a, 0x0013202a, 0x0013202a, 0x0014202a, 0x0014202a, 0x0013202a, 0x0013202a, 0x0013202a, 0x0013202a, 0x0013202a, 0x0013202c, 0x0013202c, 0x0013202c, 0x0014202c, 0x0014222d, 0x0016242f, 0x00172430, 0x00162430, 0x00162630, 0x00162731, 0x00162831, 0x00172833, 0x00172833, 0x00182934, 0x00182a34, 0x00172934, 0x00162833, 0x00162731, 0x0015242e, 0x00121e27, 0x000c151c, 0x00080e15, 0x00070c13, 0x00080f16, 0x000d151f, 0x00152532, 0x002c4658, 0x00648c9d, 0x00a0c3c7, 0x00bccccc, 0x00c7cccc, 0x00cbcbcc, 0x00cccbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00c9cccc, 0x00c1cccc, 0x00aec4c9, 0x006d8c9c, 0x002f4d5f, 0x00274153, 0x00344b5c, 0x00354d5c, 0x00304856, 0x002f4655, 0x002d4452, 0x002b414e, 0x00283c4a, 0x00273a48, 0x002f404c, 0x002a3b47, 0x00283945, 0x00263844, 0x00263742, 0x0024343e, 0x0024333d, 0x0023303a, 0x00222e38, 0x001f2832, 0x00182029, 0x00182128, 0x00182128, 0x001a2128, 0x00171d24, 0x00171d24, 0x001b2228, 0x001b2228, 0x00192026, 0x00182025, 0x001a2127, 0x001c242a, 0x001f262d, 0x00262d36, 0x0029333c, 0x002c363f, 0x002f3941, 0x00313a44, 0x00343c47, 0x00353d49, 0x00363e4a, 0x00363e4a, 0x00343c48, 0x00343c48, 0x0037404c, 0x0037424e, 0x00394450, 0x003c4652, 0x003d4754, 0x0036414f, 0x00384451, 0x003c4754, 0x003c4654, 0x003b4453, 0x003a4350, 0x0038424f, 0x003c4453, 0x00404857, 0x00414a58, 0x00404a58, 0x00404a58, 0x003e4856, 0x003e4856, 0x00404857, 0x00404858, 0x00404a59, 0x00414c5b, 0x00404b5a, 0x00404858, 0x00404858, 0x003f4856, 0x003e4855, 0x003e4856, 0x00424c5a, 0x00464f5f, 0x00444c5c, 0x00424859, 0x00414858, 0x00404858, 0x003f4958, 0x003e4957, 0x003e4856, 0x003c4654, 0x003b4351, 0x003b4250, 0x003b4351, 0x003b4452, 0x003b4452, 0x003b4452, 0x003a4452, 0x003a4554, 0x003a4554, 0x0036414f, 0x00343d4c, 0x00323b49, 0x00303846, 0x002e3642, 0x002d3540, 0x002d3540, 0x002e3641, 0x002e3641, 0x002e3642, 0x002d3440, 0x002b313c, 0x0029303a, 0x00242d34, 0x00242d34, 0x00242c34, 0x00242c34, 0x00212933, 0x001d252f, 0x001a222c, 0x00171e28, 0x00181f28, 0x00182028, 0x00182128, 0x00192229, 0x001c252c, 0x001c2630, 0x00202933, 0x00212c36, 0x00202c35, 0x0024303a, 0x0026323d, 0x0026323e, 0x00273540, 0x0023343e, 0x0023343f, 0x00243441, 0x00273845, 0x00263846, 0x00263a48, 0x002b404d, 0x002a3f4f, 0x00283c4c, 0x00304554, 0x00354c5c, 0x0038505e, 0x00364d5c, 0x0038515e, 0x003c5662, 0x00395461, 0x003c5768, 0x00435d72, 0x004a6981, 0x005e8a9e, 0x0093bcc4, 0x00b4cccc, 0x00c3cccc, 0x00c9cccc, 0x00cbccca, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00cbccca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00c8cccc, 0x00c0cccc, 0x00acc7ca, 0x00799ca9, 0x00344e5e, 0x00142230, 0x000c141f, 0x00081019, 0x000c161f, 0x00101c24, 0x00122028, 0x0013232c, 0x0013242d, 0x0014242f, 0x00132530, 0x00182c38, 0x00203644, 0x0029404f, 0x002d4654, 0x002f4856, 0x00314958, 0x00304958, 0x002e4957, 0x002d4957, 0x002e4a58, 0x002e4a58, 0x002e4a56, 0x002d4854, 0x002d4753, 0x002c4450, 0x00283e4a, 0x00203642, 0x001c303c, 0x00192c38, 0x00182a34, 0x00172934, 0x00172934, 0x00172a35, 0x00182a34, 0x00182b35, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c37, 0x00182c38, 0x00182c38, 0x00182c38, 0x00182c38, 0x00182b37, 0x00182a36, 0x00172936, 0x00152a34, 0x00152a34, 0x00152a34, 0x00152a34, 0x00152a35, 0x00172a38, 0x00182a38, 0x00182a38, 0x00182b39, 0x00182c39, 0x000e1e28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00122c32, 0x00143036, 0x0015363b, 0x00183c40, 0x001a4245, 0x001c474b, 0x001d4d50, 0x001f5254, 0x0021585a, 0x00256770, 0x0032a5ca, 0x002c8aa2, 0x00286769, 0x0028686b, 0x00286a6c, 0x00296c6e, 0x002a6c6e, 0x002a6c6e, 0x00296c6e, 0x00296b6d, 0x00286a6c, 0x00286a6c, 0x0028696c, 0x0028686b, 0x0028686a, 0x00286769, 0x00286769, 0x00286668, 0x00276668, 0x00266568, 0x00266568, 0x00266467, 0x00266467, 0x00276466, 0x00256364, 0x00256264, 0x00256163, 0x00245f61, 0x00245d60, 0x00277485, 0x002ea1c8, 0x002a8faf, 0x00205459, 0x001d4d50, 0x001c4a4d, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00152431, 0x00152431, 0x00152431, 0x00152430, 0x00142530, 0x00142430, 0x00142530, 0x00162530, 0x00162531, 0x00142431, 0x00142430, 0x0014232e, 0x0013222d, 0x0014212c, 0x0014212b, 0x0014212b, 0x0014222c, 0x0014222c, 0x0014212b, 0x0014212b, 0x0014212b, 0x0013202a, 0x00122029, 0x00121f29, 0x00131f29, 0x00131f29, 0x00111f28, 0x00111f28, 0x00111f29, 0x00111f29, 0x00111f29, 0x00111f2b, 0x00111f2b, 0x00121f2b, 0x00121f2b, 0x0013202c, 0x0014222e, 0x0016242f, 0x00162430, 0x00162530, 0x00162631, 0x00162732, 0x00162833, 0x00172833, 0x00182833, 0x00182934, 0x00172833, 0x00172732, 0x0014242e, 0x00121e26, 0x000e181f, 0x00081016, 0x00060b11, 0x00060c13, 0x00091018, 0x00101b25, 0x001c303e, 0x00446779, 0x0086b0bc, 0x00b1cbcc, 0x00c2cccc, 0x00cacccc, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00cccbcb, 0x00cccbcb, 0x00cbccca, 0x00c8cccc, 0x00b8cacb, 0x008fabb5, 0x00486776, 0x00213a4c, 0x00283d4d, 0x00314655, 0x00324857, 0x002e4755, 0x002e4655, 0x002f4755, 0x002d4451, 0x00293c4b, 0x00283b48, 0x002f404c, 0x00293a46, 0x00283944, 0x00263844, 0x00243541, 0x0024343e, 0x0024333c, 0x00212e38, 0x00202b34, 0x001a242d, 0x00161e27, 0x00172027, 0x00182027, 0x00161f24, 0x00141b21, 0x00151c22, 0x00181e24, 0x001a2127, 0x001a2127, 0x001a2126, 0x001a2125, 0x001d2428, 0x001f252c, 0x00262d36, 0x002b343c, 0x002d3840, 0x00303943, 0x00323c48, 0x00353f4c, 0x0036404c, 0x0037404c, 0x0037404d, 0x0038414d, 0x0038414e, 0x00394350, 0x00394450, 0x003b4652, 0x003d4854, 0x003c4753, 0x00384350, 0x00394553, 0x003d4856, 0x003d4856, 0x003d4856, 0x003b4654, 0x003b4654, 0x003d4856, 0x003e4957, 0x003f4957, 0x003e4856, 0x003b4654, 0x0035404e, 0x00374250, 0x00394352, 0x003b4656, 0x003c4756, 0x003c4857, 0x00344050, 0x00333c4c, 0x00343e4e, 0x0034404d, 0x0035414d, 0x0034404c, 0x00384451, 0x00404a5a, 0x00414b5b, 0x003f4858, 0x003d4757, 0x003e4858, 0x003c4958, 0x003c4a57, 0x003d4a57, 0x003e4a58, 0x003d4855, 0x003d4654, 0x003d4654, 0x003d4755, 0x003c4654, 0x003a4451, 0x00384250, 0x00394452, 0x00394453, 0x00384250, 0x0037404e, 0x00343e4c, 0x00343c49, 0x00333b48, 0x00303844, 0x00303843, 0x002f3742, 0x002f3742, 0x002f3742, 0x002d3540, 0x002b313c, 0x0029303b, 0x00232c34, 0x00232b32, 0x00262e35, 0x00262e36, 0x00242c34, 0x001f2730, 0x00202831, 0x0019202a, 0x00182029, 0x001a212a, 0x00182129, 0x00182128, 0x001c242c, 0x001e2830, 0x001f2831, 0x00212d36, 0x00243039, 0x0025313c, 0x0025303c, 0x0024303c, 0x0024333e, 0x0023333e, 0x00263843, 0x00293a48, 0x00283948, 0x00283b49, 0x00293e4c, 0x002c414e, 0x002c4150, 0x00293e4e, 0x002e4453, 0x00324a58, 0x00354b5b, 0x00334958, 0x00354d5b, 0x0037505e, 0x00385262, 0x003f586a, 0x00445e72, 0x00456279, 0x004c7288, 0x0078a4b3, 0x00a9c9cb, 0x00becccc, 0x00c8cccc, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00cbccca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cacccb, 0x00c4cccc, 0x00b9cccc, 0x009abbc3, 0x00547483, 0x001c303f, 0x000e1823, 0x00081018, 0x00081018, 0x000d1a21, 0x00112028, 0x0013222c, 0x0013242d, 0x0013242e, 0x00122430, 0x00132632, 0x00182c39, 0x00203544, 0x00273d4c, 0x002d4453, 0x00304756, 0x00304856, 0x002c4855, 0x002c4855, 0x002c4856, 0x002c4856, 0x002d4854, 0x002c4652, 0x0029424c, 0x00253c47, 0x00203540, 0x001c303b, 0x00182b38, 0x00172935, 0x00172934, 0x00172934, 0x00172934, 0x00172934, 0x00172934, 0x00182a34, 0x00182b34, 0x00182b34, 0x00182c36, 0x00182c36, 0x00182c37, 0x00182c38, 0x00182c38, 0x00182c38, 0x00182c38, 0x00182b37, 0x00182a37, 0x00182a36, 0x00162a34, 0x00152a33, 0x00152a34, 0x00152a34, 0x00152a34, 0x00172a37, 0x00182a38, 0x00182a38, 0x00182a39, 0x00182a39, 0x000e1e28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0016363b, 0x00183c40, 0x001a4245, 0x001c484c, 0x001e4f51, 0x00205457, 0x0023595c, 0x00256870, 0x0032a5ca, 0x002c8ba2, 0x0028686b, 0x00296b6d, 0x00296c6f, 0x002a6e70, 0x002a6e70, 0x002a6e70, 0x002a6e70, 0x002a6d6f, 0x00296c6f, 0x00296c6e, 0x00296b6d, 0x00286a6c, 0x0028696c, 0x0028686b, 0x0028686a, 0x00286769, 0x00286668, 0x00266568, 0x00266568, 0x00266467, 0x00266466, 0x00256364, 0x00256264, 0x00256163, 0x00245f61, 0x00245e60, 0x00256f7d, 0x002d9cc1, 0x002c9cc0, 0x0022636f, 0x001f5053, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183d41, 0x00183a3e, 0x00153439, 0x00143036, 0x00132c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0014222e, 0x0014222e, 0x0014222e, 0x0014222e, 0x0013242e, 0x0013242e, 0x00142430, 0x00162530, 0x00172632, 0x00172633, 0x00172632, 0x00162530, 0x0014242f, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014212b, 0x0013202a, 0x0013202a, 0x00132029, 0x00121e28, 0x00121e28, 0x00111d27, 0x00121e28, 0x00111e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e2a, 0x00111f2a, 0x00111f2b, 0x00121f2b, 0x0014212c, 0x0015232e, 0x0015232f, 0x00162430, 0x00162530, 0x00172631, 0x00162632, 0x00152732, 0x00152731, 0x00152731, 0x00152731, 0x0014242f, 0x00121f28, 0x000f1820, 0x00091017, 0x00060b10, 0x0004090e, 0x00060c14, 0x000b141c, 0x0015222c, 0x002c4455, 0x00668e9f, 0x00a4c4ca, 0x00bccccc, 0x00c8cccc, 0x00cccccc, 0x00cccbcc, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00cccbcc, 0x00cccbcb, 0x00cbcccb, 0x00c4cccc, 0x00a8c0c5, 0x00648491, 0x002c4858, 0x001c3040, 0x00283b48, 0x002a3d4c, 0x002b404f, 0x002c4452, 0x00304855, 0x00334b58, 0x00304754, 0x002c404d, 0x00293d4a, 0x002c3f4b, 0x00283a46, 0x00283b47, 0x00293c48, 0x00263844, 0x00253440, 0x0024333d, 0x0023303a, 0x00202c35, 0x0019242c, 0x00161e25, 0x00171e25, 0x00161e25, 0x00171e24, 0x00141c21, 0x00161d23, 0x00161c22, 0x00181f25, 0x001b2228, 0x001c2428, 0x001d2428, 0x001f252b, 0x0020282e, 0x00262c35, 0x002b343c, 0x002f3841, 0x00303a44, 0x00343d49, 0x00353f4b, 0x0037404d, 0x0038414e, 0x0039434f, 0x003b4451, 0x003c4552, 0x003c4552, 0x003b4552, 0x003c4854, 0x003e4854, 0x003c4653, 0x00384350, 0x00384452, 0x003c4855, 0x003d4856, 0x003d4856, 0x003c4855, 0x003a4754, 0x00394654, 0x00394452, 0x003c4554, 0x00394450, 0x00303c48, 0x002c3844, 0x002e3a47, 0x002c3745, 0x00343f4e, 0x0034404f, 0x00333e4d, 0x00303b4b, 0x002c3746, 0x002e3848, 0x002d3846, 0x002b3743, 0x00283440, 0x002c3844, 0x00313c4a, 0x00384451, 0x0037414f, 0x00353f4d, 0x00374151, 0x00354453, 0x00384754, 0x003a4a56, 0x003c4a57, 0x003d4a58, 0x003f4957, 0x003e4856, 0x003f4856, 0x003c4654, 0x00394351, 0x0038414f, 0x0038414f, 0x0037424f, 0x0037424f, 0x0037414f, 0x0037404e, 0x0036404c, 0x00363e4b, 0x00343d49, 0x00343c47, 0x00323a45, 0x00303843, 0x00303844, 0x002d3440, 0x002b313c, 0x002c323d, 0x00252e36, 0x00232c33, 0x00252d34, 0x00272f38, 0x00242c35, 0x00232b34, 0x00222a34, 0x001e252f, 0x001c232c, 0x001b222c, 0x00192229, 0x00192229, 0x001a232b, 0x001e2831, 0x00232c37, 0x0025303b, 0x0026333e, 0x0027333d, 0x00232f3b, 0x00212d39, 0x0021303b, 0x0024333e, 0x00283844, 0x002c3c49, 0x00293c49, 0x00283c4b, 0x002c414f, 0x002f4451, 0x002e4353, 0x002d4352, 0x002f4554, 0x00304857, 0x00314859, 0x00324859, 0x00324a59, 0x00344c5a, 0x00374f5f, 0x003f5768, 0x00445b6e, 0x00425d70, 0x003f6074, 0x00568090, 0x0094bcc3, 0x00b9cccc, 0x00c5cccc, 0x00cbcccb, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00cbccca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cacccb, 0x00c7cccc, 0x00c0cccc, 0x00afc8cb, 0x007898a6, 0x002b4454, 0x00101e29, 0x000b121a, 0x00060c14, 0x000a141c, 0x00101d25, 0x0013212b, 0x0013232c, 0x0012232d, 0x0012242e, 0x0012242f, 0x00132531, 0x00172936, 0x001c303c, 0x00263947, 0x002d404e, 0x002d4250, 0x002c4450, 0x002c4450, 0x002c4450, 0x002a4450, 0x0029424e, 0x00263e49, 0x00213843, 0x001d323d, 0x00192c38, 0x00172a36, 0x00172833, 0x00162833, 0x00172833, 0x00172833, 0x00172834, 0x00182934, 0x00182934, 0x00182a34, 0x00182a34, 0x00182b34, 0x00192c34, 0x00192c34, 0x00182c35, 0x00182c37, 0x00182c37, 0x00182c37, 0x00182c37, 0x00182c37, 0x00182b36, 0x00182b36, 0x00172c35, 0x00172c34, 0x00162b34, 0x00162b34, 0x00162b35, 0x00172a36, 0x00172938, 0x00172938, 0x00172938, 0x00172938, 0x000e1d28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00111f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0016363b, 0x00183d41, 0x001a4347, 0x001d4a4d, 0x001e5053, 0x00205558, 0x00245c5e, 0x00266972, 0x0033a6cb, 0x002d8ca3, 0x00296b6d, 0x002a6d6f, 0x002b6f70, 0x002b7071, 0x002b7072, 0x002b7072, 0x002c7072, 0x002c7071, 0x002b6f70, 0x00296d6f, 0x00296c6f, 0x002a6c6e, 0x00296a6c, 0x0028696c, 0x0028686b, 0x0028686a, 0x00276668, 0x00266568, 0x00266467, 0x00266466, 0x00256364, 0x00266264, 0x00246062, 0x00245f61, 0x00246064, 0x00287a90, 0x002d9ec3, 0x002d9ec4, 0x00246e80, 0x001f5154, 0x001d4d50, 0x001c484c, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0012242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0014222d, 0x0014222d, 0x0014222d, 0x0014222d, 0x0013232e, 0x0013232e, 0x0014242f, 0x00162530, 0x00172631, 0x00182733, 0x00182733, 0x00172632, 0x00152430, 0x0014232c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014212b, 0x0013202a, 0x0013202a, 0x00121e28, 0x00121e28, 0x00111d27, 0x00111d27, 0x00111e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e29, 0x00101e2a, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x0012202c, 0x0013202c, 0x0014212d, 0x0014232e, 0x00142430, 0x00142430, 0x00142430, 0x00142430, 0x0013242e, 0x0013232d, 0x0013202b, 0x000f1a22, 0x000b1118, 0x00080c10, 0x0006090e, 0x0004090d, 0x00080e15, 0x000d171f, 0x001b2a34, 0x00436374, 0x0088b0bc, 0x00b4cbcc, 0x00c3cccc, 0x00cbccca, 0x00cccbcb, 0x00cccbcc, 0x00cccacc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00cccbcc, 0x00cccbcb, 0x00c8cccc, 0x00bcc9cb, 0x0088a4ae, 0x00415e6e, 0x00203848, 0x001b2d3a, 0x00293a47, 0x00243544, 0x00243846, 0x0028404c, 0x002f4754, 0x00364f5c, 0x00344a57, 0x00304452, 0x00293e4c, 0x00293c49, 0x00273946, 0x00283b47, 0x002c3f4b, 0x00283845, 0x00253440, 0x0024343f, 0x0025313c, 0x00202c36, 0x0019242d, 0x00171f28, 0x00171e27, 0x00141d26, 0x00182028, 0x00151c23, 0x00151c22, 0x00161c22, 0x00181f24, 0x001c2328, 0x001f252c, 0x0022282e, 0x0022282f, 0x0020282e, 0x00232a33, 0x0029323b, 0x00303942, 0x00303944, 0x00323c48, 0x0036404c, 0x0038414e, 0x003a4450, 0x003b4450, 0x003c4653, 0x003d4754, 0x003c4653, 0x003c4653, 0x003c4854, 0x003d4854, 0x003c4552, 0x00384450, 0x00374250, 0x00394553, 0x003c4855, 0x003c4855, 0x003c4855, 0x003c4855, 0x00394553, 0x0035404e, 0x00353f4d, 0x00323c48, 0x0028343e, 0x00242f39, 0x00293540, 0x0024303c, 0x00283441, 0x002c3846, 0x002e3948, 0x00323e4c, 0x00303948, 0x002e3846, 0x002c3743, 0x00293440, 0x0027313d, 0x002a3440, 0x002a3440, 0x00293541, 0x002b3541, 0x002c3644, 0x00303c4b, 0x00334150, 0x00364554, 0x00394956, 0x003b4c58, 0x003e4c5a, 0x00404b58, 0x003d4957, 0x003f4857, 0x003c4655, 0x003b4453, 0x0038414f, 0x0036404c, 0x0036414e, 0x0036424e, 0x0036424e, 0x0037424e, 0x0038414e, 0x0037404d, 0x0038404c, 0x00353d4a, 0x00343c47, 0x00343c48, 0x00323a44, 0x002c343f, 0x002a303c, 0x00252c36, 0x00202830, 0x001e272e, 0x001f282f, 0x00222a33, 0x00242c35, 0x0028313a, 0x00262e37, 0x00202830, 0x001d242c, 0x001b222b, 0x0019222a, 0x001a232a, 0x001a232c, 0x001b2530, 0x00242e39, 0x0028333d, 0x00283641, 0x0025333e, 0x0025303c, 0x00222e39, 0x0022303c, 0x0024343f, 0x00273843, 0x002a3b48, 0x00283a48, 0x00273a48, 0x002c404e, 0x00324754, 0x00324756, 0x00314655, 0x00304655, 0x00304857, 0x00314859, 0x0033495a, 0x00334959, 0x00324a58, 0x00364d5d, 0x003d5465, 0x0043596a, 0x0042596b, 0x003b5468, 0x003b5e70, 0x00739eab, 0x00acc8ca, 0x00c0cccc, 0x00cacccb, 0x00cccbca, 0x00cbccc9, 0x00cbccc9, 0x00cbccca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00c8cccc, 0x00c4cccc, 0x00b9cccc, 0x0093b3bc, 0x00426070, 0x00142533, 0x000d151e, 0x00070c13, 0x00050c14, 0x000c171f, 0x00111f28, 0x0013222a, 0x0013232c, 0x0013242c, 0x0012242e, 0x0014242f, 0x00142430, 0x00142530, 0x00172834, 0x001c2d3a, 0x00203440, 0x00243944, 0x00253b47, 0x00243a45, 0x00233844, 0x00203541, 0x001c313c, 0x00182c38, 0x00172a36, 0x00152734, 0x00142532, 0x00162530, 0x00162630, 0x00162832, 0x00172833, 0x00172833, 0x00182934, 0x00182934, 0x00182a34, 0x00192a34, 0x00192a34, 0x001a2c34, 0x001a2c34, 0x00192c34, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182d36, 0x00182d35, 0x00172c34, 0x00162b34, 0x00162b35, 0x00162936, 0x00172937, 0x00172937, 0x00172937, 0x00172937, 0x000e1d28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00142e34, 0x00143338, 0x0017383c, 0x00183f43, 0x001b4448, 0x001d4b4e, 0x00205154, 0x0021585a, 0x00245c5f, 0x00276a73, 0x0034a6cb, 0x002f90a8, 0x002b757d, 0x002c777e, 0x002c7880, 0x002d7a81, 0x002d7a81, 0x002d7a81, 0x002d7a81, 0x002c7980, 0x002c7880, 0x002c787f, 0x002b777e, 0x002b757d, 0x002a747c, 0x002a747b, 0x0029727a, 0x00287179, 0x00287078, 0x00286f77, 0x00276d76, 0x00276d76, 0x00276c75, 0x00266b74, 0x0027717f, 0x00298299, 0x002c97b8, 0x002ea3ca, 0x002c9bbf, 0x00246d7e, 0x00205254, 0x001d4d50, 0x001c4a4d, 0x001c4649, 0x001a4245, 0x00183d41, 0x0017383c, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0014212c, 0x0014212c, 0x0014212c, 0x0012212d, 0x0013222e, 0x0013222e, 0x00142430, 0x00162531, 0x00172633, 0x00172634, 0x00172633, 0x00172633, 0x00142431, 0x0014222e, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014212b, 0x0013202a, 0x00122029, 0x00111e28, 0x00111e28, 0x00101d27, 0x00101d27, 0x00101e28, 0x00101d27, 0x00101d28, 0x00101e28, 0x00101e29, 0x00101e2a, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x00111f2b, 0x0011202c, 0x0011202c, 0x0012212d, 0x0012222e, 0x0012232d, 0x0012232d, 0x0012222c, 0x0013202a, 0x00101b24, 0x000c131c, 0x00080c10, 0x0006090c, 0x0005090b, 0x00070a0e, 0x000b1017, 0x00101b23, 0x0021343f, 0x00587c8c, 0x009dc2c7, 0x00bccccc, 0x00c8cccc, 0x00cccbca, 0x00cccbcb, 0x00cccbcc, 0x00cccacc, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccca, 0x00c9cccb, 0x00c0cbcc, 0x00a1b9c0, 0x005f7c8a, 0x002d4757, 0x001c303f, 0x00192b36, 0x00293945, 0x00223340, 0x00203241, 0x00243847, 0x002c4452, 0x0038515f, 0x00354c5c, 0x00314657, 0x002c3f4f, 0x00283848, 0x00253744, 0x00263844, 0x0030424f, 0x00273844, 0x0022323d, 0x0024323d, 0x00242f39, 0x001e2833, 0x0018222c, 0x00182028, 0x001a212a, 0x0019212a, 0x001c242c, 0x00151c23, 0x00141b21, 0x00171e24, 0x00181f24, 0x001c232b, 0x00242a32, 0x00252c35, 0x00242b34, 0x00202830, 0x00202730, 0x00212a33, 0x002b343d, 0x002c3540, 0x00303a47, 0x0037404c, 0x0038424f, 0x00394450, 0x003b4450, 0x003c4653, 0x003d4754, 0x003c4652, 0x003c4551, 0x003c4652, 0x003c4551, 0x003b4552, 0x003a4452, 0x00374250, 0x00384451, 0x003b4654, 0x003b4553, 0x003b4553, 0x003a4451, 0x0038424f, 0x00343d49, 0x00333c47, 0x002f3843, 0x0028323c, 0x0028313b, 0x0028323c, 0x00202b34, 0x00202b35, 0x002b3540, 0x0028333d, 0x002a3640, 0x0027313d, 0x0028323e, 0x002b3440, 0x0028303c, 0x00263039, 0x002c343e, 0x002c353f, 0x00242d38, 0x0026303c, 0x002b3442, 0x002c3644, 0x002e3b49, 0x0033404e, 0x00374552, 0x003b4a57, 0x003e4c59, 0x003e4a58, 0x003d4957, 0x003e4856, 0x003c4855, 0x003c4654, 0x003a4350, 0x0037404d, 0x0037404d, 0x0037414e, 0x0037424e, 0x0038424e, 0x0037404d, 0x0037404d, 0x0038404d, 0x00373f4b, 0x00343c48, 0x00353d48, 0x002f3742, 0x0029303c, 0x00282e39, 0x00232a34, 0x001f272f, 0x001c242b, 0x001c252c, 0x001d252d, 0x001f2730, 0x00262e37, 0x00283038, 0x00232b34, 0x001e242e, 0x001a202a, 0x00182029, 0x001a222b, 0x001d252f, 0x001e2833, 0x00242e38, 0x0027323c, 0x00283540, 0x0026333e, 0x00283440, 0x0024303c, 0x0024343f, 0x00283844, 0x00283844, 0x00273845, 0x00283a48, 0x00283b49, 0x002e4150, 0x00364a58, 0x00344958, 0x00324857, 0x00304655, 0x00304756, 0x00344a5a, 0x00374c5c, 0x00364c5c, 0x00374b5b, 0x00384c5c, 0x003e5464, 0x00435868, 0x00405465, 0x00354b5b, 0x002e4a5b, 0x004e7886, 0x0092b8bf, 0x00b8cccc, 0x00c7cccc, 0x00cccbcb, 0x00ccccca, 0x00cbccc9, 0x00cbccca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00c7cccc, 0x00bfcccc, 0x00a4c2c7, 0x005c7f8d, 0x001c3040, 0x00101925, 0x000a1018, 0x00040b11, 0x00060f16, 0x000c1820, 0x00122028, 0x0014222c, 0x0013232d, 0x0012232e, 0x0012232e, 0x0013232e, 0x0013222e, 0x0013222f, 0x00142330, 0x00142430, 0x00132632, 0x00142733, 0x00142834, 0x00142834, 0x00132632, 0x00122531, 0x00122531, 0x00132431, 0x00142430, 0x00142430, 0x00152530, 0x00152531, 0x00152832, 0x00162833, 0x00172833, 0x00182934, 0x00182934, 0x00182a35, 0x00192a36, 0x00192a36, 0x00192b35, 0x00192b35, 0x00182b35, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c36, 0x00182c37, 0x00182c38, 0x00192d38, 0x00182c38, 0x00172c37, 0x00162b37, 0x00162936, 0x00172937, 0x00172937, 0x00172937, 0x00162936, 0x000d1d28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0013242c, 0x00112a30, 0x00142e34, 0x00143338, 0x0016383c, 0x00183f43, 0x001b4649, 0x001d4c50, 0x001f5254, 0x0022585b, 0x00245d60, 0x00276970, 0x0032a1c4, 0x0034a7cb, 0x0036a8ca, 0x0037a8ca, 0x0037a9ca, 0x0037a9ca, 0x0037a9ca, 0x0037a9ca, 0x0037a9ca, 0x0037a9ca, 0x0037a9ca, 0x0037a8ca, 0x0036a8ca, 0x0036a8ca, 0x0034a7ca, 0x0034a6ca, 0x0034a6ca, 0x0033a6ca, 0x0033a5ca, 0x0032a5ca, 0x0031a4ca, 0x0031a4ca, 0x0030a4ca, 0x0030a4ca, 0x0030a4cb, 0x0030a4cc, 0x002ea0c7, 0x00298aa8, 0x0022606c, 0x001f5154, 0x001e4f51, 0x001d4b4e, 0x001c4649, 0x001a4347, 0x00183f43, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011222d, 0x0011232d, 0x0011232d, 0x0013242f, 0x00152631, 0x00172733, 0x00162633, 0x00152532, 0x00152532, 0x00162532, 0x0014232e, 0x0013222d, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013212b, 0x0012212b, 0x0012202a, 0x00111f28, 0x00101e28, 0x00101e28, 0x00101d27, 0x00101e28, 0x00101d27, 0x000f1c26, 0x000f1c26, 0x00101d28, 0x00101d28, 0x00101e28, 0x00111f29, 0x00111f29, 0x00111f29, 0x00111f29, 0x00111f2a, 0x00111f2b, 0x00111f2b, 0x0010202b, 0x0011202c, 0x0012202c, 0x0013212c, 0x00122029, 0x00101b24, 0x000c141e, 0x00080d15, 0x0005080c, 0x00040809, 0x0005080a, 0x00080b0f, 0x000c1219, 0x00121d25, 0x00253b47, 0x00678e9d, 0x00a4c7ca, 0x00c0cccc, 0x00cacccc, 0x00cbcccb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccca, 0x00c5cccc, 0x00acc4c7, 0x0070919c, 0x003c5868, 0x00243948, 0x001a2c37, 0x001a2934, 0x00293845, 0x00243341, 0x00202f3e, 0x001f303f, 0x002b404f, 0x00395261, 0x00385060, 0x00304757, 0x002c4050, 0x00243746, 0x00213441, 0x00263844, 0x00324350, 0x00253542, 0x0021303c, 0x0022303c, 0x001f2b35, 0x001a2630, 0x0016212a, 0x00172029, 0x001c232c, 0x001d242c, 0x001d242b, 0x00151c21, 0x00131a20, 0x00182026, 0x00171f25, 0x001c242c, 0x00242d36, 0x00263038, 0x00242d37, 0x00202831, 0x001f2831, 0x001d2630, 0x00242c36, 0x002a313c, 0x00303743, 0x00353c48, 0x00383f4b, 0x0038404c, 0x003a424e, 0x003c4451, 0x003c4451, 0x003a444f, 0x0039434d, 0x0038424d, 0x0039424e, 0x003b4450, 0x003a4451, 0x0037424f, 0x0037414f, 0x00374250, 0x00384250, 0x0038414e, 0x0036404b, 0x00343e48, 0x00313c46, 0x00303a45, 0x002d3740, 0x0028323a, 0x00253038, 0x00253038, 0x001c262d, 0x001c242d, 0x0028303a, 0x00242d36, 0x00253038, 0x00242e38, 0x00232e38, 0x00242e38, 0x00202831, 0x001e252d, 0x0020272f, 0x00232b34, 0x00202832, 0x00242c36, 0x002a323e, 0x0028303d, 0x002d3744, 0x00323d4a, 0x0036414e, 0x003c4653, 0x003d4855, 0x003c4855, 0x003c4856, 0x003c4856, 0x003d4856, 0x003d4755, 0x003c4654, 0x00394450, 0x0038424f, 0x0036414c, 0x0037424c, 0x0037424c, 0x0036404a, 0x0036404b, 0x0038404c, 0x00373f4a, 0x00343c47, 0x00313944, 0x002d3540, 0x0029313c, 0x00272f3a, 0x00242c37, 0x00202830, 0x001c242b, 0x001d262d, 0x001e242c, 0x001e242c, 0x00212830, 0x00222930, 0x0020262e, 0x001c222c, 0x001a202a, 0x00192029, 0x0019222b, 0x001d262f, 0x00202b34, 0x0025303a, 0x0025313c, 0x0024303c, 0x00222e3a, 0x00242f3c, 0x001f2c39, 0x00243440, 0x002b3c48, 0x00273844, 0x00263844, 0x00283b48, 0x002a3d4b, 0x002e4351, 0x00364c5b, 0x00344a5b, 0x00314858, 0x002d4453, 0x002c4453, 0x00324958, 0x00384e5d, 0x00394e5c, 0x00394c5b, 0x00384c5a, 0x003d5160, 0x00425766, 0x003c505f, 0x00304452, 0x0029404f, 0x00345563, 0x0068909b, 0x00a7c4c7, 0x00c0cccc, 0x00c8cccc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00c9cccc, 0x00c2cccc, 0x00adc8ca, 0x007496a4, 0x00253c4c, 0x00111c28, 0x000c1019, 0x00070c11, 0x0004090f, 0x00071118, 0x00101c24, 0x0014202b, 0x0014212c, 0x0012212d, 0x0012222e, 0x0011232c, 0x0011232c, 0x0011232d, 0x0011232d, 0x0011232d, 0x0011222e, 0x0011222e, 0x0011222e, 0x0011222f, 0x0011222f, 0x0011242e, 0x0011242e, 0x0011242e, 0x0012242e, 0x0013242f, 0x00142532, 0x00142633, 0x00142733, 0x00142833, 0x00152834, 0x00172834, 0x00172834, 0x00182935, 0x00192a35, 0x00192b36, 0x00182b37, 0x00182a36, 0x00182a36, 0x00182a36, 0x00182a36, 0x00182a36, 0x00182a37, 0x00182a37, 0x00182a37, 0x00182c38, 0x00192c39, 0x001a2d3a, 0x001a2d39, 0x00182c39, 0x00172c38, 0x00162935, 0x00152834, 0x00152834, 0x00152834, 0x00142834, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0011242c, 0x00112a30, 0x00142e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001b4649, 0x001d4c50, 0x00205356, 0x0022585b, 0x00245e60, 0x00266466, 0x002b7d8c, 0x003092ac, 0x003194ad, 0x003295ad, 0x003396ae, 0x003497ae, 0x003497ae, 0x003497ae, 0x003497ae, 0x003497ae, 0x003396ae, 0x003296ad, 0x003195ad, 0x003194ac, 0x003093ac, 0x003092ac, 0x003091ac, 0x002f90ab, 0x002e90ab, 0x002d8faa, 0x002d8faa, 0x002c8da9, 0x002c8ca9, 0x002b8ca8, 0x002a89a5, 0x00287e96, 0x00236570, 0x00205458, 0x001f5154, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183c40, 0x0016383c, 0x00153439, 0x00142e34, 0x00132c32, 0x0010282e, 0x0012242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011222d, 0x0011232d, 0x0012242e, 0x00152631, 0x00172833, 0x00172834, 0x00152633, 0x00142532, 0x00142432, 0x00152432, 0x0014232f, 0x0013222d, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0012212b, 0x0012212b, 0x0012202a, 0x00111f29, 0x00101e28, 0x00101e28, 0x00101d27, 0x00101d27, 0x00101d27, 0x000f1c26, 0x000f1c26, 0x00101d28, 0x00101d28, 0x00101e28, 0x00111f29, 0x00111f29, 0x00111f29, 0x00111f29, 0x00111f2a, 0x00111f2b, 0x00111f2b, 0x0010202b, 0x0010202b, 0x0012202b, 0x00121f28, 0x00101a23, 0x000c141c, 0x000a0e16, 0x0006080f, 0x00050709, 0x00050808, 0x0006080a, 0x00080c10, 0x000c141b, 0x0013202a, 0x002c4551, 0x00749faa, 0x00accacb, 0x00c4cccc, 0x00cacccb, 0x00cacccb, 0x00cbcccb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccc, 0x00cacccc, 0x00bccacc, 0x008cacb5, 0x00486c7a, 0x002c4454, 0x001f303d, 0x00182630, 0x0018242f, 0x00263440, 0x00243440, 0x001e2d3b, 0x001b2c39, 0x00283c4b, 0x0038505f, 0x00395261, 0x00304858, 0x002f4453, 0x00253747, 0x00203240, 0x00273844, 0x002f3e4b, 0x00243441, 0x0022303c, 0x00202e38, 0x001c2832, 0x0018242e, 0x0015202a, 0x0019242c, 0x001d252e, 0x001e262d, 0x001a2028, 0x00131a20, 0x00131a20, 0x00182127, 0x00192228, 0x001e272e, 0x00263039, 0x00263039, 0x00263038, 0x00202a33, 0x00222b34, 0x00202831, 0x00222b34, 0x00283039, 0x002d333e, 0x002f3540, 0x002e3641, 0x00303844, 0x00353d48, 0x0038404c, 0x0038404c, 0x0037404a, 0x00363e48, 0x00343c48, 0x00353d49, 0x0038404d, 0x0038414e, 0x0037404d, 0x0037404d, 0x0038414f, 0x0037404d, 0x0036404b, 0x00333c48, 0x00313b45, 0x00303944, 0x002f3842, 0x002c343d, 0x00283038, 0x00202830, 0x00242c34, 0x001c252c, 0x00192028, 0x00242c33, 0x00222a32, 0x001f272f, 0x00202831, 0x00212932, 0x00202830, 0x001b212a, 0x00181e26, 0x00181e26, 0x001c232b, 0x001f262f, 0x00202831, 0x00242b36, 0x00232b37, 0x002d3743, 0x00333c48, 0x00343d49, 0x0038424e, 0x003c4451, 0x003c4653, 0x003c4754, 0x003c4754, 0x003c4855, 0x003d4755, 0x003c4654, 0x003c4552, 0x003b4451, 0x0038434d, 0x0038434d, 0x0038414c, 0x0036404b, 0x0036404a, 0x0036404b, 0x00353e48, 0x00333c47, 0x002f3842, 0x002c343e, 0x002a323c, 0x0028303b, 0x00242d37, 0x00232b33, 0x001e272e, 0x00212930, 0x00212830, 0x0020262e, 0x0020272f, 0x001f252d, 0x001b212a, 0x001a202a, 0x00192029, 0x00192029, 0x0018212a, 0x001d262f, 0x001f2933, 0x00222d38, 0x0025313c, 0x00212d39, 0x001c2834, 0x001d2835, 0x001c2a37, 0x00223340, 0x00283946, 0x00253744, 0x00263844, 0x00283b47, 0x002b3e4b, 0x002c4250, 0x00344c5b, 0x00384f60, 0x0033495a, 0x002c4352, 0x002a4050, 0x00304655, 0x00394e5d, 0x003b4d5c, 0x00374857, 0x00354755, 0x003c4f5d, 0x00405462, 0x00384b58, 0x002a3c49, 0x00263b48, 0x00294450, 0x00446876, 0x0087acb6, 0x00b4cacc, 0x00c2cccc, 0x00cacccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccc, 0x00c5cccc, 0x00b4cbcc, 0x0087a7b2, 0x00314b5b, 0x00101e2b, 0x000c121a, 0x00080c11, 0x0004080d, 0x00040b11, 0x000b141d, 0x00141e28, 0x0015202b, 0x0013212c, 0x0012212c, 0x0011232c, 0x0011232c, 0x0011232c, 0x0011232d, 0x0011222d, 0x0012212e, 0x0012212e, 0x0012212e, 0x0012212e, 0x0012222e, 0x0011242e, 0x0011242e, 0x0011242e, 0x0012242e, 0x0013242f, 0x00132532, 0x00142733, 0x00142733, 0x00142733, 0x00142834, 0x00162834, 0x00172834, 0x00182934, 0x00192a35, 0x001a2b36, 0x00182b37, 0x00172935, 0x00172935, 0x00172935, 0x00172935, 0x00162935, 0x00172a36, 0x00182a37, 0x00182b38, 0x00182c38, 0x00192c39, 0x001a2d3b, 0x001a2d3b, 0x00192c3b, 0x00182c39, 0x00172935, 0x00152834, 0x00152834, 0x00152834, 0x00142834, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x00183a3e, 0x00194044, 0x001c4649, 0x001e4d50, 0x00205356, 0x0022595c, 0x00245f61, 0x00266466, 0x0029727b, 0x002c7d8b, 0x002d808c, 0x002e828e, 0x00308490, 0x00308490, 0x00308490, 0x00308490, 0x002e797e, 0x002d7577, 0x002c7476, 0x002c7475, 0x002c7274, 0x002b7071, 0x002a6e70, 0x00296c6f, 0x00286a6c, 0x0028686b, 0x00276668, 0x00266466, 0x00256264, 0x00245f61, 0x00245d60, 0x00235a5c, 0x0022585b, 0x00205558, 0x00205356, 0x001f5053, 0x001d4d50, 0x001c4a4d, 0x001b4649, 0x001a4347, 0x00194044, 0x00183d41, 0x0017383c, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011222d, 0x0011232d, 0x0013242f, 0x00152731, 0x00182834, 0x00182834, 0x00172834, 0x00152633, 0x00152432, 0x00142431, 0x0013222f, 0x0013222f, 0x0013222d, 0x0013222d, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0014212b, 0x0012202a, 0x00101e28, 0x00101e28, 0x00101d27, 0x00101d27, 0x00101d27, 0x000f1c26, 0x00101d27, 0x00101d28, 0x00101e29, 0x00111e29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f2a, 0x00131f2a, 0x00111f2b, 0x00111f2b, 0x00111e27, 0x00101b22, 0x000c141c, 0x00080f14, 0x00080910, 0x0005070c, 0x00040708, 0x00050708, 0x0006080a, 0x000a0c10, 0x000e141c, 0x0014242f, 0x0034525f, 0x0082adb7, 0x00b1cccc, 0x00c5cccc, 0x00cacccb, 0x00cacccb, 0x00cbcccb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccc, 0x00c6cccc, 0x00a8bec4, 0x00648794, 0x00335262, 0x00243947, 0x001a2834, 0x00111d26, 0x00121d28, 0x001e2c37, 0x0023323e, 0x001d2c39, 0x00182835, 0x00263947, 0x00364f5c, 0x00385160, 0x00324a59, 0x00314656, 0x00293c4b, 0x00223441, 0x00243441, 0x00263542, 0x00263542, 0x0024333f, 0x00212e39, 0x001c2a34, 0x00192630, 0x0017232c, 0x001b252e, 0x001f2830, 0x001c232a, 0x00151c24, 0x00111820, 0x00131a20, 0x00182026, 0x001a232a, 0x001e262d, 0x00273138, 0x00283239, 0x00263038, 0x00232d35, 0x00262f38, 0x00252d36, 0x00242d36, 0x00262d37, 0x00282e38, 0x00282f38, 0x00272f38, 0x0028303a, 0x002d353f, 0x00303843, 0x00303842, 0x00303841, 0x00303841, 0x00323842, 0x00333944, 0x00343c48, 0x00343e49, 0x00343d48, 0x00333d49, 0x00333d4a, 0x00333c48, 0x00333c48, 0x00303944, 0x00303944, 0x002f3842, 0x0029303b, 0x00282e38, 0x00252c34, 0x001b2128, 0x001f252d, 0x001e242c, 0x00171d25, 0x001c232a, 0x001d242c, 0x001c222a, 0x001d232c, 0x001f252f, 0x00192029, 0x00181e26, 0x0012161e, 0x00181d24, 0x001e242c, 0x001d242c, 0x00202730, 0x00222933, 0x00242c37, 0x002a333d, 0x002f3843, 0x00303843, 0x00333c47, 0x00363e4b, 0x0038404d, 0x00394350, 0x003b4450, 0x003b4451, 0x003b4453, 0x003b4452, 0x003a4451, 0x00394450, 0x0038424d, 0x0038424c, 0x0037414c, 0x0036404b, 0x00353f49, 0x00343e48, 0x00323c47, 0x00303a45, 0x002d3641, 0x002b333d, 0x002b333d, 0x0027303a, 0x00242c36, 0x00222a32, 0x00222a32, 0x00242c34, 0x00242c34, 0x00242b33, 0x00222931, 0x001d252c, 0x001c232b, 0x001b222b, 0x001c222c, 0x00182029, 0x0018202a, 0x00202832, 0x001c2630, 0x001c2831, 0x00222e38, 0x00232f3a, 0x001b2733, 0x00192532, 0x001e2c39, 0x00243441, 0x00243542, 0x00243642, 0x00283946, 0x00283c48, 0x00293e4a, 0x00283f4c, 0x00344b5a, 0x00385060, 0x00344b5c, 0x002f4554, 0x002a404f, 0x002c4352, 0x00364c5b, 0x00364958, 0x00314351, 0x00324352, 0x003c4e5c, 0x00405260, 0x00344654, 0x00263744, 0x00243744, 0x00243b48, 0x002c4a5a, 0x005f8392, 0x009ebfc5, 0x00bacccc, 0x00c8cccc, 0x00cccccc, 0x00cccbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccc, 0x00c7cccc, 0x00bacccc, 0x0095b4bc, 0x003f5968, 0x00142431, 0x000e151d, 0x00080d12, 0x0003080c, 0x0002080e, 0x00070e15, 0x000f1820, 0x00151f29, 0x0014222c, 0x0013222c, 0x0012222c, 0x0012222c, 0x0012222c, 0x0012222d, 0x0012222d, 0x0012212c, 0x0011202c, 0x0012212c, 0x0012212d, 0x0012222d, 0x0011242e, 0x0012242e, 0x0013242f, 0x00142430, 0x00142430, 0x00122633, 0x00132733, 0x00132733, 0x00132733, 0x00142834, 0x00152834, 0x00152834, 0x00182935, 0x00182b36, 0x00182b37, 0x00182a37, 0x00172935, 0x00172935, 0x00162834, 0x00142834, 0x00142834, 0x00162935, 0x00182b37, 0x00182c38, 0x00192c38, 0x001a2d39, 0x001a2d3a, 0x001a2d39, 0x00192c3a, 0x00182c39, 0x00172935, 0x00152834, 0x00152834, 0x00152834, 0x00142834, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x00183a3e, 0x001a4044, 0x001c4649, 0x001d4d50, 0x00205356, 0x0022595c, 0x00245f61, 0x00286c74, 0x00319ebe, 0x0034a7ca, 0x0035a8ca, 0x0036a8ca, 0x0037a9ca, 0x0038a9ca, 0x0038aaca, 0x0038aaca, 0x003498b0, 0x002e7779, 0x002d7576, 0x002c7475, 0x002c7274, 0x002b7072, 0x002a6e70, 0x00296c6f, 0x00286a6c, 0x0028686a, 0x00266568, 0x00266364, 0x00246062, 0x00245d60, 0x00235a5c, 0x0021585a, 0x00205558, 0x00205254, 0x001e5053, 0x001d4d50, 0x001c4a4d, 0x001c4649, 0x001a4347, 0x00194044, 0x00183d41, 0x0017383c, 0x00153439, 0x00143036, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011232d, 0x0012242e, 0x0013242f, 0x00152631, 0x00172833, 0x00182834, 0x00182935, 0x00172834, 0x00152532, 0x00142330, 0x0013222f, 0x0013222f, 0x0013222d, 0x0013222d, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0014212b, 0x0013202a, 0x00101e28, 0x00101e28, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101e29, 0x00111f2b, 0x00121f2a, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00131f29, 0x00111f2b, 0x00111f2a, 0x00101c24, 0x000c151c, 0x00091016, 0x00050a10, 0x0004060c, 0x0004060b, 0x00040608, 0x00050708, 0x0007080b, 0x000c0e12, 0x0010161e, 0x00152632, 0x0040606f, 0x0090b8c0, 0x00b5cccc, 0x00c6cccc, 0x00cacccb, 0x00cacccb, 0x00cbcccb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cacbcb, 0x00b5c8ca, 0x0084a0ae, 0x00446374, 0x002a4253, 0x0020303d, 0x0015212c, 0x000d1720, 0x00101924, 0x001b2833, 0x00202f3b, 0x001c2b37, 0x0013222f, 0x00213340, 0x00354c59, 0x00374f5d, 0x00324a58, 0x00304755, 0x002c404c, 0x00243743, 0x0020323f, 0x0022323f, 0x00263542, 0x00283643, 0x0023303b, 0x001e2c35, 0x001a2831, 0x0016232c, 0x001c2730, 0x001f2831, 0x00182028, 0x00131c23, 0x00131c23, 0x00151d24, 0x00182027, 0x001b232a, 0x001c252c, 0x00263037, 0x00283238, 0x00253036, 0x00253037, 0x00273039, 0x00283039, 0x00272e37, 0x00252c35, 0x00242a34, 0x00242a32, 0x00222a31, 0x00202830, 0x00232b32, 0x00272d37, 0x00262c36, 0x00252c34, 0x00282e36, 0x002c333c, 0x002e343f, 0x00303742, 0x00303843, 0x00303843, 0x00303843, 0x00303844, 0x00303843, 0x00303741, 0x002d343f, 0x002d343f, 0x002b313c, 0x00262a33, 0x0023282f, 0x0020242c, 0x00181c24, 0x00181c24, 0x001c2028, 0x00131820, 0x00141920, 0x00181d25, 0x00191d26, 0x00191c26, 0x001c2029, 0x00171b24, 0x00161922, 0x000d1018, 0x00171c22, 0x001c2228, 0x00181f25, 0x001f262d, 0x00242c34, 0x00283039, 0x002b343c, 0x002c343e, 0x002c343e, 0x002d3540, 0x00333945, 0x00363e4a, 0x0036404c, 0x0038414d, 0x0039424e, 0x0039434f, 0x00384250, 0x0038414f, 0x0036404c, 0x00343d49, 0x00323c46, 0x00313c46, 0x00313c46, 0x00303b45, 0x00303a45, 0x002f3944, 0x002c3741, 0x0029333d, 0x0029313c, 0x002a323d, 0x0028313c, 0x00252d38, 0x00232b33, 0x00232c33, 0x00242c34, 0x00242c34, 0x00242c34, 0x00202a30, 0x001b242c, 0x001c242c, 0x001c242e, 0x001c242e, 0x0018202a, 0x00161e27, 0x001e2730, 0x0019242c, 0x0018242c, 0x00202c35, 0x00232f38, 0x001c2834, 0x001a2633, 0x00222f3c, 0x00243442, 0x00223440, 0x00243441, 0x002a3c48, 0x002b3e4a, 0x002b3f4c, 0x0029404d, 0x00324958, 0x00344b5c, 0x00334859, 0x00304655, 0x002d4151, 0x002e4252, 0x00334656, 0x00324352, 0x00303f4d, 0x00334252, 0x003b4c5b, 0x003c4f5c, 0x002f404d, 0x00223140, 0x00243340, 0x00213340, 0x00203848, 0x003a596b, 0x00799ead, 0x00a9c8cb, 0x00bfcccc, 0x00c8cccc, 0x00cbcccc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00c7cccc, 0x00bccccc, 0x00a0bdc3, 0x004d6978, 0x00152632, 0x000e171d, 0x00080d13, 0x0004080c, 0x0001070c, 0x0004080e, 0x00090e17, 0x00111822, 0x0014202b, 0x0014222c, 0x0013222c, 0x0013222c, 0x0013222c, 0x0013222d, 0x0012212c, 0x0011202c, 0x0011202c, 0x0012212c, 0x0013222d, 0x0013222d, 0x0012242e, 0x0013242e, 0x00142430, 0x00152631, 0x00152631, 0x00122733, 0x00122733, 0x00122733, 0x00122733, 0x00132733, 0x00142834, 0x00142934, 0x00172a36, 0x00182b37, 0x00182c38, 0x00182a37, 0x00172935, 0x00162834, 0x00142834, 0x00142733, 0x00142834, 0x00162835, 0x00182b37, 0x00182c38, 0x00192c38, 0x00192c38, 0x001a2d39, 0x001a2d39, 0x00192c3a, 0x00182c39, 0x00172935, 0x00152834, 0x00152834, 0x00152834, 0x00152834, 0x000d1d28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0011242c, 0x00122a30, 0x00142e34, 0x00153439, 0x00183a3e, 0x001a4044, 0x001c4649, 0x001d4d50, 0x00205356, 0x0022595c, 0x00245e60, 0x002c869d, 0x0034a7cb, 0x002f8ca2, 0x002d8290, 0x002f8492, 0x00308593, 0x00308694, 0x00308794, 0x00359bb4, 0x0038aac9, 0x0030828c, 0x002d7577, 0x002c7476, 0x002c7374, 0x002c7173, 0x002b6f70, 0x00296c6f, 0x00286a6c, 0x0028686a, 0x00266467, 0x00256264, 0x00245f61, 0x00245c5e, 0x0022585b, 0x00205558, 0x00205254, 0x001e4f51, 0x001d4c50, 0x001c484c, 0x001b4649, 0x001a4347, 0x00183f43, 0x00183c40, 0x0017383c, 0x00153439, 0x00143036, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x00102229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0013212c, 0x0013212c, 0x0013212c, 0x0013232d, 0x0014242f, 0x00142430, 0x00152731, 0x00172833, 0x00182834, 0x00182935, 0x00172834, 0x00152532, 0x00142330, 0x0013222f, 0x0013222f, 0x0013222e, 0x0014232e, 0x0014232e, 0x0013222d, 0x0013222d, 0x0013232c, 0x0013232c, 0x0014222c, 0x0014212b, 0x00101e28, 0x00101e28, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101e29, 0x00111f2b, 0x00121f2b, 0x00131f2a, 0x00131f2a, 0x00131f2a, 0x00131f2a, 0x00121e29, 0x00111e29, 0x00111e29, 0x00111e29, 0x00101c27, 0x000d1720, 0x00081017, 0x00070c11, 0x0004070c, 0x0004050c, 0x0003050b, 0x00040609, 0x00040609, 0x0007080b, 0x000c0e13, 0x00101820, 0x00182b36, 0x004c6d7c, 0x009bc0c5, 0x00bbcccc, 0x00c8cccc, 0x00cacccb, 0x00cacccb, 0x00cbcccb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccc, 0x00cacccc, 0x00c8cbcc, 0x009cb7bd, 0x005c7b8a, 0x00354d5f, 0x00273948, 0x001c2833, 0x00101b24, 0x000c141c, 0x00101923, 0x001c2833, 0x00202e39, 0x001c2934, 0x0012202c, 0x0020303c, 0x00344855, 0x00364c5b, 0x00324957, 0x002d4450, 0x002b404d, 0x00263946, 0x0022323e, 0x0022303d, 0x0024333f, 0x00273440, 0x0024313c, 0x00202d37, 0x00182630, 0x0015232c, 0x001c2830, 0x001c2830, 0x00172028, 0x00141c24, 0x00161e25, 0x00172027, 0x00192128, 0x001c242b, 0x001e272e, 0x00252f36, 0x00283239, 0x00242f35, 0x00253037, 0x00272f38, 0x00262c36, 0x00252c35, 0x00252c35, 0x00232832, 0x0020252d, 0x001f252c, 0x001f252d, 0x0020272f, 0x00232932, 0x00212831, 0x0020262f, 0x00212830, 0x00252c34, 0x00292f38, 0x002b303a, 0x002b313b, 0x002c343d, 0x002f353f, 0x002d343e, 0x002c333c, 0x002c303a, 0x002a2f38, 0x002a2f38, 0x00252b33, 0x0020242b, 0x001d2027, 0x001a1d24, 0x0015181f, 0x00101219, 0x00161921, 0x000d1018, 0x000e1119, 0x00141720, 0x00181a23, 0x00151820, 0x0014171f, 0x0012141c, 0x0010141b, 0x000c0f16, 0x0014181f, 0x00161c21, 0x00191f24, 0x001d242b, 0x00242b32, 0x00293039, 0x002a323c, 0x002b333c, 0x002c323c, 0x002b323c, 0x002e3440, 0x00323944, 0x00343c48, 0x00363e48, 0x00363f49, 0x00363d48, 0x00363d49, 0x00343c48, 0x00313945, 0x00303842, 0x002e3641, 0x002d3640, 0x002d3640, 0x002d3640, 0x002e3741, 0x002d3741, 0x002c3741, 0x0029333c, 0x002c343e, 0x002d3640, 0x002a323d, 0x0028303b, 0x00273038, 0x00242d35, 0x00212931, 0x00202830, 0x00212931, 0x00202830, 0x001d262e, 0x001c242d, 0x001c242c, 0x001d252f, 0x001a222c, 0x00171f28, 0x001b242c, 0x0019242c, 0x001c262f, 0x00202c34, 0x00202c36, 0x001d2934, 0x001b2634, 0x00202e3c, 0x00243340, 0x00233440, 0x00243541, 0x002a3c48, 0x002c404d, 0x002d424e, 0x002b4250, 0x00304655, 0x00304857, 0x00304656, 0x002f4453, 0x002d4250, 0x00304251, 0x00324453, 0x0030404f, 0x00303d4c, 0x00344453, 0x003b4c5b, 0x00364856, 0x00253644, 0x001f2e3c, 0x0022303d, 0x001f2d39, 0x001c2f3e, 0x002c4456, 0x00547588, 0x008cb1be, 0x00b3cacc, 0x00c4cccc, 0x00cacccc, 0x00cbcccc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcc, 0x00c8cccc, 0x00c0cccc, 0x00a9c4c8, 0x005c7888, 0x00182b37, 0x000e171f, 0x00090e14, 0x0005090e, 0x0002050b, 0x0003040b, 0x0005080f, 0x000c1018, 0x00111a23, 0x0015202a, 0x0014212c, 0x0013222c, 0x0013222c, 0x0013222d, 0x0013222d, 0x0012212c, 0x0012212c, 0x0012212c, 0x0013222d, 0x0013222d, 0x0013242e, 0x0014242f, 0x00142530, 0x00152631, 0x00152631, 0x00132733, 0x00132733, 0x00132733, 0x00122733, 0x00142733, 0x00142834, 0x00142934, 0x00162a35, 0x00182a37, 0x00182b37, 0x00182a37, 0x00172935, 0x00162834, 0x00142834, 0x00142733, 0x00142834, 0x00162835, 0x00182a37, 0x00182c38, 0x00182c38, 0x00192c38, 0x001a2d39, 0x001a2d39, 0x00192d3a, 0x00182c39, 0x00182a37, 0x00152834, 0x00152834, 0x00152834, 0x00152834, 0x000d1d28, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0011242c, 0x00122a30, 0x00132e34, 0x00163439, 0x00183a3e, 0x001a4044, 0x001c4649, 0x001d4d50, 0x00205356, 0x0022585b, 0x00245e60, 0x002c89a1, 0x0034a6cb, 0x002c808e, 0x002b6f70, 0x002c7274, 0x002c7476, 0x002d7577, 0x002d7678, 0x003494aa, 0x0038aaca, 0x00308490, 0x002d7678, 0x002d7678, 0x002d7679, 0x002c7274, 0x002c7071, 0x002a6d6f, 0x00286a6c, 0x0028686a, 0x00266467, 0x00256163, 0x00245e60, 0x00235a5c, 0x0021585a, 0x00205356, 0x001f5053, 0x001d4c50, 0x001c484c, 0x001b4448, 0x001a4347, 0x00183f43, 0x00183c40, 0x0017383c, 0x00153439, 0x00143036, 0x00142e34, 0x00112a30, 0x0010282e, 0x0012242c, 0x00102229, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0012212c, 0x0012212c, 0x0013222d, 0x00142230, 0x00152331, 0x00162433, 0x00182634, 0x00182836, 0x00192836, 0x00192835, 0x00182834, 0x00152432, 0x00142330, 0x0013222d, 0x0012212c, 0x0013232c, 0x0014242c, 0x0014242d, 0x0014232e, 0x0014232e, 0x0014242d, 0x0014242c, 0x0014232c, 0x0014212b, 0x00111f29, 0x00111f29, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00131f29, 0x00131f29, 0x00131f2a, 0x00131f2b, 0x00131f2b, 0x00131f2b, 0x00131f2b, 0x00101e2a, 0x000f1e28, 0x000f1e28, 0x000f1c27, 0x000c1722, 0x000a111a, 0x00070c10, 0x0005080c, 0x0004050a, 0x0003040a, 0x00030509, 0x00030609, 0x00040609, 0x0006080c, 0x000b1014, 0x00121a23, 0x001b2f3a, 0x00527583, 0x00a2c3c7, 0x00bfcccc, 0x00cacccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00cccccc, 0x00c9cccc, 0x00c4cccc, 0x00b3c3c8, 0x00708f9c, 0x003e5c6c, 0x002c4252, 0x00223240, 0x0018212d, 0x000d141f, 0x000b101a, 0x00141b25, 0x001d2732, 0x00202c37, 0x001b2833, 0x0013202c, 0x001d2d38, 0x00304351, 0x00334858, 0x00304756, 0x002c424f, 0x002b3e4c, 0x00283845, 0x0024333f, 0x0022303c, 0x0022313c, 0x0023313c, 0x00202e38, 0x00223039, 0x0018242e, 0x0017232c, 0x001c2833, 0x001a2530, 0x0017212b, 0x00151e27, 0x00172028, 0x00182029, 0x0019222b, 0x001c242d, 0x00202831, 0x00253038, 0x0027333c, 0x00232f37, 0x00242f37, 0x00252f38, 0x00232b34, 0x00232b34, 0x00232a33, 0x0020272e, 0x001d242c, 0x001c242c, 0x001e272e, 0x00212930, 0x00212830, 0x00212830, 0x0020262e, 0x0020262e, 0x00212830, 0x00242a33, 0x00282c35, 0x002a2e38, 0x002c313a, 0x002d323b, 0x002c3139, 0x002c3038, 0x002a2f37, 0x00272c34, 0x00262b33, 0x0023282f, 0x001e2129, 0x001a1d24, 0x0016191f, 0x00111419, 0x000b0e14, 0x000f1218, 0x00080c11, 0x00090c11, 0x000f1217, 0x0014171c, 0x0013161c, 0x00101318, 0x00101317, 0x000c1014, 0x000b0d12, 0x00101217, 0x000e1418, 0x00131a1d, 0x00172024, 0x001c252b, 0x00232a33, 0x00252a34, 0x00282d37, 0x00282c36, 0x00282d36, 0x002c313a, 0x00303740, 0x00323a44, 0x00343c46, 0x00353c46, 0x00343a44, 0x00323844, 0x00303741, 0x002e343f, 0x002c323c, 0x002a303b, 0x002b313c, 0x0029313b, 0x0029313c, 0x002b333e, 0x002c3640, 0x002c3741, 0x002a343f, 0x002c3541, 0x002c3643, 0x0028303d, 0x0028303c, 0x0029333d, 0x00262f39, 0x00222a34, 0x00202831, 0x00202831, 0x00202833, 0x00212934, 0x001e2731, 0x0018222c, 0x001c2630, 0x001a242f, 0x0018222c, 0x001a242f, 0x001c2530, 0x001e2833, 0x001d2b34, 0x001d2b33, 0x001e2b33, 0x001c2832, 0x001d2c37, 0x0020303c, 0x00263842, 0x00263944, 0x00283b46, 0x002c404d, 0x002d4350, 0x002d4450, 0x002d4451, 0x00304653, 0x00304654, 0x00304452, 0x00304350, 0x00324350, 0x00344351, 0x0030404c, 0x00303f4c, 0x00364654, 0x003a4b58, 0x0031424f, 0x0020303c, 0x001f2e3a, 0x0022303b, 0x001e2934, 0x00182734, 0x00243747, 0x00395669, 0x00638799, 0x0095b9c3, 0x00b4cbcc, 0x00c1cccc, 0x00c9cccc, 0x00cbcccb, 0x00cbccc9, 0x00cbccc9, 0x00cbcbca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcc, 0x00c9cccc, 0x00c3cccc, 0x00b1c8cb, 0x006e8a9c, 0x001c3140, 0x000d1923, 0x000a0f15, 0x0006090e, 0x0003040b, 0x00020308, 0x00030408, 0x0005090d, 0x000b1116, 0x00111b24, 0x0014202c, 0x0014222d, 0x0013222d, 0x0012242e, 0x0012242e, 0x0011232d, 0x0011232d, 0x0013232f, 0x00142330, 0x00142330, 0x00142431, 0x00142532, 0x00152633, 0x00152633, 0x00152633, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142733, 0x00142834, 0x00142934, 0x00152a36, 0x00162a36, 0x00182a37, 0x00172935, 0x00142834, 0x00142733, 0x00142834, 0x00142834, 0x00152834, 0x00182a36, 0x00182b37, 0x00182c38, 0x00182d39, 0x001a2f3a, 0x00192e3a, 0x00182d3b, 0x00182c3a, 0x00192b38, 0x00182936, 0x00172834, 0x00172834, 0x00162834, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0011242c, 0x00122a30, 0x00132e34, 0x00163439, 0x00183a3e, 0x001a4044, 0x001c4649, 0x001d4c50, 0x00205356, 0x0022585b, 0x00245d60, 0x002c88a0, 0x0034a6cb, 0x002c808e, 0x002a6e70, 0x002c7173, 0x002c7475, 0x002d7576, 0x002d7678, 0x003494aa, 0x0038aaca, 0x00308490, 0x002d7678, 0x00318b9b, 0x0036a2c0, 0x003398b1, 0x002f8596, 0x002b7276, 0x00286a6c, 0x0028686a, 0x00266467, 0x00256163, 0x00245d60, 0x0022595c, 0x00205558, 0x00205254, 0x001d4d50, 0x001c4a4d, 0x001c4649, 0x001a4347, 0x00183f43, 0x00183c40, 0x0017383c, 0x00143439, 0x00143036, 0x00142e34, 0x00112a30, 0x00112a30, 0x0012242c, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0012212c, 0x0013222d, 0x0013222d, 0x00132230, 0x00142330, 0x00162433, 0x00182635, 0x00182836, 0x00192835, 0x00192835, 0x00182834, 0x00152432, 0x00142330, 0x0012212d, 0x0012212c, 0x0013232c, 0x0014242c, 0x0014242d, 0x0014232e, 0x0014232e, 0x0014242d, 0x0014242c, 0x0014232c, 0x0014212b, 0x00122029, 0x00111f29, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e28, 0x00131f29, 0x00131f29, 0x00131f2a, 0x00131f2b, 0x00131f2b, 0x00131f2a, 0x00121e2a, 0x00101f29, 0x000e1e27, 0x000d1c25, 0x000c1822, 0x000a131d, 0x00080c14, 0x0005080c, 0x0005050a, 0x00040408, 0x00030308, 0x00030408, 0x00030609, 0x00030609, 0x00050a0d, 0x000b1117, 0x00141d26, 0x001d323d, 0x005b808c, 0x00a9c7c9, 0x00c2cccc, 0x00cbcccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccccc, 0x00cbcccc, 0x00c7cccc, 0x00b9c9cb, 0x008fa8b5, 0x004e6c7d, 0x00334c5e, 0x00283c4a, 0x001e2c38, 0x00131c27, 0x000a101a, 0x000a0f18, 0x00151c26, 0x001d2830, 0x001e2a34, 0x001c2831, 0x0017242e, 0x00182834, 0x00283b49, 0x00324856, 0x00334858, 0x00304655, 0x002d404e, 0x00263544, 0x00243441, 0x0022323d, 0x0022313c, 0x00202e39, 0x001f2c38, 0x00202d38, 0x0018242e, 0x0018242d, 0x001f2b35, 0x001b2530, 0x0018222c, 0x0017202a, 0x00172029, 0x00182029, 0x001a222b, 0x001c242d, 0x00202831, 0x00242f37, 0x00253139, 0x00212d35, 0x00232e36, 0x00242c35, 0x00212933, 0x00202830, 0x001d262d, 0x001c242b, 0x001c242c, 0x001d262d, 0x0020282f, 0x00202830, 0x001f272f, 0x001f252e, 0x0020262e, 0x0020272e, 0x0020262f, 0x00222730, 0x00242a32, 0x00282c34, 0x00292e36, 0x002a2f37, 0x00282d35, 0x00282d35, 0x00252a32, 0x0022272e, 0x0020242b, 0x001d2228, 0x001a1c24, 0x0016181f, 0x00101418, 0x000c1014, 0x00080c10, 0x000c1014, 0x00090c11, 0x00080b0e, 0x00090c10, 0x000d1015, 0x00111419, 0x000d1014, 0x000e1114, 0x00080b0f, 0x00080a0f, 0x00090c10, 0x00080d10, 0x000e1416, 0x0011191c, 0x00141c20, 0x001a212a, 0x001e232c, 0x00252a34, 0x00232831, 0x0022272f, 0x00282c35, 0x002c313b, 0x002c333c, 0x002e343e, 0x002f353f, 0x002d343d, 0x002c323c, 0x00293038, 0x00282e36, 0x00272d35, 0x00272d35, 0x00272d37, 0x00242c35, 0x00242d36, 0x00273038, 0x002c343f, 0x002c3641, 0x002a3540, 0x002a3440, 0x002a3440, 0x0028323f, 0x0028323e, 0x002d3742, 0x0028313c, 0x00242c36, 0x00232b34, 0x001d2530, 0x001d2530, 0x00212934, 0x001f2834, 0x0018222c, 0x001a242f, 0x001c2630, 0x0019232d, 0x0019242e, 0x001d2832, 0x00202a34, 0x001e2b34, 0x00202d35, 0x00202e36, 0x001f2c36, 0x001e2c37, 0x0022313c, 0x00293b45, 0x00283c47, 0x00273c46, 0x00283e4b, 0x002c4350, 0x002f4552, 0x002e4451, 0x00304754, 0x00314754, 0x00334452, 0x00324350, 0x0031404d, 0x0032404f, 0x00313f4c, 0x0031404c, 0x00384854, 0x00384955, 0x002c3c48, 0x001b2b37, 0x001e2d38, 0x00212f3a, 0x001b2630, 0x0015212c, 0x00202e3c, 0x00304859, 0x0048687c, 0x007096a8, 0x009dbfc7, 0x00b9cccc, 0x00c4cccc, 0x00cbcccb, 0x00cbccc9, 0x00cbccc9, 0x00cbcbca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccccc, 0x00cacccc, 0x00c4cccc, 0x00b6cacc, 0x007a95a5, 0x00203644, 0x000e1a25, 0x000b1017, 0x00060910, 0x0003040a, 0x00020406, 0x00020405, 0x00030508, 0x00060a0e, 0x000d141c, 0x00131e2a, 0x0014212e, 0x0012232e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0013232f, 0x00142330, 0x00142430, 0x00142532, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142733, 0x00142834, 0x00142834, 0x00142934, 0x00152a35, 0x00172a37, 0x00172935, 0x00142733, 0x00142733, 0x00142834, 0x00142834, 0x00152834, 0x00182a36, 0x00182b37, 0x00182c38, 0x00192d39, 0x001a2f3a, 0x00192e3a, 0x00182d3b, 0x00192c3b, 0x001a2b38, 0x00182936, 0x00172834, 0x00172834, 0x00162834, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00122a30, 0x00132e34, 0x00163439, 0x00183a3e, 0x00194044, 0x001c4649, 0x001d4c50, 0x001f5254, 0x0022585b, 0x00245d60, 0x002c88a0, 0x0034a6cb, 0x002c7e8e, 0x002a6d6f, 0x002b7072, 0x002c7374, 0x002c7476, 0x002d7577, 0x003494aa, 0x0038aaca, 0x00308490, 0x002d7678, 0x00318c9d, 0x0038aacc, 0x0036a8c8, 0x0037a8ca, 0x0034a0bf, 0x002c8394, 0x0028696c, 0x00276467, 0x00256062, 0x00245c5f, 0x0022585b, 0x00205457, 0x001e5053, 0x001d4c50, 0x001c474b, 0x001a4347, 0x00194044, 0x00183c40, 0x0017383c, 0x00153439, 0x00143036, 0x00142e34, 0x00112a30, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0012212c, 0x0013212d, 0x0014222d, 0x00142130, 0x00142332, 0x00152433, 0x00172534, 0x00182735, 0x00182734, 0x00172632, 0x00172632, 0x00152432, 0x00142330, 0x0013222e, 0x0013222d, 0x0012212d, 0x0013222d, 0x0013222e, 0x00142330, 0x00142330, 0x0014232f, 0x0014232e, 0x0013222d, 0x0013212c, 0x0011202a, 0x00101f2a, 0x00101e28, 0x00101e28, 0x00101e28, 0x00101e29, 0x00101e2a, 0x00121f2b, 0x00121f2b, 0x00121f2c, 0x00121f2c, 0x00111e2c, 0x00111d2b, 0x00111c2a, 0x00101d29, 0x000f1c26, 0x000c1823, 0x000a131c, 0x00080d16, 0x0006080e, 0x0005060a, 0x00040408, 0x00040406, 0x00030306, 0x00030408, 0x00020508, 0x0003070a, 0x00060c0e, 0x000c1318, 0x00141f28, 0x001f3440, 0x00608893, 0x00aec8ca, 0x00c5cccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcc, 0x00c8cccc, 0x00c0cbcc, 0x009cb8c1, 0x00628394, 0x003b5669, 0x002d4354, 0x00253543, 0x001c2733, 0x00101823, 0x00090f18, 0x000a0f18, 0x00141c25, 0x001c272f, 0x001c2832, 0x00192630, 0x0017232d, 0x0016242e, 0x001e303c, 0x00304452, 0x00384c5b, 0x00354a59, 0x002f4251, 0x00243544, 0x00243440, 0x0023323e, 0x0021313c, 0x001e2c38, 0x001f2c38, 0x001d2b37, 0x00192531, 0x0018242e, 0x001f2b35, 0x001c2731, 0x0018222c, 0x0017202b, 0x0018202b, 0x00172029, 0x0018212a, 0x001a232c, 0x00202830, 0x001f2a32, 0x001f2b33, 0x00212d35, 0x00243038, 0x00252e37, 0x00242c35, 0x00202831, 0x001c252c, 0x001c252c, 0x001d262d, 0x001d262d, 0x001c252c, 0x001c242c, 0x001c242c, 0x001c222c, 0x001d242d, 0x001f252d, 0x001f252e, 0x00202730, 0x00222831, 0x00232931, 0x00242a32, 0x00242a32, 0x00232830, 0x0022272f, 0x001e232b, 0x001c2128, 0x001b2025, 0x00181c23, 0x00171920, 0x0014141c, 0x000b0e14, 0x000d1015, 0x000a0d12, 0x000b0e12, 0x00090c10, 0x00070a0d, 0x00080b0e, 0x00090c10, 0x000e1114, 0x000d1013, 0x000c0f12, 0x00070a0d, 0x0008090f, 0x00080a0f, 0x00060b0e, 0x000b1013, 0x000c1315, 0x000d1418, 0x00131920, 0x00181c24, 0x001d2229, 0x0021252c, 0x0023282f, 0x00252a32, 0x00262c34, 0x00252c34, 0x00262c35, 0x00282e36, 0x00262c35, 0x00242b32, 0x00232a31, 0x00252c33, 0x00272d34, 0x00272d34, 0x00242c34, 0x00232b33, 0x00232b34, 0x00273038, 0x002a333c, 0x002b343e, 0x0029333d, 0x0028323e, 0x002c3542, 0x002c3643, 0x002e3844, 0x00303a44, 0x0027313b, 0x00202a33, 0x001f2731, 0x001b232e, 0x001b232e, 0x00202833, 0x00212b35, 0x001e2832, 0x0019242e, 0x001b2530, 0x001b2530, 0x001b2530, 0x001f2834, 0x00202b36, 0x00212e38, 0x00202f38, 0x0023313a, 0x0024333c, 0x0022313c, 0x00273741, 0x002a3c46, 0x00293d48, 0x00283c48, 0x00283d4a, 0x002c4350, 0x00304654, 0x00304754, 0x00334855, 0x00344854, 0x00324350, 0x0032404e, 0x00313e4c, 0x00313d4c, 0x00313e4c, 0x0033414f, 0x00394855, 0x00374754, 0x00243440, 0x00182733, 0x001e2c38, 0x00212e38, 0x0018222c, 0x00101a24, 0x001b2734, 0x002c4050, 0x003d586c, 0x0053788b, 0x007ca4b4, 0x00a9c6ca, 0x00bdcccc, 0x00c7cccc, 0x00caccca, 0x00cbccc9, 0x00cbcbca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cbcbcb, 0x00c5cccc, 0x00b9cbcc, 0x00829baa, 0x00243948, 0x00101c26, 0x000b1017, 0x0005080f, 0x0003050b, 0x00020408, 0x00020404, 0x00020406, 0x00030709, 0x00070c13, 0x000e1721, 0x00111e2a, 0x0012222d, 0x0011232d, 0x0012242e, 0x0012242e, 0x0012242e, 0x0013232f, 0x00142330, 0x00142431, 0x00142532, 0x00162734, 0x00152633, 0x00152633, 0x00152633, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142733, 0x00142733, 0x00142834, 0x00142834, 0x00152934, 0x00172936, 0x00172935, 0x00142733, 0x00142733, 0x00142733, 0x00142834, 0x00152834, 0x00182a36, 0x00182b37, 0x00182c38, 0x00182c38, 0x00192e3a, 0x00182d39, 0x00172c39, 0x00172c38, 0x00182b38, 0x00182936, 0x00172834, 0x00172834, 0x00162834, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00122a30, 0x00132e34, 0x00163439, 0x00183a3e, 0x00194044, 0x001c4649, 0x001d4c50, 0x001f5254, 0x0021585a, 0x00245c5f, 0x002c88a0, 0x0033a6cb, 0x002c7d8d, 0x00296c6f, 0x002b7071, 0x002c7274, 0x002c7475, 0x002d7576, 0x003494aa, 0x0038aaca, 0x00308490, 0x002d7678, 0x00328c9d, 0x0038a9cb, 0x002f8390, 0x00308ca0, 0x0034a4c4, 0x0034a7ca, 0x002e8ea8, 0x0027686c, 0x00256062, 0x00245c5f, 0x0021585a, 0x00205356, 0x001e4f51, 0x001c4a4d, 0x001b4649, 0x001a4245, 0x00183d41, 0x00183a3e, 0x0015363b, 0x00153338, 0x00142e34, 0x00132c32, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0013202c, 0x0013212c, 0x0014212c, 0x00142130, 0x00142232, 0x00152433, 0x00162434, 0x00172534, 0x00172532, 0x00162530, 0x00152430, 0x00152432, 0x00142330, 0x0013222e, 0x0013222d, 0x0012212c, 0x0013222d, 0x0013222d, 0x00142330, 0x00142330, 0x0014232f, 0x0014232e, 0x0013222d, 0x0012212c, 0x0010202b, 0x0010202b, 0x00101e29, 0x00101e29, 0x00101e29, 0x000f1f29, 0x00101f2a, 0x00111f2b, 0x00111f2b, 0x00111f2c, 0x00111f2c, 0x00111e2c, 0x00111c2b, 0x00111c2a, 0x00101c28, 0x000e1924, 0x000b141e, 0x00080f16, 0x00050910, 0x0004060b, 0x00040609, 0x00040408, 0x00030305, 0x00030304, 0x00030407, 0x00020508, 0x00030709, 0x00080c0f, 0x000e141a, 0x0016202a, 0x00223a46, 0x0069929c, 0x00b3cacb, 0x00c7cccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cbcbcc, 0x00c4cccc, 0x00aec1c7, 0x007394a3, 0x00446578, 0x00334b5d, 0x002a3c4c, 0x0021303c, 0x0018232f, 0x000c141e, 0x00060c14, 0x00090e17, 0x00141c25, 0x001a242d, 0x001a2630, 0x00182530, 0x001a2630, 0x0017242e, 0x001a2a37, 0x00304451, 0x003e5161, 0x00384c5c, 0x00304453, 0x00283847, 0x00243440, 0x0023323e, 0x0021313c, 0x001c2b37, 0x001f2d38, 0x001c2a35, 0x001a2632, 0x0018232e, 0x001f2a34, 0x001c2731, 0x0018222c, 0x0019232e, 0x001b242f, 0x00172029, 0x0018202a, 0x0018212a, 0x001f2730, 0x001b262e, 0x001b2730, 0x00202c35, 0x00242f38, 0x00242d36, 0x00232c34, 0x00202830, 0x001d272e, 0x001e272e, 0x001f282f, 0x001e272e, 0x001c242c, 0x001d262d, 0x001f2730, 0x001c232c, 0x001c222b, 0x001c242b, 0x001d242c, 0x001f252d, 0x001f252e, 0x0020262e, 0x0020282f, 0x00212830, 0x0020252d, 0x001e232b, 0x001a1e26, 0x001a1e25, 0x00191d24, 0x00181c22, 0x00171920, 0x0014141c, 0x000a0c13, 0x000d1015, 0x000a0d12, 0x00080b10, 0x00080c10, 0x00070b0d, 0x00080c0f, 0x000a0d10, 0x000e1214, 0x000c1013, 0x000b0e11, 0x00060a0d, 0x0008090e, 0x00080b0f, 0x00060c0e, 0x00070c0f, 0x00080e10, 0x000a1114, 0x000e141a, 0x00181c22, 0x00171c22, 0x00181d24, 0x0021262c, 0x0024282f, 0x00232830, 0x0020252d, 0x001f252d, 0x00222830, 0x00232830, 0x0022272f, 0x00242931, 0x00272d34, 0x00282e34, 0x00252c32, 0x00222930, 0x00222a31, 0x00222a32, 0x00283039, 0x0029313c, 0x002a333d, 0x0026303b, 0x0026303c, 0x0028333f, 0x0028313e, 0x002b3440, 0x002a343d, 0x00242d36, 0x001d2730, 0x001c2430, 0x001c2430, 0x001d2630, 0x00202834, 0x00232c37, 0x00242d38, 0x001c2631, 0x001c2530, 0x001e2833, 0x00202a35, 0x00212c38, 0x00242f3b, 0x0025333c, 0x00203039, 0x0023323c, 0x00283741, 0x00263641, 0x00283843, 0x002b3c47, 0x002a3f49, 0x002b404b, 0x002c414e, 0x002e4452, 0x00314855, 0x00334955, 0x00364b56, 0x00364854, 0x0033424f, 0x0033404d, 0x00313d4b, 0x00303c4b, 0x00313e4c, 0x00364451, 0x003b4956, 0x00354451, 0x00202e3a, 0x00172531, 0x001f2d38, 0x00212e38, 0x00172029, 0x000e1520, 0x0017212d, 0x0026384a, 0x00375064, 0x0043647b, 0x005e8599, 0x008eb2bf, 0x00b3cacc, 0x00c2cccc, 0x00c9cccb, 0x00cbccc9, 0x00cbcbca, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cbcbcb, 0x00c7cccc, 0x00bdcbcc, 0x0088a1b0, 0x002a3e4f, 0x00121d2a, 0x000c1119, 0x00060910, 0x0004060b, 0x00040408, 0x00020405, 0x00010405, 0x00010407, 0x0003080c, 0x00070f17, 0x000d1822, 0x0011202b, 0x0011232d, 0x0012242e, 0x0012242e, 0x0012242e, 0x0013232f, 0x00142330, 0x00142431, 0x00142532, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142733, 0x00142733, 0x00142834, 0x00142834, 0x00152834, 0x00162935, 0x00172935, 0x00142733, 0x00142733, 0x00142733, 0x00142834, 0x00142834, 0x00172935, 0x00182a36, 0x00182a37, 0x00172b38, 0x00172c38, 0x00172c38, 0x00162b37, 0x00162b37, 0x00172a36, 0x00172935, 0x00172834, 0x00172834, 0x00162734, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00194044, 0x001b4649, 0x001d4c50, 0x001f5154, 0x00205659, 0x00245c5e, 0x002c87a0, 0x0033a6cb, 0x002b7d8c, 0x00296c6e, 0x002b6f70, 0x002c7173, 0x002c7374, 0x002c7476, 0x003494a9, 0x0038aaca, 0x00308490, 0x002d7678, 0x00328c9d, 0x0038a9cb, 0x002e7d87, 0x002b7072, 0x002c7881, 0x00329bb8, 0x0034a7cb, 0x002c8ca4, 0x00256264, 0x00245c5f, 0x0021585a, 0x00205356, 0x001f4f51, 0x001d4a4d, 0x001a4448, 0x001a4044, 0x00183c40, 0x0017383c, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f2b, 0x0013202c, 0x0013202c, 0x0013202e, 0x0014202e, 0x00142130, 0x00152332, 0x00162432, 0x00152430, 0x0014242f, 0x00152430, 0x00152431, 0x00142330, 0x0013222e, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0014232f, 0x00142330, 0x0014222e, 0x0014222c, 0x0014212c, 0x0012202c, 0x0010202b, 0x00101f2b, 0x00101e29, 0x00101e29, 0x00101e29, 0x000f1e29, 0x00101f2a, 0x00111f2b, 0x00111f2b, 0x00111f2c, 0x00101f2c, 0x00101e2c, 0x00111d2b, 0x00101c28, 0x00101a25, 0x000c1520, 0x00080f17, 0x00050910, 0x0003060c, 0x00020409, 0x00030408, 0x00030408, 0x00030405, 0x00030404, 0x00030407, 0x00020408, 0x00030609, 0x00080c10, 0x000f151a, 0x0017212c, 0x0024404d, 0x007299a3, 0x00b7cbcc, 0x00c8cccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cbcbcb, 0x00c8cccc, 0x00b8c7ca, 0x0088a4b1, 0x00507184, 0x00375468, 0x002f4354, 0x00253544, 0x001c2a35, 0x00141e28, 0x000a1018, 0x00050b13, 0x00080d16, 0x00141c25, 0x0019242d, 0x001a2630, 0x00192530, 0x001b2731, 0x0016232e, 0x00182734, 0x002e3f4e, 0x00405261, 0x00394d5d, 0x00314454, 0x002a3c4b, 0x00263644, 0x00253441, 0x0022303d, 0x001e2c39, 0x001f2c38, 0x001c2934, 0x001c2833, 0x0017232e, 0x001c2832, 0x001e2833, 0x001a242f, 0x001a242f, 0x001c2630, 0x0019232c, 0x001a242c, 0x001a232c, 0x001d262f, 0x001a242d, 0x001c2830, 0x001e2a32, 0x001f2a33, 0x00212b34, 0x00202832, 0x001e2730, 0x001e272e, 0x0020282f, 0x001e272e, 0x001c252c, 0x001c242b, 0x001c242c, 0x001f262d, 0x001f242c, 0x001e242c, 0x001e242c, 0x001c232a, 0x001c232a, 0x001c222a, 0x001d232a, 0x001e242c, 0x0020242c, 0x0020232b, 0x001d2028, 0x001a1c24, 0x00181b21, 0x00181b22, 0x00191c23, 0x0016181f, 0x00101218, 0x000a0d12, 0x000d1014, 0x00090c11, 0x00080a0f, 0x00090c10, 0x00080a0d, 0x000a0c0f, 0x000b0c10, 0x000e1114, 0x000c1013, 0x000a0d10, 0x00070a0c, 0x00080b0e, 0x000a0c10, 0x00080d10, 0x00070c0f, 0x00080c10, 0x000a1014, 0x000e1218, 0x0017191f, 0x0015181f, 0x0014181f, 0x001c2026, 0x001f242a, 0x001f242b, 0x001c2128, 0x001c2129, 0x0021272e, 0x00242830, 0x00242830, 0x00222830, 0x00242b30, 0x00242b30, 0x0021282e, 0x00202730, 0x00212933, 0x00232b34, 0x00273038, 0x0029313c, 0x0028313c, 0x00242e39, 0x00242d39, 0x00242e3b, 0x00252e3b, 0x0028303c, 0x00262f38, 0x00212a33, 0x001c252e, 0x001b232c, 0x001b212c, 0x001c222d, 0x001c232e, 0x00222c36, 0x00242f39, 0x00202b35, 0x001c2833, 0x001d2933, 0x00212d38, 0x00263240, 0x00273441, 0x00283844, 0x00243440, 0x0022333e, 0x00283945, 0x00283946, 0x00283a47, 0x002c3e4b, 0x002f444f, 0x00314652, 0x00334855, 0x00334956, 0x00334a57, 0x00344a56, 0x00364855, 0x00364653, 0x0034414f, 0x00333e4b, 0x00313c49, 0x00303b4a, 0x00333e4c, 0x00374452, 0x00394754, 0x00303e4a, 0x001a2834, 0x00182631, 0x00202f3a, 0x00202b35, 0x00141c26, 0x000c121c, 0x00131c27, 0x00233243, 0x0032485b, 0x003f5b70, 0x004c7085, 0x006c92a6, 0x009dbdc7, 0x00bbcbcc, 0x00c7cccc, 0x00c9cccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cbcccb, 0x00c8cccc, 0x00bdcccc, 0x008ca6b3, 0x002d4253, 0x00141f2b, 0x000e1219, 0x00080b11, 0x0004060c, 0x00030408, 0x00030405, 0x00020404, 0x00020406, 0x0002050a, 0x00030810, 0x00080e18, 0x000f1a24, 0x0013202c, 0x0013232d, 0x0012242e, 0x0012242e, 0x0013232f, 0x00142330, 0x00142431, 0x00142533, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142733, 0x00142733, 0x00142733, 0x00142834, 0x00152834, 0x00152834, 0x00152834, 0x00142733, 0x00142733, 0x00142733, 0x00142734, 0x00142834, 0x00152834, 0x00162834, 0x00172935, 0x00152935, 0x00162a36, 0x00162a36, 0x00162935, 0x00162935, 0x00162935, 0x00152834, 0x00162834, 0x00162734, 0x00162734, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00194044, 0x001b4649, 0x001d4b4e, 0x00205154, 0x00205659, 0x00245c5e, 0x002c87a0, 0x0033a6cb, 0x002b7d8c, 0x00296b6d, 0x002a6d6f, 0x002c7072, 0x002c7274, 0x002c7475, 0x003394a9, 0x0038aaca, 0x00308490, 0x002d7678, 0x00318c9d, 0x0038a9cb, 0x002e7d87, 0x002c7072, 0x002a6e70, 0x002a7278, 0x00319cba, 0x0032a4c8, 0x00287888, 0x00245c5f, 0x0021585a, 0x00205356, 0x001f4f51, 0x001d4a4d, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00143338, 0x00153036, 0x00132c32, 0x00102a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101e28, 0x00111f28, 0x00111f29, 0x00111f2a, 0x0012202a, 0x0012202c, 0x0012202c, 0x0013222e, 0x0014232e, 0x0014242e, 0x0014242f, 0x00142530, 0x0013242f, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0014232e, 0x0015232e, 0x0014222d, 0x0014212b, 0x0014212b, 0x0013202b, 0x00111f2b, 0x00101e2a, 0x00111d28, 0x00111c28, 0x00111e29, 0x00101e29, 0x00101e29, 0x00111f2b, 0x00111f2b, 0x00101f2a, 0x000f1f29, 0x00101f2a, 0x00111e2a, 0x000f1a24, 0x000c151f, 0x000a1018, 0x00070910, 0x0003060b, 0x00020509, 0x00010408, 0x00010408, 0x00010408, 0x00010405, 0x00020405, 0x00020508, 0x00020609, 0x0004080a, 0x00080d10, 0x0010161b, 0x0018232d, 0x00284452, 0x007ba2ab, 0x00bccccc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00c8cccc, 0x00bccacc, 0x0094afbb, 0x005d7c8f, 0x003e5b6e, 0x00324a5c, 0x002b3d4c, 0x0023303e, 0x001c2731, 0x00141c25, 0x000b1018, 0x00060b13, 0x00070d15, 0x00131c24, 0x0019242d, 0x001a2730, 0x0019272f, 0x0019262f, 0x0014222c, 0x00172431, 0x00293948, 0x003a4e5d, 0x00344b5a, 0x002f4654, 0x002a3f4e, 0x00253948, 0x00243644, 0x0023323e, 0x001f2d39, 0x001c2a35, 0x001a2832, 0x001a2832, 0x0018252f, 0x001d2a34, 0x001f2c35, 0x001c2731, 0x001c2731, 0x0018252f, 0x00192530, 0x001c2832, 0x001c2731, 0x001a2630, 0x001c2731, 0x001e2a34, 0x001d2832, 0x001d2832, 0x00202833, 0x00202832, 0x001f2730, 0x001e272f, 0x00202830, 0x001c242c, 0x00182029, 0x001b232c, 0x001b232c, 0x001d242d, 0x001d232b, 0x0020252c, 0x0020242c, 0x001e2329, 0x001d2128, 0x001c2027, 0x001b2026, 0x001c2127, 0x001d2228, 0x001e2128, 0x001c2026, 0x00181b22, 0x0014181e, 0x00171920, 0x00181c22, 0x0013161c, 0x000d1015, 0x000b0e12, 0x000a0d11, 0x00080b10, 0x0008090d, 0x0008090c, 0x00090b0e, 0x000b0c10, 0x000c0e11, 0x00101215, 0x000c1013, 0x00080c0f, 0x0006090c, 0x00080a0e, 0x000a0c10, 0x000c0e11, 0x000a0c10, 0x000a0c10, 0x000d0f14, 0x000f1016, 0x0014161c, 0x0010141b, 0x0010151c, 0x00181e24, 0x00181e24, 0x00181d24, 0x00191e24, 0x001a1f25, 0x001d222a, 0x0022272f, 0x00212730, 0x001f252d, 0x001e242c, 0x0020262e, 0x001f262e, 0x00202730, 0x00202831, 0x00212932, 0x00252d37, 0x00283039, 0x00272f3a, 0x00232d38, 0x00222c38, 0x00212b38, 0x00232d39, 0x00242d38, 0x00222b34, 0x00202830, 0x001c242c, 0x001c232c, 0x001c222c, 0x001d242e, 0x001c242e, 0x00202932, 0x00222d37, 0x00202c37, 0x001f2c36, 0x001c2a34, 0x00213039, 0x002a3946, 0x00293b48, 0x00283c48, 0x00273b48, 0x00243845, 0x00273a48, 0x00283b48, 0x002b404d, 0x002f4451, 0x00314855, 0x00344a58, 0x00344c5a, 0x00364e5d, 0x00374c5b, 0x00364957, 0x00334351, 0x0032404f, 0x0033404d, 0x00303c48, 0x00313b47, 0x00313b48, 0x0034404d, 0x00374552, 0x00354450, 0x00263540, 0x0015242f, 0x001b2934, 0x00202f39, 0x001d2831, 0x00111820, 0x00090e18, 0x00111924, 0x00202e3d, 0x002f4355, 0x003b556a, 0x0043647a, 0x0051778e, 0x007aa0b3, 0x00a7c4ca, 0x00bdcccc, 0x00c6cccc, 0x00cacbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbca, 0x00cbccc9, 0x00cbccca, 0x00c9cbca, 0x00bdcccb, 0x008facb7, 0x00314858, 0x0014202c, 0x000e1319, 0x00070c11, 0x0002070b, 0x00030407, 0x00020405, 0x00020405, 0x00020406, 0x00020409, 0x0002050c, 0x00050910, 0x00091118, 0x00121c24, 0x0014202c, 0x0013222d, 0x0013222e, 0x00132331, 0x00122431, 0x00132432, 0x00142433, 0x00142533, 0x00142733, 0x00142733, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00142633, 0x00132632, 0x00142733, 0x00142733, 0x00152834, 0x00162834, 0x00162834, 0x00152633, 0x00152633, 0x00152633, 0x00162734, 0x00162734, 0x00162734, 0x00162834, 0x00172834, 0x00172834, 0x00172834, 0x00172834, 0x00172834, 0x00172834, 0x00142834, 0x00142834, 0x00142734, 0x00162734, 0x00162734, 0x000d1d27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001a4448, 0x001d4b4e, 0x00205154, 0x00205558, 0x00225a5c, 0x002c87a0, 0x0032a5cb, 0x002a7c8c, 0x00286a6c, 0x00296c6f, 0x002b6f70, 0x002c7173, 0x002c7374, 0x003393a9, 0x0038aaca, 0x00308490, 0x002e7577, 0x00318c9d, 0x0038a9cb, 0x002e7d87, 0x002c7072, 0x002a6e70, 0x00296b6d, 0x002a7783, 0x0031a3c6, 0x002e98b8, 0x00245e62, 0x0021585a, 0x00205356, 0x001e4f51, 0x001d4a4d, 0x001a4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00143338, 0x00143036, 0x00132c32, 0x00102a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101d27, 0x00101e28, 0x00101e28, 0x00101e28, 0x00111f28, 0x00111f2b, 0x0011202b, 0x0012202c, 0x0012212c, 0x0013222d, 0x0014242f, 0x00152530, 0x0014242f, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0014222d, 0x0014222d, 0x0014222c, 0x0013202a, 0x0013202a, 0x0013202b, 0x00111f2b, 0x00101e2a, 0x00111c28, 0x00111c28, 0x00111e29, 0x00101e29, 0x00101e29, 0x00111f2b, 0x00111f2b, 0x00101f2a, 0x00101e29, 0x00101e2a, 0x00101c28, 0x000c1520, 0x00080f18, 0x0006090f, 0x0004060b, 0x00030508, 0x00030408, 0x00020407, 0x00010407, 0x00000407, 0x00000405, 0x00000405, 0x00010508, 0x00020609, 0x0004080a, 0x00090d10, 0x0010161b, 0x0018242e, 0x002c4855, 0x0080a8b0, 0x00becccc, 0x00cccacc, 0x00cccbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00c9cccc, 0x00c0cbcc, 0x00a4bcc4, 0x006a8a9d, 0x00436277, 0x00385063, 0x002f4454, 0x00283846, 0x00202d39, 0x001a242f, 0x00111923, 0x00091018, 0x00060b14, 0x00070c15, 0x00111822, 0x001a232c, 0x0019242f, 0x0018242c, 0x0017232b, 0x00132028, 0x0014222e, 0x00233240, 0x00304655, 0x00314958, 0x002f4756, 0x002c4150, 0x00283d4c, 0x00263a48, 0x00243440, 0x0022303c, 0x001d2b35, 0x001c2a34, 0x001d2b34, 0x00192731, 0x001e2c35, 0x001e2b35, 0x001c2832, 0x001c2832, 0x0017242f, 0x001a2831, 0x001c2a34, 0x00192630, 0x001b2831, 0x00202c36, 0x00212d37, 0x001f2b34, 0x00202c36, 0x00202b35, 0x00202a33, 0x00202932, 0x00212931, 0x00202930, 0x001b232b, 0x0019222b, 0x001c242e, 0x001c242d, 0x001c242d, 0x001c222b, 0x0020242b, 0x001e2329, 0x001c2027, 0x001c1f25, 0x001b1e24, 0x001a1e23, 0x001a2024, 0x001a1f24, 0x001b1e24, 0x001b1d23, 0x00161920, 0x0014181c, 0x0015181d, 0x00161920, 0x0011141b, 0x000c0f14, 0x00090d10, 0x000b0e11, 0x00080c0f, 0x0006080c, 0x0006080b, 0x000a0c0f, 0x000c0e11, 0x000e1013, 0x00101215, 0x000d1014, 0x00080b0e, 0x0006090c, 0x0008090d, 0x000a0c0f, 0x000c0d11, 0x000a0c0f, 0x000a0c0f, 0x000d0f14, 0x000e1015, 0x0014161c, 0x000c1118, 0x000f141a, 0x00161c23, 0x00151b23, 0x00141820, 0x00151a20, 0x00171c22, 0x001c2028, 0x0020242d, 0x00202630, 0x001f252e, 0x001c232c, 0x001c232c, 0x001c252d, 0x00202830, 0x00202830, 0x00202830, 0x00242c35, 0x00262e38, 0x00242c38, 0x00222c36, 0x00222c38, 0x00202a36, 0x00212b37, 0x00222a36, 0x001e2530, 0x001d262e, 0x001c242c, 0x001c242c, 0x001c232c, 0x00212831, 0x00212a33, 0x001f2831, 0x00202c34, 0x00232f39, 0x00202c36, 0x001f2d37, 0x0025343f, 0x002b3c48, 0x002d404e, 0x002c414f, 0x002b414e, 0x00283f4c, 0x00273d4b, 0x00283f4c, 0x002c4250, 0x00304654, 0x00314857, 0x00344a58, 0x00354d5c, 0x00395262, 0x00384c5c, 0x00354655, 0x00303e4d, 0x002d3b49, 0x002f3c48, 0x002f3b45, 0x002f3944, 0x00303a46, 0x0034404d, 0x00374552, 0x0030404c, 0x001c2c37, 0x0013222c, 0x001d2c36, 0x00213039, 0x001c2830, 0x0010151d, 0x00080c15, 0x000f1620, 0x001d2a38, 0x002d3f50, 0x00385064, 0x003e5d73, 0x00466881, 0x005a829a, 0x0084adbc, 0x00adc8cb, 0x00c0cccc, 0x00c9cccc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbca, 0x00cbccc9, 0x00cbccca, 0x00cacbca, 0x00bdccca, 0x0090adb7, 0x00334959, 0x0014202b, 0x000e1318, 0x00060c10, 0x0002070b, 0x00030407, 0x00020404, 0x00020404, 0x00020405, 0x00020408, 0x00010409, 0x0004070c, 0x00080c12, 0x000e141c, 0x00141c28, 0x0014212c, 0x0014222e, 0x00132431, 0x00122432, 0x00132433, 0x00132433, 0x00142533, 0x00142733, 0x00142733, 0x00152734, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00142633, 0x00132632, 0x00132632, 0x00142733, 0x00152834, 0x00162834, 0x00162734, 0x00152633, 0x00152633, 0x00152633, 0x00162734, 0x00162734, 0x00162734, 0x00162734, 0x00162734, 0x00162834, 0x00162834, 0x00162834, 0x00162834, 0x00162834, 0x00142733, 0x00142733, 0x00142633, 0x00152633, 0x00152633, 0x000d1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001d4b4e, 0x001e5053, 0x00215558, 0x00235a5c, 0x002b87a0, 0x0032a5cb, 0x002a7c8c, 0x0028696c, 0x00296c6e, 0x002b6f70, 0x002b7072, 0x002c7274, 0x003393a9, 0x0037a9ca, 0x0030848f, 0x002e7577, 0x00318c9d, 0x0038a9cb, 0x002d7d86, 0x002b7072, 0x002a6e70, 0x00296c6e, 0x0028686b, 0x002c8ba4, 0x0031a4c9, 0x00277281, 0x0022585b, 0x00205457, 0x001e4f51, 0x001c4a4d, 0x001b4649, 0x00194044, 0x00183d41, 0x0017383c, 0x00143439, 0x00153036, 0x00132c32, 0x00102a30, 0x0011282e, 0x0012242c, 0x0012242c, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101d27, 0x00101e28, 0x00101e28, 0x00111e27, 0x00111d26, 0x00111e28, 0x00111f29, 0x0012202c, 0x0013202c, 0x0014212d, 0x0014232e, 0x0014242f, 0x0014242f, 0x0013222d, 0x0012212c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0013212c, 0x0014212c, 0x0013202c, 0x00121f2b, 0x00121f2b, 0x00121f2b, 0x00111f2b, 0x00101e2a, 0x00111c28, 0x00111c28, 0x00111e29, 0x00111e29, 0x00111e29, 0x00121f2b, 0x00121f2b, 0x00111f2b, 0x00111f2a, 0x00101c28, 0x000e1824, 0x0009111c, 0x00060c14, 0x0004070c, 0x00030508, 0x00030406, 0x00030405, 0x00020404, 0x00020404, 0x00020404, 0x00010404, 0x00010404, 0x00020508, 0x00020609, 0x0004080a, 0x00090d10, 0x0010161b, 0x001a242c, 0x002f4b55, 0x0081aab0, 0x00becccc, 0x00cbcbcc, 0x00cccbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccca, 0x00ccccca, 0x00cacccb, 0x00c4cccc, 0x00afc4c8, 0x007c9bac, 0x004c6c80, 0x003b566b, 0x0033495c, 0x002b3e4d, 0x00243441, 0x001d2a36, 0x0018222c, 0x00101820, 0x00070c15, 0x00040811, 0x00070c14, 0x0010151f, 0x0019202c, 0x0018222c, 0x0016222a, 0x00142028, 0x00121e26, 0x00111d28, 0x001c2a37, 0x002c404d, 0x00344b59, 0x00314858, 0x002c4352, 0x00294050, 0x00253b48, 0x00243540, 0x0025343f, 0x001f2c37, 0x00202d37, 0x001d2b35, 0x00182630, 0x001f2d37, 0x001d2b34, 0x001c2933, 0x00192730, 0x001a2831, 0x001e2c35, 0x001c2933, 0x00192630, 0x001f2c35, 0x00222e38, 0x00222e38, 0x0024303a, 0x0024303c, 0x0025303b, 0x00212c35, 0x00222c35, 0x00242c35, 0x00202932, 0x001d262f, 0x00202831, 0x00202831, 0x001f2730, 0x001a222b, 0x001c212a, 0x0020242b, 0x001d2228, 0x001b1e25, 0x001b1e25, 0x001b1e25, 0x00191d24, 0x001a1f24, 0x001a1f25, 0x00181c23, 0x00191c23, 0x00171a22, 0x0015181f, 0x0013161c, 0x0013161e, 0x0010131b, 0x000a0d13, 0x00090c10, 0x000a0e10, 0x00070a0d, 0x0006080c, 0x0008090d, 0x000b0c10, 0x000f1014, 0x00101114, 0x00101215, 0x000c1013, 0x00080b0e, 0x0006090c, 0x00080a0d, 0x000a0c0f, 0x000c0d10, 0x000a0c0f, 0x000b0c10, 0x000c0d10, 0x000c0e14, 0x0015181f, 0x0010141a, 0x0012171d, 0x00171c22, 0x00191e25, 0x00181c23, 0x001a1d24, 0x001b1e25, 0x001d2128, 0x0020252d, 0x00222730, 0x00212730, 0x001f242d, 0x001d242c, 0x001e252d, 0x001f262f, 0x001d252f, 0x001f2630, 0x00242b34, 0x00242c36, 0x00242c36, 0x00242c37, 0x00242e38, 0x00212b36, 0x00202834, 0x00212834, 0x00202730, 0x001e242d, 0x001a212a, 0x001c232c, 0x001c232c, 0x00202831, 0x00232b34, 0x00212c34, 0x001d2831, 0x00202c35, 0x001d2a34, 0x001f2d37, 0x00263540, 0x00283a46, 0x002b3e4b, 0x002e4450, 0x002d4451, 0x002b4250, 0x0029404d, 0x0029404f, 0x002c4352, 0x002f4655, 0x00324a58, 0x002f4856, 0x00334b5a, 0x003b5363, 0x00384b5b, 0x00344352, 0x002f3c4b, 0x002c3746, 0x002c3744, 0x002d3842, 0x002e3842, 0x00303a45, 0x0036424f, 0x00364451, 0x002b3945, 0x0015242e, 0x0012212b, 0x001e2c36, 0x00202f38, 0x001a242d, 0x000d141c, 0x00070c14, 0x000d131c, 0x001c2734, 0x002c3c4b, 0x00354c5d, 0x003b576b, 0x00416178, 0x00486e86, 0x00638ca1, 0x0095b9c5, 0x00b6cbcc, 0x00c4cccc, 0x00cacccc, 0x00cbcbcb, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbca, 0x00cbccc9, 0x00cbccca, 0x00cacbca, 0x00bdccca, 0x0090acb7, 0x00314857, 0x0014202c, 0x000e1418, 0x00060c10, 0x0002070b, 0x00030508, 0x00020405, 0x00020405, 0x00020405, 0x00020407, 0x00000408, 0x00020509, 0x0004080d, 0x00080c13, 0x000f161f, 0x0013202b, 0x0014222e, 0x00122431, 0x00122432, 0x00132433, 0x00132432, 0x00142532, 0x00132632, 0x00142733, 0x00142633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00142633, 0x00132632, 0x00132632, 0x00132532, 0x00142632, 0x00162633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00162734, 0x00162734, 0x00162734, 0x00162734, 0x00162734, 0x00162734, 0x00162734, 0x00162734, 0x00162734, 0x00152733, 0x00142633, 0x00142633, 0x00142633, 0x00152633, 0x00152633, 0x000d1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001d4b4e, 0x001e5053, 0x00205558, 0x0023595c, 0x002b86a0, 0x0032a5cb, 0x002a7c8c, 0x0028686b, 0x002a6c6e, 0x002a6e70, 0x002b7071, 0x002c7274, 0x003393a9, 0x0037a9ca, 0x002f848f, 0x002c7576, 0x00318c9d, 0x0038a9cb, 0x002d7d86, 0x002b7072, 0x002a6e70, 0x00296c6e, 0x0028686b, 0x0028747e, 0x0031a3c8, 0x002a859f, 0x0022595c, 0x00205558, 0x001f5053, 0x001d4b4e, 0x001c474b, 0x001a4245, 0x00183f43, 0x00183a3e, 0x0016363b, 0x00153338, 0x00142e34, 0x00132c32, 0x00112a30, 0x0012282e, 0x0013242c, 0x00102229, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101c26, 0x00101c24, 0x00101d27, 0x00101e28, 0x00111f2b, 0x00121f2b, 0x0014212c, 0x0014222d, 0x0014222d, 0x0013222d, 0x0012212c, 0x0012202c, 0x0012202c, 0x0012202c, 0x0012202c, 0x0013202c, 0x0013202c, 0x0013202b, 0x00111f2b, 0x00111f2b, 0x00121f2b, 0x00111f2b, 0x00101e2a, 0x00111c28, 0x00111c28, 0x00121e29, 0x00121e29, 0x00121e29, 0x00131f2b, 0x00131f2b, 0x00131f2a, 0x00131e28, 0x000f1824, 0x000a121c, 0x00060c15, 0x0004080e, 0x00040608, 0x00020405, 0x00030304, 0x00030304, 0x00020203, 0x00020203, 0x00020204, 0x00010204, 0x00010304, 0x00030508, 0x00020609, 0x0004080a, 0x00090d10, 0x0010161b, 0x001a242d, 0x00304b56, 0x0080aab0, 0x00bdcccc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccc9, 0x00cacccc, 0x00c4cccc, 0x00b4c6ca, 0x0088a7b6, 0x0057788c, 0x003e5a71, 0x00375064, 0x002e4456, 0x00273849, 0x00202f3c, 0x001a2631, 0x00151f28, 0x0010161f, 0x00080c14, 0x00030710, 0x00060911, 0x0010141c, 0x001a202b, 0x0018212c, 0x00162029, 0x00142028, 0x00101c24, 0x000c1820, 0x0015222c, 0x00283a47, 0x00384c5b, 0x00344b5a, 0x002c4453, 0x002c4452, 0x00283d4b, 0x00263742, 0x00273540, 0x00202e39, 0x0022303b, 0x001e2c37, 0x00192731, 0x00202e38, 0x00202e38, 0x001d2b34, 0x00192831, 0x00202d37, 0x00212f38, 0x001e2c36, 0x001f2c36, 0x00232f38, 0x00222e38, 0x00222e38, 0x00243039, 0x0025313c, 0x0024303a, 0x001d2932, 0x001f2a32, 0x00202b34, 0x00202831, 0x00222a34, 0x00232b35, 0x00222a34, 0x00202832, 0x001b232c, 0x001b2029, 0x0020252c, 0x001f242a, 0x001d2028, 0x001c1e27, 0x001a1c24, 0x00191c24, 0x001b2026, 0x001a1f25, 0x00181c22, 0x00181c23, 0x00171922, 0x0014171d, 0x0010131a, 0x0013161c, 0x000e1117, 0x000a0d13, 0x00080c10, 0x00080b0e, 0x0006090c, 0x00080a0d, 0x00090b0e, 0x000a0c0f, 0x000b0c10, 0x000e1013, 0x00101316, 0x000e1114, 0x000a0d10, 0x00080c0f, 0x00080a0d, 0x00090b0e, 0x000b0c10, 0x000a0c0f, 0x000c0d10, 0x000b0c10, 0x000b0c12, 0x0014171e, 0x0011141b, 0x0011151c, 0x00161b20, 0x001c2027, 0x001b1f25, 0x001c2025, 0x001c1f25, 0x001b1e24, 0x001d2228, 0x001f242c, 0x0020242c, 0x0020252d, 0x0020262e, 0x0020272f, 0x001f262f, 0x001e242e, 0x00202630, 0x00242b34, 0x00242b34, 0x00232b34, 0x00242d36, 0x0027313c, 0x00242f39, 0x00202a34, 0x00202832, 0x00212832, 0x00202630, 0x001a202b, 0x001d242d, 0x001e242e, 0x001d252e, 0x00202932, 0x00252f38, 0x001e2932, 0x001c2832, 0x001c2a34, 0x001d2c35, 0x0024343f, 0x00273844, 0x002a3d49, 0x002f4550, 0x002f4552, 0x002c4250, 0x002b414f, 0x002e4454, 0x002f4755, 0x00314958, 0x00314b59, 0x002d4755, 0x00304857, 0x003a5060, 0x00354757, 0x00323f50, 0x00303a49, 0x002c3745, 0x002c3543, 0x002d3641, 0x002f3842, 0x00313b46, 0x0037424f, 0x0034414d, 0x0024303c, 0x00101d28, 0x0014222d, 0x00202d38, 0x00202d37, 0x0019232c, 0x000c131a, 0x00080b14, 0x000c111b, 0x00182430, 0x00293946, 0x00324758, 0x00395264, 0x00405b6f, 0x00446378, 0x004e748b, 0x00749cb0, 0x009fc2c8, 0x00bccccc, 0x00c7cccc, 0x00cacccb, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbca, 0x00cbccc9, 0x00cbccca, 0x00cacbca, 0x00bdcccb, 0x008facb5, 0x00304654, 0x0014212c, 0x000e141a, 0x00060c10, 0x0002070b, 0x00030408, 0x00020405, 0x00020404, 0x00020405, 0x00020407, 0x00000408, 0x00010408, 0x00010508, 0x0004070c, 0x00081016, 0x00101b25, 0x0013222c, 0x00122430, 0x00122431, 0x00132431, 0x00142431, 0x00132532, 0x00132632, 0x00132632, 0x00142633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00152633, 0x00142633, 0x00132532, 0x00132532, 0x00132531, 0x00142431, 0x00162532, 0x00162532, 0x00162532, 0x00162532, 0x00162532, 0x00142532, 0x00142533, 0x00152633, 0x00152633, 0x00152633, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142532, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x000d1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001d4a4d, 0x001e5053, 0x00205457, 0x0022595c, 0x002b86a0, 0x0032a5cb, 0x002a7b8b, 0x0028686a, 0x00296b6d, 0x002a6d6f, 0x002b7071, 0x002b7173, 0x003292a8, 0x0037a9ca, 0x0030828e, 0x002c7476, 0x00318c9d, 0x0038a9cb, 0x002d7d86, 0x002b7072, 0x00296d6f, 0x00296b6d, 0x0028686b, 0x00286a6f, 0x00309dc0, 0x002c90ae, 0x00235a5c, 0x00215659, 0x00205254, 0x001d4d50, 0x001c484c, 0x001b4448, 0x00194044, 0x00183c40, 0x0017383c, 0x00143439, 0x00143036, 0x00142e34, 0x00132c32, 0x00112a30, 0x0012282e, 0x0013242c, 0x00102229, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101d27, 0x00101d27, 0x00101d27, 0x00101c26, 0x00101c24, 0x00101d27, 0x00101e28, 0x00111f2a, 0x00121f2b, 0x0014202c, 0x0014212c, 0x0014212c, 0x0013212c, 0x0012202c, 0x0012202b, 0x0012202b, 0x0013202c, 0x0013202c, 0x0012202a, 0x00111f29, 0x00111f29, 0x00111f29, 0x00111f29, 0x00111f2a, 0x00111f2b, 0x00101e2a, 0x00111d29, 0x00111d29, 0x00121f2a, 0x00121f2a, 0x00121f2a, 0x00131f2b, 0x00131f2b, 0x00141e29, 0x00111a24, 0x000c141d, 0x00070c15, 0x00040810, 0x0004060c, 0x00040406, 0x00030406, 0x00030306, 0x00030305, 0x00020203, 0x00020202, 0x00020203, 0x00000204, 0x00010304, 0x00020507, 0x00020609, 0x0004080a, 0x00090d10, 0x0010161b, 0x0019242d, 0x00304d58, 0x0083acb2, 0x00bdcccc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccca, 0x00c9ccca, 0x00c5cccc, 0x00b8c8cc, 0x0092aebd, 0x005f8196, 0x00426176, 0x003b5368, 0x00344a5e, 0x002c3f50, 0x00243444, 0x001d2c38, 0x0018242e, 0x00141d27, 0x000f151d, 0x00080c14, 0x00040810, 0x00080911, 0x0010121b, 0x00191d28, 0x0018202b, 0x00172029, 0x00151f28, 0x00101a22, 0x000a141d, 0x000f1a24, 0x0021303c, 0x00354653, 0x00354958, 0x002f4454, 0x002f4554, 0x002c404e, 0x00273845, 0x00263542, 0x0022303d, 0x0021303c, 0x001f2c38, 0x001c2934, 0x00202e39, 0x00212f39, 0x001f2c37, 0x001d2b34, 0x00222f38, 0x00222f39, 0x0023303a, 0x00212e38, 0x00202c37, 0x001f2c35, 0x00222e38, 0x0024303a, 0x0024303c, 0x00212d38, 0x001c2730, 0x001e2832, 0x00202832, 0x00202831, 0x00222a34, 0x00222a34, 0x00212933, 0x00202831, 0x001a222b, 0x001b2029, 0x001e2329, 0x001e2329, 0x001d2028, 0x001b1e27, 0x00181b24, 0x00181b24, 0x00191e25, 0x00181c24, 0x00171a21, 0x00161821, 0x0013161e, 0x0011141b, 0x0010141a, 0x0012151c, 0x000d1016, 0x000b0d14, 0x00080c11, 0x00070a10, 0x00070a10, 0x00080b0f, 0x000a0c0f, 0x00090b0f, 0x00090a0e, 0x000d0f12, 0x00101316, 0x000e1114, 0x000c1013, 0x000b0e11, 0x00090b0f, 0x00080a0f, 0x00080a0d, 0x00080a0d, 0x00090c10, 0x000a0c11, 0x00090c12, 0x000f1118, 0x000f1219, 0x0012161c, 0x00161b21, 0x001a1f26, 0x00181c22, 0x00181c21, 0x00191c23, 0x001a1d24, 0x00191d24, 0x001a1f27, 0x001b2028, 0x001f232b, 0x0020262d, 0x0020272f, 0x00202630, 0x00202830, 0x00212831, 0x00242c35, 0x00242a34, 0x00212932, 0x00242d36, 0x0028323c, 0x0027313c, 0x00242f39, 0x00212c36, 0x00222a35, 0x00202834, 0x001d2430, 0x001f2632, 0x00232b37, 0x001e2631, 0x001d2530, 0x00212b34, 0x00202c36, 0x00212d38, 0x00202d38, 0x001c2b34, 0x00202f3b, 0x00233440, 0x002b3d4a, 0x002d424f, 0x002d4450, 0x002c4450, 0x002d4452, 0x00304756, 0x00314858, 0x00334a59, 0x00334b5a, 0x00304857, 0x00304856, 0x00354a58, 0x00334252, 0x00303c4a, 0x002f3847, 0x002d3845, 0x002d3743, 0x002e3742, 0x00303944, 0x00343d48, 0x0037424d, 0x002f3b44, 0x001b2730, 0x000e1b24, 0x00172530, 0x00212e38, 0x001f2c37, 0x0018212a, 0x000b1018, 0x00070911, 0x000b1019, 0x0017222d, 0x00263541, 0x00304452, 0x00374d5f, 0x003c5468, 0x00415c71, 0x0045647d, 0x00577d94, 0x007ca8b7, 0x00adc8cb, 0x00c2cccc, 0x00c9cccc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbca, 0x00cbccc9, 0x00cbccca, 0x00cbcbca, 0x00bfcccb, 0x008eaab4, 0x002e4452, 0x0014202d, 0x000c131b, 0x00060c10, 0x0002060a, 0x00030407, 0x00020404, 0x00020404, 0x00020405, 0x00020407, 0x00000408, 0x00000408, 0x00000408, 0x00020508, 0x00050a10, 0x000a141c, 0x00101d27, 0x0014222e, 0x00142430, 0x00142431, 0x00142431, 0x00132431, 0x00132632, 0x00132632, 0x00142633, 0x00152633, 0x00152633, 0x00152633, 0x00142533, 0x00142532, 0x00152531, 0x00152531, 0x00152531, 0x00142430, 0x00142430, 0x00152431, 0x00152431, 0x00152431, 0x00152431, 0x00152431, 0x00142431, 0x00142431, 0x00142532, 0x00142533, 0x00142532, 0x00142532, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x00142431, 0x000d1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001d4a4d, 0x001e5053, 0x00205457, 0x0022595c, 0x002b86a0, 0x0032a5cb, 0x00297b8b, 0x0028686a, 0x00286a6c, 0x00296d6f, 0x002b6f70, 0x002b7173, 0x003292a8, 0x0037a9ca, 0x002f828e, 0x002c7476, 0x00318b9c, 0x0037a9cb, 0x002d7d86, 0x002b7071, 0x002a6d6f, 0x00296b6d, 0x0028686b, 0x00276769, 0x00309aba, 0x002d95b4, 0x00245c5f, 0x0021585a, 0x00205356, 0x001e4f51, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183c40, 0x0016383c, 0x00143439, 0x00153338, 0x00142e34, 0x00132c32, 0x00112a30, 0x0012282e, 0x0013242c, 0x00102229, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101d25, 0x00101c26, 0x00101c26, 0x00101c25, 0x00101c24, 0x00111d25, 0x00111d27, 0x00111e27, 0x00111e28, 0x00121e28, 0x00121e28, 0x00121e28, 0x00121e28, 0x00111f27, 0x00101f27, 0x00101f27, 0x00121f29, 0x00122029, 0x00121e29, 0x00111d28, 0x00111d28, 0x00121e28, 0x00121e28, 0x00111f29, 0x00101e2a, 0x00101e2a, 0x00111e2a, 0x00111f2a, 0x00111f2b, 0x00121f2b, 0x00121f2b, 0x0013202c, 0x00131f2a, 0x00121c25, 0x000d151e, 0x00090e17, 0x00060910, 0x0004060c, 0x00040409, 0x00020406, 0x00010206, 0x00010206, 0x00020206, 0x00010205, 0x00000204, 0x00000204, 0x00000304, 0x00000304, 0x00000405, 0x00000607, 0x0003080a, 0x00080e11, 0x000f171d, 0x0017242e, 0x002e4f58, 0x0082aeb4, 0x00bbcccc, 0x00cacccc, 0x00cbcccb, 0x00cacccb, 0x00cacccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccc9, 0x00cbccc9, 0x00cbccc9, 0x00cccbca, 0x00cbcccb, 0x00c5cccc, 0x00bac9cc, 0x0098b4c0, 0x0066879c, 0x0046657c, 0x003c576b, 0x00364c5e, 0x00304354, 0x00283a49, 0x0022313f, 0x001c2936, 0x0017212c, 0x00141c25, 0x000e141b, 0x00090c14, 0x0005080f, 0x00080810, 0x000d1018, 0x00161b24, 0x00181f29, 0x00171f28, 0x00161e27, 0x00111a22, 0x000b141c, 0x000b141d, 0x0017242e, 0x002c3b48, 0x00344553, 0x00334554, 0x00314553, 0x002d404f, 0x00283a48, 0x00253443, 0x00233240, 0x0021303d, 0x00202d3a, 0x001f2c38, 0x00202d38, 0x001f2c37, 0x001c2a35, 0x00202d38, 0x0023303b, 0x0023303c, 0x00283540, 0x0024313c, 0x00202d37, 0x001a2831, 0x00202e37, 0x0024323c, 0x00222f39, 0x001d2833, 0x001c2732, 0x00202934, 0x00212b35, 0x00202934, 0x001f2830, 0x00212931, 0x00202830, 0x001e262d, 0x001a2129, 0x001b2028, 0x001b2127, 0x001a2026, 0x00181d24, 0x00181c24, 0x00171b21, 0x00171c21, 0x00181c22, 0x00161b20, 0x0016191e, 0x0012141a, 0x000f1218, 0x000f1218, 0x00101318, 0x000f1217, 0x000c1014, 0x000c0f14, 0x00090c11, 0x00070a0f, 0x00080b10, 0x00080c10, 0x00080b0f, 0x00080b10, 0x000b0d12, 0x000c0f14, 0x000d1014, 0x000c1014, 0x000c1115, 0x000b1014, 0x00090d11, 0x00080c10, 0x00080c10, 0x00070c10, 0x00070c10, 0x00080d11, 0x000c1116, 0x0011151c, 0x0013181d, 0x00141920, 0x00151b21, 0x00161c22, 0x0011161c, 0x0011151c, 0x00161a20, 0x00171c22, 0x00181c23, 0x00191f27, 0x00192028, 0x001c232a, 0x001e252c, 0x001d262e, 0x001d252e, 0x001e262f, 0x00212932, 0x00242c35, 0x00222b34, 0x00202831, 0x00222c35, 0x00243039, 0x00233039, 0x00222f38, 0x00232e38, 0x00242e3a, 0x00242d3a, 0x00202935, 0x00202834, 0x0025303b, 0x00212c36, 0x001c2731, 0x001d2934, 0x00222e38, 0x0026313c, 0x0023303a, 0x001c2a34, 0x001e2c37, 0x00202e3c, 0x00293948, 0x002b3e4c, 0x00293f4c, 0x002b4250, 0x002e4754, 0x00304854, 0x00314856, 0x00344958, 0x00344b59, 0x00324857, 0x00334754, 0x00344552, 0x00303f4c, 0x002c3845, 0x002d3844, 0x002d3844, 0x002c3844, 0x002d3844, 0x00313c4a, 0x0034404d, 0x00343f4a, 0x0028313c, 0x00141f28, 0x00101c26, 0x001a2731, 0x00202e39, 0x001f2c37, 0x00182029, 0x000b1018, 0x00070a10, 0x000b1017, 0x00151f28, 0x0023313c, 0x002c404d, 0x00344958, 0x003a5063, 0x0040586d, 0x00425e74, 0x00486880, 0x005a8397, 0x008cb0bc, 0x00b1c8cb, 0x00c1cccc, 0x00c9cccc, 0x00cccbcc, 0x00cccbcc, 0x00cccbcb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbca, 0x00cbccc9, 0x00cbccca, 0x00c9ccca, 0x00becccb, 0x008aa3ad, 0x00283d4c, 0x00111e2a, 0x00091018, 0x0004090e, 0x00020508, 0x00020404, 0x00000304, 0x00010304, 0x00010304, 0x00010305, 0x00010306, 0x00010307, 0x00010306, 0x00020407, 0x0003060b, 0x00060d14, 0x000c161d, 0x00121e28, 0x0014222f, 0x00142431, 0x00142431, 0x00142431, 0x00142532, 0x00132532, 0x00142532, 0x00142530, 0x00142530, 0x00142530, 0x00142530, 0x00142430, 0x00142430, 0x00142430, 0x00142430, 0x00142430, 0x00142430, 0x00142330, 0x00142330, 0x00142330, 0x00142330, 0x00142330, 0x0014232e, 0x0014232e, 0x00142430, 0x00142431, 0x00142431, 0x00142430, 0x0014242f, 0x0013242f, 0x0012242e, 0x0012242f, 0x00132430, 0x00142431, 0x00132431, 0x00132431, 0x00132431, 0x000d1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001d4a4d, 0x001f5053, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297b8b, 0x0028686a, 0x00286a6c, 0x00296c6f, 0x002b6f70, 0x002b7072, 0x003292a8, 0x0037a9ca, 0x002f828e, 0x002c7475, 0x00318b9c, 0x0037a9cb, 0x002c7c86, 0x002b7071, 0x002a6d6f, 0x00296b6d, 0x0028686b, 0x00276668, 0x003098b8, 0x002e96b6, 0x00245d60, 0x0022585b, 0x00205457, 0x001f5154, 0x001d4d50, 0x001c4a4d, 0x001b4649, 0x001a4245, 0x00183f43, 0x00183c40, 0x0017383c, 0x0016363b, 0x00153338, 0x00142e34, 0x00132c32, 0x00112a30, 0x0011282e, 0x0013242c, 0x00102229, 0x00102229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00111d25, 0x00111d25, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101d24, 0x00101d25, 0x00101d25, 0x00101e28, 0x00101e28, 0x00101c28, 0x00111c28, 0x00111c28, 0x00121e28, 0x00121e28, 0x00121e28, 0x00111e28, 0x00111e28, 0x00121f29, 0x00121f29, 0x00121f2a, 0x0012202c, 0x0011202c, 0x00121f2b, 0x00101c27, 0x000d161d, 0x00090f15, 0x00070a10, 0x0005070b, 0x00040509, 0x00030408, 0x00020405, 0x00000206, 0x00000206, 0x00000206, 0x00000205, 0x00000204, 0x00000204, 0x00000304, 0x00000304, 0x00000404, 0x00000607, 0x0003080b, 0x00080e12, 0x000f181e, 0x0016242e, 0x002d4e58, 0x0084afb4, 0x00bccccc, 0x00cbcccc, 0x00cbcccb, 0x00cacccb, 0x00cacccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccc9, 0x00cbccc9, 0x00cccccb, 0x00cccccc, 0x00c8cccc, 0x00bdcbcc, 0x00a0b9c3, 0x006f90a2, 0x004c6c81, 0x003f596e, 0x003a5062, 0x00344557, 0x002c3d4d, 0x00263544, 0x00202d3c, 0x00192633, 0x0016202b, 0x00141b23, 0x000f141a, 0x00090d12, 0x0006090d, 0x0006080c, 0x000b0d13, 0x0013181e, 0x00181f26, 0x00171f26, 0x00151d24, 0x00121b22, 0x000c151c, 0x00081018, 0x00101a25, 0x0026333f, 0x0031414f, 0x00334453, 0x002f4150, 0x002b3d4c, 0x00293c49, 0x00273847, 0x00253544, 0x0020313e, 0x001e2e3a, 0x0022313c, 0x00212f39, 0x001e2c36, 0x001d2a36, 0x0023303d, 0x0025323e, 0x0024313d, 0x002a3843, 0x00283641, 0x0021303b, 0x001b2a34, 0x0022313a, 0x0024343d, 0x00202e38, 0x001c2833, 0x001f2a34, 0x00202c36, 0x00242f39, 0x00202b35, 0x001d2830, 0x00202830, 0x001e272e, 0x001b232a, 0x001b2229, 0x001a1f27, 0x00181f25, 0x00181e24, 0x00161b21, 0x00171c22, 0x00171b20, 0x00171c20, 0x00161b20, 0x00151a1e, 0x0016191e, 0x000e1116, 0x000d1017, 0x00101319, 0x00111419, 0x000d1015, 0x000d1015, 0x000c1014, 0x00080c10, 0x00070a0f, 0x00090c11, 0x00090c10, 0x00080b10, 0x00080c10, 0x000c0f14, 0x00090c11, 0x00090c13, 0x000a0f14, 0x000c1015, 0x000c1014, 0x00090e12, 0x000a0f15, 0x000b1015, 0x000c1418, 0x000c1317, 0x000c1317, 0x0013191e, 0x00151a20, 0x0013181d, 0x0011171c, 0x0014191f, 0x00141920, 0x000f141a, 0x000e1318, 0x0014181f, 0x00171c22, 0x00161b22, 0x00191f27, 0x001a2129, 0x001b242b, 0x001e272e, 0x001d2730, 0x001c272f, 0x001e2830, 0x00202b33, 0x00202b34, 0x001c262f, 0x001a242d, 0x00202c34, 0x00212d35, 0x001f2c34, 0x00202d36, 0x00232f38, 0x0025303b, 0x0024303a, 0x00212c37, 0x001f2a34, 0x0028333d, 0x0026333c, 0x00202d37, 0x00212f38, 0x0025323c, 0x0028343d, 0x0024313b, 0x001d2b34, 0x00202d39, 0x00212f3c, 0x00283846, 0x002c3e4c, 0x002a404c, 0x002c424f, 0x00314956, 0x00304854, 0x00314754, 0x00324754, 0x00344754, 0x00334654, 0x00344451, 0x0032404c, 0x002e3a46, 0x002c3642, 0x002c3742, 0x002c3743, 0x002c3844, 0x002e3946, 0x00333f4c, 0x00343f4d, 0x002f3844, 0x001c2630, 0x00101922, 0x00141f28, 0x001c2834, 0x00212d39, 0x001f2a36, 0x00151e28, 0x00090e16, 0x00070910, 0x000b0f16, 0x00141d26, 0x00202e38, 0x002a3d49, 0x00304755, 0x00374e5f, 0x003c5469, 0x003f596f, 0x00426075, 0x00486b80, 0x00688da2, 0x0094b8c4, 0x00b4cbcc, 0x00c4cccc, 0x00cbcccc, 0x00cccbcc, 0x00cccbcb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbca, 0x00cbccc9, 0x00caccca, 0x00c8ccc9, 0x00bdcbcb, 0x00859ca8, 0x00243847, 0x00101c28, 0x00091018, 0x0004090d, 0x00020508, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010408, 0x0003070c, 0x00080c12, 0x000d151d, 0x00141e2a, 0x00152330, 0x00162431, 0x00142431, 0x00142431, 0x00142532, 0x00142532, 0x00142530, 0x00142530, 0x00142530, 0x00142430, 0x0014242f, 0x0014242f, 0x0014242e, 0x0014232e, 0x0013222d, 0x0013222d, 0x0013222e, 0x0013222e, 0x0013222d, 0x0012212d, 0x0012212d, 0x0012212c, 0x0012212c, 0x0012222e, 0x0011232f, 0x0011232f, 0x0012232e, 0x0012232d, 0x0011232d, 0x0011232d, 0x0011232e, 0x00122430, 0x00122430, 0x00122430, 0x00112430, 0x00112430, 0x000c1c27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00132e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001c4448, 0x001d4a4d, 0x001f5053, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297b8b, 0x00286769, 0x00286a6c, 0x00296c6f, 0x002a6e70, 0x002b7072, 0x003192a8, 0x0037a9ca, 0x002f828e, 0x002c7475, 0x00308a9c, 0x0037a9cb, 0x002d7c86, 0x002b6f70, 0x00296c6f, 0x00296b6d, 0x0028686a, 0x00276769, 0x003098b8, 0x002f97b6, 0x00245e60, 0x0022595c, 0x00215659, 0x00205356, 0x001f5053, 0x001d4c50, 0x001d4a4d, 0x001b4649, 0x001a4245, 0x00194044, 0x00183c40, 0x00183a3e, 0x0015363b, 0x00143338, 0x00143036, 0x00132c32, 0x00102a30, 0x0012282e, 0x0013242c, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f1b24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101c24, 0x000f1b24, 0x000e1a23, 0x000e1a22, 0x000e1a22, 0x000e1a22, 0x000e1a22, 0x000e1b23, 0x000e1b23, 0x000e1b23, 0x000f1c25, 0x000f1c25, 0x00101c26, 0x00101c26, 0x00101c27, 0x00111d27, 0x00111d27, 0x00121e28, 0x00111e28, 0x00121e29, 0x00131f2a, 0x0013202a, 0x0013202b, 0x0012212c, 0x0012202c, 0x00111d29, 0x000d1721, 0x00081016, 0x00070b10, 0x0005080c, 0x00040508, 0x00030408, 0x00020307, 0x00010205, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000304, 0x00000304, 0x00000404, 0x00000607, 0x0003080a, 0x00080e12, 0x000f181e, 0x0016242e, 0x002d4e58, 0x0084afb4, 0x00bccccc, 0x00cbcccc, 0x00cbccca, 0x00cacccb, 0x00cacccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00caccc9, 0x00cbccca, 0x00cbcccc, 0x00cacccc, 0x00c1cbcc, 0x00a7bec8, 0x007796aa, 0x00507087, 0x00425f74, 0x003b5367, 0x0035495c, 0x002f4151, 0x00283a4a, 0x00243342, 0x001d2a39, 0x00192531, 0x0016202b, 0x00131a23, 0x000d1219, 0x00080c11, 0x0005080c, 0x0005080b, 0x00090c10, 0x0012171d, 0x00171d24, 0x00161e25, 0x00151d24, 0x00141c23, 0x000e161d, 0x00071018, 0x000e1822, 0x0023303b, 0x002e3e4b, 0x00314350, 0x002e414f, 0x002a3d4b, 0x00293c4a, 0x00283b49, 0x00283a48, 0x00223340, 0x0020303d, 0x00263540, 0x0023303c, 0x001f2c38, 0x0021303c, 0x0024323f, 0x00263440, 0x0024323e, 0x00273440, 0x002b3844, 0x0023313c, 0x0021303a, 0x0022313b, 0x0022313a, 0x001d2c35, 0x00202c37, 0x0024313b, 0x00232f38, 0x00232e38, 0x001f2a34, 0x00202a34, 0x001e2730, 0x001c252c, 0x001b232a, 0x001b2129, 0x00191e26, 0x00182028, 0x00192026, 0x00161c22, 0x00151b21, 0x00141a1f, 0x00141a1e, 0x00151a1f, 0x0014191d, 0x0015181d, 0x000d1015, 0x000d1017, 0x0011141b, 0x0013161c, 0x000e1116, 0x000d1015, 0x000c1014, 0x00080c10, 0x00080b0f, 0x000c0f14, 0x000d1014, 0x000c1014, 0x000c0f14, 0x000b0e12, 0x000a0d12, 0x000a0d14, 0x000a0e13, 0x000b1014, 0x000a0f14, 0x00090e12, 0x000c1016, 0x000d1418, 0x000c1417, 0x000a1014, 0x00080f13, 0x000f151b, 0x000f141a, 0x0010151b, 0x00141920, 0x0012171d, 0x0012171d, 0x0010151c, 0x0013181e, 0x00181c23, 0x00181c23, 0x00171c22, 0x00181d25, 0x00182027, 0x00192229, 0x001d272d, 0x001e2830, 0x00202b34, 0x00202b33, 0x001f2931, 0x001c2730, 0x001a242d, 0x0018232c, 0x001c262f, 0x001f2b33, 0x001f2c34, 0x00202e37, 0x0024303b, 0x0025313c, 0x00232f38, 0x00222e38, 0x00212c38, 0x0026323d, 0x0027343e, 0x0024333c, 0x0026343e, 0x0028343e, 0x0026333c, 0x0023303a, 0x001d2c35, 0x00202d38, 0x00202f3d, 0x00243444, 0x00283c49, 0x002c414f, 0x002e4452, 0x00324a57, 0x00304754, 0x00304653, 0x00304350, 0x002f404f, 0x002e3f4d, 0x002f3c4a, 0x002f3c48, 0x002e3944, 0x002c3641, 0x002e3742, 0x002d3743, 0x002d3844, 0x00303c48, 0x0034404c, 0x00343f4b, 0x0028323d, 0x00141e28, 0x000e1821, 0x0016202a, 0x001c2833, 0x001f2b37, 0x001c2834, 0x00121b24, 0x00070d15, 0x00070a11, 0x00090d16, 0x00131c25, 0x001f2c38, 0x00293c48, 0x002f4453, 0x00344b5c, 0x003a5266, 0x003c576b, 0x00405b70, 0x00436176, 0x00507488, 0x00739aad, 0x009ec0c8, 0x00bacccc, 0x00c7cccc, 0x00cbcccc, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccc9, 0x00caccca, 0x00c8ccc9, 0x00bccacb, 0x007d95a3, 0x00203442, 0x00101b26, 0x00091017, 0x0004090c, 0x00030508, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010407, 0x0002050a, 0x0004080c, 0x00080d15, 0x000f1823, 0x0014212e, 0x00152330, 0x00142431, 0x00142431, 0x00142532, 0x00142532, 0x00142530, 0x00142530, 0x0014242f, 0x0014242f, 0x0013242f, 0x0014232e, 0x0014232e, 0x0013222d, 0x0013222d, 0x0013222d, 0x0012212c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0012212c, 0x0011202b, 0x0011202b, 0x0010202c, 0x0010202c, 0x0010212d, 0x0012212d, 0x0013222d, 0x0013222d, 0x0013222d, 0x0013222e, 0x0012232f, 0x00122430, 0x00112430, 0x00112430, 0x00112430, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001c4448, 0x001d4a4d, 0x001f5053, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297b8b, 0x00286769, 0x00286a6c, 0x00296c6f, 0x002a6e70, 0x002c7071, 0x003192a8, 0x0037a9ca, 0x002f828d, 0x002c7374, 0x00308a9c, 0x0037a9cb, 0x002d7b85, 0x002a6e70, 0x00296c6f, 0x00286a6c, 0x0028686a, 0x00276769, 0x003098b8, 0x002f97b6, 0x00245f61, 0x00235a5c, 0x0022585b, 0x00205558, 0x00205254, 0x001f5053, 0x001d4c50, 0x001d4a4d, 0x001c4649, 0x001a4347, 0x00194044, 0x00183d41, 0x00183a3e, 0x0016363b, 0x00143338, 0x00143036, 0x00132c32, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00122229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1820, 0x000d1921, 0x000d1922, 0x000e1a22, 0x000f1a22, 0x000d1921, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c181f, 0x000c1920, 0x000c1a22, 0x000e1c24, 0x000f1b24, 0x00101b25, 0x00101b25, 0x00101c26, 0x00111d27, 0x00111e28, 0x00111f2b, 0x00111f2b, 0x0013202c, 0x0014202c, 0x0013212c, 0x0012212c, 0x00121f2b, 0x00101a25, 0x000b111c, 0x00060b12, 0x0004080c, 0x00030509, 0x00030408, 0x00030408, 0x00020307, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010404, 0x00000607, 0x0003080a, 0x00080e12, 0x000f181e, 0x0016242f, 0x002d4c57, 0x0084adb2, 0x00bdcccc, 0x00cacbcc, 0x00caccca, 0x00c9cccb, 0x00cacccb, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccc9, 0x00cbcccb, 0x00c9cccc, 0x00c4cccc, 0x00adc3c9, 0x0080a0b3, 0x0054788e, 0x00436278, 0x003c576d, 0x00364d60, 0x00314657, 0x002c3e4d, 0x00263848, 0x00233140, 0x001d2a38, 0x00192431, 0x00151f2a, 0x00121924, 0x000d121a, 0x00080c11, 0x0005080c, 0x0004070a, 0x00080b10, 0x0010151b, 0x00151c23, 0x00151d24, 0x00151d24, 0x00141c23, 0x000e171d, 0x00081018, 0x000f1922, 0x001c2834, 0x00273643, 0x002e404d, 0x002e404e, 0x002c3f4d, 0x00293c4b, 0x002a3c4b, 0x002a3c4b, 0x00243544, 0x00233442, 0x00283944, 0x00243340, 0x0021303e, 0x00253442, 0x00253441, 0x0024333e, 0x0023313d, 0x00253440, 0x002a3844, 0x00283742, 0x0024343d, 0x0022313b, 0x001e2d37, 0x00182831, 0x001c2934, 0x0023303a, 0x00222f38, 0x00222e38, 0x00202c36, 0x00222d38, 0x001c262f, 0x001a242c, 0x001a222a, 0x00192129, 0x00171f28, 0x00172028, 0x00182026, 0x00172024, 0x00161d23, 0x0013191d, 0x0011171b, 0x0010151a, 0x0014181c, 0x0014181c, 0x000d1015, 0x000e1118, 0x0014171d, 0x00111419, 0x000c1014, 0x000d1015, 0x000f1217, 0x000b0f14, 0x00080b10, 0x000f1218, 0x00101318, 0x000a0d11, 0x00080c10, 0x000c0f13, 0x000d1017, 0x000c0f16, 0x000a0e13, 0x00090e12, 0x00080c10, 0x00070c10, 0x00090f14, 0x0010161b, 0x000f1519, 0x000b1216, 0x000a1015, 0x000f141a, 0x000e1419, 0x0013181e, 0x00161b21, 0x0010141a, 0x000e1319, 0x0010151c, 0x00161b21, 0x00181d24, 0x00171c22, 0x00151a20, 0x00151c22, 0x00171e24, 0x00172027, 0x001b232a, 0x001d272f, 0x00202932, 0x00202a33, 0x00202a33, 0x001f2931, 0x001c2730, 0x001b252e, 0x001a242d, 0x001d2830, 0x00202c34, 0x00212f38, 0x0024323c, 0x0024313b, 0x00212f38, 0x0023303a, 0x0027343f, 0x00273440, 0x00283642, 0x00273641, 0x00283742, 0x00293843, 0x0025333e, 0x0023323c, 0x00203039, 0x001e2d38, 0x0020303e, 0x00253745, 0x00273a48, 0x002c4150, 0x00304754, 0x00324856, 0x00304553, 0x002f4350, 0x002f404e, 0x002c3c4a, 0x002b3948, 0x002c3946, 0x002d3844, 0x002d3742, 0x002e3641, 0x002f3741, 0x002f3742, 0x002e3844, 0x00323c48, 0x0034404c, 0x00333e4a, 0x00202a35, 0x000e1823, 0x00101b24, 0x0017222c, 0x001c2831, 0x001d2a34, 0x001b2630, 0x00111922, 0x00070c14, 0x00060a11, 0x00080d15, 0x00101a24, 0x001d2b36, 0x00263845, 0x002d4150, 0x00324858, 0x00384f62, 0x003b5466, 0x003d576a, 0x00405c70, 0x0044647c, 0x00547a92, 0x007ca3b7, 0x00a8c6ca, 0x00becccc, 0x00c8cccc, 0x00cbcccb, 0x00cccbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbccca, 0x00cacccb, 0x00c8cccb, 0x00b8c9cb, 0x00748d9a, 0x001c303c, 0x00101a24, 0x00080f15, 0x0004080b, 0x00040507, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000306, 0x00010408, 0x0003060b, 0x00040910, 0x000b101c, 0x00101c2a, 0x0014222f, 0x00142431, 0x00142431, 0x00142532, 0x00142531, 0x00142530, 0x0014242f, 0x0014242f, 0x0014242f, 0x0012232e, 0x0013222d, 0x0012212c, 0x0011202c, 0x0011202c, 0x0011202c, 0x0011202c, 0x0012212c, 0x0011202c, 0x0011202c, 0x0011202c, 0x00102029, 0x00102029, 0x00102029, 0x0010202b, 0x0010202b, 0x0010202b, 0x0011202c, 0x0012212c, 0x0013222d, 0x0012212d, 0x0013222e, 0x0013222e, 0x0012232e, 0x0011232f, 0x0011232f, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x00183a3e, 0x00183f43, 0x001c4448, 0x001d4a4d, 0x001f5053, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297b8b, 0x00286769, 0x00286a6c, 0x00296c6f, 0x002a6e70, 0x002c7071, 0x003192a8, 0x0037a9ca, 0x002e828d, 0x002c7374, 0x00308a9c, 0x0037a8cb, 0x002d7b85, 0x002a6e70, 0x00296c6e, 0x00286a6c, 0x0028686a, 0x00276769, 0x003098b8, 0x002f97b6, 0x00245f61, 0x00245c5f, 0x0022595c, 0x0021585a, 0x00205457, 0x00205254, 0x001f5053, 0x001d4c50, 0x001c4a4d, 0x001c474b, 0x001b4448, 0x001a4245, 0x00183d41, 0x00183a3e, 0x0016363b, 0x00143338, 0x00143036, 0x00132c32, 0x00112a30, 0x0013282e, 0x00102229, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b161e, 0x000b161e, 0x000b161e, 0x000c151e, 0x000c151e, 0x000b151e, 0x000a151e, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c181f, 0x000c181e, 0x000c181f, 0x000c1920, 0x000d1a23, 0x000f1b24, 0x00101b25, 0x00101b25, 0x00101c26, 0x00111d27, 0x00101e28, 0x00111f2b, 0x00121f2b, 0x0013202c, 0x0013202c, 0x0013202c, 0x0012202b, 0x00101a25, 0x000b121c, 0x00080c15, 0x0004070e, 0x0004050b, 0x00030408, 0x00030408, 0x00030308, 0x00020306, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010404, 0x00000607, 0x0002080a, 0x00080e12, 0x000f171d, 0x0016242e, 0x002b4854, 0x0080a9b0, 0x00becccc, 0x00cbcbcc, 0x00caccca, 0x00c9cccb, 0x00cacccb, 0x00cbcccb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbca, 0x00cbcccc, 0x00c4cccc, 0x00b2c6cb, 0x0089a8b8, 0x005b7f94, 0x0046687e, 0x003d5b70, 0x00385065, 0x0032485b, 0x002e4353, 0x00293c4b, 0x00233443, 0x00202e3c, 0x001c2835, 0x0018232f, 0x00141d28, 0x00121923, 0x000d131b, 0x00090c12, 0x0006090d, 0x0004070a, 0x0007090e, 0x000c1218, 0x00131920, 0x00151c24, 0x00141c24, 0x00131b23, 0x000e171f, 0x00081119, 0x000c151f, 0x00131d28, 0x001f2c39, 0x002d3d4c, 0x00304150, 0x00304150, 0x002c3d4c, 0x002c3e4c, 0x002c3e4c, 0x00253846, 0x00273947, 0x002d3f4b, 0x00283846, 0x00253544, 0x00283846, 0x00263543, 0x0022313e, 0x0023323d, 0x00263640, 0x00273641, 0x00283742, 0x0024343e, 0x0024333d, 0x0020303a, 0x001c2b35, 0x00202e38, 0x0024313c, 0x00202c37, 0x00212d38, 0x00232f39, 0x00242f3a, 0x001c2630, 0x001a242d, 0x001c242d, 0x001b232c, 0x001a222b, 0x00152026, 0x00121b20, 0x00161f24, 0x00161e23, 0x0013191d, 0x0010171a, 0x000f1418, 0x0012171b, 0x0012171b, 0x000d1015, 0x0011151c, 0x00171a20, 0x0012161c, 0x000e1317, 0x000e1317, 0x000f1217, 0x000e1117, 0x000d1016, 0x0010141a, 0x00090d12, 0x0004070c, 0x0006090f, 0x000c0f14, 0x000e1117, 0x000c0f14, 0x000c1014, 0x000b1014, 0x00080d11, 0x00080c11, 0x000c1117, 0x0013191d, 0x00131a1e, 0x0010171b, 0x0012191e, 0x00141b21, 0x0011171e, 0x0010171d, 0x00161c22, 0x0010161c, 0x0010151c, 0x0010151c, 0x00151920, 0x00181c23, 0x00171c22, 0x00171c23, 0x00161c23, 0x00182026, 0x001a2229, 0x001b232a, 0x001f2730, 0x00212a34, 0x00202a33, 0x00212c35, 0x00212c35, 0x001f2932, 0x001c2730, 0x001a242d, 0x001c2730, 0x00202c34, 0x00212f38, 0x0024323c, 0x0022303b, 0x00202e38, 0x0023303c, 0x00293744, 0x00283543, 0x002c3a47, 0x002a3845, 0x00263441, 0x00263441, 0x0026343f, 0x0025343e, 0x0024343e, 0x001e2e39, 0x00223140, 0x00293a49, 0x00283c4b, 0x002c404f, 0x00304654, 0x00324754, 0x00304350, 0x002f404d, 0x002f3d4b, 0x002c3946, 0x002c3844, 0x002c3844, 0x002d3843, 0x002f3742, 0x00303742, 0x00303740, 0x00303742, 0x00303845, 0x00343d4a, 0x0034404c, 0x002d3844, 0x0019222d, 0x000d1722, 0x00131c28, 0x0019242e, 0x001c2830, 0x001c2830, 0x001a232c, 0x0010171e, 0x00080c12, 0x00050910, 0x00080d15, 0x00101a24, 0x001d2a35, 0x00253644, 0x002c3f4f, 0x00304657, 0x00344c5f, 0x00385063, 0x003a5467, 0x003d576b, 0x00405c73, 0x00466882, 0x00598299, 0x0088afbe, 0x00b0c8cc, 0x00c1cccc, 0x00c9cccc, 0x00cbcccb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcb, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcccc, 0x00c9cccc, 0x00c8cccc, 0x00c4cccc, 0x00b4c7ca, 0x006c8592, 0x00192c39, 0x000e1822, 0x00080d13, 0x0002070a, 0x00040507, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000305, 0x00010408, 0x00020509, 0x0003070b, 0x00060a13, 0x00081420, 0x000d1c28, 0x0013212f, 0x00142431, 0x00142431, 0x00142431, 0x0014242f, 0x0014242f, 0x0014242f, 0x0012242e, 0x0012232d, 0x0012212c, 0x0010202b, 0x0010202b, 0x000f1f29, 0x00101f2a, 0x0010202b, 0x0010202b, 0x0010202b, 0x0010202b, 0x00101f2a, 0x000e1e28, 0x000e1e27, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000e1d28, 0x000f1e29, 0x00101f2a, 0x0010202b, 0x0012212c, 0x0012212c, 0x0011212d, 0x0010222e, 0x0011222e, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183f43, 0x001c4448, 0x001d4a4d, 0x001f5053, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297b8b, 0x00286769, 0x00286a6c, 0x00296c6f, 0x002a6e70, 0x002b7071, 0x003291a8, 0x0037a9ca, 0x002f818d, 0x002c7274, 0x00308a9c, 0x0037a8cb, 0x002d7b84, 0x002a6d6f, 0x002a6c6e, 0x0028696c, 0x0028686a, 0x00276769, 0x003098b8, 0x002f97b6, 0x00246062, 0x00245d60, 0x00245c5e, 0x0022585b, 0x00215659, 0x00205457, 0x00205254, 0x001f5053, 0x001d4d50, 0x001d4b4e, 0x001c474b, 0x001b4448, 0x001a4245, 0x00183d41, 0x00183a3e, 0x0016363b, 0x00153338, 0x00142e34, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c141b, 0x000c141b, 0x000c141b, 0x000b141b, 0x000a141b, 0x000a141b, 0x000a141c, 0x000b151c, 0x000b151d, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161d, 0x000c171f, 0x000d1720, 0x000e1820, 0x000e1921, 0x000f1a23, 0x000f1b24, 0x000e1c25, 0x000e1c26, 0x00101e27, 0x00101e29, 0x00111f2b, 0x0013202c, 0x0013202c, 0x00121f2b, 0x00131f29, 0x00101a24, 0x000b131b, 0x00080c14, 0x0004080e, 0x00020409, 0x00020408, 0x00020408, 0x00020306, 0x00020306, 0x00000205, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00010406, 0x00030609, 0x00080c10, 0x0010151c, 0x0015212b, 0x00294550, 0x007da6ad, 0x00bccccc, 0x00c9cccb, 0x00c8ccc9, 0x00cacccb, 0x00cbcbcb, 0x00cccbcb, 0x00cccbcb, 0x00cccbca, 0x00c9ccca, 0x00c4cccc, 0x00b3c8cb, 0x008dadbe, 0x00608499, 0x00486a7f, 0x00415d72, 0x003c5468, 0x00354c60, 0x00304557, 0x002c404f, 0x00273948, 0x00213340, 0x001d2c39, 0x001a2734, 0x0017202c, 0x00141c26, 0x00111821, 0x000d131c, 0x00090c14, 0x0005090d, 0x00030509, 0x0004060b, 0x000a0f15, 0x0010171d, 0x00131b24, 0x00131c24, 0x00121b24, 0x000c1720, 0x0008111a, 0x00071019, 0x0006101b, 0x00192531, 0x0031404d, 0x00364554, 0x00324350, 0x002d3e4b, 0x002e3f4b, 0x002c3e4a, 0x00273945, 0x00283b48, 0x002c404c, 0x002a3d4b, 0x00293c4a, 0x00293c4a, 0x00263745, 0x00213240, 0x00243440, 0x00283845, 0x00263643, 0x00243440, 0x00243440, 0x00243441, 0x00233340, 0x0020303c, 0x00283742, 0x0025333e, 0x00222f3a, 0x0026323d, 0x00232f39, 0x001f2b35, 0x001a2530, 0x001a2430, 0x001c2630, 0x0019232c, 0x00182029, 0x00141c24, 0x00121a21, 0x00181f27, 0x00181e25, 0x00141a20, 0x0010151a, 0x000d1218, 0x0010141a, 0x0012171c, 0x0010141b, 0x0013171d, 0x00141920, 0x0013181e, 0x0010151c, 0x0010161b, 0x000f1418, 0x000c1115, 0x0011161a, 0x0012171b, 0x000b0e13, 0x0005090e, 0x00080c11, 0x000d1015, 0x000c0f14, 0x00080c10, 0x000d1015, 0x000d1015, 0x000a0d12, 0x000c0f14, 0x0011141b, 0x00161b20, 0x00141a20, 0x0012181d, 0x00121a20, 0x00182028, 0x00171f28, 0x00141d26, 0x00182029, 0x00121922, 0x00101620, 0x00131820, 0x00141b21, 0x00171c23, 0x00161c24, 0x00192028, 0x00182028, 0x00182029, 0x001c252d, 0x001e2730, 0x00212c36, 0x00212b36, 0x001d2933, 0x00202c36, 0x00202c36, 0x001f2a34, 0x00202c34, 0x001b2730, 0x001c2831, 0x001f2c35, 0x0022303a, 0x00283541, 0x00243440, 0x0021313d, 0x0022313e, 0x00273744, 0x00263643, 0x002c3c48, 0x002d3c48, 0x00263542, 0x0023323f, 0x00243440, 0x00243542, 0x00243440, 0x0020303d, 0x00243544, 0x00293a48, 0x00293c4a, 0x002c3f4d, 0x002f4450, 0x00314450, 0x0030414e, 0x0030404c, 0x00303d48, 0x002e3b46, 0x002f3944, 0x002f3844, 0x002f3844, 0x00303844, 0x002f3642, 0x00303641, 0x00303744, 0x00313946, 0x00353d4a, 0x00353d4b, 0x00262e3c, 0x00131b28, 0x000d1824, 0x0014202a, 0x00192530, 0x001b2630, 0x001b242e, 0x00182028, 0x0010141c, 0x00070a10, 0x0005070f, 0x00090d14, 0x00131c24, 0x001f2c35, 0x00243642, 0x002a3f4c, 0x002e4454, 0x0033495a, 0x00374d5f, 0x00395062, 0x003a5265, 0x003d566c, 0x00425f77, 0x00496d86, 0x00658ca2, 0x0093b5c2, 0x00b2c9cc, 0x00c0cccc, 0x00c5cccb, 0x00caccca, 0x00cbccc9, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcbcc, 0x00cbcccc, 0x00c9cccc, 0x00c8cccc, 0x00c4cccc, 0x00becccc, 0x00aac4c8, 0x00607a87, 0x00182936, 0x000e1720, 0x00080c13, 0x0002070a, 0x00030406, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020405, 0x00020407, 0x00020407, 0x00030408, 0x0004060c, 0x00030b15, 0x00091420, 0x00101d2a, 0x00152330, 0x00142431, 0x00142431, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0011222c, 0x0011202c, 0x0010202c, 0x0010202b, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x00101e29, 0x00101e28, 0x00101d28, 0x000f1d28, 0x000f1c26, 0x000e1c25, 0x000e1c26, 0x000e1c26, 0x000e1c26, 0x000e1c26, 0x000f1c26, 0x000f1c27, 0x000f1c26, 0x00101d27, 0x00101e28, 0x00101e28, 0x00101f29, 0x0010202a, 0x0010202b, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x0016383c, 0x00183f43, 0x001c4448, 0x001d4a4d, 0x001f5053, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297b8b, 0x00286769, 0x00286a6c, 0x00296c6f, 0x002a6e70, 0x002b7071, 0x003291a8, 0x0037a9ca, 0x002e808c, 0x002c7274, 0x0030899c, 0x0036a8cb, 0x002c7b84, 0x00296d6f, 0x00296b6d, 0x0028696c, 0x00286769, 0x00266668, 0x003098b8, 0x003097b7, 0x00256063, 0x00245e60, 0x00245c5f, 0x00235a5c, 0x0022585b, 0x0022585a, 0x00205558, 0x00205356, 0x001f5154, 0x001d4d50, 0x001d4b4e, 0x001c484c, 0x001b4448, 0x001a4245, 0x00183d41, 0x00183a3e, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0013282e, 0x0012242c, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000b1119, 0x000b1119, 0x000b1219, 0x000b131a, 0x0009141a, 0x0009141a, 0x000a141b, 0x000b151c, 0x000b151d, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161d, 0x000c161f, 0x000d1720, 0x000e1820, 0x000f1921, 0x000f1a23, 0x000f1c24, 0x000d1c25, 0x000d1d26, 0x000e1e28, 0x000e1f29, 0x0010202b, 0x0012202c, 0x00121f2c, 0x00121e29, 0x00101a24, 0x000b141c, 0x00070e14, 0x0004080e, 0x00020509, 0x00020308, 0x00020308, 0x00020307, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00010406, 0x00020508, 0x00080b10, 0x000f131a, 0x00141f2a, 0x0027404d, 0x0078a1a9, 0x00bccccc, 0x00c8cccb, 0x00c7ccca, 0x00cacccb, 0x00cbcbcb, 0x00cccbcb, 0x00cccccc, 0x00cbcccc, 0x00c5cccc, 0x00bbcbcc, 0x0094b4c3, 0x00668ca2, 0x004d7086, 0x00436074, 0x003f566b, 0x00394e63, 0x0034485c, 0x002e4252, 0x00293c4b, 0x00263845, 0x0020313e, 0x001c2b38, 0x001a2733, 0x0017202c, 0x00131c25, 0x00111821, 0x000d131c, 0x000a0d14, 0x0006090e, 0x00030508, 0x0003040a, 0x00070c12, 0x000e141c, 0x00111a23, 0x00131c24, 0x00111b24, 0x000d1720, 0x0009131c, 0x00050d17, 0x00030c14, 0x0018232d, 0x0031404b, 0x00384754, 0x00344450, 0x002f3f4c, 0x0030404c, 0x002e404a, 0x00293b46, 0x002a3d49, 0x002a404b, 0x002b404d, 0x002e4250, 0x002c404e, 0x00273947, 0x00233441, 0x00253844, 0x00283b47, 0x00273845, 0x00253844, 0x00243743, 0x00243643, 0x00223340, 0x001f303c, 0x00293842, 0x0024303b, 0x00222e38, 0x0024303b, 0x00222e38, 0x001d2934, 0x00192530, 0x001b2430, 0x001c2630, 0x0019232c, 0x00161e28, 0x00141c24, 0x00171e26, 0x001a2028, 0x00171d24, 0x00161b21, 0x0014191e, 0x0011171b, 0x0010151b, 0x0012171d, 0x0010141c, 0x000d1219, 0x000d1119, 0x000c1018, 0x000f141b, 0x0010141a, 0x000f1318, 0x000d1215, 0x00101418, 0x00111519, 0x00111418, 0x000d1015, 0x000c1014, 0x000e1116, 0x000c0f14, 0x00070a0f, 0x000d1015, 0x000e1116, 0x000c0f14, 0x000e1117, 0x000e1118, 0x0010141c, 0x0014181f, 0x0013191f, 0x0010171d, 0x000d161e, 0x00101922, 0x0018232c, 0x001a242c, 0x00151e27, 0x00101821, 0x00141a23, 0x00151c22, 0x00192026, 0x001c2229, 0x001d242c, 0x001e252f, 0x001f2831, 0x00202b34, 0x001e2831, 0x00242e3a, 0x00242e39, 0x001d2933, 0x00202d37, 0x00202d37, 0x001e2a34, 0x00212d37, 0x00202c36, 0x00212e38, 0x00212e38, 0x0022303b, 0x002b3947, 0x00283744, 0x00233440, 0x0020303d, 0x00263743, 0x00283845, 0x00253642, 0x00293845, 0x00283844, 0x0023323f, 0x00263542, 0x00263744, 0x00243642, 0x00233441, 0x00263745, 0x00283847, 0x00293c4a, 0x002c414e, 0x00304450, 0x0030424e, 0x0030414e, 0x0032404c, 0x00313d48, 0x00303b44, 0x00303a44, 0x00303946, 0x00303a46, 0x00303844, 0x002e3541, 0x00303541, 0x00303844, 0x00343c48, 0x00373e4b, 0x00303845, 0x001d2532, 0x000e1724, 0x000f1924, 0x0015212b, 0x00192530, 0x00192430, 0x001a242c, 0x00161d24, 0x000e1218, 0x00080910, 0x0006080f, 0x00090d14, 0x00141c24, 0x001e2b34, 0x00243541, 0x00293e4b, 0x002c4253, 0x00314658, 0x00344a5c, 0x00374d5e, 0x00384f61, 0x00395367, 0x003e5970, 0x00406078, 0x004c7188, 0x006d94a7, 0x0097b8c4, 0x00b2c8cc, 0x00bdcccc, 0x00c5cccb, 0x00c8ccca, 0x00c8cccc, 0x00c8cccc, 0x00c8cccc, 0x00c7cccc, 0x00c7cccc, 0x00c6cccc, 0x00c4cccc, 0x00c0cccc, 0x00b6cccc, 0x009cbcc4, 0x00506a77, 0x00142330, 0x000e141e, 0x00080b12, 0x0004060a, 0x00030405, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00020404, 0x00020405, 0x00020405, 0x00020405, 0x00020407, 0x00020408, 0x0003070d, 0x00050d16, 0x000c1723, 0x0014202c, 0x00162430, 0x00142430, 0x0012242e, 0x0012242e, 0x0012242e, 0x0011232d, 0x0011202c, 0x0011202c, 0x0011202c, 0x0010202b, 0x000f1f29, 0x000f1f29, 0x000f1f29, 0x00101d28, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000c1b24, 0x000c1b23, 0x000c1a24, 0x000c1a24, 0x000c1a24, 0x000e1c24, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000e1c25, 0x000f1c24, 0x000f1d26, 0x000e1e27, 0x000e1e27, 0x000f1f28, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x0016383c, 0x00183f43, 0x001c4448, 0x001d4a4d, 0x001e4f51, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297b8b, 0x00286769, 0x00286a6c, 0x00296c6f, 0x002a6e70, 0x002b7071, 0x003291a8, 0x0037a9ca, 0x002e808c, 0x002c7274, 0x002f899c, 0x0036a8cb, 0x002c7a84, 0x00296c6f, 0x00296b6d, 0x0028686b, 0x00286769, 0x00276668, 0x003098b8, 0x00309cbe, 0x00297c90, 0x00287c8f, 0x00287b8f, 0x00287a8f, 0x00287a8f, 0x00277a8f, 0x0026798f, 0x0026788f, 0x0025788e, 0x0024778e, 0x00237086, 0x001d4e54, 0x001c474b, 0x001b4448, 0x00194044, 0x00183c40, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1018, 0x000c1018, 0x000c1118, 0x000b131a, 0x0009141a, 0x0009141a, 0x000a141b, 0x000b151c, 0x000b151d, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161d, 0x000d1720, 0x000e1820, 0x000f1921, 0x00101a23, 0x00101b24, 0x00111c25, 0x00101c26, 0x00101d27, 0x00101f29, 0x0010202b, 0x0010202c, 0x0011202c, 0x0013202c, 0x00111c28, 0x000c151f, 0x00080e16, 0x00040a10, 0x0003060b, 0x00020408, 0x00020307, 0x00020407, 0x00020306, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00010406, 0x00020608, 0x00070a10, 0x000e121a, 0x00141d29, 0x00243d4c, 0x00709ca5, 0x00b6cccc, 0x00c5cccc, 0x00c7cccb, 0x00cacccb, 0x00cacccb, 0x00cbcccb, 0x00cccccc, 0x00c8cccc, 0x00bbcbcc, 0x00a0bbc5, 0x006f93a9, 0x0050748c, 0x00456479, 0x0040596e, 0x003c5165, 0x00364a5f, 0x00334658, 0x002d4050, 0x00293b49, 0x00253543, 0x00202f3c, 0x001c2935, 0x00192530, 0x0016202c, 0x00131b24, 0x00101720, 0x000d141c, 0x000a0d14, 0x00070a0e, 0x00040609, 0x0003050a, 0x00040a10, 0x000b1218, 0x00101820, 0x00121b24, 0x00121c24, 0x000f1820, 0x000c131c, 0x00091018, 0x00080f17, 0x0018212b, 0x002a3742, 0x0034424f, 0x0032404d, 0x00303d4b, 0x0032404d, 0x0032414e, 0x002b3c49, 0x002f4250, 0x002a3f4c, 0x002c414f, 0x00304452, 0x002f4451, 0x00263a48, 0x00213441, 0x00253844, 0x00283b47, 0x00283c48, 0x002b3e4a, 0x00283b48, 0x00273945, 0x00253743, 0x00233440, 0x00283843, 0x00222f39, 0x00202c36, 0x00202c36, 0x00202c37, 0x001e2935, 0x00192430, 0x001e2833, 0x001d2731, 0x0018212b, 0x00151f27, 0x00121c24, 0x00182028, 0x00192028, 0x00192027, 0x00181e25, 0x00141a1f, 0x0014191d, 0x0014191e, 0x0014181e, 0x000e121a, 0x000b1018, 0x000e131b, 0x000c1018, 0x000f141b, 0x000e1218, 0x000b0d14, 0x000b0e13, 0x000c0f14, 0x000b0e13, 0x0011141a, 0x0014171d, 0x00101319, 0x000d1017, 0x000c0e13, 0x00080b0f, 0x000b0e13, 0x000f1217, 0x000e1116, 0x000f1218, 0x000a0d14, 0x000c1017, 0x0010151c, 0x00141a20, 0x00161e24, 0x00141c24, 0x000f1821, 0x0019232c, 0x001b252e, 0x00172028, 0x00151c26, 0x00141b24, 0x0011181f, 0x00151c21, 0x001b2228, 0x001c232a, 0x001d262f, 0x00222e36, 0x00212d35, 0x0019262f, 0x00212d39, 0x0024303c, 0x001e2b34, 0x0023303a, 0x00223039, 0x001c2a34, 0x00202d37, 0x0024303a, 0x00293740, 0x0024333c, 0x0023313d, 0x002a3947, 0x00273744, 0x00243542, 0x0020313d, 0x00273844, 0x002b3c48, 0x001f303c, 0x0023323f, 0x00273642, 0x00243440, 0x00283744, 0x002b3c48, 0x00283b47, 0x00243744, 0x00243645, 0x00293b4a, 0x002d404e, 0x00304451, 0x00314451, 0x0030414e, 0x0030404d, 0x0032404c, 0x00313c47, 0x00303a44, 0x00313944, 0x00323a45, 0x00303945, 0x00303744, 0x002f3541, 0x00303642, 0x00323a46, 0x00363e4b, 0x00373f4c, 0x002a323f, 0x00141c29, 0x000d1523, 0x00121c27, 0x0016212c, 0x0018242d, 0x0018242e, 0x0018202a, 0x00141920, 0x000c0f16, 0x00080810, 0x0006080f, 0x00090d14, 0x00141c25, 0x001c2934, 0x00233540, 0x00283c4a, 0x002c4051, 0x00304457, 0x0034485b, 0x00364c5d, 0x00374d5f, 0x00385064, 0x003a5468, 0x003c586f, 0x00416178, 0x0053778d, 0x007095aa, 0x0091b5c2, 0x00a8c5cb, 0x00b4cacc, 0x00b6cbcc, 0x00b8cbcc, 0x00b8cbcc, 0x00b8cbcc, 0x00b8cbcc, 0x00b7cbcc, 0x00b7cccc, 0x00b5cccc, 0x00b2cccc, 0x00a9c8cc, 0x0089abb9, 0x003e5766, 0x00101d2a, 0x000b1019, 0x00080a10, 0x00040608, 0x00020405, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010404, 0x00020404, 0x00020404, 0x00020404, 0x00020404, 0x00020307, 0x00020308, 0x00030409, 0x0004080e, 0x00081018, 0x00101924, 0x0015202c, 0x0015242f, 0x0013232e, 0x0012242e, 0x0012242e, 0x0011232d, 0x0011212c, 0x0012212c, 0x0012212c, 0x0011202c, 0x0010202b, 0x0010202b, 0x00101f2a, 0x00101e28, 0x000f1c26, 0x000e1c25, 0x000d1b24, 0x000c1a21, 0x000c1a21, 0x000c1921, 0x000c1923, 0x000b1823, 0x000c1923, 0x000e1923, 0x000e1a24, 0x000f1a24, 0x000f1a24, 0x000f1b23, 0x000e1b23, 0x000e1c24, 0x000f1c25, 0x00101d26, 0x000c1c24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x0016383c, 0x00183f43, 0x001c4448, 0x001c4a4d, 0x001f4f51, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297b8b, 0x00286769, 0x0028696c, 0x00296c6f, 0x002a6e70, 0x002c7071, 0x003291a8, 0x0037a8ca, 0x002e808c, 0x002b7173, 0x0030899c, 0x0036a8cb, 0x002c7984, 0x00296c6e, 0x00286a6c, 0x0028686b, 0x00276668, 0x00266568, 0x003097b7, 0x0032a5cb, 0x0030a4ca, 0x0030a4ca, 0x0030a4ca, 0x0030a4ca, 0x0030a4ca, 0x002fa4ca, 0x002fa4ca, 0x002ea3ca, 0x002da2ca, 0x002ca2ca, 0x002ca1ca, 0x00247993, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183d41, 0x00183a3e, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1018, 0x000c1018, 0x000c1018, 0x000b131a, 0x0009141a, 0x0009141a, 0x000a141b, 0x000b151c, 0x000b151d, 0x000b151e, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161d, 0x000d1720, 0x000f1921, 0x00101a23, 0x00101b24, 0x00111c24, 0x00121c25, 0x00101d28, 0x00111f28, 0x0012202a, 0x0011202c, 0x0010202c, 0x0011202c, 0x00111f2a, 0x000e1824, 0x0008101a, 0x00050b10, 0x0003070b, 0x00020508, 0x00030406, 0x00020405, 0x00020405, 0x00020404, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010405, 0x00020508, 0x00070a0f, 0x000c1119, 0x00121c28, 0x001f3846, 0x0065929d, 0x00adcacb, 0x00c1cccc, 0x00c7cccb, 0x00c9cccb, 0x00c9cccb, 0x00cbcccb, 0x00cbcccc, 0x00c4cccc, 0x00a4bfc8, 0x00789bae, 0x00537890, 0x0045667e, 0x00405c71, 0x003d5468, 0x00384c60, 0x0034475a, 0x00304153, 0x002a3c4c, 0x00273847, 0x00243341, 0x001f2c3b, 0x001c2834, 0x00182430, 0x00141f2a, 0x00111a24, 0x00101620, 0x000d141c, 0x000a0e15, 0x00080b0f, 0x0004060a, 0x0003040a, 0x0003080e, 0x00080f15, 0x000d151c, 0x00111920, 0x00131b23, 0x00101821, 0x000c141d, 0x000b1218, 0x000a1018, 0x00131b24, 0x001e2833, 0x002a3844, 0x002f3b48, 0x002f3b48, 0x00323e4c, 0x00323f4c, 0x002c3b48, 0x00324351, 0x002e414f, 0x002c4350, 0x00304653, 0x00304552, 0x00293d4b, 0x00203441, 0x00253844, 0x00283b47, 0x002a3d49, 0x002c3d4b, 0x00293c49, 0x00283c48, 0x00293a47, 0x00283a46, 0x00283843, 0x00212f39, 0x001f2b35, 0x00202c36, 0x00202d38, 0x001c2834, 0x00192430, 0x00222c37, 0x001c2731, 0x0016202a, 0x00141f28, 0x00141d25, 0x00182128, 0x00182028, 0x001a2229, 0x00181f26, 0x00141a20, 0x0013181e, 0x0011161c, 0x0011161d, 0x000f141c, 0x000b1018, 0x000e131b, 0x00090e16, 0x000b1017, 0x000f1319, 0x00090c13, 0x00080c10, 0x00080c10, 0x00080c10, 0x00080a11, 0x000a0c14, 0x000c1016, 0x000c0f15, 0x000a0d13, 0x000b0e13, 0x000c0f14, 0x000e1116, 0x000d1014, 0x000c0f14, 0x00080c12, 0x000b0f15, 0x000c1118, 0x0010171c, 0x00131b21, 0x00161e27, 0x00141f28, 0x0019242c, 0x001a242c, 0x00151e27, 0x00181f28, 0x00181e28, 0x0010161e, 0x0010171c, 0x00161c24, 0x00192028, 0x001a232c, 0x00212d35, 0x00202d35, 0x001b2830, 0x00202c38, 0x0025323d, 0x00202d37, 0x0024313b, 0x0027343e, 0x001f2c36, 0x00222f39, 0x0024343c, 0x002c3b44, 0x00273740, 0x00253641, 0x002b3c48, 0x00273844, 0x00273844, 0x00243441, 0x00283946, 0x002f404c, 0x00243440, 0x0022313c, 0x0024343f, 0x00253441, 0x00283844, 0x002c3e4a, 0x002b404b, 0x00283c49, 0x00273a49, 0x002d404f, 0x00314654, 0x00324754, 0x00314551, 0x002f3f4b, 0x002e3c48, 0x00303c48, 0x00303b45, 0x00313944, 0x00333944, 0x00323944, 0x00303843, 0x00303742, 0x00303641, 0x00303743, 0x00343b47, 0x0038404d, 0x00353c49, 0x00222a37, 0x000f1724, 0x00101824, 0x00141d28, 0x0015202b, 0x0016212c, 0x0017212c, 0x00181f28, 0x00141820, 0x000c0d14, 0x0007080f, 0x00060810, 0x00090d15, 0x00131c25, 0x001c2834, 0x00223440, 0x00273b48, 0x002a3e4f, 0x002e4254, 0x00324659, 0x00344a5c, 0x00364c5d, 0x00364d60, 0x00375064, 0x00385468, 0x003c5970, 0x0043637a, 0x0050748c, 0x00648da3, 0x007ba4b8, 0x0088b0c2, 0x008cb3c4, 0x008eb4c4, 0x008fb5c6, 0x0092b8c8, 0x0094b9c8, 0x0096bcca, 0x0098beca, 0x0098c0cb, 0x0098c0cb, 0x008db5c7, 0x006a8ca1, 0x00294152, 0x000c1824, 0x00080d14, 0x0006080d, 0x00040608, 0x00030405, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010304, 0x00020404, 0x00020404, 0x00020307, 0x00020308, 0x00020408, 0x00040509, 0x0005080f, 0x00090e17, 0x00101923, 0x0014202c, 0x0013232e, 0x0012242e, 0x0012242e, 0x0012242e, 0x0012232d, 0x0013222d, 0x0013222d, 0x0013222c, 0x0012212c, 0x0012212c, 0x0011202c, 0x0010202b, 0x00101f28, 0x000f1d27, 0x000f1c26, 0x000e1c24, 0x000c1a20, 0x000b1920, 0x000b1921, 0x000b1820, 0x000c1820, 0x000c1820, 0x000d1921, 0x000d1922, 0x000e1a22, 0x000d1920, 0x000c1920, 0x000c1a21, 0x000c1a21, 0x000d1c23, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00112229, 0x00102229, 0x0011242c, 0x00122a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183f43, 0x001b4448, 0x001c4a4d, 0x001e4f51, 0x00205457, 0x0022585b, 0x002b859f, 0x0032a5cb, 0x00297a8a, 0x00286769, 0x0028696c, 0x00296c6e, 0x00296d6f, 0x002b6f70, 0x003191a8, 0x0037a8ca, 0x002d808c, 0x002b7173, 0x0030899b, 0x0036a8cb, 0x002c7984, 0x002a6c6e, 0x0028696c, 0x0028686a, 0x00276568, 0x00276467, 0x00276d78, 0x0028707d, 0x0026707c, 0x00266e7b, 0x00256d79, 0x00266c78, 0x00266b77, 0x00246a76, 0x00246975, 0x00246873, 0x00236671, 0x00226470, 0x002a90b2, 0x002b99be, 0x001d4d51, 0x001c484c, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0013282e, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1018, 0x000c1018, 0x000c1018, 0x000b131a, 0x0009141a, 0x0009141b, 0x000a141c, 0x000b151c, 0x000b151d, 0x000b151e, 0x000b151e, 0x000b151e, 0x000c161f, 0x000c171f, 0x000e1820, 0x00101a23, 0x00101b24, 0x00111c24, 0x00121c25, 0x00131d27, 0x00111f28, 0x0012202a, 0x0014212c, 0x0012212c, 0x0012212c, 0x00101f2a, 0x000e1924, 0x000a121c, 0x00060c14, 0x0004070c, 0x00030508, 0x00030405, 0x00030304, 0x00030404, 0x00020404, 0x00020404, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000405, 0x00020508, 0x0004080c, 0x00090e15, 0x000e1823, 0x0019303d, 0x005b808d, 0x00a8c5c8, 0x00bccccc, 0x00c4cccc, 0x00c8cccc, 0x00c8cccc, 0x00c8cccc, 0x00c5cccc, 0x00b5c5ca, 0x0082a4b7, 0x00587d94, 0x00486881, 0x00445f75, 0x003e556a, 0x00394f62, 0x0034485a, 0x00304354, 0x002c3e4e, 0x00293847, 0x00263544, 0x0023303f, 0x001f2b39, 0x001c2834, 0x0018232f, 0x00141e29, 0x00111923, 0x000f151f, 0x000d131b, 0x000b0e15, 0x00080c10, 0x0004070b, 0x0002040a, 0x0003070d, 0x00080c13, 0x000c131a, 0x0010181f, 0x00111921, 0x00101821, 0x000e141e, 0x000c1219, 0x00090f15, 0x00091018, 0x000f1721, 0x00232c39, 0x002d3744, 0x00303946, 0x00323c48, 0x00313c49, 0x002c3a46, 0x0030414f, 0x002e404e, 0x002c414f, 0x00304554, 0x00304654, 0x002c404f, 0x00253845, 0x00263946, 0x00283c48, 0x002b3d4a, 0x002b3d4c, 0x002d404d, 0x002e404e, 0x002c3d4b, 0x00283946, 0x00263541, 0x0023303a, 0x00202d37, 0x00222f39, 0x0022303a, 0x001b2733, 0x001d2934, 0x00242f39, 0x001e2832, 0x0019232c, 0x00162028, 0x00152028, 0x00172028, 0x00182028, 0x00172027, 0x00141b23, 0x00131920, 0x0011181e, 0x0010151c, 0x0012171f, 0x0010141c, 0x000a0f16, 0x000c1017, 0x000c1117, 0x000e1419, 0x0014181f, 0x000e1118, 0x000a0e13, 0x00080b10, 0x00080c10, 0x00080c12, 0x00080b12, 0x00080c13, 0x000c0e15, 0x000c0f15, 0x000d1117, 0x000d1016, 0x000c0f14, 0x00090d13, 0x00090c13, 0x00090c13, 0x00080d13, 0x000b1016, 0x000c1319, 0x0010181e, 0x00151e27, 0x00151f28, 0x00172129, 0x0019232c, 0x00151f28, 0x00171e27, 0x001a202a, 0x00141922, 0x0011181e, 0x00141b22, 0x00181f28, 0x001c232e, 0x00202a36, 0x00222d38, 0x0022303a, 0x0022303c, 0x0026343f, 0x0025333d, 0x0025333d, 0x002a3843, 0x0023303c, 0x0024323d, 0x00263641, 0x002c3c47, 0x00263742, 0x002c3c48, 0x002e3f4c, 0x002b3c48, 0x002a3b48, 0x00273845, 0x00283b47, 0x002d3f4c, 0x00283844, 0x0022323d, 0x0024343f, 0x00253442, 0x00253543, 0x002b3c49, 0x002c404c, 0x002c404d, 0x002c404d, 0x00304553, 0x00344856, 0x00344755, 0x00334350, 0x002f3c48, 0x002e3844, 0x00303944, 0x00303844, 0x00333944, 0x00343944, 0x00333944, 0x00313844, 0x00303742, 0x00303742, 0x00313843, 0x00343c48, 0x00373f4c, 0x002d3441, 0x0019202d, 0x000d1521, 0x000f1824, 0x00111c26, 0x00141e29, 0x0015202b, 0x0016202a, 0x00151c26, 0x0010141c, 0x00090c10, 0x0004080c, 0x0005090f, 0x00091017, 0x00141e28, 0x001c2936, 0x0021323f, 0x00273947, 0x00293d4d, 0x002d4051, 0x00314455, 0x00344858, 0x00354a5c, 0x00364c5f, 0x00364d60, 0x00384f64, 0x003b5469, 0x003e5971, 0x0044627b, 0x004c6e88, 0x00587b96, 0x005f85a0, 0x006188a4, 0x006188a4, 0x006088a4, 0x006089a5, 0x00618aa5, 0x00648ca8, 0x006790ab, 0x006993ac, 0x006a94ac, 0x00648aa3, 0x00446479, 0x00192c3c, 0x000a101c, 0x00070910, 0x00040609, 0x00040507, 0x00030405, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00020404, 0x00020307, 0x00020308, 0x00030408, 0x00040507, 0x0004060a, 0x0007090f, 0x000a1118, 0x00101b24, 0x0013212c, 0x0012232d, 0x0012242e, 0x0012242e, 0x0013232e, 0x00142430, 0x00142430, 0x00142430, 0x00142330, 0x0014232f, 0x0013222e, 0x0012222d, 0x0011212c, 0x0011202b, 0x00101e29, 0x00101d27, 0x000d1b23, 0x000c1a21, 0x000b1921, 0x000a1820, 0x000b1720, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c1820, 0x000c181f, 0x000c1820, 0x000c1820, 0x000c1920, 0x000d1b23, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0011242c, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4347, 0x001c484c, 0x001e4f51, 0x00205356, 0x0022585b, 0x002a859f, 0x0031a4cb, 0x00297a8a, 0x00286769, 0x0028696c, 0x00296c6e, 0x002a6d6f, 0x002b6f70, 0x003191a8, 0x0036a8ca, 0x002d808c, 0x002b7072, 0x0030899b, 0x0036a8cb, 0x002c7883, 0x00296b6d, 0x0028686b, 0x00286769, 0x00276568, 0x00266466, 0x00256264, 0x00256163, 0x00245f61, 0x00245f61, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0021575a, 0x00298eae, 0x002b9ac0, 0x001e5054, 0x001d4b4e, 0x001b4649, 0x001a4245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0012242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a1018, 0x000b1119, 0x000c1219, 0x000c141c, 0x000c141c, 0x000b141d, 0x000b151e, 0x000c161f, 0x000c161f, 0x000c161f, 0x000c1620, 0x000c1720, 0x000c1821, 0x000c1821, 0x000d1923, 0x000f1b24, 0x00101c25, 0x00111c26, 0x00121d27, 0x00131f29, 0x0013202b, 0x0012212c, 0x0012212c, 0x0013212c, 0x0011202a, 0x000c1a24, 0x000a141d, 0x00080d15, 0x0005080d, 0x00040608, 0x00030405, 0x00020404, 0x00010304, 0x00010304, 0x00010304, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000405, 0x00010408, 0x0004070a, 0x00080d13, 0x000e1620, 0x00172936, 0x004b6875, 0x009ab9c1, 0x00b5cccc, 0x00bccccc, 0x00bfcccc, 0x00c0cccc, 0x00bdcccc, 0x00b3c7cb, 0x0090abba, 0x00608296, 0x004b6c83, 0x00446278, 0x0040586d, 0x003b5064, 0x00384b5e, 0x00314558, 0x002d4051, 0x00293b4a, 0x00273644, 0x00253442, 0x0022303d, 0x001f2c38, 0x001c2834, 0x0018232f, 0x00141d28, 0x00111822, 0x000f151e, 0x000c121a, 0x000b0e15, 0x00090c10, 0x0004070b, 0x0002050a, 0x0004080c, 0x00080c11, 0x000e141b, 0x0010171e, 0x00101820, 0x00101820, 0x000e141d, 0x000c1118, 0x00080d14, 0x00060b12, 0x00070c16, 0x0019202b, 0x002b313d, 0x00303844, 0x00303a45, 0x002f3b46, 0x002c3a45, 0x002e3e4c, 0x002d404e, 0x00283e4c, 0x002c4454, 0x002f4654, 0x002b4150, 0x00293c4c, 0x00273a48, 0x00283c49, 0x002b3e4c, 0x002c404d, 0x00314452, 0x00324452, 0x002f404f, 0x00283845, 0x0023323e, 0x0021303b, 0x00202f39, 0x0021303b, 0x0020303a, 0x001b2834, 0x00202d38, 0x0026303c, 0x00222c35, 0x001d262f, 0x00182129, 0x00152026, 0x00162027, 0x00172028, 0x00171f26, 0x00131a22, 0x00111920, 0x00101820, 0x00131920, 0x00131920, 0x000f141a, 0x00090e14, 0x000b1016, 0x000e1318, 0x0014181f, 0x0014191f, 0x000c1117, 0x00080c11, 0x00080c11, 0x00090d12, 0x00090d14, 0x00080c13, 0x000c1117, 0x000b0f15, 0x000c1118, 0x0010151d, 0x000d1218, 0x00090e13, 0x00080c11, 0x000b0e13, 0x000e1015, 0x000a0c12, 0x000a0e13, 0x000c1016, 0x000e141a, 0x00121a22, 0x00131c25, 0x00121c25, 0x0018242c, 0x001b242d, 0x00141c26, 0x0019202a, 0x00161c25, 0x00131921, 0x00161c24, 0x00181e29, 0x001a222f, 0x00202935, 0x00232d3a, 0x0024323f, 0x0024313f, 0x00243340, 0x00273643, 0x00283844, 0x002b3a47, 0x00263441, 0x00273642, 0x00293945, 0x002b3b48, 0x00273844, 0x002c3e4a, 0x002e404d, 0x002b3e4c, 0x002a3f4c, 0x00273a47, 0x00253846, 0x002a3d4a, 0x002b3c49, 0x00233440, 0x0022343f, 0x00243541, 0x00233443, 0x00263a48, 0x002a404d, 0x00304452, 0x00324554, 0x00364855, 0x00374854, 0x00354450, 0x00323e4b, 0x002f3945, 0x002f3844, 0x00303844, 0x00313944, 0x00323844, 0x00333944, 0x00333944, 0x00323844, 0x00313843, 0x00323844, 0x00343a46, 0x00373d48, 0x00343c47, 0x00252d37, 0x00121a24, 0x000d161f, 0x00101922, 0x00101b25, 0x00141d28, 0x00141f29, 0x00141e28, 0x00121923, 0x000c1018, 0x0006090f, 0x0003060a, 0x0005090c, 0x00091015, 0x00131d26, 0x001c2934, 0x0020313c, 0x00253844, 0x00293c4b, 0x002c3f50, 0x00304253, 0x00324657, 0x0034495a, 0x00374b5d, 0x00384c5e, 0x00384d60, 0x00385062, 0x003a5467, 0x003d586c, 0x00415d74, 0x0048657c, 0x004d6c84, 0x004f6f87, 0x004c6d86, 0x004a6a83, 0x00486880, 0x0045657d, 0x0041647c, 0x0041647b, 0x00406479, 0x00426277, 0x003e596f, 0x002d4255, 0x00101d2b, 0x00080b15, 0x0005060b, 0x00040408, 0x00030406, 0x00020404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010304, 0x00010306, 0x00010306, 0x00020406, 0x00030508, 0x00040509, 0x0005070c, 0x00070b10, 0x000c1118, 0x00101c24, 0x0013222b, 0x0012242c, 0x0012242e, 0x0012252f, 0x00142531, 0x00142532, 0x00142532, 0x00142431, 0x00142430, 0x0012242e, 0x0012242e, 0x0012222c, 0x0012212b, 0x0011202a, 0x00101e28, 0x000f1c26, 0x000d1b24, 0x000b1822, 0x000a1821, 0x000b1720, 0x000b1720, 0x000b1620, 0x000a161f, 0x000a161e, 0x000b171d, 0x000b171f, 0x000c1820, 0x000c1820, 0x000d1922, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0011242c, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x001a4347, 0x001c484c, 0x001d4d50, 0x00205356, 0x0021585a, 0x0029859f, 0x0031a4cb, 0x00297a8a, 0x00276668, 0x0028686b, 0x00296b6d, 0x00296c6f, 0x002a6e70, 0x003191a8, 0x0036a8ca, 0x002e7f8c, 0x002c7071, 0x002f889b, 0x0035a8cb, 0x002c7883, 0x00286a6c, 0x0028686a, 0x00276668, 0x00266467, 0x00256364, 0x00256163, 0x00246062, 0x00245f61, 0x00245e60, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022585b, 0x002a8faf, 0x002b9bc0, 0x001e5054, 0x001d4b4e, 0x001c474b, 0x001a4347, 0x00183d41, 0x00183a3e, 0x00153439, 0x00142e34, 0x00122a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00091118, 0x000a1219, 0x000b141a, 0x000c141d, 0x000d151f, 0x000d161f, 0x000c1720, 0x000e1820, 0x000e1820, 0x000d1820, 0x000e1821, 0x000e1823, 0x000e1a24, 0x000d1b24, 0x000f1b25, 0x00101c26, 0x00111d27, 0x00121d28, 0x00121e28, 0x00121f29, 0x0012212c, 0x0012222d, 0x0013212c, 0x0013202a, 0x00101c24, 0x0009141c, 0x00070e14, 0x00060a0f, 0x00040708, 0x00040405, 0x00020403, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000405, 0x00010406, 0x00030708, 0x00080c0f, 0x000d131a, 0x0014202b, 0x00394f5d, 0x007c9fb1, 0x009cc0cb, 0x00a4c4cc, 0x00a7c5cc, 0x00a8c5cc, 0x00a2c1ca, 0x008db0c0, 0x006789a0, 0x004d6e84, 0x00466479, 0x00415c70, 0x003d5367, 0x00394c60, 0x00344659, 0x002e4154, 0x002b3c4d, 0x00283848, 0x00263443, 0x00243240, 0x00212f3c, 0x001e2b38, 0x001a2733, 0x0017222e, 0x00141d28, 0x00101821, 0x000f151d, 0x000c121a, 0x000b0e15, 0x00090c11, 0x0004070a, 0x00020508, 0x0004080b, 0x00080c10, 0x000d121a, 0x000f151d, 0x000e161e, 0x000e161f, 0x000c131c, 0x000c1018, 0x00080d14, 0x00050a10, 0x0004080f, 0x0010141c, 0x00222932, 0x002e3641, 0x00303945, 0x002c3945, 0x002c3a46, 0x002d3e4a, 0x002e414e, 0x002b404e, 0x002d4554, 0x002d4454, 0x002c4051, 0x002a3f4e, 0x00283c4c, 0x00293e4d, 0x002d4250, 0x002f4452, 0x00324554, 0x00314453, 0x00304150, 0x00283947, 0x0022313e, 0x00202f3b, 0x001f2f39, 0x0020303a, 0x00202f39, 0x001c2a35, 0x00202e39, 0x0024303b, 0x00222c37, 0x0019232c, 0x00121c24, 0x00131d24, 0x00182128, 0x00141d24, 0x00161f26, 0x00101820, 0x00131c22, 0x00141c24, 0x00111921, 0x00121820, 0x000e1318, 0x00080d11, 0x00060c0f, 0x000d1216, 0x00171c20, 0x0014191d, 0x00090f13, 0x00050a0f, 0x00080c11, 0x000a0f14, 0x00090e13, 0x00070c12, 0x000c1318, 0x000a1016, 0x000d141a, 0x0013181f, 0x0011171b, 0x000c1115, 0x00080c10, 0x00090d11, 0x000f1016, 0x000c0f14, 0x000a0d12, 0x000f1418, 0x0010161b, 0x0010171f, 0x00101a23, 0x00141e27, 0x001b262e, 0x001e2832, 0x001b232e, 0x0018202c, 0x00151c25, 0x00131921, 0x00181e28, 0x00181f2b, 0x0019212e, 0x001d2734, 0x00232f3b, 0x00253440, 0x0024323f, 0x00253340, 0x00243440, 0x00263542, 0x00283844, 0x00283844, 0x00293846, 0x00293a47, 0x00263844, 0x00253844, 0x002c3f4c, 0x002b3e4c, 0x00283f4c, 0x002a404c, 0x00283d4b, 0x00243947, 0x002b3e4c, 0x00304450, 0x00273945, 0x00233642, 0x00243844, 0x00243744, 0x00263b48, 0x002a404d, 0x00314855, 0x00354857, 0x00384856, 0x0036434f, 0x00323c48, 0x00303944, 0x002f3842, 0x002f3843, 0x00303944, 0x00313944, 0x00323844, 0x00323844, 0x00343845, 0x00333844, 0x00333944, 0x00343a46, 0x00373d48, 0x00383f48, 0x002e373f, 0x001c242c, 0x000d161d, 0x000e161d, 0x00101922, 0x00121b24, 0x00141d26, 0x00141e26, 0x00121c24, 0x0010161f, 0x00090d15, 0x0005080d, 0x0003070b, 0x00060a0e, 0x000b1117, 0x00131f26, 0x001c2934, 0x001f303c, 0x00233642, 0x00273a49, 0x002b3d4d, 0x002d4050, 0x00304454, 0x00334858, 0x00364a5c, 0x00384c5d, 0x00374c5d, 0x00354c5d, 0x00354d5f, 0x00385063, 0x003c566a, 0x00425c71, 0x00486379, 0x004b677e, 0x004a667d, 0x0046637a, 0x00436076, 0x003f5b71, 0x0039556b, 0x00365266, 0x00345061, 0x00344c5c, 0x00304251, 0x0023303d, 0x000e1420, 0x0006080f, 0x00040608, 0x00040507, 0x00030406, 0x00010404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020405, 0x00030408, 0x00030408, 0x00030508, 0x0005070a, 0x00080b0f, 0x000c1419, 0x00111d24, 0x0013232b, 0x0014252f, 0x00142630, 0x00142733, 0x00142733, 0x00142733, 0x00142733, 0x00142632, 0x0013242f, 0x0012242e, 0x0013242d, 0x0013222c, 0x0011202a, 0x00101f29, 0x00101e28, 0x000e1c25, 0x000c1a24, 0x000b1823, 0x000c1822, 0x000c1721, 0x000b1620, 0x0009151e, 0x0008141d, 0x0009151c, 0x000b171e, 0x000c1820, 0x000c1820, 0x000d1921, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0013242c, 0x00112a30, 0x00142e34, 0x00143036, 0x0016363b, 0x00183d41, 0x001a4245, 0x001c474b, 0x001e4d50, 0x00205254, 0x0021585a, 0x002a849f, 0x0031a4cb, 0x0029798a, 0x00276568, 0x0028686a, 0x00286a6c, 0x00296c6f, 0x002a6d6f, 0x003190a8, 0x0036a8ca, 0x002d7f8b, 0x002b6f70, 0x002f889a, 0x0035a8cb, 0x002c7882, 0x0028696c, 0x00286769, 0x00276568, 0x00266466, 0x00256264, 0x00246062, 0x00245f61, 0x00245e60, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x002a8faf, 0x002c9bc0, 0x001e5054, 0x001e4c50, 0x001c474b, 0x001b4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00142e34, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000a131a, 0x000b141b, 0x000c141c, 0x000c151d, 0x000e171f, 0x000e1720, 0x000e1820, 0x000e1821, 0x000f1921, 0x000f1921, 0x000f1922, 0x000f1a24, 0x00101c25, 0x000f1c26, 0x00101c26, 0x00101d27, 0x00111d27, 0x00131d28, 0x00121e28, 0x00111e29, 0x0011202c, 0x0011212c, 0x0013202c, 0x00101c26, 0x000c151d, 0x00080f16, 0x00050a10, 0x0004080b, 0x00040507, 0x00030404, 0x00010303, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000404, 0x00000404, 0x00020507, 0x0005090b, 0x00090f15, 0x000e1923, 0x00283b49, 0x00587990, 0x00759cb6, 0x007ca3bb, 0x007fa5bc, 0x007ea4ba, 0x00749ab1, 0x006488a0, 0x004f7088, 0x00456279, 0x00415c70, 0x003e5669, 0x003a4f62, 0x0036485c, 0x00304356, 0x002c4050, 0x002a3c4a, 0x00283745, 0x00263442, 0x0024313f, 0x00202e3b, 0x001d2b37, 0x00192733, 0x0016222e, 0x00141d28, 0x00111822, 0x000f151e, 0x000d131b, 0x000b0f16, 0x00090c10, 0x0004080b, 0x00020508, 0x00020608, 0x0006090d, 0x000a0f17, 0x000d141c, 0x000d141d, 0x000c141e, 0x000c131b, 0x000c1018, 0x00090e14, 0x00060b11, 0x0003080e, 0x00080e14, 0x00181f27, 0x0029303b, 0x00303944, 0x002d3945, 0x002c3945, 0x002c3b48, 0x002e404d, 0x002e4351, 0x002e4454, 0x002e4554, 0x002e4454, 0x002c4251, 0x002c4050, 0x002b4050, 0x002d4251, 0x00304454, 0x00304454, 0x00304352, 0x002c3f4e, 0x00283847, 0x00233340, 0x0022313d, 0x0022313d, 0x0022313c, 0x0024333d, 0x00202d38, 0x00202d38, 0x001f2c36, 0x001f2a33, 0x001b252e, 0x00111c24, 0x00141f25, 0x001c242c, 0x00121b22, 0x00141d24, 0x000f171e, 0x00171f26, 0x00141d24, 0x00121b22, 0x00121920, 0x000c1118, 0x00070c10, 0x00040a0c, 0x000b1014, 0x0013181c, 0x0010151a, 0x000a0f13, 0x00080e12, 0x00080d12, 0x000a0f13, 0x000b1015, 0x000a0f15, 0x000d1419, 0x000c1318, 0x00131a20, 0x00141920, 0x0011161b, 0x0010151a, 0x000c1014, 0x00090d12, 0x000f1217, 0x00101418, 0x000c1014, 0x000c1014, 0x00141a20, 0x00151c24, 0x00111923, 0x00101922, 0x001c262f, 0x001e2932, 0x001e2832, 0x001c2630, 0x00141c25, 0x00141a22, 0x00181f28, 0x001a202c, 0x001c2430, 0x001f2936, 0x00273440, 0x00253540, 0x00243440, 0x00253442, 0x00253441, 0x0023323f, 0x00263542, 0x002c3b48, 0x002a3846, 0x00293a46, 0x00243541, 0x00253844, 0x002d404f, 0x00293d4b, 0x002a404d, 0x0028404c, 0x00263c4a, 0x00243947, 0x00283c49, 0x002e414e, 0x00273b47, 0x00243844, 0x00283b47, 0x00293c48, 0x002a3f4c, 0x002c4450, 0x00324855, 0x00354856, 0x00354452, 0x00333d4a, 0x00313844, 0x00313742, 0x00303741, 0x00303842, 0x00303943, 0x00313944, 0x00323844, 0x00323844, 0x00323844, 0x00323844, 0x00343945, 0x00353c47, 0x00373d48, 0x00343b45, 0x00252d35, 0x00121a21, 0x000d141c, 0x0010171e, 0x00111922, 0x00121b24, 0x00121c24, 0x00111b24, 0x00111922, 0x000f141c, 0x000a0c13, 0x0005080c, 0x0004070c, 0x00070b10, 0x000c1318, 0x00141f26, 0x001b2832, 0x001f2f3a, 0x00223440, 0x00263846, 0x002a3b4b, 0x002c3e4e, 0x002e4253, 0x00324556, 0x0034495a, 0x00364a5c, 0x00354b5c, 0x00344c5c, 0x00344c5d, 0x00354d60, 0x00385164, 0x003d576a, 0x00435c72, 0x00476178, 0x00476279, 0x00446077, 0x00415c73, 0x003e586e, 0x00385167, 0x00314c60, 0x002e4859, 0x002c4250, 0x00283845, 0x001a2431, 0x000a0e19, 0x0005070e, 0x00040508, 0x00030407, 0x00030406, 0x00010404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010305, 0x00020408, 0x00030408, 0x00030408, 0x00030508, 0x0004070a, 0x00080e12, 0x000c151b, 0x00111d25, 0x0016242d, 0x00152630, 0x00152734, 0x00142834, 0x00142834, 0x00142834, 0x00142733, 0x00132530, 0x0012242e, 0x0013242e, 0x0013242c, 0x0011212b, 0x0010202a, 0x00101f29, 0x000f1e28, 0x000e1c25, 0x000d1b24, 0x000d1924, 0x000c1821, 0x000b1620, 0x000a151f, 0x0009141e, 0x000a151c, 0x000b171e, 0x000b171f, 0x000c1820, 0x000d1921, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00132c32, 0x00143036, 0x0015363b, 0x00183c40, 0x001a4245, 0x001c474b, 0x001d4c50, 0x001f5154, 0x00215659, 0x0029849f, 0x0030a4cb, 0x00287889, 0x00266467, 0x00286769, 0x0028696c, 0x00296b6d, 0x00296c6f, 0x003090a8, 0x0036a8ca, 0x002c7d8a, 0x00296d6f, 0x002e879a, 0x0034a7cb, 0x002b7681, 0x0028686a, 0x00276668, 0x00266467, 0x00266364, 0x00256163, 0x00246062, 0x00245e60, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x002a8faf, 0x002c9bc0, 0x001f5256, 0x001e4c50, 0x001c474b, 0x001b4347, 0x00183f43, 0x00183a3e, 0x00153439, 0x00142e34, 0x00122c32, 0x0010282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c141b, 0x000c151c, 0x000d161d, 0x000e161d, 0x0010181f, 0x00101820, 0x000f1921, 0x000f1922, 0x00101a23, 0x00101a23, 0x00101b24, 0x00101b25, 0x00101c27, 0x00101d27, 0x00101d27, 0x00101d27, 0x00111e28, 0x00141f29, 0x00131f28, 0x00111e29, 0x0010202b, 0x0010202b, 0x00121e2a, 0x000f1822, 0x000a1018, 0x00050b10, 0x0004080b, 0x00020508, 0x00030405, 0x00030304, 0x00010302, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000304, 0x00010406, 0x0004080a, 0x00080c12, 0x000b141d, 0x001c2e3a, 0x0039556b, 0x004c6f88, 0x00507590, 0x00547b93, 0x00557a92, 0x0051748c, 0x004a6a84, 0x00446179, 0x00415c71, 0x003d576a, 0x003a5063, 0x00364b5e, 0x00344658, 0x002f4254, 0x002b3e4e, 0x00293a47, 0x00273643, 0x00243240, 0x0023303e, 0x00202c3a, 0x001c2935, 0x00182632, 0x0016222e, 0x00151e29, 0x00131924, 0x0010171f, 0x000e141c, 0x000c1017, 0x00090c11, 0x0004080b, 0x00030609, 0x00020508, 0x0005090c, 0x00090d14, 0x000c1219, 0x000c131b, 0x000d141c, 0x000c1319, 0x000c1018, 0x000a0f15, 0x00080d13, 0x00040910, 0x00050911, 0x000f141b, 0x00242832, 0x00303742, 0x002f3944, 0x002f3844, 0x002d3946, 0x002f3d4b, 0x00324452, 0x00304453, 0x00304554, 0x00314858, 0x00304655, 0x00304756, 0x002c4251, 0x002c4251, 0x00304453, 0x00314655, 0x002f4252, 0x00283b4b, 0x00263846, 0x00263745, 0x00263643, 0x00253441, 0x00263542, 0x00273641, 0x00202d38, 0x00202f38, 0x001f2c35, 0x001a2630, 0x001c272f, 0x0018222a, 0x00182329, 0x001d272e, 0x00131c23, 0x00131c23, 0x00111920, 0x00171f27, 0x00161e25, 0x00161e26, 0x00121920, 0x000e1318, 0x00080d12, 0x00060b0f, 0x000b1014, 0x00101418, 0x000d1317, 0x000c1216, 0x000c1216, 0x00080e12, 0x00060b10, 0x00090e14, 0x0010151c, 0x00141b20, 0x00131920, 0x00171d24, 0x00161c22, 0x0012171c, 0x0013181c, 0x0010151a, 0x000c1015, 0x000f1216, 0x0012151a, 0x000e1216, 0x000a0e13, 0x0012171c, 0x001b2028, 0x00182028, 0x00111c24, 0x001c262e, 0x001d2931, 0x001c2731, 0x00202a34, 0x0017202a, 0x00151e27, 0x001a232c, 0x001e2632, 0x00202936, 0x00222e3a, 0x00283843, 0x00273843, 0x00263643, 0x00273644, 0x00273644, 0x00233240, 0x00243441, 0x002d3c4a, 0x002b3a47, 0x00283845, 0x00263844, 0x002b3e4b, 0x00304451, 0x002b3f4c, 0x002c4250, 0x002a414e, 0x00283f4c, 0x00243b48, 0x00243946, 0x00243a45, 0x00233844, 0x00243a45, 0x00283d49, 0x002c404c, 0x002e434f, 0x00304450, 0x00334652, 0x00354451, 0x00343e4c, 0x00313a45, 0x00313843, 0x00313841, 0x00313741, 0x00303841, 0x00303942, 0x00303943, 0x00313944, 0x00313944, 0x00313944, 0x00313842, 0x00353b47, 0x00363c48, 0x00363c48, 0x002c343d, 0x001a222a, 0x000f151c, 0x000d141b, 0x0010171e, 0x00121821, 0x00131a24, 0x00131a24, 0x00121822, 0x00111620, 0x000d1018, 0x00090a10, 0x0006080c, 0x0005080d, 0x00080b11, 0x0010141a, 0x00162028, 0x001a2832, 0x001e2d38, 0x0022323e, 0x00263544, 0x00293948, 0x002c3c4b, 0x002d4050, 0x00304353, 0x00334758, 0x00344859, 0x00344859, 0x00344a5a, 0x00334b5c, 0x00344c5d, 0x00354d60, 0x00395164, 0x003e576a, 0x00425c70, 0x00445f74, 0x00446074, 0x00425c72, 0x003f576d, 0x00385167, 0x00334b5f, 0x002e4657, 0x002a3f4c, 0x0024333f, 0x00161e2a, 0x00080b14, 0x0004070c, 0x00030408, 0x00020407, 0x00020405, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020308, 0x00020308, 0x00020308, 0x00020408, 0x00030508, 0x0004080c, 0x00070c12, 0x000d141c, 0x00141e27, 0x0015242f, 0x00142632, 0x00142834, 0x00142834, 0x00142834, 0x00142833, 0x00132630, 0x0012252f, 0x0013252f, 0x0014242f, 0x0011232d, 0x0011222c, 0x0010202b, 0x00101f29, 0x000e1e28, 0x000d1c26, 0x000e1c24, 0x000c1a24, 0x000a1720, 0x000a1620, 0x000a1520, 0x000a151e, 0x000b171e, 0x000b171f, 0x000c1820, 0x000d1921, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0010282e, 0x00122c32, 0x00143036, 0x00143439, 0x00183c40, 0x00194044, 0x001b4649, 0x001d4b4e, 0x001f5053, 0x00205457, 0x0028849e, 0x0030a4cb, 0x00287788, 0x00266364, 0x00276568, 0x0028686a, 0x0028696c, 0x00286a6c, 0x00308fa7, 0x0035a8ca, 0x002c7c89, 0x00296c6e, 0x002d8699, 0x0034a7cb, 0x002a7580, 0x00286668, 0x00266467, 0x00256364, 0x00256163, 0x00256062, 0x00245e60, 0x00245d60, 0x00245d60, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00245c5f, 0x00235c5e, 0x00235a5c, 0x0022595c, 0x0022585b, 0x002a8faf, 0x002b9bc0, 0x001e5054, 0x001d4c50, 0x001c474b, 0x001a4347, 0x00183d41, 0x00183a3e, 0x00153439, 0x00142e34, 0x00132c32, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c151c, 0x000e171e, 0x0010181f, 0x0010181f, 0x00101820, 0x00101920, 0x00101a23, 0x00101b24, 0x00101c24, 0x00111c24, 0x00111c25, 0x00111d27, 0x00111e28, 0x00111f28, 0x00111f29, 0x00111f29, 0x0013202a, 0x0014202a, 0x0014202b, 0x0012202b, 0x00101f2a, 0x00101c28, 0x000d1722, 0x000b111a, 0x00060c12, 0x0002080c, 0x00020509, 0x00010407, 0x00020404, 0x00030303, 0x00010302, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000404, 0x00010405, 0x00030608, 0x0005080e, 0x00081017, 0x001b2a34, 0x00324a5d, 0x003b5870, 0x00405f77, 0x0046677c, 0x0048677e, 0x0046647b, 0x00446077, 0x00415b70, 0x003e566a, 0x003a5064, 0x00354c5d, 0x00334759, 0x00304455, 0x002e4051, 0x002a3d4c, 0x00283946, 0x00263542, 0x0023323e, 0x00212f3c, 0x001e2c38, 0x001c2834, 0x00182531, 0x0016212d, 0x00141e28, 0x00131924, 0x0010171f, 0x000e141c, 0x000c1017, 0x00090c12, 0x0006090d, 0x0004060b, 0x0003050a, 0x0005080c, 0x00080b11, 0x000c1017, 0x000c1219, 0x000c131a, 0x000b1218, 0x000b1017, 0x000a0f16, 0x00080d14, 0x00060a10, 0x0004080f, 0x00090d14, 0x001b2028, 0x002b313b, 0x002f3841, 0x00303844, 0x002e3844, 0x002e3a48, 0x00334150, 0x00324252, 0x00314454, 0x00334858, 0x00314857, 0x00324858, 0x002d4453, 0x002c4150, 0x002e4352, 0x00304554, 0x002f4252, 0x00263848, 0x00233544, 0x00253644, 0x00253542, 0x00263542, 0x00263542, 0x00253440, 0x00202d38, 0x0022303a, 0x00202d37, 0x0018242d, 0x0018242d, 0x001b272f, 0x001c282f, 0x001c282f, 0x00161f26, 0x00111a21, 0x00141c24, 0x0018212a, 0x00172029, 0x0018202a, 0x00141b22, 0x000e1419, 0x00080d11, 0x00060c10, 0x000b1014, 0x000f1418, 0x000e1418, 0x000e141a, 0x000f141a, 0x000a0f14, 0x00050a0f, 0x00060c11, 0x000f141a, 0x00181f25, 0x00171f25, 0x00141c23, 0x00181e24, 0x00161b20, 0x00141a1f, 0x00181c22, 0x00101418, 0x000b0e13, 0x0011151a, 0x00101419, 0x000c1115, 0x000e1318, 0x00181c25, 0x00192029, 0x00162029, 0x001c2730, 0x001f2b33, 0x001b2630, 0x001f2a34, 0x001d2830, 0x0018222b, 0x001c2830, 0x00242f3a, 0x0025303c, 0x00283440, 0x002a3a46, 0x002a3b47, 0x002b3b49, 0x00293848, 0x00283846, 0x00243342, 0x00243341, 0x002a3948, 0x002d3d4b, 0x00283846, 0x00263844, 0x002f414f, 0x00304452, 0x002c404e, 0x002c4350, 0x002d4450, 0x002b414e, 0x00283f4c, 0x00293e4c, 0x00283c48, 0x00283c48, 0x002b404c, 0x002b3f4b, 0x002c404c, 0x0030414d, 0x0030404c, 0x0031404d, 0x0033404c, 0x00333c49, 0x00323945, 0x00313843, 0x00313841, 0x00313841, 0x00313841, 0x00303842, 0x00303943, 0x00313944, 0x00313944, 0x00313944, 0x00313943, 0x00363d48, 0x00383e49, 0x00343b46, 0x00242c35, 0x00121921, 0x000d141c, 0x000f151d, 0x0011181f, 0x00141821, 0x00141823, 0x00141823, 0x00121720, 0x000f131c, 0x000c0d15, 0x0008080e, 0x0006060c, 0x0007080d, 0x000b0c14, 0x0010151c, 0x00172028, 0x001b2833, 0x001d2d38, 0x0020303c, 0x00243442, 0x00283846, 0x002a3b49, 0x002c3e4e, 0x002f4151, 0x00314555, 0x00334859, 0x00334859, 0x00334a5a, 0x00334b5b, 0x00334a5b, 0x00334b5d, 0x00374f61, 0x003a5365, 0x003e576c, 0x00415b70, 0x00415c72, 0x00415b70, 0x003f586d, 0x003a5268, 0x00344c60, 0x00304758, 0x002c3e4c, 0x0024303c, 0x00141a24, 0x00060911, 0x00040408, 0x00030406, 0x00030304, 0x00030304, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000205, 0x00020308, 0x00020308, 0x00020308, 0x00020308, 0x00030408, 0x0002050a, 0x0004080d, 0x00080c14, 0x000e151d, 0x00141f28, 0x00142430, 0x00142733, 0x00142834, 0x00142834, 0x00142833, 0x00142731, 0x00132630, 0x00132530, 0x0014242f, 0x0012242e, 0x0011232d, 0x0010222c, 0x0010202a, 0x00102029, 0x000f1e28, 0x000f1d26, 0x000e1c25, 0x000c1923, 0x000b1821, 0x000b1620, 0x000b171f, 0x000b171e, 0x000c1820, 0x000c1820, 0x000d1921, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00142e34, 0x00153439, 0x00183a3e, 0x00183f43, 0x001b4448, 0x001c484c, 0x001e4f51, 0x00205254, 0x0028839d, 0x0030a4cb, 0x00287788, 0x00256163, 0x00266466, 0x00276568, 0x00286769, 0x0028686b, 0x002f8ea6, 0x0034a7ca, 0x002b7a88, 0x0028696c, 0x002c8498, 0x0034a6cb, 0x0029747f, 0x00266467, 0x00256364, 0x00256163, 0x00256062, 0x00245e60, 0x00245d60, 0x00245c5f, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x00235a5c, 0x0022595c, 0x0022585b, 0x0021575a, 0x00298eae, 0x002b9ac0, 0x001e5054, 0x001d4b4e, 0x001c4649, 0x001a4245, 0x00183d41, 0x0017383c, 0x00143338, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c161f, 0x000e1820, 0x000f1921, 0x00101922, 0x00101a23, 0x00101b23, 0x00101c24, 0x00101c24, 0x00121c25, 0x00131d26, 0x00131d28, 0x00121f29, 0x00122029, 0x00112029, 0x0011202a, 0x0011202a, 0x0012202a, 0x0014202b, 0x0014212c, 0x0013202a, 0x00101d28, 0x000e1823, 0x000b111a, 0x00080c12, 0x0004080c, 0x0001050a, 0x00020408, 0x00010406, 0x00000304, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020404, 0x00020404, 0x00030406, 0x0004080c, 0x00070e16, 0x00182732, 0x00324858, 0x003c5668, 0x003f5b6f, 0x00446075, 0x00446076, 0x00435d74, 0x0040596f, 0x003d5469, 0x003b5064, 0x00384d60, 0x00344a5b, 0x00324657, 0x00304252, 0x002c3f4e, 0x002a3b49, 0x00283744, 0x00243440, 0x0022303c, 0x00202e39, 0x001c2a36, 0x001b2833, 0x00182430, 0x0014202c, 0x00131c27, 0x00101822, 0x0010161e, 0x000e131b, 0x000c1017, 0x00090c13, 0x0006090d, 0x0005070a, 0x00040509, 0x0005070c, 0x00070910, 0x000b0e14, 0x000c1018, 0x000b1219, 0x000b1118, 0x000b1016, 0x00090e13, 0x00080c11, 0x00070b0f, 0x0006080d, 0x00070a10, 0x0011151c, 0x0021272e, 0x002d343c, 0x00303741, 0x00303843, 0x002e3844, 0x00303c49, 0x0031404d, 0x00324452, 0x00334655, 0x00304453, 0x00304654, 0x002c4350, 0x002c414f, 0x002c4150, 0x00304452, 0x002e4150, 0x00243744, 0x00223441, 0x00243541, 0x00253540, 0x00263541, 0x0024333e, 0x0023303c, 0x00202d38, 0x00212f3b, 0x00202e38, 0x00172430, 0x0018262f, 0x001c2933, 0x001f2c36, 0x001d2a32, 0x0018222a, 0x00131c24, 0x0018232b, 0x001a272f, 0x001b272e, 0x001d2930, 0x00182329, 0x000d151b, 0x00080f14, 0x00070c11, 0x000b1115, 0x0011181c, 0x00131920, 0x00121920, 0x0012181f, 0x000e131b, 0x00090e14, 0x00080c12, 0x000b1016, 0x00182025, 0x00162026, 0x00131b22, 0x00151c23, 0x00121820, 0x00181e25, 0x001a2028, 0x0010161c, 0x00090f15, 0x0011171c, 0x0011171b, 0x00101419, 0x0011161d, 0x00151b23, 0x001a222b, 0x0019232c, 0x001f2932, 0x001e2a33, 0x001c2730, 0x001d2934, 0x001c2833, 0x0018242d, 0x001b2730, 0x00212d37, 0x00222e39, 0x00253440, 0x00293946, 0x00293b47, 0x002c3c49, 0x002a3b48, 0x00283845, 0x00243542, 0x00243543, 0x00293a48, 0x002d404d, 0x002a3c4b, 0x00273c49, 0x00304553, 0x002d4250, 0x002f4451, 0x002b414e, 0x002a414e, 0x00283f4c, 0x002a414e, 0x002b414f, 0x002a404c, 0x002f4450, 0x00344754, 0x00304250, 0x002e3f4a, 0x00303e49, 0x00303c47, 0x00303c48, 0x00323c48, 0x00323b47, 0x00323945, 0x00323843, 0x00313842, 0x00333842, 0x00323842, 0x00313841, 0x00303742, 0x00313844, 0x00313844, 0x00313844, 0x00343b46, 0x00383f4c, 0x00383f4c, 0x002d3440, 0x0019202b, 0x000e141d, 0x000e141c, 0x000f161d, 0x0010181d, 0x00141820, 0x00141820, 0x00141820, 0x00111620, 0x000d111b, 0x000b0c14, 0x0008080d, 0x0006060b, 0x0007080e, 0x000b0d14, 0x0012161e, 0x0018222b, 0x001a2832, 0x001d2c38, 0x0020303b, 0x0023323f, 0x00253543, 0x00283847, 0x00293c4b, 0x002c4050, 0x002f4354, 0x00324758, 0x00324859, 0x0034495a, 0x0034495a, 0x00344859, 0x0032495b, 0x00344c5e, 0x00374f61, 0x003b5366, 0x003f576c, 0x00405a70, 0x003f5a70, 0x003e586d, 0x003c5469, 0x00364f62, 0x00324a5a, 0x002e404f, 0x00212d3a, 0x000d141e, 0x0002060c, 0x00020406, 0x00030305, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000205, 0x00000205, 0x00010305, 0x00020405, 0x00020407, 0x00030408, 0x0003040a, 0x0005060e, 0x00090c14, 0x000e161f, 0x0014202a, 0x0014242e, 0x00142631, 0x00142832, 0x00142832, 0x00142732, 0x00132632, 0x00132531, 0x00142430, 0x00132430, 0x0012242e, 0x0011232d, 0x0010212b, 0x00102029, 0x00101f28, 0x00111e28, 0x00101d28, 0x000e1c25, 0x000c1921, 0x000b1820, 0x000c1a21, 0x000c1921, 0x000c1a21, 0x000c1a21, 0x000d1a22, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013282e, 0x00112a30, 0x00142e34, 0x00143338, 0x0017383c, 0x00183d41, 0x00194245, 0x001c474b, 0x001d4c50, 0x001f5053, 0x0028829d, 0x002fa4cb, 0x00277688, 0x00246064, 0x00256367, 0x00266568, 0x0027676a, 0x0027686b, 0x002e8da6, 0x0034a6ca, 0x002a7886, 0x00276668, 0x002c8397, 0x0033a6cb, 0x0028727f, 0x00266468, 0x00256266, 0x00246164, 0x00246063, 0x00245f62, 0x00245e61, 0x00235c60, 0x00225c60, 0x00225c60, 0x00225c60, 0x00225c60, 0x00225c60, 0x00215b5f, 0x00225b5f, 0x0022595e, 0x0021585c, 0x0020585c, 0x00298eaf, 0x002b9ac0, 0x001e4f53, 0x001c4a4d, 0x001b4448, 0x00194044, 0x00183c40, 0x0016363b, 0x00153338, 0x00142e34, 0x00112a30, 0x0013282e, 0x00102229, 0x00102229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000e1820, 0x000f1921, 0x00101a23, 0x00101c24, 0x00101c24, 0x00101c24, 0x00101d25, 0x00101e26, 0x00121e27, 0x00131f28, 0x00131f29, 0x0013202a, 0x0013202a, 0x0012202a, 0x0011202a, 0x0013212c, 0x0014202c, 0x0014212c, 0x0013202c, 0x00121e28, 0x00101a22, 0x000c141b, 0x00080c12, 0x0005080c, 0x00030509, 0x00010408, 0x00020308, 0x00010305, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020404, 0x00020404, 0x00030405, 0x00040609, 0x00060c14, 0x00182430, 0x00334754, 0x003c5565, 0x003e586c, 0x00405a70, 0x00405a6f, 0x003d566c, 0x003b5267, 0x00384f63, 0x00374c5e, 0x0034495a, 0x00334858, 0x00304454, 0x002d4050, 0x002a3c4c, 0x00283847, 0x00263542, 0x0023323d, 0x0021303b, 0x00202d39, 0x001c2935, 0x001c2733, 0x0018232f, 0x0014202c, 0x00111b25, 0x00101820, 0x0010161e, 0x000e131b, 0x000c1018, 0x00090e14, 0x00070a0e, 0x00040609, 0x00030508, 0x0004050a, 0x0004080e, 0x00080c12, 0x000b1017, 0x000b1119, 0x000b1119, 0x000a0f15, 0x00080e12, 0x00070c0f, 0x00070a0d, 0x0005090c, 0x0005080c, 0x000b0e12, 0x00191c22, 0x00292e35, 0x00303640, 0x00303841, 0x002d3741, 0x002c3743, 0x002c3a46, 0x0030404e, 0x00304451, 0x00304351, 0x00314654, 0x002e4451, 0x002f4452, 0x002e4350, 0x00304452, 0x002d404f, 0x00283a48, 0x00253844, 0x00263744, 0x00273742, 0x0024343f, 0x0023323d, 0x0023303c, 0x0021303b, 0x0023303c, 0x00202e3a, 0x001c2a35, 0x001b2a34, 0x001a2933, 0x001a2933, 0x001a2830, 0x0018242d, 0x0017222a, 0x00202c34, 0x001e2c34, 0x001d2c31, 0x00202f34, 0x0019252c, 0x000f181e, 0x000e141b, 0x000f141a, 0x0011181d, 0x00161e23, 0x00161f25, 0x00141c24, 0x00141a22, 0x0010161e, 0x000d1319, 0x000b1016, 0x000c1116, 0x00141c22, 0x00141e24, 0x00111b22, 0x00141d25, 0x000d161f, 0x00101820, 0x00181f26, 0x0010151d, 0x00091017, 0x0010161b, 0x0010171b, 0x0013191e, 0x00171c22, 0x00141a22, 0x001b222c, 0x001c242d, 0x001e2831, 0x001c2831, 0x001c2831, 0x001f2b35, 0x00202d37, 0x00182630, 0x001c2832, 0x001d2934, 0x001d2a34, 0x0024313d, 0x00293845, 0x00293845, 0x00293b47, 0x00283a46, 0x00273a46, 0x00283a46, 0x00283b48, 0x002c404e, 0x00304452, 0x002f4451, 0x002b414e, 0x00314854, 0x00283c4a, 0x00304552, 0x00283f4c, 0x00283e4c, 0x00263c49, 0x002a414e, 0x002b414f, 0x002c424f, 0x00304654, 0x00344755, 0x00324250, 0x00303e49, 0x00303b45, 0x00303842, 0x00313943, 0x00333943, 0x00323a44, 0x00323a44, 0x00323843, 0x00313841, 0x00343842, 0x00333842, 0x00323741, 0x00313641, 0x00313843, 0x00323844, 0x00323847, 0x00363c4b, 0x0039404d, 0x00343b48, 0x00262c38, 0x00121824, 0x000c131c, 0x000e141c, 0x0010161c, 0x0010171c, 0x0011171e, 0x0012171f, 0x0012171f, 0x0010141e, 0x000b0f18, 0x00080a11, 0x0007070c, 0x0005050b, 0x0007080e, 0x000c0d15, 0x00131820, 0x0018222d, 0x00192732, 0x001c2b36, 0x001f2e39, 0x0021303b, 0x00233440, 0x00263744, 0x00283a48, 0x002b3d4d, 0x002d4153, 0x00304556, 0x00324858, 0x00324859, 0x00334859, 0x00334758, 0x00314858, 0x0033495a, 0x00344c5d, 0x00385062, 0x003b5366, 0x003f586c, 0x003e586c, 0x003d586c, 0x003c5669, 0x00375064, 0x00344b5b, 0x00304050, 0x00202c39, 0x00081019, 0x0000050a, 0x00020405, 0x00020404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020308, 0x00020308, 0x00040409, 0x0006080c, 0x000a0e15, 0x000f1820, 0x00132028, 0x0014252e, 0x00142731, 0x00142832, 0x00142733, 0x00142733, 0x00142733, 0x00122431, 0x00132431, 0x0013242e, 0x0011232d, 0x0011222c, 0x0011202a, 0x0011202a, 0x00111f2a, 0x00101d28, 0x000d1c25, 0x000c1b24, 0x000d1c24, 0x000e1c24, 0x000f1c25, 0x000f1c25, 0x000f1c25, 0x000f1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x000f1f27, 0x00102229, 0x0012242c, 0x00112a30, 0x00132c32, 0x00143036, 0x0016363b, 0x00183c40, 0x00194044, 0x001b4448, 0x001c4a4d, 0x001d4d50, 0x00246e81, 0x002da1c8, 0x002c9bbf, 0x002c98ba, 0x002d98ba, 0x002e99bb, 0x002f99bb, 0x002f9abb, 0x0030a0c4, 0x0031a0c3, 0x00276c75, 0x00256364, 0x00287380, 0x0031a2c6, 0x002f9bbd, 0x002e99ba, 0x002d98ba, 0x002d98ba, 0x002d98ba, 0x002c98ba, 0x002c98ba, 0x002c98ba, 0x002c97ba, 0x002b97ba, 0x002b96b9, 0x002b96b9, 0x002b96b9, 0x002b96b9, 0x002b96b9, 0x002b96b9, 0x002a96b9, 0x002a95b9, 0x002c9fc5, 0x002788a8, 0x001d4c50, 0x001c474b, 0x001a4347, 0x00183f43, 0x00183a3e, 0x00143439, 0x00143036, 0x00132c32, 0x00112a30, 0x0012242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000f1922, 0x00101a23, 0x00101c24, 0x00101c25, 0x00101d25, 0x00101e26, 0x00101f26, 0x00122028, 0x00132029, 0x0014202a, 0x0014202a, 0x0014202a, 0x0013202a, 0x0012202a, 0x0012212b, 0x0013212c, 0x0013212c, 0x0013212c, 0x0013202a, 0x00111b24, 0x000f141c, 0x000a0f15, 0x0006090e, 0x00040509, 0x00030408, 0x00010407, 0x00020308, 0x00010305, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020404, 0x00020404, 0x00030405, 0x00040509, 0x00070a13, 0x0016202c, 0x00314451, 0x003b5363, 0x003c5568, 0x003e586c, 0x003d576a, 0x003b5467, 0x00385063, 0x00354c5d, 0x00344959, 0x00324757, 0x00314655, 0x00304353, 0x002c3f50, 0x00293c4b, 0x00273846, 0x00253441, 0x0022313c, 0x00212f3a, 0x00202c39, 0x001e2837, 0x001b2633, 0x0017232f, 0x00141f2b, 0x00101b24, 0x00101820, 0x0010181f, 0x000f141c, 0x000c1118, 0x000a0f14, 0x00080a0f, 0x0004070a, 0x00030508, 0x00030409, 0x0004060c, 0x00070a0f, 0x00090e14, 0x00090f17, 0x000a1018, 0x000a0f14, 0x00080d11, 0x00070c10, 0x00070a0d, 0x0005080b, 0x0005080c, 0x00070a0d, 0x00101418, 0x0020252c, 0x002c313a, 0x0030353f, 0x002d353f, 0x002c3540, 0x002a3743, 0x002d3c49, 0x00304150, 0x00334452, 0x00334654, 0x00304552, 0x00304654, 0x00304452, 0x00304451, 0x002e414f, 0x00293c4a, 0x00243744, 0x00263743, 0x00253540, 0x00253440, 0x0021303c, 0x0022303c, 0x0024313c, 0x0024323d, 0x0022303c, 0x00202e3a, 0x001a2933, 0x00182630, 0x00172630, 0x00192831, 0x001c2933, 0x001c2832, 0x0024303a, 0x00202e37, 0x001c2c34, 0x001c2b32, 0x0018252c, 0x00101a21, 0x00131920, 0x00141a20, 0x00131a20, 0x00121b20, 0x00151e26, 0x00131b24, 0x00111922, 0x00131921, 0x0010161d, 0x0010141b, 0x000f141b, 0x00161d24, 0x00151e26, 0x00121c24, 0x00141e27, 0x00131c25, 0x00101820, 0x00161d25, 0x00121920, 0x00081018, 0x000d161b, 0x00131b20, 0x00181f24, 0x001a2027, 0x00151c25, 0x001b232c, 0x001a242c, 0x001d2830, 0x0019262f, 0x001c2832, 0x00202d37, 0x0024313b, 0x001c2a34, 0x00202d37, 0x00202d37, 0x00222e39, 0x00212f3a, 0x00273442, 0x00283744, 0x002b3b48, 0x002a3c48, 0x00283b47, 0x00293c48, 0x002c3e4c, 0x00314554, 0x00334855, 0x00314854, 0x002d4451, 0x00304653, 0x00273c49, 0x002c404e, 0x00283f4c, 0x0029404c, 0x00263d4a, 0x00283f4c, 0x00283f4c, 0x002b424f, 0x00304552, 0x00334453, 0x00334250, 0x00313e4a, 0x00303a46, 0x00303843, 0x00313844, 0x00333944, 0x00323944, 0x00323944, 0x00323844, 0x00313842, 0x00333843, 0x00333743, 0x00323641, 0x00313541, 0x00313642, 0x00323844, 0x00343948, 0x00373e4c, 0x0038404c, 0x002d3542, 0x001d2430, 0x000d131f, 0x000b111a, 0x000d131b, 0x000f151c, 0x000f161c, 0x0010151c, 0x0010151d, 0x0010141d, 0x000d121b, 0x00080c15, 0x00070810, 0x0006050b, 0x0006050c, 0x0008090f, 0x000d1017, 0x00141b24, 0x0018232d, 0x00182732, 0x001b2b35, 0x001e2d38, 0x0020303a, 0x0021333e, 0x00243642, 0x00273946, 0x00293c4c, 0x002c3f50, 0x00304354, 0x00314657, 0x00324658, 0x00324658, 0x00334658, 0x00324758, 0x00334859, 0x00344b5c, 0x00354d5f, 0x00385063, 0x003c5467, 0x003c5668, 0x003a5668, 0x003a5567, 0x00375163, 0x00344c5c, 0x002f4050, 0x001e2a36, 0x00050d15, 0x00000508, 0x00020404, 0x00020403, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020308, 0x00020308, 0x00030408, 0x00040509, 0x0007090f, 0x000b1018, 0x000f1920, 0x0013222a, 0x0014262f, 0x00142731, 0x00142733, 0x00142834, 0x00142733, 0x00132632, 0x00142531, 0x00142430, 0x0013242e, 0x0012232c, 0x0012212b, 0x0011202a, 0x0011202c, 0x00101e29, 0x000f1c28, 0x000f1c27, 0x000f1d27, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x00101d28, 0x000c1b25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0011282e, 0x00122c32, 0x00142e34, 0x00153439, 0x0017383c, 0x00183d41, 0x001a4245, 0x001b4649, 0x001d4b4e, 0x001e5054, 0x00257a92, 0x00298fb0, 0x002a90b0, 0x002b91b0, 0x002c91b0, 0x002c91b1, 0x002c92b1, 0x002c93b1, 0x0028798c, 0x00245f61, 0x00245f61, 0x00245f61, 0x00287c90, 0x002c92b0, 0x002c92b0, 0x002c90b0, 0x002c90b0, 0x002a90b0, 0x002a90b0, 0x002a90b0, 0x00298fb0, 0x00298fb0, 0x00298fb0, 0x00298fb0, 0x00298fb0, 0x00298fb0, 0x00298fb0, 0x00298fb0, 0x00288fb0, 0x00288eb0, 0x00288eb0, 0x002788a8, 0x001e555f, 0x001c474b, 0x001b4448, 0x00194044, 0x00183c40, 0x0017383c, 0x00153439, 0x00142e34, 0x00132c32, 0x0011282e, 0x0013242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101b24, 0x00111c24, 0x00121c25, 0x00101e28, 0x00101f28, 0x00112028, 0x00122028, 0x00142129, 0x0014212a, 0x0014212b, 0x0014212b, 0x0014212b, 0x0014212b, 0x0014212c, 0x0014222d, 0x0013222d, 0x0013222d, 0x0012212c, 0x00121d27, 0x0010171f, 0x000b1015, 0x00080b0f, 0x00040609, 0x00030407, 0x00030408, 0x00020408, 0x00020308, 0x00010305, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020404, 0x00020404, 0x00020405, 0x00040509, 0x00070911, 0x00151d28, 0x0030404d, 0x003b505f, 0x003b5364, 0x003c5568, 0x003a5466, 0x00385063, 0x00354c5f, 0x00344a5b, 0x00344858, 0x00314655, 0x00304454, 0x002e4251, 0x002c3d4d, 0x00283a4a, 0x00263745, 0x00243341, 0x0022303c, 0x00212c3a, 0x00202a38, 0x001d2735, 0x001a2533, 0x0017222e, 0x00141f2b, 0x00111b24, 0x00101821, 0x0011181f, 0x0010141c, 0x000c1218, 0x00091013, 0x00070b0e, 0x00040809, 0x00020507, 0x00020508, 0x0004060a, 0x0006080c, 0x00080c10, 0x00090e14, 0x000b1016, 0x000b1014, 0x00090e10, 0x00080c0f, 0x00080b0e, 0x0006090c, 0x0006090c, 0x0004080c, 0x00080c10, 0x00161b20, 0x00252a33, 0x002e333c, 0x002e3540, 0x002c3540, 0x002b3541, 0x002c3a47, 0x00303f4c, 0x0033404f, 0x00344350, 0x00304450, 0x00334653, 0x00314451, 0x00314453, 0x002f4250, 0x002a3c4a, 0x00243643, 0x00253643, 0x00243440, 0x00243440, 0x0020303c, 0x0022303c, 0x0025333e, 0x0026343f, 0x0024323d, 0x001e2c37, 0x0017242f, 0x00182630, 0x00182630, 0x00182730, 0x00192730, 0x001f2c36, 0x00202e38, 0x001d2c35, 0x001b2b32, 0x0018272f, 0x0016242c, 0x000e1820, 0x0010161d, 0x0010161c, 0x0010181d, 0x00101820, 0x00141c24, 0x00141c24, 0x00111922, 0x00141c25, 0x0010181f, 0x0010141c, 0x000f141b, 0x00181f27, 0x00182028, 0x00141d26, 0x00141d27, 0x00151f28, 0x0018212a, 0x00131c23, 0x00141c24, 0x00101921, 0x000f181f, 0x00151d24, 0x001a2329, 0x00192229, 0x00141c25, 0x001c242d, 0x001b242d, 0x001b262f, 0x0018252e, 0x001c2933, 0x00202c35, 0x0026333c, 0x001c2a34, 0x00202d37, 0x0024303a, 0x00202c38, 0x001c2a37, 0x00253341, 0x00283844, 0x002b3c48, 0x002b3c49, 0x002a3d49, 0x002a3d49, 0x002b3e4b, 0x002f4250, 0x002f4450, 0x002e4451, 0x002d4451, 0x00304553, 0x00273c49, 0x00293e4b, 0x002b404e, 0x002b424f, 0x00283f4c, 0x00263c4a, 0x00273d4b, 0x002b414f, 0x002e4350, 0x00314250, 0x00334050, 0x00323c4b, 0x00313a46, 0x00313844, 0x00333844, 0x00343844, 0x00333844, 0x00323844, 0x00323844, 0x00313743, 0x00333743, 0x00323642, 0x00313541, 0x00303440, 0x00303440, 0x00323643, 0x00353a48, 0x00373e4c, 0x00353d4a, 0x00272f3c, 0x00141a28, 0x000c111d, 0x000c111c, 0x000d111c, 0x0010141c, 0x0010151d, 0x0010141c, 0x000f141c, 0x000e131b, 0x000a0f17, 0x00060a13, 0x0006080f, 0x0005050c, 0x0007080e, 0x000a0b12, 0x000f131b, 0x00151c25, 0x0018232c, 0x00182631, 0x001b2a35, 0x001e2c38, 0x001f303b, 0x0021323e, 0x00243541, 0x00263745, 0x00293a4a, 0x002c3e4f, 0x002f4153, 0x00304455, 0x00314557, 0x00334658, 0x00324558, 0x00304556, 0x00324758, 0x0034495a, 0x00344a5c, 0x00364e60, 0x003b5364, 0x003a5466, 0x00385466, 0x00385364, 0x00365060, 0x00344b5b, 0x002c3c4c, 0x0019242f, 0x00040b11, 0x00010508, 0x00020404, 0x00010303, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020308, 0x00020308, 0x00030408, 0x00030509, 0x0004070c, 0x00070b12, 0x000c1219, 0x00101b23, 0x0014222c, 0x00152630, 0x00152733, 0x00152834, 0x00142834, 0x00142734, 0x00142734, 0x00142631, 0x00142430, 0x0013242d, 0x0013222c, 0x0012222b, 0x0012212c, 0x00101f2a, 0x00101d29, 0x00101e2a, 0x00111f2b, 0x00121f2b, 0x00121f2b, 0x00121f2b, 0x00121f2b, 0x00121f2b, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0013282e, 0x00112a30, 0x00142e34, 0x00143036, 0x0016363b, 0x00183a3e, 0x00183f43, 0x001a4347, 0x001c474b, 0x001d4b4e, 0x001e4e51, 0x001f5154, 0x00205458, 0x0021575a, 0x0021585b, 0x00225a5c, 0x00235b5e, 0x00235b5e, 0x00235c5e, 0x00235c5e, 0x00235a5c, 0x00235a5c, 0x0022595c, 0x00235a5c, 0x0021585c, 0x0021585b, 0x0021575a, 0x00205659, 0x00205458, 0x00205457, 0x00205457, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x00205356, 0x001f5154, 0x001f5154, 0x001e5054, 0x001e4f53, 0x001d4e51, 0x001c4b4e, 0x001c474b, 0x001a4448, 0x001a4245, 0x00183d41, 0x00183a3e, 0x0015363b, 0x00143036, 0x00142e34, 0x00112a30, 0x0012282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121c24, 0x00131d25, 0x00131e28, 0x00122029, 0x0011202a, 0x0013212a, 0x00142129, 0x0014222a, 0x0014222b, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222c, 0x0014222d, 0x0014222d, 0x0013222d, 0x0012202a, 0x000e1821, 0x000c1119, 0x00080c10, 0x0005070c, 0x00040408, 0x00030407, 0x00030408, 0x00020308, 0x00020308, 0x00010305, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020404, 0x00020404, 0x00020405, 0x00030408, 0x0006080f, 0x00111a24, 0x002c3b48, 0x00374b5a, 0x00385060, 0x00385164, 0x00375062, 0x00344c5f, 0x00344a5c, 0x00334858, 0x00324656, 0x00304454, 0x002f4351, 0x002d404f, 0x002b3c4c, 0x00283948, 0x00253644, 0x00243240, 0x00212e3c, 0x00202b38, 0x001f2836, 0x001c2634, 0x00192431, 0x0017222e, 0x00141e2a, 0x00131b26, 0x00121822, 0x00101720, 0x0010141d, 0x000e1218, 0x000b0f14, 0x00080c10, 0x0006080c, 0x00040609, 0x00040508, 0x00040609, 0x0004070a, 0x00070a0f, 0x000a0e14, 0x000c1016, 0x000b1014, 0x00090e10, 0x00080c10, 0x00080b0e, 0x0006090c, 0x0006090d, 0x0004080c, 0x0004080c, 0x000d1015, 0x001c2028, 0x00282d36, 0x002c343e, 0x002d3540, 0x002c3641, 0x002f3a46, 0x00303c48, 0x00313c48, 0x00323e4a, 0x0032404c, 0x00344350, 0x00314250, 0x00304250, 0x002f4250, 0x002b3e4c, 0x00243643, 0x00273844, 0x00253440, 0x0024343f, 0x0020303b, 0x0022313c, 0x002b3844, 0x00293742, 0x00263440, 0x00202e39, 0x001b2833, 0x001c2a34, 0x0017242e, 0x0014212c, 0x0016242f, 0x0022303b, 0x00182731, 0x00182831, 0x001a2931, 0x0018282f, 0x0018262d, 0x000c171f, 0x000f171e, 0x0010161d, 0x00141c24, 0x00141c25, 0x00101822, 0x00161f28, 0x0018212a, 0x00171f28, 0x00141b24, 0x00131921, 0x000e141c, 0x00182029, 0x0019232c, 0x00151f28, 0x00141e28, 0x0016212a, 0x001a242d, 0x00141d26, 0x00151e27, 0x0019222c, 0x00121b24, 0x00172029, 0x001c242d, 0x001c242c, 0x00141d27, 0x001d2730, 0x001d2730, 0x0018232c, 0x0018242e, 0x001c2833, 0x00202c36, 0x0027333d, 0x001c2833, 0x001b2832, 0x0024303c, 0x001f2b39, 0x00202c3c, 0x00253241, 0x00273644, 0x002b3c49, 0x002a3c4a, 0x002a3c4b, 0x002c404c, 0x002b3e4c, 0x002d404f, 0x002c404e, 0x002c4150, 0x002c4350, 0x00304754, 0x00283d4b, 0x00283c4b, 0x002e4451, 0x002e4452, 0x002e4452, 0x002a404d, 0x002d4350, 0x002f4451, 0x002e414f, 0x00303f4d, 0x00313e4d, 0x00323c4a, 0x00333c47, 0x00343a45, 0x00343944, 0x00343844, 0x00343844, 0x00323844, 0x00323844, 0x00313743, 0x00333743, 0x00313542, 0x00303440, 0x00303440, 0x00303540, 0x00343844, 0x00373c49, 0x00363c4a, 0x002f3643, 0x001d2430, 0x000f1422, 0x000c111d, 0x000c111b, 0x000d111b, 0x000f141c, 0x0010141c, 0x000f141c, 0x000e121a, 0x000c1018, 0x00080c14, 0x00040810, 0x0005080e, 0x0004060b, 0x0007080f, 0x000b0d14, 0x0010161e, 0x00161d27, 0x0017232b, 0x00182630, 0x00192934, 0x001c2c38, 0x001d2e3a, 0x0020303e, 0x00233440, 0x00253644, 0x00283849, 0x002b3c4c, 0x002e3f50, 0x00304354, 0x00314555, 0x00334656, 0x00324556, 0x00314557, 0x00324658, 0x00324859, 0x0034495c, 0x00344b5e, 0x00374f61, 0x00385063, 0x00365062, 0x00354f60, 0x00344c5d, 0x00324757, 0x00283744, 0x00141d26, 0x0002080e, 0x00020508, 0x00020404, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020308, 0x00020308, 0x00030408, 0x00030408, 0x0003050a, 0x0004080d, 0x00080c13, 0x000c131a, 0x00101c24, 0x0014232c, 0x00162631, 0x00152935, 0x00142936, 0x00142836, 0x00152835, 0x00162733, 0x00152631, 0x0014252f, 0x0014242d, 0x0014242c, 0x0013222c, 0x0011202c, 0x00111f2b, 0x00121f2b, 0x0013202c, 0x0014212c, 0x0014212c, 0x0014212c, 0x0014212c, 0x0014212c, 0x000d1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x0013242c, 0x0011282e, 0x00132c32, 0x00142e34, 0x00143338, 0x0016363b, 0x00183c40, 0x00183f43, 0x001a4347, 0x001c474b, 0x001d4a4d, 0x001d4c50, 0x001e4f51, 0x001f5154, 0x00205254, 0x00205457, 0x00205558, 0x00205558, 0x00215659, 0x00215659, 0x00215659, 0x00205558, 0x00205457, 0x00205457, 0x00205356, 0x00205254, 0x00205254, 0x001f5154, 0x001f5053, 0x001e5053, 0x001e4f51, 0x001e4f51, 0x001e4f51, 0x001e4f51, 0x001d4d50, 0x001d4d50, 0x001d4d50, 0x001d4c50, 0x001d4c50, 0x001c4a4d, 0x001c484c, 0x001c474b, 0x001b4448, 0x001a4245, 0x00183d41, 0x00183a3e, 0x0016363b, 0x00143338, 0x00142e34, 0x00132c32, 0x0010282e, 0x0013242c, 0x00102229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121d26, 0x00141f28, 0x00142028, 0x00142129, 0x0014212a, 0x0015222a, 0x0015222a, 0x0016232b, 0x0014232b, 0x0015232b, 0x0015232b, 0x0015232b, 0x0014222b, 0x0014222b, 0x0014222b, 0x0014222c, 0x0013202a, 0x00101c25, 0x000b131b, 0x00070c13, 0x0005080d, 0x0004050a, 0x00030408, 0x00020307, 0x00000206, 0x00010207, 0x00010206, 0x00000206, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00020404, 0x00020404, 0x00020404, 0x00020405, 0x00020408, 0x0003070c, 0x00101820, 0x00293844, 0x00334956, 0x00344c5c, 0x00364d5e, 0x00354c5d, 0x0033495c, 0x00324759, 0x00314556, 0x002f4454, 0x002e4453, 0x002c4250, 0x002c3f4d, 0x00293b49, 0x00273846, 0x00243543, 0x0023313e, 0x00202e3a, 0x001e2a36, 0x001c2833, 0x00192530, 0x0018242e, 0x0015202c, 0x00141e29, 0x00131c26, 0x00121923, 0x00101720, 0x000f141d, 0x000e1219, 0x000b1016, 0x00090e14, 0x00080c10, 0x0005080c, 0x0004060a, 0x00040609, 0x00040609, 0x0006080c, 0x00090b10, 0x000c0d13, 0x000c0e13, 0x000b0e12, 0x000a0d11, 0x00080c10, 0x0008090e, 0x0008090d, 0x0006080c, 0x0004070a, 0x0008090d, 0x0014151c, 0x0022252d, 0x002a2f39, 0x002d343f, 0x002e3641, 0x00303945, 0x00303a45, 0x002f3842, 0x00303944, 0x00313c48, 0x0032404c, 0x0031404d, 0x002f414e, 0x002c414e, 0x002c3e4b, 0x00263744, 0x00293946, 0x00273643, 0x00243340, 0x001f2f3b, 0x0022313d, 0x002e3d49, 0x00283944, 0x0023333e, 0x0020303b, 0x001d2b35, 0x00222f38, 0x0015212c, 0x00121d28, 0x0016232f, 0x00202d39, 0x00182531, 0x001b2834, 0x001d2b34, 0x001b2832, 0x001b2830, 0x00141d26, 0x00141c25, 0x00151e27, 0x00151e28, 0x00131c26, 0x00111b26, 0x0017202b, 0x001a242c, 0x0019222b, 0x00151e27, 0x0019222a, 0x00101921, 0x00182029, 0x0018222b, 0x00151f28, 0x00141e27, 0x0014202a, 0x0018222c, 0x0018222c, 0x0017212c, 0x001a2430, 0x0017222d, 0x0018242e, 0x001c2530, 0x001c2530, 0x0016202a, 0x00202a34, 0x00202b35, 0x001c2832, 0x001b2731, 0x001c2834, 0x0023303b, 0x00273440, 0x001c2b35, 0x00182732, 0x0022303c, 0x00253340, 0x00253442, 0x00253442, 0x00243543, 0x00293b49, 0x00293b49, 0x00293c49, 0x002c3f4d, 0x002c404e, 0x00314554, 0x002d4252, 0x002d4151, 0x002e4352, 0x00344858, 0x002a3f4d, 0x00293e4d, 0x002d424f, 0x002d434f, 0x00304752, 0x002f4450, 0x00314452, 0x00334553, 0x0031404f, 0x00303d4c, 0x00303c4a, 0x00303b48, 0x00323b47, 0x00343945, 0x00333844, 0x00333844, 0x00323844, 0x00323844, 0x00323844, 0x00333843, 0x00333743, 0x00323642, 0x00323642, 0x00323643, 0x00343844, 0x00363c48, 0x00373d48, 0x00303843, 0x00222a35, 0x00101722, 0x000b111b, 0x000c111a, 0x000c1118, 0x000c1218, 0x000e1319, 0x000e1419, 0x000d1219, 0x000d1118, 0x000b0d14, 0x00080a10, 0x0005080c, 0x0004070b, 0x00040609, 0x0007080e, 0x000b0e16, 0x00121720, 0x00161d28, 0x0017222c, 0x00182530, 0x00182834, 0x001a2b37, 0x001c2d39, 0x001f303c, 0x0022323f, 0x00243442, 0x00283848, 0x002a3a4a, 0x002c3c4c, 0x00304151, 0x00304454, 0x00334656, 0x00344657, 0x00344658, 0x00334658, 0x00324759, 0x0031485a, 0x0033495c, 0x00344c5e, 0x00364d60, 0x00354c5f, 0x00344c5e, 0x0032495a, 0x00304352, 0x0024323d, 0x000f171e, 0x0002070c, 0x00010407, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010205, 0x00010205, 0x00010305, 0x00020306, 0x00030408, 0x0003060b, 0x0005080d, 0x00080d12, 0x000c141a, 0x00121d25, 0x0014242d, 0x00152835, 0x00142938, 0x00152938, 0x00152837, 0x00152834, 0x00152733, 0x00152530, 0x00152530, 0x0014242e, 0x0013222d, 0x0011202c, 0x0012202c, 0x0013202c, 0x0013212c, 0x0013232d, 0x0012232e, 0x0012232d, 0x0011232d, 0x0012222d, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x0012242c, 0x0011242c, 0x00112a30, 0x00132c32, 0x00143036, 0x00153439, 0x0016383c, 0x00183c40, 0x00183f43, 0x001a4245, 0x001b4448, 0x001c474b, 0x001d4a4d, 0x001d4c50, 0x001d4d50, 0x001e4f51, 0x001e4f51, 0x001e5053, 0x001e5053, 0x001e5053, 0x001e5053, 0x001e5053, 0x001e4f51, 0x001e4f51, 0x001e4f51, 0x001e4d50, 0x001d4c50, 0x001d4c50, 0x001d4c50, 0x001d4b4e, 0x001d4b4e, 0x001d4b4e, 0x001d4b4e, 0x001c4a4d, 0x001d4a4d, 0x001d4a4d, 0x001d4a4d, 0x001c484c, 0x001c474b, 0x001b4649, 0x001b4448, 0x001a4347, 0x00194044, 0x00183d41, 0x00183a3e, 0x0016363b, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0013282e, 0x0013242c, 0x000f2229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00111f27, 0x00132028, 0x00142028, 0x00142128, 0x00142129, 0x00152029, 0x00152028, 0x00152028, 0x00122027, 0x00132026, 0x00122025, 0x00111f24, 0x00111f24, 0x00121f26, 0x00131f26, 0x00101d24, 0x000f1920, 0x000c141b, 0x00080d14, 0x0005080e, 0x0004040a, 0x00020308, 0x00020306, 0x00000205, 0x00000206, 0x00000206, 0x00000206, 0x00000206, 0x00000205, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00020404, 0x00020404, 0x00020404, 0x00020405, 0x00020407, 0x0003070c, 0x000e161e, 0x00253640, 0x00304652, 0x00334a57, 0x00344959, 0x0034485a, 0x00314658, 0x00314557, 0x002f4454, 0x002c4251, 0x002c4352, 0x002c4050, 0x002a3c4c, 0x00283948, 0x00263744, 0x00243440, 0x0021303c, 0x001e2d38, 0x001c2935, 0x001c2731, 0x0018242f, 0x0017222c, 0x0014202a, 0x00141c27, 0x00121a25, 0x00111822, 0x00101620, 0x000f141c, 0x000d1119, 0x000a1016, 0x000a0f15, 0x00080c11, 0x0005080c, 0x0004060b, 0x00040609, 0x00040609, 0x00040609, 0x0008090c, 0x000b0c10, 0x000b0d12, 0x000a0d12, 0x00090c11, 0x00080c10, 0x00090a10, 0x0008090d, 0x0007080c, 0x0006080a, 0x00050708, 0x000a0c10, 0x00181a21, 0x00262933, 0x002c323d, 0x002e3642, 0x00303844, 0x002f3842, 0x002e3640, 0x002e3740, 0x00303944, 0x002f3b47, 0x002e3c49, 0x002e404c, 0x002c404c, 0x00293d49, 0x00243643, 0x002a3c48, 0x00283845, 0x00253441, 0x0020303c, 0x00243540, 0x00293946, 0x002a3b46, 0x00243540, 0x0020303c, 0x00202d38, 0x0025303c, 0x0015202c, 0x00131d28, 0x00182430, 0x00212d39, 0x001c2834, 0x001c2934, 0x001f2c36, 0x001b2831, 0x001a242e, 0x001a232c, 0x00161e28, 0x00151f29, 0x00141e28, 0x000e1824, 0x00141e2b, 0x0018222c, 0x0017212b, 0x0018222b, 0x00141f28, 0x001b242d, 0x0019232c, 0x0017212a, 0x00141f28, 0x00121c25, 0x00141d27, 0x0018232e, 0x0016212c, 0x0017222c, 0x0018232e, 0x001a2632, 0x001c2834, 0x00202c35, 0x001f2b34, 0x001a2530, 0x0017232d, 0x00202c36, 0x00212d37, 0x00202c37, 0x001a2832, 0x001c2a36, 0x00283541, 0x00293844, 0x0024343f, 0x0022323d, 0x00273643, 0x00283844, 0x00293a46, 0x00283a46, 0x00243844, 0x00263846, 0x00263846, 0x00283b49, 0x002b3f4c, 0x002d4250, 0x00364b5a, 0x00344858, 0x00324655, 0x00304454, 0x00354a5a, 0x002e4354, 0x002c4050, 0x00283d4a, 0x002b404c, 0x002f4550, 0x002f4450, 0x0030424f, 0x0033424f, 0x00333f4c, 0x00303c49, 0x002f3a46, 0x002f3945, 0x00303944, 0x00323844, 0x00323844, 0x00323844, 0x00323844, 0x00323844, 0x00333844, 0x00333843, 0x00333743, 0x00333743, 0x00343844, 0x00363b47, 0x00383c48, 0x00373e49, 0x00353d47, 0x0028303a, 0x00151d26, 0x000a121a, 0x00091118, 0x000c1118, 0x000c1216, 0x000c1216, 0x000c1216, 0x000c1216, 0x000c1016, 0x000b0e14, 0x00090b11, 0x0007080d, 0x00040609, 0x00030508, 0x00030508, 0x0006080d, 0x000b0e16, 0x00121821, 0x00161e28, 0x0018222c, 0x00182430, 0x00182732, 0x001b2a36, 0x001d2c38, 0x001f2e3c, 0x0022313e, 0x00243340, 0x00273644, 0x00283948, 0x002b3c4a, 0x002e3f4e, 0x00304352, 0x00324555, 0x00344657, 0x00344658, 0x00334658, 0x00314759, 0x00304759, 0x0031485a, 0x00334a5c, 0x00334b5c, 0x00334b5c, 0x00324a5c, 0x00304757, 0x002d3f4d, 0x00202c38, 0x000b1119, 0x0002060a, 0x00010407, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020405, 0x00020507, 0x00030708, 0x00050a0c, 0x00080e14, 0x000e171c, 0x00121e27, 0x00152633, 0x00152938, 0x00162939, 0x00152838, 0x00152835, 0x00152734, 0x00152731, 0x00142530, 0x0014242f, 0x0012242e, 0x0011222c, 0x0011212c, 0x0011222c, 0x0012222d, 0x0011242e, 0x0011242e, 0x0010242d, 0x0010232d, 0x0010232d, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f2229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00132c32, 0x00143036, 0x00153439, 0x0017383c, 0x00173a3e, 0x00183d41, 0x00194044, 0x001a4347, 0x001b4448, 0x001c4649, 0x001c474b, 0x001c484c, 0x001c4a4d, 0x001c4a4d, 0x001d4a4d, 0x001d4a4d, 0x001d4a4d, 0x001d4a4d, 0x001c4a4d, 0x001c4a4d, 0x001c484c, 0x001c484c, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c474b, 0x001c4649, 0x001b4649, 0x001b4649, 0x001b4649, 0x001c4649, 0x001a4448, 0x001b4448, 0x001a4347, 0x001a4347, 0x001a4245, 0x00194044, 0x00183f43, 0x00183c40, 0x00183a3e, 0x0016363b, 0x00153439, 0x00143036, 0x00132c32, 0x00112a30, 0x0011282e, 0x0013242c, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00122028, 0x00122028, 0x00132028, 0x00131f27, 0x00131f27, 0x00141d26, 0x00131c25, 0x00131b24, 0x000f1a20, 0x000e181f, 0x000d181e, 0x000c171c, 0x000c151c, 0x000d161c, 0x000e161c, 0x000d151b, 0x000c1218, 0x00090d13, 0x0006090e, 0x0003060a, 0x00010408, 0x00020406, 0x00010404, 0x00000205, 0x00000205, 0x00000205, 0x00000205, 0x00000205, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010404, 0x00020404, 0x00020404, 0x00020404, 0x00020404, 0x00020406, 0x0004080b, 0x000c141b, 0x0024343c, 0x002f444f, 0x00304754, 0x00304556, 0x00304557, 0x00304556, 0x00314556, 0x00304454, 0x002e4352, 0x002c4251, 0x002b4050, 0x00293c4c, 0x00283848, 0x00243644, 0x0022333f, 0x0020303b, 0x001d2c37, 0x001b2834, 0x001a2630, 0x0018242e, 0x0016212c, 0x00141f29, 0x00131c27, 0x00121a25, 0x00111822, 0x000f151f, 0x000e141c, 0x000d1119, 0x000a1017, 0x00090f15, 0x00080d11, 0x0005080d, 0x0004060b, 0x00040609, 0x00040609, 0x00040609, 0x0006080b, 0x00090b0e, 0x000a0c10, 0x00090c11, 0x00090c11, 0x00080c10, 0x00080a10, 0x0008090d, 0x0007080c, 0x0005070a, 0x00040608, 0x0005070b, 0x000e1016, 0x001d2029, 0x00272c36, 0x002b333d, 0x002c3440, 0x002e343e, 0x002e343d, 0x002f353f, 0x00303742, 0x002d3843, 0x002c3944, 0x002f3f4c, 0x002c3f4b, 0x00283b47, 0x00263845, 0x0030414e, 0x002c3c49, 0x00253643, 0x0021333e, 0x00293b47, 0x00273844, 0x00293a45, 0x00263741, 0x0020303c, 0x00202e39, 0x00232f3a, 0x00182430, 0x0017232d, 0x001d2934, 0x0024303b, 0x00222e39, 0x001b2833, 0x001c2933, 0x0018252f, 0x0016212b, 0x001b242f, 0x001a232c, 0x0018232c, 0x0018222c, 0x00101924, 0x0019242e, 0x001b252f, 0x00141d27, 0x00141f28, 0x00152028, 0x0018232c, 0x001c262e, 0x0019242c, 0x00141f28, 0x00131c25, 0x00151f28, 0x001a2530, 0x0016212c, 0x0018242e, 0x0018242f, 0x001b2632, 0x001d2934, 0x0024323c, 0x0026343d, 0x001f2c35, 0x00202c36, 0x00232f38, 0x001f2c36, 0x001e2c35, 0x0016242e, 0x001a2833, 0x0023323d, 0x00283944, 0x00283a44, 0x00273844, 0x00283a46, 0x002a3c48, 0x002b3c48, 0x002a3d49, 0x002a3c48, 0x00253844, 0x00223443, 0x002a3c4b, 0x002c404d, 0x002e4452, 0x00364c5c, 0x00364c5c, 0x00344b5a, 0x00304555, 0x0034495a, 0x00304456, 0x002a3f4e, 0x00253a48, 0x002c414d, 0x00304551, 0x00324450, 0x0032414e, 0x00323d4b, 0x00313a48, 0x00303845, 0x00303844, 0x00303844, 0x00313844, 0x00323844, 0x00323844, 0x00323844, 0x00323844, 0x00323844, 0x00323843, 0x00333844, 0x00333843, 0x00343844, 0x00363b46, 0x00393e49, 0x00393f4a, 0x00383f4a, 0x002f3740, 0x001f2730, 0x000e151c, 0x00081016, 0x00091117, 0x000c1218, 0x000c1216, 0x000c1216, 0x000c1216, 0x000c1116, 0x000b0f15, 0x00080c12, 0x00070810, 0x0005070c, 0x00040508, 0x00020508, 0x00030609, 0x00070a0f, 0x000c1018, 0x00141822, 0x00171e28, 0x0018222b, 0x0019242e, 0x001a2732, 0x001c2935, 0x001e2c38, 0x00202d3b, 0x0021303d, 0x0022313f, 0x00253443, 0x00283846, 0x002a3b48, 0x002d3e4c, 0x00304351, 0x00324554, 0x00334556, 0x00334557, 0x00334557, 0x00314558, 0x00304558, 0x00304758, 0x00314859, 0x00314959, 0x00314959, 0x00304858, 0x002d4353, 0x00293a48, 0x001b2731, 0x00070e15, 0x00010509, 0x00020407, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00030407, 0x00030507, 0x00040709, 0x0004090c, 0x00091015, 0x000f181f, 0x0013202c, 0x00162734, 0x00172937, 0x00152936, 0x00162834, 0x00162834, 0x00152731, 0x00142530, 0x0014242f, 0x0012242e, 0x0011232d, 0x0011232d, 0x0012242e, 0x0013242f, 0x0012252f, 0x0011252f, 0x0011242f, 0x0011242e, 0x0011242e, 0x000c1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00102229, 0x00102229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00132c32, 0x00143036, 0x00143338, 0x0016363b, 0x0017383c, 0x00183c40, 0x00183d41, 0x00183f43, 0x00194044, 0x001a4245, 0x001a4347, 0x001a4347, 0x001b4448, 0x001c4448, 0x001c4448, 0x001c4448, 0x001c4448, 0x001b4448, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4347, 0x001a4245, 0x001a4245, 0x00194245, 0x00194245, 0x00194044, 0x00194044, 0x00194044, 0x00194044, 0x001a4044, 0x00194044, 0x00183f43, 0x00183d41, 0x00183d41, 0x00183c40, 0x00173a3e, 0x0017383c, 0x0016363b, 0x00153338, 0x00143036, 0x00132c32, 0x00112a30, 0x0010282e, 0x0013242c, 0x00102229, 0x00102229, 0x00111f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101e26, 0x00111e26, 0x00101d24, 0x00101c24, 0x00101a23, 0x000f1820, 0x000e1720, 0x000e141d, 0x000b121a, 0x00091016, 0x00080f14, 0x00070f14, 0x00060d14, 0x00080f15, 0x000a1016, 0x00091014, 0x000a0d13, 0x00070a0e, 0x0004070c, 0x00020408, 0x00010406, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000104, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x0004050a, 0x000c1118, 0x0022303a, 0x002d424e, 0x002e4454, 0x002d4454, 0x002d4454, 0x002f4454, 0x00304455, 0x00304455, 0x002e4352, 0x002d4151, 0x002c3f4f, 0x00293b4b, 0x00273847, 0x00243543, 0x0021323e, 0x001f2e39, 0x001c2b36, 0x001a2833, 0x00192530, 0x0017232c, 0x0015202b, 0x00131e28, 0x00121b26, 0x00121924, 0x00101721, 0x000f151f, 0x000d141c, 0x000d1119, 0x000c1118, 0x00091015, 0x00080c12, 0x0005090e, 0x0003070b, 0x00030609, 0x00040609, 0x00040508, 0x00040508, 0x0006080b, 0x00080a0f, 0x000a0c11, 0x00090c10, 0x00080c10, 0x00080b10, 0x0008090d, 0x0007080c, 0x0005070a, 0x00040609, 0x00040509, 0x0006080e, 0x0011151c, 0x001e242c, 0x00282e39, 0x002c323d, 0x002d323c, 0x002d323c, 0x002f343f, 0x00303641, 0x002d3641, 0x002c3843, 0x002f3d48, 0x002c3d48, 0x00273844, 0x00293c48, 0x00364854, 0x002e404c, 0x00273844, 0x00213440, 0x002a3c48, 0x00283a46, 0x00283a44, 0x00273742, 0x0024343f, 0x00202e39, 0x001d2a34, 0x00182530, 0x00192630, 0x00202d37, 0x0024323c, 0x0028353f, 0x001e2b35, 0x001c2933, 0x00192530, 0x0014202b, 0x0019242e, 0x001c2630, 0x001a242e, 0x001b242d, 0x00162029, 0x00222c35, 0x001b242d, 0x00121c24, 0x00111c24, 0x00151f28, 0x0018222b, 0x001a242c, 0x0019232c, 0x00152028, 0x00101a23, 0x0018212b, 0x001d2833, 0x001e2a34, 0x0018242f, 0x001a2631, 0x001b2733, 0x001d2a35, 0x0024323c, 0x00283740, 0x0024323c, 0x00243039, 0x0024303a, 0x001e2b34, 0x001c2a34, 0x00192731, 0x00182632, 0x00202f3a, 0x00273842, 0x00283a44, 0x00263944, 0x00283a47, 0x002b3d49, 0x002c3e4b, 0x00293c48, 0x002c3c4a, 0x00263745, 0x00223543, 0x002d404e, 0x002d414f, 0x00304453, 0x00364c5c, 0x00354c5b, 0x00344a59, 0x002f4554, 0x00334959, 0x00304454, 0x00283c4c, 0x00273c49, 0x002f4450, 0x00324551, 0x00334350, 0x00313f4c, 0x00303947, 0x00303844, 0x00303744, 0x00303744, 0x00303844, 0x00313844, 0x00323844, 0x00323844, 0x00323844, 0x00323844, 0x00313843, 0x00313843, 0x00313844, 0x00323844, 0x00353a46, 0x00383c48, 0x00393e49, 0x00383e49, 0x00343a45, 0x00252c36, 0x00151b23, 0x000c1118, 0x000a1016, 0x000c1218, 0x000c1218, 0x000c1215, 0x000c1215, 0x000c1216, 0x000c1116, 0x000a0f14, 0x00060910, 0x0004060d, 0x0004050b, 0x00030508, 0x00040508, 0x00040709, 0x00080b10, 0x000e1218, 0x00141a23, 0x00171f28, 0x0018212c, 0x00192430, 0x001c2833, 0x001d2b36, 0x001f2c39, 0x00202d3b, 0x0020303c, 0x0022313e, 0x00243441, 0x00273645, 0x00293a47, 0x002c3e4c, 0x002f4150, 0x00314454, 0x00324455, 0x00324456, 0x00324456, 0x00304556, 0x00304556, 0x00304556, 0x00304557, 0x00304657, 0x00304758, 0x002f4556, 0x002c4050, 0x00273542, 0x0017202b, 0x00030a10, 0x00000408, 0x00020406, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00030406, 0x00040406, 0x00040508, 0x00030709, 0x00050b10, 0x00091018, 0x000e1924, 0x0013202d, 0x00162633, 0x00162834, 0x00162834, 0x00162833, 0x00152731, 0x00142530, 0x0014242f, 0x0013242e, 0x0012242e, 0x0013242e, 0x00142430, 0x00142530, 0x00132630, 0x00122730, 0x00112630, 0x0012252f, 0x0012242f, 0x000d1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x00102229, 0x0013242c, 0x0011282e, 0x00112a30, 0x00132c32, 0x00142e34, 0x00143036, 0x00153439, 0x0016363b, 0x0017383c, 0x00183a3e, 0x00183c40, 0x00183c40, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183f43, 0x00183f43, 0x00183f43, 0x00183f43, 0x00183f43, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183d41, 0x00183c40, 0x00183c40, 0x00183c40, 0x00183c40, 0x00183c40, 0x00183c40, 0x00173a3e, 0x00183a3e, 0x0017383c, 0x0016363b, 0x00143439, 0x00143338, 0x00143036, 0x00142e34, 0x00132c32, 0x00112a30, 0x0011282e, 0x0012242c, 0x0012242c, 0x000f2229, 0x00101f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00101922, 0x000f1821, 0x000d161e, 0x000c141c, 0x000a1219, 0x00081017, 0x00080f16, 0x00080c14, 0x00060a11, 0x00040a0f, 0x0003090e, 0x0004080e, 0x0003080d, 0x0004080d, 0x0005090e, 0x0006090e, 0x0005080c, 0x00040509, 0x00030408, 0x00020307, 0x00030304, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010306, 0x0004040a, 0x000a0f16, 0x00202c36, 0x002c3f4c, 0x002d4351, 0x002d4353, 0x002c4353, 0x002d4454, 0x00304455, 0x00304454, 0x002f4252, 0x002e4050, 0x002b3d4d, 0x0029394a, 0x00263646, 0x00233442, 0x0020303d, 0x001e2c38, 0x001c2a35, 0x00192732, 0x0018242f, 0x0016222c, 0x0014202a, 0x00131d27, 0x00121b25, 0x00121924, 0x00101821, 0x000f151f, 0x000d141c, 0x000d1118, 0x000c1017, 0x00090f14, 0x00080c11, 0x00050a0e, 0x0004070b, 0x00040609, 0x00040609, 0x00040508, 0x00030408, 0x00040508, 0x0007080c, 0x000a0c10, 0x00090c10, 0x00080c10, 0x00080b10, 0x0008090d, 0x0008090c, 0x0006080b, 0x0005070a, 0x00040509, 0x0004050c, 0x00090c13, 0x00171a22, 0x00242832, 0x00282f39, 0x002c313c, 0x002d323c, 0x0030343f, 0x00303641, 0x002e3541, 0x002d3643, 0x002f3c48, 0x002f3e4a, 0x00273844, 0x00293c48, 0x00344854, 0x00304450, 0x00283b47, 0x00243743, 0x00283b47, 0x00283945, 0x00283943, 0x00263741, 0x00263540, 0x00202f39, 0x00202e38, 0x001b2832, 0x00182630, 0x00202d38, 0x0024333d, 0x002c3944, 0x0022303c, 0x001c2a35, 0x001e2a36, 0x00192530, 0x001b2630, 0x001c2530, 0x0017212a, 0x001a242d, 0x001f2834, 0x00202b36, 0x001b242e, 0x00141f28, 0x00121c25, 0x00131c25, 0x00162029, 0x001b242d, 0x0019242c, 0x0019242c, 0x00101b24, 0x00141e28, 0x001a2630, 0x001c2933, 0x001e2b34, 0x001b2732, 0x001a2732, 0x001c2a35, 0x0021303a, 0x00273640, 0x0026353e, 0x00243039, 0x00222e38, 0x00202c37, 0x00222f38, 0x00202f38, 0x001e2c38, 0x00233340, 0x00273844, 0x00283945, 0x00283a45, 0x00293c48, 0x002a3d49, 0x00293c48, 0x002b3d4a, 0x00283a47, 0x00283948, 0x00253846, 0x002c3f4d, 0x002e4250, 0x00304654, 0x00344b59, 0x00334958, 0x00314857, 0x00304756, 0x00304655, 0x002e4252, 0x002c404d, 0x002e424e, 0x00304450, 0x00334350, 0x0032404c, 0x00303a46, 0x002f3744, 0x00303744, 0x00303744, 0x00303744, 0x00313844, 0x00313844, 0x00323844, 0x00323844, 0x00323844, 0x00323843, 0x00303742, 0x00313843, 0x00313844, 0x00333944, 0x00353b46, 0x00393d49, 0x00393e49, 0x00373c48, 0x002c323c, 0x001c212c, 0x000e131b, 0x000c1016, 0x000c1016, 0x000d1017, 0x000c1016, 0x000c1114, 0x000c1014, 0x000c1015, 0x000b1014, 0x00080c12, 0x0004080e, 0x0004050c, 0x0004050a, 0x00040508, 0x00040609, 0x0004070b, 0x00080c11, 0x000f141b, 0x00161c24, 0x00171f29, 0x0018222e, 0x00182431, 0x001a2734, 0x001c2a38, 0x001e2b38, 0x00202c3a, 0x00202e3c, 0x0022303f, 0x00233240, 0x00263444, 0x00283847, 0x002c3c4c, 0x002f4051, 0x00304254, 0x00314454, 0x00314455, 0x00314455, 0x00304455, 0x00304455, 0x002f4455, 0x002e4454, 0x002e4454, 0x002f4454, 0x002d4354, 0x002a3d4c, 0x0022303c, 0x00101820, 0x0002080c, 0x00010406, 0x00020405, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00030304, 0x00030405, 0x00030406, 0x00040508, 0x0004080c, 0x00060b11, 0x0009111a, 0x00101924, 0x00131f2b, 0x0014222e, 0x0016242f, 0x00162530, 0x00142530, 0x0014242f, 0x0013242e, 0x0014242e, 0x0013242e, 0x0013242e, 0x00142430, 0x00142530, 0x00142630, 0x00122731, 0x00122630, 0x0012252f, 0x0013242f, 0x000d1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x00102229, 0x0013242c, 0x0012282e, 0x00112a30, 0x00132c32, 0x00142e34, 0x00142e34, 0x00143036, 0x00143338, 0x00153439, 0x00143439, 0x0015363b, 0x0016363b, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0017383c, 0x0016363b, 0x0015363b, 0x0015363b, 0x0015363b, 0x0015363b, 0x0015363b, 0x0015363b, 0x0015363b, 0x00153439, 0x00153439, 0x00143338, 0x00153338, 0x00143036, 0x00142e34, 0x00132c32, 0x00132c32, 0x00112a30, 0x0011282e, 0x0013242c, 0x0012242c, 0x000f2229, 0x000f1f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c141b, 0x000b1219, 0x00080f16, 0x00080d14, 0x00070c12, 0x00060a10, 0x00050810, 0x0004080e, 0x0004070c, 0x0003060a, 0x00030609, 0x00040509, 0x00030509, 0x00020509, 0x00030509, 0x00030509, 0x00030408, 0x00030408, 0x00020307, 0x00010206, 0x00010205, 0x00010204, 0x00000204, 0x00010204, 0x00010204, 0x00000303, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010306, 0x00030409, 0x00080e14, 0x001c2a32, 0x002b3c47, 0x002d414f, 0x002d4251, 0x002c4352, 0x002d4353, 0x002f4454, 0x00304354, 0x00304151, 0x002e3f50, 0x002b3c4c, 0x00283848, 0x00263545, 0x00243340, 0x0021303c, 0x001f2c37, 0x001c2833, 0x00192530, 0x0018242f, 0x0015202c, 0x00151f2a, 0x00141e28, 0x00141c26, 0x00141a24, 0x00121822, 0x0010161f, 0x000e141c, 0x000c1118, 0x000b1017, 0x00090e13, 0x00080c10, 0x0006090e, 0x0005070c, 0x00040608, 0x00040508, 0x00030408, 0x00030407, 0x00040508, 0x00050709, 0x0008090d, 0x00090b0f, 0x00090c10, 0x00090b10, 0x00090a0f, 0x00090a0f, 0x0008090d, 0x0007080c, 0x0005070a, 0x0005070b, 0x0005080c, 0x000d1016, 0x001c1e26, 0x00252832, 0x002b2f3a, 0x002d323c, 0x002e343e, 0x002e3540, 0x002e3541, 0x002e3543, 0x00313a47, 0x00323e4b, 0x002d3c48, 0x002d3e4a, 0x0030424e, 0x00314450, 0x00293d49, 0x00263a45, 0x00283c48, 0x00283b47, 0x00263844, 0x00263742, 0x00243540, 0x00202f39, 0x0023303b, 0x00202f39, 0x001b2a34, 0x001c2a36, 0x0022313d, 0x00273542, 0x001b2a36, 0x001a2733, 0x00232f3b, 0x001b2630, 0x0016202b, 0x0018222c, 0x00142028, 0x0018232c, 0x00212d38, 0x001d2834, 0x00192430, 0x0018232d, 0x0017222c, 0x00131e28, 0x0018222c, 0x001d2830, 0x00172029, 0x00162028, 0x00141d27, 0x001a242c, 0x001c2831, 0x0014212b, 0x001a2831, 0x0024313c, 0x001d2b37, 0x00202f3a, 0x001f2f38, 0x0022323c, 0x002a3843, 0x00232f3a, 0x0024303b, 0x0024303c, 0x0024303c, 0x0024323c, 0x0022323d, 0x00243441, 0x002c3e4b, 0x002c3c49, 0x002c3e4b, 0x002c3f4c, 0x002a3c4a, 0x00263946, 0x002c3e4c, 0x002c404d, 0x002b3d4c, 0x00273c4a, 0x00293e4c, 0x002e4452, 0x002e4554, 0x002f4756, 0x002f4755, 0x00314855, 0x00324857, 0x00304654, 0x002f4351, 0x00324452, 0x00334451, 0x0031424f, 0x0030404c, 0x002f3b47, 0x002e3744, 0x002f3642, 0x00303643, 0x00313643, 0x00323844, 0x00333844, 0x00333844, 0x00323844, 0x00323844, 0x00323743, 0x00323742, 0x00323742, 0x00323843, 0x00333844, 0x00333944, 0x00363c46, 0x00383e48, 0x00383e48, 0x00323842, 0x00242a33, 0x00141820, 0x000c1018, 0x000c1016, 0x000c1016, 0x000c0f16, 0x000c1016, 0x000c1016, 0x000c1016, 0x000b0f15, 0x000a0e14, 0x00080b10, 0x0005080d, 0x0004060b, 0x00040609, 0x00040608, 0x00040609, 0x0004080c, 0x00090e14, 0x0010161d, 0x00151d24, 0x00151f28, 0x0016202c, 0x0017232f, 0x00182531, 0x001a2834, 0x001c2937, 0x001e2b38, 0x00202c3a, 0x00202f3d, 0x00223140, 0x00243442, 0x00273544, 0x002a3a49, 0x002d3e4f, 0x002f4153, 0x00304354, 0x00314455, 0x00314455, 0x00304454, 0x002f4454, 0x002f4454, 0x002e4454, 0x002e4454, 0x002d4252, 0x002b3f50, 0x00273947, 0x001e2c38, 0x000a141c, 0x0000070b, 0x00020508, 0x00020405, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00030304, 0x00030304, 0x00020405, 0x00020406, 0x0003060a, 0x0004080d, 0x00070c13, 0x000b1219, 0x000f1820, 0x00121c25, 0x00131e28, 0x00141f29, 0x00121f28, 0x00121f28, 0x00121f28, 0x0013202b, 0x0013222c, 0x0014242e, 0x0015242e, 0x00152530, 0x00152531, 0x00142631, 0x00142530, 0x0013242f, 0x0013242e, 0x000d1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x00102229, 0x0013242c, 0x0011242c, 0x0011282e, 0x00112a30, 0x00122c32, 0x00132c32, 0x00142e34, 0x00142e34, 0x00143036, 0x00143036, 0x00143036, 0x00153338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00143338, 0x00153338, 0x00153338, 0x00153338, 0x00153338, 0x00143036, 0x00143036, 0x00143036, 0x00143036, 0x00143036, 0x00143036, 0x00143036, 0x00142e34, 0x00142e34, 0x00142e34, 0x00132c32, 0x00112a30, 0x00112a30, 0x0011282e, 0x0013282e, 0x0013242c, 0x00102229, 0x000f2229, 0x000f1f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00080c12, 0x00070b11, 0x0007090d, 0x0007080c, 0x0005070b, 0x0004060a, 0x0004050a, 0x00030409, 0x00020407, 0x00010304, 0x00010304, 0x00010304, 0x00010304, 0x00000304, 0x00000304, 0x00000304, 0x00010304, 0x00010304, 0x00000205, 0x00000206, 0x00000205, 0x00000105, 0x00000205, 0x00020204, 0x00010304, 0x00000302, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010305, 0x00010508, 0x00050e14, 0x001a282f, 0x00283a44, 0x002c404c, 0x002d404f, 0x002c4150, 0x002d4251, 0x002d4353, 0x002f4254, 0x002e4050, 0x002c3d4d, 0x0029394a, 0x00273647, 0x00243444, 0x00233240, 0x00202e3c, 0x001e2b37, 0x001c2833, 0x00182430, 0x0018232f, 0x0015202c, 0x00151f2b, 0x00151f29, 0x00151c27, 0x00141a24, 0x00121821, 0x0010161f, 0x000e141b, 0x000c1118, 0x000b1016, 0x00090e12, 0x00090d12, 0x00080b10, 0x0006080c, 0x0004060a, 0x00030408, 0x00020407, 0x00020404, 0x00040507, 0x00040608, 0x0006080a, 0x0008090c, 0x00090a0e, 0x00090a0f, 0x00090a10, 0x00090a10, 0x00090a0f, 0x0008080c, 0x0007080c, 0x0006080b, 0x0004070a, 0x00060a0c, 0x00111418, 0x001f2228, 0x00292e38, 0x002b323c, 0x002c343d, 0x002c343f, 0x002d3440, 0x002e3441, 0x00313845, 0x00333c48, 0x00313d49, 0x00344350, 0x00334450, 0x0030434f, 0x002a3f4b, 0x00283d49, 0x002a3f4b, 0x00243947, 0x00233642, 0x00263843, 0x0023343e, 0x0023323d, 0x0024323d, 0x0021303b, 0x001d2c37, 0x001a2935, 0x0023323f, 0x0023323f, 0x001b2a37, 0x001d2c38, 0x00212e3a, 0x00192530, 0x0016212c, 0x0017242c, 0x0015212a, 0x0018242e, 0x001f2c36, 0x00202c38, 0x001b2632, 0x001a2632, 0x001e2a35, 0x0017222d, 0x001b2530, 0x001c2530, 0x00162029, 0x00111b24, 0x00172028, 0x001b242d, 0x001d2934, 0x0014232c, 0x00102028, 0x001c2c36, 0x00283742, 0x00283842, 0x0023333e, 0x0021323d, 0x00283641, 0x0025333f, 0x0022303b, 0x0024323e, 0x0024323e, 0x00273641, 0x00273744, 0x00243642, 0x0030444f, 0x002a3d49, 0x0030424f, 0x002c3f4c, 0x002c3e4c, 0x00283c49, 0x002b3e4c, 0x002e4150, 0x002a3e4d, 0x00263b4a, 0x00283d4c, 0x002f4454, 0x002e4554, 0x002e4554, 0x002f4654, 0x00314855, 0x00344a57, 0x00344856, 0x00314451, 0x00344451, 0x00364451, 0x0031404c, 0x002f3c47, 0x002e3844, 0x002f3642, 0x00303741, 0x00313742, 0x00313743, 0x00333843, 0x00343845, 0x00343845, 0x00323843, 0x00313742, 0x00323642, 0x00313541, 0x00333743, 0x00343844, 0x00343844, 0x00343a46, 0x00373d47, 0x00383e48, 0x00343b44, 0x002a303a, 0x001b2029, 0x000d121a, 0x000b1017, 0x000b0f15, 0x000c0f16, 0x000c1016, 0x000d1017, 0x000d1017, 0x000c0f16, 0x000a0e15, 0x00080c13, 0x00080a10, 0x0006080c, 0x00040609, 0x00040608, 0x00040608, 0x00040709, 0x00070a0e, 0x000c1016, 0x0012181e, 0x00151c24, 0x00151d26, 0x0016202b, 0x0017222d, 0x00182430, 0x001b2733, 0x001c2835, 0x001c2936, 0x001f2b38, 0x00202e3b, 0x0021303e, 0x00233140, 0x00243342, 0x00283747, 0x002b3c4c, 0x002e4050, 0x00304254, 0x00314455, 0x00314455, 0x002f4354, 0x002e4354, 0x002e4354, 0x002e4354, 0x002d4253, 0x002c4050, 0x00293c4c, 0x00253644, 0x001a2732, 0x00071017, 0x0001060b, 0x00020608, 0x00020406, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010304, 0x00030407, 0x0004070a, 0x0005080c, 0x00060a0e, 0x000a0f14, 0x000f141a, 0x000f151c, 0x000e161c, 0x000e161c, 0x000e161c, 0x000f171f, 0x00101a22, 0x00131e26, 0x0014212a, 0x0014232c, 0x0015242e, 0x00152431, 0x00142431, 0x00142430, 0x0014242f, 0x0014242e, 0x000d1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00111f27, 0x00102229, 0x000f2229, 0x0012242c, 0x0013242c, 0x0013282e, 0x0011282e, 0x00112a30, 0x00112a30, 0x00112a30, 0x00122c32, 0x00132c32, 0x00132c32, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00142e34, 0x00132c32, 0x00132c32, 0x00132c32, 0x00122c32, 0x00132c32, 0x00112a30, 0x00112a30, 0x0010282e, 0x0011282e, 0x0013282e, 0x0013242c, 0x0012242c, 0x000f2229, 0x00102229, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x0004080c, 0x0004070a, 0x00040608, 0x00040508, 0x00030408, 0x00030408, 0x00020307, 0x00020307, 0x00000305, 0x00000304, 0x00000203, 0x00000203, 0x00000304, 0x00000304, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000205, 0x00000206, 0x00000205, 0x00000206, 0x00010205, 0x00020204, 0x00020204, 0x00010303, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010408, 0x00050d12, 0x001a272d, 0x00283842, 0x002c3c48, 0x002c3f4c, 0x002c404d, 0x002d404f, 0x002c4151, 0x002e4152, 0x002d3e4f, 0x002a3b4c, 0x00273848, 0x00263546, 0x00243343, 0x00223040, 0x001f2d3c, 0x001d2a37, 0x001a2733, 0x00182430, 0x0018232f, 0x0015202c, 0x00151f2b, 0x0015202a, 0x00141c28, 0x00141a24, 0x00121821, 0x0010161f, 0x000e141b, 0x000c1118, 0x000b1016, 0x00090e12, 0x00090d12, 0x00080c10, 0x0007090d, 0x0005070a, 0x00030408, 0x00020406, 0x00020405, 0x00030406, 0x00040608, 0x00040708, 0x00060809, 0x0008080c, 0x0008090d, 0x00090a0f, 0x00090a10, 0x00090a0f, 0x0008080d, 0x0007080c, 0x0006080b, 0x00040709, 0x00040708, 0x000a0d10, 0x00181c20, 0x00282d35, 0x0029313a, 0x0028303a, 0x002c343c, 0x002c343e, 0x002e3440, 0x00303743, 0x00303a46, 0x00303b47, 0x0033404c, 0x00344450, 0x0030434f, 0x002a3f4b, 0x00273c47, 0x00273c48, 0x00243846, 0x00253844, 0x00253843, 0x0023343f, 0x00263540, 0x0022303c, 0x001f2d38, 0x001c2c36, 0x001a2935, 0x00273643, 0x00243440, 0x00253441, 0x00293844, 0x00222f3b, 0x001f2a36, 0x001f2b35, 0x001c2932, 0x0017242d, 0x00192630, 0x001d2b35, 0x0024323e, 0x001d2935, 0x001e2b37, 0x00212d39, 0x001d2935, 0x001e2833, 0x001c2630, 0x0018222b, 0x00121c24, 0x00172028, 0x00141e28, 0x001d2832, 0x00192831, 0x0014242d, 0x00162530, 0x00283843, 0x002c3c47, 0x00283843, 0x0023343f, 0x0024343f, 0x00293844, 0x0024343f, 0x0024333e, 0x00283843, 0x00283843, 0x00283946, 0x00253844, 0x00334652, 0x00293c48, 0x002d404c, 0x002c3f4c, 0x002c3f4d, 0x002a3d4b, 0x002b3f4c, 0x002c3f4c, 0x002a3f4c, 0x00263c4a, 0x002a404f, 0x00304655, 0x00304654, 0x00304555, 0x00304654, 0x00324754, 0x00344856, 0x00354755, 0x00324250, 0x0033414e, 0x0034414d, 0x00313d49, 0x002f3a44, 0x002f3843, 0x00303843, 0x00323843, 0x00323844, 0x00323844, 0x00323844, 0x00323844, 0x00313844, 0x00303741, 0x00303540, 0x00303540, 0x00313541, 0x00333842, 0x00343944, 0x00353a46, 0x00363c48, 0x00373d48, 0x00333a43, 0x002a303a, 0x001c232c, 0x0010141d, 0x000b1018, 0x000a0f16, 0x000b0f15, 0x000c0f16, 0x000c1016, 0x000c1016, 0x000c0f16, 0x000c0e15, 0x00090c14, 0x00080b11, 0x0008090f, 0x0005070c, 0x00040609, 0x00040608, 0x00040608, 0x0004070a, 0x00080b10, 0x000e1118, 0x00121820, 0x00151c25, 0x00151d28, 0x0016202b, 0x0017232d, 0x00192530, 0x001c2733, 0x001c2834, 0x001d2934, 0x001f2b37, 0x00202d39, 0x00212f3c, 0x0023303f, 0x00233140, 0x00253444, 0x00293a4a, 0x002c3f4f, 0x002f4253, 0x00314455, 0x00314455, 0x002e4354, 0x002e4254, 0x002d4254, 0x002d4153, 0x002c4051, 0x00293e4e, 0x00283b4b, 0x00223240, 0x0014202b, 0x00040a11, 0x00020509, 0x00020507, 0x00010404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010405, 0x00020508, 0x00020509, 0x0003070a, 0x00060a0c, 0x000b0e12, 0x000a0f14, 0x00090f14, 0x00090f14, 0x00090f14, 0x000a1015, 0x00091118, 0x000c141a, 0x000e181f, 0x00101c24, 0x00131f28, 0x0014202b, 0x0014212c, 0x0014222c, 0x0012232d, 0x0012232d, 0x000d1c26, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x000f1f27, 0x00102229, 0x00102229, 0x0012242c, 0x0013242c, 0x0012242c, 0x0013282e, 0x0012282e, 0x0010282e, 0x0010282e, 0x0010282e, 0x00112a30, 0x00112a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00102a30, 0x00112a30, 0x0010282e, 0x0010282e, 0x0010282e, 0x0011282e, 0x0012282e, 0x0013282e, 0x0012242c, 0x0013242c, 0x0012242c, 0x00102229, 0x000f2229, 0x00112229, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00020405, 0x00020404, 0x00030405, 0x00020406, 0x00020406, 0x00020406, 0x00020406, 0x00020406, 0x00010304, 0x00000203, 0x00000203, 0x00000203, 0x00000203, 0x00010303, 0x00010302, 0x00010302, 0x00000204, 0x00000204, 0x00000104, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000407, 0x00050c12, 0x0018242d, 0x00263741, 0x00293b46, 0x002a3c48, 0x002b3e4a, 0x002c3f4c, 0x002c404f, 0x002d4050, 0x002c3d4e, 0x00293a4a, 0x00273748, 0x00263446, 0x00233242, 0x0021303f, 0x001e2c3c, 0x001c2938, 0x00192634, 0x00182331, 0x0017232e, 0x0015202c, 0x00151f2b, 0x0015202a, 0x00141d28, 0x00141a24, 0x00121821, 0x0010161f, 0x000e141b, 0x000c1118, 0x000b1016, 0x00090e12, 0x00090d12, 0x00090c11, 0x0008090d, 0x00050709, 0x00030507, 0x00020405, 0x00020404, 0x00030406, 0x00040608, 0x00040608, 0x00050708, 0x0007080b, 0x0007080c, 0x0008090e, 0x0008090f, 0x0008090f, 0x0007080d, 0x0006080c, 0x0006080c, 0x0004070b, 0x00030708, 0x0006090c, 0x0012151a, 0x00252a31, 0x00242b34, 0x00242c35, 0x00283039, 0x002a313b, 0x002e343f, 0x002f3641, 0x00303843, 0x002f3843, 0x00303c47, 0x0031404c, 0x00334450, 0x002c404c, 0x00223743, 0x00263b47, 0x00273b48, 0x00243845, 0x00243743, 0x00233440, 0x00253542, 0x00202f3b, 0x001d2c38, 0x001c2c36, 0x001e2e38, 0x00283742, 0x00273641, 0x002b3a45, 0x002d3b47, 0x0024303b, 0x00202c38, 0x0024303c, 0x001d2c34, 0x0016242e, 0x00182630, 0x001c2c36, 0x00253440, 0x001f2d3b, 0x001f2d3a, 0x00212f3b, 0x001f2b37, 0x001f2833, 0x00212b35, 0x0018222b, 0x00162028, 0x00171f28, 0x00141c26, 0x001a2530, 0x001f2c36, 0x001b2b34, 0x00192833, 0x0020303c, 0x0022313d, 0x00273843, 0x00243540, 0x0020303b, 0x00263541, 0x002a3945, 0x00283844, 0x002d3d49, 0x00293a46, 0x00283b47, 0x002a3f4a, 0x00304550, 0x00293d49, 0x00243845, 0x00273b48, 0x00293e4c, 0x00283c4a, 0x00293e4c, 0x00283d4b, 0x002b404d, 0x00293e4c, 0x00304554, 0x00324857, 0x00314756, 0x00324555, 0x00304453, 0x00324452, 0x00344554, 0x00354453, 0x00313f4e, 0x00303d4b, 0x00303c48, 0x002f3a46, 0x002f3944, 0x00313844, 0x00333944, 0x00333944, 0x00333944, 0x00323844, 0x00323844, 0x00303744, 0x00303644, 0x002f3540, 0x00303640, 0x00323640, 0x00323741, 0x00343842, 0x00353a46, 0x00373c48, 0x00383c48, 0x00343b44, 0x0029323b, 0x001c242d, 0x000e151e, 0x00090f18, 0x000a0e17, 0x000a0f16, 0x000b0f15, 0x000c0f16, 0x000c1016, 0x000c1016, 0x000c0e15, 0x00090c13, 0x00080b11, 0x00070810, 0x0007070c, 0x0004040a, 0x00040409, 0x00040509, 0x00040609, 0x0004070c, 0x00090c13, 0x000e121b, 0x00131822, 0x00141c26, 0x00151d28, 0x0016202b, 0x0018232d, 0x00192530, 0x001b2733, 0x001c2834, 0x001d2935, 0x001f2b37, 0x00202d39, 0x00212f3c, 0x0022303f, 0x00223040, 0x00243343, 0x00283949, 0x002c3d4d, 0x002f4051, 0x00304254, 0x00304254, 0x002e4253, 0x002c4052, 0x002d4153, 0x002d4153, 0x002b3f4f, 0x00283c4c, 0x00273848, 0x00202e3c, 0x00101a24, 0x0002080f, 0x00010408, 0x00010405, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000408, 0x00000408, 0x00020508, 0x00020609, 0x0005080c, 0x0004090c, 0x0004090c, 0x0004090c, 0x0004090c, 0x0004090c, 0x00040a0f, 0x00060c10, 0x00070e14, 0x00081017, 0x000a141b, 0x000d181f, 0x00101b23, 0x00121e27, 0x00121f28, 0x0012202a, 0x000c1c25, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00101f27, 0x00102229, 0x000f2229, 0x00102229, 0x00102229, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0012242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0011242c, 0x0012242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x0013242c, 0x00102229, 0x00102229, 0x000f2229, 0x00102229, 0x000f1f27, 0x00111f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010404, 0x00020403, 0x00030303, 0x00030304, 0x00030304, 0x00030304, 0x00030304, 0x00030304, 0x00020204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020203, 0x00020202, 0x00020202, 0x00000204, 0x00000204, 0x00000104, 0x00000104, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00010405, 0x00050b10, 0x00172129, 0x0025353f, 0x00283a46, 0x00293c47, 0x002a3d49, 0x002a3e4b, 0x002b3e4c, 0x002c3e4d, 0x002b3c4c, 0x00283848, 0x00263747, 0x00263446, 0x00243242, 0x00222f3f, 0x001f2c3b, 0x001c2837, 0x00192533, 0x00182330, 0x0018232f, 0x0016202c, 0x00151f2b, 0x00151f29, 0x00141d28, 0x00141a24, 0x00121821, 0x0010161f, 0x000e141b, 0x000c1119, 0x000b1017, 0x000b0e14, 0x000a0d12, 0x000a0c11, 0x0008090e, 0x0005070a, 0x00040507, 0x00020405, 0x00020405, 0x00030406, 0x00040608, 0x00040608, 0x00050708, 0x0006080a, 0x0007080c, 0x0008090e, 0x0008090f, 0x0008090f, 0x0007080d, 0x0006080c, 0x0006080c, 0x0005080c, 0x00040809, 0x0004080a, 0x000c1015, 0x001d2229, 0x001e232b, 0x00202830, 0x00252d36, 0x00283038, 0x002d343d, 0x00303641, 0x00303843, 0x002c3641, 0x002c3741, 0x00303c48, 0x00364552, 0x00344552, 0x00273a46, 0x002a3e4a, 0x00293d4a, 0x00253945, 0x00283a46, 0x00233541, 0x00263643, 0x0020303d, 0x0020303c, 0x001f303a, 0x0024343f, 0x00263640, 0x00273641, 0x00263540, 0x0024313c, 0x00212c38, 0x00202c38, 0x0027343f, 0x00202f38, 0x00172630, 0x00172630, 0x001a2a34, 0x00273542, 0x0022303d, 0x0021303c, 0x00202e3a, 0x00202d39, 0x001d2833, 0x00212b35, 0x001b2630, 0x0018212b, 0x0018212b, 0x00161f28, 0x0017232c, 0x001f2d37, 0x00202f38, 0x001d2c37, 0x0020303c, 0x001c2c38, 0x0020303c, 0x0022333e, 0x001d2d39, 0x0022313f, 0x00283846, 0x00283948, 0x002d3e4c, 0x002b3d4b, 0x00283b48, 0x002a3f4b, 0x002b404c, 0x00273c49, 0x00223744, 0x00263b48, 0x00283d4b, 0x00283d4c, 0x002b404e, 0x002b404e, 0x002c414f, 0x002c404d, 0x00344655, 0x00344858, 0x00344757, 0x00344555, 0x00324352, 0x00324150, 0x00334150, 0x00344050, 0x00313d4c, 0x00303b49, 0x00303a46, 0x002f3844, 0x00303944, 0x00333944, 0x00343944, 0x00343944, 0x00343843, 0x00323842, 0x00303742, 0x00303542, 0x002f3440, 0x002e343e, 0x00303540, 0x00333741, 0x00343842, 0x00353a44, 0x00383c48, 0x00383c48, 0x00393d49, 0x00313740, 0x00202730, 0x00111821, 0x000a1019, 0x00080d16, 0x00090d16, 0x000a0f16, 0x000b0f15, 0x000c0e15, 0x000c0f15, 0x000c0e15, 0x000a0d14, 0x00080b11, 0x00070910, 0x0006080e, 0x0005050b, 0x00040409, 0x00030409, 0x00040509, 0x0004060a, 0x0004080c, 0x000a0d14, 0x000f141d, 0x00131924, 0x00151d28, 0x00161e29, 0x0016202a, 0x0018222b, 0x0018242d, 0x001a2530, 0x001c2832, 0x001d2934, 0x001e2a37, 0x00202c38, 0x00202d3b, 0x0022303e, 0x00223040, 0x00233242, 0x00273748, 0x002b3c4c, 0x002d3f50, 0x002e4053, 0x002f4153, 0x002c4153, 0x002c4052, 0x002c4052, 0x002c4050, 0x00283d4c, 0x00263a48, 0x00253544, 0x001d2935, 0x000a141c, 0x0000060c, 0x00010408, 0x00000407, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000407, 0x00000408, 0x00010408, 0x00010508, 0x00020609, 0x00020609, 0x00010609, 0x00010709, 0x00010709, 0x00020609, 0x00020609, 0x0003070a, 0x0004080c, 0x0004080f, 0x00050a10, 0x00060c13, 0x00090f17, 0x000b121b, 0x000d1620, 0x000f1924, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00101f27, 0x000f1f27, 0x00102229, 0x000f2229, 0x000f2229, 0x000f2229, 0x000f2229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x00102229, 0x000f2229, 0x000f2229, 0x000f2229, 0x000f2229, 0x00102229, 0x000f1f27, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010304, 0x00020202, 0x00020202, 0x00020203, 0x00020203, 0x00020203, 0x00020203, 0x00020203, 0x00020203, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020203, 0x00020203, 0x00020203, 0x00010204, 0x00010204, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00010406, 0x0005090e, 0x00141d24, 0x0024323c, 0x00283944, 0x00283b46, 0x00283c48, 0x00283c4a, 0x002a3c4a, 0x002b3c4a, 0x00293b4a, 0x00273847, 0x00263746, 0x00253444, 0x00243140, 0x00212e3c, 0x001f2b38, 0x001c2834, 0x001a2531, 0x00192430, 0x0018232f, 0x0017212d, 0x0016202b, 0x00161e29, 0x00151d28, 0x00141b24, 0x00111822, 0x000f161f, 0x000d141c, 0x000c1119, 0x000b1018, 0x000b0e16, 0x000a0d14, 0x000b0c11, 0x00090b10, 0x0007080c, 0x00040608, 0x00030507, 0x00030406, 0x00030406, 0x00040606, 0x00040607, 0x00040607, 0x00050708, 0x00060809, 0x0007080c, 0x0008090e, 0x0008090e, 0x0007080d, 0x0007080d, 0x0007080c, 0x0006090c, 0x0005080b, 0x0004070b, 0x00070a10, 0x0013161c, 0x00171b21, 0x001c2129, 0x00242931, 0x00292e38, 0x002d323c, 0x002f3540, 0x00303640, 0x002c343f, 0x0029333d, 0x002e3844, 0x0035404e, 0x00384452, 0x0031414d, 0x0030424e, 0x002b3c49, 0x00253744, 0x00273945, 0x00253844, 0x00283b47, 0x00213440, 0x00243541, 0x00243642, 0x002a3b47, 0x00253743, 0x00243440, 0x001e2d39, 0x00202e39, 0x00202d38, 0x0023303b, 0x0027343f, 0x00202f39, 0x00182730, 0x00182831, 0x001b2a34, 0x00202f3a, 0x0025343f, 0x0023323d, 0x00202e39, 0x0024313c, 0x00202d39, 0x00192630, 0x001d2b34, 0x00182530, 0x001c2730, 0x00152129, 0x0019262e, 0x001c2931, 0x0022303a, 0x00202f38, 0x0022313c, 0x00243640, 0x0020313c, 0x001f303c, 0x001c2c39, 0x001d2e3c, 0x00243443, 0x00283a48, 0x002c3e4c, 0x002b3f4c, 0x00273c49, 0x00273c4a, 0x002a3f4e, 0x00283d4c, 0x00263b49, 0x00293d4d, 0x0029404f, 0x002a404f, 0x002d4352, 0x00344858, 0x00344554, 0x0030404e, 0x00344553, 0x00374756, 0x00374655, 0x00374554, 0x00354251, 0x0034404f, 0x00333f4d, 0x00333e4c, 0x00323c4a, 0x00303a48, 0x00303945, 0x00303944, 0x00323a45, 0x00343b45, 0x00343944, 0x00343842, 0x00323640, 0x00303540, 0x002f343e, 0x002e333e, 0x002d323d, 0x002e323c, 0x00303440, 0x00343842, 0x00353a44, 0x00383c48, 0x00393e4a, 0x003a3f4a, 0x00373b46, 0x002b2e38, 0x00181c23, 0x000c1017, 0x00090d14, 0x000a0d14, 0x000a0d15, 0x000b0e15, 0x000c0f15, 0x000c0e15, 0x000a0d14, 0x000a0c13, 0x000a0b10, 0x0008090f, 0x0006080c, 0x0004060a, 0x00040509, 0x00040408, 0x00040408, 0x00040609, 0x0004070a, 0x00050a0f, 0x000a1017, 0x000f151e, 0x00121a24, 0x00141d28, 0x00151f29, 0x0014202b, 0x0017222c, 0x0017242d, 0x00182630, 0x001b2831, 0x001c2934, 0x001e2a36, 0x00202c38, 0x00202c3a, 0x00202e3d, 0x0021303f, 0x00223040, 0x00253444, 0x00283849, 0x002b3d4d, 0x002c3f50, 0x002d4153, 0x002c4153, 0x002c4052, 0x002c4051, 0x002b3f4f, 0x00283d4b, 0x00263a46, 0x00243440, 0x001b2630, 0x00080f15, 0x0002060b, 0x00020408, 0x00010407, 0x00010404, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010304, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000305, 0x00000305, 0x00010406, 0x00020406, 0x00020407, 0x00030408, 0x00010408, 0x00010408, 0x00010407, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00030509, 0x0004060a, 0x0005080c, 0x0005090d, 0x00080c11, 0x00090f15, 0x000c1923, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00111f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00101f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00020204, 0x00020202, 0x00020202, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000304, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010406, 0x0004090d, 0x00111a21, 0x00233039, 0x00273843, 0x00283a45, 0x00283b47, 0x00283c49, 0x00293b49, 0x002a3b48, 0x00283a48, 0x00263846, 0x00263644, 0x00243443, 0x0023303f, 0x00202d3c, 0x001e2a38, 0x001c2834, 0x00192531, 0x0018242f, 0x0018212e, 0x0016202c, 0x00151f2a, 0x00151e29, 0x00151d28, 0x00131c24, 0x00101822, 0x000e161e, 0x000d141c, 0x000b1119, 0x000b1018, 0x000a0e16, 0x000a0d14, 0x000a0c11, 0x000a0c10, 0x00080a0d, 0x00050708, 0x00030506, 0x00020405, 0x00030406, 0x00040505, 0x00040606, 0x00040606, 0x00050707, 0x00050708, 0x0006080b, 0x0008080c, 0x0008090d, 0x0007080d, 0x0007080d, 0x0007080d, 0x00070a0c, 0x00070a0d, 0x0004080c, 0x0003080c, 0x00080c10, 0x00101318, 0x00181b21, 0x0020252c, 0x00282b34, 0x002b2f38, 0x002d323c, 0x002f343f, 0x002c343c, 0x0029313b, 0x002c3440, 0x00313a48, 0x0034404d, 0x0034424f, 0x0032424f, 0x002c3b48, 0x00243441, 0x00243541, 0x00283b47, 0x002c404c, 0x002a3f4a, 0x00293d48, 0x00283b47, 0x00283b47, 0x00263844, 0x00233440, 0x001e2e3a, 0x0022303c, 0x0022303c, 0x00293841, 0x002b3843, 0x0023303b, 0x001c2b34, 0x001a2a34, 0x00202f38, 0x001e2d38, 0x0022313c, 0x0022313c, 0x001e2d38, 0x0024333e, 0x0023323d, 0x0016252f, 0x001c2b34, 0x001f2e38, 0x001f2d37, 0x001a2630, 0x001f2b34, 0x0018242c, 0x00202d38, 0x0025333d, 0x0022323c, 0x00273843, 0x002b3d48, 0x0020333d, 0x001c2d3a, 0x001a2b39, 0x001f303f, 0x00273948, 0x002e4150, 0x002c414f, 0x002d4251, 0x002c4050, 0x002d4251, 0x002f4453, 0x002d4151, 0x002c4050, 0x002b4250, 0x00294150, 0x002c4352, 0x00374c5b, 0x00364756, 0x0031414e, 0x00344450, 0x00364452, 0x00364351, 0x00374250, 0x0036404f, 0x0035404c, 0x00343e4b, 0x00333d4a, 0x00323c48, 0x00313b47, 0x00303944, 0x00303a44, 0x00333b45, 0x00343a45, 0x00333943, 0x00313841, 0x002f353f, 0x002e343d, 0x002d323c, 0x002d313c, 0x002c303b, 0x002e323c, 0x00313640, 0x00363a44, 0x00383d47, 0x00383f4a, 0x0039404b, 0x00373c48, 0x002d313c, 0x001d2028, 0x000e1117, 0x00090c11, 0x00090c12, 0x000a0d12, 0x000b0e14, 0x000c0e15, 0x000c0e15, 0x000b0d14, 0x00090c13, 0x00090b11, 0x0008090f, 0x0008080e, 0x0004060a, 0x00040508, 0x00040508, 0x00040508, 0x00040609, 0x00040609, 0x0006080c, 0x00080c11, 0x000c1319, 0x00101720, 0x00121b24, 0x00141d28, 0x00141f29, 0x0014202b, 0x0014222c, 0x0016242e, 0x00182630, 0x00192831, 0x001c2834, 0x001d2935, 0x001f2b38, 0x00202c3a, 0x00202d3c, 0x00202f3e, 0x00213040, 0x00223342, 0x00263748, 0x002a3c4c, 0x002c3f4f, 0x002c4051, 0x002d4153, 0x002c4152, 0x002b3f50, 0x00283d4c, 0x00273c48, 0x00263844, 0x0021303c, 0x0018212b, 0x00060c12, 0x00020509, 0x00000407, 0x00020406, 0x00020404, 0x00010204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010305, 0x00010305, 0x00010305, 0x00010304, 0x00010304, 0x00010305, 0x00010305, 0x00010305, 0x00010305, 0x00010305, 0x00030406, 0x00030406, 0x00030506, 0x00040608, 0x0005080b, 0x000b1822, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00020204, 0x00020202, 0x00020202, 0x00010102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000304, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010406, 0x0004080c, 0x00101920, 0x00212f38, 0x00263742, 0x00283845, 0x00273a47, 0x00283a49, 0x00283b4b, 0x00283a48, 0x00263947, 0x00253846, 0x00253444, 0x00243342, 0x0022303f, 0x00202d3b, 0x001d2a38, 0x001c2834, 0x00192531, 0x0018232f, 0x0018212d, 0x0016202c, 0x00151f2a, 0x00141e29, 0x00141d28, 0x00131b24, 0x00101821, 0x000f161e, 0x000d141b, 0x000b1018, 0x000a1018, 0x000a0e16, 0x00090d14, 0x00090c11, 0x00090b10, 0x00090b0e, 0x0007080a, 0x00040507, 0x00030405, 0x00030406, 0x00030506, 0x00040504, 0x00040505, 0x00040607, 0x00050708, 0x0006080a, 0x0006080b, 0x0007080c, 0x0007080c, 0x0007080c, 0x0007080d, 0x00070a0d, 0x00070a0d, 0x0004080c, 0x0003080c, 0x0005080c, 0x000c0d11, 0x0013151a, 0x001c1f24, 0x0024272e, 0x00282b34, 0x00292d37, 0x002b313a, 0x002b3139, 0x002c313a, 0x002b313c, 0x002d3542, 0x00313b48, 0x00313e49, 0x0033424d, 0x002c3c48, 0x00243441, 0x00213340, 0x00283b47, 0x002e434e, 0x002f434f, 0x002b3e4a, 0x00283c48, 0x00243844, 0x00243642, 0x00263844, 0x0020303c, 0x0022313d, 0x0024323e, 0x00273440, 0x00283642, 0x0023313c, 0x0020303a, 0x001e2d38, 0x0023323d, 0x0024333f, 0x0021313e, 0x0020303c, 0x001c2c38, 0x0021313d, 0x0024343e, 0x001a2934, 0x001c2c35, 0x0026363f, 0x00203039, 0x001e2b34, 0x00212d38, 0x0019252e, 0x00202d38, 0x002a3843, 0x001c2c37, 0x00253641, 0x002c404a, 0x00233540, 0x00213340, 0x001f303e, 0x001f303e, 0x00283a48, 0x00304452, 0x00304452, 0x00314554, 0x00324756, 0x00304655, 0x00344958, 0x00304755, 0x002c4251, 0x002e4654, 0x002c4453, 0x00304755, 0x00344857, 0x00344453, 0x0034424f, 0x0034424e, 0x0034404f, 0x0035404e, 0x00373f4e, 0x00363f4c, 0x00343e4b, 0x00333d49, 0x00333d49, 0x00323c48, 0x00333c47, 0x00333b46, 0x00333b46, 0x00333b46, 0x00343945, 0x00323844, 0x00303640, 0x002e343e, 0x002c333c, 0x002d323a, 0x002c313c, 0x002c313c, 0x0030353f, 0x00343842, 0x00383c46, 0x0039404a, 0x0039414c, 0x0038404a, 0x00303641, 0x0020242e, 0x0010141c, 0x000a0c12, 0x00090c11, 0x00090c11, 0x00090c11, 0x000a0d14, 0x000c0e14, 0x000c0e14, 0x000a0c14, 0x00090c13, 0x00080a10, 0x0007080d, 0x0005070c, 0x00040509, 0x00030408, 0x00030408, 0x00040508, 0x00040609, 0x0004070a, 0x0007090d, 0x000a0e13, 0x000e141b, 0x00111820, 0x00121b25, 0x00141e28, 0x00151f2a, 0x0014202b, 0x0014222c, 0x0016242e, 0x00172630, 0x00192831, 0x001c2834, 0x001d2935, 0x001f2b38, 0x00202c3a, 0x00202d3c, 0x00212f3e, 0x0021303f, 0x00223241, 0x00263645, 0x002a3a4b, 0x002c3d4d, 0x002c4051, 0x002c4052, 0x002c4052, 0x002a3e4e, 0x00293c4b, 0x00283a48, 0x00253643, 0x001f2c38, 0x00121b24, 0x00040910, 0x00010408, 0x00000408, 0x00020406, 0x00020404, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020304, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020404, 0x00020404, 0x00020404, 0x00030406, 0x000b1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x00121f27, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010101, 0x00010102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000304, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020407, 0x0004080c, 0x00111a21, 0x0022303a, 0x00273743, 0x00263844, 0x00263947, 0x00283a49, 0x00283b4a, 0x00283a48, 0x00263947, 0x00253845, 0x00243444, 0x00243342, 0x0021303f, 0x001d2c3c, 0x001c2938, 0x001a2834, 0x00182532, 0x0018232f, 0x0018212d, 0x0016202c, 0x00152029, 0x00141e29, 0x00141c28, 0x00121b24, 0x00101821, 0x000e151e, 0x000c131a, 0x000b1118, 0x00091018, 0x00080e16, 0x00080c14, 0x00080b11, 0x00080b10, 0x00090b0e, 0x0008090b, 0x00040608, 0x00040507, 0x00040507, 0x00030406, 0x00030405, 0x00030506, 0x00040607, 0x00050708, 0x00060809, 0x00060809, 0x0006080a, 0x0007080c, 0x0007080c, 0x0007080c, 0x00070a0d, 0x00070a0d, 0x0005080c, 0x0004070b, 0x0004060a, 0x0008090c, 0x000f1015, 0x00181a20, 0x0020232a, 0x00252830, 0x00282b33, 0x00292f36, 0x002c3138, 0x002c3139, 0x002b303b, 0x002c333d, 0x002d3641, 0x002e3843, 0x00313e49, 0x002d3c48, 0x002a3946, 0x002a3a48, 0x00293c48, 0x002e414d, 0x0030424f, 0x002c3e4a, 0x00273944, 0x00203440, 0x0020323e, 0x00223340, 0x00202f3c, 0x0022313e, 0x0022313e, 0x0022313c, 0x0025343f, 0x0022323c, 0x0020313c, 0x001e303a, 0x0021333d, 0x00263742, 0x00253743, 0x00243542, 0x001d2e3b, 0x001f303c, 0x001f303d, 0x001d2e39, 0x001e303a, 0x00243540, 0x0022313c, 0x0022303a, 0x00202e38, 0x001c2a34, 0x0022303b, 0x002b3b46, 0x001c2c37, 0x00243440, 0x00253842, 0x0020343e, 0x00273846, 0x00283948, 0x00263745, 0x002c3f4c, 0x00334755, 0x00354a58, 0x00334857, 0x00344a59, 0x002f4655, 0x00304856, 0x002e4655, 0x002d4453, 0x002e4654, 0x002f4755, 0x00344a59, 0x00344756, 0x00344452, 0x0034434f, 0x0036424e, 0x0035404e, 0x00373f4e, 0x00383f4d, 0x00353e4b, 0x00343d48, 0x00303c47, 0x00313c48, 0x00333d48, 0x00343c48, 0x00343c47, 0x00333b46, 0x00333a45, 0x00333843, 0x00323642, 0x0030343f, 0x002e343e, 0x002f343e, 0x002f343c, 0x002f343c, 0x0030343e, 0x00313640, 0x00353944, 0x00383d47, 0x003b414b, 0x003b414c, 0x00343b46, 0x00232a34, 0x00101620, 0x000b0d15, 0x000a0c12, 0x00090c11, 0x00090c11, 0x00090c11, 0x000a0d12, 0x000c0f13, 0x000b0d13, 0x00090c13, 0x00080b12, 0x00080910, 0x0005070c, 0x00040509, 0x00040508, 0x00040508, 0x00040508, 0x00040509, 0x00040609, 0x0005070a, 0x00080a0d, 0x000b0f14, 0x000f151c, 0x00121821, 0x00131b25, 0x00141e29, 0x0015202a, 0x0014202b, 0x0016212c, 0x0017242e, 0x00182630, 0x001a2831, 0x001c2834, 0x001d2935, 0x001f2b38, 0x00202c3a, 0x00202d3b, 0x00202f3d, 0x00202f3f, 0x00223240, 0x00263445, 0x00283848, 0x002b3c4c, 0x002c404f, 0x002c4050, 0x002a3f50, 0x00293c4c, 0x00293c4a, 0x00263945, 0x00233440, 0x001c2833, 0x000c141c, 0x0004070e, 0x00010408, 0x00010408, 0x00020306, 0x00020404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010101, 0x00010102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000304, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010407, 0x0004060c, 0x00101920, 0x0021303a, 0x00263744, 0x00253845, 0x00263948, 0x00263a4a, 0x00253b4c, 0x00263a4b, 0x00273848, 0x00263646, 0x00253444, 0x00233243, 0x00212f40, 0x001d2c3b, 0x001b2838, 0x001a2834, 0x00182533, 0x00182330, 0x0018212d, 0x0017202b, 0x00152028, 0x00141e28, 0x00131c27, 0x00121b24, 0x00101821, 0x000e161e, 0x000c131a, 0x000b1219, 0x00091018, 0x00080f17, 0x00090e15, 0x000a0d14, 0x00090c12, 0x00090c0f, 0x0008090b, 0x00040608, 0x00040608, 0x00040608, 0x00030406, 0x00030405, 0x00030406, 0x00040508, 0x00040708, 0x00060809, 0x00060809, 0x0006080a, 0x0007080c, 0x0007080c, 0x0007080c, 0x00070a0d, 0x0006090c, 0x0005080c, 0x0004070a, 0x00040609, 0x0005070a, 0x000c0c12, 0x0013161b, 0x001b1e25, 0x00202329, 0x0024272d, 0x00262b31, 0x002b2f35, 0x002c3038, 0x002a3039, 0x002a313b, 0x002c343e, 0x002d3640, 0x002f3944, 0x002d3946, 0x002d3a48, 0x002f3c49, 0x002c3b48, 0x002c3c49, 0x0030404d, 0x002e3d4a, 0x00283744, 0x0022333f, 0x0021323e, 0x0022313e, 0x0022313f, 0x00233240, 0x0023323f, 0x0024343f, 0x0024343f, 0x00243440, 0x00263742, 0x0024343f, 0x0024343f, 0x00253642, 0x00253744, 0x00283948, 0x00283847, 0x00233442, 0x0020313f, 0x0021323f, 0x00243540, 0x00283844, 0x00253540, 0x0025333e, 0x0023313b, 0x00212f39, 0x001d2b36, 0x00263540, 0x0023343f, 0x0021333e, 0x00233540, 0x00243842, 0x002c3c4a, 0x0030404f, 0x002e404e, 0x002f404f, 0x00344855, 0x00344856, 0x00354a59, 0x00344b5a, 0x00304756, 0x002e4454, 0x002c4352, 0x002e4352, 0x002f4352, 0x00324655, 0x00344958, 0x00344656, 0x00344351, 0x0035424f, 0x0037414e, 0x0038404e, 0x00383f4e, 0x00383f4c, 0x00363e4a, 0x00333d48, 0x00313c46, 0x00323c47, 0x00333c48, 0x00343c47, 0x00343b46, 0x00333944, 0x00313841, 0x00313540, 0x0030343f, 0x0030343e, 0x0030343f, 0x00313540, 0x00313540, 0x0031363f, 0x00333841, 0x00343944, 0x00373c46, 0x003a3f48, 0x003b404a, 0x00353b44, 0x00282f38, 0x00141b24, 0x00090d17, 0x000a0c14, 0x000b0c12, 0x000a0c11, 0x00090c11, 0x00090c11, 0x000a0d12, 0x000a0d12, 0x00080c11, 0x00070a10, 0x00060910, 0x0006080f, 0x0005070c, 0x00040509, 0x00040609, 0x00040508, 0x00040508, 0x00040508, 0x00040609, 0x0006080b, 0x00090b10, 0x000c1014, 0x000f151c, 0x00121821, 0x00121b25, 0x00141e28, 0x0015202a, 0x0014202b, 0x0016212c, 0x0018242e, 0x00182630, 0x001a2832, 0x001c2834, 0x001d2836, 0x001f2b38, 0x00202c3a, 0x00202d3c, 0x00202f3e, 0x0020303f, 0x00233140, 0x00253444, 0x00283647, 0x0029394a, 0x002b3d4d, 0x002b3e4e, 0x00293d4d, 0x00283c4c, 0x00283b49, 0x00253844, 0x0021323e, 0x0019242f, 0x00091019, 0x0003050c, 0x00020408, 0x00030307, 0x00030306, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010101, 0x00010101, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00020408, 0x0003060c, 0x00101720, 0x00212d39, 0x00263643, 0x00253845, 0x00253948, 0x00253a4a, 0x00243b4c, 0x00243a4c, 0x00263748, 0x00253546, 0x00243444, 0x00233142, 0x00202e3f, 0x001d2b3a, 0x001b2838, 0x001b2734, 0x00182432, 0x00182330, 0x0018222d, 0x0016202a, 0x00152028, 0x00141e26, 0x00131c25, 0x00101b24, 0x00101922, 0x000d161d, 0x000c141b, 0x000c121a, 0x000b1018, 0x000a1018, 0x000b0f16, 0x000c0e15, 0x000b0d14, 0x000a0c11, 0x0008090d, 0x0005070a, 0x00040508, 0x00030508, 0x00030408, 0x00030408, 0x00030508, 0x00040608, 0x00040608, 0x00050709, 0x0005070a, 0x0005070a, 0x0006080b, 0x0006080b, 0x0006080b, 0x0006080c, 0x0006080b, 0x0004080b, 0x0004070a, 0x00040709, 0x0005070a, 0x00080a0f, 0x000d1015, 0x0016181f, 0x001b1d24, 0x001e2128, 0x0023262c, 0x00282c32, 0x002b2e35, 0x002a3038, 0x002a303a, 0x002b323c, 0x002c343f, 0x002d3741, 0x002c3743, 0x002c3643, 0x002e3744, 0x002d3744, 0x002c3844, 0x002f3a47, 0x002a3743, 0x00273541, 0x00253540, 0x0024343f, 0x00283743, 0x00273743, 0x00243440, 0x00243440, 0x0023323e, 0x0020303c, 0x0022313d, 0x00253540, 0x00253440, 0x00273642, 0x00253442, 0x00223343, 0x00243545, 0x00293c4a, 0x002f404f, 0x00293a49, 0x00283946, 0x00283945, 0x00293b47, 0x00273743, 0x00283641, 0x0026343e, 0x0024313c, 0x001d2c38, 0x00243440, 0x002a3a46, 0x00233440, 0x00283a47, 0x00314450, 0x00324452, 0x00304351, 0x00304251, 0x002e4250, 0x00324754, 0x00314654, 0x00324755, 0x00304654, 0x00304453, 0x002e4050, 0x002c3e4d, 0x002c3e4d, 0x00314251, 0x00354655, 0x00374757, 0x00354454, 0x00354251, 0x0036414e, 0x0038404e, 0x0038404e, 0x00383f4c, 0x00383f4c, 0x00363d4a, 0x00343d48, 0x00343c48, 0x00343c48, 0x00343c47, 0x00343a46, 0x00343a44, 0x00313840, 0x0030363f, 0x0030353e, 0x0030343f, 0x00303440, 0x00303440, 0x00313440, 0x00323740, 0x00333843, 0x00343b46, 0x00373d48, 0x00393f4b, 0x003a404b, 0x00373b45, 0x002c3038, 0x001c2028, 0x000c1017, 0x00080b12, 0x000a0c12, 0x000b0c11, 0x000b0c11, 0x00090c11, 0x00090c11, 0x00090c11, 0x00090c10, 0x00080a10, 0x0007090f, 0x0006080e, 0x0005070c, 0x0004060a, 0x00040609, 0x00040608, 0x00040608, 0x00030408, 0x0003040a, 0x0004050b, 0x0006080e, 0x000b0c14, 0x000c1018, 0x0010161e, 0x00121822, 0x00111a24, 0x00141d28, 0x00141e29, 0x0014202a, 0x0016212c, 0x0017242e, 0x00182530, 0x001a2831, 0x001b2834, 0x001c2836, 0x001e2938, 0x001f2b3a, 0x00202c3c, 0x00202e3d, 0x0020303f, 0x00233140, 0x00243444, 0x00273546, 0x00283848, 0x002b3b4c, 0x002a3c4c, 0x00283c4c, 0x00273c4b, 0x00273c48, 0x00243843, 0x0020303b, 0x0016202a, 0x00060c13, 0x00030408, 0x00020306, 0x00030304, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000104, 0x00000204, 0x00000204, 0x00000204, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010101, 0x00010101, 0x00010102, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020205, 0x00020408, 0x0002060b, 0x000f151f, 0x00202c38, 0x00243441, 0x00253544, 0x00263847, 0x00263a49, 0x00243a4b, 0x0024394a, 0x00263747, 0x00253545, 0x00253444, 0x00233040, 0x00202d3c, 0x001d2a38, 0x001b2835, 0x001a2634, 0x00182331, 0x00182230, 0x0018222d, 0x0016202b, 0x00152028, 0x00141d26, 0x00111c24, 0x00101a24, 0x000f1922, 0x000d161d, 0x000c141b, 0x000d131b, 0x000c1119, 0x000b1018, 0x000b0f17, 0x000c0e15, 0x000a0d14, 0x000a0c12, 0x0008090f, 0x0004060b, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00040508, 0x00040608, 0x00040608, 0x00040709, 0x0004070a, 0x0004070a, 0x0004070a, 0x0005070a, 0x0005070a, 0x0005070a, 0x0005070a, 0x0004080a, 0x0003070a, 0x0004070a, 0x00050708, 0x0006080b, 0x00090c10, 0x00101317, 0x0015181f, 0x001a1d24, 0x0020232a, 0x00252830, 0x002a2d34, 0x002c2f38, 0x002b303a, 0x002b323c, 0x002c343f, 0x002c3640, 0x002e3641, 0x002e343f, 0x002e333e, 0x002e3440, 0x002d3541, 0x00303844, 0x002c3744, 0x002b3844, 0x002a3842, 0x00283640, 0x002b3945, 0x002b3a47, 0x00283945, 0x00253642, 0x0022313e, 0x00202e3c, 0x0022303c, 0x0026343f, 0x00273440, 0x00283642, 0x00283644, 0x00263645, 0x00253746, 0x00263947, 0x002f4250, 0x00314452, 0x002e414e, 0x00293c48, 0x00243844, 0x00253542, 0x002a3844, 0x0026343e, 0x0024313d, 0x0021303c, 0x0024333f, 0x002a3947, 0x00283846, 0x002d404d, 0x00304451, 0x00324654, 0x00324655, 0x00314454, 0x002f4250, 0x00304452, 0x00314553, 0x00314553, 0x00304450, 0x00324450, 0x0030404c, 0x002e3d4c, 0x002f3e4d, 0x00344451, 0x00364553, 0x00374654, 0x00364452, 0x00374250, 0x0037414e, 0x0038404d, 0x00383f4c, 0x00373e4b, 0x00363e4b, 0x00353d48, 0x00343c48, 0x00343c48, 0x00343c48, 0x00343a46, 0x00323844, 0x00303841, 0x002f353e, 0x002e343c, 0x0030363e, 0x0031363f, 0x00303540, 0x00303540, 0x00313740, 0x00323841, 0x00333a45, 0x00363d48, 0x0038404b, 0x0039414c, 0x00383e49, 0x002f323c, 0x0020242b, 0x0010131a, 0x00080b10, 0x00080a10, 0x000a0c10, 0x000b0c11, 0x000b0c11, 0x00090c10, 0x00090c10, 0x00090b10, 0x00090a10, 0x0008090f, 0x0008090f, 0x0007080d, 0x0004060a, 0x00040508, 0x00040508, 0x00040608, 0x00040708, 0x00030409, 0x0003040b, 0x0004050c, 0x00080911, 0x000c0d17, 0x000e131a, 0x0010171f, 0x00121923, 0x00101a24, 0x00131c27, 0x00141e29, 0x0015202a, 0x0015202b, 0x0015232c, 0x0018252f, 0x00192731, 0x001a2833, 0x001b2835, 0x001d2838, 0x001f2b3a, 0x00202c3c, 0x00212d3c, 0x00202f3e, 0x00223140, 0x00233242, 0x00253445, 0x00283747, 0x00283949, 0x00283a4a, 0x00263a4a, 0x00263b49, 0x00243b48, 0x00243741, 0x001f2d38, 0x00131c25, 0x0004080e, 0x00030305, 0x00030303, 0x00020203, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010101, 0x00010101, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00010103, 0x00010103, 0x00020204, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020205, 0x00020408, 0x0001050b, 0x000e151f, 0x00202a38, 0x00243341, 0x00263544, 0x00273845, 0x00263948, 0x00253848, 0x00253948, 0x00263745, 0x00243544, 0x00243241, 0x00212f3d, 0x001f2c39, 0x001c2937, 0x001a2835, 0x00192533, 0x00182331, 0x00182230, 0x0018212c, 0x0016202b, 0x00151f2a, 0x00141e28, 0x00131c25, 0x00111a24, 0x00101922, 0x000f1720, 0x000c141c, 0x000e131c, 0x000c111b, 0x000b1019, 0x000b0f18, 0x000a0e16, 0x000a0d14, 0x000a0c12, 0x00080a10, 0x0005070c, 0x00040509, 0x00040509, 0x00030508, 0x00030508, 0x00040508, 0x00040608, 0x00040608, 0x00040708, 0x00040709, 0x0004070a, 0x00040609, 0x0004070a, 0x0005070a, 0x0004070a, 0x0005070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x00040608, 0x00040608, 0x0007090c, 0x000c0f12, 0x0011141a, 0x00161920, 0x001c2026, 0x0022252c, 0x00282b32, 0x002b2e37, 0x002b3039, 0x002b313b, 0x002c343e, 0x002c343f, 0x002e3440, 0x002f343e, 0x002f333d, 0x002f343f, 0x002f3440, 0x00313844, 0x00303844, 0x002e3844, 0x002c3843, 0x002c3842, 0x002e3b48, 0x00303d4b, 0x002d3c49, 0x002b3b47, 0x00293845, 0x00293644, 0x002a3844, 0x002c3944, 0x002b3844, 0x002c3945, 0x002c3948, 0x002c3c4b, 0x002d404e, 0x00304452, 0x002d414f, 0x002d404d, 0x002c3f4c, 0x002c3f4b, 0x00223441, 0x00223340, 0x00253440, 0x0024323c, 0x0024333e, 0x00253440, 0x0024323f, 0x00263442, 0x002f3e4c, 0x00324351, 0x002c404d, 0x002d4250, 0x00354958, 0x00354858, 0x002f4250, 0x002c414f, 0x00314553, 0x00334554, 0x00324450, 0x00344451, 0x00344350, 0x00344250, 0x00344251, 0x00354351, 0x00364451, 0x00374552, 0x00364451, 0x0037434f, 0x0038414e, 0x0038404d, 0x00383f4c, 0x00373e4b, 0x00363e49, 0x00343c48, 0x00343c48, 0x00343c48, 0x00343c46, 0x00323944, 0x00303742, 0x002f353f, 0x002e343d, 0x002e343c, 0x0030373f, 0x0031383f, 0x00313840, 0x00313840, 0x00313841, 0x00323842, 0x00343c47, 0x00373f49, 0x0038404a, 0x00363e49, 0x002f3440, 0x0021242e, 0x0011141b, 0x00080c12, 0x0007090f, 0x00080a0e, 0x000a0c10, 0x000a0c10, 0x000b0c11, 0x000a0c10, 0x00090c10, 0x00090a10, 0x0008090f, 0x0008090e, 0x0007080d, 0x0005070c, 0x0004060a, 0x00030508, 0x00040508, 0x00040608, 0x00040608, 0x00030409, 0x0003040a, 0x0006070d, 0x000b0c13, 0x000f1018, 0x0010151c, 0x00121820, 0x00131923, 0x00101a24, 0x00131c27, 0x00141e29, 0x00141e29, 0x0014202a, 0x0014212b, 0x0016242e, 0x00192731, 0x001b2833, 0x001c2834, 0x001d2837, 0x001f2b39, 0x00202c3b, 0x00212c3c, 0x00202e3d, 0x0021303f, 0x00233142, 0x00243444, 0x00263546, 0x00273747, 0x00253848, 0x00263949, 0x00243948, 0x00243845, 0x00233440, 0x001c2934, 0x000e171e, 0x0003070b, 0x00020404, 0x00020303, 0x00010303, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00010103, 0x00010103, 0x00020204, 0x00000304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020205, 0x00020408, 0x0002050b, 0x000e151e, 0x00202a37, 0x00243240, 0x00263544, 0x00263846, 0x00263847, 0x00243848, 0x00253948, 0x00263745, 0x00243444, 0x00233040, 0x00202d3c, 0x001d2b38, 0x001c2936, 0x001a2734, 0x00182433, 0x00182331, 0x00182230, 0x0017212c, 0x0016202b, 0x00151f2a, 0x00151e29, 0x00141c26, 0x00131b24, 0x00111923, 0x00101820, 0x000d151e, 0x000e131d, 0x000d111c, 0x000b101a, 0x000b1018, 0x00090e17, 0x00080c15, 0x00090c13, 0x00080b11, 0x0007080e, 0x0005070c, 0x0004060b, 0x00040609, 0x00040609, 0x00040609, 0x00040609, 0x00040608, 0x00040708, 0x00040708, 0x00040609, 0x00040609, 0x0004070a, 0x0004070a, 0x0004070a, 0x0005070a, 0x0005080b, 0x0006080b, 0x0006080b, 0x00050708, 0x00040608, 0x0006080a, 0x000a0b10, 0x000e1016, 0x0014161d, 0x00191c23, 0x001f2128, 0x0024272e, 0x00282c33, 0x002b3037, 0x002b3139, 0x002c333c, 0x002d343d, 0x002f343d, 0x0030343e, 0x0030343e, 0x00303440, 0x00303541, 0x00313843, 0x00303843, 0x002e3842, 0x002d3841, 0x002c3841, 0x002e3944, 0x002e3b48, 0x002e3b48, 0x002f3d49, 0x00313e4a, 0x00323f4c, 0x00323f4b, 0x00313f4a, 0x00303d49, 0x00303d49, 0x00303e4c, 0x00304150, 0x00344855, 0x00354a58, 0x00304452, 0x002c3e4c, 0x00273a48, 0x002c404c, 0x00223541, 0x00213340, 0x0022333f, 0x0021313c, 0x0024343f, 0x00273641, 0x00283643, 0x00283644, 0x002f3f4c, 0x00304150, 0x002b3f4c, 0x002b404c, 0x00324655, 0x00344655, 0x002d404e, 0x002a3e4c, 0x00314452, 0x00344553, 0x00344451, 0x00374553, 0x00384553, 0x00384451, 0x00374452, 0x00374451, 0x00374450, 0x00374451, 0x00374451, 0x0037434f, 0x0038414e, 0x0038404c, 0x00373f4c, 0x00373e4a, 0x00353d48, 0x00343c48, 0x00343c47, 0x00333b46, 0x00323a45, 0x00303742, 0x002f3541, 0x002f353f, 0x002f353f, 0x0030363e, 0x00313840, 0x00323940, 0x00323940, 0x00323941, 0x00333842, 0x00343943, 0x00343c47, 0x00353c47, 0x00333b46, 0x002c343f, 0x00232834, 0x00141620, 0x00080c11, 0x0006090e, 0x00070a0e, 0x00090b0e, 0x000b0c10, 0x000a0c10, 0x000b0c11, 0x000b0c11, 0x000a0b10, 0x0008090f, 0x0007080d, 0x0007080d, 0x0006080c, 0x0005070c, 0x00040609, 0x00040608, 0x00040508, 0x00030507, 0x00030508, 0x00030409, 0x0004040a, 0x0007080d, 0x000c0c13, 0x00101119, 0x0011151c, 0x00111820, 0x00121923, 0x00101924, 0x00121c26, 0x00141d28, 0x00141e29, 0x00141f29, 0x0014212b, 0x0017242d, 0x00192630, 0x001c2832, 0x001c2833, 0x001d2936, 0x001f2b38, 0x00202c3b, 0x00202c3c, 0x00202e3c, 0x00213040, 0x00233141, 0x00243343, 0x00243444, 0x00253545, 0x00253748, 0x00253848, 0x00243846, 0x00223643, 0x0021323d, 0x00192630, 0x000b1219, 0x0003050b, 0x00020405, 0x00010404, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00010103, 0x00010103, 0x00020204, 0x00000204, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00030304, 0x00030408, 0x0004060a, 0x000f141c, 0x00212b35, 0x00243340, 0x00253443, 0x00263745, 0x00263847, 0x00253848, 0x00253848, 0x00263846, 0x00243444, 0x00233140, 0x00202e3c, 0x001d2b38, 0x001b2836, 0x00192634, 0x00182431, 0x00182330, 0x0018222e, 0x0018212c, 0x0016202b, 0x00151f2a, 0x00151d28, 0x00141c26, 0x00131c24, 0x00121a24, 0x00101821, 0x000f161f, 0x000f141e, 0x000d121c, 0x000b101a, 0x000b1018, 0x00090e17, 0x00090c15, 0x00080c13, 0x00080b12, 0x00080910, 0x0006080c, 0x0004060b, 0x00040609, 0x00040609, 0x00040609, 0x00040609, 0x00040609, 0x00040708, 0x00040708, 0x00040609, 0x0004070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x0005070a, 0x0006080b, 0x0007080c, 0x0007080b, 0x00060809, 0x00060809, 0x00050708, 0x0007080c, 0x000b0c12, 0x00101218, 0x0015181f, 0x001b1d24, 0x0020232a, 0x0024282f, 0x00282c32, 0x002a3037, 0x002c313a, 0x002e343d, 0x002f343d, 0x0030343e, 0x0030343d, 0x0030343f, 0x002f3540, 0x002f3740, 0x00303841, 0x002f3841, 0x002d3840, 0x002d3840, 0x002d3842, 0x002d3843, 0x002e3844, 0x00303b47, 0x00333c48, 0x00343f4b, 0x0036404c, 0x0034404c, 0x0034404c, 0x0033404c, 0x0034404f, 0x00344352, 0x00384a58, 0x00384c59, 0x00374957, 0x00304150, 0x00273947, 0x002c404c, 0x00283a46, 0x00273945, 0x00243642, 0x0023343f, 0x00283844, 0x002c3c47, 0x002d3d49, 0x002d3c49, 0x002c3c4a, 0x002f404f, 0x002d404e, 0x002e404f, 0x00304250, 0x00324150, 0x002e3e4d, 0x002c3e4c, 0x00344453, 0x00374655, 0x00374554, 0x00384654, 0x003a4554, 0x00394453, 0x00384453, 0x00384452, 0x00384451, 0x00384451, 0x00384451, 0x0038424f, 0x0037404d, 0x0036404c, 0x00353e4a, 0x00363d49, 0x00353c48, 0x00343b46, 0x00323944, 0x00313843, 0x00303843, 0x00303641, 0x00303640, 0x002f353f, 0x00303640, 0x00303740, 0x00323841, 0x00333842, 0x00333842, 0x00343842, 0x00343843, 0x00343943, 0x00343944, 0x00323843, 0x002c323d, 0x00232833, 0x00171c25, 0x000b0e17, 0x0007090f, 0x00070a0f, 0x00070a0d, 0x00070a0d, 0x00090b10, 0x00090b10, 0x000a0b10, 0x00090b10, 0x00090a10, 0x0007080d, 0x0006080c, 0x0006080c, 0x0006080c, 0x0005070a, 0x00040608, 0x00040608, 0x00040608, 0x00030407, 0x00030408, 0x00030409, 0x0004040a, 0x0006080d, 0x000a0c13, 0x0010111a, 0x0010141c, 0x0010161e, 0x00101821, 0x00101824, 0x00121c26, 0x00141d28, 0x00141e29, 0x0015202a, 0x0017212c, 0x0018232e, 0x001b2630, 0x001c2831, 0x001c2832, 0x001d2935, 0x001f2b38, 0x00202c3a, 0x00202c3c, 0x00202f3e, 0x00223140, 0x00233341, 0x00233241, 0x00243341, 0x00243444, 0x00253647, 0x00243748, 0x00243645, 0x00213441, 0x001f2f39, 0x0017222b, 0x00060e14, 0x00020509, 0x00010405, 0x00000404, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010204, 0x00010204, 0x00000103, 0x00000103, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00030404, 0x00040506, 0x00040709, 0x000c1218, 0x001f2832, 0x0024323d, 0x00243441, 0x00263644, 0x00263745, 0x00253848, 0x00253848, 0x00253645, 0x00243443, 0x00223040, 0x00202e3c, 0x001d2a38, 0x001b2836, 0x00192634, 0x00182431, 0x0018232f, 0x0018222e, 0x0017212c, 0x0016202a, 0x00161e29, 0x00141d28, 0x00131c26, 0x00121a24, 0x00101823, 0x00101720, 0x000f151f, 0x000e141e, 0x000e121c, 0x000c1019, 0x000a0f18, 0x00090e16, 0x00090c14, 0x00090c12, 0x00080c11, 0x00080910, 0x0006080c, 0x0004060b, 0x00040608, 0x00040608, 0x00040608, 0x00040508, 0x00040608, 0x00040608, 0x00040608, 0x00040609, 0x0004070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x0005070a, 0x0006080b, 0x0007080c, 0x0006080b, 0x0004080a, 0x0004080a, 0x00040809, 0x0005080c, 0x00080a0e, 0x000c0e14, 0x0013151a, 0x00181a20, 0x001e2027, 0x0021242b, 0x0024282f, 0x00282c34, 0x002a3038, 0x002c323c, 0x002e343c, 0x002f343c, 0x002f343c, 0x002f353d, 0x002e353e, 0x002e363f, 0x002f3840, 0x002f3841, 0x002e3740, 0x002e3840, 0x002d3641, 0x002d3541, 0x002d3641, 0x002e3742, 0x002f3742, 0x00313945, 0x00343d49, 0x00343f4c, 0x0036404d, 0x0036414e, 0x0035414f, 0x00354351, 0x00394957, 0x003a4c58, 0x00374856, 0x00324451, 0x002c3c4b, 0x002f404d, 0x002e3f4c, 0x0030404d, 0x002b3c48, 0x00263744, 0x002c3c48, 0x0032404d, 0x0032404d, 0x0031404d, 0x00303f4c, 0x00334150, 0x00344452, 0x00354453, 0x00364553, 0x00374454, 0x00344250, 0x00344250, 0x00394855, 0x003c4957, 0x003a4755, 0x003a4755, 0x003a4655, 0x003a4654, 0x00394454, 0x00394451, 0x00384450, 0x00384450, 0x00384350, 0x0037414e, 0x0036404c, 0x00353e4a, 0x00343c48, 0x00353c47, 0x00343a45, 0x00323844, 0x00303841, 0x002f3840, 0x002f3740, 0x00303640, 0x00303640, 0x00303640, 0x00303741, 0x00313841, 0x00333844, 0x00343844, 0x00333743, 0x00323743, 0x00343844, 0x00343944, 0x00333741, 0x002e323c, 0x00242832, 0x00161a23, 0x000c1019, 0x00080c13, 0x00080b10, 0x00080b10, 0x00070a0e, 0x00070a0e, 0x00080a0e, 0x0008090e, 0x0008090e, 0x0008090d, 0x0006080c, 0x0006080c, 0x0006080b, 0x0006080b, 0x0005070a, 0x00040609, 0x00040608, 0x00040508, 0x00040508, 0x00030407, 0x00030407, 0x00030409, 0x0004050b, 0x0007080e, 0x000b0c13, 0x0010111a, 0x0010141e, 0x0010161f, 0x00111821, 0x00101a24, 0x00131c27, 0x00141d28, 0x00141e29, 0x0015202a, 0x0017212c, 0x0018232d, 0x001a2530, 0x001c2731, 0x001d2833, 0x001e2935, 0x001e2a37, 0x00202c39, 0x001f2c3b, 0x001f2f3d, 0x00213140, 0x00223240, 0x00233240, 0x00243341, 0x00243442, 0x00243544, 0x00243545, 0x00243444, 0x00213340, 0x001f2c37, 0x00121c24, 0x00040b11, 0x00020409, 0x00010406, 0x00000405, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00000002, 0x00000002, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010404, 0x00030405, 0x00040608, 0x000a0f15, 0x001c252f, 0x0023303c, 0x00253440, 0x00263543, 0x00273745, 0x00253847, 0x00253747, 0x00253644, 0x00233341, 0x0022303f, 0x00202c3c, 0x001c2a38, 0x001b2836, 0x00192634, 0x00182431, 0x0018232f, 0x0018222d, 0x0017212c, 0x0016202a, 0x00161e28, 0x00141c27, 0x00131b26, 0x00101824, 0x00101823, 0x000e1620, 0x000e141e, 0x000d141d, 0x000e121c, 0x000b1019, 0x000a0f17, 0x00090e16, 0x00090c14, 0x00090c10, 0x00080c0f, 0x00080a0d, 0x0007080a, 0x00040608, 0x00040507, 0x00030507, 0x00030507, 0x00030507, 0x00030507, 0x00040608, 0x00040608, 0x00040608, 0x0004070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x0005070a, 0x0006080b, 0x0006080b, 0x0004080b, 0x0003080b, 0x0003080b, 0x0004080b, 0x0007090d, 0x000a0c10, 0x00101217, 0x0016171c, 0x001c1d24, 0x00202228, 0x0022242c, 0x00242930, 0x00272c35, 0x00293039, 0x002c323a, 0x002d343b, 0x002f353c, 0x002f353c, 0x002d353c, 0x002d363e, 0x002e3640, 0x002f3840, 0x002f3840, 0x002f3840, 0x002f3740, 0x002f353f, 0x002e343e, 0x002e343f, 0x002e343e, 0x002f3540, 0x00313944, 0x00323c47, 0x00343e4b, 0x0036404c, 0x0037404f, 0x0035414f, 0x00374553, 0x00384956, 0x00374854, 0x00354654, 0x00344452, 0x00344453, 0x00344453, 0x00344452, 0x00314050, 0x0030404e, 0x00344453, 0x00394755, 0x00384453, 0x00384454, 0x00394654, 0x003a4754, 0x003a4754, 0x003b4754, 0x003b4654, 0x003b4656, 0x003a4554, 0x003a4654, 0x003c4a57, 0x003c4956, 0x003b4855, 0x003a4754, 0x003b4854, 0x003a4754, 0x003b4553, 0x003a444f, 0x0038424d, 0x0038424c, 0x0037404c, 0x0036404b, 0x00343d48, 0x00323c46, 0x00333b45, 0x00333944, 0x00323844, 0x00303844, 0x002f3841, 0x002e3740, 0x002f3640, 0x00303640, 0x00303742, 0x00303742, 0x00323843, 0x00323844, 0x00333844, 0x00333843, 0x00323642, 0x00323642, 0x00333743, 0x00333843, 0x002e313c, 0x00252830, 0x001a1d24, 0x000d1016, 0x00080c11, 0x00080b11, 0x00080b11, 0x00080b10, 0x00070a0f, 0x00070a0f, 0x00070a0d, 0x0006090c, 0x0006090c, 0x0006090c, 0x0004080b, 0x0005070a, 0x0005070a, 0x0005070a, 0x0004070a, 0x00040609, 0x00040609, 0x00030408, 0x00030408, 0x00030408, 0x00030407, 0x00040508, 0x0005070a, 0x00080a0f, 0x000c0f14, 0x000f1219, 0x0011151f, 0x00111620, 0x00121822, 0x00111a25, 0x00121c27, 0x00141d28, 0x00141e29, 0x0015202a, 0x0017212c, 0x0018222c, 0x001a242f, 0x001b2530, 0x001c2733, 0x001d2834, 0x001e2937, 0x001e2b38, 0x001d2c39, 0x001e2f3c, 0x0020303f, 0x00203340, 0x00223341, 0x00243442, 0x00243442, 0x00243442, 0x00243442, 0x00243442, 0x0021313e, 0x001e2a34, 0x000f1820, 0x0004080f, 0x00020409, 0x00020307, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00000002, 0x00000002, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020405, 0x00030406, 0x00070c12, 0x0019232c, 0x00232f3b, 0x0024323e, 0x00263441, 0x00273644, 0x00253745, 0x00253745, 0x00243544, 0x00223240, 0x00212f3e, 0x001f2c3a, 0x001c2938, 0x001c2836, 0x001a2634, 0x00182432, 0x00182330, 0x0018222e, 0x0016212c, 0x0015202b, 0x00141e29, 0x00141c27, 0x00131b26, 0x00111924, 0x00101822, 0x000e1620, 0x000e141e, 0x000d141d, 0x000e121c, 0x000b1019, 0x000a0f18, 0x00090e18, 0x00090c15, 0x00090c11, 0x00080c0f, 0x00080a0c, 0x00070809, 0x00040608, 0x00040507, 0x00030407, 0x00030407, 0x00030407, 0x00030507, 0x00040608, 0x00040608, 0x00040608, 0x0004070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x0005070a, 0x0005070a, 0x0006080b, 0x0006080b, 0x0004080b, 0x0003080b, 0x0003080b, 0x0004080b, 0x0006080c, 0x00080a0d, 0x000c0e12, 0x00121418, 0x00181a20, 0x001c1f24, 0x001f2228, 0x0022252c, 0x00242930, 0x00272c35, 0x00282f37, 0x002a3038, 0x002d343c, 0x002f353c, 0x002d353c, 0x002d353e, 0x002e3640, 0x002f3840, 0x002f3840, 0x002f3840, 0x002f3740, 0x002f353f, 0x002e343d, 0x002e343d, 0x002e343d, 0x002f353f, 0x002e3640, 0x002d3841, 0x00303945, 0x00323c48, 0x00343d4b, 0x00333f4c, 0x0034414e, 0x00354450, 0x00344450, 0x00344452, 0x00374554, 0x00384655, 0x00374554, 0x00384555, 0x00384655, 0x00384655, 0x003b4858, 0x003c4858, 0x00394654, 0x00394654, 0x003c4857, 0x003c4856, 0x003c4855, 0x003b4754, 0x003b4655, 0x003b4656, 0x003b4654, 0x003c4754, 0x003c4856, 0x003b4855, 0x003b4754, 0x003a4652, 0x003a4652, 0x00394551, 0x00384350, 0x0038414c, 0x0036404b, 0x0036404a, 0x00363f49, 0x00343c47, 0x00313a44, 0x00303942, 0x00303843, 0x00313844, 0x00313843, 0x00303743, 0x002e3740, 0x002e3640, 0x002f3640, 0x00303640, 0x00303742, 0x00323844, 0x00333944, 0x00333944, 0x00343944, 0x00343844, 0x00323742, 0x00313541, 0x00303440, 0x002c303c, 0x00242630, 0x00191c23, 0x000f1217, 0x00080b10, 0x00070a10, 0x00080b11, 0x00080b11, 0x00080b10, 0x00070a0f, 0x00070a0f, 0x00070a0d, 0x0006090c, 0x0006090c, 0x0006090c, 0x0004080b, 0x0005070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x00040609, 0x00040609, 0x00030408, 0x00030408, 0x00030408, 0x00030407, 0x00030508, 0x0006080b, 0x00090c10, 0x000c1015, 0x000e1319, 0x0010151e, 0x00121720, 0x00121822, 0x00111a25, 0x00121c26, 0x00141d28, 0x00141e29, 0x0015202a, 0x0017212c, 0x0018222c, 0x0019232e, 0x001a242f, 0x001b2530, 0x001c2832, 0x001d2935, 0x001e2a38, 0x001d2c39, 0x001e2e3c, 0x0020303f, 0x00203340, 0x00233341, 0x00243342, 0x00243342, 0x00243342, 0x00243342, 0x00243340, 0x0021303c, 0x001c2630, 0x000d141d, 0x0003070e, 0x00030409, 0x00010306, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020405, 0x00030407, 0x00060c11, 0x0018222c, 0x00232f3a, 0x0024313d, 0x00253440, 0x00263542, 0x00253644, 0x00253644, 0x00233443, 0x00223040, 0x00202d3d, 0x001e2b3a, 0x001c2937, 0x001c2836, 0x001a2634, 0x00182432, 0x00182330, 0x0017222f, 0x0015202c, 0x00141f2b, 0x00141d28, 0x00131c27, 0x00131b26, 0x00111a23, 0x00101821, 0x00101620, 0x000f151f, 0x000e141e, 0x000e131c, 0x000c101a, 0x000a0e18, 0x00090d18, 0x00080c16, 0x00080c12, 0x00080c10, 0x00070a0e, 0x0005080b, 0x00030609, 0x00030508, 0x00030408, 0x00030407, 0x00030407, 0x00030507, 0x00040608, 0x00040608, 0x00040608, 0x0004070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x0005070a, 0x0006080b, 0x0006080b, 0x0006080b, 0x0004080b, 0x0003080b, 0x0003080b, 0x0004080b, 0x0005080b, 0x0007080a, 0x000b0c0f, 0x00101114, 0x0015171a, 0x00191c1f, 0x001d1f24, 0x00202228, 0x0022262c, 0x00252931, 0x00272c34, 0x00282d35, 0x002c3038, 0x002e333b, 0x002e343c, 0x002f353e, 0x002f353f, 0x002e3640, 0x002e3740, 0x002f3840, 0x002f3740, 0x002e343e, 0x002c333c, 0x002d343c, 0x002e343d, 0x002e353e, 0x002d353e, 0x002c363e, 0x002d3841, 0x002f3842, 0x00303944, 0x002f3b45, 0x00313e48, 0x0034404c, 0x0033404b, 0x0034414d, 0x00374450, 0x00384551, 0x00384552, 0x00384552, 0x00394654, 0x003a4754, 0x003c4855, 0x003b4654, 0x003a4453, 0x003a4554, 0x003c4856, 0x003b4855, 0x00394654, 0x00384654, 0x003a4554, 0x003c4555, 0x003c4554, 0x003c4654, 0x003a4654, 0x00384452, 0x00384350, 0x0036414e, 0x0037414e, 0x0037414e, 0x0037404c, 0x00363e48, 0x00343d48, 0x00343d48, 0x00343c47, 0x00323944, 0x00303840, 0x00303840, 0x00303740, 0x00303640, 0x00303640, 0x00303640, 0x002f353f, 0x002f3640, 0x00303640, 0x00303740, 0x00303742, 0x00323844, 0x00333944, 0x00343945, 0x00343944, 0x00343943, 0x00323640, 0x002e333c, 0x00292e38, 0x0022252f, 0x00181b22, 0x000e1117, 0x00080c10, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00080b10, 0x00080b0f, 0x00070a0d, 0x0006090c, 0x0006090c, 0x0006090c, 0x0004080b, 0x0004080a, 0x00040709, 0x00040609, 0x00040609, 0x00040508, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00030407, 0x00040508, 0x0006080c, 0x00080c10, 0x000b1015, 0x000e1319, 0x0010151d, 0x0012171f, 0x00121820, 0x00131a24, 0x00131c24, 0x00141d27, 0x00151f2a, 0x0016202b, 0x0018212c, 0x0019232d, 0x001a242f, 0x001a242f, 0x001b2530, 0x001c2732, 0x001d2935, 0x001e2a38, 0x001d2c39, 0x001f2e3b, 0x0020303e, 0x0021323f, 0x0023313f, 0x0024313f, 0x0024313f, 0x0024313f, 0x0024313f, 0x0024313f, 0x00202d38, 0x001a222c, 0x000b0f18, 0x0003050c, 0x00020308, 0x00000205, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00030405, 0x00030508, 0x00070b10, 0x00182129, 0x00232f3a, 0x0024313e, 0x00253440, 0x00263543, 0x00253644, 0x00243544, 0x00223341, 0x00213040, 0x00202d3c, 0x001e2b39, 0x001d2837, 0x001c2835, 0x001a2634, 0x00182432, 0x00182330, 0x0016212f, 0x0014202c, 0x00141e2a, 0x00141d28, 0x00121c26, 0x00131b26, 0x00121b24, 0x00101821, 0x00101720, 0x000f151f, 0x000e141e, 0x000e131d, 0x000c101a, 0x000b0f18, 0x00090d17, 0x00090c14, 0x00090c12, 0x00080c10, 0x00070a0e, 0x0005080c, 0x00030709, 0x00030508, 0x00030408, 0x00030408, 0x00030407, 0x00030507, 0x00040608, 0x00040608, 0x00040608, 0x0004070a, 0x0004070a, 0x0004070a, 0x0005070a, 0x0005070a, 0x0006080b, 0x0006080b, 0x0006080b, 0x0004080b, 0x0003080b, 0x0003080b, 0x0004080b, 0x0005080b, 0x00060809, 0x00090b0c, 0x000d0f12, 0x00121417, 0x0017181c, 0x001a1c1f, 0x001d1f24, 0x00202328, 0x0023262d, 0x00242930, 0x00262b33, 0x00282e36, 0x002b3038, 0x002c323a, 0x002c333b, 0x002c333c, 0x002c343c, 0x002c343e, 0x002d353e, 0x002e353e, 0x002d343d, 0x002c323c, 0x002c333c, 0x002e343d, 0x002e343e, 0x002d353d, 0x002c363c, 0x002c3740, 0x002e3841, 0x002f3843, 0x002f3944, 0x00303a44, 0x00303c47, 0x00303c47, 0x00323e48, 0x0034404c, 0x0037434f, 0x0037434f, 0x0038434f, 0x00384450, 0x00384451, 0x00384452, 0x00384452, 0x00384351, 0x00394353, 0x003a4452, 0x00384451, 0x00364350, 0x00364350, 0x00384351, 0x00394352, 0x00384250, 0x00384250, 0x00374250, 0x0035414e, 0x00343f4c, 0x00343d49, 0x00343c48, 0x00343c49, 0x00343c48, 0x00343c46, 0x00323b45, 0x00313b46, 0x00313a44, 0x00313843, 0x0030363f, 0x0030363f, 0x0030363f, 0x00303640, 0x00303640, 0x002f3540, 0x002f353f, 0x002f353f, 0x00303640, 0x00303740, 0x00303742, 0x00313843, 0x00323844, 0x00333944, 0x00333843, 0x0031343f, 0x002d3039, 0x00272b33, 0x0020242c, 0x00181c24, 0x00101319, 0x00080c11, 0x00070a0f, 0x00070a0f, 0x00080b10, 0x00080b10, 0x00070a0f, 0x00070a0f, 0x00080b10, 0x00080b0f, 0x00070a0d, 0x0006090c, 0x0006090c, 0x0006090c, 0x0004080b, 0x0003070a, 0x00040608, 0x00040609, 0x00040609, 0x00030508, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x0004050a, 0x0008080f, 0x000b0e14, 0x000c1018, 0x000f131c, 0x0010151d, 0x0011171f, 0x00121820, 0x00131a24, 0x00141c25, 0x00141d27, 0x00151f2a, 0x0016202b, 0x0018212c, 0x0019232d, 0x001a242f, 0x001a2430, 0x001a2531, 0x001b2833, 0x001c2835, 0x001c2a38, 0x001d2c39, 0x001f2e3b, 0x0020303d, 0x0021323f, 0x0023313f, 0x0024313f, 0x0024313f, 0x0024313f, 0x0024313f, 0x0023313e, 0x001e2c38, 0x00161f28, 0x00080c14, 0x00030409, 0x00020308, 0x00010305, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00010204, 0x00010204, 0x00010204, 0x00010203, 0x00010103, 0x00010203, 0x00010203, 0x00010203, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020404, 0x00020404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00030406, 0x00030507, 0x00060a0e, 0x00182026, 0x00233039, 0x00233240, 0x00233442, 0x00243444, 0x00243544, 0x00243443, 0x00223240, 0x0021303f, 0x00202d3c, 0x001f2b39, 0x001d2837, 0x001c2735, 0x00192533, 0x00182331, 0x00182230, 0x0017202e, 0x0015202c, 0x00141e2a, 0x00131c28, 0x00121c26, 0x00121a25, 0x00121a24, 0x00111822, 0x00101720, 0x000f151f, 0x000e141e, 0x000f131c, 0x000c101a, 0x000b1018, 0x00090e14, 0x00080c13, 0x00090c12, 0x00080c10, 0x00080a10, 0x0007090d, 0x0004080b, 0x00040609, 0x00030408, 0x00030407, 0x00030406, 0x00030505, 0x00040507, 0x00040508, 0x00040608, 0x00040609, 0x0004070a, 0x0005070a, 0x0005070a, 0x0006080b, 0x0006080b, 0x0006080b, 0x0006080b, 0x0005080c, 0x0005080b, 0x0004080b, 0x0004080b, 0x0005080b, 0x0006080b, 0x00080a0d, 0x000c0e11, 0x00111316, 0x00141619, 0x0017191c, 0x001a1c21, 0x001c2026, 0x0020242a, 0x0022272d, 0x00242930, 0x00282c34, 0x00282e36, 0x00293038, 0x002a3039, 0x002b313b, 0x002c323c, 0x002c333c, 0x002e343d, 0x002e343d, 0x002c343d, 0x002c333c, 0x002c333c, 0x002c343c, 0x002d343d, 0x002d353d, 0x002c363d, 0x002d3740, 0x002e3841, 0x002f3842, 0x00303842, 0x00303842, 0x00303a43, 0x00303a44, 0x00303a45, 0x00333c48, 0x00343d49, 0x00343e49, 0x00353e4a, 0x00353e4b, 0x00343e4b, 0x00343f4c, 0x00343f4c, 0x0035404d, 0x0037404e, 0x0037404e, 0x0036404c, 0x00343f4a, 0x0034404b, 0x0034404c, 0x0036404c, 0x0036404c, 0x00353f4b, 0x0034404b, 0x00343e4a, 0x00343e49, 0x00333c48, 0x00333c47, 0x00333b46, 0x00323a44, 0x00313943, 0x00313944, 0x00303844, 0x00303742, 0x00303640, 0x002f353f, 0x002f353f, 0x002f3540, 0x002f3440, 0x002f3440, 0x002f3540, 0x002f3540, 0x002f3540, 0x00303540, 0x00303540, 0x00303640, 0x00313840, 0x00313841, 0x00313841, 0x0030353f, 0x002d3039, 0x00272931, 0x00202329, 0x00181b21, 0x00101318, 0x000b0e14, 0x00080b10, 0x00070a0f, 0x00080b10, 0x00080b10, 0x00080b0f, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x0007090d, 0x0006090c, 0x0005080b, 0x0005080b, 0x0004070a, 0x00040609, 0x00040508, 0x00040508, 0x00040508, 0x00030408, 0x00030408, 0x00030407, 0x00030407, 0x00030407, 0x00030408, 0x0006070c, 0x000a0b12, 0x000c1017, 0x000d111a, 0x000f131d, 0x0010151e, 0x0010171e, 0x00101820, 0x00111a24, 0x00121c26, 0x00141d28, 0x00141e29, 0x0015202a, 0x0017202b, 0x0018222c, 0x0019232f, 0x00192430, 0x00192531, 0x001a2834, 0x001a2835, 0x001c2a38, 0x001c2c38, 0x001e2d3b, 0x001f303d, 0x0020313e, 0x0023313f, 0x0024313f, 0x0023313f, 0x0024313f, 0x0023313f, 0x0021303d, 0x001d2b36, 0x00121b23, 0x00060b10, 0x00030408, 0x00020305, 0x00020305, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000304, 0x00000304, 0x00000304, 0x00000304, 0x00000304, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00000102, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00020405, 0x00020404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00030406, 0x00030507, 0x0005080d, 0x00181f25, 0x00222f39, 0x00203240, 0x00223442, 0x00243544, 0x00243544, 0x00243443, 0x00233140, 0x0021303f, 0x00202d3c, 0x001f2b39, 0x001d2837, 0x001c2734, 0x00182432, 0x00182230, 0x0018212f, 0x0017202e, 0x0016202c, 0x00141e2b, 0x00141d28, 0x00121c26, 0x00111b25, 0x00121a24, 0x00121923, 0x00101720, 0x00101620, 0x000f151e, 0x000e141b, 0x000c1018, 0x000b1016, 0x00090e13, 0x00080d11, 0x00080c12, 0x00080c12, 0x00090a11, 0x0008090f, 0x0006080d, 0x0004060a, 0x00030508, 0x00030507, 0x00030504, 0x00030504, 0x00030506, 0x00040508, 0x00040609, 0x00040609, 0x00040609, 0x0005070a, 0x0006080b, 0x0006080b, 0x0007080c, 0x0007080c, 0x0007080c, 0x0007080c, 0x0006080c, 0x0004080b, 0x0004080b, 0x0005080b, 0x0006080b, 0x0007080c, 0x000a0c10, 0x000f1014, 0x00131418, 0x0015181a, 0x00181c20, 0x001b1e24, 0x001d2228, 0x0020252c, 0x0024282f, 0x00272c32, 0x00282d35, 0x00282f36, 0x00293038, 0x002a303a, 0x002b313b, 0x002c323c, 0x002c333c, 0x002d343d, 0x002c343d, 0x002c343c, 0x002a333c, 0x002a333c, 0x002c343c, 0x002c343d, 0x002d353f, 0x002d3640, 0x002d3840, 0x002d3840, 0x002e3840, 0x002e3840, 0x002e3840, 0x002f3840, 0x00303942, 0x00323a44, 0x00333b44, 0x00333c45, 0x00333c46, 0x00333b46, 0x00313b46, 0x00313b47, 0x00333c48, 0x00343f4b, 0x00353f4b, 0x00353f4a, 0x00353f49, 0x00323c47, 0x00313c46, 0x00323c47, 0x00333d48, 0x00343d48, 0x00333d48, 0x00323d48, 0x00333d48, 0x00323c47, 0x00333c47, 0x00343c47, 0x00333b46, 0x00323a44, 0x00313843, 0x00313843, 0x00303842, 0x00303641, 0x002f343e, 0x002e343d, 0x002e343f, 0x002e343f, 0x002f3440, 0x002f3440, 0x00303640, 0x00303640, 0x00303640, 0x00303540, 0x00313540, 0x0030353e, 0x0030363e, 0x0030363e, 0x002e343d, 0x002b3038, 0x00262931, 0x001e2128, 0x00181b20, 0x00101418, 0x000a0d11, 0x00080c10, 0x00080b10, 0x00080b10, 0x00080b10, 0x00080b10, 0x00070a0f, 0x0006090e, 0x0006090e, 0x0006090e, 0x0006090d, 0x0007080c, 0x0006080b, 0x0005070a, 0x0005070a, 0x00040609, 0x00040508, 0x00030508, 0x00030508, 0x00030508, 0x00030507, 0x00030407, 0x00020405, 0x00020405, 0x00030406, 0x00040609, 0x0008080e, 0x000b0c14, 0x000d1018, 0x000e121a, 0x000f141e, 0x000e161e, 0x000e181e, 0x000e1820, 0x000e1923, 0x00101b25, 0x00111c26, 0x00141d28, 0x00141f29, 0x0016202b, 0x0018212c, 0x0018232d, 0x00182430, 0x00192531, 0x001a2834, 0x00192835, 0x001b2a38, 0x001c2b38, 0x001d2d3a, 0x001e2f3c, 0x0020303e, 0x0022303e, 0x0023313e, 0x0022313e, 0x0022313e, 0x0021303d, 0x001f2e3b, 0x001b2832, 0x0010181e, 0x0004090c, 0x00030406, 0x00030305, 0x00020206, 0x00020206, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00000102, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00020404, 0x00020404, 0x00010304, 0x00000304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020405, 0x00030406, 0x0004080c, 0x00171d24, 0x00222f38, 0x00213240, 0x00223441, 0x00243442, 0x00243442, 0x00243441, 0x00233140, 0x0021303f, 0x00202d3c, 0x001f2b39, 0x001d2837, 0x001c2734, 0x00182432, 0x00182230, 0x0018212f, 0x0017202e, 0x0016202c, 0x00141e2b, 0x00141d28, 0x00121c27, 0x00101b26, 0x00111a25, 0x00111924, 0x00101823, 0x000f1620, 0x000e141e, 0x000e141b, 0x000c1117, 0x000b1015, 0x00090e12, 0x00080d11, 0x00080c12, 0x00080c12, 0x00090a11, 0x00090a10, 0x0007080d, 0x0004060a, 0x00030408, 0x00030407, 0x00030404, 0x00030405, 0x00030408, 0x00040508, 0x00040609, 0x00040609, 0x00040609, 0x0005070a, 0x0006080b, 0x0006080b, 0x0007080c, 0x0007080c, 0x0007080c, 0x0007080c, 0x0007080c, 0x0005080b, 0x0005080b, 0x0006080b, 0x0006080b, 0x0006080b, 0x00080a0e, 0x000c0e12, 0x00101114, 0x00121418, 0x0015181d, 0x00181c21, 0x001c2026, 0x001e2329, 0x0022272d, 0x00242930, 0x00262c34, 0x00272d35, 0x00282e37, 0x00282f38, 0x00293039, 0x002a303a, 0x002b313b, 0x002b323c, 0x002a323b, 0x002a333c, 0x0029323b, 0x0029323c, 0x002b333c, 0x002c343c, 0x002c343d, 0x002c353f, 0x002c3640, 0x002c3740, 0x002c3740, 0x002c373e, 0x002c373e, 0x002e383f, 0x00303841, 0x00313942, 0x00323a43, 0x00323a43, 0x00333b44, 0x00323a45, 0x00313a44, 0x00313a46, 0x00313c48, 0x00333e4a, 0x00343e4a, 0x00343d48, 0x00343e48, 0x00323c47, 0x00313b46, 0x00313b46, 0x00323b46, 0x00323b44, 0x00313b44, 0x00303b44, 0x00303b44, 0x00303b44, 0x00313b44, 0x00323a45, 0x00323a44, 0x00313944, 0x00313843, 0x00313841, 0x002f353f, 0x002e343d, 0x002d323c, 0x002c333c, 0x002e343e, 0x002f343f, 0x00303540, 0x00303540, 0x00303640, 0x00303640, 0x00303640, 0x0030343f, 0x002f343d, 0x002d333c, 0x002c333a, 0x002a3138, 0x00282f37, 0x00252a32, 0x0020232b, 0x00181c23, 0x0013161a, 0x000c0f13, 0x00080b0e, 0x00070a0f, 0x00080b10, 0x00080b10, 0x00080b10, 0x00080b10, 0x00070a0f, 0x0006090e, 0x0006090d, 0x0006090d, 0x0006090c, 0x0006080c, 0x0006080b, 0x0005070a, 0x00040609, 0x00040609, 0x00030508, 0x00030408, 0x00030408, 0x00030408, 0x00030407, 0x00030407, 0x00020404, 0x00020404, 0x00020405, 0x0004060a, 0x0008090f, 0x000c0c14, 0x000e1018, 0x000e131b, 0x000f141e, 0x000e161e, 0x000d181e, 0x000e1820, 0x000e1923, 0x00101b25, 0x00101c26, 0x00141d27, 0x00141f29, 0x0016202b, 0x0018212c, 0x0018232d, 0x00182430, 0x00192531, 0x001a2734, 0x001a2835, 0x001c2a37, 0x001d2b38, 0x001e2d3a, 0x001e2f3c, 0x0020303d, 0x0021303e, 0x0021303e, 0x0022303e, 0x0021303d, 0x0020303a, 0x001e2d38, 0x0018242e, 0x000d1419, 0x00040708, 0x00030404, 0x00030304, 0x00020205, 0x00020206, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00000102, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00020405, 0x00020405, 0x00010404, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00020405, 0x00020405, 0x0004080c, 0x00161e24, 0x00222f38, 0x0022323e, 0x0021323f, 0x00233340, 0x00243440, 0x00243440, 0x0023323f, 0x0021303d, 0x00202d3b, 0x001f2b39, 0x001c2937, 0x001c2734, 0x00182432, 0x00182230, 0x0018212f, 0x0017202e, 0x0016202c, 0x00141e2b, 0x00141d29, 0x00121c28, 0x00101b27, 0x00101b25, 0x00101924, 0x00101823, 0x000d1520, 0x000e141e, 0x000d141b, 0x000b1117, 0x000b1016, 0x00090e14, 0x00080d13, 0x00080c13, 0x00090c13, 0x000a0b12, 0x00090b10, 0x0007080d, 0x0004060a, 0x00030508, 0x00030508, 0x00030507, 0x00030507, 0x00030508, 0x00040508, 0x00040609, 0x00040609, 0x00040609, 0x0005070a, 0x0006080b, 0x0006080b, 0x0007080c, 0x0007080c, 0x0007080c, 0x0007080c, 0x0007080c, 0x0006080b, 0x0007080c, 0x0007080c, 0x0007080c, 0x0007080c, 0x0007080c, 0x000a0c0f, 0x000d0f13, 0x00101316, 0x0014171b, 0x00171a1f, 0x001a1d24, 0x001d2027, 0x0020242b, 0x0022272e, 0x00242a32, 0x00252c33, 0x00262c34, 0x00282d37, 0x00282f38, 0x002a3039, 0x002a3039, 0x002a3039, 0x002a3038, 0x002a3139, 0x002a3139, 0x002b3139, 0x002c323a, 0x002c333a, 0x002c343c, 0x002d343d, 0x002c353e, 0x002d3640, 0x002d363f, 0x002c373e, 0x002c373d, 0x002d373e, 0x002f3840, 0x002f3840, 0x00303840, 0x00313942, 0x00323a43, 0x00323a43, 0x00323a43, 0x00323a45, 0x00333c47, 0x00333d48, 0x00343e48, 0x00333d48, 0x00333d47, 0x00323c47, 0x00313c47, 0x00323b46, 0x00323b45, 0x00323a43, 0x00313942, 0x00303a42, 0x00303942, 0x00303942, 0x00303943, 0x00313944, 0x00313944, 0x00313944, 0x00303742, 0x00303640, 0x002d343d, 0x002c323c, 0x002c333c, 0x002c333c, 0x002c333c, 0x002e343e, 0x00303640, 0x00303640, 0x002f353f, 0x002f353e, 0x002e343d, 0x002d333c, 0x002c303b, 0x002a2f38, 0x00272d35, 0x00252c34, 0x00232830, 0x0020242c, 0x001b1e26, 0x0014181e, 0x000e1116, 0x00080c0f, 0x00060a0d, 0x00060c0e, 0x00060c0e, 0x00070b0f, 0x00080b10, 0x00080b10, 0x00080b10, 0x00070a0f, 0x00070a0e, 0x0005080c, 0x0004080c, 0x0005080b, 0x0006080b, 0x0005070a, 0x00040609, 0x00040609, 0x00030508, 0x00030508, 0x00030508, 0x00030508, 0x00030508, 0x00030508, 0x00020405, 0x00020405, 0x00020405, 0x0005070b, 0x00090b10, 0x000c0e14, 0x000f1118, 0x000f131b, 0x0010141e, 0x000f151e, 0x000e171e, 0x000f1820, 0x000f1922, 0x00101b24, 0x00121c24, 0x00141d26, 0x00141f28, 0x0016202b, 0x0018212c, 0x0019232d, 0x0019242e, 0x001b2530, 0x001c2733, 0x001c2834, 0x001c2a36, 0x001e2b37, 0x00202d38, 0x00202f3b, 0x0020303d, 0x0021303e, 0x0021303d, 0x0021303d, 0x0020303c, 0x00202f3a, 0x001e2c38, 0x0017222b, 0x00091014, 0x00040507, 0x00030403, 0x00020304, 0x00020205, 0x00020205, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00000102, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00020404, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00030405, 0x00030405, 0x0004080c, 0x00161e24, 0x00222f38, 0x0022323d, 0x0021323f, 0x0023333f, 0x0024343f, 0x0024343f, 0x0023323f, 0x0020303d, 0x00202d3b, 0x001e2b39, 0x001c2937, 0x001c2734, 0x00182432, 0x00182230, 0x0018212f, 0x0017202e, 0x0016202c, 0x00141e2b, 0x00141d28, 0x00121c28, 0x00111b27, 0x00111a25, 0x00111924, 0x00101823, 0x000f1620, 0x000f151e, 0x000d141b, 0x000a1117, 0x000a1016, 0x00090e14, 0x00080d13, 0x00080c13, 0x00090c13, 0x000a0b12, 0x00090b10, 0x0008080e, 0x0004060a, 0x00030408, 0x00030408, 0x00030407, 0x00030407, 0x00030408, 0x00040508, 0x00040609, 0x00040609, 0x00040609, 0x0005070a, 0x0006080b, 0x0006080b, 0x0007080c, 0x0007080c, 0x0006080b, 0x0006080b, 0x0006080b, 0x0006080b, 0x0007080c, 0x0007080c, 0x0007080c, 0x0006080b, 0x0006080b, 0x0008090c, 0x000c0d10, 0x000e1014, 0x00111418, 0x0015181c, 0x00181c20, 0x001b1e24, 0x001d2228, 0x0020252c, 0x00232830, 0x00242931, 0x00242a32, 0x00272c34, 0x00282d35, 0x00292e36, 0x002a2f37, 0x002a2f37, 0x00293038, 0x002a3038, 0x002a3038, 0x002a3038, 0x002b3139, 0x002c323a, 0x002c323a, 0x002c333c, 0x002c343d, 0x002d353e, 0x002d353e, 0x002c353c, 0x002c353c, 0x002c353c, 0x002e3640, 0x002e3640, 0x002f3840, 0x00303841, 0x00313a43, 0x00323a43, 0x00323a43, 0x00323b44, 0x00333c47, 0x00333c47, 0x00333d48, 0x00323c47, 0x00323c46, 0x00323c47, 0x00323b46, 0x00333b45, 0x00323a44, 0x00323a43, 0x00313942, 0x00303841, 0x00303841, 0x00303841, 0x00303842, 0x00303843, 0x00313843, 0x00303842, 0x00303641, 0x002f353f, 0x002c333c, 0x002c323c, 0x002c333c, 0x002c333c, 0x002c333c, 0x002d343c, 0x002d343d, 0x002d343d, 0x002d333c, 0x002b313b, 0x002a303a, 0x002a3039, 0x00282d36, 0x00252b33, 0x00222830, 0x0020272e, 0x001d242b, 0x001a1f27, 0x0014171f, 0x000f1218, 0x000a0d12, 0x00080b0e, 0x00060a0d, 0x00060c0e, 0x00060c0e, 0x00070b0f, 0x00080b10, 0x00080b10, 0x00080b10, 0x00070a0f, 0x0006090e, 0x0005080c, 0x0004080c, 0x0005080b, 0x0005070a, 0x0004070a, 0x00040609, 0x00040609, 0x00030508, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00020407, 0x00020407, 0x00030407, 0x0006080c, 0x000a0b11, 0x000d0f15, 0x000f1218, 0x000f131b, 0x0010141e, 0x000f151e, 0x000f171e, 0x0010181f, 0x000f1921, 0x00111b24, 0x00121c24, 0x00141d26, 0x00141f28, 0x0016202b, 0x0018212c, 0x0019232d, 0x0019232e, 0x001b2530, 0x001c2733, 0x001c2834, 0x001e2a35, 0x001e2a36, 0x00202c38, 0x00202f3b, 0x0021303d, 0x0021303e, 0x0021303d, 0x0020303d, 0x001f2f3c, 0x001f2e39, 0x001c2934, 0x00141e25, 0x00060c10, 0x00020407, 0x00020402, 0x00020303, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000102, 0x00000102, 0x00000102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000102, 0x00000102, 0x00000102, 0x00000102, 0x00000102, 0x00010102, 0x00010102, 0x00010102, 0x00010102, 0x00010102, 0x00010103, 0x00000104, 0x00000104, 0x00000104, 0x00000104, 0x00000204, 0x00000203, 0x00000203, 0x00000203, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010304, 0x00010304, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020404, 0x00030405, 0x00030407, 0x0003070b, 0x00121920, 0x00222e38, 0x0022323d, 0x0021323e, 0x0022333e, 0x00213440, 0x00223340, 0x0022313e, 0x00202f3c, 0x00202d3a, 0x001e2b38, 0x001c2836, 0x001c2734, 0x00192431, 0x00182230, 0x0018212e, 0x0017202e, 0x0016202b, 0x00141e28, 0x00141c28, 0x00131b26, 0x00121b26, 0x00121a25, 0x00111924, 0x00111723, 0x00101621, 0x000e141f, 0x000d141b, 0x000a1117, 0x000a1016, 0x00080d14, 0x00080c13, 0x00080c12, 0x00080c12, 0x00090a11, 0x00080910, 0x0008080e, 0x0006080b, 0x00040609, 0x00040508, 0x00030507, 0x00030507, 0x00030508, 0x00040508, 0x00040608, 0x00040608, 0x00040608, 0x0004070a, 0x0005070a, 0x0005070a, 0x0006080b, 0x0006080b, 0x0007080c, 0x0007080c, 0x0006080b, 0x0006080b, 0x0006080b, 0x0006080b, 0x0006080c, 0x0006080c, 0x0005080b, 0x0006080c, 0x00080b0e, 0x000c0f12, 0x000f1215, 0x0013161b, 0x0016191e, 0x00181c22, 0x001b2026, 0x001f2329, 0x0021252c, 0x0023272e, 0x00242830, 0x00262b33, 0x00282c34, 0x00292e36, 0x002a2f37, 0x00292f37, 0x00292f37, 0x002a3038, 0x002a3038, 0x002a3038, 0x002b3039, 0x002b313a, 0x002c323b, 0x002c333c, 0x002c343d, 0x002c343d, 0x002d353e, 0x002d343c, 0x002c343d, 0x002c343d, 0x002d353f, 0x002d353f, 0x002f3740, 0x00303841, 0x00323a43, 0x00323a43, 0x00323a43, 0x00323b44, 0x00333b46, 0x00333c46, 0x00323c47, 0x00333c46, 0x00333b46, 0x00323b45, 0x00323a44, 0x00333a44, 0x00323943, 0x00323942, 0x00313941, 0x00303841, 0x00303841, 0x00303841, 0x00313841, 0x00313841, 0x00313741, 0x00303640, 0x0030353f, 0x002e333c, 0x002c303a, 0x002c303a, 0x002c323b, 0x002c323a, 0x002c323a, 0x002c323a, 0x002c323a, 0x002c3139, 0x002b3039, 0x00292e38, 0x00282c36, 0x00272c34, 0x00242931, 0x0022272e, 0x0020242c, 0x001e2229, 0x001b1f25, 0x00161a20, 0x0010141b, 0x000b0e14, 0x00080b10, 0x00080b0e, 0x00080b0e, 0x00070c0e, 0x00060b0e, 0x00070b0e, 0x00080b0f, 0x00080b0f, 0x00070a0e, 0x0006090d, 0x0005080c, 0x0004080c, 0x0004080c, 0x0005080b, 0x0005070a, 0x0004070a, 0x00040609, 0x00040609, 0x00040509, 0x00030508, 0x00030508, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00030408, 0x00040508, 0x0007080d, 0x000a0c12, 0x000c0f16, 0x000e1218, 0x000e131b, 0x000f141d, 0x0010161f, 0x0010171f, 0x00101820, 0x00101821, 0x00121a24, 0x00121c24, 0x00131d25, 0x00141f27, 0x0015202a, 0x0017212c, 0x0018222d, 0x0019232e, 0x001b2530, 0x001c2733, 0x001c2834, 0x001e2a35, 0x001e2a36, 0x00202c38, 0x00202e3b, 0x0021303d, 0x0021303e, 0x0021303d, 0x0020303c, 0x001e2f3b, 0x001e2d38, 0x001b2731, 0x00101820, 0x0004080e, 0x00020307, 0x00010303, 0x00010202, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000303, 0x00000303, 0x00000303, 0x00000303, 0x00000303, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00000103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000201, 0x00000201, 0x00000201, 0x00000102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010303, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020304, 0x00030304, 0x00030406, 0x0003060c, 0x00111820, 0x00222e38, 0x0021323b, 0x0020323c, 0x0020333d, 0x001e333f, 0x0020323f, 0x0020303d, 0x00202e3b, 0x001f2c39, 0x001d2938, 0x001c2835, 0x001b2632, 0x001a242f, 0x0019222d, 0x0018212c, 0x0018202c, 0x0016202a, 0x00141d28, 0x00131c27, 0x00131b26, 0x00131b26, 0x00121a25, 0x00111924, 0x00111723, 0x00101621, 0x000e141f, 0x000c131a, 0x000a1117, 0x00091015, 0x00080d11, 0x00070c10, 0x00080b11, 0x00080a11, 0x00080910, 0x0008080e, 0x0007080d, 0x0008080c, 0x0005070a, 0x00040507, 0x00030407, 0x00030407, 0x00030408, 0x00030408, 0x00030408, 0x00030407, 0x00030407, 0x00040508, 0x00040609, 0x00040609, 0x00040609, 0x0005070a, 0x0007080c, 0x0008090c, 0x0007080c, 0x0005070a, 0x0005070a, 0x0004080b, 0x0004080b, 0x0004090c, 0x0004080c, 0x0004080b, 0x00070a0c, 0x000b0e11, 0x000e1215, 0x0012151a, 0x0015181d, 0x00181b20, 0x001a1d24, 0x001d2027, 0x0020232a, 0x0023252c, 0x0024272e, 0x00242931, 0x00262b33, 0x00282d35, 0x00292e36, 0x00292e36, 0x00292e36, 0x00292e36, 0x00292e36, 0x002a2f37, 0x002c3039, 0x002a303a, 0x002b313b, 0x002b323c, 0x002c343c, 0x002d343d, 0x002e343d, 0x002e343d, 0x002c333d, 0x002c323c, 0x002c333e, 0x002e3540, 0x002f3740, 0x00303942, 0x00313a43, 0x00323a43, 0x00323a43, 0x00323a43, 0x00323b44, 0x00323b44, 0x00323a45, 0x00323a45, 0x00323a44, 0x00323a44, 0x00313844, 0x00313843, 0x00313842, 0x00313841, 0x00313841, 0x00303841, 0x00303841, 0x00303841, 0x00303740, 0x00303740, 0x00303640, 0x002f343e, 0x002e333c, 0x002c3139, 0x002a2f37, 0x002a2f37, 0x002b3038, 0x002b3139, 0x002b3139, 0x002b3139, 0x002b3038, 0x002a2f37, 0x00282d35, 0x00272c34, 0x00242931, 0x00232830, 0x0021262e, 0x0020242a, 0x001d2126, 0x001b1e24, 0x00181b20, 0x0013161b, 0x000c1016, 0x00080b11, 0x00080b10, 0x00080b0f, 0x00080c0f, 0x00080b0e, 0x00070a0d, 0x0006090c, 0x0006090c, 0x0006090c, 0x0007080c, 0x0006080b, 0x0005070a, 0x0005070a, 0x0004070a, 0x0004070a, 0x0004070a, 0x00040609, 0x00040508, 0x00040508, 0x00040609, 0x00030508, 0x00030408, 0x00030406, 0x00020405, 0x00030408, 0x00040508, 0x00040508, 0x00040609, 0x0008090d, 0x00090d12, 0x000c1016, 0x000c1118, 0x000c131a, 0x000c141c, 0x0010161f, 0x00121720, 0x00121720, 0x00111821, 0x00121924, 0x00131b25, 0x00141d25, 0x00141f27, 0x0015202a, 0x0018212c, 0x0018222c, 0x0019232e, 0x001b2530, 0x001c2733, 0x001c2834, 0x001e2a35, 0x001e2a36, 0x00202c38, 0x00202e3a, 0x00202f3c, 0x0021303d, 0x0021303e, 0x0020303c, 0x001f2f3a, 0x001d2b37, 0x0018242e, 0x000b131b, 0x0004060c, 0x00020206, 0x00020203, 0x00010203, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000201, 0x00000201, 0x00000201, 0x00000102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010303, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020304, 0x00030304, 0x00030404, 0x0003060b, 0x000e141c, 0x00212d38, 0x0021313c, 0x0020313c, 0x0020323c, 0x001f333f, 0x0020323f, 0x00202f3c, 0x00202d3b, 0x001e2c39, 0x001c2a38, 0x001c2835, 0x001b2731, 0x0019242f, 0x0019232c, 0x0018212c, 0x0018202c, 0x0015202a, 0x00141d28, 0x00131c27, 0x00131b26, 0x00131b26, 0x00121a25, 0x00111924, 0x00111723, 0x00101621, 0x000f141f, 0x000c131a, 0x000a1117, 0x00091015, 0x00080d11, 0x00070c10, 0x00070b10, 0x00070a10, 0x0007090f, 0x0007080d, 0x0007080d, 0x0008080c, 0x0006080b, 0x00030507, 0x00030407, 0x00030407, 0x00030408, 0x00030408, 0x00030408, 0x00030407, 0x00030507, 0x00040508, 0x00040609, 0x00040609, 0x00040609, 0x0005070a, 0x0007080c, 0x0008080c, 0x0007080c, 0x0005080b, 0x0005080b, 0x0004080b, 0x0004090c, 0x0004090c, 0x0004090c, 0x0003080a, 0x0004080b, 0x00080c0f, 0x000c1013, 0x00101318, 0x0014171c, 0x0015181e, 0x00181b22, 0x001b1e24, 0x001e2128, 0x0020242a, 0x0022242c, 0x0022272f, 0x00242931, 0x00272c34, 0x00282d35, 0x00292e36, 0x00292e36, 0x00292e36, 0x00292e36, 0x002a2f37, 0x002b3038, 0x002a303a, 0x002a303a, 0x0029303a, 0x002b333c, 0x002c343c, 0x002e343d, 0x002e343e, 0x002c333d, 0x002b313c, 0x002c323d, 0x002d353f, 0x002f3740, 0x00303841, 0x00313942, 0x00313942, 0x00313942, 0x00313942, 0x00313942, 0x00313942, 0x00313944, 0x00313944, 0x00313944, 0x00313844, 0x00313843, 0x00303742, 0x00303641, 0x00303740, 0x00303740, 0x00303740, 0x002f3740, 0x00303640, 0x002f353f, 0x002e343e, 0x002d343c, 0x002d323c, 0x002c3039, 0x002a2f37, 0x00282d35, 0x00282d35, 0x002a2f37, 0x002a3036, 0x002c3038, 0x002b3038, 0x00292e36, 0x00282c34, 0x00252a33, 0x00242830, 0x0022272f, 0x0020242c, 0x001f232b, 0x001d2127, 0x001b1e23, 0x00181b20, 0x0014181c, 0x00101317, 0x000a0d12, 0x00070a10, 0x00070a0f, 0x00080b10, 0x00080b0f, 0x00070a0e, 0x00070a0c, 0x0006090c, 0x0006090c, 0x0006090c, 0x0006080b, 0x0004060a, 0x00040609, 0x0004070a, 0x0004070a, 0x0004070a, 0x00040609, 0x00040508, 0x00030408, 0x00030406, 0x00040508, 0x00030508, 0x00030408, 0x00030406, 0x00020405, 0x00030408, 0x00040508, 0x00040609, 0x0006080b, 0x000a0c0f, 0x000a0e12, 0x000b1016, 0x000b1118, 0x000b131a, 0x000c141c, 0x0010161f, 0x00121720, 0x00121720, 0x00111720, 0x00121824, 0x00121a25, 0x00141d26, 0x00141f27, 0x0015202a, 0x0018212c, 0x0018222c, 0x0019232e, 0x001b2530, 0x001c2733, 0x001c2834, 0x001e2935, 0x001f2a36, 0x00202c38, 0x00202e3a, 0x00202e3b, 0x0020303c, 0x0020303c, 0x001f303b, 0x001e2d38, 0x001c2a35, 0x0016212c, 0x00081018, 0x0003050b, 0x00020206, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000201, 0x00000201, 0x00000201, 0x00000102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010303, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020304, 0x00030304, 0x00030404, 0x0002060a, 0x000a1019, 0x001d2a34, 0x0021303b, 0x0020303b, 0x0020303c, 0x001f323c, 0x0020323d, 0x00202f3c, 0x00202d3b, 0x001f2c39, 0x001c2a38, 0x001b2835, 0x001a2731, 0x0018242f, 0x0018232c, 0x0018212c, 0x0017212c, 0x0015202a, 0x00141e28, 0x00131c27, 0x00131b26, 0x00131b26, 0x00121a25, 0x00111824, 0x00101723, 0x00101621, 0x0010151f, 0x000d131a, 0x000a1117, 0x00091015, 0x00080d11, 0x00060c10, 0x00060b10, 0x00060a10, 0x0005090e, 0x0006090d, 0x0006080d, 0x0007080c, 0x0006080c, 0x00040508, 0x00030408, 0x00030408, 0x00030409, 0x00030409, 0x00030409, 0x00030408, 0x00030408, 0x00040508, 0x00040609, 0x00040609, 0x00040609, 0x00040609, 0x0005080b, 0x0006080b, 0x0006080b, 0x0007080c, 0x0007080c, 0x0006090c, 0x0004090c, 0x00050a0d, 0x0004090c, 0x0004080b, 0x0004080b, 0x0006090c, 0x00090c10, 0x000c1014, 0x00111419, 0x0014171c, 0x0016191e, 0x00181d22, 0x001d2025, 0x001f2228, 0x0020232b, 0x0021252e, 0x00232830, 0x00252a32, 0x00282c34, 0x00282d35, 0x00282d35, 0x00282e36, 0x00282d35, 0x00292e36, 0x002a2f37, 0x002a3038, 0x002a3038, 0x002a3039, 0x002a303a, 0x002b323c, 0x002c323c, 0x002c333c, 0x002c333c, 0x002c323c, 0x002c333c, 0x002d353f, 0x002e3740, 0x00303841, 0x00313942, 0x00303942, 0x00303942, 0x00303841, 0x00303841, 0x00303841, 0x00303843, 0x00303843, 0x00303843, 0x00303843, 0x00303742, 0x00303641, 0x00303541, 0x00303640, 0x00303640, 0x00303640, 0x002f3640, 0x002f353f, 0x002d343d, 0x002c323c, 0x002c313b, 0x002c303a, 0x002b2f38, 0x00292e36, 0x00282d35, 0x00282d35, 0x00282e36, 0x00282e34, 0x00292e34, 0x00282d35, 0x00272c34, 0x00252a32, 0x00242830, 0x0022252e, 0x0020242c, 0x001f222a, 0x001c2028, 0x001a1d24, 0x00171a1f, 0x0014171c, 0x00101418, 0x000c0f14, 0x00080c10, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0d, 0x0006090d, 0x0006090c, 0x0006090c, 0x0007080c, 0x0006080c, 0x0004070b, 0x0004070b, 0x0004070b, 0x00040609, 0x00040508, 0x00030408, 0x00020307, 0x00020405, 0x00030508, 0x00030408, 0x00020408, 0x00020406, 0x00020405, 0x00020407, 0x00020408, 0x00040508, 0x0007080c, 0x000b0c10, 0x000a0e13, 0x000b1016, 0x000b1118, 0x000b131a, 0x000c141c, 0x0010161f, 0x00111620, 0x00121720, 0x00121720, 0x00121824, 0x00131a25, 0x00141d26, 0x00141f27, 0x0015202a, 0x0018212c, 0x0018222c, 0x0019232e, 0x001b2530, 0x001c2733, 0x001e2834, 0x001f2935, 0x00202a36, 0x00212c38, 0x00212d3a, 0x00202d3b, 0x00202f3c, 0x001f303c, 0x001f2e3a, 0x001e2d38, 0x001c2934, 0x00142029, 0x00060d15, 0x0003040a, 0x00020206, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000201, 0x00000201, 0x00000201, 0x00000102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010102, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010102, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010303, 0x00000302, 0x00000302, 0x00000302, 0x00000302, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020304, 0x00030304, 0x00040404, 0x0003060a, 0x00080f17, 0x001a2630, 0x00202f3a, 0x0020303b, 0x0020303c, 0x0020313d, 0x0020313d, 0x00202f3c, 0x00202d3a, 0x001f2b38, 0x001e2837, 0x001c2834, 0x001a2732, 0x0018242f, 0x0018232d, 0x0018212c, 0x0018202c, 0x0017202b, 0x00141e29, 0x00131c27, 0x00121b26, 0x00121a25, 0x00111924, 0x00111824, 0x00111723, 0x00101722, 0x0010151f, 0x000d141a, 0x000a1117, 0x00091015, 0x00080d11, 0x00060c10, 0x00060b10, 0x00050a0f, 0x00050a0e, 0x0006090d, 0x0006090d, 0x0007080c, 0x0007080c, 0x00040509, 0x00030508, 0x00030408, 0x0003040a, 0x0003040a, 0x00030409, 0x00030408, 0x00030408, 0x00040508, 0x00040609, 0x00040609, 0x00040609, 0x00040609, 0x0005070a, 0x0006080b, 0x0006080b, 0x0008080c, 0x0008090d, 0x0007090d, 0x00050a0d, 0x00050b0e, 0x00040a0d, 0x00050a0c, 0x0006090c, 0x0006090c, 0x00070a0d, 0x000a0d12, 0x00101318, 0x00111419, 0x0014171c, 0x00171b20, 0x001b1f23, 0x001d2028, 0x001e222a, 0x0020242c, 0x0021262f, 0x00242830, 0x00262b33, 0x00262b33, 0x00272c34, 0x00282c34, 0x00282d35, 0x00282d35, 0x00292e36, 0x002a2f37, 0x002a2f37, 0x00292f38, 0x00293039, 0x002a303a, 0x002b313b, 0x002b313b, 0x002c323c, 0x002c333c, 0x002d343d, 0x002d343e, 0x002e3740, 0x002f3840, 0x00303841, 0x00303841, 0x00303840, 0x00303840, 0x00303840, 0x002f3840, 0x002f3742, 0x00303742, 0x002f3742, 0x00303742, 0x00303641, 0x002f3440, 0x002f3440, 0x002f353f, 0x002f353f, 0x002f353f, 0x002f353f, 0x002e343d, 0x002d323b, 0x002c313a, 0x002c3039, 0x002b2f38, 0x002a2e37, 0x00282e36, 0x00282c34, 0x00282c34, 0x00272c34, 0x00272c33, 0x00282b32, 0x00272a31, 0x00252830, 0x0023262e, 0x0021242d, 0x0020222b, 0x001e2029, 0x001c1f28, 0x001a1d25, 0x00181a20, 0x0014161c, 0x00101418, 0x000d1015, 0x00090c11, 0x00080b10, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0f, 0x00070a0e, 0x0006090d, 0x0006090d, 0x0006090d, 0x0007080e, 0x0006080c, 0x0004070c, 0x0004070c, 0x0004070c, 0x00040609, 0x00030508, 0x00030408, 0x00020406, 0x00020405, 0x00030408, 0x00030408, 0x00020308, 0x00020406, 0x00020405, 0x00020307, 0x00020308, 0x00040509, 0x0008080c, 0x000b0c11, 0x000b0e14, 0x000b1016, 0x000b1118, 0x000b131a, 0x000c141c, 0x0010161f, 0x00111620, 0x00121720, 0x00121720, 0x00111823, 0x00141a25, 0x00141d26, 0x00141f27, 0x0015202a, 0x0018212c, 0x0018222c, 0x0019232e, 0x001b2530, 0x001c2733, 0x001e2834, 0x00202935, 0x00202936, 0x00222c38, 0x00222d3a, 0x00222d3b, 0x00202d3b, 0x001f2f3c, 0x001e2e39, 0x001d2c38, 0x001a2833, 0x00131c25, 0x00050910, 0x00020408, 0x00020205, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x00000202, 0x00000202, 0x00000202, 0x00000102, 0x00010102, 0x00010102, 0x00010102, 0x00010103, 0x00010102, 0x00000102, 0x00000102, 0x00000102, 0x00000102, 0x00010103, 0x00010102, 0x00010102, 0x00010102, 0x00010102, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010304, 0x00010304, 0x00010304, 0x00000204, 0x00000204, 0x00010304, 0x00030304, 0x00030405, 0x00030609, 0x00080d15, 0x0018242e, 0x001f2d3a, 0x0020303c, 0x0020303f, 0x0020303f, 0x0021303f, 0x00202e3c, 0x00202c3a, 0x001f2b38, 0x001f2836, 0x001d2834, 0x001c2733, 0x00192430, 0x0018222d, 0x0018212c, 0x0017202c, 0x00171f2a, 0x00151d28, 0x00131c27, 0x00121b26, 0x00121a25, 0x00111924, 0x00111824, 0x00121823, 0x00111721, 0x0010151f, 0x000d131b, 0x000b1118, 0x000a1015, 0x00080d11, 0x00060c10, 0x00060b10, 0x00050a0f, 0x00050a0f, 0x0006090e, 0x0007090f, 0x0008080d, 0x0007080c, 0x0005070a, 0x00040609, 0x00030408, 0x00030409, 0x00030409, 0x00030409, 0x00030408, 0x00030408, 0x00040508, 0x00040608, 0x00040609, 0x00040609, 0x00040609, 0x0005070a, 0x0005070a, 0x0006080b, 0x0007080c, 0x0008080c, 0x0007090c, 0x00050a0d, 0x00050a0d, 0x00050a0d, 0x00060a0d, 0x0006090c, 0x0006090c, 0x0006090c, 0x00080c10, 0x000d1014, 0x00101318, 0x0013151a, 0x0015181e, 0x00181c21, 0x001b1e25, 0x001c2028, 0x001e222b, 0x0020242c, 0x0021272f, 0x00232830, 0x00242931, 0x00252a32, 0x00262b34, 0x00282c34, 0x00282d34, 0x00292e36, 0x00292e36, 0x00292e36, 0x00282e38, 0x00282f38, 0x00293038, 0x002a3038, 0x002b3039, 0x002c323b, 0x002c333c, 0x002d333c, 0x002e343d, 0x002f343f, 0x00303540, 0x00303640, 0x00303640, 0x00303640, 0x00303640, 0x00303640, 0x00303740, 0x00303641, 0x00303640, 0x00303540, 0x00303640, 0x002f353f, 0x002d343d, 0x002c333c, 0x002c333c, 0x002c333c, 0x002e333c, 0x002e333c, 0x002d323b, 0x002c3138, 0x002b3038, 0x002b3037, 0x00292e36, 0x002a2d35, 0x00292c34, 0x00272b33, 0x00252a32, 0x00242931, 0x00252830, 0x0025282f, 0x0024282e, 0x0023262c, 0x0020242b, 0x001f2229, 0x001d2028, 0x001b1e26, 0x001a1d24, 0x00181b22, 0x0017181e, 0x0014141a, 0x00101116, 0x000c0d12, 0x000a0c10, 0x00080b0e, 0x00070a0e, 0x00070a0e, 0x00070a0d, 0x00070a0d, 0x00070a0f, 0x00070a0f, 0x0006090e, 0x0005090d, 0x0005080c, 0x0006080c, 0x0006080c, 0x0005070c, 0x0004070b, 0x0004060a, 0x00040509, 0x00030508, 0x00030408, 0x00020405, 0x00030405, 0x00030408, 0x00030408, 0x00020308, 0x00020406, 0x00020405, 0x00020407, 0x00030409, 0x0004070c, 0x00080a0f, 0x000b0c12, 0x000a0f15, 0x000c1017, 0x000c1218, 0x000c131a, 0x000d141c, 0x0010161e, 0x00111620, 0x00111720, 0x00121821, 0x00121824, 0x00141a25, 0x00141d26, 0x00141f27, 0x0015202a, 0x0018222c, 0x0018232d, 0x0019242e, 0x001a2530, 0x001c2733, 0x001d2834, 0x001f2935, 0x00202a37, 0x00202c38, 0x00212c3a, 0x00212c3b, 0x00202d3b, 0x001f2e3a, 0x001f2e39, 0x001c2c37, 0x00192630, 0x00101820, 0x0003050a, 0x00030305, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00020204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00010204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00000204, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010103, 0x00010102, 0x00010102, 0x000a1821, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24, 0x000c1b24}; \ No newline at end of file +// file: ritchie.png +int intense_milk_width = 400; +int intense_milk_height = 251 +;uint32_t intense_milk[100400] = {0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000a0a0b, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00242525, 0x00121313, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0038393a, 0x000b0b0b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00898989, 0x00a4a4a4, 0x00949494, 0x00868686, 0x007c7c7c, 0x00787878, 0x00787878, 0x00787878, 0x00828282, 0x00929292, 0x00a4a4a4, 0x00acacac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00333434, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00afafaf, 0x008c8c8c, 0x00707070, 0x00555555, 0x00484848, 0x00383838, 0x002c2c2c, 0x00232323, 0x001d1d1d, 0x001c1c1c, 0x001f1f1f, 0x00232323, 0x00242424, 0x00282828, 0x00323232, 0x003f3f3f, 0x00525252, 0x006d6d6d, 0x00848484, 0x00acacac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x002c2d2d, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009b9b9b, 0x008d8d8d, 0x00666666, 0x00474747, 0x002b2b2b, 0x00161616, 0x00050505, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00020202, 0x00131313, 0x00262626, 0x003d3d3d, 0x005d5d5d, 0x00858585, 0x00a8a8a8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00212223, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00adadad, 0x007e7e7e, 0x00515151, 0x002c2c2c, 0x000c0c0c, 0x00030303, 0x00050505, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00010101, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00070707, 0x00282828, 0x004c4c4c, 0x00727272, 0x00a2a2a2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000f1010, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00545454, 0x00838383, 0x00505050, 0x00212121, 0x00050505, 0x00050505, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00020202, 0x00010101, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00050505, 0x001c1c1c, 0x00454545, 0x00787878, 0x00a4a4a4, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00050505, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00979797, 0x005e5e5e, 0x001d1d1d, 0x00050505, 0x00000000, 0x00000000, 0x00040404, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00171717, 0x004e4e4e, 0x008a8a8a, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00aeaeae, 0x007f7f7f, 0x00383838, 0x00010101, 0x00000000, 0x00000000, 0x00050505, 0x00040404, 0x00000000, 0x00000000, 0x00040404, 0x00040404, 0x00000000, 0x00000000, 0x00010101, 0x00030303, 0x00050505, 0x00060606, 0x00070707, 0x00060606, 0x00060606, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00060606, 0x00030303, 0x00000000, 0x00040404, 0x00050505, 0x00000000, 0x00030303, 0x00202020, 0x006f6f6f, 0x00aaaaaa, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00666666, 0x00b2b2b2, 0x00aeaeae, 0x00a9a9a9, 0x00a7a7a7, 0x00a8a8a8, 0x00acacac, 0x00b0b0b0, 0x00898989, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00acacac, 0x00686868, 0x00151515, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00020202, 0x000c0c0c, 0x000d0d0d, 0x00111111, 0x00151515, 0x00181818, 0x00191919, 0x00191919, 0x00191919, 0x00181818, 0x00151515, 0x00121212, 0x000e0e0e, 0x00090909, 0x00040404, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00010101, 0x00000000, 0x00010101, 0x00000000, 0x000a0a0a, 0x004e4e4e, 0x009f9f9f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00787878, 0x00a8a8a8, 0x00a2a2a2, 0x00909090, 0x00808080, 0x006e6e6e, 0x00606060, 0x00555555, 0x004c4c4c, 0x00494949, 0x004b4b4b, 0x00525252, 0x00575757, 0x00646464, 0x00787878, 0x00888888, 0x00969696, 0x00a4a4a4, 0x00afafaf, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a4a4, 0x00515151, 0x000c0c0c, 0x00000000, 0x00020202, 0x00000000, 0x00010101, 0x00020202, 0x00010101, 0x00000000, 0x00000000, 0x00040404, 0x000a0a0a, 0x00161616, 0x00242424, 0x00292929, 0x002b2b2b, 0x002d2d2d, 0x00303030, 0x00313131, 0x00313131, 0x00303030, 0x00303030, 0x00303030, 0x002e2e2e, 0x002c2c2c, 0x00272727, 0x00202020, 0x00181818, 0x00101010, 0x000a0a0a, 0x00020202, 0x00020202, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00010101, 0x00020202, 0x00020202, 0x00030303, 0x00363636, 0x00979797, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00434343, 0x00a8a8a8, 0x008f8f8f, 0x006c6c6c, 0x00404040, 0x00181818, 0x00080808, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00121212, 0x00343434, 0x00545454, 0x00818181, 0x009b9b9b, 0x00b3b3b3, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009b9b9b, 0x00404040, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00030303, 0x00090909, 0x00131313, 0x00202020, 0x002a2a2a, 0x002d2d2d, 0x002a2a2a, 0x002d2d2d, 0x002d2d2d, 0x002d2d2d, 0x002d2d2d, 0x002c2c2c, 0x002c2c2c, 0x002c2c2c, 0x002b2b2b, 0x002d2d2d, 0x002d2d2d, 0x002e2e2e, 0x002f2f2f, 0x002f2f2f, 0x002d2d2d, 0x00292929, 0x00262626, 0x001b1b1b, 0x00080808, 0x00000000, 0x00000000, 0x00030303, 0x00020202, 0x00000000, 0x00030303, 0x00000000, 0x00040404, 0x00050505, 0x00010101, 0x00282828, 0x00848484, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00434343, 0x00939393, 0x00606060, 0x00282828, 0x00000000, 0x00000000, 0x00040404, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00040404, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00111111, 0x003e3e3e, 0x007e7e7e, 0x00aaaaaa, 0x001f1f1f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9c9c, 0x003b3b3b, 0x00020202, 0x00000000, 0x00060405, 0x00000000, 0x00030102, 0x00000000, 0x00010000, 0x00040404, 0x00111111, 0x00232323, 0x002c2c2c, 0x00292929, 0x00272727, 0x00282828, 0x00282828, 0x00282828, 0x00282828, 0x00282728, 0x00282828, 0x00282828, 0x00282828, 0x002a2a2a, 0x002a2a2a, 0x00292929, 0x00282828, 0x00272526, 0x00272725, 0x00292828, 0x00292929, 0x00292929, 0x00282828, 0x00282828, 0x00252726, 0x001b1c1c, 0x00080a09, 0x00030303, 0x00010101, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00030303, 0x00030303, 0x00292929, 0x00878787, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b2b2b4, 0x00888888, 0x00383938, 0x000d0f0c, 0x00000000, 0x00020403, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00202020, 0x00646464, 0x00a5a5a5, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a8a6aa, 0x00414042, 0x00020003, 0x00000001, 0x00000000, 0x00030000, 0x00020000, 0x00020000, 0x00050201, 0x000d0a09, 0x00232122, 0x00242424, 0x00252726, 0x00262825, 0x00262825, 0x00262624, 0x00262624, 0x00272526, 0x00282627, 0x00282628, 0x00292528, 0x00282628, 0x00272728, 0x00272728, 0x00262827, 0x00262827, 0x00282627, 0x00282627, 0x00292625, 0x00282724, 0x00292625, 0x00282725, 0x00272725, 0x00272727, 0x00242625, 0x00242728, 0x0026292a, 0x00232627, 0x00151716, 0x00040404, 0x00000000, 0x00020100, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00282828, 0x00909090, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00575456, 0x00b1b0b2, 0x00aca8a9, 0x00a8a7a8, 0x00aca8a8, 0x00acaca8, 0x00b6b3b0, 0x000c0c0c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008d888c, 0x00343337, 0x0008080a, 0x00000100, 0x00000100, 0x00000100, 0x00000200, 0x00000200, 0x00000200, 0x00000001, 0x00030002, 0x00010000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00030303, 0x00010101, 0x00000000, 0x001d1d1d, 0x005f5f5f, 0x00afafaf, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b2b0b3, 0x00444246, 0x00070508, 0x00000001, 0x00030104, 0x00030102, 0x00000000, 0x00000000, 0x00040402, 0x00141412, 0x00222220, 0x00222224, 0x00232425, 0x00242625, 0x00232724, 0x00222623, 0x00232422, 0x00242422, 0x00242324, 0x00252426, 0x00272326, 0x00272328, 0x00252426, 0x00242426, 0x00242524, 0x00242524, 0x00242523, 0x00252424, 0x00252424, 0x00272423, 0x00272421, 0x00272421, 0x00252421, 0x00242423, 0x00242423, 0x00242625, 0x00202424, 0x00202324, 0x00222526, 0x00232424, 0x001b1b1b, 0x000c0c0a, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00020202, 0x00000000, 0x00070707, 0x00383838, 0x00979797, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00666666, 0x00989898, 0x00787879, 0x0058585a, 0x003b3b3c, 0x00222224, 0x00141314, 0x000f0d0e, 0x000c0908, 0x000a0706, 0x000b0807, 0x000b0805, 0x000b0805, 0x000d0a08, 0x000f0e0c, 0x001a191d, 0x002d2e31, 0x00484a49, 0x00646563, 0x00848583, 0x00a7a8a8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a2a4a1, 0x00494448, 0x00140f14, 0x0007060a, 0x00000001, 0x00000100, 0x00000200, 0x00000000, 0x00000100, 0x00000300, 0x00000300, 0x00000001, 0x00030000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00020202, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00050505, 0x00000000, 0x00000000, 0x00030303, 0x00010101, 0x00000000, 0x00080808, 0x00262626, 0x00747474, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00625f60, 0x00130f12, 0x00050104, 0x00000001, 0x00010002, 0x00000001, 0x00000103, 0x0006090a, 0x00121715, 0x001d2220, 0x00222727, 0x001d2124, 0x001e2224, 0x001f2325, 0x001f2424, 0x001e2323, 0x001d2220, 0x001f2221, 0x00202123, 0x00212123, 0x00222023, 0x00222023, 0x00222023, 0x00212121, 0x00202220, 0x0020221e, 0x0020221e, 0x00212121, 0x00212121, 0x00222021, 0x00222120, 0x00222120, 0x00222120, 0x00212120, 0x00212120, 0x00212322, 0x00202423, 0x001f2223, 0x001d2021, 0x00212322, 0x00232323, 0x001c1b19, 0x0010100e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00030303, 0x00000000, 0x00060606, 0x00505050, 0x00a5a5a5, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00959493, 0x00626061, 0x00353233, 0x00221f20, 0x000f0d10, 0x0008090c, 0x0005080b, 0x00010508, 0x00000404, 0x00020603, 0x00000000, 0x00000000, 0x00020000, 0x00030000, 0x00020000, 0x00020000, 0x00010002, 0x00000002, 0x00000104, 0x00000201, 0x00030607, 0x000d0d0d, 0x00100c0d, 0x00150e10, 0x0030292c, 0x004f4a4c, 0x00807c80, 0x00a3a1a2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007d7d77, 0x00282821, 0x00080408, 0x00050308, 0x00000004, 0x00010204, 0x00040300, 0x00030000, 0x00000000, 0x00000000, 0x00000301, 0x00000605, 0x00080607, 0x000c0809, 0x00171516, 0x00191919, 0x001e1e1e, 0x00232323, 0x00252525, 0x00262626, 0x00242424, 0x00242424, 0x00212121, 0x001a1a1a, 0x00101010, 0x00060606, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00171717, 0x00444444, 0x009c9c9c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00747371, 0x001c1b19, 0x00000000, 0x00040304, 0x00000000, 0x00000001, 0x00000002, 0x0008090b, 0x00141818, 0x001e2122, 0x001c2121, 0x00171c1c, 0x001c1f21, 0x001c1f21, 0x001c1f21, 0x001b1f21, 0x001b2020, 0x001b2020, 0x001c2020, 0x001e1f20, 0x001f1f20, 0x00201e20, 0x00211d20, 0x00211e1f, 0x00201f1d, 0x00201f1c, 0x001f201b, 0x001e201c, 0x001e201f, 0x001e1f20, 0x001e1f20, 0x001f1f1f, 0x001f1f1f, 0x001f1f1d, 0x001f1f1d, 0x001f1f1d, 0x001d1f1e, 0x00202221, 0x00202123, 0x001b1c1d, 0x001a1a1a, 0x001e1e1e, 0x00201e1f, 0x001e1c1d, 0x00101010, 0x00040404, 0x00010101, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00020202, 0x00141414, 0x00656565, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00949496, 0x005c5a5b, 0x0030302e, 0x00191817, 0x00100c0a, 0x000e0604, 0x00080000, 0x00080000, 0x00080000, 0x000b0000, 0x00090000, 0x000b0000, 0x000c0000, 0x00100000, 0x00140000, 0x00150000, 0x00140000, 0x00140000, 0x00140000, 0x00120000, 0x000d0000, 0x000c0000, 0x00090000, 0x00080000, 0x000a0000, 0x000a0000, 0x000a0000, 0x000b0000, 0x000e0703, 0x0014100e, 0x00201f1d, 0x00404143, 0x00717475, 0x00a4a8a4, 0x00000000, 0x00000000, 0x00000000, 0x00313131, 0x005d5d5c, 0x001c1912, 0x00080500, 0x00000001, 0x00000004, 0x00000004, 0x00000000, 0x00020000, 0x00040000, 0x00080404, 0x000c0c0e, 0x00101817, 0x0018201f, 0x00242424, 0x00282826, 0x00292828, 0x00292929, 0x002b2b2b, 0x002c2c2c, 0x002d2d2d, 0x002d2d2d, 0x002c2c2c, 0x002c2c2c, 0x00282828, 0x00292929, 0x002b2b2b, 0x002b2b2b, 0x00272727, 0x001d1d1d, 0x00101010, 0x00080808, 0x00040404, 0x00000000, 0x00000000, 0x00010101, 0x00030303, 0x00000000, 0x00000000, 0x00030303, 0x00000000, 0x00050505, 0x00080808, 0x00303030, 0x00828282, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a8a3, 0x00313530, 0x00090d08, 0x00000100, 0x00000200, 0x00000000, 0x00030303, 0x000c0a0b, 0x00151414, 0x001c181c, 0x001e1a1d, 0x00201b1e, 0x00201c1f, 0x00201c1f, 0x00201c1f, 0x001d1c1e, 0x001c1c1e, 0x001c1c1e, 0x001c1c1e, 0x001c1c1e, 0x001d1c1e, 0x001f1b1e, 0x00201b1e, 0x00211a1c, 0x00211a1b, 0x00201b1b, 0x00201c19, 0x001f1c18, 0x001d1c19, 0x001c1c1e, 0x001a1d20, 0x001a1d20, 0x001c1c1e, 0x001c1c1e, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1a, 0x001c1c1b, 0x001c1c1c, 0x001c1c1c, 0x001d1d1d, 0x001d1d1d, 0x001c1c1c, 0x001a1a1a, 0x001a1a1a, 0x00111111, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x002c2c2c, 0x00868686, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00afb6b5, 0x00787c7c, 0x00404143, 0x00222222, 0x00100e0f, 0x00020000, 0x00030000, 0x00080000, 0x000b0000, 0x00100000, 0x00180000, 0x00240200, 0x00310800, 0x00421200, 0x00541d00, 0x00602504, 0x00682b06, 0x006e3009, 0x0070320b, 0x006f320a, 0x006b3109, 0x00683008, 0x00602a03, 0x00592400, 0x00491500, 0x00400e00, 0x00300300, 0x00200000, 0x00180000, 0x00150000, 0x000d0000, 0x00050000, 0x00080500, 0x00020100, 0x00040408, 0x00111216, 0x002a292d, 0x0050504f, 0x0084867d, 0x00adafa6, 0x00404342, 0x00131311, 0x00040000, 0x00050000, 0x00000001, 0x00000006, 0x00000406, 0x00000704, 0x00080802, 0x00110f0b, 0x001d181c, 0x00262227, 0x0029292b, 0x002b2c2c, 0x002b2e2d, 0x002b2e2d, 0x002c2c2c, 0x002c2c2c, 0x002b2b2b, 0x002b2b2b, 0x002a2a2a, 0x002b2b2b, 0x002b2b2b, 0x002b2b2b, 0x002c2c2c, 0x002c2c2c, 0x002b2b2b, 0x002c2c2c, 0x002c2c2c, 0x002a2a2a, 0x00272727, 0x00242424, 0x001b1b1b, 0x00111111, 0x00080808, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00080808, 0x00040404, 0x00202020, 0x00686868, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00505550, 0x000a100a, 0x00000200, 0x00000400, 0x00000100, 0x00000200, 0x00070806, 0x00131313, 0x001e1b1c, 0x00201c1f, 0x001f181c, 0x0020181c, 0x00241b20, 0x0022191e, 0x0020191d, 0x001e191c, 0x001c1a1c, 0x001c1a1c, 0x001b1b1c, 0x001a191d, 0x001b191c, 0x001d191e, 0x001d191c, 0x001e191b, 0x001e191b, 0x001e1919, 0x001d1a19, 0x001c1b18, 0x001b1b19, 0x00181c1e, 0x00181c1f, 0x00181c1e, 0x00181c1e, 0x001a1b1c, 0x001a1b1c, 0x001b1b1b, 0x001b1b1b, 0x001b1b19, 0x00191918, 0x001a1a1a, 0x001c1c1c, 0x001d1d1d, 0x001b1b1b, 0x0019191b, 0x001a1a1c, 0x00181818, 0x00181818, 0x000c0c0c, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x000b0b0b, 0x00444444, 0x00b0b0b0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a7a9, 0x00707473, 0x00383c37, 0x001c1d19, 0x00050401, 0x00050000, 0x000b0000, 0x00110000, 0x00190200, 0x00220400, 0x00421b01, 0x0058290c, 0x006f3918, 0x007f411c, 0x008a461b, 0x00964b1a, 0x009e4c19, 0x00a24c16, 0x00a84f16, 0x00aa5118, 0x00a95318, 0x00a85318, 0x00a65418, 0x00a45317, 0x00a15014, 0x009d4d11, 0x009f4e18, 0x00984a19, 0x008d451c, 0x007d3e1c, 0x00643011, 0x00461c00, 0x002e1000, 0x00230c00, 0x000e0000, 0x000a0000, 0x000b0000, 0x00080001, 0x00080004, 0x000f0a0a, 0x0022201c, 0x0032312d, 0x000a0b0c, 0x00000000, 0x00050000, 0x00070100, 0x00000003, 0x00000308, 0x0003090b, 0x000c130f, 0x001c1d19, 0x00222120, 0x0028242a, 0x002c262c, 0x002b2628, 0x00272624, 0x00222524, 0x00212624, 0x00242625, 0x00252525, 0x00262626, 0x00272727, 0x00282828, 0x00282828, 0x00292929, 0x00292929, 0x00282828, 0x00282828, 0x00272727, 0x00262626, 0x00272727, 0x00272727, 0x00262626, 0x00252525, 0x00272727, 0x00232323, 0x001c1c1c, 0x000e0e0e, 0x00010101, 0x00000000, 0x00030303, 0x00030303, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00060606, 0x00181818, 0x00595959, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007e7d81, 0x00262728, 0x00000102, 0x00020705, 0x00000300, 0x00000200, 0x00010804, 0x00090e0b, 0x00121514, 0x00191919, 0x001c181c, 0x001c171a, 0x001c1319, 0x001b1217, 0x001c1417, 0x001c1417, 0x00191418, 0x00181618, 0x0018171b, 0x0018181c, 0x0018171c, 0x0018171b, 0x0018171c, 0x0018171b, 0x0018171b, 0x0018171b, 0x0017181b, 0x0015181b, 0x0014181b, 0x0014181b, 0x0015181b, 0x0015181b, 0x0015181b, 0x0015181b, 0x0015181b, 0x00151819, 0x00171818, 0x00181818, 0x00191918, 0x00191817, 0x001a1918, 0x001a1819, 0x00181718, 0x00171518, 0x0018181c, 0x001c1c1d, 0x001c1c1c, 0x001c1c1c, 0x00141414, 0x00090909, 0x00020202, 0x00000000, 0x00010101, 0x00000000, 0x00020202, 0x00000000, 0x001c1c1c, 0x00757575, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b1bc, 0x007c787d, 0x00413c3c, 0x00201c17, 0x00090700, 0x00080400, 0x000b0000, 0x00130000, 0x00280800, 0x004b1c00, 0x006d330a, 0x00843d0b, 0x00964711, 0x00a44e14, 0x00ae561a, 0x00b35818, 0x00b85815, 0x00bb5b15, 0x00bd5a12, 0x00bc590f, 0x00bd5b10, 0x00bc5a10, 0x00b9580e, 0x00b95810, 0x00ba5910, 0x00bd5a12, 0x00be5b13, 0x00be5c11, 0x00b8560b, 0x00be5d14, 0x00ba5c1c, 0x00b0551d, 0x00a85422, 0x00a05428, 0x008b481d, 0x0070370f, 0x005c2d0c, 0x00411c02, 0x00240700, 0x00110000, 0x000c0000, 0x000a0000, 0x00080000, 0x00030000, 0x00010004, 0x00010004, 0x00030000, 0x00000000, 0x00000708, 0x00081114, 0x00111818, 0x00202420, 0x00242424, 0x00242325, 0x0024222b, 0x00242229, 0x00282122, 0x00282421, 0x00242827, 0x00242b2a, 0x00262827, 0x00272727, 0x00262626, 0x00262626, 0x00252525, 0x00242424, 0x00222222, 0x00212121, 0x00242424, 0x00242424, 0x00242424, 0x00242424, 0x00252525, 0x00262626, 0x00272727, 0x00282828, 0x00252525, 0x00212121, 0x00202020, 0x00202020, 0x001b1b1b, 0x000d0d0d, 0x00010101, 0x00000000, 0x00000000, 0x00030303, 0x00000000, 0x00080808, 0x00000000, 0x00000000, 0x001b1b1b, 0x00585858, 0x00666666, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0020201f, 0x00ada9a7, 0x007a747a, 0x00514c52, 0x002d292e, 0x00080709, 0x00000000, 0x00000100, 0x00000000, 0x00040400, 0x000c0c06, 0x0014140d, 0x00181411, 0x00160e0c, 0x00140a0a, 0x00180c0c, 0x001c0c10, 0x001a0b0c, 0x001a0e0c, 0x00190e0c, 0x00170f0d, 0x00181110, 0x00181414, 0x00181516, 0x00191617, 0x00171516, 0x00171516, 0x00171516, 0x00171516, 0x00161616, 0x00151618, 0x00131719, 0x0011181a, 0x00131719, 0x00141719, 0x00151618, 0x00151618, 0x00151619, 0x00141719, 0x00141719, 0x00151618, 0x00151716, 0x00171715, 0x00171614, 0x00161514, 0x00171614, 0x00181718, 0x00181719, 0x00161519, 0x00141317, 0x00161618, 0x00141414, 0x00161616, 0x00151515, 0x00060606, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00080808, 0x003b3b3b, 0x00adadad, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008e8c97, 0x00504c55, 0x00261d22, 0x00120704, 0x000a0000, 0x00110000, 0x00180100, 0x00331100, 0x005a2d13, 0x007b401a, 0x00944918, 0x00a95416, 0x00ba5c15, 0x00be5a10, 0x00c0580c, 0x00c05809, 0x00c15807, 0x00c45c07, 0x00c75e08, 0x00c75f07, 0x00c55d04, 0x00c86007, 0x00c76107, 0x00c76008, 0x00c8610a, 0x00c8610c, 0x00c6600a, 0x00c55e0b, 0x00c65d07, 0x00c85f06, 0x00c65c04, 0x00c35908, 0x00bf590d, 0x00bb5813, 0x00b75818, 0x00b4591b, 0x00b25c23, 0x00a0521e, 0x008e491c, 0x00743a16, 0x0058280d, 0x00371302, 0x001b0100, 0x000c0000, 0x00080000, 0x00050006, 0x00000003, 0x00040400, 0x00060a05, 0x000a1516, 0x00142022, 0x001c2020, 0x00212121, 0x00231f22, 0x00221e23, 0x001f1f28, 0x001f1f27, 0x00232020, 0x0023201d, 0x001f2020, 0x001c2020, 0x001f2020, 0x00202020, 0x00202020, 0x00202020, 0x00202020, 0x00202020, 0x00202020, 0x00202020, 0x001f1f1f, 0x00202020, 0x00212121, 0x00212121, 0x00202020, 0x00202020, 0x001f1f1f, 0x001f1f1f, 0x00202020, 0x00212121, 0x00212121, 0x00222222, 0x00202020, 0x00181818, 0x000e0e0e, 0x000a0a0a, 0x00010101, 0x00000000, 0x00020202, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00141414, 0x00676767, 0x00787878, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00060607, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009b9c9c, 0x00696b6a, 0x00404040, 0x001d1c1c, 0x00080607, 0x00020000, 0x00040000, 0x00050000, 0x00050000, 0x00080000, 0x000c0000, 0x00140400, 0x00180600, 0x001b0500, 0x001b0300, 0x001b0000, 0x001c0000, 0x001e0000, 0x001c0100, 0x001a0400, 0x00160700, 0x00140600, 0x00130500, 0x00100600, 0x00100800, 0x00110902, 0x00130b04, 0x00120c03, 0x00171008, 0x0019140c, 0x0017140c, 0x0014130f, 0x00141614, 0x00131615, 0x00111414, 0x00171516, 0x00161514, 0x00141314, 0x00141415, 0x00141418, 0x00121518, 0x00121516, 0x00141514, 0x00151514, 0x00151413, 0x00161310, 0x00161312, 0x00151414, 0x00151416, 0x00151418, 0x00141518, 0x00161618, 0x00141414, 0x00141414, 0x00141414, 0x000d0d0d, 0x00040404, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00020202, 0x001e1e1e, 0x00747474, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a7adaf, 0x006f7073, 0x00332f34, 0x000e070b, 0x000c0000, 0x000b0000, 0x00200700, 0x003c1700, 0x00642e0f, 0x008c431c, 0x00a7501f, 0x00b8581c, 0x00bc5711, 0x00ba5708, 0x00c05c08, 0x00c45d06, 0x00c8620a, 0x00c66006, 0x00c46003, 0x00c96507, 0x00cc6808, 0x00c96603, 0x00cb6700, 0x00cc6802, 0x00cc6700, 0x00cc6600, 0x00cc6a05, 0x00cc6a08, 0x00ca6808, 0x00c86709, 0x00cb680b, 0x00cc6405, 0x00cc6003, 0x00cc6407, 0x00c76408, 0x00c05f06, 0x00c05f08, 0x00c45d0c, 0x00c15808, 0x00c2570b, 0x00be550f, 0x00b9581a, 0x00a14f1a, 0x007f3e18, 0x005d2e14, 0x00301204, 0x000d0000, 0x00080004, 0x00030003, 0x000c0905, 0x00141813, 0x00132220, 0x00132121, 0x001b1e20, 0x00211d20, 0x0023181e, 0x0020181f, 0x001c1f28, 0x001b2228, 0x001c2022, 0x001c1e1d, 0x001e1e1e, 0x001f1d1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001f1f1f, 0x001f1f1f, 0x001d1d1d, 0x00191919, 0x00161616, 0x00080808, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00030303, 0x00141414, 0x00787878, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00050505, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009a9ea0, 0x00686c6e, 0x00383c3f, 0x00131617, 0x00000000, 0x00030000, 0x00050000, 0x000a0000, 0x00100200, 0x00130000, 0x00160000, 0x00250700, 0x00361100, 0x00421902, 0x004a1e05, 0x0054230c, 0x0059270e, 0x005c2910, 0x005f2b13, 0x00602c14, 0x005f2c12, 0x00552708, 0x00512707, 0x004c2407, 0x00482006, 0x00401c02, 0x00381700, 0x00301100, 0x002a0e00, 0x00200700, 0x00190300, 0x00170300, 0x00180800, 0x00180c02, 0x00140d06, 0x0014100c, 0x00171310, 0x0018100f, 0x0018100f, 0x00171310, 0x00161514, 0x00171718, 0x0014181a, 0x00121516, 0x00111214, 0x00141414, 0x00151413, 0x00161310, 0x00161310, 0x00141412, 0x00141414, 0x00141317, 0x00131417, 0x00141415, 0x00131313, 0x00141414, 0x00141414, 0x00101010, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00060606, 0x00484848, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00949894, 0x004f504e, 0x001c1816, 0x000b0000, 0x000f0000, 0x001d0300, 0x00391400, 0x00602e10, 0x00884822, 0x00a25325, 0x00b35723, 0x00bb561b, 0x00c35c19, 0x00c76016, 0x00c25f0f, 0x00c1600b, 0x00c46308, 0x00c66508, 0x00c86808, 0x00ca6a08, 0x00cc6a08, 0x00c86701, 0x00c96700, 0x00cc6c04, 0x00c96800, 0x00cc6a00, 0x00cc6b00, 0x00cc6a02, 0x00c96800, 0x00c86700, 0x00c86800, 0x00cc6804, 0x00cc6906, 0x00cc6400, 0x00c86400, 0x00c96802, 0x00c86904, 0x00cb6804, 0x00cc6404, 0x00cc5e01, 0x00cc5a00, 0x00cc5800, 0x00c85703, 0x00c05910, 0x00ae591e, 0x009a562a, 0x006d3a1d, 0x00260400, 0x000f0000, 0x00060000, 0x00100500, 0x001d1a10, 0x00101812, 0x0018211e, 0x001c1c1e, 0x001f1a1d, 0x00261a1e, 0x00241b1e, 0x00191c21, 0x00121b20, 0x00141c21, 0x001c2023, 0x00201e1f, 0x001e1b18, 0x001d1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001b1b1b, 0x001b1b1b, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001a1a1a, 0x00181818, 0x00121212, 0x000b0b0b, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00212121, 0x00888888, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00060607, 0x00060607, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a7adaf, 0x00788081, 0x003c4448, 0x000f1316, 0x00000003, 0x00000002, 0x00050100, 0x000c0000, 0x00140000, 0x001c0400, 0x002c0c00, 0x00461b04, 0x005d280d, 0x006f3110, 0x007c350f, 0x00924619, 0x009b4b19, 0x00a4501c, 0x00a9561d, 0x00ac581e, 0x00ac5c1d, 0x00ac5c1d, 0x00ac591a, 0x00b45b1a, 0x00b05817, 0x00a95317, 0x00a24f16, 0x00984914, 0x008c4310, 0x007f3a0b, 0x0074340a, 0x00682e06, 0x00572401, 0x00441800, 0x00330f00, 0x00240700, 0x00190100, 0x00170400, 0x00180906, 0x001a0b05, 0x001b0d07, 0x00190f0a, 0x00150f0c, 0x00100e0f, 0x000e0f10, 0x000f1214, 0x00141416, 0x00121212, 0x00131210, 0x0014110f, 0x00151210, 0x00141311, 0x00131313, 0x00121115, 0x00111215, 0x00111113, 0x00111111, 0x00121212, 0x00131313, 0x00111111, 0x000c0c0c, 0x00040404, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00232323, 0x009f9f9f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00878682, 0x00393933, 0x000e0b04, 0x00080000, 0x00140000, 0x00320c00, 0x00592300, 0x008c4211, 0x00a85118, 0x00b35518, 0x00b25417, 0x00a64c15, 0x009b4410, 0x009b4813, 0x00a35116, 0x00ad5a16, 0x00b76114, 0x00c16c17, 0x00c36d12, 0x00c46a0c, 0x00c26504, 0x00c86604, 0x00cc6c08, 0x00cc6b08, 0x00c46300, 0x00c76704, 0x00c76805, 0x00c56905, 0x00c66801, 0x00c96800, 0x00cc6a00, 0x00cc6b00, 0x00cc6800, 0x00c86300, 0x00cc6801, 0x00cc6b02, 0x00c66800, 0x00c86800, 0x00cc6b03, 0x00cc6602, 0x00cc6000, 0x00cc6000, 0x00cc5f00, 0x00c85c00, 0x00c86104, 0x00be5f0f, 0x00b8601e, 0x00a55324, 0x005c2000, 0x00160000, 0x00241410, 0x00220b00, 0x001e0800, 0x00170c01, 0x0018140d, 0x001c1c1a, 0x001a1718, 0x001d1414, 0x00201818, 0x001a191d, 0x0014181f, 0x00141923, 0x00171a23, 0x001a1918, 0x001c1a16, 0x001a1918, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00181818, 0x00181818, 0x00181818, 0x00191919, 0x001a1a1a, 0x00191919, 0x00181818, 0x00191919, 0x00141414, 0x000a0a0a, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00373737, 0x00a2a2a2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00919598, 0x00515859, 0x0014181a, 0x00000001, 0x00020000, 0x00080000, 0x000f0100, 0x00150000, 0x00270700, 0x00441a00, 0x005d2e0e, 0x00753c19, 0x00904e26, 0x00a5582a, 0x00b25b27, 0x00bd5c24, 0x00bb5516, 0x00c05813, 0x00c25910, 0x00c25a0d, 0x00c05a0b, 0x00c05c0a, 0x00be5c08, 0x00bf5905, 0x00c45605, 0x00c65404, 0x00c35408, 0x00c1550c, 0x00c15812, 0x00bf5a17, 0x00bc5b1c, 0x00b85b1f, 0x00af5920, 0x00a85823, 0x00964f20, 0x00804018, 0x00683112, 0x0054230c, 0x003e1202, 0x002a0500, 0x001b0000, 0x00180300, 0x00160800, 0x00140c07, 0x00140f0f, 0x00111113, 0x000e1114, 0x000c1012, 0x000e0f10, 0x00101010, 0x0011100f, 0x0013100d, 0x0011100f, 0x00101010, 0x00101012, 0x00101012, 0x00101010, 0x00101010, 0x00101010, 0x00101010, 0x00111111, 0x00101010, 0x00080808, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00020202, 0x00111111, 0x00707070, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00bab6b3, 0x007b7774, 0x0028231c, 0x000c0400, 0x000c0000, 0x001f0500, 0x00441c00, 0x0072350c, 0x009d4e18, 0x00bf5d19, 0x00c2580d, 0x00c4580b, 0x00b44e05, 0x009b4000, 0x00863500, 0x00773000, 0x00722f00, 0x00783600, 0x00824006, 0x008a490a, 0x0094500a, 0x00a96016, 0x00bb6c1b, 0x00be6811, 0x00c06409, 0x00c4670a, 0x00c76809, 0x00c6690a, 0x00c56808, 0x00c46807, 0x00c56704, 0x00c96700, 0x00cc6700, 0x00cc6500, 0x00cb6300, 0x00c66400, 0x00cb6c05, 0x00c86b02, 0x00c46600, 0x00c76902, 0x00c96a04, 0x00c96603, 0x00cc6604, 0x00cc6500, 0x00cc6400, 0x00cc6200, 0x00cc6400, 0x00c15c00, 0x00bc5909, 0x00bc5c19, 0x00964b19, 0x00320d00, 0x00331a0a, 0x00522c1c, 0x003d1705, 0x002a0c00, 0x00170200, 0x00170c05, 0x001d1813, 0x001c1511, 0x001c1614, 0x00191615, 0x0018181c, 0x00181924, 0x0014151f, 0x00141412, 0x00181914, 0x00171715, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00181818, 0x00181818, 0x00171717, 0x00161616, 0x00171717, 0x00171717, 0x00171717, 0x00161616, 0x00171717, 0x00171717, 0x00131313, 0x00090909, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00060606, 0x00010101, 0x005c5c5c, 0x00b1b1b1, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b2b4b3, 0x00787c7c, 0x00303334, 0x000e0e0e, 0x00030000, 0x00090000, 0x00140000, 0x00180000, 0x002f0900, 0x00501f00, 0x007c3c09, 0x009b5014, 0x00af5d21, 0x00b45c1d, 0x00b95a17, 0x00bc5810, 0x00c0540a, 0x00c45406, 0x00c85604, 0x00cb5703, 0x00c85602, 0x00c65500, 0x00c45700, 0x00c25802, 0x00c25904, 0x00c25804, 0x00c85806, 0x00c85707, 0x00c85708, 0x00c85508, 0x00c75409, 0x00c75409, 0x00c75409, 0x00c6560a, 0x00c25308, 0x00c1570e, 0x00be5714, 0x00b85818, 0x00b45823, 0x00ac5425, 0x0096451c, 0x00793717, 0x004c200a, 0x00301607, 0x001c0800, 0x00100300, 0x000e0805, 0x000f0f0f, 0x000c1012, 0x000a0d10, 0x000e0f10, 0x00101010, 0x0010100e, 0x0010100c, 0x00100f0d, 0x000e0e0e, 0x000f0f10, 0x000f1011, 0x000f0f0f, 0x000f0f0f, 0x000e0e0e, 0x000e0e0e, 0x00101010, 0x00101010, 0x000b0b0b, 0x00030303, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x003d3d3d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b3acaa, 0x0078706c, 0x001c1511, 0x000c0000, 0x00100000, 0x00280700, 0x00542000, 0x008c4817, 0x00b25a1c, 0x00bf5b13, 0x00c15608, 0x00c75808, 0x00c75c08, 0x00c8630f, 0x00c16414, 0x00a8550b, 0x007f3900, 0x00581c00, 0x003a0900, 0x00280000, 0x002f0b00, 0x003f1a00, 0x00623510, 0x00824c1b, 0x00985619, 0x00ad6119, 0x00bd6817, 0x00c1680e, 0x00c26408, 0x00c46404, 0x00c76404, 0x00c86403, 0x00ca6200, 0x00cc6200, 0x00cc6400, 0x00cc6704, 0x00c86807, 0x00c46807, 0x00bf6501, 0x00bf6501, 0x00c46908, 0x00c26705, 0x00c36405, 0x00cc680b, 0x00cc6407, 0x00cc6103, 0x00cc6203, 0x00cc6404, 0x00c96406, 0x00c56208, 0x00be6009, 0x00b2641c, 0x0068380a, 0x00290300, 0x006e3d27, 0x007c4831, 0x005c290f, 0x00380d00, 0x00190000, 0x001e1004, 0x001c170f, 0x00181511, 0x0016120f, 0x00171214, 0x0018141d, 0x0017141d, 0x00141615, 0x00121611, 0x00141614, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00141414, 0x00141414, 0x00131313, 0x00151515, 0x00161616, 0x00111111, 0x00070707, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00111111, 0x00818181, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a8a8a8, 0x005f6061, 0x001b1c1d, 0x00000000, 0x00050000, 0x000f0000, 0x001e0200, 0x00310700, 0x00541e00, 0x00814118, 0x00a65a25, 0x00b45816, 0x00be5a10, 0x00bf580b, 0x00bc5303, 0x00c15501, 0x00c85902, 0x00cb5900, 0x00cc5800, 0x00cb5700, 0x00cc5800, 0x00cb5a00, 0x00c85b00, 0x00c85c04, 0x00c85e07, 0x00c75e09, 0x00c45d0a, 0x00c25b09, 0x00c35c0b, 0x00c65c0e, 0x00c75c0e, 0x00c8590b, 0x00c95808, 0x00cc5706, 0x00cc5704, 0x00cc5b04, 0x00cc5702, 0x00c85504, 0x00c5560a, 0x00c15812, 0x00bd581a, 0x00ba5821, 0x00ad5c30, 0x00966347, 0x006f4e3c, 0x00442b1f, 0x001e0e05, 0x00080000, 0x00020001, 0x0006090c, 0x000b0f12, 0x000c0f11, 0x000e100f, 0x0010100e, 0x00100f0c, 0x000f0e0c, 0x000d0d0c, 0x000d0d0d, 0x000d0e10, 0x000e0e0e, 0x000e0e0e, 0x000c0c0c, 0x000c0c0c, 0x000e0e0e, 0x000f0f0f, 0x000c0c0c, 0x00060606, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x001f1f1f, 0x00b0b0b0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b5b1ae, 0x00766f6b, 0x00100702, 0x000c0100, 0x00100000, 0x00340b00, 0x00713811, 0x009c521e, 0x00b86120, 0x00c35d11, 0x00c65a06, 0x00c55701, 0x00cc6008, 0x00cc6308, 0x00c96408, 0x00c5650b, 0x00be6811, 0x00b66a20, 0x00a46428, 0x00794418, 0x00491e00, 0x00290800, 0x001b0000, 0x001a0000, 0x002d0700, 0x004c2000, 0x00743e0c, 0x00955618, 0x00ac6119, 0x00be6918, 0x00c4670e, 0x00c76407, 0x00c96203, 0x00cc6306, 0x00cc6308, 0x00c86007, 0x00c25e08, 0x00b75c08, 0x00bc6712, 0x00c06a14, 0x00c0680f, 0x00c1660c, 0x00c3650a, 0x00c46408, 0x00c46106, 0x00c56005, 0x00c76107, 0x00c86007, 0x00c45e04, 0x00c86408, 0x00c96708, 0x00c26000, 0x00bc6410, 0x00a05f24, 0x004c1600, 0x00491300, 0x00834a30, 0x00935430, 0x00753c15, 0x00441700, 0x001d0200, 0x000e0600, 0x000d0e0a, 0x0017140f, 0x0016120f, 0x00140d11, 0x00171117, 0x00161718, 0x00101312, 0x00131414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00121212, 0x00131313, 0x00131313, 0x00141414, 0x00141414, 0x00131313, 0x00131313, 0x00121212, 0x00131313, 0x00121212, 0x00131313, 0x00131313, 0x000e0e0e, 0x00060606, 0x00000000, 0x00000000, 0x00030303, 0x00000000, 0x00040404, 0x00000000, 0x00373737, 0x00a2a2a2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9c9c, 0x004c4c4d, 0x000c0c0d, 0x00020001, 0x000b0301, 0x000f0000, 0x001f0000, 0x00401100, 0x0075340c, 0x00a85722, 0x00bd6022, 0x00bc520e, 0x00c4530b, 0x00c75407, 0x00c95808, 0x00c85905, 0x00c75801, 0x00c75c00, 0x00c95f00, 0x00c75f00, 0x00cc6404, 0x00cb6606, 0x00cb6708, 0x00c9660b, 0x00c8640c, 0x00c86510, 0x00c66411, 0x00c06212, 0x00bd6718, 0x00b86518, 0x00b86115, 0x00b85e11, 0x00bb5c0e, 0x00c05c0c, 0x00c45d0a, 0x00c85f08, 0x00c45800, 0x00c55800, 0x00c55c04, 0x00c35d0b, 0x00bd5b10, 0x00b65714, 0x00ae5417, 0x00a15424, 0x00885434, 0x006f4a37, 0x00503425, 0x002e1b11, 0x00120803, 0x00030000, 0x00000104, 0x0003070a, 0x0005080b, 0x00090a0c, 0x000c0c0b, 0x000e0d0a, 0x000e0d0a, 0x000c0c0b, 0x000c0c0c, 0x000c0e0d, 0x000d0d0d, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000a0a0a, 0x00080808, 0x00000000, 0x00010101, 0x00010101, 0x00010101, 0x00000000, 0x00141414, 0x00838383, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b4b0, 0x0066625f, 0x00120b07, 0x000c0200, 0x000d0000, 0x00341303, 0x00803916, 0x00b45826, 0x00bb5f1f, 0x00b4550c, 0x00bb5702, 0x00c86006, 0x00cc6406, 0x00cb6001, 0x00cc6304, 0x00cc6404, 0x00ca6807, 0x00c06407, 0x00b96108, 0x00bc6816, 0x00bb681f, 0x00aa6024, 0x00784016, 0x00491c00, 0x00220000, 0x00160000, 0x00140000, 0x001b0200, 0x00422000, 0x00774618, 0x009e5c1f, 0x00b46218, 0x00c46611, 0x00c86308, 0x00c86109, 0x00c4630c, 0x00b95c0a, 0x00a85308, 0x009e510e, 0x00a05314, 0x00aa5614, 0x00b45b14, 0x00c05e11, 0x00c96410, 0x00cb6509, 0x00c66003, 0x00c66306, 0x00c8670c, 0x00c4640c, 0x00c3620c, 0x00c4600a, 0x00c66107, 0x00ca6303, 0x00c7630b, 0x00bf6721, 0x00904816, 0x00360000, 0x00572304, 0x00995829, 0x00a35c2a, 0x0084431c, 0x00491a02, 0x00180804, 0x0008080a, 0x000d120a, 0x0014170c, 0x00100c08, 0x00140d0c, 0x00151418, 0x00101014, 0x00111113, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00101010, 0x00101010, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00121212, 0x00111111, 0x00101010, 0x00101010, 0x00101010, 0x000c0c0c, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00090909, 0x006a6a6a, 0x000c0c0c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009b9b99, 0x00393938, 0x00070603, 0x00030000, 0x00080000, 0x00120000, 0x002c0800, 0x00612b0d, 0x00995128, 0x00b45d26, 0x00ba5613, 0x00c15408, 0x00cc5809, 0x00cc5708, 0x00c75201, 0x00c85803, 0x00cc5f05, 0x00cc6004, 0x00cc6405, 0x00cc6808, 0x00c6690a, 0x00c26a0e, 0x00bd6c14, 0x00b86a19, 0x00b4671c, 0x00b36420, 0x00b16221, 0x00af5f22, 0x00a95c20, 0x009a5518, 0x00945010, 0x00944805, 0x00984700, 0x00a44c00, 0x00b05502, 0x00bc5e0a, 0x00c26310, 0x00c26414, 0x00c06316, 0x00b95f14, 0x00b05b16, 0x00a85b1c, 0x009b521a, 0x007c3a0c, 0x00592300, 0x002d0800, 0x00200400, 0x00140000, 0x000d0000, 0x00080000, 0x00040000, 0x00000003, 0x00000004, 0x00000004, 0x00030404, 0x00090807, 0x000c0c0a, 0x000d0c0b, 0x000c0c0a, 0x000c0c0a, 0x000d0c0b, 0x000c0c0a, 0x000c0c0a, 0x000c0c0a, 0x000d0c0c, 0x000c0c0e, 0x00080c0e, 0x00070a0c, 0x00070a0c, 0x00000000, 0x00010000, 0x00000000, 0x00010000, 0x00000000, 0x000c0e0d, 0x00585858, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b0b0b0, 0x006c6967, 0x00160f09, 0x000c0000, 0x00160000, 0x00341400, 0x00854e2f, 0x00b55828, 0x00c45616, 0x00c0560d, 0x00c25c0a, 0x00cc6910, 0x00c46102, 0x00c86404, 0x00c86101, 0x00cc6404, 0x00c55d00, 0x00c56101, 0x00c86807, 0x00c46505, 0x00c36405, 0x00c5640b, 0x00c06314, 0x00b46726, 0x009a5b26, 0x00673610, 0x00300e00, 0x00120000, 0x000c0000, 0x00100000, 0x001c0000, 0x00582701, 0x00884813, 0x00b2621e, 0x00bd6415, 0x00bd600c, 0x00c1640f, 0x00c16714, 0x00b86215, 0x009b4a0a, 0x00752700, 0x006f2000, 0x00903f08, 0x00aa581c, 0x00b35c18, 0x00b86012, 0x00c16811, 0x00c06409, 0x00c06308, 0x00bc5e08, 0x00c86713, 0x00c5610c, 0x00c05a02, 0x00cc6507, 0x00c65f01, 0x00c45f0f, 0x00b76224, 0x00622500, 0x00400b00, 0x00783807, 0x00a35c27, 0x00aa5d2c, 0x00904f29, 0x004c2515, 0x001a0800, 0x000a0400, 0x00131204, 0x00141004, 0x00130d08, 0x00121014, 0x000e0d14, 0x00100f10, 0x0010100e, 0x0010100e, 0x00101010, 0x000f1010, 0x000f1011, 0x000f1011, 0x000f1011, 0x00101010, 0x00101010, 0x00100f10, 0x00100f10, 0x00101010, 0x00101010, 0x00101010, 0x000f1010, 0x00101010, 0x00101010, 0x00101010, 0x00101010, 0x000f0f0f, 0x000f0f0f, 0x000f0f0f, 0x00101010, 0x000f0f0f, 0x00111111, 0x00101010, 0x000e0e0e, 0x000f0f0f, 0x000f0f0f, 0x00080808, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00040404, 0x00323232, 0x00949494, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009e9c9d, 0x002a2c27, 0x00040600, 0x00020000, 0x000a0000, 0x00190000, 0x00401000, 0x00803a1a, 0x00b4592b, 0x00bf581c, 0x00c0540d, 0x00c45506, 0x00c45804, 0x00c45a03, 0x00c25a02, 0x00c96409, 0x00c76407, 0x00cb6809, 0x00cc6909, 0x00ca6608, 0x00ca690d, 0x00bf6812, 0x00b36b1d, 0x00a16824, 0x00946430, 0x007a4d24, 0x00603415, 0x004e2107, 0x003b0c00, 0x00360700, 0x00320300, 0x00380000, 0x00550f00, 0x00833200, 0x00ab5304, 0x00bb610b, 0x00bb6410, 0x00b8651b, 0x00b26528, 0x00a55d2c, 0x00914f24, 0x00733913, 0x004a1b00, 0x00260200, 0x00110000, 0x000d0000, 0x00060000, 0x00050000, 0x00090000, 0x00090000, 0x00050000, 0x00020000, 0x00000001, 0x00000003, 0x00000000, 0x00000000, 0x00010000, 0x00070506, 0x0009090b, 0x000a080b, 0x000e0806, 0x00100807, 0x00100908, 0x000f0807, 0x000e0805, 0x000c0808, 0x00080a0e, 0x00050c14, 0x00040c14, 0x00040b10, 0x00020403, 0x00030000, 0x00050100, 0x00020000, 0x00000100, 0x00060908, 0x00262825, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00555455, 0x00727071, 0x00130e0e, 0x000b0000, 0x001c0000, 0x00421300, 0x00975224, 0x00b45921, 0x00c25414, 0x00c8540c, 0x00cc5c08, 0x00c75c01, 0x00c86409, 0x00c46307, 0x00c66508, 0x00c46004, 0x00c86005, 0x00c96007, 0x00c86007, 0x00c66205, 0x00c46401, 0x00c46402, 0x00c56008, 0x00c4600a, 0x00c0610b, 0x00b66012, 0x00b16c2c, 0x00855022, 0x00401a02, 0x001c0300, 0x00100000, 0x000e0000, 0x00170000, 0x00370e00, 0x00703810, 0x00a56027, 0x00b8661c, 0x00bf630e, 0x00c46007, 0x00c46008, 0x00c25f12, 0x00b96020, 0x007a3202, 0x00440800, 0x003d0b00, 0x00623008, 0x00945c24, 0x00a5621c, 0x00b46514, 0x00b96108, 0x00c2620a, 0x00c6600b, 0x00c45d08, 0x00c66008, 0x00c86307, 0x00c35d00, 0x00c75f04, 0x00be6315, 0x00974f1d, 0x004d1200, 0x00460e00, 0x00854617, 0x00ab5c22, 0x00b05d24, 0x009c5128, 0x00642b0c, 0x00250400, 0x00140300, 0x00140a00, 0x000e0c04, 0x00101014, 0x000c0b10, 0x00100c09, 0x00100c07, 0x000d0c09, 0x000c0e0c, 0x000b0e0f, 0x000a0e10, 0x000b0f12, 0x000c0f11, 0x000d0d0f, 0x000e0c0d, 0x00100c0d, 0x00100c0c, 0x000e0d0c, 0x000d0d0c, 0x000c0e0d, 0x000b0e0d, 0x000c0e0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000e0e0e, 0x000f0f0f, 0x000d0d0d, 0x00090909, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00030303, 0x006e6e6e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a9a7ae, 0x00202022, 0x00040500, 0x00030000, 0x000f0100, 0x001c0000, 0x00552204, 0x00984e25, 0x00b45824, 0x00c55818, 0x00c75308, 0x00c85300, 0x00c75500, 0x00c55a01, 0x00c76105, 0x00c86404, 0x00cc6c0a, 0x00c76a08, 0x00c3680a, 0x00c16812, 0x00c36e1e, 0x00b86c26, 0x00985818, 0x006e3a05, 0x00431a00, 0x00240200, 0x001c0000, 0x001d0000, 0x001e0000, 0x00260000, 0x003c0c00, 0x00683310, 0x0092542b, 0x00b36838, 0x00b26429, 0x00b1611b, 0x00b86b20, 0x00ae6925, 0x00985b23, 0x006d3814, 0x004c1c04, 0x002a0000, 0x00190000, 0x00130000, 0x000d0000, 0x00040000, 0x00000004, 0x00000004, 0x00000001, 0x00060000, 0x00080000, 0x00080000, 0x00070000, 0x00050000, 0x00050000, 0x00080000, 0x000c0000, 0x000b0000, 0x00080000, 0x00080000, 0x000f0807, 0x00100a08, 0x000c0506, 0x000e0909, 0x000f0a0a, 0x000d0907, 0x000a0706, 0x0006090c, 0x00060c12, 0x00040c13, 0x0001080e, 0x00030404, 0x00000000, 0x00020000, 0x00020000, 0x00000000, 0x00000100, 0x00191b18, 0x00aeb2ad, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0078787a, 0x001d1c1b, 0x00080000, 0x00190000, 0x004a1800, 0x00934c1d, 0x00b75a1c, 0x00c35810, 0x00ca570a, 0x00c85200, 0x00cc5c03, 0x00cc6204, 0x00c35e04, 0x00c05f04, 0x00c5650b, 0x00c46307, 0x00c76107, 0x00c96008, 0x00c96009, 0x00c86007, 0x00c56101, 0x00c56101, 0x00c66008, 0x00c86008, 0x00c96101, 0x00c66306, 0x00bb6113, 0x00b06325, 0x009c5f34, 0x00623318, 0x00240300, 0x00140000, 0x000e0000, 0x00100000, 0x00210400, 0x00512601, 0x009c5d26, 0x00b4641c, 0x00bd5d05, 0x00cb6308, 0x00c45b04, 0x00c16418, 0x00af612a, 0x00874a20, 0x004b1c00, 0x00220000, 0x00330900, 0x005b2b00, 0x0094571b, 0x00b06622, 0x00bc641a, 0x00bd5e0e, 0x00c86110, 0x00c45c05, 0x00be5800, 0x00c96406, 0x00c55e00, 0x00c56411, 0x00b56428, 0x00753407, 0x003b0400, 0x00531b00, 0x00904a17, 0x00ac5b21, 0x00b25821, 0x009e4c1c, 0x006c300e, 0x00270100, 0x000e0000, 0x00131008, 0x0006080c, 0x000b0d13, 0x000f0c0b, 0x000f0c08, 0x000d0c09, 0x000c0d0b, 0x000a0d0e, 0x000a0e10, 0x000a0e10, 0x000b0e10, 0x000d0d0f, 0x000e0c0d, 0x00100c0d, 0x00100c0d, 0x000e0c0d, 0x000d0d0d, 0x000b0e0d, 0x000b0e0d, 0x000c0e0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000e0e0e, 0x000d0d0d, 0x000c0c0c, 0x000d0d0d, 0x000e0e0e, 0x000d0d0d, 0x000c0c0c, 0x00090909, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00404040, 0x009b9b9b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a8abad, 0x001d2124, 0x00000004, 0x00080303, 0x00100000, 0x00200000, 0x006c310d, 0x009e4f1b, 0x00b95815, 0x00c25709, 0x00c65501, 0x00c75600, 0x00c85c04, 0x00ca5f06, 0x00cb6207, 0x00cc6808, 0x00cc6b02, 0x00c86700, 0x00c66804, 0x00c57019, 0x00ae6523, 0x00844c1a, 0x00562c0c, 0x002c0d00, 0x001a0000, 0x00190000, 0x00180000, 0x00270000, 0x004a1a00, 0x00763d0c, 0x009d5a20, 0x00b06221, 0x00b76018, 0x00b85f18, 0x00b76225, 0x00b46931, 0x00a4642f, 0x00804b1c, 0x00522803, 0x00301000, 0x001d0400, 0x00100000, 0x000b0000, 0x00080000, 0x00070000, 0x00040000, 0x00030000, 0x00040000, 0x00080000, 0x000c0000, 0x00100000, 0x00120000, 0x00120000, 0x00100000, 0x00100000, 0x00110000, 0x001a0000, 0x001a0000, 0x001e0000, 0x00200200, 0x00180100, 0x000c0000, 0x00060304, 0x00080a10, 0x0004080d, 0x0005080c, 0x000a0a0c, 0x000c0b09, 0x00080804, 0x00050403, 0x00060807, 0x000a0d0e, 0x00040708, 0x00000000, 0x00000000, 0x00030200, 0x00000000, 0x00000000, 0x000f0f0f, 0x008c8e8d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00858d8e, 0x00283434, 0x00000000, 0x00110000, 0x00481a00, 0x008d4114, 0x00bd5f25, 0x00bd5613, 0x00c35508, 0x00cc5b07, 0x00cb5b00, 0x00c95f00, 0x00c76104, 0x00c15c04, 0x00c4600a, 0x00c6620a, 0x00c25d04, 0x00c66004, 0x00c86006, 0x00ca5e08, 0x00ca5e08, 0x00ca5f06, 0x00c85f06, 0x00c46008, 0x00c46007, 0x00c45b00, 0x00c96004, 0x00c8600b, 0x00c45e10, 0x00bd5f17, 0x00ac5c20, 0x007d3d13, 0x003b0f00, 0x00130000, 0x000d0300, 0x00050000, 0x00140600, 0x00431f00, 0x00905424, 0x00b8641b, 0x00be5d08, 0x00c46409, 0x00bf6209, 0x00bd6213, 0x00b4611d, 0x0099521c, 0x00602500, 0x00280000, 0x00200000, 0x00310d00, 0x005d2f10, 0x00985628, 0x00b86326, 0x00c15e11, 0x00c96008, 0x00cb6205, 0x00c45d00, 0x00c35c04, 0x00be5b0b, 0x00bd641f, 0x00a45720, 0x00581d00, 0x00310000, 0x005b2809, 0x0090512b, 0x00ae5a25, 0x00b95e24, 0x00a34f1a, 0x00682b01, 0x00250800, 0x00070000, 0x0006080e, 0x00040c13, 0x00080c0f, 0x00090c0d, 0x000b0c0d, 0x000b0c0c, 0x000b0c0c, 0x000b0c0a, 0x000c0c0a, 0x000c0c0c, 0x000c0b0c, 0x000c0b0c, 0x000c0b0d, 0x000c0c0d, 0x000c0c0d, 0x000b0c0c, 0x000b0c0c, 0x000b0c0a, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000b0b0b, 0x000b0b0b, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000b0b0b, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00121212, 0x00737373, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a8a9ab, 0x002a3032, 0x00040909, 0x00040301, 0x000c0000, 0x00250100, 0x006c3313, 0x00a75423, 0x00bc5615, 0x00c45405, 0x00c95800, 0x00c75b00, 0x00c45c00, 0x00c56103, 0x00ca6609, 0x00cc680a, 0x00cc6909, 0x00c66702, 0x00c56b09, 0x00be6814, 0x00a25917, 0x006c380b, 0x00341100, 0x00100000, 0x000a0000, 0x00130000, 0x00200200, 0x00431800, 0x007d481a, 0x00a06227, 0x00a55f19, 0x00b16218, 0x00bd6819, 0x00bc6416, 0x00bc681f, 0x00a35820, 0x00743609, 0x00461800, 0x002c0800, 0x001c0000, 0x00140000, 0x00100000, 0x000e0000, 0x000d0000, 0x000f0000, 0x00100000, 0x00160000, 0x001e0500, 0x00280b00, 0x002f0c00, 0x00391500, 0x00481f00, 0x00532808, 0x005c3010, 0x0064381a, 0x006f4024, 0x00774528, 0x007c4624, 0x00844925, 0x0091542c, 0x0090572f, 0x006d3e1e, 0x003a1700, 0x00140200, 0x00090300, 0x0008080c, 0x0003070c, 0x00040408, 0x00060606, 0x000d0906, 0x000e0b04, 0x000c0804, 0x00070602, 0x00060807, 0x00000203, 0x00000001, 0x00030102, 0x00040000, 0x00030000, 0x0009080a, 0x00656468, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009ca1a6, 0x00384143, 0x00000601, 0x000d0700, 0x003c1500, 0x00854116, 0x00b85920, 0x00c05410, 0x00c3570d, 0x00c95c0b, 0x00ca5d04, 0x00cc6102, 0x00c05b00, 0x00c36004, 0x00c5610c, 0x00c56310, 0x00bf5a08, 0x00c45f09, 0x00c46005, 0x00c75f04, 0x00ca5d05, 0x00cb5c07, 0x00cb5c07, 0x00c95d08, 0x00c46008, 0x00c46007, 0x00c95e04, 0x00ca5c03, 0x00c75803, 0x00cb5d08, 0x00c85e0a, 0x00c15f12, 0x00b05d1e, 0x00894a1c, 0x00442004, 0x00120100, 0x00050300, 0x00040000, 0x00150100, 0x00401600, 0x00904e19, 0x00b6631c, 0x00b8600a, 0x00bc6004, 0x00c05f06, 0x00bf600e, 0x00b9611c, 0x00a0561f, 0x0067300c, 0x00310900, 0x00160000, 0x00200000, 0x00451600, 0x007c3c12, 0x00ac5b1f, 0x00bd6015, 0x00be5c08, 0x00c45f09, 0x00c45f0b, 0x00c15c0b, 0x00bd5b10, 0x00ba6223, 0x008b4719, 0x003e0a00, 0x002b0300, 0x00582810, 0x00954c22, 0x00b25821, 0x00b9591b, 0x00a3511c, 0x00572a0c, 0x00140000, 0x00070204, 0x00080c13, 0x00050b11, 0x00050b10, 0x00070b0d, 0x000a0c0b, 0x000b0c08, 0x000b0a06, 0x000b0a06, 0x000a0906, 0x000c0b09, 0x000b0b0b, 0x000b0a0e, 0x000a0b0e, 0x000a0b0e, 0x000a0b0c, 0x000a0c0b, 0x000b0b09, 0x000a0a0a, 0x000a0a0a, 0x000a0a0a, 0x000a0a0a, 0x000a0a0a, 0x000a0a0a, 0x000a0a0a, 0x000a0a0a, 0x000b0b0b, 0x000a0a0a, 0x00090909, 0x00090909, 0x000a0a0a, 0x000a0a0a, 0x000a0a0a, 0x000a0a0a, 0x00080808, 0x00020202, 0x00010101, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00535353, 0x00b0b0b0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00434344, 0x00444448, 0x0003070c, 0x00000000, 0x000c0000, 0x00250600, 0x0069310a, 0x00a25220, 0x00b75014, 0x00c6550f, 0x00c95607, 0x00c85b03, 0x00c46203, 0x00c36804, 0x00c46b06, 0x00c86c08, 0x00cc6606, 0x00c56207, 0x00bc6a16, 0x00b46e26, 0x008e4f18, 0x00501f00, 0x00220600, 0x000c0000, 0x00060000, 0x00120400, 0x00240300, 0x00653310, 0x00985823, 0x00b06622, 0x00b3651a, 0x00b46618, 0x00ba6b22, 0x00ac6320, 0x00985c20, 0x00693807, 0x003e1400, 0x002a0600, 0x001e0000, 0x00180000, 0x00200000, 0x00350b00, 0x00411200, 0x004c1a00, 0x005a2804, 0x0069370c, 0x00784211, 0x00844813, 0x008e4c17, 0x00944e17, 0x009d541a, 0x00a2581c, 0x00a55a20, 0x00a5581f, 0x00a4561d, 0x00a8551e, 0x00aa571e, 0x00af561c, 0x00b85b1c, 0x00b95818, 0x00b85713, 0x00b75b1a, 0x00b05f25, 0x0094501f, 0x00582701, 0x00200000, 0x000a0000, 0x00080708, 0x0008090c, 0x00040507, 0x00070400, 0x000f0903, 0x00100800, 0x00090400, 0x00040403, 0x00000404, 0x00000001, 0x00000001, 0x00030000, 0x00060000, 0x00080408, 0x003c3c40, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b2b3b7, 0x00484d54, 0x00101414, 0x00060000, 0x002b0f00, 0x00783b11, 0x00b0571e, 0x00c05410, 0x00c95609, 0x00c85c08, 0x00c65e06, 0x00c46002, 0x00c05e00, 0x00c05c03, 0x00c5630e, 0x00bc5b0a, 0x00b75709, 0x00b8580c, 0x00c66415, 0x00c25e06, 0x00c55d02, 0x00ca5c00, 0x00cc5b01, 0x00cc5a07, 0x00c95c07, 0x00c45f06, 0x00c45f04, 0x00c95b04, 0x00cc5c07, 0x00c85d0b, 0x00c86110, 0x00c15c10, 0x00bb580d, 0x00be6014, 0x00ab5b16, 0x008c501a, 0x004e2803, 0x00100000, 0x000c0400, 0x000a0000, 0x00140000, 0x00411600, 0x008b4d20, 0x00b1601c, 0x00ba5d0c, 0x00c05f0b, 0x00c3620e, 0x00b85808, 0x00b45c17, 0x00a65b23, 0x00703309, 0x00380d00, 0x00220000, 0x00190000, 0x002c0900, 0x005b2908, 0x00925020, 0x00b86224, 0x00bd5c14, 0x00bc5a08, 0x00c5600d, 0x00c3580c, 0x00bc5815, 0x00ac5c24, 0x006d3008, 0x00280300, 0x00280400, 0x00622910, 0x00954822, 0x00bc5e24, 0x00b15718, 0x008e4d1b, 0x00512707, 0x00110000, 0x000c070c, 0x00040810, 0x00030912, 0x0005090c, 0x00080a09, 0x000a0905, 0x000c0904, 0x000b0801, 0x000a0802, 0x000a0906, 0x00090909, 0x0008090c, 0x0008090c, 0x0008090c, 0x0008090b, 0x00090909, 0x00090908, 0x00090909, 0x00090909, 0x00090909, 0x00090909, 0x00090909, 0x00090909, 0x00090909, 0x00090909, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00090909, 0x00090909, 0x00080808, 0x00080808, 0x00090909, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00313131, 0x00909090, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0067666a, 0x0008070b, 0x00010004, 0x000e0200, 0x001a0000, 0x00643408, 0x00a2571d, 0x00b85815, 0x00c55510, 0x00c95409, 0x00c65406, 0x00c15901, 0x00c16604, 0x00c57008, 0x00c46e04, 0x00c46a04, 0x00cb6809, 0x00c46916, 0x00b06c2c, 0x007c4819, 0x00401700, 0x00190000, 0x000c0000, 0x00060000, 0x000b0000, 0x002a1000, 0x00734118, 0x00a15c23, 0x00bb671d, 0x00bc620d, 0x00bd640e, 0x00c06c1a, 0x00ac5c18, 0x00823f04, 0x004b1800, 0x00350c00, 0x002d0700, 0x003b1600, 0x00532c11, 0x00673b1c, 0x0079441a, 0x00874a1c, 0x00934f1c, 0x009c531b, 0x00a1581c, 0x00a75b1b, 0x00ab5b16, 0x00b05c15, 0x00b85d17, 0x00bc5e18, 0x00bb5f18, 0x00ba5e15, 0x00bb5c14, 0x00ba5910, 0x00be5a12, 0x00c35b14, 0x00c35a12, 0x00c4560d, 0x00c45204, 0x00cc5808, 0x00cc5704, 0x00c05002, 0x00bc560d, 0x00b85f1d, 0x009c5018, 0x0071380d, 0x00280700, 0x00130400, 0x00090100, 0x00080607, 0x00070604, 0x00040200, 0x00090200, 0x000f0901, 0x00060502, 0x00040504, 0x00000001, 0x00000000, 0x00030000, 0x00060103, 0x00050308, 0x001c1c23, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0067686b, 0x00171819, 0x00060000, 0x00270a00, 0x00642f0b, 0x00a85520, 0x00bf5815, 0x00c45309, 0x00cc5b09, 0x00c85c05, 0x00bf5b00, 0x00bf6001, 0x00bd6006, 0x00c16415, 0x00b75810, 0x00a04200, 0x00ac4d05, 0x00be5f15, 0x00bd5c0c, 0x00c25c07, 0x00c45c01, 0x00c85c00, 0x00c85b00, 0x00c95a06, 0x00c85c08, 0x00c35e05, 0x00c35e05, 0x00c85e0d, 0x00c1590c, 0x00ba590f, 0x00b65810, 0x00ac4d07, 0x00ac4b02, 0x00bb5806, 0x00bb5e0d, 0x00b16219, 0x00975921, 0x00583110, 0x00160000, 0x000e0000, 0x000c0000, 0x001c0200, 0x003c1000, 0x00914e1c, 0x00b5611f, 0x00b65b0e, 0x00bd5c09, 0x00c7610f, 0x00c36011, 0x00bc601a, 0x00a3541c, 0x00793c13, 0x00340900, 0x00140000, 0x00190400, 0x001f0300, 0x00401800, 0x0084441c, 0x00ae5f28, 0x00b86018, 0x00c05d0f, 0x00c55809, 0x00c2560c, 0x00bf601e, 0x009a501e, 0x004f2003, 0x00220000, 0x002b0000, 0x0060250e, 0x00984818, 0x00b05a20, 0x00b26429, 0x008a4b1d, 0x00401700, 0x00100000, 0x00080409, 0x0003060f, 0x0006070a, 0x00080806, 0x000b0803, 0x000b0800, 0x000a0800, 0x00090701, 0x00080804, 0x00070808, 0x0007080b, 0x0005080b, 0x0007080b, 0x00080809, 0x00080708, 0x00080806, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00090909, 0x00090909, 0x00090909, 0x00080808, 0x00080808, 0x00070707, 0x00080808, 0x00040404, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00121212, 0x00707070, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0088898c, 0x00151419, 0x00070205, 0x000c0000, 0x00180000, 0x00613008, 0x009c551a, 0x00b4590c, 0x00c45908, 0x00c45205, 0x00cc590e, 0x00cc6315, 0x00c8640e, 0x00c76b07, 0x00c46c00, 0x00bd6700, 0x00c06702, 0x00c46910, 0x00b86824, 0x00784319, 0x00371501, 0x00100000, 0x00080000, 0x00080000, 0x00100200, 0x00381b00, 0x00754410, 0x00a05916, 0x00b86110, 0x00cb660c, 0x00c86102, 0x00c25f04, 0x00b35808, 0x008c3b00, 0x00661f00, 0x006a2a00, 0x00743806, 0x00824515, 0x008e4d1b, 0x0098531c, 0x00a6591c, 0x00b3601c, 0x00ba631a, 0x00bb6015, 0x00ba5f12, 0x00b85c10, 0x00b95c0f, 0x00bd5f12, 0x00c15f14, 0x00c05b10, 0x00ba560e, 0x00b85a14, 0x00bb5c17, 0x00c05c12, 0x00c25a0d, 0x00c4590c, 0x00c85a0d, 0x00c6580c, 0x00c35406, 0x00c55203, 0x00ca5503, 0x00cc5704, 0x00c95705, 0x00c55a0c, 0x00c15b12, 0x00b75814, 0x00a5541a, 0x00753810, 0x003c1400, 0x00110000, 0x000a0100, 0x000c0c0e, 0x00040808, 0x00030200, 0x00080602, 0x00080602, 0x00080602, 0x00000000, 0x00020100, 0x00020001, 0x00030105, 0x00040309, 0x00090c11, 0x00acb1b1, 0x00000000, 0x00000000, 0x00000000, 0x007a7a7c, 0x001f1f1d, 0x00100a02, 0x001b0300, 0x005b2200, 0x00a04c1a, 0x00bd581a, 0x00c4550e, 0x00c75c10, 0x00c55c0b, 0x00c75f07, 0x00c46005, 0x00bc5f06, 0x00ba6214, 0x00a95419, 0x008c3804, 0x00903900, 0x00ac5310, 0x00c26014, 0x00bc5404, 0x00c45b06, 0x00c45b04, 0x00c45c01, 0x00c35d03, 0x00c35c07, 0x00c25c08, 0x00c25d05, 0x00c05d0a, 0x00b4550d, 0x00bc6322, 0x00a85316, 0x008e3c00, 0x009e4807, 0x00b85d14, 0x00bf5c0a, 0x00c4600c, 0x00b75804, 0x00b46016, 0x00915015, 0x005c2d05, 0x00240600, 0x00100000, 0x00080000, 0x00120000, 0x00481800, 0x00934f21, 0x00b46020, 0x00bb5b0f, 0x00c45d0a, 0x00be5401, 0x00ba5207, 0x00c0601d, 0x00ab5920, 0x007d3e11, 0x003b1400, 0x00110000, 0x000c0000, 0x00110000, 0x00351501, 0x00693817, 0x00a25b24, 0x00b85d17, 0x00c55b0a, 0x00cb5908, 0x00c65b0d, 0x00b45818, 0x007f3e14, 0x003f1100, 0x00170000, 0x00260400, 0x00511e02, 0x008e4a1f, 0x00ac5922, 0x00a8571f, 0x00824115, 0x00320700, 0x00110000, 0x00080306, 0x00090404, 0x000a0603, 0x000b0702, 0x00090700, 0x00080800, 0x00060700, 0x00070804, 0x00060807, 0x00060708, 0x00060708, 0x00070708, 0x00070708, 0x00080607, 0x00080607, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00070707, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00070707, 0x00070707, 0x00070707, 0x00070707, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00010101, 0x00020202, 0x00545454, 0x000c0c0c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a0a3a5, 0x00343438, 0x00010004, 0x00080000, 0x00160000, 0x004f1f04, 0x0094501c, 0x00b35b15, 0x00bf5603, 0x00c75500, 0x00cc5b07, 0x00ca5c09, 0x00ca610c, 0x00c8650a, 0x00c96a04, 0x00c46900, 0x00c16b06, 0x00c07014, 0x00af6319, 0x00894b16, 0x00341000, 0x00110000, 0x00090001, 0x00060000, 0x000c0000, 0x00351800, 0x00754210, 0x00a8611c, 0x00c36918, 0x00c25e01, 0x00c95e00, 0x00ca5d00, 0x00c86004, 0x00be5c0c, 0x00a44d0c, 0x009a4a0e, 0x00a15317, 0x00ab5b1e, 0x00b46122, 0x00ba6320, 0x00bb6017, 0x00bb5c0e, 0x00bf5c09, 0x00c35d08, 0x00c15b04, 0x00c35d08, 0x00c35f0a, 0x00c05b08, 0x00bf5808, 0x00c0580a, 0x00c4590c, 0x00c15a11, 0x00a24404, 0x00ac5010, 0x00bc5914, 0x00c25910, 0x00c4570a, 0x00c45607, 0x00c55708, 0x00c45605, 0x00c85908, 0x00c85705, 0x00ca5503, 0x00cb5604, 0x00c85604, 0x00c45407, 0x00c4560b, 0x00bd5916, 0x00b05a24, 0x007c3a10, 0x00401400, 0x00180000, 0x00060000, 0x00000406, 0x00020508, 0x00050706, 0x00050401, 0x00060400, 0x00020000, 0x00040100, 0x00000001, 0x00000004, 0x0000030a, 0x0002040a, 0x00989b9a, 0x00000000, 0x00000000, 0x009e9697, 0x00343331, 0x000c0800, 0x00100000, 0x00482000, 0x00964a17, 0x00b75112, 0x00ca5711, 0x00cb570c, 0x00c3580c, 0x00c05a09, 0x00c35d08, 0x00be5d09, 0x00b86316, 0x00ab5b1c, 0x00803206, 0x006c1c00, 0x009b480f, 0x00b85c18, 0x00c0590c, 0x00c85d0b, 0x00c45a08, 0x00c45b06, 0x00c15c02, 0x00bf5e04, 0x00bf5c08, 0x00bf5d0c, 0x00bc5e10, 0x00b95e17, 0x00b26020, 0x00873600, 0x00883700, 0x00a04d11, 0x00b05814, 0x00bc5e14, 0x00c05b0b, 0x00c05702, 0x00c65d07, 0x00ba5804, 0x00b66017, 0x009c561d, 0x005b2c0a, 0x001e0200, 0x00080000, 0x000a0000, 0x001d0000, 0x00552205, 0x0098511e, 0x00b7601d, 0x00bd5a0c, 0x00c55c0b, 0x00c75c0c, 0x00c0570e, 0x00b85815, 0x00a7581e, 0x00763f11, 0x003a1800, 0x00120200, 0x00080000, 0x000f0100, 0x00260c00, 0x0067340f, 0x00a35820, 0x00be5f15, 0x00c45804, 0x00c45301, 0x00c25b12, 0x00ac5924, 0x006e3210, 0x002d0b00, 0x00130000, 0x00240400, 0x004c1c01, 0x00843c0e, 0x00b1602a, 0x00a15520, 0x006c3108, 0x001a0000, 0x000f0000, 0x000e0200, 0x000c0400, 0x000a0601, 0x00080801, 0x00050802, 0x00050703, 0x00050704, 0x00050704, 0x00060606, 0x00060606, 0x00070506, 0x00070506, 0x00070508, 0x00070506, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00070707, 0x00050505, 0x00080808, 0x00000000, 0x00010101, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00404040, 0x00a9a9a9, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b1b5b8, 0x005a5c60, 0x0009080c, 0x00060000, 0x00100000, 0x00401100, 0x008a4618, 0x00b0571d, 0x00bb540d, 0x00cc5a0a, 0x00cc5902, 0x00cc5c02, 0x00cc6406, 0x00ca6401, 0x00cc6a04, 0x00c96500, 0x00c36604, 0x00bc6a16, 0x00ac6824, 0x00814b1a, 0x003c1800, 0x000e0000, 0x000e0400, 0x00080000, 0x00100000, 0x003d1800, 0x007e471b, 0x00ac5f21, 0x00bc6014, 0x00c5600a, 0x00c35a00, 0x00c85e00, 0x00cc6105, 0x00c65c06, 0x00c05b08, 0x00bf5f11, 0x00c06015, 0x00c05c12, 0x00c56015, 0x00c25c0f, 0x00bf5a08, 0x00c35d09, 0x00c46008, 0x00c25c04, 0x00c25c04, 0x00c45d06, 0x00c15c08, 0x00bf5a08, 0x00c0590a, 0x00c1590b, 0x00c05608, 0x00c25505, 0x00c25b11, 0x009a4007, 0x00863000, 0x00a64b10, 0x00bb5a19, 0x00bf580e, 0x00c15607, 0x00c65c0b, 0x00c15706, 0x00c1590b, 0x00c15607, 0x00ca5807, 0x00cb5500, 0x00cc5400, 0x00cc5301, 0x00c65003, 0x00c95812, 0x00bc5210, 0x00b65b23, 0x00843f14, 0x00411200, 0x00180300, 0x00080506, 0x0000040a, 0x00000409, 0x00000404, 0x00040300, 0x00020000, 0x00020000, 0x00000000, 0x00000003, 0x00000005, 0x0004060a, 0x00838182, 0x00000000, 0x00b9b1b8, 0x004c4549, 0x000c0805, 0x000c0000, 0x00381a00, 0x007b440e, 0x00af5713, 0x00c95c0f, 0x00c74f01, 0x00cc5508, 0x00cc5e11, 0x00bd5709, 0x00c05c0e, 0x00b55c14, 0x00b0672e, 0x00743306, 0x00510a00, 0x007d3007, 0x00b05619, 0x00c05e14, 0x00c25807, 0x00c85b09, 0x00c2580a, 0x00c05a09, 0x00bf5e04, 0x00be5e04, 0x00bc5c09, 0x00b95d14, 0x00ad581d, 0x009f501a, 0x00762c00, 0x00863800, 0x009f490b, 0x00b55613, 0x00c05c11, 0x00c25c0e, 0x00c05a0c, 0x00c1590b, 0x00c15807, 0x00c45d0a, 0x00c05b09, 0x00b55d18, 0x00985423, 0x0052270a, 0x00120000, 0x00080000, 0x00110000, 0x00240200, 0x005d2a05, 0x00a05a23, 0x00b05c17, 0x00bc5c10, 0x00c35b10, 0x00c3580e, 0x00c05a11, 0x00b85c18, 0x00a2581a, 0x0076400d, 0x00361400, 0x000f0000, 0x00080000, 0x00080000, 0x00240800, 0x0061300a, 0x00a2551a, 0x00ba5b10, 0x00c65909, 0x00c45708, 0x00b95816, 0x009a4e1b, 0x00582608, 0x001d0000, 0x00100000, 0x00200600, 0x00461600, 0x0083431a, 0x00ac622c, 0x00985424, 0x00461a01, 0x001c0000, 0x00120000, 0x000c0000, 0x000c0803, 0x00050704, 0x00010604, 0x00000807, 0x00020504, 0x00040503, 0x00060504, 0x00080404, 0x00080404, 0x00080405, 0x00060407, 0x00050507, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00050505, 0x00050505, 0x00040404, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x002d2d2d, 0x008b8b8b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x001f2020, 0x00858b90, 0x001f1e22, 0x00080000, 0x000d0000, 0x00270200, 0x007c3b0f, 0x00b05a1e, 0x00c35e1b, 0x00c35409, 0x00c95402, 0x00cc5800, 0x00cc6004, 0x00cb6707, 0x00c86907, 0x00c16708, 0x00c0680f, 0x00b8681c, 0x00985518, 0x00673409, 0x00361500, 0x00100000, 0x000a0000, 0x00080000, 0x00160200, 0x00442000, 0x0081471b, 0x00aa5c24, 0x00bd5f19, 0x00c75d0d, 0x00cc6008, 0x00c95d00, 0x00c75c01, 0x00c55c04, 0x00c45c08, 0x00c7600e, 0x00c5600c, 0x00c05906, 0x00ca5d0c, 0x00c45504, 0x00c45a08, 0x00c6600a, 0x00c05a06, 0x00bf5904, 0x00c45e08, 0x00c75e08, 0x00c35903, 0x00c25904, 0x00c05908, 0x00c25a0d, 0x00c45c10, 0x00c45b0c, 0x00c25805, 0x00bc570b, 0x00ac521a, 0x00792700, 0x00702000, 0x009d4c17, 0x00b15819, 0x00b85810, 0x00be5808, 0x00c25b0a, 0x00bf590c, 0x00bc5508, 0x00c45707, 0x00c55300, 0x00cc5100, 0x00cc5402, 0x00ca5206, 0x00cb540c, 0x00cc550f, 0x00c35514, 0x00b2541c, 0x00843e14, 0x00401700, 0x00110000, 0x00010004, 0x0000080f, 0x00000408, 0x00040504, 0x00020100, 0x00000000, 0x00000100, 0x00000102, 0x00000204, 0x00000406, 0x00626063, 0x007b787b, 0x00646168, 0x00181115, 0x000c0000, 0x002e1300, 0x006a3808, 0x00a05817, 0x00bb5b0d, 0x00c45300, 0x00cc5907, 0x00cc5403, 0x00c55508, 0x00c35c13, 0x00b95e18, 0x00ac5f24, 0x00743811, 0x00430c00, 0x005f1c00, 0x009d4c1a, 0x00b85a14, 0x00c35c0b, 0x00cb5e0e, 0x00c45707, 0x00c45b0c, 0x00bf5a0a, 0x00bc5c04, 0x00bb5f0a, 0x00b86018, 0x00ad581e, 0x00893c10, 0x00681c00, 0x00803600, 0x009d4c0e, 0x00ba5d18, 0x00c25c12, 0x00c05708, 0x00c3580a, 0x00c3580c, 0x00c1570b, 0x00c35808, 0x00c65a06, 0x00c55803, 0x00be580b, 0x00af5c1d, 0x00894c1f, 0x0047230a, 0x00130000, 0x000c0000, 0x00100000, 0x00300c00, 0x006d390e, 0x00a35c23, 0x00b8601c, 0x00ba570f, 0x00c45c10, 0x00bc5409, 0x00c35f14, 0x00b75c14, 0x00a05517, 0x00733c0c, 0x00300d00, 0x000a0000, 0x00080001, 0x000a0000, 0x00230600, 0x00602b03, 0x009f551b, 0x00bb5c16, 0x00c0580c, 0x00c05910, 0x00b65c1c, 0x008c481b, 0x00512408, 0x00140000, 0x00120000, 0x00200000, 0x00441700, 0x008a4c21, 0x009e5f32, 0x00784729, 0x002b0600, 0x00180000, 0x00100000, 0x00050100, 0x00000303, 0x00000507, 0x0000080a, 0x00010606, 0x00040504, 0x00070401, 0x00080401, 0x00080401, 0x00080405, 0x00050507, 0x00050507, 0x00040406, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00050505, 0x00040404, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00202020, 0x007b7b7b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a0a7ab, 0x0045494c, 0x00030000, 0x000f0000, 0x001a0000, 0x005c280a, 0x00ab5720, 0x00be5812, 0x00c25308, 0x00c85604, 0x00cc5d05, 0x00cc6105, 0x00ca670d, 0x00c06811, 0x00ba6c1b, 0x00a8641c, 0x00985a20, 0x00774518, 0x004b2406, 0x00260c00, 0x000e0000, 0x00080100, 0x00080000, 0x001a0600, 0x004a2300, 0x00864b12, 0x00b46425, 0x00c1631d, 0x00c35c13, 0x00cb5e0e, 0x00c85a01, 0x00cb5d00, 0x00c95e05, 0x00c55c08, 0x00c35c0d, 0x00c45e0f, 0x00c45d08, 0x00c05801, 0x00c85c08, 0x00c15807, 0x00bb5908, 0x00b85b0c, 0x00b4580d, 0x00b8590e, 0x00c05a0c, 0x00c45707, 0x00c95804, 0x00c95804, 0x00c75809, 0x00c3580c, 0x00bf580e, 0x00c05a0e, 0x00c15c09, 0x00ba580b, 0x00b75a20, 0x00914014, 0x00501000, 0x00581e00, 0x0089481b, 0x00a85a20, 0x00b5560c, 0x00bf5808, 0x00be580b, 0x00bc570b, 0x00c0590e, 0x00c25408, 0x00c75002, 0x00cc5406, 0x00c8540c, 0x00c6510c, 0x00cc560e, 0x00c85109, 0x00c95914, 0x00b85a1f, 0x007c3a12, 0x003c1400, 0x00120400, 0x00000105, 0x00000206, 0x00000406, 0x00010200, 0x00000000, 0x00000000, 0x00000400, 0x00000403, 0x00000203, 0x004e4d52, 0x00838389, 0x0020232a, 0x00080100, 0x00210500, 0x00602c08, 0x009e5318, 0x00b85c14, 0x00bf5808, 0x00c55701, 0x00cc5905, 0x00cc5704, 0x00c85508, 0x00be5914, 0x00ac6023, 0x007c4216, 0x003a0e00, 0x00310200, 0x00803808, 0x00b65d1c, 0x00be5909, 0x00c35703, 0x00cb6012, 0x00c1560a, 0x00c4590a, 0x00c05908, 0x00b85909, 0x00b35c14, 0x009e501c, 0x00772d06, 0x00651c00, 0x00762901, 0x00a85318, 0x00b45810, 0x00c15c0c, 0x00c45b0b, 0x00c3580c, 0x00c3540c, 0x00c3580c, 0x00c45809, 0x00c75906, 0x00c75804, 0x00c95804, 0x00c05605, 0x00b8580d, 0x00ae5f1e, 0x00834416, 0x00401500, 0x00110000, 0x000a0000, 0x00100000, 0x00341100, 0x007b4313, 0x00a75c1f, 0x00b85c16, 0x00be5a10, 0x00be580e, 0x00c45c11, 0x00bd5708, 0x00bb5c12, 0x00aa581c, 0x006a3005, 0x00270800, 0x000b0000, 0x000a0200, 0x00080000, 0x00200700, 0x00613516, 0x00974f1c, 0x00b55c18, 0x00bc550a, 0x00be580e, 0x00b0581b, 0x00844012, 0x00411700, 0x00130000, 0x000d0000, 0x001c0500, 0x00461f07, 0x00805033, 0x00926245, 0x0050250c, 0x001d0000, 0x00130100, 0x00040000, 0x00000406, 0x0000060b, 0x0000050a, 0x00000407, 0x00040404, 0x00080401, 0x00090300, 0x00080401, 0x00070403, 0x00040406, 0x00040406, 0x00040406, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00111111, 0x00686868, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0073787d, 0x0016171a, 0x000d0100, 0x00190000, 0x003e0f00, 0x00954f27, 0x00bb581b, 0x00c25108, 0x00c55605, 0x00ca5e08, 0x00c76008, 0x00c3640e, 0x00bc6818, 0x00aa631b, 0x0092571c, 0x00714013, 0x00502908, 0x002b0d00, 0x00150000, 0x000f0000, 0x00080000, 0x000a0000, 0x00200800, 0x00562e07, 0x00905317, 0x00af6019, 0x00bd6014, 0x00c15c10, 0x00c35b10, 0x00c85e10, 0x00c55c05, 0x00c45c04, 0x00c45d08, 0x00c45e0c, 0x00c25c10, 0x00bf590c, 0x00c25904, 0x00c55c04, 0x00c65a06, 0x00c15a08, 0x00bc5e10, 0x00ad560c, 0x009c4804, 0x00a64d0c, 0x00bb5917, 0x00bf560e, 0x00c55708, 0x00c85604, 0x00c75809, 0x00c3580a, 0x00bc540b, 0x00bc570b, 0x00c05b08, 0x00bc590b, 0x00bb5917, 0x00b15c2b, 0x00682d0e, 0x00300000, 0x00522000, 0x00844518, 0x00ad5818, 0x00b8570e, 0x00bb570c, 0x00bc560c, 0x00c05910, 0x00c2580f, 0x00c25206, 0x00c55107, 0x00c4540d, 0x00c5520c, 0x00c85109, 0x00cb5308, 0x00ca5206, 0x00c45610, 0x00af561f, 0x007a3c15, 0x00361403, 0x000c0000, 0x00050000, 0x00030304, 0x00030301, 0x00000000, 0x00000000, 0x00000200, 0x00010300, 0x00000000, 0x00282c2e, 0x0028292d, 0x0008080a, 0x00150500, 0x004c1d02, 0x0092491c, 0x00b95816, 0x00c6590a, 0x00c45705, 0x00c85a05, 0x00cb5604, 0x00c85407, 0x00c75812, 0x00b05517, 0x00884b1b, 0x00411700, 0x00220000, 0x00562408, 0x009e5319, 0x00ba5c10, 0x00c05805, 0x00c25602, 0x00c3580c, 0x00c2580d, 0x00c15809, 0x00bc5a0d, 0x00af5a17, 0x00924810, 0x00642300, 0x00500f00, 0x00752b08, 0x00ac5829, 0x00be611d, 0x00be5909, 0x00bc5403, 0x00c05605, 0x00c5580b, 0x00c5580c, 0x00c4570a, 0x00c55708, 0x00c75805, 0x00c45402, 0x00c85808, 0x00c45908, 0x00bc5608, 0x00bb5f16, 0x00ae591b, 0x00864617, 0x00391700, 0x00140400, 0x000c0000, 0x00180000, 0x004a2000, 0x00864718, 0x00b46023, 0x00b85611, 0x00c05910, 0x00c0560c, 0x00c15405, 0x00c0580d, 0x00b85916, 0x009f531c, 0x00643211, 0x001e0100, 0x000b0000, 0x00090301, 0x00060000, 0x00210c00, 0x00643410, 0x00a35925, 0x00b85916, 0x00bd560c, 0x00be5b13, 0x00a75215, 0x007e4118, 0x00391200, 0x00130000, 0x000f0000, 0x00170000, 0x0041200c, 0x007a5036, 0x00785037, 0x00290c00, 0x00130100, 0x00040000, 0x00020609, 0x0000080c, 0x00000308, 0x00000407, 0x00040404, 0x00070300, 0x00080200, 0x00070300, 0x00040402, 0x00030405, 0x00010405, 0x00030404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00090909, 0x00585858, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009ca0a2, 0x003b3f44, 0x00060302, 0x00150000, 0x00280000, 0x00783711, 0x00b05826, 0x00c45616, 0x00c55309, 0x00c55c0b, 0x00c0620d, 0x00b86410, 0x00b0681b, 0x00965719, 0x00713c0e, 0x00471d00, 0x00280800, 0x00140000, 0x000d0000, 0x000d0000, 0x00140000, 0x00200800, 0x003e1c02, 0x006b370c, 0x0098541a, 0x00bb6820, 0x00bd6213, 0x00bd5c0b, 0x00c05f10, 0x00c06114, 0x00bc5f12, 0x00bd5f0f, 0x00ba5c0a, 0x00bc5c0b, 0x00bf5d0e, 0x00bf5b10, 0x00c05a0c, 0x00c55b08, 0x00c95c07, 0x00c85b06, 0x00c05704, 0x00c06214, 0x00b45c14, 0x008d3b00, 0x00863200, 0x00a34a13, 0x00b8591e, 0x00bb570f, 0x00bd5507, 0x00c25708, 0x00c55809, 0x00c3570d, 0x00c0560a, 0x00bf5806, 0x00bf5806, 0x00c55a0e, 0x00b45718, 0x00905027, 0x004c1c00, 0x002a0000, 0x004b1700, 0x008d4514, 0x00ae5618, 0x00b85712, 0x00bc550c, 0x00bc550c, 0x00bf560e, 0x00c0540c, 0x00c1530a, 0x00c4540a, 0x00c65408, 0x00c45108, 0x00cb580b, 0x00cc5404, 0x00c85306, 0x00c45a16, 0x00a8531c, 0x006c310d, 0x00361000, 0x00140000, 0x00080000, 0x00040304, 0x00020304, 0x00000000, 0x00000000, 0x00000100, 0x00000000, 0x00040807, 0x00020100, 0x000c0000, 0x00320f00, 0x00803d18, 0x00b85a23, 0x00c3520c, 0x00cc5808, 0x00cb5908, 0x00c05203, 0x00c85a0d, 0x00bc5410, 0x00b4581d, 0x00904818, 0x00471e00, 0x001d0000, 0x00300200, 0x0087471e, 0x00ac5c1a, 0x00b85b0c, 0x00c05c0c, 0x00c05908, 0x00be5609, 0x00c0580d, 0x00be5a10, 0x00ad5413, 0x008c4414, 0x00581d00, 0x003c0800, 0x006c2d0e, 0x00ab5624, 0x00b95819, 0x00b9550b, 0x00c05a0b, 0x00c25a0f, 0x00c05509, 0x00c35606, 0x00c75808, 0x00c85707, 0x00c45202, 0x00c8590a, 0x00c05504, 0x00be5706, 0x00c05a0c, 0x00bc580f, 0x00bc5810, 0x00bc580f, 0x00b15a18, 0x007d4410, 0x003c1900, 0x00170200, 0x000e0000, 0x00250700, 0x00582509, 0x009b4e20, 0x00b7571a, 0x00c05410, 0x00c3530c, 0x00c75812, 0x00c25a15, 0x00b75614, 0x00b45f20, 0x009b5219, 0x00592400, 0x00170000, 0x000c0000, 0x00040403, 0x00040000, 0x002f1301, 0x00703a1b, 0x00a45321, 0x00bb5a19, 0x00bd5a0d, 0x00b85a0e, 0x00a8581c, 0x007d3d16, 0x00370d00, 0x00140000, 0x00140000, 0x00160000, 0x00452410, 0x00785541, 0x00432a1a, 0x00150700, 0x00040000, 0x00000204, 0x0000060b, 0x00000207, 0x00020306, 0x00040203, 0x00060200, 0x00080100, 0x00050200, 0x00030301, 0x00010405, 0x00010405, 0x00020403, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00040404, 0x00030303, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x004c4c4c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0075797c, 0x00101216, 0x00050000, 0x001b0000, 0x004b1400, 0x00a55324, 0x00bc5719, 0x00c75510, 0x00c25308, 0x00c06114, 0x00b5681c, 0x009b5c18, 0x0076430a, 0x004b1c00, 0x002b0300, 0x001d0000, 0x00180000, 0x001b0200, 0x00240c00, 0x00311300, 0x00411c00, 0x00602f0b, 0x00884c1f, 0x00ab5e20, 0x00b86118, 0x00c06012, 0x00c35e0c, 0x00c45f0c, 0x00c15f0c, 0x00bc5f10, 0x00b86013, 0x00a75106, 0x00a65208, 0x00b35c14, 0x00bc6319, 0x00bc5c11, 0x00bf590c, 0x00c85b0b, 0x00c75805, 0x00c65805, 0x00c45a08, 0x00bc5a0b, 0x00b85d17, 0x00a45118, 0x007b2b00, 0x00722300, 0x00974514, 0x00b05a1c, 0x00b85c14, 0x00bd580a, 0x00c05606, 0x00c7580d, 0x00c6570b, 0x00c25506, 0x00c35606, 0x00c55706, 0x00b8540c, 0x00a95d27, 0x007d441d, 0x00320600, 0x00270000, 0x004f1800, 0x008c4419, 0x00b1581e, 0x00bd5916, 0x00bb530c, 0x00bc540c, 0x00c05810, 0x00c0560c, 0x00c45507, 0x00c35304, 0x00c45509, 0x00c05004, 0x00ca5506, 0x00cc5708, 0x00c55308, 0x00c05916, 0x00a34f1a, 0x006d3009, 0x002b0600, 0x000f0000, 0x00030000, 0x00000307, 0x00000104, 0x00000000, 0x00020200, 0x00020000, 0x00000100, 0x000d0400, 0x00240400, 0x006c3311, 0x00ad5627, 0x00bf5415, 0x00c95208, 0x00cc5605, 0x00ca5503, 0x00c35607, 0x00bf5a14, 0x00b55c23, 0x00954e21, 0x00572402, 0x00180000, 0x00170000, 0x00632903, 0x00a45824, 0x00b15914, 0x00bc5c0f, 0x00c05a0b, 0x00c05809, 0x00c15c0e, 0x00b85a12, 0x00aa581a, 0x00843d0d, 0x00491100, 0x00340100, 0x005e2708, 0x009b5628, 0x00bb5f1e, 0x00bb5408, 0x00be5609, 0x00c1590c, 0x00c45a10, 0x00c3580a, 0x00c45504, 0x00c45501, 0x00c55605, 0x00c45607, 0x00c35808, 0x00c05809, 0x00bc5909, 0x00bb580c, 0x00bb5811, 0x00ba5712, 0x00be5810, 0x00ba5d19, 0x00aa6023, 0x007d4515, 0x00462003, 0x001c0000, 0x00160000, 0x002c0400, 0x006b2f0d, 0x00a45423, 0x00ba5818, 0x00c45710, 0x00c3540d, 0x00c2550f, 0x00bc5814, 0x00b85a14, 0x00b15914, 0x00995018, 0x004c1c00, 0x00130000, 0x00040000, 0x00010000, 0x000e0000, 0x00371302, 0x007e3d1b, 0x00ac5821, 0x00b7580e, 0x00bb5809, 0x00b95b14, 0x00a8541d, 0x007b391b, 0x00401202, 0x00160000, 0x00100000, 0x00180000, 0x00442818, 0x00503c30, 0x0020130c, 0x00090502, 0x00000000, 0x00000406, 0x00000305, 0x00030105, 0x00040102, 0x00050000, 0x00050000, 0x00040301, 0x00030303, 0x00000403, 0x00000404, 0x00020403, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00020202, 0x00030303, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00484848, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a0a2a1, 0x004a4d4e, 0x00000004, 0x00090000, 0x00300a00, 0x007d3c17, 0x00b5571d, 0x00c65810, 0x00c45608, 0x00bf5c0f, 0x00b26320, 0x008c511a, 0x00582e06, 0x002b0b00, 0x00170000, 0x00200000, 0x002b0500, 0x00401400, 0x00512100, 0x006a3401, 0x00884a0f, 0x00a05819, 0x00b16020, 0x00bc631e, 0x00c46213, 0x00c35e0c, 0x00bf590c, 0x00c25c0c, 0x00c45d0a, 0x00c05a03, 0x00bc5904, 0x00bc6110, 0x00994802, 0x00853900, 0x00904608, 0x00ac601c, 0x00b75f13, 0x00ba5808, 0x00c45908, 0x00c55706, 0x00c35606, 0x00c85d0e, 0x00bb5304, 0x00b85810, 0x00bc632c, 0x00904115, 0x00601b00, 0x00612100, 0x00894712, 0x00a45b18, 0x00b45c10, 0x00b95404, 0x00c55509, 0x00c8540a, 0x00c55108, 0x00c65608, 0x00c05301, 0x00c15b0a, 0x00b95b14, 0x00a1541c, 0x00642d10, 0x002a0400, 0x00200000, 0x004d1d0a, 0x008f431c, 0x00b4561e, 0x00be5410, 0x00c05209, 0x00c0580f, 0x00bd560b, 0x00c05504, 0x00c05402, 0x00c45808, 0x00b94e02, 0x00c05308, 0x00c5560a, 0x00c45104, 0x00cc590c, 0x00c35b16, 0x00a04a14, 0x00592200, 0x00240600, 0x00050000, 0x00000008, 0x00000106, 0x00000001, 0x00040100, 0x00060100, 0x00050000, 0x00170000, 0x00561c00, 0x00a45224, 0x00be5820, 0x00c0510b, 0x00cb580c, 0x00c85603, 0x00c45200, 0x00c75d0f, 0x00ae5514, 0x00985424, 0x005b2e10, 0x00200300, 0x00100000, 0x00331000, 0x00955021, 0x00b45c1b, 0x00b65812, 0x00bf590f, 0x00c55507, 0x00c35405, 0x00bf5d0e, 0x00a55615, 0x00753f19, 0x00441904, 0x00230000, 0x00491500, 0x0098511e, 0x00b35e18, 0x00b35402, 0x00c35d0b, 0x00c45d12, 0x00c0560c, 0x00c15304, 0x00c65706, 0x00c65704, 0x00c25403, 0x00c05606, 0x00c15c0c, 0x00bb5508, 0x00bc5808, 0x00c05c0c, 0x00c05a0e, 0x00b95811, 0x00b75b1a, 0x00ac551e, 0x009c4a15, 0x00aa5621, 0x00ae5e2c, 0x008c4621, 0x00581e04, 0x002c0100, 0x001d0000, 0x00371200, 0x006e3b16, 0x00a4571c, 0x00b95810, 0x00c05001, 0x00c55001, 0x00c5570e, 0x00bc550e, 0x00b85810, 0x00b36024, 0x00874720, 0x00390f00, 0x00140000, 0x00090000, 0x00050000, 0x00180200, 0x004f1f08, 0x008c481c, 0x00b05818, 0x00bc5a10, 0x00c25b11, 0x00ba5613, 0x00b25824, 0x0086401b, 0x003a0f00, 0x001c0200, 0x00100000, 0x00140200, 0x0034261e, 0x001f140e, 0x000c0604, 0x00040100, 0x00020001, 0x00020003, 0x00040004, 0x00040004, 0x00050002, 0x00040102, 0x00020202, 0x00010302, 0x00000402, 0x00000402, 0x00010302, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00010101, 0x00030303, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00484848, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0080807e, 0x0020201e, 0x00020000, 0x00140000, 0x00471700, 0x00a35626, 0x00bc5414, 0x00c6550d, 0x00bf5c14, 0x00b35f1e, 0x00884914, 0x00471700, 0x00230000, 0x00280500, 0x003c1400, 0x0058290e, 0x00804922, 0x009d5f2c, 0x00a86325, 0x00b1641f, 0x00b86518, 0x00b85f0f, 0x00bf600e, 0x00c15d08, 0x00c15b03, 0x00c45f09, 0x00c15d13, 0x00bd5a12, 0x00c15b0c, 0x00c15c08, 0x00c05c05, 0x00b95f0c, 0x00a35410, 0x00652200, 0x005d2200, 0x008d4d1b, 0x00ae5f1e, 0x00b65a10, 0x00c05a09, 0x00c55905, 0x00c55708, 0x00c45808, 0x00c45a0a, 0x00bc580e, 0x00b45719, 0x00ac5828, 0x00823b18, 0x00480c00, 0x00572000, 0x00884b14, 0x00ab5e1b, 0x00b4570c, 0x00c2560c, 0x00c75409, 0x00c25006, 0x00c55509, 0x00c45506, 0x00c35606, 0x00c05306, 0x00b85818, 0x00914c24, 0x00431500, 0x001a0000, 0x001c0000, 0x005e250c, 0x009c4c20, 0x00b85618, 0x00bd500c, 0x00bd540e, 0x00bb5209, 0x00bf5404, 0x00c25504, 0x00c05405, 0x00c05509, 0x00c1550d, 0x00c1530a, 0x00c45205, 0x00c95607, 0x00c8580a, 0x00bc5814, 0x00904415, 0x00481700, 0x000e0000, 0x00010005, 0x00000204, 0x00000000, 0x00010000, 0x00070000, 0x00110000, 0x002e0600, 0x0095491b, 0x00bc581d, 0x00c0520c, 0x00ca580c, 0x00c75708, 0x00c45506, 0x00c45808, 0x00b95a12, 0x009f5521, 0x006b3715, 0x00220400, 0x00100000, 0x00200300, 0x00653518, 0x00ad5c23, 0x00bb5810, 0x00be5610, 0x00be520a, 0x00ca570a, 0x00c2570b, 0x00af5814, 0x008a4c1a, 0x00401e0a, 0x00150000, 0x002c0600, 0x00753c1c, 0x00ab5918, 0x00bc5c08, 0x00c05a06, 0x00be5705, 0x00bb5408, 0x00c1570c, 0x00c65809, 0x00c75505, 0x00c65406, 0x00c45608, 0x00c05808, 0x00bc5705, 0x00be5c09, 0x00b95608, 0x00bc5911, 0x00b95a18, 0x00ab541a, 0x009c4f1e, 0x00783812, 0x00531000, 0x00984110, 0x00b4561f, 0x00b65a28, 0x009f4e24, 0x0062280d, 0x002e0400, 0x001c0000, 0x003c1800, 0x00844819, 0x00ac5817, 0x00c3580c, 0x00ca5504, 0x00c55508, 0x00c0540a, 0x00bc5810, 0x00b45818, 0x00ac5c27, 0x0072350e, 0x00320d00, 0x00100000, 0x00050000, 0x00080000, 0x001e0000, 0x005d2b0a, 0x009c521c, 0x00b45a17, 0x00bc540c, 0x00c4560f, 0x00c05412, 0x00b45822, 0x00904f29, 0x00441800, 0x00270500, 0x00110000, 0x000e0000, 0x00100801, 0x00040000, 0x00050404, 0x00000001, 0x00020204, 0x00040001, 0x00040001, 0x00040004, 0x00010004, 0x00010204, 0x00000302, 0x00000402, 0x00000302, 0x00010302, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00010101, 0x00030303, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00494949, 0x00313131, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009b9c9f, 0x005a5956, 0x00040000, 0x000a0300, 0x00220800, 0x0074360c, 0x00b45a20, 0x00c65811, 0x00bf5311, 0x00ac5c2a, 0x007f421a, 0x003c0a00, 0x00280000, 0x004a1800, 0x00763b14, 0x00a15726, 0x00b76529, 0x00b8621a, 0x00bc6214, 0x00bc6110, 0x00bc600c, 0x00be600c, 0x00c0620d, 0x00be6309, 0x00bc6106, 0x00c06208, 0x00bc5f0c, 0x00b85c19, 0x00b75a1c, 0x00ba5816, 0x00b8550b, 0x00b85704, 0x00b85e0c, 0x00ac5f1a, 0x00763a06, 0x002e0300, 0x00451800, 0x00904d22, 0x00b05d20, 0x00bc5e0c, 0x00c05700, 0x00c65402, 0x00c85405, 0x00bf5807, 0x00bd5a0d, 0x00b8540c, 0x00bc5c1e, 0x00ad592b, 0x006f2a04, 0x00380200, 0x004e1c00, 0x00894814, 0x00ae5d1f, 0x00b6550e, 0x00c3580c, 0x00c05407, 0x00c05205, 0x00c6550c, 0x00c34f06, 0x00cc540b, 0x00c35613, 0x00ad531c, 0x007a3a13, 0x002e0e00, 0x00100000, 0x00290800, 0x00662e11, 0x00ac5528, 0x00bc541a, 0x00c05115, 0x00c1500f, 0x00c3540b, 0x00c05105, 0x00c05407, 0x00c15408, 0x00c3520c, 0x00c3510c, 0x00c2540c, 0x00c2570b, 0x00c35808, 0x00c15a10, 0x00b85a20, 0x007e3811, 0x00300e01, 0x00080000, 0x00040000, 0x00030200, 0x00000006, 0x000a0000, 0x00200000, 0x00753811, 0x00ad5516, 0x00c3590b, 0x00c85300, 0x00cc5805, 0x00c65407, 0x00c0560d, 0x00b65410, 0x00ac5d27, 0x00703b19, 0x00300c00, 0x00140000, 0x00190000, 0x00421300, 0x009e5b28, 0x00b05712, 0x00c1590c, 0x00c45309, 0x00c9530b, 0x00cb570e, 0x00b95515, 0x00985426, 0x0050260b, 0x00130000, 0x00120000, 0x00441c01, 0x00945423, 0x00b45912, 0x00bc5404, 0x00c2580f, 0x00c0550e, 0x00bf570a, 0x00bc5408, 0x00c1530a, 0x00c5540c, 0x00c4540c, 0x00c35408, 0x00c25600, 0x00c05600, 0x00c15802, 0x00be580c, 0x00b4571b, 0x00a65627, 0x00874424, 0x00481400, 0x001e0000, 0x002f0200, 0x00a0501e, 0x00b45111, 0x00bc5411, 0x00bb591c, 0x00a45425, 0x006f3313, 0x00360e00, 0x00200000, 0x00501d01, 0x00914d22, 0x00b85b1d, 0x00c2560e, 0x00c45406, 0x00c25307, 0x00c05910, 0x00b95611, 0x00b55411, 0x00ad5c26, 0x00582909, 0x00200700, 0x00080000, 0x00060000, 0x000d0000, 0x00280800, 0x006a3609, 0x00a75d21, 0x00b65812, 0x00c0520b, 0x00c64f07, 0x00c3530f, 0x00b45c20, 0x00a05927, 0x00662b07, 0x002e0400, 0x00140000, 0x000b0400, 0x00000000, 0x00000406, 0x00000507, 0x00000201, 0x00020100, 0x00040000, 0x00020007, 0x00000008, 0x00000204, 0x00000301, 0x00000200, 0x00010100, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00020202, 0x00010101, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004b4b4b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00909296, 0x003b3734, 0x00070000, 0x000f0000, 0x003c1800, 0x009c5422, 0x00b85818, 0x00c0510b, 0x00bf591a, 0x008c4317, 0x00420800, 0x00430b00, 0x007f4418, 0x00a6622f, 0x00b26429, 0x00bd621c, 0x00bf5d0e, 0x00c15d05, 0x00c46005, 0x00c46005, 0x00c25e06, 0x00bd5c08, 0x00bb5e0d, 0x00b66111, 0x00b46214, 0x00aa5b10, 0x00b26320, 0x00ac5d27, 0x0094420d, 0x00852a00, 0x00963800, 0x00b15202, 0x00b95e0f, 0x00af5f1a, 0x0080420f, 0x003f1701, 0x00200000, 0x00481300, 0x00935025, 0x00a75817, 0x00be6316, 0x00c4580c, 0x00c8580c, 0x00ba5404, 0x00c05a0b, 0x00c45a0c, 0x00b9510b, 0x00b2541a, 0x009d5022, 0x00592300, 0x002d0000, 0x00461300, 0x008a491c, 0x00ad5a20, 0x00b1510c, 0x00bd580a, 0x00c05405, 0x00c05008, 0x00c8540c, 0x00ca530b, 0x00c4500c, 0x00bc5718, 0x00a15320, 0x005b3010, 0x001c0200, 0x00140000, 0x00401802, 0x00843e19, 0x00b45827, 0x00b74d14, 0x00c35212, 0x00c0500a, 0x00c3550a, 0x00c05408, 0x00c05308, 0x00c4500b, 0x00c4500c, 0x00c0530e, 0x00be560b, 0x00c25807, 0x00c35808, 0x00bc500f, 0x00ac5423, 0x005f2c14, 0x00180000, 0x000c0000, 0x00050000, 0x00030001, 0x00100000, 0x004e1b00, 0x00a05420, 0x00b85911, 0x00cb5d08, 0x00cc5601, 0x00c44f00, 0x00c7580d, 0x00b95514, 0x00b25f26, 0x00804318, 0x003b1500, 0x00160000, 0x00120000, 0x00280300, 0x007a3b0d, 0x00af5d1c, 0x00bc5b12, 0x00c15608, 0x00c45005, 0x00c45006, 0x00c4540d, 0x00b2571e, 0x00723b1a, 0x002c0e00, 0x000c0000, 0x00190400, 0x00592800, 0x00a4571c, 0x00bf5b11, 0x00c15206, 0x00c15410, 0x00be5410, 0x00bd550a, 0x00c3580c, 0x00c4540c, 0x00c2510b, 0x00c2520c, 0x00c1530a, 0x00c15403, 0x00c35804, 0x00bb5405, 0x00b75b18, 0x009b4f22, 0x00682d11, 0x002c0300, 0x00190000, 0x00120000, 0x002f0b00, 0x00a85a26, 0x00be5812, 0x00c1530a, 0x00bd530a, 0x00b9591b, 0x00aa5a28, 0x00773c1c, 0x00441400, 0x00300000, 0x00632707, 0x00a15120, 0x00b65618, 0x00bc530b, 0x00c5580c, 0x00bc540c, 0x00bd540c, 0x00c3570d, 0x00b45515, 0x00905026, 0x003d1600, 0x00180300, 0x00080000, 0x000b0200, 0x000f0000, 0x003b1900, 0x007e4817, 0x00b05b1c, 0x00bc510c, 0x00cc540b, 0x00c74e05, 0x00bc540c, 0x00b05614, 0x00af5d2a, 0x008a4a23, 0x00421d00, 0x000e0000, 0x00080000, 0x00030301, 0x00000303, 0x00000606, 0x00020100, 0x00040000, 0x00010008, 0x0000000b, 0x00000305, 0x00000301, 0x00020100, 0x00040000, 0x00020100, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00020202, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004d4d4d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x006d6e71, 0x00181210, 0x000b0000, 0x001b0100, 0x00572806, 0x00ac5d28, 0x00bb5a19, 0x00bd5817, 0x00a24204, 0x00550600, 0x00732900, 0x00a9591c, 0x00b6611c, 0x00b45c10, 0x00c16617, 0x00c26513, 0x00bc5e09, 0x00be5e06, 0x00c05f06, 0x00c45f07, 0x00c35e0c, 0x00bc5f14, 0x00b5601e, 0x00ac602a, 0x00a66333, 0x008c4d26, 0x00632802, 0x00440600, 0x005e1800, 0x009a480f, 0x00b85e1b, 0x00ba5a0e, 0x00ba5a0e, 0x00b75e17, 0x009b5019, 0x00562707, 0x001c0000, 0x001d0000, 0x00380d00, 0x008b5433, 0x00a05c2c, 0x00af581c, 0x00bb5c14, 0x00bf580b, 0x00c45908, 0x00c15206, 0x00c0540b, 0x00c55e1b, 0x00ae581d, 0x00854618, 0x00481800, 0x001e0000, 0x00441900, 0x0090502a, 0x00a6541c, 0x00ba580d, 0x00c05605, 0x00be5408, 0x00c2560c, 0x00be4e08, 0x00be4f0b, 0x00bd5414, 0x00b15820, 0x0085481b, 0x00431a00, 0x00170000, 0x001b0000, 0x00511f00, 0x00995024, 0x00b4541b, 0x00c35715, 0x00bc4f0a, 0x00bf530b, 0x00be5408, 0x00c05207, 0x00c54f08, 0x00c54f0a, 0x00c0500a, 0x00bf5406, 0x00c25504, 0x00c35405, 0x00c5540e, 0x00bf5920, 0x0090481e, 0x00431600, 0x00120000, 0x000c0000, 0x00100000, 0x00280300, 0x0089471c, 0x00b45c1f, 0x00c05b10, 0x00c55706, 0x00cb5605, 0x00c85508, 0x00bd5512, 0x00b25920, 0x00924e20, 0x004a1c00, 0x00140000, 0x000e0000, 0x001c0000, 0x004e1f05, 0x00a85c27, 0x00b85714, 0x00bf5712, 0x00bf520c, 0x00c0540b, 0x00c0550b, 0x00bc560f, 0x00a7541d, 0x004d2006, 0x00120000, 0x000c0000, 0x002a0c00, 0x007c3808, 0x00b65715, 0x00c75810, 0x00c35307, 0x00bf540c, 0x00bd550f, 0x00bc550c, 0x00c3570f, 0x00c45208, 0x00c35007, 0x00c45610, 0x00c0550e, 0x00bd520b, 0x00bc5713, 0x00b4581d, 0x009a5022, 0x0056260b, 0x001c0000, 0x000c0000, 0x000c0100, 0x000d0000, 0x004a2206, 0x00aa5923, 0x00bd5512, 0x00c45710, 0x00c3540c, 0x00bf5009, 0x00be5915, 0x00b0571e, 0x00904618, 0x00581c00, 0x003e0500, 0x006f2d07, 0x00a65929, 0x00b4581c, 0x00bc5411, 0x00c0540d, 0x00bf5008, 0x00c4540a, 0x00ba5510, 0x00b46028, 0x00783b14, 0x002d0b00, 0x000e0000, 0x00080003, 0x00040000, 0x00120400, 0x004c2705, 0x009e541e, 0x00bc5817, 0x00c45310, 0x00c34f08, 0x00c15408, 0x00bd560c, 0x00b85414, 0x00b56028, 0x008e4f21, 0x00522704, 0x00230500, 0x000c0000, 0x00000000, 0x00000608, 0x00030000, 0x00040000, 0x00010007, 0x0000000a, 0x00000307, 0x00000303, 0x00040000, 0x00060000, 0x00020100, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00070707, 0x00545454, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00313132, 0x00545456, 0x00060000, 0x00100000, 0x00381300, 0x007f441c, 0x00b66025, 0x00bb5714, 0x00b04c0b, 0x00812400, 0x00a85413, 0x00b15e18, 0x00bf6115, 0x00c2600d, 0x00c8640d, 0x00bc5c04, 0x00b05701, 0x00c06a19, 0x00bc6517, 0x00b76017, 0x00b45d17, 0x00b4601f, 0x00ab6028, 0x00904c1c, 0x00662704, 0x00460b00, 0x00310000, 0x00450e00, 0x00723710, 0x009a5725, 0x00aa5a1d, 0x00b45a15, 0x00bf5c12, 0x00bc580e, 0x00be5d16, 0x00aa581a, 0x00773e14, 0x00280300, 0x00100000, 0x00180300, 0x002e0a00, 0x0079472b, 0x00a06031, 0x00aa591b, 0x00b8540b, 0x00c6590a, 0x00c35408, 0x00be5208, 0x00c05a11, 0x00b05714, 0x00a45922, 0x00773d15, 0x002b0400, 0x00240100, 0x003d1000, 0x008c4b25, 0x00b1591c, 0x00b55308, 0x00bc580d, 0x00bc570c, 0x00be530c, 0x00c15610, 0x00bc520e, 0x00b65717, 0x00a4571e, 0x00773e11, 0x00341100, 0x00160000, 0x00300900, 0x00713713, 0x00b15c25, 0x00ba5414, 0x00b9510c, 0x00bc530a, 0x00bd5307, 0x00c05207, 0x00c44f0a, 0x00c44e09, 0x00c15008, 0x00c05205, 0x00c05402, 0x00c35403, 0x00c95409, 0x00bc4f0e, 0x00b45b24, 0x007c3d16, 0x00240800, 0x000e0000, 0x001d0000, 0x00622b0c, 0x00af5c25, 0x00b95610, 0x00c1570b, 0x00c15304, 0x00c45207, 0x00c55a14, 0x00b15418, 0x009c5221, 0x00582605, 0x00210400, 0x000c0000, 0x00130100, 0x00310c00, 0x00814524, 0x00b45c22, 0x00bb510f, 0x00bd5110, 0x00be530f, 0x00c0580f, 0x00bb570d, 0x00b65812, 0x00934917, 0x003b1500, 0x00110000, 0x00100000, 0x00411800, 0x009b4813, 0x00bf540e, 0x00c6530c, 0x00c45108, 0x00c0550b, 0x00be570d, 0x00be550d, 0x00c0540c, 0x00c45207, 0x00c4540a, 0x00c0540d, 0x00ba5512, 0x00b65417, 0x00b05621, 0x0091451f, 0x00511a00, 0x001d0200, 0x00060000, 0x00030300, 0x00040000, 0x00190400, 0x006c3a19, 0x00b25922, 0x00bb4e0b, 0x00bc500b, 0x00c2540c, 0x00c25003, 0x00bf5004, 0x00bd550f, 0x00b5581b, 0x00964b19, 0x006e2c02, 0x00561400, 0x0081380c, 0x00b35c24, 0x00b85315, 0x00bd4f08, 0x00c8550c, 0x00bf5005, 0x00c0570f, 0x00b45411, 0x00a85824, 0x00562307, 0x00200400, 0x00060000, 0x00000002, 0x00040100, 0x00250d00, 0x00773910, 0x00b55c24, 0x00b74f12, 0x00c0500c, 0x00c45609, 0x00c25506, 0x00bf5007, 0x00bc5512, 0x00b45d21, 0x0094501f, 0x00501c00, 0x00180000, 0x00080000, 0x00000001, 0x00040000, 0x00050000, 0x00010004, 0x00000108, 0x00000307, 0x00000204, 0x00060000, 0x00070000, 0x00040000, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00101010, 0x00606060, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000c0c0c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00959597, 0x003c3a3b, 0x00040000, 0x00160000, 0x00451500, 0x00944c1c, 0x00ba5917, 0x00be540b, 0x00b8530d, 0x00b85810, 0x00b86013, 0x00b96211, 0x00be5d0a, 0x00c25e09, 0x00bf5e0a, 0x00bc610e, 0x00b96618, 0x00aa5d18, 0x00a85e24, 0x00a46131, 0x008c5128, 0x00602e0c, 0x003d1000, 0x00300600, 0x002f0100, 0x00300000, 0x005f2200, 0x008a4813, 0x00a45e20, 0x00ab5e1b, 0x00b46018, 0x00bb5f14, 0x00bc580e, 0x00be570e, 0x00c05810, 0x00b85c1c, 0x00874410, 0x00481f00, 0x000a0000, 0x00040000, 0x00120100, 0x002d0e00, 0x00704520, 0x009c5b27, 0x00b85916, 0x00bf5408, 0x00c1570c, 0x00bb540d, 0x00b1540f, 0x00b45c18, 0x00b55c1c, 0x00974814, 0x00693114, 0x001d0000, 0x001c0000, 0x00411b08, 0x008d4b20, 0x00b05b20, 0x00b35410, 0x00b7530b, 0x00bf560e, 0x00be550d, 0x00b85108, 0x00bb5811, 0x00b45c18, 0x009c531b, 0x005d2c09, 0x00270200, 0x00220000, 0x004a1900, 0x009f5224, 0x00b15416, 0x00b7520c, 0x00be570c, 0x00bc5408, 0x00c05108, 0x00c3500b, 0x00c34e0a, 0x00c0500a, 0x00c05207, 0x00c05304, 0x00c25204, 0x00cc5408, 0x00c54f08, 0x00c05818, 0x009d5020, 0x004c2910, 0x00190000, 0x003e0b00, 0x009c5124, 0x00b85814, 0x00c6590a, 0x00c45406, 0x00c7570b, 0x00c0510a, 0x00b55314, 0x00a55524, 0x006c3410, 0x00290900, 0x000e0000, 0x000d0000, 0x001a0300, 0x00572709, 0x00a45b2d, 0x00b45214, 0x00c25310, 0x00bf5312, 0x00be5412, 0x00bc530a, 0x00b6530b, 0x00b2591a, 0x007d390e, 0x00311002, 0x00110000, 0x001f0300, 0x005c2a09, 0x00af5518, 0x00c15209, 0x00c24f08, 0x00c3520a, 0x00c1550d, 0x00bf540c, 0x00c1550c, 0x00c05308, 0x00c4570c, 0x00c0550b, 0x00b55109, 0x00b25817, 0x00a85621, 0x008a4721, 0x00511c07, 0x001e0000, 0x00080000, 0x00090a0c, 0x00030400, 0x00080000, 0x00270500, 0x008b4c28, 0x00b55218, 0x00c4540d, 0x00c1530c, 0x00be510b, 0x00c4550c, 0x00c3550a, 0x00bd5206, 0x00b95208, 0x00b45413, 0x00af571b, 0x00833100, 0x00752400, 0x00993f07, 0x00b75214, 0x00c65410, 0x00c45008, 0x00c0510a, 0x00bc540c, 0x00ba5108, 0x00b85818, 0x0090471b, 0x00421300, 0x000f0000, 0x00020003, 0x00010100, 0x00100000, 0x00461900, 0x00944c21, 0x00b3551e, 0x00bc5311, 0x00be540b, 0x00c15304, 0x00c85508, 0x00c9570a, 0x00be550c, 0x00b3581a, 0x00883f13, 0x003e0f00, 0x000d0000, 0x00040001, 0x00050000, 0x00050000, 0x00010002, 0x00000006, 0x00000308, 0x00000205, 0x00060000, 0x00080000, 0x00030000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00181818, 0x006f6f6f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00121213, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00747472, 0x00252221, 0x00080000, 0x001c0200, 0x00632806, 0x00b46029, 0x00c25911, 0x00c45406, 0x00bc5206, 0x00c05e11, 0x00bc600d, 0x00ba600b, 0x00bd5e0c, 0x00c06316, 0x00b55f16, 0x00af621f, 0x00a8672c, 0x00874e1c, 0x006f3915, 0x004a1b00, 0x002c0700, 0x00250500, 0x001e0000, 0x001d0000, 0x00431400, 0x00773c18, 0x00a05820, 0x00a95814, 0x00b96218, 0x00bd6415, 0x00b6580c, 0x00b7570b, 0x00c15c11, 0x00c25910, 0x00bc5107, 0x00bf5d18, 0x00a4561a, 0x005c2a01, 0x00160800, 0x00000000, 0x00060000, 0x000e0000, 0x00280b00, 0x006a3811, 0x00a8571f, 0x00b85817, 0x00ba5712, 0x00bc5a15, 0x00b65b16, 0x00b15611, 0x00b85510, 0x00b85b1f, 0x008d481d, 0x004e1d06, 0x00180000, 0x001c0200, 0x00471700, 0x00904e24, 0x00b05c25, 0x00b45515, 0x00b9530d, 0x00bb5209, 0x00bb5308, 0x00ba5309, 0x00b7540c, 0x00ac581b, 0x0085451e, 0x004c1d05, 0x00200000, 0x00300100, 0x007e3914, 0x00ae5721, 0x00b65410, 0x00bc5409, 0x00bc5408, 0x00be510b, 0x00c1500e, 0x00c04f0d, 0x00c0500c, 0x00be520a, 0x00be5307, 0x00c05105, 0x00cc5408, 0x00c85109, 0x00c15514, 0x00a4521d, 0x005b3015, 0x00280400, 0x0076340c, 0x00b45c23, 0x00be560b, 0x00c65403, 0x00ca570a, 0x00c2520c, 0x00bb5411, 0x00ae5720, 0x0081431c, 0x00381000, 0x00100000, 0x000a0000, 0x00100000, 0x00341200, 0x00894c20, 0x00b05b23, 0x00b85011, 0x00c35210, 0x00c05413, 0x00be5410, 0x00b95008, 0x00b95814, 0x00ae5d27, 0x00682c08, 0x00260700, 0x00130000, 0x003d1400, 0x007c3c14, 0x00b95a1a, 0x00c2530a, 0x00c05009, 0x00c2540d, 0x00c0530c, 0x00bd5109, 0x00c35408, 0x00c05004, 0x00c0540c, 0x00b9540f, 0x00b25815, 0x00aa5d22, 0x0083461c, 0x004a1b00, 0x00220000, 0x00150000, 0x000c0407, 0x001f1d20, 0x000f0c08, 0x00160400, 0x003b0a00, 0x00a3562e, 0x00b64e11, 0x00ca560f, 0x00c55510, 0x00bc510c, 0x00bd540e, 0x00bc530b, 0x00bc5006, 0x00c2570b, 0x00bf540c, 0x00b8530f, 0x00b25518, 0x00973d04, 0x008e3300, 0x00af4c0f, 0x00c45410, 0x00c04c07, 0x00bf540e, 0x00bc530c, 0x00c3540c, 0x00b74f08, 0x00b0571d, 0x00713008, 0x00220400, 0x00060000, 0x00000000, 0x00070000, 0x00240500, 0x00642c0d, 0x00ae5c2c, 0x00b85618, 0x00b7500b, 0x00c05408, 0x00c04c00, 0x00ca5408, 0x00c65407, 0x00c35b16, 0x00ac5521, 0x00642808, 0x001c0400, 0x00080200, 0x00060000, 0x00050000, 0x00010000, 0x00000104, 0x00000206, 0x00000207, 0x00040001, 0x00060000, 0x00030000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00232323, 0x00838383, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000c0c0d, 0x00080808, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005d5d5c, 0x00110d0b, 0x000a0100, 0x00280a00, 0x007a3810, 0x00b85a1c, 0x00c15104, 0x00cc5804, 0x00cc5e0c, 0x00c45d0c, 0x00bf5e0b, 0x00ba5f10, 0x00b86019, 0x00b36326, 0x00985824, 0x00713c13, 0x004a2404, 0x00301300, 0x00180000, 0x00160000, 0x00140000, 0x00190000, 0x00320d00, 0x005c2c06, 0x008a4a1b, 0x00a95b22, 0x00b45812, 0x00c35d10, 0x00c55808, 0x00bf5202, 0x00bc550c, 0x00be580e, 0x00be5808, 0x00c05808, 0x00c05605, 0x00b9550b, 0x00b45b1c, 0x008b4b20, 0x00260c00, 0x00070000, 0x00080000, 0x000c0000, 0x00110000, 0x00280400, 0x00652c05, 0x009c501f, 0x00b05818, 0x00b45610, 0x00b65812, 0x00b85510, 0x00be5410, 0x00b65114, 0x00a85621, 0x0081441d, 0x00311000, 0x00110000, 0x00210200, 0x00471702, 0x00934c28, 0x00b05824, 0x00b75110, 0x00c0540c, 0x00c4580c, 0x00bb5004, 0x00ba530a, 0x00b8581b, 0x00a45328, 0x007b381d, 0x003b0900, 0x002b0000, 0x00581900, 0x009e5024, 0x00b75614, 0x00b85004, 0x00bc5209, 0x00bd500c, 0x00bf500f, 0x00bf4f10, 0x00bb5110, 0x00ba520d, 0x00bd530a, 0x00c05108, 0x00bf4b02, 0x00c45310, 0x00bd5a1f, 0x00934616, 0x00461600, 0x00431300, 0x00a45523, 0x00c05c1b, 0x00c6580c, 0x00c04d00, 0x00c9570c, 0x00ba4f0b, 0x00b25519, 0x00924a1a, 0x00491e00, 0x00160000, 0x00080000, 0x000d0000, 0x00290900, 0x0069330d, 0x00ac5e25, 0x00b55414, 0x00bb5212, 0x00bd5110, 0x00bc520e, 0x00be550d, 0x00bd500a, 0x00ba5a1c, 0x00955024, 0x004d1c00, 0x00200000, 0x00280400, 0x006c3010, 0x009d4d1d, 0x00b85818, 0x00bd540e, 0x00bc530c, 0x00bd540e, 0x00be530f, 0x00c05009, 0x00c45104, 0x00c25002, 0x00bc4f0a, 0x00b45515, 0x00a8591f, 0x0083491a, 0x00452301, 0x00160000, 0x00100000, 0x00180300, 0x0035231e, 0x003a2b25, 0x000b0000, 0x001e0000, 0x0068280c, 0x00ae5529, 0x00c05516, 0x00c25109, 0x00bd4d08, 0x00bb500c, 0x00ba5310, 0x00b85412, 0x00b85410, 0x00bd5510, 0x00bf540c, 0x00bd520c, 0x00bb5514, 0x00b04f11, 0x00ac4f14, 0x00ad4c12, 0x00b04808, 0x00c15514, 0x00bc5210, 0x00bf5511, 0x00c0540c, 0x00bc5009, 0x00b95410, 0x009c4a14, 0x004a1a00, 0x00180000, 0x00050000, 0x00030000, 0x00100000, 0x00391300, 0x008c461e, 0x00b25820, 0x00b45310, 0x00bd560d, 0x00c2580f, 0x00c05209, 0x00c25108, 0x00c15610, 0x00b5541d, 0x00813b16, 0x00301104, 0x00060000, 0x00060000, 0x00040000, 0x00010000, 0x00000100, 0x00000204, 0x00000305, 0x00010005, 0x00020004, 0x00010002, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00373737, 0x009d9d9d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00090909, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00acb4b3, 0x0050504e, 0x00040000, 0x00080000, 0x00431e0c, 0x00944718, 0x00bc5410, 0x00cc5908, 0x00cb5500, 0x00c25807, 0x00c36016, 0x00ba601c, 0x00af5f20, 0x009d5621, 0x0071340b, 0x00481900, 0x00301000, 0x00180200, 0x00100000, 0x00140000, 0x00130000, 0x00220500, 0x00482004, 0x00784319, 0x009b5824, 0x00ae5c1c, 0x00b55912, 0x00bc590c, 0x00c15706, 0x00c95405, 0x00c85508, 0x00c25710, 0x00c05910, 0x00c05908, 0x00bd5701, 0x00bf5601, 0x00bd5808, 0x00b95816, 0x00984b1c, 0x00552c1b, 0x00100000, 0x00080000, 0x00060000, 0x0020120c, 0x00190000, 0x002c0100, 0x005c2200, 0x00934c17, 0x00ac591c, 0x00b05414, 0x00bb5714, 0x00bd5110, 0x00be5413, 0x00b3561a, 0x009c5320, 0x00643713, 0x00230500, 0x00140000, 0x001e0000, 0x00501c05, 0x00975028, 0x00af541b, 0x00b8500c, 0x00c2540b, 0x00bf5005, 0x00c2550f, 0x00b64e10, 0x00b15321, 0x009c4d29, 0x00642915, 0x00330000, 0x003a0400, 0x00823f1a, 0x00b2571c, 0x00ba530a, 0x00bc5009, 0x00bc500b, 0x00be4f0e, 0x00bc4f10, 0x00ba5111, 0x00b95210, 0x00bc510a, 0x00bf5009, 0x00c04f0a, 0x00c05819, 0x00a34c19, 0x00702901, 0x00420b00, 0x007c3d16, 0x00b65b20, 0x00c0530c, 0x00c65608, 0x00c85508, 0x00c0500b, 0x00b85618, 0x00a45622, 0x005b2600, 0x001f0500, 0x000a0000, 0x00080000, 0x00160000, 0x004b1900, 0x00984e1d, 0x00b45814, 0x00ba5109, 0x00bc5412, 0x00be5414, 0x00bc500b, 0x00c0540f, 0x00ba5312, 0x00ac541f, 0x00703712, 0x00300800, 0x00210000, 0x00512000, 0x00934519, 0x00b65720, 0x00b85214, 0x00bc5310, 0x00bb530e, 0x00bc540d, 0x00bd520e, 0x00c0520b, 0x00c55004, 0x00c55308, 0x00bb5214, 0x00ad5620, 0x008d4c20, 0x004d2300, 0x00160200, 0x000e0000, 0x001a0400, 0x00392012, 0x00543c2d, 0x002d1609, 0x00110000, 0x002e0900, 0x00883e1c, 0x00b65422, 0x00bc500f, 0x00c05008, 0x00c2550f, 0x00bf5511, 0x00b65010, 0x00b95515, 0x00bc5718, 0x00b84f0d, 0x00bf520d, 0x00c1530c, 0x00bb500a, 0x00bc5411, 0x00b85414, 0x00b45214, 0x00be5a1a, 0x00ba5310, 0x00bb5310, 0x00c05710, 0x00bd500a, 0x00c0540d, 0x00bf560e, 0x00ac5215, 0x007a3810, 0x00310900, 0x00100000, 0x00030001, 0x00080002, 0x00220800, 0x005d2605, 0x00a65825, 0x00b65717, 0x00b9530d, 0x00b9530d, 0x00bc530c, 0x00c5560d, 0x00c4550f, 0x00bc5719, 0x00904318, 0x003c1606, 0x000b0000, 0x00040000, 0x00010000, 0x00000100, 0x00000200, 0x00000200, 0x00000104, 0x00000107, 0x00000105, 0x00000002, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004a4a4a, 0x00b2b2b2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00080808, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009ba2a1, 0x003d3f3e, 0x00040000, 0x000f0000, 0x004e220a, 0x00a8501b, 0x00c3540b, 0x00c95404, 0x00c75809, 0x00bc5f19, 0x00ae6027, 0x009d592e, 0x00723b1a, 0x00481c01, 0x00290800, 0x00170000, 0x00120000, 0x00140000, 0x00140000, 0x00260a00, 0x00482202, 0x00703e14, 0x0090501d, 0x00a8581e, 0x00b85c1a, 0x00bd5b10, 0x00bb5509, 0x00bc5d12, 0x00bc590e, 0x00c3540b, 0x00c05009, 0x00c05717, 0x00be5915, 0x00b95200, 0x00c25a02, 0x00bd5700, 0x00bf5808, 0x00be5812, 0x00aa501d, 0x007d4027, 0x00290600, 0x00080000, 0x00040102, 0x00241818, 0x0038231d, 0x00270400, 0x002d0000, 0x00511c00, 0x00854415, 0x00a8571d, 0x00b45415, 0x00bd5412, 0x00bb4f0d, 0x00b95815, 0x00ab5619, 0x0091501c, 0x00582a06, 0x00150000, 0x00130000, 0x00210400, 0x004c1e06, 0x009b5224, 0x00b35419, 0x00bb4c08, 0x00c45008, 0x00c2500c, 0x00bb4d0d, 0x00b85218, 0x00ac5222, 0x008b4726, 0x00531d06, 0x002b0000, 0x00582005, 0x00a95625, 0x00b25011, 0x00bc520e, 0x00bb4c06, 0x00bc4d0b, 0x00bd5110, 0x00bc5314, 0x00bb5210, 0x00bc4f08, 0x00c0510a, 0x00bb4f0d, 0x00b3541d, 0x00843d18, 0x004e1200, 0x005c1c00, 0x00a45521, 0x00c15a17, 0x00c8550a, 0x00cb580b, 0x00c15008, 0x00bf5618, 0x00ab5420, 0x00723810, 0x00301000, 0x00060000, 0x00040000, 0x000c0000, 0x00340e00, 0x007d3811, 0x00ac5117, 0x00c15810, 0x00bd5003, 0x00bc5210, 0x00bf5415, 0x00c0500c, 0x00c05614, 0x00b25620, 0x008c461b, 0x003e1400, 0x00240100, 0x00461b00, 0x00803f13, 0x00af511a, 0x00c05418, 0x00c05216, 0x00bd5011, 0x00bb510f, 0x00bc540d, 0x00bc540c, 0x00c0540c, 0x00c44f0a, 0x00c35212, 0x00b95520, 0x0095481f, 0x0055260b, 0x00210500, 0x000e0000, 0x00100000, 0x003c1c04, 0x00654127, 0x00513420, 0x001e0500, 0x00120000, 0x003f1800, 0x00a45528, 0x00b75214, 0x00bf530b, 0x00c05207, 0x00bb520c, 0x00bb5310, 0x00bc5311, 0x00bd5412, 0x00c05310, 0x00c15210, 0x00c1510d, 0x00c1510c, 0x00c2510b, 0x00c15008, 0x00c05108, 0x00be530c, 0x00bb5612, 0x00bb5613, 0x00bc530f, 0x00c0530c, 0x00c0530c, 0x00bd520c, 0x00b8500d, 0x00b55818, 0x009a4b17, 0x005f2604, 0x001b0000, 0x00080004, 0x00030003, 0x000e0000, 0x003b1200, 0x00904e24, 0x00af5214, 0x00bc540d, 0x00b8530f, 0x00bd5711, 0x00bf520c, 0x00c55710, 0x00c05614, 0x00a04d1b, 0x00421904, 0x000d0000, 0x00010000, 0x00000100, 0x00000200, 0x00000200, 0x00000100, 0x00000100, 0x00000006, 0x00000006, 0x00000002, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00040404, 0x00000000, 0x00010101, 0x00000000, 0x000c0c0c, 0x00646464, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008d9091, 0x00303133, 0x00050000, 0x00190200, 0x005b2708, 0x00b7581d, 0x00c9590d, 0x00be5005, 0x00ba5a15, 0x00a65c27, 0x00804823, 0x004f220c, 0x002c0900, 0x00170000, 0x00150000, 0x00140000, 0x001d0100, 0x00391500, 0x00552b09, 0x00724115, 0x008b501c, 0x00a45c21, 0x00b15d1c, 0x00b85813, 0x00bd550f, 0x00bf570c, 0x00be580c, 0x00b4580d, 0x00b7590f, 0x00c45a11, 0x00c45410, 0x00b85213, 0x00bb5613, 0x00c05908, 0x00bf5600, 0x00bb5501, 0x00bb5405, 0x00bd540e, 0x00ba581e, 0x009b4e26, 0x004f1e07, 0x000c0000, 0x00040100, 0x00160e0f, 0x00402c2b, 0x0053332b, 0x00350c00, 0x002c0000, 0x00491400, 0x00803c10, 0x00a3501b, 0x00b45317, 0x00bd5615, 0x00ba540e, 0x00b35410, 0x00a8581c, 0x007f4114, 0x003a1500, 0x00120000, 0x000d0000, 0x001d0300, 0x005e2807, 0x009d5020, 0x00b85517, 0x00bf500c, 0x00c04f0d, 0x00c35212, 0x00bf5111, 0x00b6541a, 0x00a15223, 0x00793c18, 0x003e1000, 0x00360500, 0x00803b15, 0x00b05a27, 0x00b75214, 0x00bd520e, 0x00c15413, 0x00bb4f0e, 0x00b44c0c, 0x00bb5110, 0x00c2520c, 0x00bd4f08, 0x00b85014, 0x00a04819, 0x0064280b, 0x00460e00, 0x00843808, 0x00b35516, 0x00ca5b10, 0x00c85204, 0x00c95409, 0x00bc4f0e, 0x00b1541c, 0x00904c20, 0x003c1800, 0x00140700, 0x00000000, 0x00040100, 0x001a0000, 0x0057230c, 0x009e481c, 0x00bc5414, 0x00c45408, 0x00c05002, 0x00ba510b, 0x00b9500f, 0x00be5010, 0x00b75118, 0x009e5024, 0x005d2403, 0x002d0800, 0x00371200, 0x0072390e, 0x00a65721, 0x00bb5314, 0x00c55110, 0x00c35012, 0x00bf4f10, 0x00bd5110, 0x00bc530c, 0x00bb520a, 0x00bb520c, 0x00be5113, 0x00b34f19, 0x00a35228, 0x0064280c, 0x00250600, 0x00100000, 0x00110000, 0x00351500, 0x006c4022, 0x00714629, 0x003c200c, 0x00140000, 0x00200400, 0x00633412, 0x00ac5824, 0x00b9510e, 0x00c05207, 0x00c25408, 0x00bf5610, 0x00bb5310, 0x00bb4f0d, 0x00bd4e0c, 0x00c04e0b, 0x00c04e0b, 0x00bf500f, 0x00be5010, 0x00be510e, 0x00bf520d, 0x00c0540d, 0x00bd550f, 0x00b45411, 0x00b0500f, 0x00bc5411, 0x00bb500c, 0x00ba4f09, 0x00bc530f, 0x00bc5412, 0x00b85718, 0x00ae5318, 0x008c4317, 0x00401705, 0x00130000, 0x00070000, 0x00090000, 0x00200400, 0x005c2807, 0x00ae5820, 0x00b8510e, 0x00b8520c, 0x00bc540c, 0x00bf4f08, 0x00c4530b, 0x00c4550e, 0x00aa531c, 0x004c2007, 0x000d0000, 0x00000002, 0x00000304, 0x00000200, 0x00000100, 0x00010100, 0x00010000, 0x00000004, 0x00000106, 0x00000002, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00212121, 0x007d7d7d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007a7a78, 0x00202124, 0x00050000, 0x00250800, 0x006e330d, 0x00b75615, 0x00c5580c, 0x00c05f1c, 0x00a45823, 0x00673818, 0x00341705, 0x00170100, 0x000e0000, 0x00100000, 0x001f0600, 0x003a1300, 0x00602b07, 0x00884315, 0x009d4f16, 0x00ac5b19, 0x00b35c16, 0x00b85c14, 0x00bc5812, 0x00be5611, 0x00be5611, 0x00bb5813, 0x00b85911, 0x00b35b0f, 0x00b4590c, 0x00bc5409, 0x00c1570e, 0x00bd5613, 0x00bb540f, 0x00c05608, 0x00bc5504, 0x00ba570a, 0x00ba560c, 0x00ba5109, 0x00bd5815, 0x00ad541c, 0x007b3d14, 0x00230a00, 0x00070000, 0x00060000, 0x002a1917, 0x00644339, 0x00603628, 0x00401502, 0x002c0000, 0x00421200, 0x006f340c, 0x00994918, 0x00b85a1c, 0x00ba500c, 0x00b85009, 0x00b45818, 0x00a25822, 0x006f3c18, 0x00230200, 0x000c0000, 0x00090000, 0x00240700, 0x00693611, 0x009c4f18, 0x00b15414, 0x00b84f0d, 0x00bd500c, 0x00c2520c, 0x00bc5210, 0x00ae5318, 0x009c5122, 0x00632f10, 0x00280000, 0x004c1800, 0x008e4c26, 0x00af561f, 0x00b85213, 0x00bc5311, 0x00bf5312, 0x00bc500e, 0x00bd500d, 0x00c2510b, 0x00bc500c, 0x00b25018, 0x0088390d, 0x00481100, 0x00541900, 0x00ac531a, 0x00c3570f, 0x00cc5606, 0x00cb5102, 0x00c8510b, 0x00ba5418, 0x00a05324, 0x005c2b0d, 0x00160400, 0x00000000, 0x00010404, 0x00090000, 0x00381100, 0x00813d1e, 0x00b65624, 0x00c15211, 0x00c04c02, 0x00c45205, 0x00be5409, 0x00ba5310, 0x00b85216, 0x00af5726, 0x00753814, 0x00340400, 0x00380d00, 0x00663212, 0x009c5120, 0x00b4561b, 0x00bf5410, 0x00c2510b, 0x00c1500c, 0x00c1500f, 0x00c25110, 0x00c0510d, 0x00bc5209, 0x00b85410, 0x00b2571f, 0x00a0542b, 0x00643014, 0x00260800, 0x000c0000, 0x000e0000, 0x00370c00, 0x006c3417, 0x008c5234, 0x0064371f, 0x001c0600, 0x000e0000, 0x00371000, 0x008b4d22, 0x00b0551b, 0x00bc510a, 0x00c05105, 0x00bc4e00, 0x00b94f06, 0x00bd520c, 0x00c0540f, 0x00c0500c, 0x00c1500c, 0x00c25312, 0x00bc5114, 0x00b95419, 0x00b8571e, 0x00b3551d, 0x00af5419, 0x00ae5419, 0x00b1591c, 0x00b65c1d, 0x00b65415, 0x00bb5413, 0x00bb5110, 0x00bd5411, 0x00bb5410, 0x00b4500d, 0x00b45111, 0x00a7501a, 0x00783614, 0x00370b00, 0x000e0000, 0x000a0000, 0x000e0000, 0x002e0800, 0x00954c1f, 0x00b45415, 0x00ba510b, 0x00c35307, 0x00c75004, 0x00c95306, 0x00c65407, 0x00b1581b, 0x00542409, 0x000c0000, 0x00000004, 0x00000207, 0x00000100, 0x00000000, 0x00030000, 0x00030000, 0x00000001, 0x00000003, 0x00000001, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00030303, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00404040, 0x009f9f9f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x006c6968, 0x0016171b, 0x00090000, 0x002c0b00, 0x007c3f17, 0x00b45b1c, 0x00b45410, 0x009e4d17, 0x00682d06, 0x002a0800, 0x00130000, 0x000e0000, 0x00130000, 0x002c1200, 0x00583113, 0x00844922, 0x00a35826, 0x00b45c22, 0x00bc5c19, 0x00bf5c14, 0x00be580c, 0x00be5408, 0x00c05408, 0x00c3540d, 0x00c15610, 0x00b85611, 0x00b1540f, 0x00b0550c, 0x00b4570c, 0x00b8540b, 0x00b9510b, 0x00bf5712, 0x00be5610, 0x00b85005, 0x00bd560b, 0x00b8550d, 0x00bc5913, 0x00bb520c, 0x00ba520d, 0x00b25110, 0x009d521f, 0x004a2407, 0x000f0000, 0x00080000, 0x000c0000, 0x00402118, 0x00764d3e, 0x00754734, 0x0054240c, 0x002f0200, 0x003c0b00, 0x00682a03, 0x00984918, 0x00b45417, 0x00ba5312, 0x00b15011, 0x00ac571d, 0x00965122, 0x00532406, 0x00120000, 0x000d0100, 0x000d0000, 0x002c0d00, 0x006b350b, 0x00a05721, 0x00b3581c, 0x00b8500e, 0x00be5009, 0x00bf500a, 0x00b4500c, 0x00ab551d, 0x0083461e, 0x00421400, 0x00290000, 0x00572408, 0x00994e23, 0x00ad541d, 0x00b35218, 0x00b75112, 0x00bd5110, 0x00be4f0b, 0x00be4f0b, 0x00b85012, 0x00a34917, 0x00702600, 0x00450b00, 0x007c3a14, 0x00bb581a, 0x00cc5808, 0x00c95000, 0x00cb5408, 0x00bd500f, 0x00b25724, 0x007a3c19, 0x002b0900, 0x000a0300, 0x00000100, 0x00040000, 0x001c0600, 0x00602c10, 0x00a05026, 0x00bc561d, 0x00c04f0d, 0x00bf4c04, 0x00c35409, 0x00bb5209, 0x00b65412, 0x00ad541f, 0x0090451c, 0x00430c00, 0x003a0a00, 0x00693114, 0x0098512c, 0x00b35723, 0x00ba5111, 0x00be510b, 0x00be5005, 0x00bf5009, 0x00c1510c, 0x00c0500c, 0x00bf500d, 0x00bc5210, 0x00b35518, 0x00a3572a, 0x00723c1c, 0x002b0e00, 0x000c0000, 0x000b0000, 0x00270c00, 0x006c3014, 0x00934c2a, 0x0080442b, 0x00461a09, 0x00110000, 0x00180100, 0x005c2604, 0x00a45523, 0x00b25011, 0x00bf520c, 0x00be5005, 0x00c05308, 0x00bf540c, 0x00bc540d, 0x00b9500f, 0x00b74f10, 0x00b65114, 0x00b5541c, 0x00ab511e, 0x009a4819, 0x00883f16, 0x007f3a13, 0x007b360d, 0x007a3104, 0x00803000, 0x00883100, 0x009e4006, 0x00b34e11, 0x00b85012, 0x00b8500e, 0x00ba520d, 0x00ba520d, 0x00bb5410, 0x00b45216, 0x009f491c, 0x0068280b, 0x00210000, 0x000e0000, 0x000b0000, 0x001d0400, 0x00652c0b, 0x00a95624, 0x00b64f0c, 0x00c45004, 0x00c95105, 0x00cc5407, 0x00c65402, 0x00b25817, 0x00562809, 0x000e0000, 0x00000004, 0x00000207, 0x00000100, 0x00000000, 0x00030000, 0x00030000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00030303, 0x00020202, 0x00030303, 0x00000000, 0x00010101, 0x000b0b0b, 0x00626262, 0x00313131, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00635e5e, 0x00101014, 0x00090000, 0x00341000, 0x007a421b, 0x00a95f29, 0x00994f18, 0x00602600, 0x002d0200, 0x00160000, 0x00150000, 0x002f0e00, 0x00522806, 0x007e461c, 0x009d5a27, 0x00b05e27, 0x00b55c20, 0x00b4561b, 0x00b55416, 0x00ba5616, 0x00bf5712, 0x00c5560c, 0x00c75507, 0x00c45304, 0x00c05306, 0x00b9550c, 0x00b85611, 0x00a54401, 0x00ab4608, 0x00bc581b, 0x00b95414, 0x00ba500e, 0x00c0570f, 0x00b95208, 0x00bc560d, 0x00b3510c, 0x00ba5613, 0x00bc5411, 0x00bc5310, 0x00ba5113, 0x00b15824, 0x007a3f21, 0x002c0800, 0x00110000, 0x00080000, 0x00160200, 0x00503021, 0x00855035, 0x008b4d2c, 0x005c2301, 0x003a0600, 0x00370800, 0x00592201, 0x0092461b, 0x00b25825, 0x00b2511a, 0x00af5017, 0x00ab541b, 0x008f4b1f, 0x00380f00, 0x00140000, 0x000b0000, 0x000c0000, 0x00331800, 0x0073431b, 0x009d5523, 0x00ae5115, 0x00b84c0c, 0x00c3510c, 0x00c0510d, 0x00b55416, 0x00994e1d, 0x0068310d, 0x00200000, 0x00270100, 0x00652c0d, 0x00985028, 0x00aa5827, 0x00ac5015, 0x00b64d0c, 0x00bc4f0a, 0x00b95010, 0x00ae5019, 0x00883c11, 0x00561300, 0x005d1a00, 0x00a45425, 0x00bf5410, 0x00cc5707, 0x00c65001, 0x00c4560f, 0x00b4531c, 0x00944a21, 0x00401400, 0x00140000, 0x00020000, 0x00080504, 0x000e0000, 0x00461d06, 0x0088441c, 0x00b05422, 0x00bb5014, 0x00c2500f, 0x00c0500c, 0x00bc510c, 0x00b4510c, 0x00ad5518, 0x009a5125, 0x005d1f00, 0x003e0400, 0x006e2f0c, 0x009d502a, 0x00b05428, 0x00b64c14, 0x00c15211, 0x00bd520b, 0x00ba5207, 0x00bb5308, 0x00bc5209, 0x00bc4d09, 0x00bc4f10, 0x00b7541a, 0x00a75423, 0x007c4321, 0x002e0d00, 0x00100300, 0x000d0400, 0x001d0400, 0x005a2c15, 0x00964c28, 0x009e522f, 0x0064301b, 0x00240200, 0x00160000, 0x00371005, 0x0089401a, 0x00b4531d, 0x00b64d0d, 0x00bf540e, 0x00b9500c, 0x00be5410, 0x00bc530f, 0x00b44f0e, 0x00b05317, 0x00ac5622, 0x00984c1c, 0x00803b12, 0x006c300f, 0x00552206, 0x003c1300, 0x00320c00, 0x00320800, 0x00400b00, 0x005c1800, 0x00782700, 0x00973b05, 0x00b04d14, 0x00b75114, 0x00b84e0c, 0x00bd5109, 0x00bf530b, 0x00bc530f, 0x00b85012, 0x00b24e18, 0x0096451c, 0x004c1f08, 0x00180100, 0x000b0000, 0x00140100, 0x00330c00, 0x008a4b2a, 0x00b05118, 0x00c04f08, 0x00c74e05, 0x00cc5406, 0x00c65501, 0x00b15915, 0x0057280a, 0x00130000, 0x00020001, 0x00000005, 0x00000000, 0x00000000, 0x00020000, 0x00020000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x002b2b2b, 0x00888888, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005c5558, 0x000b0a10, 0x00080000, 0x003a1903, 0x007b4a26, 0x00864e24, 0x005f2a04, 0x002d0500, 0x00190000, 0x00220000, 0x00401700, 0x00713b14, 0x008e4e1f, 0x009c5421, 0x009b4c18, 0x00a04f18, 0x00ac5822, 0x00b15c25, 0x00b0581f, 0x00b65619, 0x00bd5614, 0x00c3540c, 0x00c35305, 0x00c15304, 0x00c05407, 0x00bb570d, 0x00b95814, 0x00a84709, 0x00913300, 0x00a24612, 0x00b55820, 0x00b95211, 0x00bd540e, 0x00bc560f, 0x00b8530d, 0x00b85510, 0x00b6510d, 0x00bc5210, 0x00bf5311, 0x00be5010, 0x00b7541c, 0x00a0542c, 0x00602b10, 0x00190000, 0x000a0000, 0x00080000, 0x00220b00, 0x0069391c, 0x00945630, 0x00914e28, 0x006c2f0c, 0x00380900, 0x00300100, 0x00581d00, 0x008f4520, 0x00b05628, 0x00b8551f, 0x00b25014, 0x00ab5722, 0x00773c1e, 0x00270100, 0x000f0000, 0x00060000, 0x000d0000, 0x00371b04, 0x007a401a, 0x00a65320, 0x00b75014, 0x00c0500e, 0x00c0500b, 0x00b8500e, 0x00a8521a, 0x0088461c, 0x00350900, 0x001b0000, 0x002c0000, 0x00643016, 0x00904c27, 0x00a95624, 0x00b95414, 0x00b84f0c, 0x00b25117, 0x00a45021, 0x006c2b08, 0x004a0b00, 0x00803206, 0x00b85c21, 0x00c2520c, 0x00cb5408, 0x00c45408, 0x00b85412, 0x00a85829, 0x00632b0e, 0x001e0200, 0x000b0000, 0x00030000, 0x000a0000, 0x002c0700, 0x00713716, 0x00a35321, 0x00b8561a, 0x00b94d0c, 0x00c1500c, 0x00bf500d, 0x00b85010, 0x00b35717, 0x00a45720, 0x006c300b, 0x00400700, 0x00702c04, 0x009e4d20, 0x00b25423, 0x00b84e1a, 0x00bb4b0f, 0x00bf4e0c, 0x00bc510a, 0x00b95208, 0x00bb540a, 0x00b95208, 0x00bb500a, 0x00bb5518, 0x00ae5424, 0x008e4826, 0x00411601, 0x00140000, 0x00080000, 0x001f0b00, 0x0055260b, 0x008c4a27, 0x00a6562f, 0x00894323, 0x00411b09, 0x00130000, 0x00210300, 0x00562210, 0x00a74f28, 0x00bc521b, 0x00bc500f, 0x00bd520c, 0x00bc5210, 0x00b85011, 0x00b35115, 0x00ab541e, 0x009b5023, 0x007c3e18, 0x00572404, 0x003b1000, 0x00260000, 0x00210000, 0x00230200, 0x00310d00, 0x00481b05, 0x00662b0d, 0x008b3e15, 0x00a74f1c, 0x00ae4d16, 0x00bb5418, 0x00bb5214, 0x00bd5110, 0x00c0520b, 0x00bb4f05, 0x00b84f0b, 0x00b95012, 0x00ba531c, 0x00aa5326, 0x007c4428, 0x00341400, 0x000e0000, 0x000c0000, 0x00180000, 0x005c2b17, 0x00aa5628, 0x00bc5214, 0x00c44f0b, 0x00c85308, 0x00c55706, 0x00b35c19, 0x0054280a, 0x00130000, 0x00060000, 0x00020001, 0x00020000, 0x00020000, 0x00000004, 0x00000004, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00535353, 0x00acacac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00544f55, 0x0008050e, 0x00080000, 0x003c1c08, 0x006e4628, 0x00512f14, 0x00200400, 0x00110000, 0x00280c00, 0x0058280c, 0x008f4d25, 0x00aa5b27, 0x009b4712, 0x007c3005, 0x006e2b06, 0x00733818, 0x007a4321, 0x00884b21, 0x009a5421, 0x00ad571c, 0x00b95815, 0x00bf5811, 0x00bd560c, 0x00b9570c, 0x00b9580e, 0x00b95611, 0x00b35412, 0x00b0581a, 0x008c3c05, 0x007a2e01, 0x00954516, 0x00b25215, 0x00b7520f, 0x00bb5714, 0x00b6530e, 0x00be5810, 0x00b9500a, 0x00be510c, 0x00be510c, 0x00be5009, 0x00ba5110, 0x00b3581d, 0x00934e20, 0x00381000, 0x00100000, 0x00060000, 0x000c0200, 0x003d1e07, 0x007d4826, 0x00a65a2f, 0x00a05024, 0x0070300e, 0x00440f00, 0x00340400, 0x00561f06, 0x0090431f, 0x00b15425, 0x00b65015, 0x00b15018, 0x00a0542b, 0x00541f05, 0x001e0400, 0x00090000, 0x00030000, 0x00140300, 0x0052210b, 0x00944824, 0x00b4521e, 0x00b84d0e, 0x00bb500c, 0x00b54e0b, 0x00b25417, 0x00a05020, 0x00682c13, 0x00320500, 0x00160000, 0x002a0700, 0x00582509, 0x00944b20, 0x00b35115, 0x00b44f10, 0x00aa5220, 0x008b421c, 0x004f1a00, 0x00551a00, 0x00a34914, 0x00c15814, 0x00c4540c, 0x00c5540c, 0x00c0540f, 0x00ac5319, 0x00844422, 0x00320d00, 0x00100100, 0x00040000, 0x000c0000, 0x00170000, 0x005c240a, 0x00944920, 0x00b0571d, 0x00ba5512, 0x00bd4f08, 0x00c04e09, 0x00bc4d0c, 0x00b55014, 0x00aa5620, 0x00814013, 0x00410e00, 0x005b2002, 0x00a24b1c, 0x00b85117, 0x00b94f13, 0x00c05314, 0x00c35514, 0x00be510c, 0x00bc500b, 0x00bc500b, 0x00bc530c, 0x00b9510b, 0x00b9510b, 0x00b4551a, 0x008e441f, 0x0058230e, 0x00180000, 0x00190200, 0x001b0000, 0x0051240a, 0x00984b20, 0x00ac5528, 0x00974d28, 0x005c280c, 0x001d0800, 0x000d0000, 0x00391000, 0x007e3b1e, 0x00b05028, 0x00bc501b, 0x00bc540d, 0x00bc5107, 0x00bf520f, 0x00b85219, 0x00a65224, 0x00874622, 0x0055280e, 0x00290900, 0x00140000, 0x00140000, 0x00190000, 0x00300d00, 0x00522303, 0x00783b14, 0x009c5021, 0x00b55a28, 0x00ba571f, 0x00b84e13, 0x00bc5114, 0x00be5211, 0x00bc4c0a, 0x00c0500c, 0x00c0540d, 0x00b9500a, 0x00bb510f, 0x00ba5419, 0x00b05123, 0x00994821, 0x00844623, 0x005d3214, 0x00311600, 0x000e0000, 0x00100000, 0x002f0a00, 0x008f4828, 0x00b05120, 0x00c05218, 0x00c45410, 0x00c1590c, 0x00af5c1d, 0x0052270a, 0x00130000, 0x000b0000, 0x00080000, 0x00060000, 0x00030000, 0x00000008, 0x00000009, 0x00000001, 0x00000100, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x001c1c1c, 0x00808080, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00504c52, 0x0006040c, 0x00080000, 0x00341b0a, 0x0046270e, 0x00280c00, 0x001a0000, 0x002d1000, 0x0064391b, 0x00985429, 0x00b05e27, 0x00b4591b, 0x00b95c20, 0x00a34c1b, 0x00742a01, 0x00480f00, 0x00330400, 0x003d1100, 0x005a2704, 0x00874317, 0x00a04e19, 0x00b1581b, 0x00b45815, 0x00b2560d, 0x00b5560e, 0x00ba5613, 0x00b75615, 0x00b15818, 0x00a7581e, 0x006c2700, 0x006f2700, 0x009c4814, 0x00ac5016, 0x00b85a1b, 0x00b65412, 0x00ba520d, 0x00bc5009, 0x00c25711, 0x00be510b, 0x00bc5007, 0x00bc540c, 0x00b2500c, 0x00aa5820, 0x00703714, 0x00250500, 0x00080000, 0x00050000, 0x00190400, 0x00683a1c, 0x009d5024, 0x00af5523, 0x00a55628, 0x00763410, 0x003c0900, 0x00330100, 0x0064240a, 0x009a4a23, 0x00b45420, 0x00b35018, 0x00af5724, 0x008c4823, 0x00371000, 0x000c0000, 0x00070308, 0x00070000, 0x00220000, 0x0064280f, 0x00a44e21, 0x00b14e14, 0x00bc5615, 0x00b7500d, 0x00b85316, 0x00ac511f, 0x009b4f2c, 0x005b220c, 0x00240100, 0x00150000, 0x00270000, 0x00642c0f, 0x00924010, 0x00a8521e, 0x00a0582f, 0x006a2e0e, 0x00420e00, 0x006c2d0b, 0x00b5581b, 0x00c5580c, 0x00c5540b, 0x00c15410, 0x00b45314, 0x00a25525, 0x0050230b, 0x00140000, 0x00030000, 0x00030000, 0x00150000, 0x00360a00, 0x00803714, 0x00ae5323, 0x00b25014, 0x00ba520f, 0x00bf520d, 0x00bd500c, 0x00ba5010, 0x00b05119, 0x00954b1d, 0x00541500, 0x00501500, 0x0099522f, 0x00b4521c, 0x00bd4d0e, 0x00bf500f, 0x00bc500c, 0x00ba500c, 0x00b9510c, 0x00bb510f, 0x00bb510f, 0x00bc5310, 0x00b8500e, 0x00b25011, 0x00a1501c, 0x00622d14, 0x001c0000, 0x00150000, 0x00180000, 0x004f1e07, 0x008e4924, 0x00ae521e, 0x00ad5421, 0x007c3e1c, 0x00341000, 0x000c0000, 0x00200900, 0x005b2404, 0x00a8542e, 0x00b54e20, 0x00ba4c14, 0x00bb530c, 0x00b7530b, 0x00b45118, 0x00a64f22, 0x007c3a1c, 0x00411400, 0x00170000, 0x000d0000, 0x00140200, 0x001c0300, 0x00442006, 0x00713f1c, 0x009c582a, 0x00ac5824, 0x00b45015, 0x00bc4f10, 0x00c05012, 0x00bd4d0e, 0x00bd4e0d, 0x00be4f0c, 0x00bf4b08, 0x00c04f0c, 0x00bf520f, 0x00b85011, 0x00b45218, 0x00ab511f, 0x00984922, 0x00793410, 0x006d2c04, 0x00814820, 0x00623617, 0x00250500, 0x00130000, 0x00170000, 0x00662e19, 0x00984821, 0x00ba541b, 0x00c45410, 0x00c0580c, 0x00ad5b1d, 0x0051260b, 0x00150000, 0x000c0000, 0x00080000, 0x00060000, 0x00030000, 0x00000008, 0x00000009, 0x00000003, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000001, 0x00000001, 0x00000001, 0x00000000, 0x00030303, 0x00000000, 0x00000000, 0x00020200, 0x004d4d4c, 0x00a8a8a6, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0048494c, 0x0007040c, 0x00050000, 0x00190700, 0x00250900, 0x00200000, 0x00441400, 0x0084441a, 0x00ac5e25, 0x00ae5414, 0x00b95b15, 0x00b25a14, 0x00b15611, 0x00c05b18, 0x00b85819, 0x00944810, 0x005c2400, 0x00240000, 0x001a0000, 0x002f0900, 0x00643114, 0x00985028, 0x00ad5924, 0x00b25510, 0x00ba580d, 0x00b9520f, 0x00b85310, 0x00b85410, 0x00ad5414, 0x00a05627, 0x005d1a00, 0x00631e00, 0x0090451a, 0x00aa541c, 0x00b45717, 0x00bb5411, 0x00ba500c, 0x00bc5411, 0x00b8500c, 0x00b85106, 0x00bc560c, 0x00b3510f, 0x00af541c, 0x009e5626, 0x00491800, 0x00110000, 0x00080000, 0x00110000, 0x00482109, 0x0091481c, 0x00ac521c, 0x00b2541c, 0x00a64e1d, 0x007f3818, 0x003b0200, 0x00390600, 0x00662c12, 0x009e5225, 0x00ad541d, 0x00b0521a, 0x00ac5a28, 0x00693517, 0x00250800, 0x00080000, 0x00050000, 0x00110000, 0x00300900, 0x00783410, 0x00ac5420, 0x00b05013, 0x00b95418, 0x00b44d17, 0x00ae4c16, 0x00b05820, 0x009c5224, 0x00521c00, 0x002a0300, 0x00140000, 0x001c0000, 0x00582005, 0x00884a28, 0x007f4d30, 0x00542105, 0x00521500, 0x008d4217, 0x00b65915, 0x00c45a0c, 0x00c8550a, 0x00ba4f0b, 0x00ac541d, 0x007c4018, 0x001e0000, 0x00070000, 0x00000000, 0x000a0300, 0x00180000, 0x0063280c, 0x00a54c22, 0x00b84e1a, 0x00bb5118, 0x00b74e10, 0x00b54e0d, 0x00b85312, 0x00b14f11, 0x00a54e1a, 0x00642200, 0x004c0c00, 0x009d4a21, 0x00af5020, 0x00b8521b, 0x00b95014, 0x00b95010, 0x00b95210, 0x00b75310, 0x00b65410, 0x00b3510f, 0x00b55110, 0x00ba500f, 0x00b75014, 0x00a84f1c, 0x00733210, 0x001d0000, 0x000f0000, 0x00190000, 0x004b1a01, 0x00964a24, 0x00ae5424, 0x00ad531c, 0x00984d1e, 0x00492107, 0x00180000, 0x00120000, 0x00401804, 0x008c4018, 0x00b5531d, 0x00ba4d12, 0x00c05010, 0x00be5514, 0x00a84d13, 0x009d5229, 0x0070371d, 0x002c0400, 0x00110000, 0x000d0000, 0x000e0000, 0x002e0d00, 0x005d2b0f, 0x00934c24, 0x00a65120, 0x00b6541d, 0x00b95014, 0x00b94c10, 0x00bc4e10, 0x00bc4f10, 0x00bc4f10, 0x00bd5110, 0x00b84b0a, 0x00c4500d, 0x00c44c0c, 0x00bb480d, 0x00b8511d, 0x00a35027, 0x00864422, 0x00521e00, 0x00501a00, 0x007d3a0a, 0x00a45a28, 0x009b5226, 0x00602708, 0x001c0000, 0x00130000, 0x00280100, 0x008f4f31, 0x00b45015, 0x00c65208, 0x00c4540a, 0x00b0571d, 0x0052240c, 0x00100000, 0x00080000, 0x00040000, 0x00030000, 0x00000000, 0x00000203, 0x00000105, 0x00000003, 0x00000001, 0x00000001, 0x00000001, 0x00020000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010000, 0x00000001, 0x00010002, 0x00010004, 0x00000003, 0x00000003, 0x00000001, 0x00010000, 0x00000000, 0x00000000, 0x001b1c17, 0x00878881, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004a4d4e, 0x0008060c, 0x00060000, 0x000e0000, 0x00210100, 0x004d1d07, 0x008b4a26, 0x00ad581d, 0x00bb5a13, 0x00bc5409, 0x00bd580c, 0x00bb5d13, 0x00b7580e, 0x00bc4f08, 0x00ba510b, 0x00b45c1a, 0x00924f1c, 0x00532c12, 0x00180100, 0x000e0000, 0x00210400, 0x00491801, 0x0088451c, 0x00b05d1e, 0x00b5560e, 0x00b95210, 0x00bf5513, 0x00bc550c, 0x00b55412, 0x00a5531e, 0x00863e16, 0x004c0d00, 0x005e1f00, 0x00954b1d, 0x00ab551f, 0x00b35114, 0x00b8510f, 0x00bb530e, 0x00b9510b, 0x00b85209, 0x00b7530b, 0x00b4500e, 0x00b6551b, 0x00aa531c, 0x007c3b13, 0x00230400, 0x000c0000, 0x000c0000, 0x002c0c00, 0x0083421c, 0x00a54f1b, 0x00b24d10, 0x00bb581e, 0x00a04c22, 0x00783618, 0x002c0000, 0x00300300, 0x007b401e, 0x009f5324, 0x00b2541a, 0x00a54a12, 0x009c582c, 0x00491c00, 0x00120000, 0x000d0400, 0x00050000, 0x00180200, 0x004e1e00, 0x008c4416, 0x00ae541c, 0x00b55015, 0x00b94f19, 0x00b84d16, 0x00b65212, 0x00aa5118, 0x009b552b, 0x00501c04, 0x001f0000, 0x001c0100, 0x001c0000, 0x00461e0a, 0x004f2d1a, 0x003d1100, 0x00662300, 0x00ac5521, 0x00bf5e14, 0x00bf5404, 0x00c65408, 0x00bb5314, 0x009b5224, 0x00401400, 0x00120000, 0x00030001, 0x00040403, 0x00080000, 0x003f1700, 0x00843e18, 0x00b04d1c, 0x00c04f16, 0x00bb4c12, 0x00be5418, 0x00b55315, 0x00ac4f14, 0x00a8521f, 0x00782c01, 0x00490800, 0x00853f1a, 0x00ac501e, 0x00ba5216, 0x00ba5014, 0x00b85011, 0x00b9500e, 0x00b9510e, 0x00b7500d, 0x00b5500f, 0x00bb5516, 0x00b34e11, 0x00b35016, 0x00a84f1c, 0x00813b14, 0x00350600, 0x00120000, 0x000d0000, 0x003d1500, 0x008e4c24, 0x00b05322, 0x00b2501c, 0x00a45422, 0x0069310a, 0x00270c00, 0x00100000, 0x00280600, 0x006c3115, 0x00ac5220, 0x00b74a0c, 0x00be4c0c, 0x00bf5214, 0x00ab4d15, 0x00a95e33, 0x0066351c, 0x00210200, 0x00130000, 0x00130000, 0x00120000, 0x002a0c00, 0x00683418, 0x00995127, 0x00ac5119, 0x00b64d0f, 0x00ba4c0c, 0x00bf4e0e, 0x00bf4f10, 0x00bc4f10, 0x00bb4d0f, 0x00ba4c0e, 0x00bb4e11, 0x00bc5011, 0x00bc4c0c, 0x00bc4f12, 0x00b6501d, 0x00a44c24, 0x0076341a, 0x003e0a00, 0x003b0c00, 0x00662e04, 0x00a5541c, 0x00ae5115, 0x00ae4f1a, 0x009d4d25, 0x004e200b, 0x00160000, 0x001d0000, 0x005a2912, 0x00a95018, 0x00c3570f, 0x00c1570e, 0x00a34d15, 0x00461d04, 0x000c0000, 0x00050000, 0x00020000, 0x00020000, 0x00000000, 0x00000101, 0x00000103, 0x00000000, 0x00000000, 0x00000001, 0x00000001, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000200, 0x00000000, 0x00000000, 0x00000000, 0x00000001, 0x00000002, 0x00000004, 0x00010004, 0x00020001, 0x00020000, 0x00040301, 0x00000000, 0x005c5c58, 0x00b0b0ac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004e5152, 0x000a080c, 0x00080000, 0x001d0100, 0x004b1e02, 0x008a4924, 0x00b46330, 0x00b85815, 0x00be570c, 0x00c0580d, 0x00bc5408, 0x00ba5207, 0x00c15810, 0x00bf5415, 0x00ba5216, 0x00b9581a, 0x00a95a24, 0x00824c28, 0x003c1c07, 0x00080000, 0x00090100, 0x00130000, 0x00431c00, 0x008e4f19, 0x00b05b1b, 0x00b44e0f, 0x00c05312, 0x00bc540d, 0x00b8530f, 0x00b05218, 0x00ab5728, 0x00702f09, 0x003f0400, 0x005d2102, 0x008f4822, 0x00ab511c, 0x00ba5512, 0x00bc5107, 0x00bc5007, 0x00bd5411, 0x00b85010, 0x00b7500f, 0x00b75112, 0x00b35014, 0x00a55428, 0x00421501, 0x00170000, 0x000b0000, 0x00140000, 0x00622f13, 0x009a4f24, 0x00ae5016, 0x00b04d10, 0x00ad541f, 0x009b5228, 0x00632e12, 0x00240000, 0x00320800, 0x008b502e, 0x00af5522, 0x00b24f15, 0x00af5822, 0x00824016, 0x00310c00, 0x000c0000, 0x00060200, 0x00050000, 0x00200800, 0x00602c06, 0x00a6521d, 0x00b44c12, 0x00bd4e17, 0x00bf4e14, 0x00b84c0d, 0x00b35114, 0x00ac5826, 0x008f4c26, 0x0056250f, 0x00230000, 0x00140000, 0x00180000, 0x00180000, 0x00360d00, 0x0084380f, 0x00bc591c, 0x00c35808, 0x00c75602, 0x00c6530c, 0x00b1521c, 0x0070391a, 0x00170000, 0x000b0000, 0x00040000, 0x00030000, 0x00130000, 0x006c3714, 0x00a25020, 0x00b7511a, 0x00bd4d11, 0x00bd4d0e, 0x00bd5314, 0x00b04f14, 0x00a55221, 0x007d3b19, 0x00490b00, 0x00682100, 0x00a85828, 0x00b15417, 0x00b8530f, 0x00bc500b, 0x00bf4f09, 0x00c04f0a, 0x00c04f0c, 0x00c14d0c, 0x00bf4c0e, 0x00bf4c13, 0x00b64c19, 0x00a85328, 0x0084431f, 0x00340a00, 0x00170000, 0x00190000, 0x003c1600, 0x00925326, 0x00aa5621, 0x00ae4a15, 0x00ac5020, 0x00874b29, 0x00330d00, 0x00140000, 0x00190000, 0x00572309, 0x00944920, 0x00b65418, 0x00c0500c, 0x00bf4b0c, 0x00b64f18, 0x009c5328, 0x0068391e, 0x00190200, 0x000a0000, 0x000b0000, 0x00110000, 0x002b0600, 0x00753f20, 0x00a05426, 0x00b1571a, 0x00b9530d, 0x00bf530b, 0x00bd520c, 0x00b74d0b, 0x00b44c0c, 0x00b84d10, 0x00bf4f11, 0x00c15014, 0x00bb4a11, 0x00be5318, 0x00ac4b0a, 0x00a65116, 0x00934e25, 0x00592007, 0x002e0000, 0x002e0000, 0x00642500, 0x00a5541e, 0x00ba520f, 0x00c24f0a, 0x00bf4e14, 0x00af4f1c, 0x008d481d, 0x00401100, 0x00160000, 0x002c0800, 0x00904a1f, 0x00ac5418, 0x00bc5d18, 0x00964c14, 0x00371a00, 0x00080200, 0x00000000, 0x00000003, 0x00040001, 0x00040003, 0x00020004, 0x00000003, 0x00020000, 0x00000000, 0x00000000, 0x00000101, 0x00000100, 0x00000100, 0x00000100, 0x00000100, 0x00000100, 0x00000100, 0x00000400, 0x00000200, 0x00000100, 0x00000300, 0x00000000, 0x00000000, 0x00000000, 0x00000001, 0x00020003, 0x00050106, 0x00000001, 0x00302e30, 0x009f9f9f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00555658, 0x000e0b0c, 0x000c0000, 0x00341300, 0x007b4422, 0x00ad5f2e, 0x00b75718, 0x00bb5209, 0x00c45708, 0x00be560b, 0x00bc5409, 0x00c05308, 0x00c2540d, 0x00bc5114, 0x00b95318, 0x00b35114, 0x00ac5922, 0x00834b21, 0x00412208, 0x00080000, 0x00040200, 0x000e0300, 0x001f0400, 0x00522000, 0x009e541e, 0x00b4531a, 0x00bc5011, 0x00bd520e, 0x00b8500c, 0x00b65114, 0x00b35824, 0x009e552b, 0x005a1e00, 0x00370100, 0x005f2309, 0x00964a1d, 0x00b1581c, 0x00b95209, 0x00bb4f05, 0x00bd5012, 0x00ba5014, 0x00bc5112, 0x00b74e0c, 0x00ba5111, 0x00ac5421, 0x00683418, 0x00230600, 0x000a0000, 0x000b0000, 0x00371200, 0x00804422, 0x00ad5723, 0x00b25014, 0x00ad4f15, 0x00a85422, 0x0090502a, 0x00481800, 0x001e0000, 0x00461700, 0x009e5227, 0x00af531d, 0x00ad4f14, 0x00a45321, 0x005b260c, 0x001e0300, 0x00040000, 0x00020300, 0x00080000, 0x003a1800, 0x008d4217, 0x00b14d18, 0x00bc4d16, 0x00be4c11, 0x00b94c0c, 0x00b85012, 0x00ad4f14, 0x00ad5925, 0x00914b24, 0x00501c04, 0x00210400, 0x000e0000, 0x00150000, 0x004a1c04, 0x009e4919, 0x00be530f, 0x00c45200, 0x00cb5c09, 0x00bb5110, 0x009b481c, 0x003c1302, 0x000c0000, 0x00080000, 0x000b0101, 0x000a0000, 0x003e1e09, 0x008a4820, 0x00ac521d, 0x00bb5317, 0x00bb4b0c, 0x00bc4f0e, 0x00b44f11, 0x00a9511f, 0x008c431f, 0x00481000, 0x004a1100, 0x009d5126, 0x00ac5218, 0x00b25310, 0x00b75009, 0x00be5008, 0x00c05009, 0x00bf4d0a, 0x00c04c0c, 0x00c44c0e, 0x00c44b10, 0x00be4a16, 0x00b04d20, 0x008d4825, 0x00471800, 0x001d0000, 0x00170000, 0x003e1400, 0x008a4f28, 0x00a9581e, 0x00b05315, 0x00b45423, 0x00a04f2a, 0x00471904, 0x001c0000, 0x001b0000, 0x003f1701, 0x00854320, 0x00a74f1c, 0x00b85010, 0x00c0510f, 0x00b84c0f, 0x00a9501d, 0x00794325, 0x00200400, 0x00060000, 0x00050000, 0x000e0000, 0x002c0700, 0x00753b1a, 0x00994c1e, 0x00b5571d, 0x00b44c09, 0x00bb4f05, 0x00ba4f03, 0x00b84f07, 0x00b9510c, 0x00bb5413, 0x00bb5214, 0x00ba4c10, 0x00b4470d, 0x00b64e1c, 0x00a84c1b, 0x00a75f2c, 0x00743c0f, 0x00360c00, 0x001c0000, 0x00250000, 0x00622b12, 0x009c4e22, 0x00b35115, 0x00bd4a04, 0x00c34a03, 0x00c14d0e, 0x00b84f15, 0x00a8521c, 0x0089481c, 0x00340b00, 0x00200000, 0x006b300c, 0x009d5220, 0x00b35e21, 0x008a4612, 0x00321903, 0x00030000, 0x00000000, 0x00000003, 0x00030004, 0x00040004, 0x00020004, 0x00020001, 0x00020000, 0x00000000, 0x00000100, 0x00000200, 0x00000200, 0x00000100, 0x00000100, 0x00000100, 0x00000100, 0x00000100, 0x00000100, 0x00000100, 0x00000400, 0x00020400, 0x00000000, 0x00000000, 0x00000100, 0x00000000, 0x00050104, 0x00020003, 0x00111014, 0x00807f83, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005f5f5f, 0x00120f0e, 0x000f0000, 0x00381400, 0x0081441f, 0x00b45b20, 0x00c0550c, 0x00cb590b, 0x00c65608, 0x00b95106, 0x00bd570e, 0x00c0550e, 0x00bc500b, 0x00bb510d, 0x00bd5916, 0x00b05414, 0x00a45b23, 0x00613610, 0x00281000, 0x000d0000, 0x00080000, 0x002b140b, 0x00452413, 0x002c0000, 0x006e300b, 0x00b05928, 0x00b44e14, 0x00bd500f, 0x00bd500d, 0x00b44f0e, 0x00b25519, 0x00a24e20, 0x00904926, 0x004b1400, 0x00340100, 0x00652b0a, 0x00924b1b, 0x00b25417, 0x00bb510f, 0x00ba4c0c, 0x00bc4c0e, 0x00c05415, 0x00bb5110, 0x00bc5412, 0x00a75017, 0x0088502c, 0x002f1000, 0x00080000, 0x00040000, 0x00140000, 0x0050250c, 0x00964d21, 0x00ad5219, 0x00b95418, 0x00ae4c14, 0x00a04c1e, 0x00884525, 0x002a0000, 0x00240000, 0x00642c0d, 0x009c5428, 0x00a95016, 0x00ae5420, 0x00884426, 0x003b0e02, 0x000c0000, 0x00000406, 0x00000100, 0x001b0a00, 0x0064270a, 0x00a94e23, 0x00b84e1a, 0x00b94b0f, 0x00b85010, 0x00b84f0d, 0x00b9500c, 0x00b85110, 0x00ae5016, 0x00974c22, 0x0049200e, 0x001f0200, 0x00240000, 0x00682e0e, 0x00af5119, 0x00c6570e, 0x00c75805, 0x00c1590e, 0x00ab4f19, 0x00733113, 0x001a0000, 0x00050003, 0x00050004, 0x000b0000, 0x00220400, 0x00744020, 0x009e5121, 0x00b04f16, 0x00bc5311, 0x00bb4e0b, 0x00b85310, 0x00a94f17, 0x00924924, 0x00541800, 0x00370100, 0x00763820, 0x00ac5829, 0x00b25013, 0x00b8500c, 0x00b94e07, 0x00bc5009, 0x00bc500c, 0x00b84a0c, 0x00bb490e, 0x00c14c14, 0x00be4c14, 0x00b9531f, 0x00914014, 0x00582405, 0x00270200, 0x00180000, 0x00441802, 0x00904d28, 0x00aa541e, 0x00af4e0c, 0x00b15113, 0x00a4542c, 0x00652813, 0x002f0800, 0x001d0000, 0x00340f00, 0x006a3410, 0x00a05125, 0x00b04f1b, 0x00bf5419, 0x00b44a0e, 0x00ac5318, 0x008c481b, 0x003a1200, 0x000f0000, 0x00080404, 0x00060000, 0x00230200, 0x00763c18, 0x00a14e1d, 0x00b24f15, 0x00b74c0d, 0x00be5010, 0x00ba500e, 0x00b64c08, 0x00b74d09, 0x00ba500c, 0x00b9510e, 0x00b54c0b, 0x00b74d11, 0x00b5541e, 0x00a6552a, 0x008d502e, 0x00411c04, 0x001e0800, 0x00130000, 0x001c0100, 0x00602d11, 0x00914823, 0x00ad5020, 0x00b44b10, 0x00bb4c0b, 0x00bd4d09, 0x00bd500f, 0x00ba5214, 0x00b35117, 0x00a85524, 0x007c3a1a, 0x003a0200, 0x00450900, 0x008e4c24, 0x00a95b28, 0x0078380e, 0x002f1407, 0x00040000, 0x00020000, 0x00000000, 0x00000001, 0x00000001, 0x00000003, 0x00000101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010000, 0x00010000, 0x00020000, 0x00020000, 0x00040100, 0x00050300, 0x00040000, 0x00030000, 0x00020001, 0x00606261, 0x00b2b5b6, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x006d6c6c, 0x00181715, 0x000b0000, 0x00341000, 0x00773814, 0x00b75818, 0x00c85809, 0x00cc5708, 0x00c45304, 0x00bc550c, 0x00b8550f, 0x00b8540e, 0x00b9530c, 0x00bd560d, 0x00bc5a15, 0x00ab5314, 0x00904d1a, 0x00421f00, 0x00130100, 0x000d0000, 0x001d0603, 0x004c291a, 0x00734a34, 0x00320700, 0x00400900, 0x00914820, 0x00ae5320, 0x00b84f13, 0x00bf5110, 0x00b5500c, 0x00b35414, 0x00ac501b, 0x00a8542a, 0x0078381a, 0x003c0800, 0x00300400, 0x00602908, 0x00994c1c, 0x00b85921, 0x00bc5115, 0x00bb4b0d, 0x00bd5011, 0x00ba5010, 0x00b8500e, 0x00ac5117, 0x009a582e, 0x00472008, 0x000f0300, 0x00010002, 0x00080000, 0x00230700, 0x00612807, 0x009f5020, 0x00ad4f17, 0x00b45017, 0x00b15320, 0x00994c23, 0x00642b14, 0x00280000, 0x00280000, 0x0076401e, 0x00a45520, 0x00a9501b, 0x00a85533, 0x005f220f, 0x00210804, 0x00020001, 0x00000304, 0x00090000, 0x003d0f00, 0x00914423, 0x00b3501e, 0x00b74c0f, 0x00b85010, 0x00b64e0b, 0x00b84a04, 0x00bf500c, 0x00b64c0b, 0x00ad5725, 0x00824e36, 0x003a1503, 0x00340500, 0x007f3c14, 0x00b95719, 0x00ca5910, 0x00c25709, 0x00b25511, 0x00984c24, 0x00431100, 0x000f0000, 0x00030004, 0x00050001, 0x00110000, 0x00552307, 0x00985027, 0x00ab5420, 0x00b14e13, 0x00b8500c, 0x00b7520f, 0x00b0581c, 0x008f4717, 0x005a2006, 0x00330000, 0x00591b08, 0x009c5233, 0x00ac531e, 0x00b34f0f, 0x00bb4f0d, 0x00ba4d0a, 0x00ba500f, 0x00b85010, 0x00b74a0f, 0x00bb4d14, 0x00bd5219, 0x00b2501a, 0x00964718, 0x006c3008, 0x00270000, 0x001d0000, 0x00481a07, 0x008a4c2d, 0x00a64f21, 0x00b55218, 0x00b45214, 0x00ab5420, 0x007b3e23, 0x00340500, 0x00200000, 0x00280000, 0x00642e0c, 0x009c5827, 0x00ac521c, 0x00b65017, 0x00bb5019, 0x00af501b, 0x00964f1f, 0x00582804, 0x00160000, 0x000f0000, 0x000a0000, 0x00200800, 0x006c3817, 0x00954818, 0x00b45015, 0x00bd5010, 0x00c15011, 0x00bc4c0e, 0x00b84e12, 0x00bd5317, 0x00bd5012, 0x00b64c0b, 0x00b44e0f, 0x00b45419, 0x00ac5520, 0x009c5025, 0x006c3415, 0x00340e00, 0x00140000, 0x000c0000, 0x001b0400, 0x00532b10, 0x008f4a23, 0x00b05724, 0x00b44c16, 0x00c05318, 0x00bc4f10, 0x00bc500f, 0x00b84f0c, 0x00b64d0c, 0x00b85014, 0x00aa4b16, 0x00a45328, 0x00742e09, 0x00400000, 0x006a2b08, 0x009c562e, 0x006c3212, 0x00200802, 0x00060003, 0x00030000, 0x00000000, 0x00000000, 0x00000200, 0x00000203, 0x00000103, 0x00000001, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020000, 0x00020000, 0x00020000, 0x00030000, 0x00040000, 0x00020000, 0x00020000, 0x00040000, 0x00040000, 0x00020000, 0x00020000, 0x00000000, 0x004c4c48, 0x00aaaca9, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00817e7f, 0x00242422, 0x00080000, 0x00280b00, 0x006e3414, 0x00b75b1b, 0x00c55507, 0x00c35002, 0x00c05004, 0x00bf5811, 0x00b3530d, 0x00b75810, 0x00b5580d, 0x00b35307, 0x00b2540d, 0x00ac551c, 0x007a3810, 0x002f0f00, 0x000c0000, 0x00100000, 0x0034140c, 0x006c3b1d, 0x00844d2c, 0x004d1e06, 0x002c0000, 0x005e2208, 0x00a35730, 0x00b25019, 0x00bb5110, 0x00b75310, 0x00b45210, 0x00c05a1e, 0x00ac4d18, 0x009b4d23, 0x00692d0d, 0x002c0400, 0x00340c00, 0x00652d10, 0x00994e25, 0x00b4531d, 0x00bb4e11, 0x00b84b10, 0x00b84c0f, 0x00b84b0c, 0x00b45118, 0x00a45425, 0x006d3617, 0x00240b02, 0x00080000, 0x00070000, 0x000c0000, 0x00361000, 0x00602704, 0x00a05524, 0x00ab541c, 0x00a84b10, 0x00a9521e, 0x0098512c, 0x00410c00, 0x001c0000, 0x00381000, 0x008a491f, 0x009c4a18, 0x00ab5228, 0x00924527, 0x003a1004, 0x000f0000, 0x00000000, 0x00060000, 0x00230100, 0x00692d14, 0x00aa4f1f, 0x00b84f10, 0x00b74d0c, 0x00b84e0c, 0x00b84f0d, 0x00b74c0d, 0x00b84e13, 0x00a74c1c, 0x00884d31, 0x00461500, 0x00602301, 0x00974818, 0x00be5819, 0x00c1540e, 0x00b6550e, 0x00a2541b, 0x0070391d, 0x001e0000, 0x000b0000, 0x00060000, 0x000b0000, 0x00320e00, 0x00854019, 0x00aa501d, 0x00b2511a, 0x00b45014, 0x00b14d0d, 0x00aa5214, 0x008e4b1b, 0x00592504, 0x002b0000, 0x00400b00, 0x008d3c1d, 0x00b05024, 0x00b2541a, 0x00b04d0d, 0x00bc5011, 0x00b94b0f, 0x00b94e15, 0x00b94e15, 0x00b94b10, 0x00ba5215, 0x00ae5318, 0x00934917, 0x00673411, 0x00280300, 0x002b0500, 0x004d1e06, 0x00904b28, 0x00a85025, 0x00ab4615, 0x00b85421, 0x00ab5427, 0x00864422, 0x00340d00, 0x001f0000, 0x002c0000, 0x0072341e, 0x009a4e23, 0x00ab5218, 0x00b65010, 0x00b84e0f, 0x00b24b17, 0x00a45028, 0x00663417, 0x00220500, 0x00120000, 0x00140000, 0x002a0500, 0x00643010, 0x00984e20, 0x00ac5119, 0x00b64d0f, 0x00c35314, 0x00b6450c, 0x00bb4c16, 0x00b94a16, 0x00bc4d19, 0x00bd4c14, 0x00b64c13, 0x00b0531d, 0x00a05323, 0x00753b17, 0x00461e04, 0x001d0300, 0x00120000, 0x00130000, 0x00280700, 0x00602b08, 0x00985024, 0x00b0521c, 0x00b34a10, 0x00ba5014, 0x00b4490c, 0x00bd5414, 0x00b44b09, 0x00b64a08, 0x00c05314, 0x00b34b0f, 0x00b8551d, 0x00ad501a, 0x00a55221, 0x006c2400, 0x00551700, 0x00844826, 0x00542610, 0x00140000, 0x00060008, 0x00030003, 0x00000001, 0x00000000, 0x00000200, 0x00000203, 0x00000005, 0x00000005, 0x00020004, 0x00020001, 0x00020001, 0x00020001, 0x00020001, 0x00020003, 0x00030003, 0x00030004, 0x00030004, 0x00020004, 0x00040005, 0x00000003, 0x00000003, 0x00040307, 0x00000003, 0x00000003, 0x0009090b, 0x00363532, 0x00a4a5a0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00928f90, 0x00313130, 0x00050000, 0x00180000, 0x00642f13, 0x00b1581b, 0x00c6590a, 0x00ca580b, 0x00c15208, 0x00b9540f, 0x00b3540f, 0x00b0540c, 0x00b5580c, 0x00b5560b, 0x00b55816, 0x00ae5928, 0x00602102, 0x00220400, 0x000c0000, 0x00180000, 0x00401708, 0x008c4f25, 0x00945427, 0x00633014, 0x00250000, 0x00310600, 0x008a5032, 0x00ac5522, 0x00b44f10, 0x00b5500c, 0x00bb530e, 0x00b64c0a, 0x00b55012, 0x00b05720, 0x008f491f, 0x004f2208, 0x00220000, 0x00330a00, 0x006d341b, 0x009f4e21, 0x00b4521c, 0x00b54c14, 0x00bb4d14, 0x00bc4e10, 0x00b95014, 0x00ad511d, 0x008f4822, 0x00391301, 0x00100000, 0x00050000, 0x00080000, 0x00130000, 0x002f0b00, 0x006b3410, 0x009e5626, 0x00af561c, 0x00ac5117, 0x00a34e1c, 0x0086431e, 0x00300700, 0x001d0000, 0x00531d00, 0x00965026, 0x00a75023, 0x00a0502b, 0x005a2512, 0x00200300, 0x00050000, 0x00050000, 0x00120000, 0x00451a05, 0x009c4d21, 0x00b35016, 0x00b44a0e, 0x00b94f10, 0x00b44a0c, 0x00bc5216, 0x00b64d15, 0x00a94f20, 0x007c3e1f, 0x00480f00, 0x00702400, 0x00a94f18, 0x00c05614, 0x00bc540c, 0x00b45a18, 0x00945120, 0x00431b08, 0x00100000, 0x00060000, 0x000a0000, 0x00150000, 0x00602e15, 0x00a14f20, 0x00b44f16, 0x00b64d14, 0x00b55015, 0x00ac5117, 0x009b511f, 0x0060300d, 0x00250200, 0x00290200, 0x005a1e0d, 0x00ab4b23, 0x00b94c14, 0x00af4a0c, 0x00ba5614, 0x00bd5012, 0x00bb4a10, 0x00ba4b15, 0x00b84c18, 0x00b54c14, 0x00b0521b, 0x00954c19, 0x006d380e, 0x00310a00, 0x00280400, 0x004d1c04, 0x008c4a2a, 0x00a44f24, 0x00b0501f, 0x00b45325, 0x00a54f28, 0x00854225, 0x00471400, 0x00210000, 0x00300700, 0x00703118, 0x0095451e, 0x00ae521c, 0x00b45010, 0x00bb4f0d, 0x00b44c10, 0x00af5126, 0x00874022, 0x00371300, 0x00100000, 0x001c0000, 0x002e0400, 0x006c3011, 0x00994e24, 0x00aa501c, 0x00b14c10, 0x00be5010, 0x00bc4b0b, 0x00bc4c12, 0x00b94b17, 0x00b94d1f, 0x00b34a1d, 0x00b24c20, 0x00aa4f24, 0x008a401b, 0x00592304, 0x002e0b00, 0x00180300, 0x000f0000, 0x00120000, 0x002d0800, 0x0068300b, 0x00994b1a, 0x00ac4d15, 0x00b84e12, 0x00bd5011, 0x00b84d10, 0x00b94f10, 0x00b64c0c, 0x00ba500f, 0x00bc4f0f, 0x00b74a0c, 0x00b84f10, 0x00b54d11, 0x00b65015, 0x00b2541c, 0x00a34e1e, 0x00672000, 0x006b3318, 0x00361002, 0x00110103, 0x00030005, 0x00020004, 0x00020001, 0x00000000, 0x00000000, 0x00000000, 0x00000001, 0x00020001, 0x00030001, 0x00030000, 0x00030000, 0x00030000, 0x00030000, 0x00040001, 0x00040001, 0x00040003, 0x00040003, 0x00030003, 0x00050106, 0x00000003, 0x00000004, 0x00010005, 0x00000004, 0x0006080c, 0x00292a2d, 0x009a9a98, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00080808, 0x00060606, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a3a4, 0x003c3d3b, 0x00030000, 0x00160000, 0x004f1e05, 0x00ad581d, 0x00c4590d, 0x00c45207, 0x00c4540c, 0x00b4500c, 0x00b75712, 0x00b95610, 0x00b45008, 0x00ba5710, 0x00b25417, 0x00a8542a, 0x00591c04, 0x001e0000, 0x000c0000, 0x00200200, 0x00562811, 0x009c5824, 0x009e581f, 0x006f3c1a, 0x00220000, 0x001d0100, 0x005c351c, 0x009d5525, 0x00b15113, 0x00bd5110, 0x00be4e08, 0x00ba4f08, 0x00b8530f, 0x00b15113, 0x00a65420, 0x007d401c, 0x00421500, 0x00200000, 0x00351100, 0x00703417, 0x00a4542c, 0x00aa4a18, 0x00b95014, 0x00be4e0f, 0x00b84a0a, 0x00b44d13, 0x00aa5628, 0x00582408, 0x001c0000, 0x00100100, 0x00040000, 0x00060000, 0x00140300, 0x00341200, 0x00743c1b, 0x00a65723, 0x00ae5115, 0x00b04e14, 0x00a65121, 0x006b2f15, 0x002e0000, 0x002c0000, 0x00662f10, 0x00974d24, 0x009d542c, 0x00763d25, 0x00351004, 0x00080000, 0x00020202, 0x00040000, 0x00260c00, 0x007c3916, 0x00af5424, 0x00b14a16, 0x00bb4d14, 0x00bb4b0d, 0x00b84c10, 0x00b64c18, 0x00ac5428, 0x006a2b0c, 0x00490a00, 0x008c3502, 0x00bd5517, 0x00c6570e, 0x00bd540c, 0x00ac5819, 0x00773c12, 0x00240500, 0x00080000, 0x00040000, 0x000c0000, 0x003a1100, 0x008e4c27, 0x00a94d19, 0x00b74d11, 0x00b94b0f, 0x00b65018, 0x00a0511f, 0x0068310c, 0x002b1000, 0x00120000, 0x00350b00, 0x00843d24, 0x00b44818, 0x00c44c0c, 0x00bb500c, 0x00b8500b, 0x00ba4c0c, 0x00be4e0f, 0x00bf4d12, 0x00b44912, 0x00ad511f, 0x009d5227, 0x00673110, 0x00370c00, 0x00300400, 0x00582107, 0x008e421d, 0x00ac5326, 0x00ac4e1c, 0x00a85020, 0x009e542f, 0x007a4025, 0x00391303, 0x00240000, 0x00400c00, 0x00783414, 0x009f4818, 0x00b04f13, 0x00b65210, 0x00b34c09, 0x00b74c13, 0x00b14f20, 0x00984a28, 0x005a240d, 0x00200400, 0x001a0100, 0x00441400, 0x00783718, 0x009f4f27, 0x00ac5121, 0x00b14f18, 0x00b54d10, 0x00bf500d, 0x00c04f0c, 0x00bd4c0c, 0x00b94e15, 0x00b04e1f, 0x00a6502a, 0x008c4428, 0x00622913, 0x00380f00, 0x001d0000, 0x00100000, 0x000f0000, 0x00140000, 0x003c1000, 0x0074320c, 0x009f4b17, 0x00b45116, 0x00b85011, 0x00b74d11, 0x00b74d11, 0x00b84d10, 0x00b94c0e, 0x00bc4c0e, 0x00bc4c0f, 0x00bc4d11, 0x00bc4f10, 0x00bb4f0d, 0x00ba4e0d, 0x00ba4d12, 0x00b94d17, 0x00c05822, 0x00a0481c, 0x005e240a, 0x00280700, 0x000a0000, 0x00030002, 0x00010004, 0x00030001, 0x00080000, 0x00080000, 0x00080000, 0x00060000, 0x00050000, 0x00050000, 0x00060000, 0x00060000, 0x00060000, 0x00060000, 0x00060000, 0x00070000, 0x00070000, 0x00060000, 0x00070000, 0x00040000, 0x00060101, 0x00020000, 0x00020204, 0x00000002, 0x0006090c, 0x0046474a, 0x00a1a1a3, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000f0f0f, 0x00141414, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00313131, 0x00494c4c, 0x00040100, 0x00110000, 0x00441800, 0x009c4c14, 0x00c05910, 0x00c45408, 0x00c6550c, 0x00b6510d, 0x00b55411, 0x00bc5411, 0x00b8500d, 0x00b8530f, 0x00b05116, 0x00a75429, 0x00571b02, 0x00170000, 0x000c0000, 0x00270902, 0x005f3016, 0x00a35a22, 0x00a55a20, 0x007c4521, 0x00210000, 0x00110000, 0x00381c07, 0x00985628, 0x00af5216, 0x00bc5010, 0x00be4e0a, 0x00bb5008, 0x00b8520b, 0x00b4500d, 0x00ac5318, 0x009c5024, 0x006c3214, 0x002d0c00, 0x00180000, 0x00441805, 0x00783c1f, 0x00a9562a, 0x00b3501a, 0x00bb4e10, 0x00bc4d0b, 0x00bb5212, 0x00ac511b, 0x0083421e, 0x003a1100, 0x00120000, 0x00080000, 0x00040204, 0x00040000, 0x00180500, 0x004a220c, 0x00924d24, 0x00b0551f, 0x00b34c10, 0x00ae4c17, 0x009e5431, 0x005f2610, 0x002a0000, 0x00360a00, 0x00713713, 0x00985a34, 0x00884d31, 0x00502414, 0x00110200, 0x00020100, 0x00030300, 0x00180600, 0x005c260a, 0x00a75631, 0x00af5023, 0x00b44e1a, 0x00b94f18, 0x00b54c16, 0x00b04c1e, 0x00a6512b, 0x00591c00, 0x004f1000, 0x00963a04, 0x00c25614, 0x00c6580d, 0x00b8550f, 0x009c511a, 0x00562400, 0x00130000, 0x00090000, 0x00080000, 0x00150000, 0x006c3514, 0x00a45122, 0x00b35018, 0x00b94c10, 0x00bc4c10, 0x00b25019, 0x00823c14, 0x00441800, 0x00130100, 0x00140000, 0x0051200d, 0x00994a29, 0x00c04e19, 0x00c84c0a, 0x00bc4e08, 0x00b85008, 0x00ba4d0a, 0x00ba4d0f, 0x00b74d11, 0x00b0531d, 0x009c5027, 0x00652a0c, 0x00320500, 0x00340800, 0x0063280f, 0x008e4421, 0x00ac4f20, 0x00b14e1b, 0x00ae5220, 0x00a15024, 0x00793c1a, 0x00441500, 0x00260000, 0x00481b08, 0x007b3414, 0x00a04819, 0x00b75214, 0x00b8500c, 0x00b04d0d, 0x00b2541a, 0x00b35628, 0x00954320, 0x006c2c12, 0x00400f00, 0x002f0900, 0x0050250a, 0x0083411c, 0x00a85428, 0x00ad4d1d, 0x00b44c18, 0x00b95018, 0x00b84f13, 0x00b44b09, 0x00b54c0b, 0x00b44f11, 0x00a74d18, 0x0091481f, 0x00703519, 0x00441c0b, 0x00240700, 0x00110000, 0x000d0000, 0x00130000, 0x001c0000, 0x004a1e06, 0x00783917, 0x00a44f22, 0x00b4501a, 0x00b5480d, 0x00b84b0e, 0x00b85013, 0x00b74f12, 0x00bb5013, 0x00bc4f10, 0x00bd4d10, 0x00bc4c0e, 0x00b84c0f, 0x00b94d0c, 0x00ba4d08, 0x00bb4e0b, 0x00bb4e10, 0x00be5114, 0x00c15415, 0x00b35724, 0x00683117, 0x00280800, 0x00100000, 0x000b0000, 0x000c0000, 0x00100000, 0x00190000, 0x00200000, 0x00220000, 0x00260600, 0x00290c00, 0x002c1000, 0x002b0e00, 0x002c0f00, 0x002d1000, 0x002a0c00, 0x00260900, 0x00230800, 0x001f0300, 0x00190000, 0x00130000, 0x000e0000, 0x000f0000, 0x00080000, 0x00060000, 0x00040000, 0x00030000, 0x00212020, 0x00373539, 0x00545458, 0x00838288, 0x00acacb2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00101010, 0x00252526, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005f6261, 0x00100d09, 0x000f0000, 0x003c1100, 0x00863a05, 0x00bf5a14, 0x00c35305, 0x00c85609, 0x00b9530c, 0x00b55110, 0x00b95014, 0x00bc5114, 0x00b7500d, 0x00b15414, 0x00a95826, 0x00612505, 0x00190000, 0x000e0000, 0x00200600, 0x005e3219, 0x00a05826, 0x00a45620, 0x00844520, 0x002d0200, 0x00110000, 0x00220600, 0x00945326, 0x00ac5215, 0x00b65014, 0x00ba4d0f, 0x00b9500c, 0x00b85009, 0x00b4500a, 0x00b15212, 0x00ae5721, 0x008f471d, 0x0058280c, 0x00240200, 0x001c0000, 0x00401603, 0x00854321, 0x00aa5324, 0x00b24d10, 0x00b74d09, 0x00b64f0c, 0x00aa4d11, 0x009c5426, 0x00602a0b, 0x00210000, 0x000f0000, 0x00050104, 0x00000004, 0x00060000, 0x00240800, 0x006b3014, 0x00a6552a, 0x00b4501a, 0x00b44f19, 0x00a85024, 0x008e4828, 0x0051240e, 0x00290400, 0x00411800, 0x007c4928, 0x00925338, 0x00683420, 0x00240b07, 0x00080000, 0x00070000, 0x00130000, 0x003d1000, 0x00915032, 0x00a2512c, 0x00aa5125, 0x00a94c1d, 0x00a84c1f, 0x00a84f2a, 0x00974c2c, 0x00471200, 0x005c2201, 0x00a14814, 0x00bf5817, 0x00bf5813, 0x00b05818, 0x00814418, 0x00370f00, 0x00110000, 0x00100000, 0x00100200, 0x003b1905, 0x00975127, 0x00ad5018, 0x00b84f14, 0x00ba4c10, 0x00bb4c13, 0x00af5320, 0x00703311, 0x00310c00, 0x00100000, 0x00270b00, 0x0072361c, 0x00a54f28, 0x00bc4c17, 0x00bf4808, 0x00b94903, 0x00b84c05, 0x00bc500f, 0x00b34e13, 0x00ac551e, 0x00944f20, 0x005e2b0e, 0x00320700, 0x00370800, 0x00622815, 0x00944420, 0x00ac5020, 0x00b34f1a, 0x00b04f1b, 0x009d4a1e, 0x00722c05, 0x00480d00, 0x00370100, 0x005d2204, 0x0089431e, 0x00ac521d, 0x00b45010, 0x00b95210, 0x00b45214, 0x00a54d1b, 0x009c4f27, 0x007b381c, 0x00591c08, 0x004c1200, 0x00581d01, 0x0078340f, 0x00994e1d, 0x00aa531f, 0x00ae4d16, 0x00b95016, 0x00b4480c, 0x00b74c10, 0x00ba5216, 0x00b04f14, 0x00a95319, 0x00984f1c, 0x00763e14, 0x0049260a, 0x00200c00, 0x00060000, 0x00080300, 0x000f0100, 0x00140000, 0x00340c00, 0x0060280c, 0x00884012, 0x00a4501c, 0x00b75427, 0x00b44c1f, 0x00b24716, 0x00b74e18, 0x00b75215, 0x00b34d0e, 0x00b54b0d, 0x00b94b0f, 0x00bb4c10, 0x00bb4e10, 0x00b9500e, 0x00ba4e0c, 0x00bd4e0c, 0x00bc500c, 0x00b44e08, 0x00bc5810, 0x00ba530a, 0x00b35c22, 0x00592a0a, 0x00210300, 0x00280500, 0x00361000, 0x00471e07, 0x00522207, 0x00642607, 0x00722c0a, 0x0079320f, 0x007d3710, 0x00823a10, 0x00843c0e, 0x00883e0a, 0x00884008, 0x00883e08, 0x00843d0a, 0x007f3c0a, 0x00783809, 0x006e3206, 0x00642d06, 0x005c2c08, 0x00481e00, 0x003a1700, 0x00280c00, 0x00180000, 0x00100000, 0x000b0000, 0x00080000, 0x00060103, 0x0008070b, 0x00212025, 0x0045454c, 0x0072727a, 0x00a2a2aa, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000f0f0f, 0x002f2f30, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007b7c7d, 0x00262320, 0x000b0000, 0x002e0900, 0x00702c00, 0x00b85c1c, 0x00c15408, 0x00c75507, 0x00bc530b, 0x00b7520f, 0x00b74f13, 0x00ba5216, 0x00b45010, 0x00b35516, 0x00ae5720, 0x007c370e, 0x00340e00, 0x00140000, 0x00140000, 0x0046250f, 0x00894c23, 0x009e5728, 0x008c4c29, 0x00421200, 0x00140000, 0x001d0000, 0x008f4b1f, 0x00aa5015, 0x00af5018, 0x00b34e13, 0x00b84f0d, 0x00b84d08, 0x00b64e09, 0x00b4500e, 0x00b15016, 0x00a04d1c, 0x00884723, 0x00502109, 0x00160000, 0x001e0000, 0x004c1800, 0x0089431e, 0x00ac531e, 0x00b35213, 0x00ae4c0d, 0x00af5015, 0x00a4521d, 0x008a481e, 0x004e1f04, 0x001e0100, 0x00060000, 0x00050408, 0x00040004, 0x00110000, 0x003a0f00, 0x00884724, 0x00aa5324, 0x00ad4f1c, 0x00a54e21, 0x009e5734, 0x007b4f37, 0x00462612, 0x00290800, 0x004d2308, 0x00783b21, 0x00622815, 0x002c0c05, 0x000f0000, 0x000d0000, 0x00140000, 0x002c0400, 0x00632c13, 0x00733010, 0x007e3510, 0x00823813, 0x00883d1a, 0x008c4124, 0x0075351b, 0x003c0c00, 0x00653113, 0x00a35324, 0x00b75c24, 0x00af571b, 0x00a05723, 0x005d2e0e, 0x001f0000, 0x00150000, 0x00100000, 0x00200700, 0x00704224, 0x00a45423, 0x00ae490c, 0x00b94c0e, 0x00bc4c0f, 0x00b84c14, 0x00ae5224, 0x00773b1c, 0x003c1400, 0x00180000, 0x00401800, 0x008c4825, 0x00ac5024, 0x00ba4c18, 0x00be4c0f, 0x00ba500c, 0x00b75310, 0x00af4e17, 0x00a54f1d, 0x00904c1e, 0x00602904, 0x00310500, 0x00390c00, 0x00662c18, 0x008f472c, 0x00a74c22, 0x00b25020, 0x00aa4c1b, 0x00943f12, 0x00702802, 0x004e0d00, 0x00541500, 0x0079370f, 0x009c4e25, 0x00aa501e, 0x00b55111, 0x00b44f0c, 0x00ad5016, 0x00a15121, 0x0084401d, 0x0064280f, 0x004d1400, 0x00581c07, 0x00723014, 0x0090461f, 0x00a8521e, 0x00b05217, 0x00b24d12, 0x00b74d12, 0x00bc4e10, 0x00b7480c, 0x00b44e15, 0x00b0511e, 0x009c4c1c, 0x00814016, 0x005b2a07, 0x00301100, 0x00140400, 0x00080300, 0x00040100, 0x000d0300, 0x00240a00, 0x00491e08, 0x0074381b, 0x00984c23, 0x00ac5418, 0x00b25011, 0x00b54c18, 0x00b6481c, 0x00b84c1f, 0x00b8501e, 0x00b45017, 0x00b04d10, 0x00b65014, 0x00b84e12, 0x00b85011, 0x00b9500e, 0x00b84f0c, 0x00b84c0b, 0x00bb4b0c, 0x00b94c0b, 0x00b85108, 0x00c15c10, 0x00bc580d, 0x00a85718, 0x00491a00, 0x00391400, 0x00642e0c, 0x007d4016, 0x008c481c, 0x00984d1c, 0x00a8541d, 0x00b45a20, 0x00b95c22, 0x00bc5b20, 0x00bc591e, 0x00bd581b, 0x00bd5c18, 0x00bc5b14, 0x00bb5914, 0x00bb5c17, 0x00ba5f1a, 0x00b75e1c, 0x00b05b1c, 0x00a8581c, 0x009f541d, 0x00904d1c, 0x0081441b, 0x00743d19, 0x00602f11, 0x004e2308, 0x003c1400, 0x00220100, 0x00100000, 0x000c0100, 0x00080000, 0x00040000, 0x00181418, 0x00403d43, 0x006c6d71, 0x00a0a1a4, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000b0b0b, 0x002c2c2e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9c9d, 0x003d3a39, 0x00060000, 0x001b0000, 0x00572000, 0x00a85722, 0x00bf580f, 0x00c55404, 0x00bf5408, 0x00b9530d, 0x00b65212, 0x00b45417, 0x00b05315, 0x00b15417, 0x00b35115, 0x009e4816, 0x00612506, 0x002a0400, 0x00120100, 0x001d0c00, 0x00542e10, 0x0085502d, 0x008d5132, 0x005c2814, 0x00150000, 0x001c0000, 0x00884017, 0x00a85017, 0x00a9521c, 0x00ad5018, 0x00b94f13, 0x00bb4a0a, 0x00b94e0a, 0x00b64f0c, 0x00b25012, 0x00ab501a, 0x00a35225, 0x00783714, 0x00340c00, 0x001d0000, 0x00230000, 0x004e1a04, 0x008b421c, 0x00a65121, 0x00ab4f1b, 0x00b1521c, 0x00ac4d17, 0x00a85424, 0x0080401a, 0x003f1300, 0x00140000, 0x00070000, 0x00030000, 0x00090000, 0x001e0500, 0x005a2e15, 0x00915028, 0x00904419, 0x00843e19, 0x00703518, 0x00583018, 0x003c200b, 0x00200300, 0x00270100, 0x00470e00, 0x00440a00, 0x00330900, 0x00260800, 0x00250800, 0x00290c00, 0x00310c00, 0x003c0f00, 0x00431000, 0x00451100, 0x00441000, 0x00481400, 0x00511802, 0x00430d00, 0x002c0200, 0x004d2003, 0x007b3a16, 0x008d451c, 0x00975327, 0x00844d28, 0x003e1c09, 0x00130000, 0x00140000, 0x00190000, 0x004b2007, 0x0093562f, 0x00a8521e, 0x00b34d10, 0x00bc4c0c, 0x00bd4d0e, 0x00b44a13, 0x00aa5021, 0x00884626, 0x004c1a00, 0x002c0100, 0x005c2806, 0x00a05229, 0x00af5020, 0x00b64b18, 0x00b74c15, 0x00b15114, 0x00a75119, 0x00a1552a, 0x00854422, 0x00551e04, 0x00300000, 0x00410e00, 0x006f3410, 0x0094481c, 0x00a95427, 0x00ad5228, 0x009f4a24, 0x007f3613, 0x005e1c00, 0x00541800, 0x006b2a04, 0x008d4219, 0x00a65224, 0x00ac501c, 0x00ad4c11, 0x00b24d10, 0x00aa5018, 0x008c4921, 0x0066361b, 0x00441e0c, 0x00330900, 0x005c1c04, 0x008c3d1c, 0x00ab4f21, 0x00b05017, 0x00b35211, 0x00b34f0d, 0x00b54a11, 0x00bb4d15, 0x00b84a0c, 0x00b85014, 0x00ab501d, 0x0090451c, 0x00693116, 0x003f1904, 0x001c0500, 0x000c0000, 0x000a0000, 0x00150500, 0x002a0e00, 0x00441a00, 0x006a300d, 0x008f4822, 0x00a6532a, 0x00ac5020, 0x00b45214, 0x00b64d0d, 0x00b84c10, 0x00bc4c17, 0x00ba4c19, 0x00b44917, 0x00af4b16, 0x00af5019, 0x00b05218, 0x00b05013, 0x00b24e0c, 0x00b54e0b, 0x00b74d0b, 0x00b84c0b, 0x00b84c10, 0x00ba4c0c, 0x00c05004, 0x00c3580a, 0x00bc5b14, 0x00914308, 0x00451000, 0x00663210, 0x009e5121, 0x00b1581b, 0x00b85815, 0x00bb5a10, 0x00bd5c0b, 0x00be5c08, 0x00c05b09, 0x00c15a09, 0x00c6570b, 0x00c7580d, 0x00c0570f, 0x00bf5811, 0x00c05910, 0x00c15a10, 0x00c15a0f, 0x00c15b0d, 0x00c15b0d, 0x00c15c10, 0x00bb570d, 0x00bc5b14, 0x00b55814, 0x00b55b1c, 0x00b0591f, 0x00a04c16, 0x00913f0a, 0x007a3306, 0x004f2000, 0x00341200, 0x00200400, 0x00100000, 0x000b0000, 0x00070000, 0x00181516, 0x00464748, 0x00808585, 0x00a4aca9, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00070707, 0x00232424, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00797879, 0x00555253, 0x00070403, 0x000b0000, 0x003b1300, 0x008a481e, 0x00ba5a15, 0x00c45504, 0x00c25408, 0x00bc5209, 0x00b85310, 0x00b25112, 0x00b05315, 0x00b05214, 0x00b44f11, 0x00b4541e, 0x0090421e, 0x00582309, 0x001e0600, 0x000c0000, 0x001f0600, 0x0045220e, 0x00633620, 0x005d3425, 0x001a0403, 0x00180000, 0x007c3711, 0x00a7501a, 0x00aa5420, 0x00ac5119, 0x00b84f15, 0x00bb4b0f, 0x00bd4d0e, 0x00b84d0e, 0x00b65013, 0x00b05017, 0x00ab501d, 0x00964a1f, 0x00693314, 0x00280300, 0x00150000, 0x001d0000, 0x00481400, 0x00814020, 0x00a2542c, 0x00ac5121, 0x00b5521a, 0x00af4e17, 0x00a25325, 0x00753c1c, 0x003b1a0a, 0x000d0000, 0x00040000, 0x00050000, 0x00130100, 0x00280800, 0x005e2807, 0x00591800, 0x004d0900, 0x004d0f00, 0x00421000, 0x00441800, 0x004c1d00, 0x00541f00, 0x00652100, 0x006a2404, 0x00692d0e, 0x006e3619, 0x006c3618, 0x006b3415, 0x006e3514, 0x006b300a, 0x006e3007, 0x006b2e04, 0x005c2602, 0x00582001, 0x005d1f00, 0x00551700, 0x00481300, 0x00440f00, 0x004c1000, 0x00541500, 0x00602804, 0x004d2003, 0x00230500, 0x00100000, 0x00100000, 0x00321003, 0x007d492b, 0x00a0582e, 0x00ac531c, 0x00b75114, 0x00ba4c0c, 0x00bc4d0c, 0x00b4490f, 0x00ac4d1c, 0x00964d29, 0x00571c00, 0x00430c00, 0x0078380f, 0x00aa5324, 0x00b14e1b, 0x00b24b17, 0x00b14e1b, 0x00a7531f, 0x00964f22, 0x00753c1c, 0x00471600, 0x00300000, 0x00420d00, 0x0074330f, 0x009c5024, 0x00a9521e, 0x00a84d1b, 0x00954014, 0x007a2e0b, 0x00682a0d, 0x00683015, 0x00784020, 0x00915432, 0x009d5732, 0x00a05028, 0x00a85124, 0x00ac5524, 0x009d491c, 0x007d3710, 0x004f2004, 0x002a0700, 0x002c0800, 0x0051200c, 0x008a3d1d, 0x00ae4e24, 0x00b64d14, 0x00b44b08, 0x00b8500d, 0x00b85010, 0x00b64c16, 0x00b34b19, 0x00b1511f, 0x00a04d1c, 0x007f3814, 0x00551f03, 0x00300900, 0x00140000, 0x00100000, 0x001e0800, 0x00311100, 0x00481c00, 0x006c330c, 0x0090491c, 0x00a85424, 0x00af5320, 0x00b04f1c, 0x00b24e19, 0x00b14b10, 0x00b64c10, 0x00b84e12, 0x00b94e14, 0x00b64f18, 0x00b2501c, 0x00ad5323, 0x00a95424, 0x00a85323, 0x00a85220, 0x00ac531c, 0x00b0551c, 0x00b45419, 0x00b45017, 0x00b54e18, 0x00ba5014, 0x00c45108, 0x00c2560c, 0x00b55b1c, 0x00742a00, 0x00430900, 0x00804017, 0x00b3591c, 0x00c25a0f, 0x00c95d09, 0x00c95c03, 0x00c55c00, 0x00c45d00, 0x00c55e00, 0x00c75e03, 0x00cc5d04, 0x00cc5e0b, 0x00c56015, 0x00c4601a, 0x00c46016, 0x00c45e10, 0x00c15a09, 0x00c25804, 0x00c65903, 0x00ca5d05, 0x00c85902, 0x00ca5c06, 0x00c35502, 0x00c35606, 0x00c55b0f, 0x00c05810, 0x00bd5510, 0x00b95a1a, 0x00a25620, 0x00783b0c, 0x005b2400, 0x00431800, 0x00280800, 0x00130000, 0x00080000, 0x00070401, 0x001c1d1c, 0x00565b59, 0x00969d99, 0x001f2020, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x001c1c1c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00767478, 0x001a1e21, 0x00000000, 0x001e0700, 0x00643014, 0x00b0581b, 0x00c35808, 0x00c45607, 0x00c05004, 0x00bc4e08, 0x00b84e0c, 0x00b65114, 0x00b04f13, 0x00b24f14, 0x00b45420, 0x00a8502b, 0x00894324, 0x004c2005, 0x00280d00, 0x000d0000, 0x000c0000, 0x00221009, 0x0032221b, 0x00130802, 0x00170000, 0x006c2e0b, 0x00a14e1d, 0x00ad531c, 0x00b04d15, 0x00b54f14, 0x00b84b11, 0x00be4d14, 0x00bb4a10, 0x00b74c10, 0x00b04e10, 0x00ac4f17, 0x00a85424, 0x00944e29, 0x004f1c05, 0x00170000, 0x000a0000, 0x00140000, 0x00441f0f, 0x00763e21, 0x00994c21, 0x00b65319, 0x00b24c0d, 0x00ac531e, 0x0098532a, 0x0060351c, 0x00240b00, 0x000c0000, 0x000c0000, 0x00140200, 0x00200100, 0x00451100, 0x00531000, 0x00641800, 0x00792b04, 0x00843803, 0x00904306, 0x00a14f11, 0x00ae5618, 0x00b75c20, 0x00b85c1c, 0x00b55816, 0x00b95c1c, 0x00b85c24, 0x00b75c23, 0x00b85719, 0x00bf5d1b, 0x00be5e19, 0x00ba5d1b, 0x00b45f1f, 0x00ac591d, 0x00ac531c, 0x00a14a13, 0x00944304, 0x00792f00, 0x00672400, 0x00581c00, 0x00491400, 0x00370a00, 0x00220000, 0x00170000, 0x00170000, 0x0039180e, 0x00854b2f, 0x009c5024, 0x00a64c18, 0x00b14e13, 0x00b84e0c, 0x00bc4c0c, 0x00ba4a0b, 0x00b44e17, 0x00a25128, 0x00682300, 0x005c1c00, 0x008e4518, 0x00ae4f18, 0x00b74e16, 0x00b44e1c, 0x00ab4f21, 0x00934a20, 0x00713b17, 0x00320c00, 0x00240000, 0x004e1800, 0x00843f19, 0x00a04c20, 0x00ab501e, 0x00a34816, 0x00903b0b, 0x007d3008, 0x00732e08, 0x00804020, 0x008c4f32, 0x0083482e, 0x00743c22, 0x006f3922, 0x007c482e, 0x0081472c, 0x00774027, 0x0058281a, 0x00371002, 0x00220300, 0x002c0500, 0x005c2100, 0x0093441d, 0x00af4e22, 0x00b9501c, 0x00b54e0d, 0x00b8500c, 0x00b44c0c, 0x00b04810, 0x00b34e1d, 0x00ab5129, 0x00894727, 0x00622e16, 0x003c1200, 0x00240200, 0x001a0000, 0x00230100, 0x003c1201, 0x00582108, 0x00803817, 0x009d4820, 0x00b35424, 0x00b6501c, 0x00b24913, 0x00b44a10, 0x00b64c13, 0x00b44c14, 0x00b34d18, 0x00b34c18, 0x00b34c15, 0x00ac4c13, 0x00a44e16, 0x00994f19, 0x008c481b, 0x00844119, 0x00883f20, 0x00883c20, 0x00873d1e, 0x0088401c, 0x008a4117, 0x00924212, 0x00a44614, 0x00b54c14, 0x00c65714, 0x00c15a19, 0x00a55422, 0x00591700, 0x00551800, 0x00934c1a, 0x00bb5c14, 0x00cc6009, 0x00cc5d01, 0x00cc5f02, 0x00cb6108, 0x00cb640c, 0x00cc670c, 0x00cb680b, 0x00c96708, 0x00c4660c, 0x00bd641b, 0x00b45c18, 0x00b0570f, 0x00b3580b, 0x00bb5d0b, 0x00c3610a, 0x00c86308, 0x00cc6407, 0x00ca6103, 0x00ca5f03, 0x00ca5d04, 0x00c75b04, 0x00c65908, 0x00c35808, 0x00bf5408, 0x00c0580c, 0x00c15a10, 0x00be5e19, 0x00af581f, 0x008c4418, 0x005c2405, 0x00370d00, 0x001f0500, 0x000a0000, 0x00030000, 0x000d0d0c, 0x00383a38, 0x007f807e, 0x008c8c89, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00161617, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00949599, 0x0031383e, 0x00000406, 0x00100000, 0x00471e08, 0x00a35724, 0x00ba5814, 0x00c0580f, 0x00bb5008, 0x00b55012, 0x00b15019, 0x00b05420, 0x00a8501e, 0x00a65120, 0x009f4c20, 0x009e4f2d, 0x00985538, 0x007a4b30, 0x004b2c1a, 0x001a0907, 0x00050001, 0x00060000, 0x00040000, 0x00040000, 0x00180300, 0x005e280a, 0x009b4d23, 0x00b0521b, 0x00b14b0f, 0x00b54d11, 0x00b54a11, 0x00bb4d17, 0x00b74911, 0x00b64c11, 0x00b55014, 0x00b15014, 0x00a84d15, 0x00a44e21, 0x00844224, 0x00300e03, 0x000e0000, 0x000b0000, 0x000e0000, 0x00351100, 0x00743c1d, 0x009e4c1d, 0x00ab511e, 0x00964718, 0x0085451e, 0x00633219, 0x00381200, 0x00240100, 0x00320f00, 0x003c1400, 0x00623014, 0x007c3c18, 0x00a05328, 0x00b55d2e, 0x00b3551d, 0x00b85a14, 0x00c16313, 0x00bc590b, 0x00bc5608, 0x00c45d0e, 0x00c05706, 0x00c85c06, 0x00c15500, 0x00c35909, 0x00ca5f11, 0x00c25302, 0x00cc5f0b, 0x00c55602, 0x00c35804, 0x00bd5b06, 0x00bf5e0b, 0x00be5a10, 0x00bd590f, 0x00bd5a0a, 0x00ba5e15, 0x00b4612c, 0x00a0542b, 0x008e4a1f, 0x00743710, 0x00572004, 0x00401100, 0x00300a00, 0x00300700, 0x00602509, 0x00813b14, 0x0098481c, 0x00a14b18, 0x00af5119, 0x00b44f12, 0x00b84c0f, 0x00b85018, 0x00ac5124, 0x007b2902, 0x00782a00, 0x00a35120, 0x00ac4c16, 0x00b04e1a, 0x00a24c21, 0x008a401b, 0x005e2504, 0x002f0000, 0x002e0700, 0x00502204, 0x0086441e, 0x00a55123, 0x00af4d1b, 0x00aa4613, 0x00993e0e, 0x008f3e13, 0x00904d28, 0x00895030, 0x007f4a30, 0x005e2d17, 0x003d1000, 0x002b0200, 0x00200000, 0x00280a00, 0x003f1e0e, 0x00250600, 0x00160000, 0x00170000, 0x002c0800, 0x00602e08, 0x00984c1c, 0x00af4d18, 0x00b74b14, 0x00b6490e, 0x00b44c0a, 0x00b75313, 0x00af4b15, 0x00aa4b1c, 0x00a24e28, 0x007f3c1f, 0x004a1c08, 0x00260200, 0x001c0000, 0x002c0400, 0x00401403, 0x00612c16, 0x008c4528, 0x00a44e2b, 0x00b04c21, 0x00b54a18, 0x00b84912, 0x00bb4910, 0x00bc4a10, 0x00b94b10, 0x00b74d12, 0x00b14f17, 0x00ac5020, 0x00a44e23, 0x009c4920, 0x008f451c, 0x00783e14, 0x00603006, 0x004c2100, 0x00421600, 0x003e0900, 0x003f0200, 0x003e0100, 0x00410400, 0x004d0f00, 0x006a2100, 0x00943907, 0x00b54f14, 0x00c05413, 0x00b45419, 0x0086411c, 0x00450c00, 0x00703006, 0x00a95c21, 0x00c2610e, 0x00cc6103, 0x00cc6202, 0x00cc6103, 0x00ca6008, 0x00c8630d, 0x00c36712, 0x00bc6611, 0x00b4640f, 0x00ae6013, 0x009f5414, 0x00904404, 0x008a3600, 0x00983f00, 0x00b15600, 0x00c4660b, 0x00ca690d, 0x00c96507, 0x00cc6908, 0x00cc6302, 0x00cc6809, 0x00cc6409, 0x00c75e03, 0x00c96008, 0x00c65d08, 0x00c55904, 0x00c35200, 0x00cc5c08, 0x00bf540c, 0x00b8581b, 0x00ac5c2c, 0x0085441f, 0x0054230a, 0x002d0c00, 0x00150000, 0x000a0000, 0x00050100, 0x0023221f, 0x006c6967, 0x00b2b0ac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00161617, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b1b8ba, 0x00585e60, 0x00070604, 0x000c0000, 0x00341000, 0x007b3e17, 0x00ac5c28, 0x00b6591f, 0x00aa4f17, 0x009b4d23, 0x008c4924, 0x00864420, 0x00804220, 0x00783d1e, 0x0071391c, 0x00703c25, 0x0070432f, 0x006b4736, 0x0064493d, 0x003a2622, 0x000d0000, 0x00080000, 0x00080000, 0x00050000, 0x00100000, 0x00441603, 0x009a542f, 0x00a94e16, 0x00b84f0f, 0x00bc4e10, 0x00ba4d12, 0x00b04b15, 0x00b2501a, 0x00b25018, 0x00b04b10, 0x00b64c10, 0x00b74d12, 0x00ac4a14, 0x00a04f25, 0x0073381f, 0x00260000, 0x000e0000, 0x00080000, 0x000c0000, 0x00281001, 0x00653520, 0x007c452c, 0x005a2b11, 0x00401200, 0x00380700, 0x00470c00, 0x006c2800, 0x00934714, 0x00a45218, 0x00ba6224, 0x00b85c1c, 0x00b95814, 0x00be5609, 0x00c85d09, 0x00c05a00, 0x00c15e03, 0x00c26610, 0x00c0600d, 0x00cc630f, 0x00cc6009, 0x00cc6105, 0x00cc6808, 0x00c46200, 0x00cc6908, 0x00cc650c, 0x00cc650c, 0x00c96106, 0x00c66204, 0x00c46500, 0x00c26602, 0x00c46308, 0x00c46008, 0x00c85c04, 0x00c65a06, 0x00c0580f, 0x00bf5815, 0x00bc571a, 0x00b85820, 0x00b25624, 0x009f4c1d, 0x007c350d, 0x00581b00, 0x00430800, 0x003c0200, 0x00521800, 0x00743613, 0x00964e24, 0x00a3501f, 0x00ab4b18, 0x00b4501d, 0x00af4c1f, 0x009c3c10, 0x00993b0a, 0x00aa4d1c, 0x00a85020, 0x00954820, 0x00763c20, 0x00431700, 0x00230000, 0x00340800, 0x00672c06, 0x00984d22, 0x00a85220, 0x00ad4e18, 0x00b34c14, 0x00b7511c, 0x00a84c1f, 0x009c4f28, 0x0081472c, 0x005c3020, 0x002f1008, 0x00140000, 0x000c0000, 0x000c0000, 0x000a0000, 0x00080000, 0x000a0000, 0x000c0000, 0x00130000, 0x00340f02, 0x006c361a, 0x00964d21, 0x00ac5015, 0x00b85010, 0x00bb4d0f, 0x00b74a0d, 0x00b64c11, 0x00b1501a, 0x00a44c20, 0x00954e2e, 0x0067321f, 0x002d0600, 0x001f0000, 0x00280300, 0x00491600, 0x00763414, 0x00994b25, 0x00ab5026, 0x00b44c20, 0x00bb4b1c, 0x00b74814, 0x00b94b11, 0x00bc4f10, 0x00b84c0d, 0x00b8470d, 0x00ba4f16, 0x00b3541c, 0x00a14e1c, 0x00964d23, 0x007d4122, 0x00582919, 0x00331005, 0x001c0100, 0x000f0000, 0x000a0000, 0x000d0000, 0x00150000, 0x00220000, 0x002e0000, 0x00440500, 0x005c1a00, 0x00813604, 0x00a14408, 0x00be5714, 0x00c25713, 0x00b25820, 0x00582504, 0x003b1000, 0x00884815, 0x00b8631c, 0x00c86308, 0x00ca5e00, 0x00c55d00, 0x00cc6708, 0x00c85d01, 0x00c4620f, 0x00b86820, 0x00a05e1e, 0x00915720, 0x006c3403, 0x00501600, 0x00672400, 0x00a44e00, 0x00cb6e0f, 0x00c66702, 0x00c26200, 0x00c86a0f, 0x00c7660a, 0x00cc6401, 0x00cc6400, 0x00cc6808, 0x00c06000, 0x00cc6c09, 0x00cc6a08, 0x00c46000, 0x00ca6407, 0x00c76000, 0x00c55b00, 0x00cc5a06, 0x00c85508, 0x00c25910, 0x00b55818, 0x00ac5b28, 0x00773510, 0x00401000, 0x00240500, 0x000c0000, 0x00040000, 0x0014100c, 0x00585550, 0x00b0b0ac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00030303, 0x00181919, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00808487, 0x00262320, 0x000a0000, 0x001b0000, 0x00491f06, 0x00905737, 0x00965029, 0x00803c17, 0x00501d03, 0x00411803, 0x00370f00, 0x002e0900, 0x002c0800, 0x002a0c00, 0x00280c00, 0x00240c01, 0x00200a01, 0x0024120c, 0x0022140f, 0x00180d0b, 0x000c0404, 0x00040000, 0x00030000, 0x000c0000, 0x002e0c00, 0x008c4f32, 0x00ab501c, 0x00b84e0c, 0x00b74909, 0x00b4490c, 0x00b14f18, 0x00ac4d18, 0x00b04d15, 0x00b24910, 0x00b84c0f, 0x00ba4d12, 0x00b04a13, 0x00ac5121, 0x00944a27, 0x005c2812, 0x001a0000, 0x00070000, 0x00020000, 0x00080000, 0x00200000, 0x002d0000, 0x00330600, 0x004c1800, 0x00773411, 0x00a5562a, 0x00b35920, 0x00b75510, 0x00bf590c, 0x00c15c09, 0x00ba5403, 0x00c65f0c, 0x00c95e05, 0x00cc6507, 0x00cc6805, 0x00c96604, 0x00c1660b, 0x00c56810, 0x00cc6509, 0x00cc6204, 0x00cc6606, 0x00c66604, 0x00c36904, 0x00c16908, 0x00c56810, 0x00c4660e, 0x00ca6808, 0x00cb6905, 0x00c86a01, 0x00c76902, 0x00c96706, 0x00cc6407, 0x00cc6103, 0x00cc6002, 0x00cc5f04, 0x00cc5c08, 0x00c65809, 0x00c85a11, 0x00c45912, 0x00bd5815, 0x00b75e1f, 0x00a95a24, 0x008a4018, 0x00682704, 0x00400500, 0x003b0100, 0x004f1300, 0x00793613, 0x009d4d26, 0x00a85026, 0x00a84e21, 0x00a74c1e, 0x00a54d1e, 0x00a04f24, 0x008e4522, 0x0062270b, 0x002e0000, 0x00200000, 0x00441a00, 0x0078411c, 0x00a15223, 0x00ab4f19, 0x00b3521b, 0x00ae4c15, 0x00b2501b, 0x00a44919, 0x00974821, 0x00733418, 0x003d1101, 0x001a0000, 0x000a0000, 0x00040001, 0x00080405, 0x00050100, 0x00080000, 0x000f0500, 0x00110800, 0x00140200, 0x003c1809, 0x00753e27, 0x00994f2c, 0x00aa5220, 0x00b35012, 0x00b54c08, 0x00b94d0c, 0x00b64c11, 0x00ad4d1c, 0x00a04c24, 0x008a4826, 0x004e1a02, 0x00260000, 0x00260000, 0x003d1200, 0x00693517, 0x0096502c, 0x00a65328, 0x00ac4d1c, 0x00b74d19, 0x00bc4a14, 0x00b9430b, 0x00c04b10, 0x00bc4c10, 0x00b44b0c, 0x00b34c10, 0x00b5501a, 0x00aa4d1c, 0x0095481d, 0x00844620, 0x004d1d00, 0x002c0800, 0x00150000, 0x00100101, 0x00080000, 0x00060000, 0x000a0000, 0x00100000, 0x00200000, 0x00441408, 0x006e301a, 0x00944d2c, 0x00a25628, 0x00a8531b, 0x00b04c0a, 0x00c05814, 0x00bc5716, 0x009f4c18, 0x00390a00, 0x00572c08, 0x009e581c, 0x00bc6112, 0x00c35c00, 0x00cc6200, 0x00c76105, 0x00c05e09, 0x00c86615, 0x00b55f18, 0x00965521, 0x00703b10, 0x00380400, 0x003c0600, 0x00733608, 0x00ab6326, 0x00c36a16, 0x00c05e00, 0x00ca6901, 0x00ca6b04, 0x00c06407, 0x00c96c10, 0x00c45e00, 0x00cc6808, 0x00c96c0f, 0x00c86c0c, 0x00c76803, 0x00c66700, 0x00c56806, 0x00c46807, 0x00c06302, 0x00cc6d0f, 0x00c25100, 0x00c65100, 0x00c85603, 0x00c85c0f, 0x00b95512, 0x00b66026, 0x00954e21, 0x00562204, 0x00240400, 0x00120000, 0x00060000, 0x000c0806, 0x00464844, 0x00b0b4b1, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00181819, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009ea1a2, 0x00454648, 0x00080404, 0x00070000, 0x001a0700, 0x00391f11, 0x00270500, 0x00230200, 0x00281308, 0x00403129, 0x0064554d, 0x007f716b, 0x0090847e, 0x00978c88, 0x008f8681, 0x00837d78, 0x0075716e, 0x00555250, 0x00302f2d, 0x00131414, 0x00030405, 0x00000304, 0x00000407, 0x00020000, 0x00150000, 0x0075442e, 0x00a54e1f, 0x00b54c0e, 0x00bb5413, 0x00b14c0e, 0x00b35018, 0x00b44e18, 0x00b1460c, 0x00be5114, 0x00b85013, 0x00b04c10, 0x00b04c17, 0x00ad4f1e, 0x00a45125, 0x008c502f, 0x002f1301, 0x00070000, 0x00050100, 0x00110300, 0x00260000, 0x00551800, 0x008b4011, 0x00a55015, 0x00b85714, 0x00c45d18, 0x00b9540f, 0x00bc5a0f, 0x00c46310, 0x00c66810, 0x00c3680e, 0x00c3660d, 0x00c46410, 0x00c56109, 0x00c96402, 0x00c96601, 0x00c6680c, 0x00c96a0d, 0x00cc6300, 0x00cc6600, 0x00c96804, 0x00c06606, 0x00be6c14, 0x00b76818, 0x00b7681c, 0x00bc6a19, 0x00c46809, 0x00c06100, 0x00c86806, 0x00c86808, 0x00cb6509, 0x00cc6506, 0x00cc6501, 0x00ca6600, 0x00c86700, 0x00c66702, 0x00c96609, 0x00c9640c, 0x00c45e08, 0x00bc5805, 0x00ba580b, 0x00bc5c17, 0x00be5c1e, 0x00b65821, 0x00a4501e, 0x00702b00, 0x003e0500, 0x00340000, 0x00521800, 0x007c3d1e, 0x00985428, 0x0099582b, 0x008c522a, 0x00673415, 0x003e1000, 0x002b0000, 0x00390400, 0x00662810, 0x00914b24, 0x00a65322, 0x00b15019, 0x00b55017, 0x00ac4c14, 0x00ac5220, 0x009e4f23, 0x00783512, 0x00471300, 0x001f0000, 0x00100000, 0x00090000, 0x00090004, 0x000d0607, 0x001b100d, 0x00291b13, 0x00342014, 0x00372010, 0x00240c00, 0x00512c14, 0x008a472a, 0x00a7512c, 0x00af5325, 0x00b05119, 0x00b05010, 0x00b1500d, 0x00b74f12, 0x00b3511d, 0x00964923, 0x00743a1e, 0x00371100, 0x001f0000, 0x00330000, 0x005f2001, 0x00934c28, 0x00a35329, 0x00ac5327, 0x00a84c1c, 0x00a64c17, 0x00b0521a, 0x00b65318, 0x00b84e12, 0x00ba480d, 0x00b8470d, 0x00b84e14, 0x00b0501e, 0x00a04f24, 0x008e4c2a, 0x00612f16, 0x00240200, 0x00110000, 0x00080000, 0x00080000, 0x000b0000, 0x000c0000, 0x00110000, 0x00310900, 0x005c2105, 0x008c4123, 0x00a24e2a, 0x00a45128, 0x00a64f20, 0x00ab4c11, 0x00b7500d, 0x00c0500c, 0x00c55918, 0x00b45921, 0x00782d00, 0x003b0000, 0x00804415, 0x00b16218, 0x00c2650b, 0x00c45c00, 0x00c96007, 0x00c56010, 0x00bc611c, 0x00a75920, 0x0084471c, 0x00481802, 0x00280000, 0x00430500, 0x0090460c, 0x00b6631f, 0x00bc6114, 0x00c6660e, 0x00c96708, 0x00c56401, 0x00c56503, 0x00c66707, 0x00bf6307, 0x00c66d17, 0x00b9620e, 0x00b35a06, 0x00c46b14, 0x00c26506, 0x00c26705, 0x00bc680a, 0x00a95800, 0x00c36d18, 0x00c0640e, 0x00cc6a0d, 0x00cc670c, 0x00c85c0d, 0x00c0560c, 0x00c15b0d, 0x00b9570c, 0x00b85c19, 0x00a0501c, 0x006c3210, 0x00250000, 0x00140401, 0x00020001, 0x00030402, 0x003d413e, 0x009ba09e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00161717, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b1af, 0x005c5d5f, 0x000c1012, 0x00000004, 0x00040408, 0x00030102, 0x00181210, 0x00574e4b, 0x009b928f, 0x00c4c1c0, 0x00cacacc, 0x00cccccc, 0x00c8c8ca, 0x00c5c5c7, 0x00c8c9cb, 0x00cbcccc, 0x00cbcccc, 0x00c0c4c4, 0x00c9cccc, 0x00c4c7c8, 0x00acb0b0, 0x00818686, 0x003c4040, 0x00040b0c, 0x00000000, 0x00090000, 0x00502d20, 0x00954c24, 0x00ac4e17, 0x00b05013, 0x00ac4b0d, 0x00b34d14, 0x00b14710, 0x00bd4f13, 0x00b7490b, 0x00ad4508, 0x00b24c14, 0x00b4501c, 0x00ab4e1f, 0x00a25327, 0x00915534, 0x005d3a26, 0x00210a00, 0x00110000, 0x00371400, 0x007c3e1f, 0x00a45424, 0x00b45718, 0x00c75e15, 0x00c85707, 0x00c65403, 0x00c96116, 0x00c8681c, 0x00c06614, 0x00b86513, 0x00ac6218, 0x00ad641d, 0x00ad5a14, 0x00c56a1c, 0x00c86508, 0x00c46100, 0x00c36206, 0x00c56205, 0x00c86000, 0x00cc6c04, 0x00c36402, 0x00bd6810, 0x00a45913, 0x00864105, 0x00733400, 0x008e4907, 0x00bf6a12, 0x00cc6c0c, 0x00c76208, 0x00c96108, 0x00cc6108, 0x00cb6205, 0x00c86401, 0x00c56600, 0x00c26800, 0x00c26800, 0x00c46500, 0x00c66400, 0x00c86401, 0x00c86404, 0x00c76208, 0x00c45d08, 0x00c45808, 0x00c0560d, 0x00b85916, 0x00b5612b, 0x009a542f, 0x0064240a, 0x003a0000, 0x003a0600, 0x00582600, 0x00683b14, 0x00401900, 0x002e0700, 0x00280000, 0x004b1506, 0x00823e27, 0x00a45330, 0x00ac501f, 0x00b04a11, 0x00b84b0e, 0x00b0470c, 0x00ae4c18, 0x00a85428, 0x00692806, 0x00340500, 0x00190000, 0x00100000, 0x00050000, 0x00030104, 0x000b090c, 0x00181414, 0x00251b16, 0x002d1d16, 0x00372017, 0x003f2417, 0x00462a1a, 0x00663d28, 0x0088462b, 0x009c4b28, 0x00a65129, 0x00a65123, 0x00a2501b, 0x00a6541e, 0x00a6521e, 0x0094481d, 0x00672c10, 0x00280000, 0x001c0000, 0x00340d00, 0x00723710, 0x009d5020, 0x00ac5120, 0x00ae4b19, 0x00b04a18, 0x00b4511c, 0x00b2551b, 0x00ac5114, 0x00a94d0d, 0x00ac4c0c, 0x00b84f14, 0x00b34a14, 0x00aa4a1a, 0x00a04f28, 0x00793e20, 0x003a1000, 0x00150000, 0x000d0000, 0x00040102, 0x00000000, 0x000c0200, 0x000e0000, 0x00140000, 0x004d2309, 0x008c4926, 0x00a04b20, 0x00a94616, 0x00b7501c, 0x00b04e18, 0x00ad4a10, 0x00b84e0c, 0x00c4540d, 0x00ca540c, 0x00be5414, 0x00a25325, 0x00480600, 0x005f1b00, 0x009f541a, 0x00ba6310, 0x00c06103, 0x00c45f04, 0x00c15c0b, 0x00b9601e, 0x00a55828, 0x00733816, 0x00310400, 0x00200000, 0x00340000, 0x0099511f, 0x00be6620, 0x00c66314, 0x00c8610a, 0x00c66006, 0x00c56103, 0x00c56505, 0x00c66707, 0x00c4680c, 0x00bd6813, 0x00b46921, 0x00904701, 0x00964300, 0x00bd6310, 0x00c5680b, 0x00c5690a, 0x00b8680b, 0x009e5000, 0x00a05006, 0x00bd6a1e, 0x00c46c10, 0x00c76a0b, 0x00c05c08, 0x00c75d0d, 0x00c35a05, 0x00c35804, 0x00c05405, 0x00c25d19, 0x00a8541f, 0x00783a17, 0x002b0900, 0x000f0000, 0x00030000, 0x00010302, 0x00494d50, 0x00b2b6b8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00151516, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9792, 0x0044403c, 0x00080808, 0x00000104, 0x00000408, 0x0012191d, 0x00656c70, 0x00a8afb3, 0x00c3c7ca, 0x00c0c4c7, 0x00c5c8cc, 0x00c7c9cc, 0x00c8cbcc, 0x00c8cbcc, 0x00c9cccc, 0x00cbcccc, 0x00c8c8cc, 0x00c4c4c8, 0x00cccccc, 0x00c4c4c6, 0x00cccccc, 0x00cac8c9, 0x00c1c0bf, 0x00c5c4c3, 0x00a09f9d, 0x00535152, 0x0009050a, 0x00140000, 0x00653318, 0x009a5228, 0x00ab5421, 0x00b04f16, 0x00b54f14, 0x00b64c10, 0x00b5480c, 0x00b5480c, 0x00bb4e11, 0x00b85014, 0x00ab4810, 0x00a75020, 0x00904d2c, 0x005f2912, 0x00300000, 0x00390500, 0x006c3008, 0x00a05421, 0x00b6591c, 0x00bd5510, 0x00c0550e, 0x00c6580d, 0x00cc5e0d, 0x00cc5f0f, 0x00b8540b, 0x00a14500, 0x00b66015, 0x00965010, 0x003a0c00, 0x002d0000, 0x00490800, 0x00a85518, 0x00c46411, 0x00c86206, 0x00cb660e, 0x00ca650b, 0x00c86200, 0x00c46100, 0x00c2660a, 0x00aa580d, 0x006c2800, 0x00330000, 0x002f0000, 0x005f2900, 0x00b3641c, 0x00bd5d05, 0x00cb5f08, 0x00cc5e08, 0x00cc5e08, 0x00cc6008, 0x00c76306, 0x00c26503, 0x00c16700, 0x00c46700, 0x00ca6700, 0x00cc6800, 0x00cb6600, 0x00c56200, 0x00c56300, 0x00c96402, 0x00cb6205, 0x00c65e06, 0x00bf5e0b, 0x00b45308, 0x00bd5517, 0x00bc5b25, 0x00924517, 0x00541b00, 0x00280400, 0x001e0200, 0x00280400, 0x004e200b, 0x007f3f24, 0x009c4f2c, 0x00ac5123, 0x00b24e19, 0x00b74c13, 0x00bc4c10, 0x00b54405, 0x00ba4f14, 0x00ad511f, 0x009b5027, 0x00875236, 0x00442310, 0x00140200, 0x00030000, 0x00000403, 0x00000406, 0x0004080a, 0x00141415, 0x00282323, 0x00332b2a, 0x00302424, 0x00281817, 0x00220c09, 0x00150000, 0x001c0000, 0x00350c00, 0x0053200c, 0x007b3e29, 0x0094553b, 0x008f5434, 0x00774826, 0x00482000, 0x001e0000, 0x00240000, 0x00390600, 0x007c3d1f, 0x00a05825, 0x00a85117, 0x00b64d15, 0x00bb4a11, 0x00b74910, 0x00b3490d, 0x00af4a0c, 0x00ae4d0c, 0x00ae510f, 0x00af5112, 0x00ac4c16, 0x00ab5024, 0x009c4f2c, 0x00682e14, 0x00260400, 0x000d0000, 0x000c0204, 0x00020003, 0x00000003, 0x00040000, 0x00120000, 0x00381300, 0x0071391c, 0x009a502b, 0x00ac5022, 0x00b44b17, 0x00b94c12, 0x00ba4c10, 0x00b4490d, 0x00b84d0e, 0x00bc500b, 0x00bc4d04, 0x00c75408, 0x00bc5919, 0x006f2e0c, 0x00340000, 0x00883e08, 0x00b35e18, 0x00c0610e, 0x00bc5800, 0x00c2600b, 0x00b86016, 0x009d5523, 0x00693314, 0x00250000, 0x001c0000, 0x00380800, 0x00925228, 0x00b56325, 0x00ba590f, 0x00c35908, 0x00cc640e, 0x00cc6407, 0x00c46000, 0x00c46403, 0x00c16509, 0x00b8620f, 0x00b26721, 0x00703804, 0x00642800, 0x00964802, 0x00bf6410, 0x00c86808, 0x00c76805, 0x00c46c0d, 0x00b46310, 0x00762c00, 0x00a05718, 0x00b46811, 0x00c57210, 0x00cc6c09, 0x00c86102, 0x00cc650f, 0x00c45603, 0x00cb5703, 0x00c75404, 0x00c85d14, 0x00ab541a, 0x00733c17, 0x00250700, 0x000d0000, 0x0009050a, 0x00000004, 0x005c6063, 0x001f1f1f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00141415, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00948d8c, 0x00403a38, 0x00080402, 0x00000000, 0x00101315, 0x004d5456, 0x00989fa3, 0x00bcc5c8, 0x00bec7ca, 0x00c2cacc, 0x00c7cccc, 0x00c9cccc, 0x00c8cbcc, 0x00c8cacc, 0x00c8cacc, 0x00c9cacc, 0x00c9cacc, 0x00cbcccc, 0x00cccccc, 0x00cacaca, 0x00c9c8c8, 0x00c8c7c5, 0x00cbc8c7, 0x00cccbc8, 0x00ccc8c6, 0x00c4c0be, 0x00bbb9ba, 0x0098999d, 0x003a3231, 0x00210400, 0x004b1900, 0x008f4a24, 0x00a45022, 0x00a4430d, 0x00b95115, 0x00b84d10, 0x00bc5115, 0x00b04a11, 0x00ac4a14, 0x00a8501d, 0x008c4017, 0x00581d01, 0x00320000, 0x00551500, 0x008c401a, 0x00b15b21, 0x00b8550f, 0x00c65808, 0x00cc5b08, 0x00c65706, 0x00cc600f, 0x00c65c06, 0x00c5600f, 0x00ac500c, 0x008e3800, 0x00b96925, 0x00955722, 0x001e0000, 0x00170000, 0x00450e00, 0x00af632c, 0x00c46517, 0x00c75f05, 0x00c96109, 0x00c86006, 0x00c76201, 0x00c66403, 0x00bf640a, 0x00b06019, 0x007d3c12, 0x002b0000, 0x00190000, 0x00381000, 0x00a45e20, 0x00c46716, 0x00c96008, 0x00cc5d04, 0x00cc5e08, 0x00cc6009, 0x00c4630a, 0x00c16407, 0x00c36401, 0x00c56400, 0x00c65f00, 0x00ca6100, 0x00c96500, 0x00c86701, 0x00c56400, 0x00c36000, 0x00c86000, 0x00cc6405, 0x00c66107, 0x00c9600a, 0x00ca5806, 0x00bf5007, 0x00b25415, 0x009e5722, 0x0069380d, 0x00320c00, 0x00320900, 0x0055220c, 0x008d4a2d, 0x00a95830, 0x00aa4814, 0x00b0470c, 0x00ba4d12, 0x00b4470c, 0x00b85018, 0x00ac4e1c, 0x009e4e26, 0x00864a2a, 0x00572f19, 0x001e0800, 0x00140c05, 0x00252723, 0x00525957, 0x007c8483, 0x00a6a9a8, 0x00b1b3b2, 0x00b3b1b4, 0x00b9b5b8, 0x00bbb5bc, 0x00b8b0b6, 0x00b8abad, 0x00a29596, 0x007c7371, 0x004c3e3b, 0x00260c08, 0x00260300, 0x003f180c, 0x004c2818, 0x002c1502, 0x001a0500, 0x00190000, 0x003b0e00, 0x00854227, 0x009f4d27, 0x00a55018, 0x00ae4f0f, 0x00b6490c, 0x00bb490c, 0x00b94c0d, 0x00b84c0d, 0x00ba4c0e, 0x00b84f0f, 0x00b14f0f, 0x00a84d13, 0x00a65322, 0x00904a25, 0x00602912, 0x002c0700, 0x000f0000, 0x00080303, 0x00020005, 0x00020003, 0x000d0401, 0x00140000, 0x00421a04, 0x007f4225, 0x00a2502a, 0x00ac4b1f, 0x00b54916, 0x00bc4b12, 0x00b6490c, 0x00b44a08, 0x00b5480a, 0x00ba4e0c, 0x00c1520e, 0x00c0540d, 0x00c05c14, 0x00a04d13, 0x00360000, 0x00541f00, 0x00a6581c, 0x00bc5e12, 0x00c36010, 0x00c05e0f, 0x00bc6319, 0x009f571a, 0x0062300b, 0x00250200, 0x00160000, 0x00330e00, 0x0084481b, 0x00b06223, 0x00ba5f18, 0x00c76415, 0x00cc6211, 0x00c35903, 0x00c66003, 0x00c96708, 0x00c06408, 0x00bc6814, 0x00a45a18, 0x00723504, 0x00380900, 0x00582500, 0x00a85d17, 0x00c46910, 0x00c46402, 0x00c66400, 0x00c86b0a, 0x00c06a17, 0x00a55b1d, 0x00641f00, 0x00a05c10, 0x00b4680e, 0x00c06702, 0x00cc6904, 0x00cc640a, 0x00cc600c, 0x00ca5600, 0x00cc5800, 0x00c65000, 0x00c0580d, 0x00a65b21, 0x00794420, 0x00270500, 0x000b0000, 0x00020001, 0x00090c0d, 0x007c7b79, 0x000c0c0c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00131313, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008e8c8f, 0x003b3838, 0x00040100, 0x00000000, 0x00262628, 0x00767778, 0x00afb0b1, 0x00c6c8c7, 0x00caccc9, 0x00c9cac5, 0x00c4c4be, 0x00cacac2, 0x00c8c7c3, 0x00cbcac7, 0x00ccccc8, 0x00ccccc8, 0x00cacbc7, 0x00c8c9c5, 0x00c9cac6, 0x00ccccc8, 0x00c8c9c4, 0x00ccccc8, 0x00ccccc8, 0x00ccccc8, 0x00cacbc6, 0x00c8c8c4, 0x00c8c9c4, 0x00ccccca, 0x00c2c3c6, 0x00aba8a7, 0x006c5f57, 0x002c1102, 0x00441904, 0x00854728, 0x00a65425, 0x00ac4b14, 0x00b24a0d, 0x00b65015, 0x00a94d20, 0x009f4f28, 0x007b3914, 0x00430800, 0x003e0400, 0x006c2b07, 0x00a45624, 0x00af5416, 0x00c05910, 0x00c65908, 0x00c85902, 0x00cc5e03, 0x00c85d01, 0x00c45e00, 0x00c56504, 0x00b96009, 0x009d4c10, 0x00803401, 0x00ae6029, 0x00945629, 0x002c0b00, 0x001c0000, 0x00552101, 0x00a85d26, 0x00bb5c0e, 0x00c85f02, 0x00cb6004, 0x00c96002, 0x00c36000, 0x00c46404, 0x00c3660c, 0x00b56319, 0x008d4c1d, 0x003a0d00, 0x00100000, 0x00200400, 0x007e420e, 0x00b8641b, 0x00c26107, 0x00c86000, 0x00c86006, 0x00c56008, 0x00c2610c, 0x00c2620a, 0x00c56004, 0x00c85f02, 0x00cc650c, 0x00c65c08, 0x00bd5a0a, 0x00bf600e, 0x00c4620b, 0x00c35e04, 0x00c65c04, 0x00cc6107, 0x00c95d01, 0x00c85c00, 0x00c85c02, 0x00c45b04, 0x00c1590c, 0x00ba5a14, 0x00aa5419, 0x0091481b, 0x00521b00, 0x003b0a00, 0x00521d04, 0x00874527, 0x00a85026, 0x00af4d19, 0x00b14e14, 0x00af511a, 0x00a04f25, 0x00985534, 0x00632c11, 0x00360e00, 0x00281001, 0x0050453c, 0x00838079, 0x00adb0aa, 0x00b9bcb6, 0x00bcbfb9, 0x00c6c6c0, 0x00ccccc8, 0x00cccbc9, 0x00c7c5c9, 0x00c7c6cc, 0x00cccbcc, 0x00cac9c8, 0x00c1c0bf, 0x00b9b9c0, 0x00b7b4bc, 0x00a49c9f, 0x00726664, 0x00372923, 0x00130500, 0x000c0200, 0x00100000, 0x00381608, 0x00784028, 0x009c4c24, 0x00af4f1e, 0x00b24c15, 0x00b74f12, 0x00b4490c, 0x00b44b0c, 0x00b44f10, 0x00b84f10, 0x00bc480d, 0x00b9440c, 0x00b44811, 0x00ad5220, 0x00925026, 0x0058290c, 0x00280900, 0x000e0000, 0x00030000, 0x00000001, 0x00080001, 0x000f0000, 0x00170000, 0x0058280d, 0x008e4924, 0x00a54e21, 0x00b44d20, 0x00b74818, 0x00b34311, 0x00b84c17, 0x00b04e14, 0x00b05011, 0x00b44f11, 0x00b74e0c, 0x00c0510f, 0x00bd5818, 0x00a0511b, 0x005d1e00, 0x00360000, 0x0084481e, 0x00b56021, 0x00bc5a10, 0x00c05c11, 0x00ba5f18, 0x00995018, 0x00612f06, 0x001e0300, 0x00150100, 0x002c1000, 0x006a3a0f, 0x00af5f18, 0x00bf600c, 0x00bd600c, 0x00bc5f0b, 0x00c36010, 0x00c86410, 0x00c56207, 0x00bc5f04, 0x00bb6414, 0x00a9601e, 0x006f380c, 0x00310400, 0x00320b00, 0x006d3c13, 0x00b4671c, 0x00c76a0b, 0x00c46300, 0x00c66400, 0x00c86404, 0x00c0640c, 0x00b4641c, 0x00803a00, 0x00632100, 0x009e5a12, 0x00c06d11, 0x00c46804, 0x00cc680c, 0x00ca620a, 0x00cc650e, 0x00c05100, 0x00cc5800, 0x00cb5a05, 0x00bb5810, 0x00a3541d, 0x00743a1c, 0x00220000, 0x000c0000, 0x00020000, 0x00181816, 0x00989899, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x000e0e0f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a4a4, 0x003c3b3c, 0x00060405, 0x00080607, 0x00323234, 0x00828284, 0x00b7b7b8, 0x00cccccc, 0x00c7c8c4, 0x00c8c6c0, 0x00ccc9c0, 0x00ccccc0, 0x00ccc8bd, 0x00ccccc4, 0x00cccbc4, 0x00ccc9c4, 0x00c9c9c3, 0x00cbcbc4, 0x00ccccc8, 0x00ccccc8, 0x00c8c9c4, 0x00ccccc8, 0x00c8cac4, 0x00c8cac6, 0x00c8cac6, 0x00c4c8c4, 0x00c8ccc7, 0x00c8ccc9, 0x00c4c8c4, 0x00c8cac9, 0x00c8c8c7, 0x00b5b1ae, 0x00776b65, 0x00321a12, 0x003d1402, 0x0084411e, 0x00a35022, 0x00ab501c, 0x00a44c1c, 0x00944a28, 0x006f2f11, 0x003f0500, 0x00490d00, 0x00843f18, 0x00a45624, 0x00b45b19, 0x00be5b0e, 0x00c95d09, 0x00c85a01, 0x00c85c00, 0x00cb6004, 0x00c75e00, 0x00c56000, 0x00c06000, 0x00bd6710, 0x009a5018, 0x00752e01, 0x00a45924, 0x009b5c2f, 0x003e1808, 0x001d0000, 0x00642f0d, 0x00a95f27, 0x00c36414, 0x00cc6004, 0x00c75b00, 0x00cc6404, 0x00c56103, 0x00c26105, 0x00bf5f07, 0x00b86115, 0x009c5720, 0x005a2b09, 0x00110000, 0x001a0400, 0x005c2800, 0x00b06424, 0x00be620b, 0x00c46100, 0x00c46005, 0x00c46008, 0x00c3610a, 0x00c56008, 0x00c95e04, 0x00c95d08, 0x00c25b12, 0x00be5f1f, 0x00b45e26, 0x00ad5b1f, 0x00b55a13, 0x00c25f0f, 0x00c95f0b, 0x00c85a03, 0x00cc5d04, 0x00ca5d04, 0x00c86004, 0x00c66008, 0x00c75b05, 0x00c65809, 0x00c35610, 0x00b55518, 0x00934b1b, 0x00652c09, 0x003d0b00, 0x004b1400, 0x00843a1b, 0x00a55229, 0x00a8511e, 0x009c5020, 0x00894e2f, 0x004a1d09, 0x00300c00, 0x00543a30, 0x008c7f78, 0x00ada8a3, 0x00c4c4c0, 0x00c5c7c3, 0x00caccc7, 0x00cbccc5, 0x00ccc9c2, 0x00ccc9c4, 0x00cccbc8, 0x00cccccc, 0x00c9cacc, 0x00c6c8cc, 0x00c8cccb, 0x00c4c8c7, 0x00c6cccc, 0x00c8cbcc, 0x00c5c1c4, 0x00bfbbb8, 0x009a9693, 0x00615f5b, 0x001c1c1c, 0x00160b08, 0x0049281c, 0x00895038, 0x00a7522a, 0x00b04917, 0x00b84d14, 0x00b6490c, 0x00b74e10, 0x00b34f0f, 0x00ae4d0e, 0x00b04a0e, 0x00be4813, 0x00be4919, 0x00b34b1c, 0x009c4c22, 0x0064300e, 0x002f1300, 0x000a0000, 0x00020000, 0x00040404, 0x00040000, 0x000b0000, 0x001b0000, 0x005a260c, 0x008c451f, 0x00ab5320, 0x00b14c14, 0x00b84915, 0x00bb4916, 0x00b74817, 0x00b44d19, 0x00b04f16, 0x00ab4d0e, 0x00b4500c, 0x00bd5413, 0x00c05518, 0x00b0511e, 0x0084431d, 0x00380200, 0x00642900, 0x009f5924, 0x00b65c19, 0x00bc5c14, 0x00b65c1b, 0x009d511b, 0x00632e08, 0x00260400, 0x00110000, 0x001a0700, 0x00532e07, 0x009a5d20, 0x00be610a, 0x00c75f00, 0x00c26208, 0x00be610a, 0x00c0600a, 0x00c0600c, 0x00bd610c, 0x00ba6719, 0x00a45b1c, 0x00683001, 0x002e0700, 0x001c0000, 0x00441d03, 0x00885020, 0x00b56413, 0x00c96907, 0x00c56601, 0x00c86602, 0x00ca6407, 0x00c5650d, 0x00c06b19, 0x00a65d16, 0x005e1f00, 0x00642500, 0x00a0580d, 0x00b96910, 0x00c76c10, 0x00c9680c, 0x00c46209, 0x00cc6a12, 0x00c45400, 0x00cb5800, 0x00c65704, 0x00b85510, 0x00a45424, 0x00662c0e, 0x00180000, 0x000d0100, 0x000a0704, 0x00353839, 0x00a4a6ac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00080809, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00bbb8b0, 0x004c4944, 0x00100e0a, 0x00050403, 0x00323031, 0x00878788, 0x00bfbec2, 0x00c8c8cc, 0x00c6c6c8, 0x00ccccca, 0x00ccc9c5, 0x00cccac3, 0x00ccc7bd, 0x00ccc9c0, 0x00cbc8c3, 0x00ccccc6, 0x00ccccc8, 0x00cac9c5, 0x00ccccc8, 0x00cbccc8, 0x00c9cac6, 0x00cbccca, 0x00c8ccc9, 0x00c8cccb, 0x00c8cccc, 0x00c8cccc, 0x00c7cccc, 0x00c7cccc, 0x00c5cccc, 0x00c7cccc, 0x00c6cac7, 0x00cbccc8, 0x00cccbc8, 0x00b9b3b1, 0x0078706e, 0x00341d14, 0x004b1d06, 0x00834426, 0x00975332, 0x00874828, 0x005f2c15, 0x003c0800, 0x00561700, 0x008d4116, 0x00b0571d, 0x00b75712, 0x00bd590f, 0x00c15c09, 0x00c55d04, 0x00c76002, 0x00c45f04, 0x00c35e05, 0x00c85c07, 0x00cb5f08, 0x00c56005, 0x00bf6414, 0x00954c18, 0x006f2d00, 0x00984f14, 0x009e5f2a, 0x0050240c, 0x00250000, 0x00743912, 0x00ac5d23, 0x00c45f11, 0x00c85b00, 0x00c85c00, 0x00c86001, 0x00c15c04, 0x00c5610c, 0x00c45e0a, 0x00c06214, 0x00ac5f1c, 0x00774214, 0x001a0400, 0x00100000, 0x00340800, 0x00a3602c, 0x00b86012, 0x00c46004, 0x00c45e06, 0x00c55d05, 0x00c86007, 0x00c95e04, 0x00cc5c00, 0x00c75d0c, 0x00af551a, 0x007e3309, 0x00571c00, 0x005d2200, 0x0093450f, 0x00c0611c, 0x00cb5c0d, 0x00cc5a06, 0x00cb5a06, 0x00c75b07, 0x00c6600b, 0x00c25c07, 0x00c85d0b, 0x00c85908, 0x00c95405, 0x00c6580d, 0x00b05714, 0x009c5520, 0x006c3514, 0x00401000, 0x00440f00, 0x0074381f, 0x0098542f, 0x00824721, 0x003f1701, 0x002a1004, 0x00745e55, 0x00a49791, 0x00c4bdbb, 0x00cbc9ca, 0x00c7c8c9, 0x00c9cccc, 0x00c8cbca, 0x00c9cbc8, 0x00cacbc7, 0x00cbcac6, 0x00cbcac7, 0x00cbcac7, 0x00cacaca, 0x00c9cbca, 0x00c7ccca, 0x00c8ccc9, 0x00c7ccc7, 0x00cacbc4, 0x00ccc8c4, 0x00ccc6c0, 0x00c6bdb8, 0x00b8b5b1, 0x007c807d, 0x003b3834, 0x00281008, 0x005c2b18, 0x009d4c2d, 0x00ac481d, 0x00b84c14, 0x00ba4c0c, 0x00b44c0a, 0x00b04e0c, 0x00af5114, 0x00ae4d16, 0x00b5481c, 0x00b44823, 0x00a84d2a, 0x00713011, 0x00351100, 0x000d0000, 0x00020000, 0x00000200, 0x00030000, 0x000a0000, 0x00200200, 0x0051200a, 0x008e4824, 0x00a34e1e, 0x00ac4e13, 0x00b04b0c, 0x00b74c10, 0x00b54913, 0x00b04818, 0x00b34c1a, 0x00b14c10, 0x00b7500c, 0x00b84c03, 0x00c45c15, 0x00b5531c, 0x009c4823, 0x004e1200, 0x00410800, 0x009b5321, 0x00b05a18, 0x00bb5c16, 0x00b45a18, 0x009c5120, 0x00602b09, 0x00200000, 0x00120000, 0x00160100, 0x003e1f00, 0x008b541e, 0x00b26419, 0x00c66306, 0x00c75d00, 0x00bf5e02, 0x00bf6106, 0x00c46104, 0x00bc5e06, 0x00bb6820, 0x00a05b24, 0x00622c08, 0x002c0700, 0x00120000, 0x00190000, 0x005d2f08, 0x00a56121, 0x00be650f, 0x00c66402, 0x00c36405, 0x00c26409, 0x00c4640a, 0x00c5650d, 0x00be6107, 0x00ba6818, 0x00904e19, 0x00490f00, 0x00642900, 0x00a36020, 0x00b86712, 0x00c2690d, 0x00c56811, 0x00c4640b, 0x00c76202, 0x00c95d00, 0x00ca5600, 0x00c55507, 0x00b95411, 0x00a25220, 0x00481600, 0x00180000, 0x00060000, 0x00060b0b, 0x00666c70, 0x00b3b5bb, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040505, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00706c64, 0x001a1810, 0x00040200, 0x002a2926, 0x007c7c7c, 0x00bcbcbe, 0x00c6c7ca, 0x00cbcccc, 0x00cbcacc, 0x00c8c8c9, 0x00c8c7c5, 0x00ccccc8, 0x00ccc8c3, 0x00ccccc6, 0x00cac9c6, 0x00c9c8c5, 0x00cbcac7, 0x00ccccc8, 0x00c8c8c7, 0x00c7c7c5, 0x00c9c9c8, 0x00cbcccc, 0x00cacbcc, 0x00c8cccc, 0x00c8cccc, 0x00c8cccc, 0x00c8cbcc, 0x00c8cbcc, 0x00c8cbcc, 0x00c7cccc, 0x00c8ccca, 0x00c6cac7, 0x00cccbcc, 0x00c9c8c8, 0x00adacac, 0x006c625d, 0x003a1b0f, 0x00532918, 0x006d3f2d, 0x005b2c19, 0x003a1000, 0x00521f03, 0x0090441b, 0x00b3541c, 0x00bc540d, 0x00c85b0c, 0x00c25708, 0x00c55b07, 0x00c95c03, 0x00c85c02, 0x00c35d08, 0x00c45c09, 0x00c85a09, 0x00c85a07, 0x00c45c05, 0x00bc6016, 0x00944c1a, 0x006a2900, 0x0090470c, 0x009f5e29, 0x005c2d14, 0x00280000, 0x007b3c0f, 0x00ae5c1e, 0x00c45c10, 0x00c95802, 0x00c85c00, 0x00c85f06, 0x00c15b0a, 0x00c45e10, 0x00c75c0c, 0x00c46010, 0x00b65f13, 0x008a4c12, 0x00311400, 0x00110000, 0x00280200, 0x00844824, 0x00b7601a, 0x00c45f07, 0x00c55c05, 0x00c95c06, 0x00ca5d04, 0x00c85b00, 0x00cc5c00, 0x00c45d0e, 0x009a4815, 0x005a1f00, 0x00240000, 0x002e0600, 0x006e3005, 0x00b45f20, 0x00c85e10, 0x00cc5a06, 0x00c85b06, 0x00c45d0c, 0x00be5c0f, 0x00be5a10, 0x00c75c0c, 0x00cc5b09, 0x00cc5904, 0x00c85501, 0x00bc5608, 0x00b45c1b, 0x00985020, 0x00713412, 0x00491500, 0x003f1000, 0x005f3014, 0x00411c02, 0x002c1709, 0x00786b63, 0x00b4aaa4, 0x00c8c2c0, 0x00ccc9c8, 0x00c7c7c8, 0x00cacbcc, 0x00c8cccc, 0x00c8cccc, 0x00c8cccc, 0x00cacccb, 0x00caccc9, 0x00caccc8, 0x00caccc8, 0x00caccc8, 0x00c8ccc9, 0x00c4cccc, 0x00c5cccc, 0x00c8ccc8, 0x00caccc3, 0x00cccac3, 0x00ccc9c3, 0x00ccc7c4, 0x00c7c4c0, 0x00b8bfbb, 0x008c8d89, 0x00594c46, 0x00310c02, 0x006c2a17, 0x00a44d2c, 0x00ac4815, 0x00b1480a, 0x00b64f0e, 0x00ae4a0a, 0x00af4e14, 0x00b0501e, 0x00a8441c, 0x00a94c2c, 0x00813b1e, 0x00481801, 0x00100000, 0x00080400, 0x00000100, 0x00000200, 0x00090100, 0x00160000, 0x004d1d08, 0x00884426, 0x00a24c21, 0x00af5019, 0x00af4d10, 0x00b04c0a, 0x00b64d0f, 0x00b44b10, 0x00af4814, 0x00b14c16, 0x00b74d0c, 0x00b64c03, 0x00c65b0f, 0x00bc5814, 0x00a14c1f, 0x00682004, 0x003d0000, 0x007f3c21, 0x00ad5923, 0x00b45a17, 0x00b96424, 0x009b511d, 0x00582605, 0x00270700, 0x00100000, 0x00140000, 0x00321100, 0x00703e14, 0x00aa6020, 0x00bb6010, 0x00c25a00, 0x00cb6002, 0x00c46005, 0x00c16006, 0x00bb5d02, 0x00ba6515, 0x00985820, 0x00643310, 0x002c0800, 0x00170000, 0x000e0000, 0x002c0f00, 0x00773e0c, 0x00b26318, 0x00c1640a, 0x00c46403, 0x00c16407, 0x00c2640a, 0x00c4630c, 0x00c46209, 0x00c66508, 0x00c16814, 0x00a45c21, 0x00652b00, 0x00431000, 0x006c3508, 0x00a45f19, 0x00bc6c19, 0x00c06b14, 0x00c1660c, 0x00c56606, 0x00c86000, 0x00c95500, 0x00cc5601, 0x00ca5a0c, 0x00b55818, 0x00894821, 0x00330b00, 0x000a0000, 0x00020400, 0x001e2224, 0x0087898d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a2a49b, 0x002b2c25, 0x00030400, 0x00161713, 0x0070706f, 0x00b4b4b4, 0x00cbcbcc, 0x00c9c8cc, 0x00cac9cc, 0x00cacbcc, 0x00c8c9cc, 0x00c6c7ca, 0x00c0c1c3, 0x00b0b1b3, 0x00b4b4b6, 0x00c4c4c5, 0x00c4c4c6, 0x00cbc9cc, 0x00cccacc, 0x00c8c7c9, 0x00cccacc, 0x00cccbcc, 0x00c8c6c8, 0x00cccacc, 0x00ccc9cc, 0x00ccc9cc, 0x00ccc9cc, 0x00ccc9cc, 0x00ccc8cc, 0x00ccc8cc, 0x00cbc9cc, 0x00c7ccca, 0x00c8cccb, 0x00c8cbcc, 0x00cccccc, 0x00cccccc, 0x00b1aba8, 0x005a4843, 0x00311911, 0x00341912, 0x00300f02, 0x00441600, 0x0089471d, 0x00bc5a1c, 0x00c8580c, 0x00ca5708, 0x00c95705, 0x00c85707, 0x00cc5906, 0x00cc5904, 0x00cc5704, 0x00c85809, 0x00c95b0c, 0x00c95a08, 0x00c55904, 0x00c25c06, 0x00b95e17, 0x00954b1c, 0x00672200, 0x00843b07, 0x00a05e2e, 0x00673c20, 0x00280000, 0x00813d10, 0x00b35a1b, 0x00c55910, 0x00ca5806, 0x00c75b04, 0x00c75e09, 0x00c15a0f, 0x00c45c14, 0x00c85a0f, 0x00c55a0c, 0x00bd5e0c, 0x00a15815, 0x00542b0c, 0x00150000, 0x001c0000, 0x005c2811, 0x00b45d23, 0x00c55c0c, 0x00c75807, 0x00cc5c08, 0x00c95b04, 0x00c75900, 0x00cc5b00, 0x00c25d0d, 0x00a45823, 0x005c280c, 0x00140000, 0x00130000, 0x00502100, 0x00a76124, 0x00bd5f0f, 0x00c45c00, 0x00c45f04, 0x00c1600d, 0x00ac4f0f, 0x00b75519, 0x00c65913, 0x00c95806, 0x00cc5c02, 0x00c95800, 0x00c75a0b, 0x00be550f, 0x00bc5514, 0x00ac5118, 0x00823d0e, 0x00411400, 0x00200a00, 0x001c1207, 0x00766f68, 0x00c0bab4, 0x00c7c4bc, 0x00ccc8c5, 0x00ccc8c8, 0x00cccbcc, 0x00cccbcc, 0x00c9cacc, 0x00cbcccc, 0x00c9cccc, 0x00c8cccc, 0x00c8cccc, 0x00c8cccc, 0x00c8cccc, 0x00c8ccca, 0x00c6cccc, 0x00c1cccc, 0x00c3cccc, 0x00c6cccc, 0x00cacbcc, 0x00ccc9ca, 0x00cccaca, 0x00cccbca, 0x00cacbc7, 0x00c6cbc8, 0x00c0c4c3, 0x00999898, 0x00514040, 0x00330b02, 0x006c3019, 0x00a25124, 0x00ae5018, 0x00b44d11, 0x00b0480c, 0x00b24c17, 0x00ae501f, 0x00a34b24, 0x00904828, 0x00502007, 0x001d0400, 0x00060000, 0x00000100, 0x00000101, 0x00040200, 0x00100000, 0x003a1400, 0x00813e20, 0x00a34c25, 0x00af4c1c, 0x00b34d18, 0x00ad4c15, 0x00ae4c12, 0x00b54d10, 0x00b64c0e, 0x00b34a10, 0x00b54c0e, 0x00c1530a, 0x00bc4e01, 0x00c05912, 0x00ac541b, 0x00743110, 0x00460700, 0x006a1d00, 0x00ad582a, 0x00b65d1e, 0x00b46124, 0x00904f23, 0x00532608, 0x001f0800, 0x000a0000, 0x000c0000, 0x00260800, 0x00652e0d, 0x00a35724, 0x00c0611c, 0x00c45c0d, 0x00c55809, 0x00cc600e, 0x00c85c05, 0x00c05c06, 0x00bd6718, 0x009a5818, 0x0058300c, 0x00240e00, 0x000c0000, 0x000c0000, 0x00100000, 0x004a210a, 0x00984f16, 0x00be6414, 0x00c06408, 0x00c36404, 0x00c36405, 0x00c66308, 0x00ca620a, 0x00c75f07, 0x00c66108, 0x00c46812, 0x00b6671c, 0x0094521a, 0x00441200, 0x003a0a00, 0x00773f0f, 0x00a46321, 0x00ba6c1a, 0x00c0680b, 0x00c76808, 0x00cb6402, 0x00cc5c00, 0x00cc5800, 0x00ca5807, 0x00bc5713, 0x00ac5a28, 0x00642d0c, 0x001f0700, 0x00080200, 0x00000200, 0x00545557, 0x00afa7a8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00515550, 0x000a0e0b, 0x00040805, 0x004c4f4e, 0x00adafae, 0x00c9cacc, 0x00c9c9cb, 0x00c8c8c9, 0x00cbcbcc, 0x00bcbcc0, 0x009a9b9e, 0x00737477, 0x0054565a, 0x00484b4f, 0x004f5155, 0x00585b5d, 0x0078787a, 0x00a3a2a6, 0x00c1c1c3, 0x00cacacc, 0x00c8c8ca, 0x00c8c7c9, 0x00c9c8c8, 0x00cccacb, 0x00cccacb, 0x00ccc9cb, 0x00ccc9c9, 0x00ccc8c9, 0x00ccc8c9, 0x00ccc8c9, 0x00ccc9ca, 0x00c5c8c9, 0x00c7cccc, 0x00c0c5c5, 0x00c6c9c8, 0x00c9cacc, 0x00cbc8c8, 0x009b9392, 0x00413330, 0x00180500, 0x00321406, 0x00703d20, 0x00a45928, 0x00bc540e, 0x00c65000, 0x00cc5b08, 0x00c85300, 0x00cc5707, 0x00cc5805, 0x00cc5702, 0x00cc5604, 0x00c85609, 0x00c8590b, 0x00c85904, 0x00c65901, 0x00c35c07, 0x00b85d16, 0x00964c1b, 0x00611f00, 0x00772f00, 0x009f5f30, 0x006f4427, 0x00280000, 0x0087400d, 0x00b45815, 0x00c6580d, 0x00cb5807, 0x00c75b05, 0x00c45d0a, 0x00c1590c, 0x00c55b12, 0x00c8580e, 0x00c55708, 0x00c35c07, 0x00b25e15, 0x00743f15, 0x00200000, 0x00140000, 0x00391000, 0x00a85925, 0x00c05c13, 0x00c45609, 0x00cb5c0b, 0x00c45a06, 0x00c45802, 0x00c85b00, 0x00c15b0a, 0x00ad5c24, 0x00683311, 0x00180000, 0x000d0000, 0x003c1700, 0x009a5c23, 0x00b86011, 0x00c25f04, 0x00c06004, 0x00b45c0e, 0x007f2f00, 0x00903d11, 0x00b55418, 0x00c2560c, 0x00cb5a04, 0x00cb5900, 0x00cc5a0a, 0x00c45208, 0x00ca5710, 0x00bb5618, 0x00944f1e, 0x00462000, 0x00150c00, 0x00656a67, 0x00b8bcb8, 0x00c9cbc8, 0x00c5c7c4, 0x00cbcbc9, 0x00c7c6c4, 0x00cccacb, 0x00cbc7ca, 0x00cccbcc, 0x00cccbcc, 0x00cbcccc, 0x00c9cccc, 0x00c9cccc, 0x00c8cccc, 0x00c8ccca, 0x00c8ccca, 0x00c7cccc, 0x00c4cccc, 0x00c5cccc, 0x00c8cccc, 0x00cccbcc, 0x00cbc8cc, 0x00cbc9cc, 0x00c9c8c7, 0x00c6c8c4, 0x00c4c8c4, 0x00c8cccb, 0x00bcbec2, 0x009c989b, 0x0046322f, 0x00330c00, 0x00824624, 0x009b4c1c, 0x00aa4b16, 0x00b14a14, 0x00b14d1a, 0x00a64a1c, 0x009b512a, 0x00683112, 0x00270b00, 0x00090000, 0x00040402, 0x00000003, 0x00010101, 0x000a0000, 0x002c0e00, 0x00733c1f, 0x00a4502a, 0x00b04c1d, 0x00b44a16, 0x00b44b14, 0x00b04c17, 0x00b24c17, 0x00b54c10, 0x00b54b0c, 0x00b54c0a, 0x00b84f0b, 0x00c05509, 0x00c05910, 0x00ac5318, 0x00853b0d, 0x00460e00, 0x00541900, 0x00a3501f, 0x00b45a1f, 0x00b15e24, 0x00945120, 0x00502408, 0x00170000, 0x000c0400, 0x00080000, 0x001a0100, 0x00502106, 0x00964c1e, 0x00b85c20, 0x00c05810, 0x00c8590d, 0x00c7590e, 0x00c3580c, 0x00c25a0d, 0x00bc6118, 0x00a15c1e, 0x00603307, 0x001f0c00, 0x00050000, 0x00080304, 0x000d0000, 0x001f0000, 0x006a3312, 0x00ad5b1d, 0x00c26311, 0x00bf6208, 0x00c06403, 0x00c36301, 0x00c76202, 0x00cc6206, 0x00ca5d05, 0x00c45f06, 0x00c3660f, 0x00bc6410, 0x00b16522, 0x00703811, 0x00320300, 0x00401300, 0x007a4613, 0x00aa681b, 0x00bb6b10, 0x00c4680c, 0x00c96406, 0x00cc6203, 0x00cc5b00, 0x00c35400, 0x00be570d, 0x00b6591d, 0x00985124, 0x00431b00, 0x000e0000, 0x00080200, 0x0020201e, 0x00877f7e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a0a6a8, 0x00141c1e, 0x00000405, 0x00242a2c, 0x008f9395, 0x00c0c4c7, 0x00c8cccc, 0x00c8c9cb, 0x00c8c8c8, 0x00afadae, 0x00757474, 0x003b3b3b, 0x00131314, 0x00000004, 0x00010408, 0x00000104, 0x00000202, 0x00141b18, 0x00414646, 0x007d8280, 0x00b2b5b4, 0x00c4c8c7, 0x00c7c8c8, 0x00cbccca, 0x00cbcbc9, 0x00cbccc8, 0x00cccbc8, 0x00cccbc8, 0x00cccac8, 0x00ccc9c7, 0x00ccc9c7, 0x00cbcac8, 0x00cacbcc, 0x00c8cccc, 0x00c1c6c4, 0x00c8cccc, 0x00c5c9cc, 0x00c4c6cc, 0x00c1c0c2, 0x00756c68, 0x002c1a0d, 0x00482510, 0x00834a28, 0x00954714, 0x00b85813, 0x00c45707, 0x00cc590a, 0x00cc5808, 0x00cc5606, 0x00ca5503, 0x00c85702, 0x00c65a04, 0x00c45b0b, 0x00c45908, 0x00c65800, 0x00c65800, 0x00c65c05, 0x00b85c12, 0x00944e15, 0x005b1e00, 0x00682600, 0x009c5f2f, 0x00704123, 0x002c0000, 0x008c440b, 0x00b45810, 0x00c65909, 0x00cc5a06, 0x00c45b04, 0x00c35c05, 0x00c15b05, 0x00c55c09, 0x00c8590a, 0x00c45605, 0x00c65a04, 0x00bc5f12, 0x008c4c13, 0x00340b00, 0x00100000, 0x00200400, 0x008d4f1d, 0x00b4601b, 0x00bc590c, 0x00c35d0b, 0x00bd5c0b, 0x00be5c08, 0x00c75c03, 0x00c25808, 0x00b55919, 0x007b360f, 0x00280500, 0x00100000, 0x00300c00, 0x0088501c, 0x00b45d13, 0x00be5c05, 0x00ba5e08, 0x00a85914, 0x00440e00, 0x004c1500, 0x008c3e12, 0x00b75718, 0x00c85a0c, 0x00cb5500, 0x00c85603, 0x00c65608, 0x00c75c18, 0x00ad5622, 0x00743e1c, 0x00311805, 0x0048463a, 0x00b1bab4, 0x00bfcacb, 0x00bdc8cc, 0x00c6cccc, 0x00c7cccc, 0x00c4c7c9, 0x00cbcbcc, 0x00ccc9ca, 0x00cccaca, 0x00cccaca, 0x00cccaca, 0x00cccbc8, 0x00cccbc8, 0x00ccccc8, 0x00ccccc8, 0x00ccccc8, 0x00ccccc8, 0x00cccbc7, 0x00ccccca, 0x00cccacc, 0x00ccc8cc, 0x00cccacc, 0x00cccbcc, 0x00cccbc7, 0x00c8c9c3, 0x00caccc8, 0x00cbcccc, 0x00c6c8cc, 0x00bcbcbd, 0x008f8683, 0x00311c10, 0x00431f08, 0x00884f2d, 0x00a34d22, 0x00b04c1c, 0x00ae4d20, 0x00a04c22, 0x007d401b, 0x003a1400, 0x00110100, 0x00030000, 0x00000001, 0x00020004, 0x000b0000, 0x00210600, 0x00613018, 0x0098502c, 0x00aa4a1a, 0x00b84e18, 0x00b44a13, 0x00b54913, 0x00b84a16, 0x00b84915, 0x00b44810, 0x00b4490c, 0x00bb4e09, 0x00be540b, 0x00b9540f, 0x00b1591d, 0x0088441b, 0x004c1300, 0x00491400, 0x0083451a, 0x00b06021, 0x00b05d1e, 0x008f4e22, 0x004e2304, 0x001c0800, 0x00080000, 0x00050000, 0x00150200, 0x004c2000, 0x00894614, 0x00b35b1d, 0x00c15a17, 0x00c45511, 0x00c6550f, 0x00c55809, 0x00bc560a, 0x00b85d1d, 0x00a15928, 0x00592a0a, 0x00250d00, 0x00070400, 0x00000100, 0x00040300, 0x000f0000, 0x00401100, 0x008c441a, 0x00b95f1f, 0x00c36011, 0x00bf6209, 0x00c06304, 0x00c56200, 0x00c85f00, 0x00cc5f00, 0x00cc5e03, 0x00c46308, 0x00c1640c, 0x00c06007, 0x00ba6216, 0x009f5826, 0x00501a00, 0x00260000, 0x00482000, 0x0085510e, 0x00ae6917, 0x00c26817, 0x00c45e08, 0x00cc6206, 0x00cc5f02, 0x00c15802, 0x00c45d0e, 0x00c05912, 0x00b05920, 0x00743912, 0x00280400, 0x000d0000, 0x00030000, 0x00575350, 0x00aca8a6, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005a5d60, 0x000a0e11, 0x00000004, 0x00666a6d, 0x00b8bcbf, 0x00c4c8ca, 0x00c4c8c8, 0x00c8cac9, 0x00aeaeae, 0x00646361, 0x001c1b19, 0x00020100, 0x00000000, 0x00000001, 0x00040408, 0x00000003, 0x00000402, 0x00000100, 0x00000100, 0x00222724, 0x00727673, 0x00b6bab7, 0x00c9ccca, 0x00c7c8c6, 0x00c9cbc8, 0x00c9cbc8, 0x00cacac8, 0x00cacac8, 0x00cacac8, 0x00cacac8, 0x00cbcac8, 0x00cacaca, 0x00c9cacc, 0x00c6c9c8, 0x00c9cbc7, 0x00c8ccc9, 0x00c7cbcc, 0x00c4c8cc, 0x00c9cacc, 0x00a8a4a0, 0x00514338, 0x003b1d08, 0x00653312, 0x00803808, 0x00b85c1a, 0x00c35b10, 0x00c8580c, 0x00c95608, 0x00c95705, 0x00c75804, 0x00c25c06, 0x00bf5c09, 0x00bf5c0f, 0x00c25a0c, 0x00c95900, 0x00ca5900, 0x00c75906, 0x00b85913, 0x00944d1a, 0x00561c00, 0x00581c00, 0x00925c32, 0x0063381b, 0x002e0000, 0x00934a11, 0x00b55910, 0x00c55807, 0x00cc5b06, 0x00c45b06, 0x00c25c04, 0x00c25a00, 0x00c45b04, 0x00c55b0a, 0x00c45808, 0x00c75807, 0x00bf5b10, 0x009c5214, 0x004f1f00, 0x000f0000, 0x00120000, 0x0068360c, 0x00aa5d20, 0x00ba5a0e, 0x00c15b0a, 0x00b95b0b, 0x00bc5f0b, 0x00c45b02, 0x00c25804, 0x00c15c18, 0x008d4012, 0x00360f01, 0x00100000, 0x00280800, 0x00743f14, 0x00b45e18, 0x00be5908, 0x00b85a0a, 0x00a85e20, 0x00300800, 0x001e0000, 0x00581c00, 0x009c4b16, 0x00c05c14, 0x00c55706, 0x00c55804, 0x00c45b0c, 0x00bc5814, 0x009b4e1e, 0x004e2510, 0x0033231c, 0x00989894, 0x00c0c8c5, 0x00c4cccc, 0x00c6cccc, 0x00c4cbcc, 0x00c0c6c8, 0x00c9cccc, 0x00cacbcc, 0x00cccbcc, 0x00cccac9, 0x00cccbc8, 0x00cccbc8, 0x00cccbc8, 0x00cccbc8, 0x00ccccc8, 0x00ccccc8, 0x00ccccc8, 0x00ccccc8, 0x00ccccc4, 0x00cccac7, 0x00ccc7cc, 0x00ccc7cc, 0x00ccc9cc, 0x00cccbcc, 0x00ccccc8, 0x00caccc7, 0x00c6c8c4, 0x00c9cbca, 0x00cacbcc, 0x00c5c5c7, 0x00bcb8b5, 0x0070655c, 0x001b0500, 0x00683c24, 0x009f5029, 0x00ac4e23, 0x00a74f26, 0x00954c27, 0x004e2000, 0x001a0100, 0x000b0100, 0x00000000, 0x00000003, 0x000a0002, 0x00190100, 0x00502411, 0x008c4829, 0x00a44b1f, 0x00af4914, 0x00b4480e, 0x00b44a10, 0x00b34910, 0x00b84912, 0x00b94810, 0x00b5480d, 0x00b84f0d, 0x00c0550e, 0x00be5714, 0x00b3581f, 0x00893c10, 0x00551900, 0x00410b00, 0x007b4119, 0x00a1612f, 0x00a86022, 0x008a4a13, 0x004c2103, 0x001a0100, 0x00080000, 0x00070000, 0x000d0000, 0x003c1704, 0x00824315, 0x00ad5c1a, 0x00bb5c12, 0x00c15b0d, 0x00c65a12, 0x00c1550c, 0x00c55f10, 0x00bb6019, 0x00995222, 0x00623013, 0x00240700, 0x00080000, 0x00030301, 0x00000100, 0x00000000, 0x00130000, 0x00602801, 0x00a5541e, 0x00bf5f1a, 0x00c35e0e, 0x00c2600b, 0x00c06004, 0x00c56200, 0x00c55d00, 0x00ca5e00, 0x00c85f04, 0x00c16409, 0x00bc6005, 0x00c96409, 0x00c0600c, 0x00b46422, 0x007c3c0d, 0x00340c00, 0x00200100, 0x00512900, 0x00915818, 0x00bc6c22, 0x00c46310, 0x00cb6309, 0x00cc6408, 0x00c45d06, 0x00c35a07, 0x00c45707, 0x00b85510, 0x009f5423, 0x00501c00, 0x001b0200, 0x00060000, 0x0023221e, 0x0080817d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00aeacad, 0x00211e1d, 0x000a0706, 0x001d1a1b, 0x009b9b9c, 0x00c2c2c4, 0x00cacbcc, 0x00c9cccc, 0x00bbbebd, 0x006e706f, 0x001e1e1c, 0x00000000, 0x00000000, 0x00020200, 0x00000000, 0x00000000, 0x00000201, 0x00000100, 0x00000100, 0x00000000, 0x00000000, 0x002a2c29, 0x00808280, 0x00bec0bf, 0x00c7c8c9, 0x00c8c9cb, 0x00c8c9cb, 0x00c8c9cb, 0x00c8c9cc, 0x00c8c9cc, 0x00c8c9cc, 0x00c9cacc, 0x00c9cacc, 0x00c7c8c9, 0x00c9c9c8, 0x00ccc9c6, 0x00c8c6c2, 0x00c7c8c4, 0x00caccc9, 0x00cbcbc9, 0x00c3c2bf, 0x00747470, 0x002a1c14, 0x00381700, 0x00683006, 0x00b45c1c, 0x00c0570f, 0x00c25911, 0x00bc5409, 0x00c35804, 0x00c35d08, 0x00b95d08, 0x00af5408, 0x00b1500e, 0x00be5611, 0x00cb5804, 0x00cc5800, 0x00c8550c, 0x00b9561c, 0x00934c26, 0x00501a00, 0x00451100, 0x0081543a, 0x004b2714, 0x002a0000, 0x009a5220, 0x00b75a16, 0x00c35508, 0x00ca5808, 0x00c3590b, 0x00c25b0a, 0x00c35900, 0x00c35902, 0x00c3580c, 0x00c35611, 0x00c75510, 0x00c05715, 0x00a85819, 0x006c3809, 0x00100000, 0x000b0000, 0x00451700, 0x00a05522, 0x00bd5911, 0x00c55807, 0x00bb5908, 0x00bf5e0a, 0x00c35a00, 0x00c45900, 0x00c0570e, 0x00944311, 0x003d1809, 0x000d0000, 0x001d0400, 0x005c2d0c, 0x00b7601e, 0x00c45b0c, 0x00bd570e, 0x00ab5c26, 0x00320d00, 0x00130000, 0x00330700, 0x00804011, 0x00b2601f, 0x00bb5d11, 0x00be5c0c, 0x00bf5f11, 0x00b15610, 0x007b3404, 0x00361505, 0x00655c5f, 0x00c6c6cc, 0x00c9cccc, 0x00c9c6c7, 0x00cccbc8, 0x00cccbc9, 0x00c9c9c9, 0x00cbcccc, 0x00c6c7c8, 0x00c7c8c9, 0x00c9cbca, 0x00cbcbc9, 0x00cccbc8, 0x00cccbc8, 0x00cccbc9, 0x00cbcbc9, 0x00cacccb, 0x00cacbcc, 0x00cacccb, 0x00c9ccc8, 0x00cbccc8, 0x00ccc8ca, 0x00ccc7cc, 0x00ccc8cc, 0x00cccacb, 0x00c8cbca, 0x00c4ccc9, 0x00c8cccc, 0x00c7cacb, 0x00c8c8c8, 0x00cccac9, 0x00ccc6c1, 0x00b2a8a0, 0x003b2b22, 0x00320d00, 0x00904721, 0x00a55024, 0x009a4e28, 0x00703616, 0x00280900, 0x000d0000, 0x00070000, 0x00020003, 0x00060000, 0x00170100, 0x00401806, 0x007f4021, 0x00a54c24, 0x00b04918, 0x00b85118, 0x00b04a0e, 0x00b04b0e, 0x00af480c, 0x00b34b0e, 0x00b64c0c, 0x00b94e08, 0x00bf560e, 0x00be5714, 0x00ae5117, 0x00904019, 0x00601a00, 0x004d0c00, 0x0070320d, 0x00a15e2c, 0x00995a24, 0x0080481b, 0x00451e00, 0x00140000, 0x00080000, 0x000b0000, 0x00160000, 0x00411800, 0x007b4018, 0x00a75519, 0x00bc5d15, 0x00bc5a0b, 0x00be5c08, 0x00c05c06, 0x00bb5a06, 0x00b95e10, 0x009e5418, 0x00582e0e, 0x001e0800, 0x000f0000, 0x00050000, 0x00040000, 0x00040100, 0x00080300, 0x00270f00, 0x007b3f0b, 0x00b25d1a, 0x00c05e14, 0x00c45c0c, 0x00c85f0c, 0x00c25c06, 0x00c76209, 0x00c05e05, 0x00be6008, 0x00bf620b, 0x00be6108, 0x00bd5d03, 0x00ca6408, 0x00c56208, 0x00bd6412, 0x00a15a18, 0x00572c04, 0x00200000, 0x00280800, 0x0060320d, 0x00a35c18, 0x00c06915, 0x00c5650c, 0x00ca640a, 0x00c96008, 0x00c35600, 0x00c95800, 0x00c55a0c, 0x00b45921, 0x00753310, 0x002d0c00, 0x000e0300, 0x00040600, 0x00585c57, 0x00b1ada8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00989795, 0x000b0704, 0x00040000, 0x00585454, 0x00b7b4b4, 0x00cccbcc, 0x00c8c8c9, 0x00cacbcc, 0x00929493, 0x00383938, 0x00000000, 0x00020200, 0x00000000, 0x00000000, 0x00040402, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00040402, 0x00000000, 0x00020200, 0x004b4b4b, 0x00a5a5a5, 0x00cbcbcc, 0x00c8c9cb, 0x00c8c9cc, 0x00c8c9cc, 0x00c8c9cc, 0x00c8c9cc, 0x00c7c9cc, 0x00c8c8cc, 0x00c8c9cc, 0x00cacccb, 0x00c9c8c7, 0x00c9c5c3, 0x00cccbc8, 0x00c8c7c3, 0x00c8c8c4, 0x00cbcac7, 0x00c8c8c8, 0x0096999c, 0x003c3834, 0x001c0800, 0x004d2000, 0x00b05c24, 0x00bf5813, 0x00bd550f, 0x00c25a0f, 0x00c05803, 0x00c15d08, 0x00b15809, 0x009e4703, 0x009b440e, 0x00af5017, 0x00c4580c, 0x00c85504, 0x00c8540f, 0x00bb551e, 0x00984c27, 0x00501800, 0x00370c00, 0x0071503c, 0x00391c0f, 0x002b0000, 0x00a25826, 0x00ba5c16, 0x00bf5408, 0x00c65808, 0x00c4570a, 0x00c55a0b, 0x00c25906, 0x00bf5807, 0x00be5611, 0x00c05614, 0x00c65515, 0x00c05614, 0x00b35a19, 0x00844818, 0x00160100, 0x000a0000, 0x00270300, 0x00925228, 0x00bc5a18, 0x00c55708, 0x00be5705, 0x00c15c08, 0x00c25802, 0x00c45905, 0x00c0580d, 0x009f4b16, 0x004d2410, 0x00130000, 0x00170100, 0x00481d02, 0x00b15c21, 0x00c3580e, 0x00c25814, 0x00a04f1c, 0x002c0900, 0x00140000, 0x00290400, 0x00784115, 0x00af6427, 0x00b45c14, 0x00b95b0c, 0x00b4580e, 0x009f5014, 0x00582000, 0x003c251a, 0x00b0acb1, 0x00c3c4cc, 0x00c8c8cc, 0x00ccc9c8, 0x00ccc4bf, 0x00cccbc8, 0x00c8c8c4, 0x00c6c6c6, 0x00cbcccc, 0x00c8cbcc, 0x00c9cccc, 0x00cacccb, 0x00cbcbc9, 0x00cbcbc9, 0x00cbcbcb, 0x00cbcbcb, 0x00cacbcc, 0x00cacbcc, 0x00c8cccc, 0x00c8cccb, 0x00caccc9, 0x00cccacc, 0x00ccc9cc, 0x00cccacc, 0x00cccbcc, 0x00c7cccc, 0x00c5cccc, 0x00c5caca, 0x00c9cacc, 0x00cccacb, 0x00cbc8c5, 0x00cccbc6, 0x00c0b9b4, 0x007c726c, 0x00200400, 0x00743818, 0x00984f2b, 0x008b4c2d, 0x00421600, 0x00150300, 0x00060000, 0x00020003, 0x00080001, 0x00150000, 0x003b1604, 0x0077401f, 0x009c4f26, 0x00ae4c1c, 0x00b44814, 0x00ae450c, 0x00b44d11, 0x00b34c10, 0x00b04b0d, 0x00b44c0e, 0x00b8500e, 0x00b9550d, 0x00bb5b15, 0x00ad5519, 0x00944414, 0x005c1500, 0x004b0a00, 0x00733014, 0x009d5c36, 0x00985829, 0x007c4417, 0x003b1800, 0x00150000, 0x000a0000, 0x00080000, 0x00170000, 0x003c1200, 0x00783b11, 0x00a75820, 0x00b85a14, 0x00bf5b10, 0x00bb5c10, 0x00b85e10, 0x00b45d0e, 0x00ad5e14, 0x009a5215, 0x006a350c, 0x001e0800, 0x00040000, 0x00030003, 0x00080308, 0x00060000, 0x00080000, 0x00130300, 0x00442000, 0x00955016, 0x00b95f15, 0x00c25c0f, 0x00c45b0a, 0x00c75d0c, 0x00c05908, 0x00c76210, 0x00bf600c, 0x00bc600c, 0x00be6410, 0x00bd6412, 0x00bc600c, 0x00c25f05, 0x00c46005, 0x00bf6107, 0x00b6671c, 0x00774212, 0x00381300, 0x00190000, 0x00340f00, 0x00794310, 0x00af6821, 0x00bb6411, 0x00c56109, 0x00cc650c, 0x00ca5c03, 0x00c95600, 0x00c85806, 0x00c05a19, 0x009f4f20, 0x00481700, 0x00180100, 0x00000000, 0x002c302d, 0x00908e88, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005a5a5a, 0x00060504, 0x00000000, 0x008d8c8c, 0x00c4c2c3, 0x00c6c6c6, 0x00cacaca, 0x00c8c8c8, 0x00686868, 0x000e0e0e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00010101, 0x00000000, 0x00000000, 0x00030301, 0x00000000, 0x00000000, 0x00020202, 0x00191919, 0x00838383, 0x00c5c5c5, 0x00c8c8c8, 0x00c8c8ca, 0x00c8c8ca, 0x00c8c8ca, 0x00c9c9cb, 0x00c8c9cb, 0x00c9c9cb, 0x00c8c9cb, 0x00c8c9c8, 0x00c8c9c8, 0x00c8c8ca, 0x00c8c8ca, 0x00c8c8c8, 0x00c9c8c7, 0x00cac9c8, 0x00cbc9ca, 0x00b6b4b5, 0x00676360, 0x000d0000, 0x003b1700, 0x00a05524, 0x00bc5a18, 0x00c5570e, 0x00c65406, 0x00c55804, 0x00c15a09, 0x00bc5c14, 0x00974108, 0x006a2100, 0x00944920, 0x00b85b1b, 0x00c0580b, 0x00c2560c, 0x00bc5716, 0x009e4b18, 0x00581e00, 0x002c0d00, 0x004c3827, 0x00381b11, 0x003e0d00, 0x00ad5c26, 0x00c15e16, 0x00ba5308, 0x00c65c0b, 0x00c85703, 0x00c55507, 0x00bf5712, 0x00b65114, 0x00b34e11, 0x00b95010, 0x00be510b, 0x00c45b12, 0x00b65914, 0x0097511c, 0x00290800, 0x000f0000, 0x00170000, 0x00704220, 0x00ab5418, 0x00c4580b, 0x00c55602, 0x00c65704, 0x00c3580e, 0x00be570e, 0x00bf590f, 0x00a75217, 0x00633013, 0x00170000, 0x00120000, 0x00361200, 0x00af5e28, 0x00c05912, 0x00c05811, 0x00a95520, 0x00310c00, 0x00110000, 0x00280400, 0x007a441a, 0x00a75c20, 0x00b85d17, 0x00bc570b, 0x00b75d1c, 0x007a4017, 0x00381703, 0x00645650, 0x00c9c9cb, 0x00c4c7c8, 0x00c8cccc, 0x00cbcac8, 0x00ccc9c7, 0x00cbcac8, 0x00cacac8, 0x00cacaca, 0x00cacaca, 0x00c9cbca, 0x00c9cbca, 0x00cccccc, 0x00c8c8c8, 0x00c6c6c6, 0x00cccccc, 0x00cccccc, 0x00c7c7c7, 0x00cccccc, 0x00c8cac9, 0x00cbcccc, 0x00c8c8c8, 0x00cccbcc, 0x00c8c7c8, 0x00cccacb, 0x00cccccc, 0x00c8c9c8, 0x00c9cbca, 0x00c8c9c8, 0x00cccccc, 0x00cacaca, 0x00cac9c8, 0x00c8c8c6, 0x00ccc9c7, 0x00b0acaa, 0x00281810, 0x00431804, 0x0087513a, 0x0063331c, 0x00240400, 0x000a0000, 0x00010108, 0x00000004, 0x00160501, 0x003b1300, 0x00743a16, 0x009c5325, 0x00a4501c, 0x00ab4c17, 0x00b04a14, 0x00b34a14, 0x00b74d14, 0x00b54a11, 0x00b4480c, 0x00bc4f10, 0x00bd5615, 0x00b45816, 0x00a7581c, 0x00824012, 0x00531700, 0x00490c00, 0x0072321e, 0x00965438, 0x0097583a, 0x00723f20, 0x00371300, 0x000c0000, 0x00070000, 0x00100100, 0x00130000, 0x003c1000, 0x00834518, 0x00a9581c, 0x00b3540f, 0x00c05c14, 0x00bb5811, 0x00b35916, 0x00ad5d20, 0x0095511d, 0x007e461d, 0x00582c10, 0x00210400, 0x00080000, 0x00030200, 0x00010004, 0x00020004, 0x00070000, 0x00100000, 0x001f0000, 0x00733d11, 0x00ad5d1f, 0x00bb5b0f, 0x00c25c0a, 0x00c45c08, 0x00c15b0a, 0x00be5b0b, 0x00c05d0b, 0x00c0600c, 0x00c05e0b, 0x00bb5c0c, 0x00b4601b, 0x00a3500a, 0x00bc5f0e, 0x00c06008, 0x00c06007, 0x00ba6415, 0x00a05b22, 0x00602c09, 0x001f0000, 0x001a0000, 0x003c1b04, 0x00825126, 0x00b16522, 0x00c46713, 0x00c45f04, 0x00cc6105, 0x00c85b04, 0x00c25404, 0x00c7590e, 0x00ba5a1d, 0x006d2a05, 0x002b0400, 0x000c0400, 0x000a0f0c, 0x00666664, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000c0c0c, 0x00383838, 0x00040404, 0x00191919, 0x00a6a6a6, 0x00c8c8c8, 0x00cacaca, 0x00cacaca, 0x00b5b5b5, 0x00535353, 0x00050505, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00060606, 0x006d6d6d, 0x00bfbfbf, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c7c8c6, 0x00c8c9c8, 0x00c6c9cc, 0x00c5c8cb, 0x00c8c8c9, 0x00c8c7c8, 0x00ccc8c9, 0x00ccc9ca, 0x00c8c5c4, 0x007e7a78, 0x001b120d, 0x00331402, 0x00914d21, 0x00b75818, 0x00c5540b, 0x00c95303, 0x00c45503, 0x00c2580a, 0x00b85411, 0x0094400c, 0x00541400, 0x00773819, 0x00a75419, 0x00bc5b12, 0x00bf570c, 0x00bf5813, 0x00a44d14, 0x005d2000, 0x001f0600, 0x002b1d0d, 0x002f1208, 0x00511d05, 0x00b15b21, 0x00bf590f, 0x00c05a0e, 0x00be5705, 0x00c95804, 0x00c55708, 0x00b4541b, 0x00963b08, 0x00963400, 0x00b85315, 0x00c1570e, 0x00be5609, 0x00ba5910, 0x00a4561f, 0x00441900, 0x00130000, 0x000f0000, 0x004d2a0e, 0x00a2541d, 0x00c05910, 0x00c55300, 0x00c95704, 0x00c25711, 0x00bf5814, 0x00c05910, 0x00ac5717, 0x006e3512, 0x001c0000, 0x00100000, 0x002e0c00, 0x00a25623, 0x00b95611, 0x00be5610, 0x00ab5720, 0x00340c00, 0x00120000, 0x00240100, 0x00764119, 0x00a85c20, 0x00ba5c16, 0x00be570d, 0x00ab5315, 0x00613315, 0x00342118, 0x008d8883, 0x00c9cbc8, 0x00caccc9, 0x00c5c9c6, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c8c8c8, 0x00cccccc, 0x00cacaca, 0x00c7c7c7, 0x00c6c6c6, 0x00cbcbcb, 0x00c6c6c6, 0x00c9c9c9, 0x00cccccc, 0x00c8c8c8, 0x00c3c3c3, 0x00cccccc, 0x00c3c3c3, 0x00cbcbcb, 0x00cacaca, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00cccccc, 0x00bdbdbd, 0x0057504c, 0x00200800, 0x0068493d, 0x00391a0c, 0x00160000, 0x00040001, 0x00040005, 0x00120402, 0x00341304, 0x00703412, 0x009f5020, 0x00a8501c, 0x00a54610, 0x00b3501a, 0x00b45018, 0x00ab440f, 0x00b1480e, 0x00b84b0c, 0x00be5211, 0x00c0561a, 0x00b85c21, 0x00a25621, 0x0076380c, 0x00481600, 0x00360700, 0x00612d17, 0x008b533e, 0x008f5840, 0x005e2d17, 0x002a0800, 0x00100000, 0x00040000, 0x00080100, 0x00130000, 0x00431600, 0x007f4118, 0x00a85920, 0x00ba5e1c, 0x00bc5d17, 0x00b35918, 0x00a9581c, 0x009b5424, 0x007b4018, 0x00502004, 0x002d0800, 0x00140000, 0x000b0000, 0x00060000, 0x00030102, 0x00000003, 0x00040305, 0x00040000, 0x00110000, 0x00481d00, 0x00904f1c, 0x00b75d18, 0x00c05a09, 0x00c25906, 0x00c35c08, 0x00c45f0d, 0x00bc5909, 0x00bc5a08, 0x00c15c0b, 0x00bc5a08, 0x00bb6017, 0x00aa6028, 0x00611800, 0x00a14b03, 0x00bd600c, 0x00bf5d06, 0x00c06312, 0x00b66524, 0x00844819, 0x003c1600, 0x00110000, 0x001b0500, 0x00512f15, 0x00a36028, 0x00b75f11, 0x00c66309, 0x00cb6205, 0x00c55b07, 0x00c25504, 0x00c85707, 0x00be5812, 0x00904114, 0x00410f00, 0x000c0000, 0x00010300, 0x00484848, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b2b2b2, 0x00121212, 0x00000000, 0x003a3a3a, 0x00b8b8b8, 0x00cbcbcb, 0x00cccccc, 0x00c8c8c8, 0x00a6a6a6, 0x00444444, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00020202, 0x00030303, 0x00000000, 0x00030303, 0x00010101, 0x00000000, 0x00000000, 0x00606060, 0x00b8b8b8, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c6, 0x00c7c8c8, 0x00c5c8cb, 0x00c5c8cb, 0x00c7c7c8, 0x00c8c7c8, 0x00c9c8c8, 0x00cac8c9, 0x00ccccca, 0x0094908e, 0x002f2824, 0x002c0f00, 0x00824014, 0x00b45718, 0x00c4550c, 0x00c85506, 0x00c45504, 0x00c45a0c, 0x00b6520f, 0x00984410, 0x00460900, 0x005c2104, 0x00974912, 0x00ba5d18, 0x00bf580e, 0x00be5812, 0x00a65016, 0x00672900, 0x001b0000, 0x00100200, 0x00260700, 0x006c3419, 0x00b25920, 0x00bd550a, 0x00c35c0f, 0x00bc5404, 0x00c55804, 0x00bf5810, 0x00984617, 0x006d2000, 0x00842800, 0x00bb581b, 0x00c45b13, 0x00bc5304, 0x00be580c, 0x00aa581c, 0x005c2c11, 0x00140000, 0x000e0000, 0x002c0c00, 0x0099501d, 0x00bc5913, 0x00c25300, 0x00c95705, 0x00c2550f, 0x00c05813, 0x00bd560c, 0x00b05817, 0x00743a16, 0x00210000, 0x000d0000, 0x00280900, 0x00954b1a, 0x00b75614, 0x00bb5610, 0x00ad5c22, 0x00360d00, 0x00150000, 0x001f0000, 0x00713c18, 0x00aa5920, 0x00b95914, 0x00bc580e, 0x009c4a0e, 0x00492105, 0x0044362c, 0x00bcb8b4, 0x00cacac8, 0x00ccccca, 0x00c8c8c6, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00cacaca, 0x00c8c8c8, 0x00cccccc, 0x00c6c6c6, 0x00c8c8c8, 0x00cacaca, 0x00c4c4c4, 0x00cccccc, 0x00c7c7c7, 0x00cccccc, 0x00cacaca, 0x00c8c8c8, 0x00cccccc, 0x00c2c2c2, 0x00c9c9c9, 0x00c8c8c8, 0x00cacaca, 0x00c8c8c8, 0x00c9c9c9, 0x00c8c8c8, 0x00cacaca, 0x00cbcbcb, 0x00c7c7c7, 0x008d8c8b, 0x00070403, 0x002e2825, 0x00100300, 0x000e0000, 0x000b0000, 0x00130000, 0x00401808, 0x007a3d20, 0x00a55226, 0x00ae4c18, 0x00b04a14, 0x00b24913, 0x00b04710, 0x00ab440d, 0x00ad4914, 0x00b95416, 0x00c05509, 0x00c0580d, 0x00b1571a, 0x009e5224, 0x0073381c, 0x00340700, 0x001f0000, 0x00391100, 0x004f230a, 0x005b3019, 0x00482516, 0x00210a00, 0x000a0000, 0x00060000, 0x00080000, 0x00160000, 0x00481800, 0x00914f24, 0x00af5c28, 0x00b2581c, 0x00b35918, 0x00a95818, 0x00985723, 0x0074431d, 0x00431d08, 0x00200200, 0x00130000, 0x00100000, 0x000b0000, 0x00070000, 0x00040001, 0x00040003, 0x00040000, 0x000f0807, 0x00030000, 0x00120000, 0x00643616, 0x00a05721, 0x00bc5a0f, 0x00c75a04, 0x00c45905, 0x00c05906, 0x00c35e0c, 0x00c05b09, 0x00c25b08, 0x00c45e0c, 0x00ba5c0f, 0x00b26121, 0x007e4419, 0x00360000, 0x009d4d0f, 0x00ba5c10, 0x00c15d08, 0x00c0600c, 0x00b46014, 0x00a05d20, 0x0060340e, 0x001d0000, 0x000e0000, 0x00280c00, 0x007f4214, 0x00b7641e, 0x00c66510, 0x00c75f04, 0x00c75d07, 0x00c55804, 0x00c85604, 0x00bd550f, 0x00ac5928, 0x00562002, 0x00100000, 0x00000000, 0x00282627, 0x0088888a, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a5a5a5, 0x00000000, 0x00000000, 0x00575757, 0x00bbbbbb, 0x00c9c9c9, 0x00cccccc, 0x00c6c6c6, 0x00a8a8a8, 0x00474747, 0x00000000, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00626262, 0x00b2b2b2, 0x00c6c6c6, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c5, 0x00c7c8c8, 0x00c5c8cb, 0x00c4c8ca, 0x00c7c7c8, 0x00c8c6c7, 0x00c9c8c8, 0x00cac8c9, 0x00c9c8c7, 0x00a3a09d, 0x00423c38, 0x00240b00, 0x00763509, 0x00b5581b, 0x00c2560e, 0x00c85608, 0x00c45506, 0x00c3580c, 0x00b85410, 0x009d4b16, 0x00430800, 0x00420d00, 0x0088400e, 0x00b65d1c, 0x00c05a11, 0x00bb540f, 0x00aa5118, 0x00713408, 0x00190000, 0x000e0000, 0x00250100, 0x00844828, 0x00b4571c, 0x00bf540a, 0x00c0580b, 0x00c05809, 0x00bf5708, 0x00b05414, 0x006e2b05, 0x00511200, 0x008a3505, 0x00bc5a1c, 0x00c25911, 0x00c05407, 0x00c2580a, 0x00ac5414, 0x00743e1f, 0x00180000, 0x000c0000, 0x001a0000, 0x00894518, 0x00b35614, 0x00c25506, 0x00c75505, 0x00c2540d, 0x00c05510, 0x00bd5508, 0x00b25918, 0x00793e18, 0x00240000, 0x000d0000, 0x00240800, 0x00854013, 0x00b55919, 0x00b95813, 0x00b05f25, 0x003c1000, 0x00190000, 0x001b0000, 0x006a3618, 0x00ab5720, 0x00b85611, 0x00b85810, 0x0090450c, 0x00391800, 0x00595149, 0x00ccc8c5, 0x00c9c8c7, 0x00cac9c8, 0x00ccccca, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c7c7c7, 0x00c2c2c2, 0x00cacaca, 0x00c6c6c6, 0x00cccccc, 0x00c7c7c7, 0x00c1c1c1, 0x00bebebe, 0x00bababa, 0x00c8c8c8, 0x00bfbfbf, 0x00c0c0c0, 0x00c5c5c5, 0x00cbcbcb, 0x00c9c9c9, 0x00c9c9c9, 0x00cacaca, 0x00c8c8c8, 0x00cccccc, 0x00c8c8c8, 0x00cbcbcb, 0x00c8c8c8, 0x00c7c7c7, 0x00b0b1b3, 0x00080f10, 0x00000000, 0x00090000, 0x00100000, 0x001e0000, 0x004d2013, 0x0087482c, 0x009d4d24, 0x00ac4c1a, 0x00ae450d, 0x00b44813, 0x00b74913, 0x00b3440c, 0x00b84b11, 0x00ba5419, 0x00b34e10, 0x00bc5510, 0x00bb5e1c, 0x00a05420, 0x00622400, 0x00340000, 0x00400f00, 0x00582105, 0x00491200, 0x003d0700, 0x00320100, 0x00200000, 0x00170000, 0x00100000, 0x000c0000, 0x00170300, 0x0034140a, 0x00895535, 0x009f5a2c, 0x00b05f2a, 0x00ab5720, 0x00a45821, 0x00864718, 0x00431a00, 0x00200400, 0x000c0000, 0x00080000, 0x000c0304, 0x00060000, 0x00030000, 0x00070202, 0x00040002, 0x00040000, 0x00050000, 0x00090000, 0x00080000, 0x00341b0a, 0x00885029, 0x00b26024, 0x00c35c0b, 0x00ca5903, 0x00c45c08, 0x00be5808, 0x00c05a0b, 0x00c45c0c, 0x00c25805, 0x00c05c0c, 0x00b9611a, 0x00a05923, 0x00441500, 0x00310000, 0x00a0541c, 0x00b85c13, 0x00c45f0c, 0x00c46009, 0x00b85d0a, 0x00b46820, 0x00844c17, 0x003f1800, 0x00100000, 0x001b0100, 0x004c1800, 0x00aa6026, 0x00bc6114, 0x00c56008, 0x00c75d06, 0x00c85a05, 0x00c85705, 0x00bc540b, 0x00b85f28, 0x006e300d, 0x00220800, 0x00080200, 0x00100c0c, 0x00686868, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00949494, 0x00000000, 0x00040404, 0x00727272, 0x00bdbdbd, 0x00c9c9c9, 0x00cacaca, 0x00c7c7c7, 0x00b5b5b5, 0x00515151, 0x00010101, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00707070, 0x00bcbcbc, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c5, 0x00c6c8c7, 0x00c4c8ca, 0x00c4c8ca, 0x00c7c7c8, 0x00c8c6c7, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00afaeac, 0x0054504c, 0x00220900, 0x006c2e03, 0x00b55c1f, 0x00c0570f, 0x00c45407, 0x00c45507, 0x00c05509, 0x00b85510, 0x009b4916, 0x00400c00, 0x002e0000, 0x0078370b, 0x00ac591d, 0x00be5b14, 0x00b9530d, 0x00ae551c, 0x007b3b10, 0x00180000, 0x00110000, 0x002b0100, 0x00975431, 0x00b65619, 0x00c25409, 0x00bf5507, 0x00c0580d, 0x00bb5a11, 0x00924109, 0x00451200, 0x004a1600, 0x00954617, 0x00b75617, 0x00be550c, 0x00c35607, 0x00c45607, 0x00b35614, 0x008c4f2c, 0x00200000, 0x000c0000, 0x00150000, 0x0070340d, 0x00a65015, 0x00c1590e, 0x00c55405, 0x00c4540d, 0x00c2540d, 0x00c3580a, 0x00b85c19, 0x007f401a, 0x00290400, 0x000c0000, 0x001f0400, 0x00733308, 0x00b05a1e, 0x00b85914, 0x00b05f24, 0x00481800, 0x001e0000, 0x00190000, 0x00643018, 0x00aa541e, 0x00ba5511, 0x00b75813, 0x00843e08, 0x00381d07, 0x006b6860, 0x00ccc9c5, 0x00ccc8c8, 0x00ccc8c8, 0x00cccacb, 0x00c9c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00cccccc, 0x00cccccc, 0x00c0c0c0, 0x00cccccc, 0x00c2c2c2, 0x00bbbbbb, 0x00828282, 0x00484848, 0x003c3c3c, 0x00383838, 0x00696969, 0x00adadad, 0x00c4c4c4, 0x00c8c8c8, 0x00c4c4c4, 0x00cbcbcb, 0x00c8c8c8, 0x00c8c8c8, 0x00cbcbcb, 0x00c8c8c8, 0x00cccccc, 0x00cccccc, 0x00c8c8c8, 0x00c3c3c3, 0x0020211f, 0x00090400, 0x00120000, 0x00290200, 0x00683320, 0x008f4c2f, 0x009f4c23, 0x00ab4f1c, 0x00ac4813, 0x00b44b14, 0x00b44816, 0x00b64814, 0x00c04b10, 0x00c14d0e, 0x00c05310, 0x00c25d20, 0x00b45a2a, 0x008e421c, 0x004c1000, 0x00320000, 0x00642404, 0x009e522c, 0x00b55b2c, 0x00b75924, 0x00ac581b, 0x009f5418, 0x00874714, 0x00672e09, 0x00441000, 0x00290000, 0x00230100, 0x00300f00, 0x0060381e, 0x00895837, 0x009c5f38, 0x008a4d26, 0x00552101, 0x00230000, 0x00130000, 0x00080000, 0x00070000, 0x00020000, 0x00000000, 0x00000001, 0x00000006, 0x00040309, 0x00050001, 0x000f0305, 0x00241918, 0x000b0000, 0x00160000, 0x00613619, 0x009f5724, 0x00b85b15, 0x00c15706, 0x00c45704, 0x00bd5a0d, 0x00be5c10, 0x00bf580b, 0x00c45b0b, 0x00be5401, 0x00bd5b10, 0x00b06024, 0x00783a0d, 0x002a0000, 0x00481800, 0x00a05420, 0x00bd5f18, 0x00c25d0b, 0x00c25c04, 0x00c26107, 0x00b9620e, 0x00a55c16, 0x00632f00, 0x00170000, 0x00140000, 0x00280100, 0x00793d11, 0x00b1601c, 0x00c56411, 0x00c75f07, 0x00ca5c04, 0x00c85705, 0x00c1550c, 0x00b85b1d, 0x00884217, 0x00361403, 0x000c0000, 0x00040000, 0x004b4a48, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00858585, 0x00020202, 0x00000000, 0x00828282, 0x00c0c0c0, 0x00c9c9c9, 0x00c8c8c8, 0x00c9c9c9, 0x00c2c2c2, 0x00686868, 0x000e0e0e, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00151515, 0x00848484, 0x00cacaca, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c4, 0x00c5c7c6, 0x00c4c7c9, 0x00c4c7c9, 0x00c6c6c8, 0x00c6c6c6, 0x00c7c7c7, 0x00c7c8c8, 0x00c8c9c8, 0x00b2b4b1, 0x005d5a58, 0x001c0600, 0x00602400, 0x00b35c20, 0x00be5611, 0x00c45408, 0x00c4570a, 0x00bf540a, 0x00b95611, 0x00964713, 0x003e0d00, 0x00200000, 0x00672d07, 0x00a1541d, 0x00bb5915, 0x00ba540e, 0x00b3591e, 0x00813f14, 0x00180000, 0x00160000, 0x00390a00, 0x00a45c33, 0x00bc5818, 0x00c35409, 0x00c3580c, 0x00bb570f, 0x00b35a1b, 0x006c2700, 0x002d0400, 0x0050240e, 0x009e5121, 0x00b65412, 0x00c0560c, 0x00c45405, 0x00c45202, 0x00bc5814, 0x009d5830, 0x002c0400, 0x000c0000, 0x00140100, 0x00542000, 0x009b4c16, 0x00bf5b13, 0x00c45406, 0x00c5540e, 0x00c4540d, 0x00c45708, 0x00b75a16, 0x0082421b, 0x002e0800, 0x000c0000, 0x001a0300, 0x00612801, 0x00b05e24, 0x00b75814, 0x00af5c20, 0x00582405, 0x00240200, 0x00170000, 0x00582815, 0x00a54f1c, 0x00bc5714, 0x00b45818, 0x00763503, 0x003b2413, 0x00767572, 0x00cccac8, 0x00cccaca, 0x00cccacc, 0x00cac5c7, 0x00c8c7c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c2c2c2, 0x00c6c6c6, 0x00cacaca, 0x00bbbbbb, 0x009b9b9b, 0x002d2d2d, 0x00040404, 0x00050505, 0x00020202, 0x00030303, 0x00080808, 0x00161616, 0x006e6e6e, 0x00b2b2b2, 0x00c5c5c5, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c8c8c8, 0x00c5c5c5, 0x00c8c8c8, 0x00cccccc, 0x00c9c9c9, 0x00c7c6c4, 0x003c3836, 0x00140400, 0x00411807, 0x0080432b, 0x00954828, 0x00a24a21, 0x00ad4e19, 0x00ab480e, 0x00b04a11, 0x00b24c13, 0x00b54b17, 0x00ba4c16, 0x00c35014, 0x00c65617, 0x00bb5818, 0x00ac541d, 0x00782c05, 0x00410000, 0x00400700, 0x007b3e14, 0x00a55b25, 0x00b45a1d, 0x00c05714, 0x00c35610, 0x00c35d13, 0x00b85911, 0x00ad5614, 0x00aa5822, 0x00ab5b34, 0x0099502f, 0x006d320e, 0x00461400, 0x002e0000, 0x00350500, 0x004a1800, 0x00350800, 0x001a0000, 0x00160000, 0x00070000, 0x00020004, 0x00000000, 0x00000000, 0x00040000, 0x000c0100, 0x000f0000, 0x00100000, 0x00260c04, 0x00503830, 0x0054413b, 0x001e0700, 0x003a1100, 0x008b4e24, 0x00b25d20, 0x00be5a10, 0x00c45809, 0x00c65c0c, 0x00bc580e, 0x00be5c10, 0x00bd5709, 0x00c25c0e, 0x00c05c12, 0x00b8601f, 0x008e4b19, 0x003f0900, 0x00270000, 0x007a4321, 0x00ab5c24, 0x00ba5c14, 0x00c05e0d, 0x00c05c06, 0x00c05d02, 0x00ba5c04, 0x00b45f12, 0x00894912, 0x00311200, 0x000e0000, 0x00190000, 0x00401400, 0x00a45d27, 0x00bb6218, 0x00c45f09, 0x00c85c04, 0x00c85604, 0x00c6580d, 0x00bc5814, 0x00a15320, 0x004a1f08, 0x000d0000, 0x00060000, 0x00373433, 0x00a09c9f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00828282, 0x00010101, 0x00000000, 0x00848484, 0x00c0c0c0, 0x00c9c9c9, 0x00c8c8c8, 0x00c8c8c8, 0x00c6c6c6, 0x00949494, 0x003c3c3c, 0x00030303, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00090909, 0x004b4b4b, 0x00a2a2a2, 0x00c6c6c6, 0x00c5c5c5, 0x00c5c5c5, 0x00c5c5c5, 0x00c5c5c5, 0x00c5c5c5, 0x00c5c5c5, 0x00c5c5c5, 0x00c5c5c5, 0x00c5c4c3, 0x00c5c5c5, 0x00c3c6c8, 0x00c2c5c8, 0x00c4c4c6, 0x00c5c5c5, 0x00c6c6c6, 0x00c6c8c7, 0x00c5c8c9, 0x00afb2b1, 0x005e5d5c, 0x00170300, 0x00581d00, 0x00b15c21, 0x00bc5713, 0x00c4550c, 0x00c2570b, 0x00bf560d, 0x00b95512, 0x00944614, 0x003b0e00, 0x001a0000, 0x00552302, 0x00944c1b, 0x00b85817, 0x00bc5510, 0x00b75a1c, 0x00884315, 0x00270400, 0x001b0000, 0x00501a00, 0x00ac5c2d, 0x00bd5614, 0x00c45408, 0x00c2560c, 0x00b75614, 0x009c4f18, 0x004b1200, 0x00220000, 0x005a311a, 0x00a75826, 0x00ba5510, 0x00c65809, 0x00c65402, 0x00c45001, 0x00bf5814, 0x00a4572b, 0x00461500, 0x000f0000, 0x000e0000, 0x00390e00, 0x00924b1c, 0x00b85815, 0x00c45408, 0x00c6530c, 0x00c6540a, 0x00c25204, 0x00b85813, 0x00854319, 0x00340b00, 0x000d0000, 0x00160100, 0x00531d00, 0x00ae602c, 0x00b85815, 0x00b25a1e, 0x006a3110, 0x002b0500, 0x00140000, 0x004c2010, 0x009b4815, 0x00b95815, 0x00b0571a, 0x00713204, 0x003b2618, 0x00818181, 0x00cccbca, 0x00cccaca, 0x00cccacc, 0x00c8c4c7, 0x00c8c6c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00cccccc, 0x00c8c8c8, 0x00c3c3c3, 0x00999999, 0x00232323, 0x00010101, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00060606, 0x000f0f0f, 0x00696969, 0x00b5b5b5, 0x00c8c8c8, 0x00c7c7c7, 0x00c6c6c6, 0x00c6c6c6, 0x00c5c5c5, 0x00c5c5c5, 0x00cacaca, 0x00cacaca, 0x00c4c1c2, 0x0041393a, 0x0030130c, 0x00804028, 0x00ad5430, 0x00a84314, 0x00b04610, 0x00b24c10, 0x00ac4a0a, 0x00ac4b0a, 0x00b24d10, 0x00bc5216, 0x00bd5015, 0x00bd5317, 0x00ba5c22, 0x008f4715, 0x00541800, 0x003c0000, 0x00622200, 0x00945114, 0x00ad641c, 0x00b35e0c, 0x00b95c05, 0x00c45f07, 0x00c25c04, 0x00bc5504, 0x00bf570a, 0x00c45914, 0x00c45816, 0x00bd5314, 0x00b85315, 0x00b05414, 0x00a65318, 0x00893f0e, 0x005c1d00, 0x00310300, 0x001e0000, 0x00140000, 0x000b0000, 0x00050002, 0x00000004, 0x00000103, 0x00080300, 0x00140000, 0x002c0200, 0x00521800, 0x00783711, 0x008c5230, 0x008c5d42, 0x003c1d0c, 0x00250200, 0x00662b04, 0x00a4541e, 0x00bb5c17, 0x00be570d, 0x00bc5409, 0x00bc550a, 0x00c1590c, 0x00c05809, 0x00c05708, 0x00bd5a12, 0x00b35e21, 0x00924d1c, 0x00542200, 0x00260000, 0x00491000, 0x00a15a2d, 0x00b55e1c, 0x00b5580c, 0x00bc6314, 0x00bc6110, 0x00be5d09, 0x00c3600e, 0x00b95b0e, 0x00a95c20, 0x005c310e, 0x00160000, 0x00100000, 0x001e0300, 0x00763e15, 0x00ad6022, 0x00c0600f, 0x00c85c04, 0x00c85705, 0x00c65608, 0x00c2580d, 0x00b35c23, 0x005c290d, 0x001a0000, 0x000b0000, 0x0024211f, 0x00837c80, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00868686, 0x00000000, 0x00030303, 0x00848484, 0x00bfbfbf, 0x00cacaca, 0x00cacaca, 0x00c4c4c4, 0x00c4c4c4, 0x00bcbcbc, 0x00737373, 0x00161616, 0x00000000, 0x00040404, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00232323, 0x008b8b8b, 0x00c4c4c4, 0x00c1c1c1, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c2, 0x00c4c4c4, 0x00c2c5c8, 0x00c1c4c7, 0x00c3c4c5, 0x00c4c4c4, 0x00c4c6c5, 0x00c4c7c6, 0x00c7cacb, 0x00afb2b1, 0x0060605e, 0x00170300, 0x00541a00, 0x00af5c21, 0x00b95512, 0x00c0540c, 0x00bf5309, 0x00bf560e, 0x00b65410, 0x00944716, 0x00340e00, 0x00160000, 0x00451800, 0x00884619, 0x00b65818, 0x00bc560f, 0x00b65819, 0x008e4616, 0x00381000, 0x00230000, 0x00662807, 0x00ae5a26, 0x00bc530f, 0x00c45408, 0x00bf530b, 0x00b5581b, 0x00813f14, 0x00390b00, 0x001f0000, 0x0063381c, 0x00ad5c24, 0x00bc540b, 0x00c85707, 0x00c85300, 0x00c55204, 0x00be5613, 0x00a85321, 0x00642a0c, 0x00140100, 0x000a0000, 0x002a0400, 0x008c4c25, 0x00b25616, 0x00c4550c, 0x00c45009, 0x00c85308, 0x00c55405, 0x00ba5814, 0x008b451b, 0x003a0f00, 0x000e0000, 0x000f0000, 0x00461400, 0x00a85d2c, 0x00b85918, 0x00b5581b, 0x007a3915, 0x00310800, 0x00130000, 0x003f190b, 0x00914213, 0x00b55818, 0x00ab541a, 0x0072340b, 0x00382317, 0x008b898c, 0x00ccc8c8, 0x00ccc9c9, 0x00c8c6c7, 0x00c8c7c9, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c5c5c5, 0x00c5c5c5, 0x00a6a6a6, 0x00494949, 0x000a0a0a, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00262626, 0x00848484, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c5c5c5, 0x00c8c8c8, 0x00c6c6c6, 0x00cbcbcb, 0x00cccccc, 0x00c5c2c3, 0x00544749, 0x002e0b04, 0x00904429, 0x00a84419, 0x00b4430e, 0x00bc4a0d, 0x00ae4402, 0x00b4500a, 0x00b75712, 0x00b65717, 0x00b8571e, 0x00ba5b26, 0x00a94e1c, 0x00752800, 0x00440c00, 0x003a0800, 0x00763a06, 0x009c5818, 0x00b46617, 0x00bb650a, 0x00c66907, 0x00ca6803, 0x00c66300, 0x00c86403, 0x00cb6309, 0x00c85c08, 0x00c95809, 0x00c85508, 0x00c75505, 0x00c75807, 0x00c6580c, 0x00bd5710, 0x00b3561a, 0x00a15522, 0x00824720, 0x00491e00, 0x00200100, 0x00110000, 0x00060000, 0x00080304, 0x00110908, 0x00382418, 0x00693a1a, 0x00904b1d, 0x00a44e18, 0x00a9541d, 0x009c5528, 0x0078401c, 0x00260000, 0x003c1000, 0x00984f1c, 0x00b35716, 0x00bc560d, 0x00c0560a, 0x00c0580f, 0x00c05a10, 0x00c4590d, 0x00bc5409, 0x00bc5c17, 0x00ad581d, 0x00904e20, 0x005b2804, 0x00280000, 0x003a0800, 0x00924c21, 0x00ae5b20, 0x00b45811, 0x00b85d12, 0x00af5f18, 0x00ac5c18, 0x00b45c18, 0x00ba5f18, 0x00b85c16, 0x00b26225, 0x007c4418, 0x00331000, 0x000c0000, 0x000f0000, 0x00381000, 0x00a36330, 0x00b96115, 0x00c65d07, 0x00c85808, 0x00c45304, 0x00c55708, 0x00bb5d1e, 0x006c3010, 0x00300f00, 0x000a0000, 0x0015110e, 0x006a6367, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008e8e8e, 0x00020202, 0x00000100, 0x00777878, 0x00bcbdbc, 0x00cbcccc, 0x00c4c6c5, 0x00c2c4c3, 0x00c6c8c7, 0x00c0c2c1, 0x00b0b1b0, 0x00676868, 0x001c1d1c, 0x00000000, 0x00000100, 0x00010302, 0x00000000, 0x00000000, 0x00000000, 0x00000100, 0x00000000, 0x00242625, 0x007a7c7b, 0x00b9bbba, 0x00c6c8c7, 0x00c2c4c3, 0x00c3c4c4, 0x00c3c4c4, 0x00c3c4c4, 0x00c3c4c4, 0x00c3c4c4, 0x00c3c4c4, 0x00c3c4c4, 0x00c4c4c4, 0x00c4c4c2, 0x00c4c4c4, 0x00c2c5c8, 0x00c4c7c9, 0x00c4c6c5, 0x00c3c3c1, 0x00c1c3c2, 0x00c3c6c5, 0x00c8cbcc, 0x00a9acac, 0x00545452, 0x00160100, 0x00501800, 0x00ab581f, 0x00bc5816, 0x00c0540c, 0x00c1550c, 0x00bf560e, 0x00b65514, 0x008c4414, 0x00300f00, 0x00140000, 0x00340b00, 0x0083431a, 0x00b55b1c, 0x00bd5710, 0x00b75615, 0x00954818, 0x00481a03, 0x00270000, 0x007a3810, 0x00af561d, 0x00c05510, 0x00c45309, 0x00bf5610, 0x00b45d24, 0x00602705, 0x002b0300, 0x002d0800, 0x006e3b18, 0x00b05b1c, 0x00c15405, 0x00ca5402, 0x00ca5301, 0x00c35005, 0x00bf5614, 0x00ab501a, 0x007f3e18, 0x00160000, 0x000c0000, 0x001f0000, 0x007b4020, 0x00b0581c, 0x00c1550d, 0x00c8540c, 0x00c85208, 0x00c55405, 0x00bc5a15, 0x008c4419, 0x003e1100, 0x000b0000, 0x00100000, 0x00370a00, 0x00a65d30, 0x00bb581a, 0x00b55315, 0x00985027, 0x00370800, 0x00140000, 0x002e0d00, 0x00843d10, 0x00b1581f, 0x00ab5720, 0x006f3009, 0x003a2219, 0x00898489, 0x00ccc7c8, 0x00ccc8c8, 0x00cccccc, 0x00c3c4c5, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c3c3c3, 0x00c5c5c5, 0x008b8b8b, 0x00111111, 0x00070707, 0x00000000, 0x00000000, 0x00030303, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00626262, 0x00b4b4b4, 0x00c3c3c3, 0x00c4c4c4, 0x00c9c9c9, 0x00c0c0c0, 0x00cbcbcb, 0x00cccccc, 0x00c3c3c3, 0x00ccc7c7, 0x00483939, 0x00361006, 0x00904428, 0x00ac481d, 0x00b64711, 0x00ba4809, 0x00bb4f07, 0x00bd560b, 0x00bb5c14, 0x00b45f20, 0x00a3572a, 0x007f3915, 0x00531200, 0x00400500, 0x005c2400, 0x00874d14, 0x00a7641d, 0x00b36414, 0x00c0660c, 0x00c86607, 0x00ca6601, 0x00cc6600, 0x00ca6600, 0x00cb6700, 0x00cc6403, 0x00cc6408, 0x00cc640b, 0x00cc630c, 0x00c96108, 0x00c75d06, 0x00c45806, 0x00c1550c, 0x00bd5815, 0x00b45719, 0x00af561c, 0x009e5320, 0x00743c12, 0x003c1800, 0x001d0c00, 0x00180900, 0x00492e24, 0x0082543f, 0x009c5128, 0x00b0551d, 0x00b6581b, 0x00b35d25, 0x008c4c24, 0x00441100, 0x00250000, 0x00743d19, 0x00a7551c, 0x00b7540d, 0x00c1570b, 0x00c25408, 0x00c0580c, 0x00bb550b, 0x00bf580e, 0x00b95c18, 0x00a45824, 0x0082481f, 0x004d2207, 0x00210000, 0x00390a00, 0x007f4116, 0x00ad5c20, 0x00b35610, 0x00bf6014, 0x00a85109, 0x00914e14, 0x00894c1b, 0x00935020, 0x00a95f2e, 0x00b0602b, 0x00ab5d27, 0x009d5a27, 0x005e3009, 0x000e0000, 0x00080000, 0x001d0500, 0x0072421a, 0x00b3641f, 0x00bd5b08, 0x00c85b0c, 0x00c95809, 0x00c65402, 0x00bc5815, 0x0087421b, 0x003c1400, 0x000c0000, 0x00090502, 0x0050484c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9c9c, 0x00000000, 0x00000000, 0x00616362, 0x00b8bab9, 0x00c9cbca, 0x00c8c9c8, 0x00c4c6c5, 0x00c3c4c4, 0x00c1c3c2, 0x00c0c1c0, 0x00acaead, 0x007e807f, 0x003f4040, 0x000e100f, 0x00000000, 0x00000000, 0x00010302, 0x00000000, 0x001a1c1b, 0x00484948, 0x00848685, 0x00b7b8b8, 0x00c1c3c2, 0x00bcbdbc, 0x00c3c4c4, 0x00c2c4c3, 0x00c2c4c3, 0x00c2c4c3, 0x00c2c4c3, 0x00c2c4c3, 0x00c2c4c3, 0x00c2c4c3, 0x00c2c4c3, 0x00c2c1c0, 0x00c4c4c4, 0x00c0c3c5, 0x00bec1c4, 0x00c1c3c2, 0x00c2c2c0, 0x00c2c4c3, 0x00c4c6c5, 0x00c7cacb, 0x00a1a4a4, 0x00454544, 0x00150000, 0x00501600, 0x00ac5920, 0x00bd5918, 0x00c3570f, 0x00c1530a, 0x00be550f, 0x00b45616, 0x00874214, 0x002c1000, 0x000e0000, 0x002c0700, 0x00783b14, 0x00b65c1f, 0x00bd5710, 0x00ba5613, 0x009f4c18, 0x0056220a, 0x00300000, 0x00873e12, 0x00b3561a, 0x00c1560f, 0x00c3540b, 0x00bd5512, 0x00a95624, 0x004e1f05, 0x00200000, 0x00320b00, 0x00783e15, 0x00b45a18, 0x00c35304, 0x00cc5402, 0x00cc5302, 0x00c15008, 0x00bf5614, 0x00b45318, 0x008d481c, 0x001c0000, 0x000c0000, 0x00190000, 0x00703b1f, 0x00a9541c, 0x00bd540e, 0x00c8540c, 0x00c85007, 0x00c45304, 0x00bb5915, 0x008d4418, 0x00401400, 0x000b0000, 0x000d0000, 0x00300800, 0x00a05a2f, 0x00ba5518, 0x00bb5314, 0x00a75728, 0x004c1500, 0x00180000, 0x00200300, 0x00783810, 0x00ab5924, 0x00ad5b26, 0x0075340f, 0x00381e15, 0x007a7377, 0x00ccc8c9, 0x00ccc8c8, 0x00cacbcc, 0x00bfc4c4, 0x00c2c4c3, 0x00c3c3c3, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c3c3c3, 0x00c3c3c3, 0x00c4c4c4, 0x00bcbcbc, 0x00767676, 0x00090909, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00060606, 0x00000000, 0x00474747, 0x009d9d9d, 0x00c4c4c4, 0x00c5c5c5, 0x00c2c2c2, 0x00c4c4c4, 0x00c5c5c5, 0x00cacaca, 0x00cccccc, 0x00c4c0be, 0x0040302b, 0x003d1705, 0x00934722, 0x00b04c1b, 0x00b64c14, 0x00bd5315, 0x00bc5817, 0x00b55917, 0x00ab5618, 0x008e440e, 0x00642400, 0x00490e00, 0x00501400, 0x00723408, 0x0098561c, 0x00ae6620, 0x00b46414, 0x00be640e, 0x00c8630a, 0x00cc6306, 0x00cc6201, 0x00cc6300, 0x00ca6400, 0x00c96500, 0x00cb6402, 0x00ca6503, 0x00cb6605, 0x00ca6606, 0x00c86605, 0x00c86407, 0x00c96008, 0x00c85d0b, 0x00c25a0d, 0x00c35a11, 0x00bc540b, 0x00bc5c1b, 0x00a45a24, 0x0074431c, 0x002e1400, 0x00190400, 0x00341408, 0x00622f18, 0x009e5227, 0x00b25b25, 0x00ad5820, 0x00a05625, 0x005c2508, 0x00270000, 0x00481400, 0x008b491c, 0x00b45a1d, 0x00be5810, 0x00be550c, 0x00b85108, 0x00b95813, 0x00b95c1a, 0x00b15819, 0x00a0521c, 0x00733812, 0x00401400, 0x00250200, 0x003b1400, 0x00743a11, 0x00a35720, 0x00b65c18, 0x00ba5a0e, 0x00b55509, 0x00883400, 0x004c1200, 0x003e1000, 0x00441500, 0x00501d00, 0x007c3e1b, 0x009f5b2f, 0x00aa602c, 0x00804519, 0x00261000, 0x000a0200, 0x000b0000, 0x00462304, 0x00a86324, 0x00bb5d10, 0x00c3590b, 0x00c95809, 0x00ca5503, 0x00c05812, 0x00944819, 0x004a1b01, 0x000e0000, 0x00050100, 0x00473e41, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00aeaeae, 0x000a0a0a, 0x00010302, 0x00444544, 0x00b6b8b7, 0x00c6c8c7, 0x00c9cbca, 0x00c4c6c5, 0x00bec0bf, 0x00c0c2c1, 0x00c0c1c0, 0x00c0c2c1, 0x00b5b7b6, 0x009b9c9c, 0x007c7e7d, 0x00676868, 0x005c5d5c, 0x00565857, 0x00686968, 0x007f8080, 0x009fa0a0, 0x00bbbcbc, 0x00c6c8c7, 0x00c0c2c1, 0x00bdbfbe, 0x00c5c7c6, 0x00c0c2c1, 0x00c0c2c1, 0x00c0c2c1, 0x00c0c2c1, 0x00c0c2c1, 0x00c0c2c1, 0x00c0c2c1, 0x00c0c2c1, 0x00c0c0be, 0x00c4c4c4, 0x00bfc2c4, 0x00bcbfc1, 0x00c1c1c1, 0x00c2c2c0, 0x00c0c2c0, 0x00c5c7c4, 0x00c8cccb, 0x00969897, 0x0030302e, 0x00160000, 0x00511600, 0x00af5921, 0x00bc5716, 0x00c2540c, 0x00c15209, 0x00bd540e, 0x00b45719, 0x007e3d11, 0x00280d00, 0x000c0000, 0x00270300, 0x00703410, 0x00b45a1d, 0x00bb540b, 0x00ba540e, 0x00a75018, 0x00672b11, 0x00390000, 0x00944615, 0x00b45514, 0x00c0550c, 0x00c1530c, 0x00bc5617, 0x009d4e20, 0x003e1403, 0x00180000, 0x00370c00, 0x00804014, 0x00b65917, 0x00c35304, 0x00cc5401, 0x00cc5304, 0x00c15008, 0x00bf5513, 0x00bb5618, 0x009e5322, 0x00260400, 0x000c0000, 0x00160000, 0x00633219, 0x00a14f1a, 0x00bc540f, 0x00c8530e, 0x00c85007, 0x00c35305, 0x00b95814, 0x008f461a, 0x00451800, 0x000c0000, 0x000b0000, 0x00290400, 0x009a552c, 0x00b95317, 0x00c05413, 0x00b15a26, 0x00682b06, 0x00250400, 0x00190000, 0x00672e0b, 0x009d5525, 0x00ac5c2a, 0x007d3c16, 0x00361811, 0x00665c61, 0x00ccc9ca, 0x00ccc8c8, 0x00c8cbcc, 0x00bfc4c4, 0x00c0c2c1, 0x00c1c1c1, 0x00c2c2c2, 0x00c2c2c2, 0x00c2c2c2, 0x00c2c2c2, 0x00c1c1c1, 0x00c1c1c1, 0x00c0c0c0, 0x00b8b8b8, 0x006d6d6d, 0x00020202, 0x00000000, 0x00000000, 0x00030303, 0x00020202, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00030303, 0x00000000, 0x003d3d3d, 0x00979797, 0x00c2c2c2, 0x00c4c4c4, 0x00bebebe, 0x00c6c6c6, 0x00c4c4c4, 0x00cbcbcb, 0x00cccccc, 0x00c2beb9, 0x00251809, 0x00482103, 0x009c4d19, 0x00b95719, 0x00ba551a, 0x00b95c24, 0x00a45828, 0x008d4c22, 0x00682b03, 0x00521700, 0x004c0d00, 0x00642200, 0x008e4312, 0x00ac5a1c, 0x00ba6214, 0x00c0620d, 0x00c3620e, 0x00c6600e, 0x00ca600f, 0x00cc5e0d, 0x00cc5e07, 0x00cc6004, 0x00ca6106, 0x00c96408, 0x00c86506, 0x00c66803, 0x00c76900, 0x00c66b00, 0x00c86906, 0x00c86807, 0x00ca6705, 0x00cc6506, 0x00c45c01, 0x00ca5e08, 0x00c55400, 0x00c0580d, 0x00b36027, 0x00804521, 0x002d0c00, 0x00110000, 0x00110000, 0x00321000, 0x005e2a08, 0x00894c24, 0x00925730, 0x006c381a, 0x002f0600, 0x00260000, 0x007e401c, 0x00a65822, 0x00b45818, 0x00b75510, 0x00ba5917, 0x00b45a1a, 0x00ac5a23, 0x009c5220, 0x00854417, 0x005c2300, 0x00340800, 0x00270100, 0x003c1400, 0x00743e1a, 0x00aa5b24, 0x00b75c17, 0x00b4580e, 0x00b95c10, 0x00b4560e, 0x008c3b01, 0x003d0800, 0x001c0000, 0x00170000, 0x001a0000, 0x00391401, 0x006b3818, 0x00a35c2c, 0x00975527, 0x00543018, 0x00100000, 0x00080000, 0x001f0700, 0x00955923, 0x00b66018, 0x00bd560c, 0x00c95809, 0x00cc5704, 0x00c35810, 0x00a3511c, 0x00582403, 0x00120000, 0x00030000, 0x00393234, 0x004d4b4c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00262626, 0x00020403, 0x00232424, 0x00acaead, 0x00c5c7c6, 0x00c8c9c8, 0x00c2c4c3, 0x00bcbebd, 0x00c0c1c0, 0x00c0c1c0, 0x00babcbb, 0x00bbbcbc, 0x00c0c2c1, 0x00bcbebd, 0x00b0b2b1, 0x00aaacab, 0x00acaead, 0x00b7b8b8, 0x00bec0bf, 0x00c0c2c1, 0x00bcbdbc, 0x00b8bab9, 0x00bdbfbe, 0x00c0c2c1, 0x00bdbfbe, 0x00bfc0c0, 0x00bfc0c0, 0x00bfc0c0, 0x00bfc0c0, 0x00bfc0c0, 0x00bfc0c0, 0x00bfc0c0, 0x00bfc0c0, 0x00bdbdbc, 0x00c2c2c2, 0x00bec1c4, 0x00bcc0c2, 0x00c1c1c1, 0x00c0bfbd, 0x00bfbfbd, 0x00c5c7c4, 0x00c8cac9, 0x00838482, 0x001b1a17, 0x00170100, 0x00571a00, 0x00b15a23, 0x00bc5414, 0x00c05009, 0x00c3520a, 0x00be550f, 0x00b1581c, 0x0074360c, 0x00230c00, 0x000b0000, 0x00280400, 0x00703310, 0x00b3591e, 0x00ba530a, 0x00bc530b, 0x00b05318, 0x00783418, 0x00420200, 0x009f4b17, 0x00b65410, 0x00bd5308, 0x00bd530a, 0x00b95719, 0x0094481f, 0x00340f02, 0x00150000, 0x00370c00, 0x007e3d11, 0x00b65917, 0x00c05204, 0x00c85003, 0x00c95105, 0x00c35008, 0x00c05310, 0x00bd5614, 0x00a85824, 0x00350e00, 0x00120000, 0x00150000, 0x00582b15, 0x009c4d19, 0x00bc5410, 0x00c8530e, 0x00c85109, 0x00c35307, 0x00b85714, 0x0090471c, 0x00481a03, 0x000d0000, 0x000a0000, 0x00260200, 0x00935129, 0x00b85216, 0x00c25310, 0x00b4561c, 0x00884016, 0x00381000, 0x001c0000, 0x00542004, 0x008d4c24, 0x00a85a29, 0x007f3d17, 0x00301208, 0x00504649, 0x00cac3c4, 0x00cac8c9, 0x00c6c9c8, 0x00c0c5c5, 0x00c0c1c0, 0x00c0c0c0, 0x00c0c0c0, 0x00c0c0c0, 0x00c0c0c0, 0x00c0c0c0, 0x00c0c0c0, 0x00c0c0c0, 0x00c0c0c0, 0x00bdbdbd, 0x00787878, 0x00020202, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00474747, 0x00a1a1a1, 0x00c0c0c0, 0x00c1c1c1, 0x00bfbfbf, 0x00c1c1c1, 0x00c6c6c6, 0x00cacaca, 0x00c3c3c3, 0x00b3ada7, 0x00170500, 0x005e3511, 0x00a0551d, 0x00b45a1d, 0x00ab5420, 0x00984f24, 0x00693314, 0x00451800, 0x003c1000, 0x00521f02, 0x00783a17, 0x009f5427, 0x00b86024, 0x00c05f14, 0x00c45f07, 0x00c75f04, 0x00c46008, 0x00c65f0c, 0x00ca5d0d, 0x00cb5c0c, 0x00cb5d08, 0x00ca5e08, 0x00c86109, 0x00c7640a, 0x00c46507, 0x00c46804, 0x00c46900, 0x00c46a00, 0x00c46a02, 0x00c56904, 0x00c86804, 0x00ca6704, 0x00ca6503, 0x00cc6404, 0x00cc5e01, 0x00c05606, 0x00aa5621, 0x0064270a, 0x00240200, 0x00120000, 0x00280d00, 0x0046250d, 0x003a1000, 0x004d2000, 0x0060351c, 0x00361000, 0x001c0000, 0x004a1c0c, 0x009a552c, 0x00ae5c24, 0x00ac561a, 0x00aa5418, 0x00a95820, 0x00a05524, 0x00844419, 0x00612804, 0x00471300, 0x002c0000, 0x00310400, 0x0058280c, 0x00814723, 0x00a05828, 0x00b85b1b, 0x00b8540b, 0x00b85a0e, 0x00b65c10, 0x00bc5c16, 0x00a9561d, 0x00632c0c, 0x00260400, 0x000a0000, 0x00090000, 0x00110000, 0x002f0c00, 0x00783c14, 0x009a592f, 0x007c4e30, 0x00280c00, 0x00100300, 0x00140000, 0x007a4515, 0x00b16020, 0x00bc5810, 0x00c8580a, 0x00ca5506, 0x00c2560c, 0x00ae581d, 0x00642a02, 0x00170100, 0x00030000, 0x002d2a2b, 0x00949094, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000c0c0c, 0x004a4a4a, 0x00000100, 0x00080a09, 0x00939494, 0x00c4c6c5, 0x00c8cac9, 0x00c1c3c2, 0x00bfc0c0, 0x00bdbfbe, 0x00bfc0c0, 0x00bfc0c0, 0x00bec0bf, 0x00bcbebd, 0x00b9bbba, 0x00b8b9b8, 0x00babcbb, 0x00bec0bf, 0x00bbbcbc, 0x00bbbcbc, 0x00bfc0c0, 0x00c0c1c0, 0x00bcbdbc, 0x00bcbdbc, 0x00bcbebd, 0x00babcbb, 0x00bdbfbe, 0x00bdbfbe, 0x00bdbfbe, 0x00bdbfbe, 0x00bdbfbe, 0x00bdbfbe, 0x00bdbfbe, 0x00bdbfbe, 0x00bcbcbb, 0x00bdbfbe, 0x00bcbfc1, 0x00bcc0c2, 0x00bfbfbf, 0x00bcbbb9, 0x00bebfbb, 0x00c8c9c5, 0x00bec0bd, 0x00696968, 0x000c0907, 0x00180100, 0x005e2000, 0x00b45c24, 0x00be5414, 0x00c4510c, 0x00c45208, 0x00be5410, 0x00b05a20, 0x00682f07, 0x00200b00, 0x000a0000, 0x002a0500, 0x00713410, 0x00b45a1f, 0x00bd540c, 0x00c0540a, 0x00b75519, 0x00873c1d, 0x004e0600, 0x00a84e19, 0x00b9540f, 0x00be5409, 0x00bc530b, 0x00b7571a, 0x008a4019, 0x00310b00, 0x00140000, 0x00330a00, 0x00783912, 0x00b35a1b, 0x00bf530b, 0x00c35007, 0x00c75107, 0x00c75008, 0x00c3520c, 0x00be550f, 0x00ab5821, 0x00451a00, 0x00170000, 0x00140000, 0x004f2410, 0x00994b1a, 0x00bb5411, 0x00c6530e, 0x00c7500a, 0x00c3540b, 0x00b65717, 0x0090481d, 0x00491c04, 0x000d0000, 0x000a0000, 0x00250000, 0x008d4d24, 0x00b65114, 0x00c4540f, 0x00b85414, 0x00a25220, 0x00501d01, 0x00250000, 0x003d1000, 0x007c411f, 0x00a55a29, 0x007c3a12, 0x00280a00, 0x003a3030, 0x00b4afaf, 0x00cccacb, 0x00c7c8c8, 0x00c0c4c3, 0x00c0c0c0, 0x00c0c0c0, 0x00c0c0c0, 0x00bfbfbf, 0x00bfbfbf, 0x00bfbfbf, 0x00bfbfbf, 0x00bfbfbf, 0x00c1c1c1, 0x00bebebe, 0x008c8c8c, 0x001e1e1e, 0x00000000, 0x00040404, 0x00000000, 0x00010101, 0x00010101, 0x00000000, 0x00010101, 0x00080808, 0x00000000, 0x00090909, 0x00616161, 0x00b1b1b1, 0x00bfbfbf, 0x00c0c0c0, 0x00bebebe, 0x00bfbfbf, 0x00c7c7c7, 0x00c8c8c8, 0x00c4c4c4, 0x00847c74, 0x001c0300, 0x007a4d28, 0x009e5d2b, 0x00924c19, 0x006d320c, 0x004e1f05, 0x00280700, 0x001b0000, 0x00300a00, 0x006b3819, 0x00a15f35, 0x00b36029, 0x00b85712, 0x00c45b0a, 0x00c96008, 0x00c45f04, 0x00bd6009, 0x00be610a, 0x00c56005, 0x00c85f04, 0x00c86006, 0x00c46106, 0x00c16405, 0x00c16604, 0x00c46505, 0x00c56504, 0x00c46604, 0x00c26801, 0x00c06a00, 0x00c26900, 0x00c46805, 0x00c76705, 0x00ca6b06, 0x00c96601, 0x00cc6300, 0x00c46314, 0x00974c20, 0x00451100, 0x001c0000, 0x00190000, 0x00593115, 0x007d5025, 0x00603004, 0x00370d00, 0x002a0a00, 0x001c0000, 0x002c0400, 0x007c4730, 0x00a25b2e, 0x00aa5c28, 0x00a15825, 0x00914d21, 0x00773c16, 0x00592706, 0x00401400, 0x002e0300, 0x00300000, 0x004b1500, 0x0073350c, 0x0098501e, 0x00ab5920, 0x00b35717, 0x00ba5510, 0x00bc580f, 0x00b85c14, 0x00b45912, 0x00bb5811, 0x00b45b20, 0x008b4b24, 0x003f1703, 0x000d0000, 0x00030000, 0x00060000, 0x00140000, 0x00401500, 0x00844e2c, 0x00935c38, 0x00582d0f, 0x00130000, 0x00150000, 0x005c2b02, 0x00a95f27, 0x00bd5c18, 0x00c7580d, 0x00c85408, 0x00c1550c, 0x00b55c1c, 0x006b2e00, 0x001c0500, 0x00020000, 0x00242223, 0x00838182, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00808080, 0x00040504, 0x00010302, 0x00696b6a, 0x00babcbb, 0x00cacccb, 0x00c4c5c4, 0x00c0c2c1, 0x00babcbb, 0x00b9bbba, 0x00bbbcbc, 0x00bcbdbc, 0x00bdbfbe, 0x00c0c1c0, 0x00c0c1c0, 0x00bdbfbe, 0x00bbbcbc, 0x00bcbebd, 0x00bbbcbc, 0x00bcbebd, 0x00bec0bf, 0x00bcbdbc, 0x00bbbcbc, 0x00bcbebd, 0x00bcbebd, 0x00bcbebd, 0x00bcbebd, 0x00bcbebd, 0x00bcbebd, 0x00bcbebd, 0x00bcbebd, 0x00bcbebd, 0x00bcbebd, 0x00bfbfbd, 0x00bbbcbc, 0x00babdc0, 0x00bcbfc1, 0x00bcbcbc, 0x00bdbcbb, 0x00c3c4c0, 0x00cacbc7, 0x00a7a7a5, 0x004a4948, 0x00060200, 0x001e0500, 0x00692803, 0x00b45a22, 0x00be5211, 0x00c6510c, 0x00c45007, 0x00bd5410, 0x00b05b24, 0x00602803, 0x001c0900, 0x000a0000, 0x002c0800, 0x00743412, 0x00b2581d, 0x00be550d, 0x00c05308, 0x00ba5417, 0x00934220, 0x005c0f00, 0x00ab5018, 0x00bb540d, 0x00c05509, 0x00bc550c, 0x00b4551a, 0x00813813, 0x00300900, 0x00130000, 0x002b0600, 0x00703714, 0x00b05a20, 0x00bc5410, 0x00c0510d, 0x00c5510a, 0x00ca5207, 0x00c85208, 0x00bf540c, 0x00ac581e, 0x00582808, 0x001b0000, 0x00130000, 0x00461c0b, 0x0098491a, 0x00bb5413, 0x00c4500e, 0x00c6500b, 0x00c2540c, 0x00b65618, 0x0091481e, 0x004b1c04, 0x000d0000, 0x000a0000, 0x00240000, 0x0088481f, 0x00b25112, 0x00c5550f, 0x00be5410, 0x00b35a23, 0x006a300f, 0x00310400, 0x002c0100, 0x006b361a, 0x00a55d2d, 0x007c3b10, 0x00230700, 0x00261e1c, 0x008b8887, 0x00c9c9c9, 0x00cbcbcb, 0x00c4c4c4, 0x00bfbfbf, 0x00bebebe, 0x00bebebe, 0x00bdbdbd, 0x00bdbdbd, 0x00bdbdbd, 0x00bdbdbd, 0x00bdbdbd, 0x00bdbdbd, 0x00bcbcbc, 0x00a5a5a5, 0x00585858, 0x00030303, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x002d2d2d, 0x008a8a8a, 0x00bcbcbc, 0x00bdbdbd, 0x00c0c0c0, 0x00bbbbbb, 0x00c3c3c3, 0x00c8c8c8, 0x00c8c8c8, 0x00c6c6c6, 0x00484039, 0x00220600, 0x00683c20, 0x006b340f, 0x00521c00, 0x002e0400, 0x00180000, 0x000d0000, 0x00120200, 0x001b0200, 0x00461f05, 0x007e461f, 0x00a85d26, 0x00c06119, 0x00c45d0c, 0x00c45b04, 0x00c15b03, 0x00be6006, 0x00be6005, 0x00c36003, 0x00c46002, 0x00c46007, 0x00c46007, 0x00c16204, 0x00c16202, 0x00c46404, 0x00c46404, 0x00c46305, 0x00c46404, 0x00c26801, 0x00c46802, 0x00c66805, 0x00c76705, 0x00c46700, 0x00c56702, 0x00c56505, 0x00bf6b21, 0x006f350f, 0x002c0400, 0x00150000, 0x002c0900, 0x00743c13, 0x00a4622c, 0x0094541b, 0x006c3407, 0x00341000, 0x001a0000, 0x003d1705, 0x007a4b33, 0x007f4623, 0x00763b14, 0x00652e0c, 0x00512000, 0x00380b00, 0x00270000, 0x002f0300, 0x00431300, 0x00642e0a, 0x0087461a, 0x00a45720, 0x00b0581a, 0x00b85813, 0x00bc550c, 0x00bc5409, 0x00bf590f, 0x00b75812, 0x00b65811, 0x00be550c, 0x00b75511, 0x00a65928, 0x00663314, 0x00220d03, 0x00040000, 0x00030000, 0x000c0200, 0x001c0400, 0x00542c12, 0x009a6037, 0x00824a23, 0x00280800, 0x00180000, 0x00421300, 0x009d5926, 0x00bd5e1c, 0x00c75810, 0x00c7540b, 0x00c2560e, 0x00ba5f18, 0x00743400, 0x00220a00, 0x00030000, 0x001c1c1c, 0x00727272, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x001f1f1f, 0x00888888, 0x00080a09, 0x00030404, 0x00323433, 0x009d9f9e, 0x00c8c9c8, 0x00c6c8c7, 0x00c0c2c1, 0x00b9bbba, 0x00babcbb, 0x00b9bbba, 0x00b9bbba, 0x00babcbb, 0x00b9bbba, 0x00b7b8b8, 0x00b8b9b8, 0x00bcbdbc, 0x00babcbb, 0x00bbbcbc, 0x00b9bbba, 0x00b8b9b8, 0x00b9bbba, 0x00bcbebd, 0x00bcbebd, 0x00b9bbba, 0x00bbbcbc, 0x00bbbcbc, 0x00bbbcbc, 0x00bbbcbc, 0x00bbbcbc, 0x00bbbcbc, 0x00bbbcbc, 0x00bbbcbc, 0x00bebebc, 0x00b9bbba, 0x00babdc0, 0x00babdc0, 0x00babab8, 0x00c1c0bd, 0x00c7c6c3, 0x00c2c3bf, 0x007f7f7d, 0x00242422, 0x00050000, 0x00250b00, 0x0076340e, 0x00b45820, 0x00bc4f0f, 0x00c7500a, 0x00c65006, 0x00bf5410, 0x00ae5a25, 0x00552000, 0x00180500, 0x000b0000, 0x00330c00, 0x007d3c18, 0x00b0571c, 0x00bf560d, 0x00c05004, 0x00bc5414, 0x009c4824, 0x006b1a00, 0x00ac5015, 0x00ba540b, 0x00be5609, 0x00bd570e, 0x00b3561c, 0x007e3510, 0x00310a00, 0x00130000, 0x00200000, 0x00653215, 0x00aa5824, 0x00ba5614, 0x00bd5412, 0x00c4500c, 0x00cc5004, 0x00cb5004, 0x00bf5309, 0x00ad581d, 0x00693714, 0x00200200, 0x00140000, 0x00411907, 0x00984b1b, 0x00b95413, 0x00c4500e, 0x00c5500c, 0x00c0530c, 0x00b45719, 0x00924820, 0x004b1c04, 0x000c0000, 0x000b0000, 0x00230000, 0x00804218, 0x00b35414, 0x00c25409, 0x00c4550f, 0x00b5571d, 0x00884522, 0x00420f00, 0x00230000, 0x005c2b12, 0x00a0582a, 0x007d3e11, 0x00240a00, 0x00110d08, 0x00525150, 0x00bababa, 0x00ccc8c9, 0x00cbc8c7, 0x00bebcbd, 0x00bdbdbd, 0x00bcbcbc, 0x00bcbcbc, 0x00bcbcbc, 0x00bcbcbc, 0x00bcbcbc, 0x00bcbcbc, 0x00bcbcbc, 0x00bebebe, 0x00b7b7b7, 0x00929292, 0x00393939, 0x000c0c0c, 0x00010101, 0x00000000, 0x00000000, 0x00010101, 0x00020202, 0x00000000, 0x00202020, 0x006c6c6c, 0x00ababab, 0x00bbbbbb, 0x00bbbbbb, 0x00bdbdbd, 0x00bcbcbc, 0x00c4c4c4, 0x00cacaca, 0x00c4c4c4, 0x00a3a3a3, 0x001c1414, 0x00220b08, 0x003c190f, 0x00390e00, 0x003b1000, 0x00280800, 0x00160100, 0x00080000, 0x00040000, 0x000a0400, 0x00110400, 0x00381800, 0x00754318, 0x00aa5c1d, 0x00bc5e11, 0x00c15b0a, 0x00c96009, 0x00c85c00, 0x00c55e00, 0x00c06004, 0x00c06007, 0x00c35f08, 0x00c45e08, 0x00c75d07, 0x00c75d04, 0x00c46004, 0x00c36204, 0x00c36204, 0x00c56205, 0x00c86206, 0x00ca6305, 0x00c96404, 0x00c86502, 0x00c86700, 0x00c46908, 0x00bd6c19, 0x009d6021, 0x00401c00, 0x00180100, 0x00110000, 0x004b220b, 0x00914718, 0x00bb5e20, 0x00b95816, 0x00af5a1d, 0x0074380c, 0x00391000, 0x00311400, 0x00391f10, 0x00311505, 0x00260800, 0x001d0000, 0x001e0000, 0x002c0400, 0x00421200, 0x00642b04, 0x00884418, 0x00a25621, 0x00ac581e, 0x00b05718, 0x00b45512, 0x00bc5812, 0x00c0580d, 0x00bf5406, 0x00bd5307, 0x00ba5511, 0x00bc560f, 0x00c65706, 0x00be5304, 0x00b45b19, 0x008c4c1c, 0x003e1b05, 0x000b0000, 0x00050000, 0x00030000, 0x00090400, 0x00281100, 0x00884d21, 0x00985728, 0x005a2e16, 0x00210000, 0x00310300, 0x00904f22, 0x00b85c1c, 0x00c45810, 0x00c75610, 0x00c1560f, 0x00bb5f16, 0x007b3b02, 0x00280e00, 0x00040000, 0x00141615, 0x00646463, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a4a6, 0x007c7c7c, 0x00444442, 0x000c0503, 0x00070100, 0x00080401, 0x00827f7e, 0x00c1c1c0, 0x00c8c8c6, 0x00c1c1c0, 0x00bebebc, 0x00b9b9bb, 0x00bcbcbd, 0x00bbbcbd, 0x00b8bab9, 0x00b7bbb8, 0x00b9bdba, 0x00b9bebc, 0x00b8bbba, 0x00babcb9, 0x00babcbb, 0x00b9babc, 0x00babbbc, 0x00bcbcbc, 0x00b8b8b8, 0x00b8b8ba, 0x00bcbdbc, 0x00b9bbba, 0x00b9bbb8, 0x00babbb7, 0x00b9bbb7, 0x00b8bbba, 0x00b8bbba, 0x00b9bbba, 0x00babab8, 0x00bcbbb8, 0x00b8b8b6, 0x00b9bcbf, 0x00b8bcbe, 0x00b8b8b6, 0x00c2c1be, 0x00c5c4c1, 0x00b5b4b1, 0x005a5a58, 0x00080402, 0x00050000, 0x002c0f00, 0x00823d14, 0x00b85920, 0x00bf4e0c, 0x00c8500b, 0x00c85109, 0x00be5413, 0x00ac5826, 0x004e1800, 0x00160000, 0x000f0000, 0x003d1200, 0x00884520, 0x00b45719, 0x00c4560d, 0x00c35004, 0x00be5413, 0x00a44e27, 0x00782400, 0x00b25014, 0x00bd540c, 0x00bc5206, 0x00bd5710, 0x00b4561f, 0x007d3410, 0x00340c00, 0x00100000, 0x00160000, 0x005c3015, 0x00a45622, 0x00ba5616, 0x00bf5214, 0x00c34f0c, 0x00c85005, 0x00c85103, 0x00c05207, 0x00b0581b, 0x00784018, 0x00280400, 0x00150000, 0x003e1806, 0x00984c1b, 0x00ba5414, 0x00c2520e, 0x00c7540f, 0x00bf520c, 0x00b45719, 0x00934920, 0x004b1b06, 0x000c0000, 0x000a0000, 0x00220000, 0x007a3d15, 0x00b45718, 0x00bf5106, 0x00c1530a, 0x00b25011, 0x00a2542a, 0x00531700, 0x00240000, 0x00512310, 0x00925026, 0x00783e15, 0x00250f00, 0x00030000, 0x00252423, 0x00a7a7a7, 0x00c6c3c4, 0x00cccacb, 0x00bcbcbe, 0x00bbbcbd, 0x00bcbcbc, 0x00bbbbb9, 0x00bcbbb9, 0x00bcbabb, 0x00bbbbbc, 0x00babbbc, 0x00babbbc, 0x00b9bcbd, 0x00b8b9b8, 0x00b4b6b4, 0x008f8f8d, 0x003b3c3c, 0x001f2024, 0x000c0d10, 0x00080808, 0x00060606, 0x00161616, 0x00303032, 0x0068686a, 0x00a8a9ab, 0x00bcbcbc, 0x00bcbcbc, 0x00bcbcbc, 0x00bbbcbc, 0x00c0c0c2, 0x00c0c0c2, 0x00cccacb, 0x00bcb9b8, 0x00726c6a, 0x000e0000, 0x00280400, 0x00461708, 0x00643018, 0x007c492d, 0x00572c14, 0x002a0900, 0x00120000, 0x00060000, 0x00000000, 0x00020200, 0x00130700, 0x00351700, 0x00713807, 0x00a85a1b, 0x00bd6319, 0x00bc5907, 0x00c65d02, 0x00c45d00, 0x00bf5f05, 0x00bd5f08, 0x00c25d0b, 0x00c65d0a, 0x00ca5c09, 0x00ca5c08, 0x00c55f07, 0x00c46005, 0x00c46005, 0x00c56006, 0x00cb5f08, 0x00cb6005, 0x00ca6202, 0x00c96300, 0x00c86400, 0x00bc6407, 0x00b36c24, 0x00764614, 0x00240e00, 0x000e0100, 0x00110000, 0x00582c0e, 0x00ab5821, 0x00bc540d, 0x00c4550b, 0x00bf5811, 0x00a55518, 0x00763c0d, 0x00300800, 0x00170000, 0x000c0000, 0x00130000, 0x00210400, 0x00370f00, 0x005d2a0c, 0x0085451c, 0x009d511c, 0x00b05b20, 0x00b05515, 0x00b45411, 0x00b85713, 0x00bc5711, 0x00ba540c, 0x00bb5209, 0x00c15405, 0x00c25409, 0x00bc540f, 0x00ba540e, 0x00c25708, 0x00bd5605, 0x00b65810, 0x00a65c24, 0x005a2c0e, 0x00200700, 0x000c0000, 0x00000000, 0x00000000, 0x00201101, 0x00683105, 0x00a45f2e, 0x00865032, 0x00310200, 0x00290000, 0x00854720, 0x00b15718, 0x00c2580f, 0x00c55710, 0x00c0550e, 0x00bc5c14, 0x00823f07, 0x002d1200, 0x00060200, 0x00121110, 0x005d5d5d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00adacb0, 0x007b7f81, 0x00424648, 0x0008080a, 0x00060000, 0x00110000, 0x00190400, 0x00180804, 0x00453a38, 0x00a4a09c, 0x00cccbc7, 0x00cac9c5, 0x00c0c0bc, 0x00bab6bb, 0x00bbb8be, 0x00b8b8bc, 0x00b5b7b6, 0x00b4bab4, 0x00b3bcb4, 0x00b2bcb7, 0x00b5beb9, 0x00b8b9b5, 0x00b8b8b7, 0x00b7b9bd, 0x00b8b9bd, 0x00bbb7ba, 0x00bcb7b8, 0x00b8b7bb, 0x00b7b8b9, 0x00b6b9b8, 0x00b8b9b5, 0x00b9b9b0, 0x00b8bab1, 0x00b5bab7, 0x00b4b9b8, 0x00b8b8b6, 0x00b9b7b3, 0x00bab6b1, 0x00bcb9b5, 0x00b9babc, 0x00b8bbbc, 0x00bbbcbc, 0x00bfbebb, 0x00cac8c4, 0x00868480, 0x00262624, 0x00030000, 0x00080000, 0x00331100, 0x0092491d, 0x00b75215, 0x00c3500a, 0x00c85008, 0x00c5500c, 0x00bb5317, 0x00a85529, 0x004c1100, 0x00180000, 0x00130000, 0x0055220c, 0x0094491e, 0x00bc5414, 0x00c44f03, 0x00c45005, 0x00bc5311, 0x00aa5223, 0x008b3406, 0x00b65011, 0x00c1530c, 0x00c05107, 0x00bf5511, 0x00b65624, 0x00823b19, 0x002d0900, 0x000c0000, 0x000f0000, 0x004c270f, 0x009c4e18, 0x00bb5411, 0x00c45214, 0x00c34d0d, 0x00c4520d, 0x00c2540b, 0x00c05308, 0x00b45717, 0x00904e26, 0x00280000, 0x00150000, 0x003a1605, 0x00944916, 0x00bc5814, 0x00be510c, 0x00c1510c, 0x00bf520c, 0x00b65619, 0x00904721, 0x004c1c0b, 0x000b0000, 0x00070000, 0x00200000, 0x00743912, 0x00b35518, 0x00c05108, 0x00bd5109, 0x00bc5815, 0x00ad5620, 0x00662100, 0x002c0000, 0x004b1d0e, 0x008b4c2c, 0x00743d20, 0x00220d03, 0x00090604, 0x000d0c09, 0x00595a56, 0x00c1c1c1, 0x00c8c8ca, 0x00c0c2c6, 0x00bcc0c2, 0x00b8b9b7, 0x00b9b8b5, 0x00bbb8b4, 0x00b7b4b3, 0x00bfbec2, 0x00b8bac0, 0x00b6bcc0, 0x00b4bcbd, 0x00b3bab6, 0x00b8bcb6, 0x00b8bab6, 0x00a2a5a6, 0x00747682, 0x004c4d58, 0x00414042, 0x00484745, 0x00656668, 0x00929598, 0x00b0b4b7, 0x00b8bbbd, 0x00b8bab9, 0x00babab8, 0x00b8b9b8, 0x00bcbfc0, 0x00b8bcc0, 0x00c7c9cc, 0x00c8c4c8, 0x00a39898, 0x0033201c, 0x00351004, 0x00733418, 0x00a05228, 0x00af5d28, 0x00ab5c25, 0x00a25828, 0x0071340f, 0x00340900, 0x00190000, 0x00060000, 0x00000100, 0x00020200, 0x000b0000, 0x00300d00, 0x006e380c, 0x009f591a, 0x00b36014, 0x00bc600c, 0x00c16109, 0x00bc5e08, 0x00bd5c08, 0x00c45f0b, 0x00c85f0c, 0x00c55b08, 0x00c55b07, 0x00c55c08, 0x00c45e08, 0x00c45e07, 0x00c45e07, 0x00c85e07, 0x00c85f04, 0x00c96002, 0x00ca6202, 0x00ca6200, 0x00c16510, 0x00ab692c, 0x004c2200, 0x00150300, 0x000a0000, 0x00180200, 0x00673b1c, 0x00b56625, 0x00c05b0b, 0x00c85b0c, 0x00bf5406, 0x00bc590e, 0x00ad5918, 0x007c3c0d, 0x00300300, 0x00120000, 0x00240d00, 0x0058280c, 0x008b4820, 0x00a55622, 0x00b3591c, 0x00b2530b, 0x00bb580e, 0x00b6550e, 0x00b5520c, 0x00bd550f, 0x00c25814, 0x00bc5411, 0x00b8520b, 0x00bf5408, 0x00c05408, 0x00bc5610, 0x00b65611, 0x00b35810, 0x00b25a13, 0x00b35b15, 0x00ab5d24, 0x007c4524, 0x00371300, 0x000c0000, 0x00030000, 0x00020100, 0x000f0000, 0x004c1a00, 0x00a05e31, 0x0098582f, 0x00642905, 0x00280000, 0x00743813, 0x00ad5518, 0x00c0580f, 0x00c55911, 0x00c1560f, 0x00ba5814, 0x00883f0b, 0x00341400, 0x00080000, 0x00140c0d, 0x005b575a, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b8b4b0, 0x00918e8f, 0x004c484b, 0x00100d0c, 0x00070000, 0x000f0000, 0x00240700, 0x003e1200, 0x005c2e16, 0x004f2c1d, 0x00281108, 0x007a7068, 0x00bdbbb5, 0x00c7c8c3, 0x00c4c4c2, 0x00b8b7bb, 0x00b8b5bb, 0x00b8b7bb, 0x00b7b8b8, 0x00b3b8b3, 0x00b4bcb5, 0x00b2bcb5, 0x00acb5b0, 0x00b6b8b4, 0x00b6b8b5, 0x00b4b8bc, 0x00b4b7bc, 0x00bab5b8, 0x00bab5b7, 0x00b7b6ba, 0x00b4b8ba, 0x00b2b5b4, 0x00b6b8b3, 0x00bbb9af, 0x00b8b8af, 0x00b1b8b4, 0x00b1b8b8, 0x00b7b8b6, 0x00bcb9b5, 0x00bcb9b2, 0x00b8b6b2, 0x00b7babb, 0x00b3b7b9, 0x00babbbc, 0x00ccccca, 0x00b3aca8, 0x00514a44, 0x000f0b08, 0x00080000, 0x00100000, 0x003f1800, 0x009f5222, 0x00ba5415, 0x00c6530d, 0x00c44d05, 0x00c25110, 0x00b6531b, 0x00a1542b, 0x00450e00, 0x00170000, 0x001a0000, 0x00622a0d, 0x00a05020, 0x00c25713, 0x00c85205, 0x00c75107, 0x00be510e, 0x00ad521a, 0x00943a04, 0x00b54c0b, 0x00c05006, 0x00c45104, 0x00c0520c, 0x00b5521f, 0x008d4320, 0x00361100, 0x00100000, 0x000d0000, 0x003c1c05, 0x00904512, 0x00bc5414, 0x00c45012, 0x00c44e10, 0x00c05310, 0x00bf540c, 0x00c05105, 0x00b75513, 0x00995127, 0x002f0100, 0x00170000, 0x00391504, 0x00944914, 0x00b95811, 0x00bd520c, 0x00c1530c, 0x00be520a, 0x00b65417, 0x00914520, 0x004b1a0b, 0x000a0000, 0x00060000, 0x001e0000, 0x00733814, 0x00b1541a, 0x00bf520c, 0x00bc5209, 0x00bc5713, 0x00b2571c, 0x00702500, 0x00300000, 0x00471a0c, 0x0086492e, 0x00774228, 0x00250f06, 0x00050000, 0x00080000, 0x00201912, 0x0094908d, 0x00c8c8c8, 0x00cbcccc, 0x00b8bbbd, 0x00c0c1bf, 0x00b0b0ac, 0x00bebcb8, 0x00bdbcbb, 0x00b4b4b8, 0x00b3b6bd, 0x00b2b9bf, 0x00b2babc, 0x00b4b8b5, 0x00b5bab2, 0x00b9bab5, 0x00b9bbba, 0x00b7b8c3, 0x00b5b7c1, 0x00c0bebf, 0x00bab9b6, 0x00b4b7b8, 0x00b5b9bc, 0x00b4bbbd, 0x00b4b8ba, 0x00b4b6b5, 0x00b5b7b4, 0x00b8bcb8, 0x00afb4b4, 0x00c6cccc, 0x00c4c5c7, 0x00b0a8a6, 0x006c5853, 0x00240300, 0x007b462c, 0x00a9582c, 0x00b65418, 0x00bc5812, 0x00bd5911, 0x00ba5918, 0x00ac5823, 0x007e3c18, 0x00411500, 0x00160100, 0x00080000, 0x00000000, 0x00080100, 0x00100000, 0x00290700, 0x00663509, 0x009b591e, 0x00b15e17, 0x00ba5c10, 0x00bf5f11, 0x00bf5d0c, 0x00bc5605, 0x00c05908, 0x00c75e0b, 0x00c45c08, 0x00c75e09, 0x00c6600a, 0x00c7600b, 0x00c76009, 0x00c66008, 0x00c56005, 0x00c65e03, 0x00c65f01, 0x00c76002, 0x00bc6415, 0x00915624, 0x00371500, 0x000c0000, 0x000b0000, 0x00200900, 0x0070401d, 0x00b96923, 0x00c35f08, 0x00c85d0b, 0x00c25504, 0x00c45804, 0x00bd5a0d, 0x00a35015, 0x0074340c, 0x00290400, 0x004a2614, 0x008c5031, 0x00a45728, 0x00b25418, 0x00b9530d, 0x00bd5508, 0x00b85001, 0x00ba540a, 0x00c15c17, 0x00b7520f, 0x00aa480b, 0x00af541e, 0x00b25b24, 0x00ae5417, 0x00ab5116, 0x00a14f19, 0x009c501c, 0x00975019, 0x00964c14, 0x009b490d, 0x00a3551e, 0x008e4e27, 0x00582a13, 0x00140000, 0x00080000, 0x00040000, 0x000a0000, 0x00320c00, 0x00824820, 0x00a45d30, 0x00934d22, 0x003c0300, 0x00682903, 0x00aa5214, 0x00bd560c, 0x00c4580f, 0x00c25710, 0x00bc5817, 0x00893e0c, 0x00371400, 0x000a0000, 0x00140b0c, 0x00585458, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a8aca6, 0x005f605c, 0x001c1c1c, 0x00050000, 0x00140000, 0x00280400, 0x00441000, 0x00732f03, 0x00a85722, 0x00aa5c29, 0x008d542d, 0x00442005, 0x00362518, 0x008d8984, 0x00c6c8c5, 0x00c4c8c8, 0x00c5c6c8, 0x00babbbc, 0x00afafb0, 0x00b1b1b3, 0x00b8b9bb, 0x00b4b5b4, 0x00b0b1af, 0x00b8b9b7, 0x00b4b5b1, 0x00b2b5b4, 0x00b0b6b8, 0x00b0b4b8, 0x00b4b3b4, 0x00b7b4b3, 0x00b4b4b6, 0x00b3b6b8, 0x00b1b4b4, 0x00b4b5b1, 0x00b8b5ae, 0x00b6b6b0, 0x00afb6b5, 0x00aeb6b8, 0x00b2b5b6, 0x00b4b4b3, 0x00b3b4af, 0x00afb0ac, 0x00b0b6b8, 0x00b9bfc4, 0x00c7c9cc, 0x00bdbabb, 0x00746760, 0x00312017, 0x001c0f09, 0x001c0a01, 0x001c0000, 0x004e1e00, 0x00a85827, 0x00b65212, 0x00c4550f, 0x00c1500a, 0x00be530f, 0x00b0551c, 0x0095532b, 0x003a0c00, 0x00140000, 0x00250700, 0x00703410, 0x00aa5620, 0x00b85009, 0x00c44e01, 0x00c55003, 0x00c2530a, 0x00ba5518, 0x00ab480b, 0x00b84d08, 0x00c35004, 0x00c44e00, 0x00c35003, 0x00b95017, 0x009b4b23, 0x00380f00, 0x000e0000, 0x000a0000, 0x002e1100, 0x007f3a0b, 0x00b8571b, 0x00c04e11, 0x00c55010, 0x00c0510d, 0x00c1530a, 0x00c35004, 0x00ba5310, 0x00a0572b, 0x00380800, 0x00180000, 0x00391402, 0x00924812, 0x00b85710, 0x00be530d, 0x00c1530c, 0x00bf5009, 0x00b65417, 0x00914520, 0x00491808, 0x000b0000, 0x00050000, 0x001c0000, 0x00703915, 0x00ad541b, 0x00bd540e, 0x00bd500a, 0x00bc5412, 0x00b65820, 0x00762c04, 0x00320400, 0x0043180a, 0x00824627, 0x00784023, 0x00290e04, 0x00110200, 0x00271005, 0x002c1709, 0x0041342c, 0x00b5aeaa, 0x00cac7c8, 0x00c3c1c4, 0x00babab8, 0x00bcbcba, 0x00b0b2b0, 0x00b1b4b4, 0x00b3b7b9, 0x00b2b6bb, 0x00afb3b8, 0x00b0b4b6, 0x00b5b5b4, 0x00b7b7b0, 0x00b6b4ae, 0x00b4b2ae, 0x00b6b4b7, 0x00bababc, 0x00b3b4b0, 0x00b5b7b3, 0x00b1b4b4, 0x00aeb3b3, 0x00b0b5b4, 0x00b3b8b6, 0x00b4b8b4, 0x00b5b9b4, 0x00b3bab6, 0x00bbc2be, 0x00c7ccca, 0x00bebab5, 0x00907e73, 0x002d0d00, 0x00542407, 0x009b582f, 0x00b55b23, 0x00bb5310, 0x00c55a0c, 0x00c55708, 0x00bc4e03, 0x00bf5918, 0x00b15b29, 0x0083411c, 0x004c2108, 0x001d0400, 0x000b0000, 0x00080000, 0x000a0000, 0x000e0000, 0x00200300, 0x005a2b0b, 0x00a2541e, 0x00b05313, 0x00bb5b16, 0x00c05f16, 0x00c05b0f, 0x00c45d0c, 0x00c45f0b, 0x00be5803, 0x00c05c04, 0x00c05c04, 0x00bf5b03, 0x00c05c04, 0x00c15c04, 0x00c45f06, 0x00c66008, 0x00c56109, 0x00c0610b, 0x00b66820, 0x00703f14, 0x00240800, 0x00080000, 0x000c0000, 0x002b0e00, 0x0078441c, 0x00bd6b20, 0x00c86409, 0x00ca6009, 0x00c55903, 0x00c55903, 0x00be5706, 0x00b95816, 0x00ac5826, 0x005f2304, 0x00330000, 0x006b3414, 0x009c572c, 0x00b1541a, 0x00bb5210, 0x00ba520f, 0x00bc540f, 0x00b9510b, 0x00b04e0a, 0x00b0561c, 0x00a95a2c, 0x00955435, 0x008c5037, 0x00844828, 0x006c3518, 0x00572a14, 0x00431a04, 0x004a1800, 0x00551a00, 0x00611900, 0x008a3d0c, 0x009d552b, 0x00703718, 0x002d0a00, 0x000e0000, 0x00000004, 0x00040000, 0x001c0600, 0x00623415, 0x00a85c31, 0x00ac5c2c, 0x00662400, 0x006c2800, 0x00ad5313, 0x00bd540c, 0x00c4580b, 0x00c2580d, 0x00bc5815, 0x008a3f0d, 0x00361400, 0x00080000, 0x00140c0d, 0x00545357, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000c0d0c, 0x00888a84, 0x00343630, 0x00100e08, 0x000d0200, 0x00180000, 0x00390d00, 0x006d2f0a, 0x00a45420, 0x00bb5f1f, 0x00b8500a, 0x00c05f1b, 0x00ac5e25, 0x007e471b, 0x00341300, 0x00514236, 0x009b9794, 0x00c6c7c8, 0x00bfc2c3, 0x00c0c3c2, 0x00bababc, 0x00b2b0b3, 0x00b2b0b4, 0x00b5b1b6, 0x00b5b1b6, 0x00b5b4b4, 0x00b2b2b0, 0x00b0b3b2, 0x00acb4b6, 0x00aeb4b7, 0x00b2b4b3, 0x00b3b3b1, 0x00b2b3b4, 0x00b0b4b4, 0x00b1b4b5, 0x00b1b3b0, 0x00b4b1ad, 0x00b3b2af, 0x00afb5b8, 0x00afb6ba, 0x00afb3b8, 0x00aeb1b4, 0x00b4b8b5, 0x00b3b8b4, 0x00b2b8bb, 0x00bcc2c7, 0x00c2c2c8, 0x00898182, 0x0041281d, 0x003d2011, 0x00442c24, 0x00290e04, 0x00240000, 0x00602806, 0x00af5c27, 0x00b4500e, 0x00c0530c, 0x00c2530a, 0x00be540b, 0x00b15718, 0x008f5029, 0x00350c00, 0x00150000, 0x00361300, 0x007e3e14, 0x00ae581d, 0x00bd5711, 0x00c4540a, 0x00c45104, 0x00be4d04, 0x00ba500e, 0x00b54e0c, 0x00b64b04, 0x00c15208, 0x00c65304, 0x00c25308, 0x00b75118, 0x00a4562d, 0x00441900, 0x00130000, 0x000c0000, 0x001f0500, 0x006d3006, 0x00b35820, 0x00bc4e12, 0x00c65010, 0x00c0500b, 0x00c15208, 0x00c45104, 0x00bc5410, 0x00a5592c, 0x00410d00, 0x00190000, 0x003b1403, 0x00934712, 0x00b85510, 0x00bf5410, 0x00c1530c, 0x00c05108, 0x00b85517, 0x0090441e, 0x00461504, 0x000c0000, 0x00050000, 0x001a0000, 0x006c3815, 0x00aa541c, 0x00be5613, 0x00be510c, 0x00bc5213, 0x00b65821, 0x007a3009, 0x00340800, 0x00411b09, 0x00854928, 0x00793f1e, 0x002e0c00, 0x00200600, 0x004d2815, 0x0064402b, 0x00180100, 0x005c4e46, 0x00c6bebd, 0x00c8c4c8, 0x00c7c5c6, 0x00b1b3b2, 0x00b8bbba, 0x00adb2b2, 0x00acb3b4, 0x00aeb2b4, 0x00b2b5b8, 0x00b3b3b4, 0x00b5b2b1, 0x00b7b3b0, 0x00b7b3b0, 0x00b4b1ad, 0x00b0b0ac, 0x00b0b0ae, 0x00b0b2b0, 0x00b2b7b5, 0x00b2b7b7, 0x00b0b4b4, 0x00b1b4b4, 0x00b0b4b1, 0x00afb3ae, 0x00b0b4b0, 0x00b8bdba, 0x00c6cac7, 0x00c1c0bc, 0x0094897f, 0x00351804, 0x00401200, 0x00945428, 0x00b05d28, 0x00b75615, 0x00bc540b, 0x00c15403, 0x00c45402, 0x00c35304, 0x00c1550d, 0x00bc591c, 0x00b05c28, 0x00905025, 0x00603113, 0x00200300, 0x00120000, 0x00130206, 0x000a0000, 0x000d0000, 0x001a0000, 0x004e1300, 0x0093481c, 0x00b0602e, 0x00aa571c, 0x00b45a18, 0x00bb5d13, 0x00bc5808, 0x00c46009, 0x00c25d04, 0x00c25d03, 0x00c35e04, 0x00c46007, 0x00c56109, 0x00c5610b, 0x00c35f08, 0x00bd5f0a, 0x00bc6210, 0x00b06928, 0x00542a08, 0x00190400, 0x00060000, 0x000c0000, 0x00381400, 0x00844a1c, 0x00bc6718, 0x00c86508, 0x00c86307, 0x00c75f05, 0x00c45c05, 0x00bd5604, 0x00bf540c, 0x00bc5a1c, 0x00a75429, 0x00541000, 0x00430900, 0x007c3e19, 0x00a7501c, 0x00b9581c, 0x00b55419, 0x00b25118, 0x00b4551a, 0x00ac5620, 0x00974f24, 0x00784122, 0x00532a1b, 0x002f0d04, 0x001e0000, 0x00180000, 0x00160000, 0x00160000, 0x00240000, 0x00470b00, 0x007a3202, 0x00a2531d, 0x00a85925, 0x008a4721, 0x004b1f0f, 0x00130000, 0x00030003, 0x00030102, 0x00120400, 0x00452005, 0x00a1582e, 0x00ac5725, 0x00944c1e, 0x008a3e0b, 0x00b65717, 0x00c1570c, 0x00c45808, 0x00c25709, 0x00bc5814, 0x008a3f0d, 0x00321100, 0x00080000, 0x00150e10, 0x0057565b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b5b2b0, 0x0060605c, 0x001c1914, 0x00090200, 0x000d0000, 0x00280300, 0x005e2708, 0x009f5425, 0x00b55d21, 0x00b95914, 0x00c0590e, 0x00ca5d0e, 0x00bc5304, 0x00c06218, 0x00b6682b, 0x006e3409, 0x00310a00, 0x00604a43, 0x00b1a9a8, 0x00cccccc, 0x00c3c6c7, 0x00bfbdbe, 0x00b8b4b7, 0x00b4acb5, 0x00b7aeb9, 0x00b8b1bc, 0x00b0aeb5, 0x00b0b0b2, 0x00afb2b3, 0x00acb4b5, 0x00acb4b6, 0x00b0b3b2, 0x00b0b2b0, 0x00afb2b1, 0x00afb2b3, 0x00aeb1b2, 0x00b0b0b2, 0x00b3b0af, 0x00b2b0b3, 0x00adb3b9, 0x00acb4bb, 0x00acb2ba, 0x00acb2b7, 0x00a7afb0, 0x00b0b8b8, 0x00c1c8c9, 0x00c2c3c6, 0x00949094, 0x003f2e2a, 0x00380f00, 0x00734632, 0x0059382c, 0x00240100, 0x00310200, 0x0075340f, 0x00b25c24, 0x00b75310, 0x00be520a, 0x00c15105, 0x00c45204, 0x00b65611, 0x008c4c20, 0x00340a00, 0x00190000, 0x00492107, 0x008d4818, 0x00b0581b, 0x00b55411, 0x00bc540d, 0x00c2530a, 0x00c05008, 0x00bf520d, 0x00bf5410, 0x00b74d09, 0x00bc540d, 0x00b8510a, 0x00b65513, 0x00b05724, 0x00a15c37, 0x00441f08, 0x00120000, 0x00080000, 0x00140000, 0x005d2703, 0x00a85523, 0x00bb5015, 0x00c65211, 0x00c05009, 0x00c25206, 0x00c55205, 0x00bc5411, 0x00a75a2a, 0x004a1400, 0x001c0000, 0x00401604, 0x00944815, 0x00b85411, 0x00bf5410, 0x00c1510c, 0x00c2530a, 0x00b85616, 0x0090441c, 0x00401200, 0x000c0000, 0x00040000, 0x00190000, 0x006b3818, 0x00a85520, 0x00be5714, 0x00c0510f, 0x00bd5012, 0x00b55621, 0x0078300a, 0x00330b00, 0x00431e0b, 0x00894c25, 0x007e411a, 0x00330c00, 0x00280300, 0x006c3519, 0x008c5435, 0x0058331c, 0x00160000, 0x0058504e, 0x00bebcc0, 0x00c9c8cc, 0x00c1c2c5, 0x00b0b4b7, 0x00acb4b3, 0x00b0b8b7, 0x00b0b4b4, 0x00aeaeae, 0x00b2afb0, 0x00b3aeb1, 0x00b1acae, 0x00b0acad, 0x00b0b0ae, 0x00b2b4b0, 0x00b1b6b3, 0x00aab0b3, 0x00a9b0b4, 0x00aab0b4, 0x00adb1b4, 0x00afb0b3, 0x00afb0b1, 0x00b6b8b7, 0x00c0c1c0, 0x00c9cccc, 0x00c4c3c0, 0x00968e87, 0x003c2416, 0x00401400, 0x00814016, 0x00ac5720, 0x00b85515, 0x00bd570e, 0x00bf580b, 0x00bb5404, 0x00bc5704, 0x00c35b0c, 0x00bd5508, 0x00b85209, 0x00bc5c18, 0x00af5a1c, 0x009f5b25, 0x007b4823, 0x00381200, 0x00130000, 0x000f0000, 0x000a0000, 0x000d0000, 0x00170000, 0x00240000, 0x00592c14, 0x00925936, 0x00a25e2b, 0x00ad5c1c, 0x00bc6016, 0x00be5a05, 0x00c75f05, 0x00c55c00, 0x00c35a00, 0x00c15900, 0x00c05c03, 0x00c05e09, 0x00c0600c, 0x00be6110, 0x00b56214, 0x00a66429, 0x003f1a00, 0x00140200, 0x00050000, 0x000c0000, 0x004a1d00, 0x0097541e, 0x00bb6411, 0x00c46403, 0x00c56205, 0x00c46007, 0x00c05f0b, 0x00c15c0c, 0x00c55508, 0x00c3520c, 0x00be591c, 0x009c481a, 0x003f0200, 0x004f1700, 0x0091481b, 0x00a4531e, 0x00a95824, 0x00a55628, 0x00994d27, 0x00783819, 0x00441700, 0x001e0000, 0x000d0000, 0x00090000, 0x000f0000, 0x00150000, 0x00100000, 0x00240300, 0x005e2502, 0x009a501f, 0x00b05c22, 0x00b1591a, 0x00b25c1e, 0x00a45928, 0x00612f14, 0x001d0000, 0x00080000, 0x00070000, 0x000a0000, 0x002d0d00, 0x00975528, 0x00ad5b25, 0x00ae5d27, 0x00ac551c, 0x00ba5614, 0x00c4580e, 0x00c55706, 0x00c25708, 0x00bc5814, 0x00883c0c, 0x002f1000, 0x00070000, 0x00141011, 0x005c5d61, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a8a3a4, 0x004a4240, 0x00100601, 0x000d0000, 0x00170000, 0x00441c04, 0x00894a28, 0x00af5c2d, 0x00b85718, 0x00bd560b, 0x00c45e08, 0x00bd5800, 0x00ca5f06, 0x00cb6108, 0x00c56109, 0x00c36b1d, 0x00b26930, 0x00693410, 0x002c0e00, 0x00544844, 0x00a9a8a5, 0x00c8cbca, 0x00ccccca, 0x00c1bebf, 0x00bfb9c0, 0x00b4aeb7, 0x00a8a6af, 0x00b1b0b7, 0x00b0afb3, 0x00adb0b1, 0x00abb1b4, 0x00aab2b3, 0x00acb1ae, 0x00adb1ae, 0x00acb0af, 0x00acb0b0, 0x00acadb0, 0x00b0afb3, 0x00b4b0b3, 0x00b0aeb4, 0x00a9acb5, 0x00a6acb5, 0x00a9b0b8, 0x00adb4b8, 0x00b7bfc0, 0x00b9c0c0, 0x00cccccc, 0x009c9694, 0x00382b2b, 0x002a0d04, 0x00753e24, 0x00905539, 0x005a3122, 0x001f0000, 0x00420d00, 0x00844017, 0x00af561d, 0x00b95410, 0x00c2540b, 0x00c35004, 0x00c55204, 0x00b65412, 0x0086461d, 0x00330800, 0x001d0000, 0x005c2f11, 0x009c5220, 0x00b0571a, 0x00b4581a, 0x00b75617, 0x00ba5312, 0x00b85110, 0x00b75215, 0x00b6551b, 0x00ae541d, 0x00ac5823, 0x00ae5f28, 0x00a65c2a, 0x0098542c, 0x00854f33, 0x003c200e, 0x00100500, 0x00080100, 0x000f0000, 0x004d1d00, 0x00994d1f, 0x00ba5118, 0x00c65210, 0x00c05008, 0x00c15208, 0x00c45207, 0x00bc5412, 0x00a95929, 0x00521800, 0x00200000, 0x00461907, 0x00984a18, 0x00b85410, 0x00c05310, 0x00c0500b, 0x00c25308, 0x00b85616, 0x008c431a, 0x003c0f00, 0x000c0000, 0x00040000, 0x001a0100, 0x006b391a, 0x00a85520, 0x00bd5614, 0x00c1500f, 0x00be5113, 0x00b45522, 0x00742d07, 0x00300900, 0x0044210d, 0x00884a20, 0x0084441b, 0x00380d00, 0x00330500, 0x0085401c, 0x009f572f, 0x00936043, 0x00240600, 0x000f0300, 0x00575356, 0x00b4b0b3, 0x00cac7c8, 0x00c8c8c8, 0x00b9bcbd, 0x00a7aead, 0x00a6adac, 0x00acacae, 0x00b0afb1, 0x00b4b0b5, 0x00b3afb4, 0x00b0afb4, 0x00adb0b1, 0x00abb0ac, 0x00a6ada9, 0x00aeb4b7, 0x00abaeb5, 0x00acaeb4, 0x00afb0b4, 0x00b0afb3, 0x00b8b4b8, 0x00c2c0c3, 0x00c8c7c8, 0x00bebcbd, 0x008a8481, 0x0031231b, 0x002c0d00, 0x00764222, 0x00a55c2f, 0x00ae5016, 0x00c05814, 0x00ba530a, 0x00bc5409, 0x00be5909, 0x00be5808, 0x00bb5407, 0x00bc5407, 0x00bf5408, 0x00bc550c, 0x00ba5910, 0x00b65f1c, 0x00a25820, 0x008e5128, 0x005e3115, 0x00260400, 0x00140000, 0x00120000, 0x000c0000, 0x00100000, 0x00160000, 0x00320a00, 0x0064300e, 0x008e4f21, 0x00a55b23, 0x00b4601f, 0x00b45b14, 0x00ba5c10, 0x00bd5f10, 0x00be5e10, 0x00bc5e10, 0x00bc5d10, 0x00bc5d10, 0x00b95f14, 0x00b7631a, 0x009e5e27, 0x00320f00, 0x000f0000, 0x00050000, 0x00100000, 0x005e2b06, 0x00a65c1e, 0x00bd640f, 0x00c36404, 0x00c06205, 0x00b95d08, 0x00ab5408, 0x00ba5c12, 0x00cb5b0d, 0x00c75004, 0x00c0500a, 0x00ba5c22, 0x00702f08, 0x003c0500, 0x006c310a, 0x0094562c, 0x0090512b, 0x007c4222, 0x00481602, 0x00240000, 0x00100000, 0x000c0000, 0x00040000, 0x00050000, 0x00100000, 0x00140000, 0x00320c00, 0x007a4628, 0x00a35b2b, 0x00a95317, 0x00b45714, 0x00b75712, 0x00b45310, 0x00ab551d, 0x00793e1a, 0x00340f00, 0x00100000, 0x00080000, 0x00080000, 0x00200500, 0x0080441a, 0x00ab5a24, 0x00ae581c, 0x00ba5b1b, 0x00ba520f, 0x00c4550c, 0x00c65805, 0x00c15807, 0x00bc5a18, 0x007f3608, 0x002a0c00, 0x00050000, 0x00141414, 0x0064666a, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008c8c88, 0x00342e2c, 0x000f0000, 0x00180000, 0x002e0500, 0x00632c0d, 0x00924d20, 0x00b2571f, 0x00bc5313, 0x00c15209, 0x00c85a07, 0x00c46201, 0x00c46800, 0x00c66500, 0x00cc6e06, 0x00c86804, 0x00bc640b, 0x00b06421, 0x00a1683c, 0x004c2c15, 0x001a0c02, 0x003e3e38, 0x00919791, 0x00c6cac4, 0x00c5c8c2, 0x00c3c3c1, 0x00babcbb, 0x00aab1b0, 0x00acb0b3, 0x00aeafb2, 0x00adaeb1, 0x00aaaeb0, 0x00a8afae, 0x00a9aeab, 0x00a9aeab, 0x00a9aeac, 0x00abaeaf, 0x00acacb0, 0x00adacb1, 0x00b0acb2, 0x00aeacb3, 0x00aaacb4, 0x00abb0b7, 0x00b1b7bc, 0x00b6bcbf, 0x00c7cccc, 0x00c8c8c6, 0x008c837e, 0x00302019, 0x00170000, 0x005a301f, 0x0098542e, 0x009a552e, 0x00582c19, 0x001f0000, 0x004b1600, 0x008e481e, 0x00ae551c, 0x00b9520f, 0x00c55308, 0x00c65004, 0x00c25109, 0x00b2541a, 0x0080421f, 0x00310600, 0x00230000, 0x006c3b1d, 0x00a45824, 0x00ac5217, 0x00b05720, 0x00ae5723, 0x00b35926, 0x00b05b2b, 0x00a4572c, 0x008f4925, 0x00783c1f, 0x00623015, 0x004a1d01, 0x003a1000, 0x002b0100, 0x00260400, 0x00130400, 0x00070300, 0x00020001, 0x000a0000, 0x003e1500, 0x00874018, 0x00b85219, 0x00c3510e, 0x00bf5008, 0x00c05209, 0x00c2520c, 0x00b95416, 0x00ac592a, 0x00591d00, 0x00260000, 0x004c1c08, 0x009c4c1a, 0x00b85412, 0x00c05410, 0x00c0500b, 0x00c05107, 0x00b65514, 0x00874018, 0x00350a00, 0x000b0000, 0x00050000, 0x00190200, 0x006c3b1c, 0x00ac5521, 0x00bc5311, 0x00c04f0c, 0x00bf5214, 0x00b25622, 0x006f2c06, 0x002d0700, 0x0046210c, 0x008c4c21, 0x00844217, 0x003d1000, 0x00410e00, 0x0097461b, 0x00a95424, 0x00915230, 0x003e1600, 0x000e0000, 0x000d0504, 0x003c2e2c, 0x009e908c, 0x00c5bcbb, 0x00ccc9c8, 0x00bdc4c5, 0x00b4bcbe, 0x00aab1b5, 0x00a8acb3, 0x00a8a8b1, 0x00a8a8b1, 0x00a9abb4, 0x00a8aeb3, 0x00a8b0ad, 0x00a8afab, 0x00aaacab, 0x00a8a7a9, 0x00b0acad, 0x00b8b3b4, 0x00c1b9ba, 0x00ccc7c8, 0x00cac3c4, 0x00b3acac, 0x006c6465, 0x00211614, 0x00321f17, 0x00674634, 0x00956143, 0x009e582e, 0x00b25825, 0x00b55217, 0x00bb5413, 0x00bc520e, 0x00c0540a, 0x00c05308, 0x00c05308, 0x00c55910, 0x00c55a13, 0x00bb520a, 0x00bc550c, 0x00b9550d, 0x00bb5b16, 0x00af5719, 0x00a15623, 0x008d5024, 0x005b2908, 0x002c0700, 0x00140000, 0x00170000, 0x00170000, 0x00170000, 0x001e0000, 0x002c0300, 0x00471700, 0x00633014, 0x00834929, 0x0092542d, 0x00a45f34, 0x00af6432, 0x00b36029, 0x00b45c1f, 0x00b95d1b, 0x00bc601c, 0x00b8601b, 0x00995520, 0x002b0900, 0x000c0000, 0x00060000, 0x001c0300, 0x00743a0e, 0x00af5f1a, 0x00bd640d, 0x00c06306, 0x00bd640c, 0x00ac580b, 0x008a4100, 0x00a15010, 0x00c55d12, 0x00c85404, 0x00c55306, 0x00be5915, 0x00a75b24, 0x004d1400, 0x00380a00, 0x005c341a, 0x0049240d, 0x00200200, 0x000c0000, 0x00080000, 0x00050100, 0x00080200, 0x000b0000, 0x00100000, 0x00270500, 0x005b280b, 0x009b542e, 0x00a65120, 0x00ab4e10, 0x00b5540f, 0x00ba540e, 0x00b84e0a, 0x00bf500d, 0x00b75418, 0x00954c20, 0x0054250a, 0x00120000, 0x00070000, 0x00050000, 0x00180200, 0x005e2705, 0x00a65721, 0x00af5312, 0x00bc550e, 0x00be510c, 0x00c4540a, 0x00c65804, 0x00be5705, 0x00bb5c1a, 0x00742f04, 0x00230600, 0x00040000, 0x00191c1d, 0x00707678, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007e8078, 0x002f2c23, 0x00110100, 0x00190000, 0x00441200, 0x007c3a1c, 0x00a45726, 0x00b65c1d, 0x00be550f, 0x00c9570a, 0x00cc5805, 0x00cc6005, 0x00c66700, 0x00c56c00, 0x00c56800, 0x00c56a00, 0x00be690b, 0x00b96c1e, 0x00a96930, 0x006c3b15, 0x00301300, 0x000f0000, 0x00120c03, 0x002c2b21, 0x007a7b70, 0x00bcbeb4, 0x00c5c8bf, 0x00c4c8c3, 0x00c2cbc8, 0x00b3bab9, 0x00afaeb2, 0x00aeacb0, 0x00abacad, 0x00a8abaa, 0x00a7aba8, 0x00a7aca8, 0x00a8acab, 0x00aaadae, 0x00acacb0, 0x00a9a8ad, 0x00a8a6ad, 0x00acaab0, 0x00b4b4b8, 0x00bebec0, 0x00c4c6c5, 0x00c9c8c5, 0x00b8b3ae, 0x00695c55, 0x002d180e, 0x001f0400, 0x00200000, 0x0068351b, 0x009d5020, 0x00a05425, 0x00542711, 0x001e0000, 0x004d1700, 0x00974f24, 0x00b45a22, 0x00b84f0c, 0x00c44e04, 0x00c54e03, 0x00c0500c, 0x00af531d, 0x007d4122, 0x00310900, 0x00240200, 0x006e432e, 0x009c5b34, 0x009a5022, 0x0087421b, 0x0074320c, 0x00612000, 0x004f1300, 0x003f0b00, 0x002c0300, 0x00260700, 0x00160000, 0x00140300, 0x00100000, 0x00100000, 0x000b0000, 0x00050000, 0x00000000, 0x00000001, 0x000d0100, 0x00341000, 0x00783a15, 0x00b4541c, 0x00c1510d, 0x00bd5109, 0x00be5208, 0x00c0510d, 0x00b85115, 0x00ad5b2c, 0x00602000, 0x002b0000, 0x00511e08, 0x009e4c19, 0x00b85312, 0x00c25310, 0x00c0500b, 0x00bf5008, 0x00b25415, 0x0083401a, 0x00300800, 0x00080000, 0x00050000, 0x001c0300, 0x00703c1c, 0x00af5520, 0x00c05010, 0x00bf4d08, 0x00be5413, 0x00b15823, 0x006c2b04, 0x002b0400, 0x0045200c, 0x008d4d23, 0x00813d12, 0x00431200, 0x004a1300, 0x00a54d1b, 0x00b45720, 0x009e5530, 0x00451400, 0x00160000, 0x00372820, 0x002b1107, 0x0034180c, 0x006e564e, 0x00ac9d98, 0x00c8c7c5, 0x00c0c6c8, 0x00bdc4c8, 0x00b7bcc3, 0x00b4b5bf, 0x00b1b3bc, 0x00acb0b8, 0x00a6acb0, 0x00a7afae, 0x00afb4b0, 0x00b5b5b4, 0x00bab7b4, 0x00c6c2c0, 0x00ccc7c5, 0x00cac3c4, 0x00bfb8b8, 0x00878284, 0x003c393a, 0x00131010, 0x000c0402, 0x00261810, 0x00432819, 0x00512811, 0x00652f10, 0x0075330b, 0x00904216, 0x00a45022, 0x00b35825, 0x00b5571d, 0x00b55314, 0x00bb5411, 0x00bc520e, 0x00bc510c, 0x00c1550d, 0x00c05308, 0x00c15206, 0x00c35408, 0x00c0570e, 0x00b55614, 0x00ab581d, 0x00a15928, 0x008e542b, 0x00744525, 0x00562e12, 0x003e1600, 0x00300700, 0x00260000, 0x00250000, 0x002a0000, 0x002d0000, 0x00320100, 0x003f0800, 0x004c0e00, 0x00551000, 0x00621500, 0x007b2800, 0x009e4404, 0x00b65a18, 0x00b45a18, 0x00934c1a, 0x00270700, 0x000b0000, 0x000a0000, 0x00290d00, 0x00884814, 0x00b56118, 0x00bc600a, 0x00bd6008, 0x00bd6614, 0x00a55711, 0x00713400, 0x008a470f, 0x00bd5e16, 0x00c65807, 0x00c85606, 0x00c0580b, 0x00b45d1b, 0x00884713, 0x003b0f00, 0x001d0000, 0x00170000, 0x000d0100, 0x00010206, 0x00000004, 0x00030000, 0x000a0000, 0x00160000, 0x00391400, 0x00703c14, 0x009b5422, 0x00a94d18, 0x00bb5418, 0x00bc5411, 0x00ba530a, 0x00bc500b, 0x00bf500d, 0x00c45010, 0x00b94f13, 0x00a75423, 0x006f3816, 0x00140000, 0x00030000, 0x00000005, 0x000d0000, 0x00441200, 0x00a95e2c, 0x00b65714, 0x00bb5006, 0x00c5550f, 0x00c45408, 0x00c65804, 0x00bb5404, 0x00b75c1e, 0x006c2a02, 0x001a0000, 0x00030000, 0x00202424, 0x007d8486, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00787a73, 0x00282824, 0x000e0000, 0x00200000, 0x00511900, 0x008d4116, 0x00b2581f, 0x00bb5b16, 0x00bd560b, 0x00c35808, 0x00cc5f0a, 0x00cc6407, 0x00cc6401, 0x00c86700, 0x00c76800, 0x00ca6900, 0x00bc6304, 0x00b77028, 0x00945d2c, 0x00532c10, 0x00280c00, 0x00140000, 0x00100000, 0x00180500, 0x001c0d01, 0x00281c0f, 0x004e4739, 0x00908f84, 0x00c1c4be, 0x00c8cccc, 0x00c1c4c8, 0x00c7c4ca, 0x00c3bfc4, 0x00bcbabc, 0x00b8b8b6, 0x00b3b4b2, 0x00aeb2af, 0x00aeb1b0, 0x00b0b4b4, 0x00b4b5b8, 0x00b9b8bd, 0x00bebcc1, 0x00c3bdc3, 0x00ccc5c4, 0x00ccc6c0, 0x00bcb4ac, 0x00897c70, 0x00442c20, 0x002d0f00, 0x004b2716, 0x0048210f, 0x002e0600, 0x006a3414, 0x00a95823, 0x00984a18, 0x004f230b, 0x001f0000, 0x00521b00, 0x00a4592c, 0x00b1541a, 0x00bf5110, 0x00c34c04, 0x00c84f08, 0x00be4d0c, 0x00b45824, 0x006c3115, 0x00260100, 0x001c0701, 0x00301812, 0x00381401, 0x00340c00, 0x002a0800, 0x00250600, 0x00200100, 0x001a0000, 0x00120000, 0x000c0000, 0x00070000, 0x00030000, 0x00010103, 0x00000003, 0x00020004, 0x00040005, 0x00000000, 0x00000000, 0x00000001, 0x00090000, 0x002a0b00, 0x006d3415, 0x00b45721, 0x00c05310, 0x00bc5209, 0x00bd530a, 0x00c0510f, 0x00b85115, 0x00ae5b2a, 0x00662501, 0x002d0000, 0x005c280e, 0x009c4814, 0x00bc5513, 0x00bf500d, 0x00c0500b, 0x00bc5009, 0x00b1581b, 0x007b3d1a, 0x00210000, 0x000a0000, 0x00080000, 0x001f0300, 0x00763f1d, 0x00b0501a, 0x00c4500d, 0x00c4510c, 0x00bc5410, 0x00af5923, 0x00652500, 0x002a0200, 0x0048200c, 0x008d4d26, 0x00823d14, 0x00451300, 0x00581e00, 0x00b25821, 0x00b7551b, 0x00a4542c, 0x00501800, 0x001c0000, 0x004b3221, 0x006f442d, 0x0052210a, 0x00401401, 0x00401f12, 0x005f514c, 0x008f8d8e, 0x00b2b6b8, 0x00c4c8cc, 0x00c4c5c9, 0x00c1c0c5, 0x00c1c2c6, 0x00c5c6c9, 0x00c2c5c4, 0x00c4c6c2, 0x00c6c7c3, 0x00c8c8c4, 0x00c2c3bf, 0x00a7a7a5, 0x00747474, 0x003b3c3f, 0x0014181b, 0x00060a0d, 0x00000305, 0x00030404, 0x00080501, 0x000f0400, 0x00150400, 0x001e0500, 0x00260800, 0x002f0900, 0x003e0e00, 0x00551c03, 0x007c3c1d, 0x009c542c, 0x00ab5827, 0x00b35419, 0x00bd5410, 0x00c25206, 0x00c44f00, 0x00ca5402, 0x00c65304, 0x00c15304, 0x00bf5810, 0x00b65611, 0x00ae5415, 0x00af5d21, 0x00a0571c, 0x009a571d, 0x0097541c, 0x00914f1a, 0x008b4818, 0x00834114, 0x007c3c11, 0x00793810, 0x0076340c, 0x0079350a, 0x007f3809, 0x00873c08, 0x00944309, 0x00a24c0c, 0x00af5510, 0x00b65b16, 0x00b55b1c, 0x00813c0f, 0x00240500, 0x000c0000, 0x000c0000, 0x00432306, 0x00945117, 0x00b76012, 0x00c0600d, 0x00bf600c, 0x00b96216, 0x00a05718, 0x00602b00, 0x00642c00, 0x00bb6623, 0x00c45d0e, 0x00c35703, 0x00c15706, 0x00bb5a10, 0x00a95b20, 0x005d2a07, 0x00200300, 0x000b0000, 0x00010103, 0x00000308, 0x00000000, 0x00100000, 0x00270500, 0x00512104, 0x008c4f25, 0x009e541a, 0x00ac5616, 0x00b75417, 0x00b85014, 0x00b44f0c, 0x00b9530d, 0x00bc520e, 0x00ba4c0c, 0x00be4c10, 0x00bb5118, 0x00ae5420, 0x0081441d, 0x002b1508, 0x00040206, 0x0000000a, 0x00080000, 0x002d0400, 0x009b5729, 0x00b45713, 0x00bd5003, 0x00c4510a, 0x00c45106, 0x00c85b06, 0x00bc580a, 0x00a8551c, 0x005d2300, 0x00140000, 0x00000000, 0x00292d30, 0x00959ba0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007a7e7b, 0x00282924, 0x00080000, 0x00220300, 0x005d250a, 0x0097491f, 0x00b7571a, 0x00bf580e, 0x00c05805, 0x00c45c03, 0x00c85f04, 0x00ca6103, 0x00cc6405, 0x00cc6806, 0x00c96a05, 0x00c36804, 0x00c46c10, 0x00b5681c, 0x00804818, 0x00411b00, 0x00220800, 0x00130000, 0x00150000, 0x00351400, 0x00633b1f, 0x00774d30, 0x005c381b, 0x00321700, 0x002f1f09, 0x004f4538, 0x00807c78, 0x00b0aeb2, 0x00c6c2c8, 0x00cac4cb, 0x00ccc7c8, 0x00c8c4c4, 0x00c2c4c1, 0x00c1c4c4, 0x00c1c4c4, 0x00c0c4c4, 0x00c0c1c4, 0x00c3c2c6, 0x00ccc8cc, 0x00c8c0c0, 0x00a89994, 0x007f6c60, 0x00503b28, 0x00331500, 0x00451901, 0x00632f17, 0x0085543d, 0x005b2d16, 0x002f0400, 0x006c3516, 0x00a85923, 0x00944813, 0x004b2007, 0x00210000, 0x00581f00, 0x00a85b2a, 0x00b45419, 0x00c15211, 0x00c34c08, 0x00c7500c, 0x00bd5010, 0x00aa501d, 0x00521800, 0x001c0000, 0x000a0000, 0x000d0506, 0x00100000, 0x00140000, 0x000a0000, 0x00070000, 0x00060000, 0x00050000, 0x00000000, 0x00000003, 0x00000004, 0x00000105, 0x00000105, 0x00000309, 0x00000009, 0x00000005, 0x00000000, 0x000a0802, 0x00090100, 0x000c0000, 0x00270800, 0x00683117, 0x00b15624, 0x00be5210, 0x00bb520a, 0x00bd530a, 0x00c2520e, 0x00bb5317, 0x00ac5928, 0x00672602, 0x00300000, 0x00682d13, 0x00a24c18, 0x00bc5412, 0x00be4f0c, 0x00c0510d, 0x00bb530c, 0x00ac561c, 0x00703818, 0x001b0000, 0x00080000, 0x00080000, 0x00200200, 0x00844623, 0x00b7511a, 0x00c54f0a, 0x00c24f08, 0x00b9520f, 0x00aa5822, 0x00602400, 0x00290100, 0x004a2210, 0x008d4f2a, 0x007d3b13, 0x00471400, 0x00652a06, 0x00b3581d, 0x00b95418, 0x00a65129, 0x00581b00, 0x001c0000, 0x00452810, 0x008d5738, 0x008d4b28, 0x00773414, 0x00561d04, 0x003c1807, 0x00331e14, 0x0043362c, 0x00595149, 0x00746963, 0x008c8480, 0x00948f8f, 0x00949394, 0x008f8e8c, 0x008e8e8c, 0x00777874, 0x0060615d, 0x00434440, 0x002c2c2a, 0x00191b1a, 0x000a0b0c, 0x00000305, 0x00000104, 0x00010302, 0x00020300, 0x00070100, 0x00070000, 0x00080000, 0x000a0000, 0x000c0000, 0x00100000, 0x00160000, 0x001c0000, 0x002a0500, 0x00461803, 0x006d3312, 0x00964c1e, 0x00b2581b, 0x00bc540e, 0x00c35307, 0x00c35002, 0x00c65406, 0x00c45408, 0x00bc5107, 0x00bc560d, 0x00c05914, 0x00b4530e, 0x00b45912, 0x00b25a13, 0x00b25a14, 0x00b05915, 0x00ad5816, 0x00a85617, 0x00a65418, 0x00a45418, 0x00a15318, 0x00a3541a, 0x00a65619, 0x00a95718, 0x00af5814, 0x00b45b13, 0x00ba5c10, 0x00ba5e17, 0x00b45b21, 0x0079370f, 0x001d0300, 0x00080000, 0x00120000, 0x005b3411, 0x00a35d1d, 0x00b85e0e, 0x00bd5c0b, 0x00be5e10, 0x00b86019, 0x009b5219, 0x00522400, 0x00491800, 0x00b06223, 0x00bd5e0e, 0x00c45a06, 0x00c55804, 0x00c3580c, 0x00b45a1c, 0x00854318, 0x003f1600, 0x000e0000, 0x00000000, 0x00010000, 0x000c0000, 0x003c1500, 0x006d3310, 0x00904b20, 0x00a4541f, 0x00ac5413, 0x00b55510, 0x00b44d0b, 0x00b9500f, 0x00ba5512, 0x00b24e0b, 0x00b65212, 0x00bc581b, 0x00b65019, 0x00b2501a, 0x00ae531b, 0x00955125, 0x00472a17, 0x00070000, 0x00000004, 0x00060000, 0x00240200, 0x007f421b, 0x00b05515, 0x00bc5105, 0x00c7540b, 0x00c65306, 0x00c55905, 0x00b8590e, 0x009b4f1c, 0x00511e01, 0x00120000, 0x00020100, 0x0035383b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008a8988, 0x00262a2c, 0x00040000, 0x00230600, 0x00612b0d, 0x00954218, 0x00b8551d, 0x00c05612, 0x00c25906, 0x00c15f00, 0x00c56600, 0x00cc6a02, 0x00cc6a04, 0x00cc6508, 0x00c8640b, 0x00c3660f, 0x00bc6a1a, 0x00a56120, 0x00703c0c, 0x00381200, 0x00180000, 0x00130000, 0x00230500, 0x004c2200, 0x00824914, 0x009f561c, 0x00ad6023, 0x00a25c20, 0x00844915, 0x0060370c, 0x003c2004, 0x00312015, 0x00403737, 0x00595158, 0x00706a70, 0x008c8485, 0x009b9794, 0x00a3a3a3, 0x00abacac, 0x00a9abaa, 0x00a3a4a5, 0x009b9c9f, 0x00808082, 0x00686465, 0x00544643, 0x00412718, 0x003f1c04, 0x00411900, 0x0062300d, 0x0085421c, 0x009b5430, 0x009c5e40, 0x00542008, 0x002c0000, 0x006b381c, 0x00a05624, 0x0088410f, 0x00411a00, 0x00240000, 0x005d2200, 0x00ad5c28, 0x00b85417, 0x00c15211, 0x00c24e0f, 0x00c15011, 0x00bb5316, 0x00ae5b28, 0x005c2508, 0x00240600, 0x00060000, 0x00010002, 0x00060000, 0x00050000, 0x00000000, 0x00000001, 0x00000000, 0x00000102, 0x00000406, 0x00000506, 0x00000405, 0x00000303, 0x00000001, 0x00040405, 0x00010004, 0x00020001, 0x00060000, 0x00291c10, 0x00200d07, 0x00140000, 0x00250500, 0x00643017, 0x00ae5624, 0x00bc5310, 0x00ba530a, 0x00bd5108, 0x00c4510c, 0x00bc5214, 0x00ab5827, 0x00682701, 0x00310000, 0x00723518, 0x00a84f1a, 0x00bc5311, 0x00bd4e0c, 0x00bf520f, 0x00b85410, 0x00a2531c, 0x00623014, 0x00160000, 0x00080000, 0x000c0000, 0x00250100, 0x00935028, 0x00ba5118, 0x00c54d08, 0x00c14f05, 0x00b7520f, 0x00a75822, 0x005c2000, 0x00260000, 0x004a2112, 0x00884d2e, 0x0072340f, 0x00481400, 0x00783912, 0x00b25519, 0x00ba5518, 0x00a44f25, 0x005e2003, 0x00180000, 0x002e0f00, 0x008e5029, 0x00ac5c2c, 0x00a95223, 0x009b481c, 0x007f3e1a, 0x00622f10, 0x00481d00, 0x00401c01, 0x00371b04, 0x00392414, 0x002f231d, 0x00322c2a, 0x002c292a, 0x00262628, 0x001e2122, 0x00121413, 0x00060504, 0x00030000, 0x00030000, 0x00040000, 0x00050000, 0x00060000, 0x00080000, 0x000b0000, 0x00100000, 0x00140000, 0x00140000, 0x00130000, 0x00100000, 0x000d0000, 0x000c0000, 0x000e0000, 0x000d0000, 0x00110000, 0x00260800, 0x004a1f02, 0x00783b0e, 0x009d4f16, 0x00b85a1b, 0x00b5500c, 0x00ba510b, 0x00be550d, 0x00bb540a, 0x00bd560c, 0x00c25711, 0x00ba510b, 0x00b9540f, 0x00b8550f, 0x00b95610, 0x00b95811, 0x00b85910, 0x00b85b10, 0x00b75b10, 0x00b65c10, 0x00b45c10, 0x00b55d11, 0x00b85d10, 0x00b85d10, 0x00bb5c0c, 0x00bc5a08, 0x00bd5904, 0x00b9580e, 0x00af5b24, 0x00682c0c, 0x00180100, 0x00080000, 0x00210800, 0x0074461c, 0x00ad6421, 0x00b85d0e, 0x00bf5c0d, 0x00bf5c12, 0x00b9601b, 0x00975019, 0x00481a00, 0x00360800, 0x00a75d21, 0x00bc5e11, 0x00c55b07, 0x00c75804, 0x00c5560d, 0x00bc5416, 0x00b05722, 0x006a2c05, 0x00200400, 0x000c0000, 0x001e0700, 0x00441804, 0x007e3813, 0x00a44d1c, 0x00b15720, 0x00ac5015, 0x00b45416, 0x00b2500e, 0x00b8520c, 0x00b64e08, 0x00b85411, 0x00b05010, 0x00ae561a, 0x00ac5823, 0x00954515, 0x00984715, 0x00a94f17, 0x00a45726, 0x00683e1f, 0x00180600, 0x00040000, 0x00080000, 0x001b0000, 0x005f2c0d, 0x00a8551b, 0x00ba5109, 0x00c8550c, 0x00c85408, 0x00c15706, 0x00b45b16, 0x00874318, 0x00401400, 0x000c0000, 0x00060504, 0x00454649, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9894, 0x00302a25, 0x00040000, 0x00180400, 0x005d2b0f, 0x009a4e23, 0x00b9541c, 0x00c45511, 0x00c25708, 0x00c25d03, 0x00c36700, 0x00c76d00, 0x00ca6c00, 0x00c66700, 0x00c7670c, 0x00c46819, 0x00b4631c, 0x009c581f, 0x00602f09, 0x002d0800, 0x00180000, 0x00210000, 0x00381300, 0x00693910, 0x009a5a20, 0x00ad5f18, 0x00c2671a, 0x00be6013, 0x00ba6119, 0x00af6224, 0x00925a2b, 0x006f482a, 0x003d261b, 0x000c0000, 0x000c060c, 0x001c181c, 0x00302828, 0x00383130, 0x00393838, 0x003c3d3f, 0x003b3c3d, 0x00343537, 0x002e2f30, 0x00222021, 0x00181110, 0x00220f05, 0x0049240d, 0x006b3816, 0x0080441c, 0x009e5728, 0x00ab5421, 0x00ad5828, 0x009d5834, 0x00501800, 0x002b0100, 0x00663820, 0x009a5628, 0x00824114, 0x00371300, 0x00250200, 0x00612400, 0x00ad5b26, 0x00b75112, 0x00c0500e, 0x00bf4e0f, 0x00bd4f13, 0x00b74f10, 0x00b15c25, 0x00753c19, 0x002b0a00, 0x000b0000, 0x00000000, 0x00060000, 0x00030000, 0x00000204, 0x00000204, 0x00000101, 0x00000201, 0x00000304, 0x00000301, 0x00000300, 0x00000300, 0x00000000, 0x00040000, 0x00030001, 0x00060000, 0x000f0000, 0x004c3624, 0x00452718, 0x00240000, 0x00280400, 0x00642f15, 0x00ad5622, 0x00bc5410, 0x00ba530a, 0x00bc5108, 0x00c34e09, 0x00bc5013, 0x00aa5827, 0x00662500, 0x00330000, 0x007b3c1e, 0x00ac521c, 0x00bb510f, 0x00bd4e0d, 0x00bf5312, 0x00b35414, 0x00964c1a, 0x0051270e, 0x00130000, 0x00080000, 0x000e0000, 0x002e0400, 0x009d552b, 0x00ba5014, 0x00c54d08, 0x00c15008, 0x00b75513, 0x00a55723, 0x00581d00, 0x00240000, 0x00482014, 0x007c482e, 0x00632808, 0x004a1300, 0x0088461b, 0x00b05315, 0x00b85618, 0x00a44e23, 0x00622407, 0x001c0000, 0x00230500, 0x00874720, 0x00ad5622, 0x00b65319, 0x00b75418, 0x00af5522, 0x009e4e1e, 0x00944c1c, 0x0085481c, 0x006c3c18, 0x00452309, 0x000e0000, 0x00070000, 0x00070000, 0x00040000, 0x00030000, 0x00050000, 0x000b0000, 0x000e0000, 0x00110000, 0x00180000, 0x00240800, 0x00311002, 0x003b1704, 0x00411904, 0x004b1e04, 0x00542508, 0x0056290d, 0x00572b13, 0x00532b18, 0x004e2a18, 0x0044230c, 0x003a1d08, 0x00291002, 0x001a0300, 0x00150000, 0x001d0000, 0x003c1000, 0x00642b04, 0x0090481c, 0x00aa5622, 0x00b7581d, 0x00b85312, 0x00bc540e, 0x00be540b, 0x00bc500b, 0x00c05410, 0x00be5210, 0x00be5210, 0x00be530d, 0x00be530c, 0x00bc5409, 0x00bc5408, 0x00bb5606, 0x00ba5707, 0x00b85706, 0x00b85706, 0x00b95807, 0x00ba5805, 0x00bc5605, 0x00be5705, 0x00c15704, 0x00ba5910, 0x00ac5c2b, 0x00592305, 0x00140200, 0x000e0000, 0x00401d01, 0x00874d1e, 0x00af601b, 0x00bc5f10, 0x00c45e14, 0x00bc5810, 0x00b85e1c, 0x00944c19, 0x003c1100, 0x00300500, 0x009b551c, 0x00b85f15, 0x00c35c08, 0x00c75805, 0x00c5540b, 0x00c0500c, 0x00c25b1a, 0x00903f0d, 0x003f1400, 0x00240600, 0x00502410, 0x00844526, 0x00ab5020, 0x00b44e14, 0x00b65014, 0x00b24d10, 0x00b8571b, 0x00b14f10, 0x00ba540e, 0x00b14c08, 0x00b35518, 0x00ad5723, 0x009b5023, 0x007e3a0f, 0x00702b02, 0x008c3e12, 0x00ae5018, 0x00aa531d, 0x007f4823, 0x00341800, 0x00090000, 0x00070000, 0x00120000, 0x00471a04, 0x00a35625, 0x00b85310, 0x00c55309, 0x00c85508, 0x00c0580b, 0x00b25c1e, 0x00703614, 0x002b0900, 0x000a0000, 0x00100f0d, 0x005d5c60, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b0aba6, 0x00443d39, 0x000c0000, 0x00150000, 0x0054280c, 0x0093481f, 0x00b85620, 0x00c85814, 0x00c65706, 0x00c66109, 0x00c26607, 0x00c26a06, 0x00c46d06, 0x00c46700, 0x00be6200, 0x00c06912, 0x00b86b25, 0x008b4c1c, 0x00542407, 0x00200000, 0x001a0000, 0x00280200, 0x00522003, 0x00854618, 0x00a85d20, 0x00b86118, 0x00bc5d0d, 0x00c35e0e, 0x00be5a10, 0x00bc611c, 0x00ab5c25, 0x00854a23, 0x00623922, 0x00361e18, 0x00080000, 0x00000003, 0x00000001, 0x00040000, 0x00040000, 0x00000000, 0x00000001, 0x00000002, 0x00000002, 0x00000103, 0x00040301, 0x00080000, 0x002a1103, 0x007a4728, 0x009f592e, 0x00b05e29, 0x00b1541a, 0x00b65114, 0x00b3541c, 0x00a0562d, 0x004a1300, 0x00240000, 0x00653a27, 0x00985a34, 0x00753a13, 0x002e0c00, 0x00240200, 0x00602400, 0x00ab5924, 0x00b85010, 0x00bf4f0b, 0x00bd5010, 0x00bd5010, 0x00be510c, 0x00ad5012, 0x00804015, 0x002f0800, 0x000e0000, 0x00090100, 0x00070000, 0x00060000, 0x00000104, 0x00000005, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020000, 0x00040000, 0x00080100, 0x00060000, 0x00050000, 0x000c0000, 0x00180200, 0x00674429, 0x006e4028, 0x00400f00, 0x002f0300, 0x00682d11, 0x00ad541d, 0x00bc540f, 0x00b9530a, 0x00ba5109, 0x00c44d0a, 0x00bc4e12, 0x00aa5a28, 0x005f2000, 0x00370000, 0x00814020, 0x00b0521b, 0x00bc500e, 0x00c04f0f, 0x00bc5213, 0x00b05619, 0x00884417, 0x00401b08, 0x000e0000, 0x00060000, 0x00110000, 0x003c0d00, 0x00a35728, 0x00b85013, 0x00c34e09, 0x00c0500b, 0x00b65415, 0x00a45524, 0x00551c00, 0x00220000, 0x00462318, 0x006b3d28, 0x00521c00, 0x00501400, 0x00984f23, 0x00b15114, 0x00b85618, 0x00a44e21, 0x0064270a, 0x00140000, 0x00160000, 0x00793c17, 0x00a8521c, 0x00b75110, 0x00bd500a, 0x00bc500e, 0x00ba5110, 0x00b65212, 0x00b05920, 0x009e5a2e, 0x006a3c1c, 0x00180000, 0x000a0000, 0x00080000, 0x00080000, 0x00110000, 0x00200300, 0x00350f00, 0x00491c06, 0x005a240d, 0x00662c11, 0x00703215, 0x00773515, 0x0087421c, 0x008e4319, 0x00964617, 0x009d4a18, 0x00a04d1c, 0x00a14f20, 0x009c4f26, 0x009a4d24, 0x00944918, 0x008b4313, 0x0079370f, 0x00682c0c, 0x00542208, 0x00391000, 0x00280400, 0x002c0600, 0x004e1c0a, 0x00834327, 0x00ac582c, 0x00b7541c, 0x00bd520e, 0x00c0500b, 0x00bf4f10, 0x00c05014, 0x00c25015, 0x00c25014, 0x00c25010, 0x00c2500d, 0x00c2510b, 0x00c2530a, 0x00c1530a, 0x00c05509, 0x00c0550b, 0x00be560b, 0x00bd560c, 0x00bd560c, 0x00be550c, 0x00c0560d, 0x00c2560c, 0x00bb5a19, 0x00a95f31, 0x004c1c00, 0x00130000, 0x00130000, 0x0064310f, 0x009c531d, 0x00b25c15, 0x00bc5c10, 0x00c35c13, 0x00b85410, 0x00b75e1d, 0x008c4815, 0x00300500, 0x002f0700, 0x008a4915, 0x00b4601b, 0x00c35d11, 0x00c8590a, 0x00c75807, 0x00c45406, 0x00c6550c, 0x00b04f14, 0x00632708, 0x003a0a00, 0x006c3214, 0x009f562c, 0x00af4c14, 0x00b84b0e, 0x00bd5016, 0x00b84f17, 0x00b45119, 0x00b45216, 0x00b64f0c, 0x00b45214, 0x00a85425, 0x00904a26, 0x00652e14, 0x004a1500, 0x00652303, 0x0098451b, 0x00b9531a, 0x00b14f17, 0x00934f24, 0x00562c10, 0x000c0000, 0x00050000, 0x000c0000, 0x002e0800, 0x0099532b, 0x00b65619, 0x00c15209, 0x00c85608, 0x00c15b12, 0x00ab5a22, 0x005b2b0e, 0x001b0100, 0x00090000, 0x00221f1c, 0x007c797f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b6b0ac, 0x00645c57, 0x000a0100, 0x00130000, 0x004c1d00, 0x00944d1f, 0x00b75821, 0x00c25414, 0x00c85508, 0x00c45500, 0x00c86506, 0x00c46a06, 0x00c36b07, 0x00c16907, 0x00c46909, 0x00c16c14, 0x00ad641c, 0x0080450e, 0x00451900, 0x001c0000, 0x001c0000, 0x003c1604, 0x0064300f, 0x00945120, 0x00b86727, 0x00bc6118, 0x00bc5d0f, 0x00c46518, 0x00bb6018, 0x00ae591b, 0x00924814, 0x0070340c, 0x004b1d05, 0x00250600, 0x000d0000, 0x00060001, 0x00010407, 0x00000303, 0x00040000, 0x00070000, 0x00010103, 0x00000003, 0x00000003, 0x00000001, 0x00000001, 0x00020000, 0x00080000, 0x002f0f00, 0x00894b24, 0x00ac5521, 0x00c05a1c, 0x00bc4c0a, 0x00c55710, 0x00b35114, 0x009c5126, 0x00440e00, 0x00200000, 0x00613827, 0x00955939, 0x006b3111, 0x00250600, 0x00200000, 0x00592201, 0x00a85826, 0x00b65010, 0x00bf4f08, 0x00bd5110, 0x00bc500f, 0x00c1530c, 0x00b04f11, 0x00874318, 0x00360a00, 0x00130000, 0x002c1d18, 0x00211005, 0x000c0000, 0x00010002, 0x00000004, 0x00020000, 0x00060000, 0x00060000, 0x00040000, 0x00040000, 0x00070100, 0x00080000, 0x00050000, 0x00050000, 0x000d0000, 0x00260a00, 0x00724828, 0x008c5432, 0x005e2203, 0x003b0700, 0x006d2f10, 0x00af541b, 0x00bb530c, 0x00b7540c, 0x00ba520c, 0x00c34e0c, 0x00bc5014, 0x00a85a29, 0x00551800, 0x003e0500, 0x00874423, 0x00b1531b, 0x00bc4f0c, 0x00c05010, 0x00b95012, 0x00b0581e, 0x007a3c11, 0x002d0f00, 0x00080000, 0x00060000, 0x00150000, 0x00511f00, 0x00a65827, 0x00b65011, 0x00c0500a, 0x00bf500c, 0x00b45015, 0x00a05425, 0x00561c00, 0x00210000, 0x0043241a, 0x00552f1d, 0x00441200, 0x005c1c00, 0x00a35424, 0x00b35117, 0x00b85419, 0x00a55123, 0x0064280b, 0x00180000, 0x001b0000, 0x006d3413, 0x00a2511b, 0x00b55410, 0x00bf5008, 0x00c04c03, 0x00c75008, 0x00c9560f, 0x00bc5718, 0x00a45624, 0x006f3917, 0x001c0000, 0x00160400, 0x0024110b, 0x00372017, 0x00502f1f, 0x005f321c, 0x00703a1e, 0x00844421, 0x00964c27, 0x00a4542a, 0x00aa572c, 0x00ac5629, 0x00ac5423, 0x00b0521c, 0x00b45015, 0x00b65013, 0x00b74f10, 0x00b65014, 0x00b45018, 0x00b35117, 0x00b45212, 0x00b85818, 0x00b65821, 0x00ab5424, 0x00984e25, 0x007b3f1d, 0x0058280f, 0x00431804, 0x00380900, 0x00501703, 0x00813714, 0x00a8501e, 0x00b75414, 0x00bd5410, 0x00c05314, 0x00bd4d10, 0x00bf4f11, 0x00bf4f10, 0x00c04f0d, 0x00c0500c, 0x00c1500a, 0x00c1500a, 0x00c1510b, 0x00c0520b, 0x00bd520b, 0x00bc540c, 0x00bd550f, 0x00bd550f, 0x00bd540e, 0x00bd540e, 0x00bf540c, 0x00b65618, 0x00a46032, 0x00421500, 0x00130000, 0x00200400, 0x00814016, 0x00b05a1e, 0x00b85c14, 0x00b9570c, 0x00c05811, 0x00b85411, 0x00b56020, 0x00834210, 0x00240000, 0x002c0600, 0x007f4214, 0x00b26121, 0x00c05d15, 0x00c45a09, 0x00c55803, 0x00c85904, 0x00c65404, 0x00c05a19, 0x0081380f, 0x00480c00, 0x00602301, 0x009a5127, 0x00ac4e16, 0x00b74c0d, 0x00ba4d10, 0x00b84c12, 0x00b04d14, 0x00b3541c, 0x00af541e, 0x00a65424, 0x00803d1a, 0x00521d04, 0x00300700, 0x00401000, 0x007d3717, 0x00aa5223, 0x00bb5014, 0x00b44f11, 0x00a15322, 0x00703c1a, 0x00190200, 0x00080000, 0x00090001, 0x001c0000, 0x00854625, 0x00b15720, 0x00c1530a, 0x00c85708, 0x00c15c18, 0x009a4e1b, 0x00461d08, 0x00100000, 0x00050000, 0x00363330, 0x009a969c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b9b5b2, 0x0079726e, 0x0018100b, 0x000c0100, 0x00361602, 0x008d4515, 0x00b85515, 0x00c0530e, 0x00c55308, 0x00cc5c08, 0x00cc6304, 0x00cc6a06, 0x00c76902, 0x00c86806, 0x00c3650a, 0x00bd6716, 0x00ab611d, 0x0076400c, 0x003a1400, 0x001d0200, 0x00250800, 0x00542201, 0x00844414, 0x00a95f1f, 0x00bb681c, 0x00bd6311, 0x00bf6211, 0x00b96219, 0x00a05414, 0x00844512, 0x006c3c16, 0x00401d06, 0x00180100, 0x000c0000, 0x00080000, 0x00030000, 0x00000100, 0x00000404, 0x00000201, 0x00000000, 0x00030000, 0x00000001, 0x00000004, 0x00000004, 0x00030304, 0x00000002, 0x00030000, 0x000e0000, 0x00371100, 0x0090481e, 0x00b8561a, 0x00c85410, 0x00c84d05, 0x00bc4b01, 0x00ad4c0c, 0x009d5227, 0x00481100, 0x00240000, 0x005c3020, 0x008c5033, 0x00662f14, 0x001c0000, 0x00180000, 0x00511e02, 0x00a25628, 0x00b65212, 0x00be5007, 0x00bc510c, 0x00bb510f, 0x00b94d0c, 0x00b1531b, 0x008c4924, 0x00380a00, 0x00180000, 0x00482d24, 0x004d2f20, 0x002c1105, 0x00100101, 0x00060002, 0x00060000, 0x00080000, 0x00060000, 0x00030001, 0x00000005, 0x00000005, 0x00010002, 0x00040004, 0x00000004, 0x000a0000, 0x003d1e05, 0x007c4c28, 0x009d5b33, 0x00742e09, 0x00490e00, 0x0076330e, 0x00b45318, 0x00bb520a, 0x00b4540c, 0x00b7520c, 0x00c04e0f, 0x00ba5017, 0x00a35626, 0x004c0f00, 0x00481000, 0x008c4926, 0x00b15319, 0x00bb4e09, 0x00c25111, 0x00b74f12, 0x00a9541c, 0x006a3007, 0x001d0300, 0x00060000, 0x00060000, 0x001a0300, 0x00693210, 0x00a85824, 0x00b45111, 0x00bd500c, 0x00bc500e, 0x00b25018, 0x00a15429, 0x00561e03, 0x001d0000, 0x00381e14, 0x00401f10, 0x00380b00, 0x00692802, 0x00ab5626, 0x00b55218, 0x00b55217, 0x00a55324, 0x00632808, 0x00180000, 0x00160000, 0x00592402, 0x0099501c, 0x00ad5414, 0x00ba540e, 0x00bc4c05, 0x00c14d06, 0x00c54d08, 0x00bd5314, 0x00a85526, 0x00713817, 0x00210000, 0x002a1304, 0x00462a1a, 0x0063412d, 0x00784e34, 0x00875333, 0x00985730, 0x00a45728, 0x00ab5423, 0x00af531f, 0x00ae521e, 0x00af511c, 0x00b2541d, 0x00b5541c, 0x00b95414, 0x00bb5210, 0x00bb510f, 0x00ba500e, 0x00ba5113, 0x00bb5212, 0x00bb510d, 0x00ba500c, 0x00b84e12, 0x00b34e13, 0x00b35218, 0x00b1581f, 0x00a1521c, 0x008c4416, 0x006b2805, 0x00541500, 0x005d1c00, 0x00833d12, 0x00a35218, 0x00b25614, 0x00bc540f, 0x00bc5008, 0x00bc540b, 0x00b9550b, 0x00bb550b, 0x00bc5409, 0x00bc5409, 0x00be540b, 0x00be530c, 0x00bc540d, 0x00ba520d, 0x00ba540e, 0x00ba5510, 0x00bb5610, 0x00bc560f, 0x00bc550c, 0x00bc550c, 0x00b45817, 0x009d5c2c, 0x00380c00, 0x00170000, 0x003f1b02, 0x00984918, 0x00be5a18, 0x00bd5910, 0x00bc560c, 0x00bf5710, 0x00b85815, 0x00ac5a1c, 0x00743707, 0x001e0000, 0x00290500, 0x007e451c, 0x00ae6126, 0x00b95d16, 0x00c25b09, 0x00c45802, 0x00c45800, 0x00c25805, 0x00bf5e17, 0x009a4814, 0x005f1a00, 0x00501400, 0x00874828, 0x00ac5828, 0x00b25214, 0x00b64e0b, 0x00b94d0c, 0x00b85014, 0x00a94e1c, 0x008c4926, 0x00683418, 0x00411700, 0x00220000, 0x00280400, 0x00602d17, 0x009b4d24, 0x00b3521b, 0x00b84e0c, 0x00b4500a, 0x00a95418, 0x0084471a, 0x00341400, 0x000c0000, 0x00050005, 0x00100000, 0x00683015, 0x00ab5421, 0x00c1550d, 0x00c85708, 0x00bd5918, 0x0083380b, 0x00310d00, 0x000a0000, 0x00090400, 0x0053504d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9a96, 0x00312a24, 0x000c0000, 0x00240b00, 0x00713e1b, 0x00b1581b, 0x00c45408, 0x00c85708, 0x00c95a06, 0x00cc6006, 0x00c86404, 0x00c86502, 0x00cc6a08, 0x00c66509, 0x00bf6817, 0x00a55e1e, 0x00733b09, 0x003a1000, 0x00200000, 0x00341600, 0x005e340f, 0x009f5920, 0x00b46019, 0x00b86012, 0x00bd6410, 0x00b96314, 0x00ab5b14, 0x00904d14, 0x0069350a, 0x003b1800, 0x001a0400, 0x00080000, 0x00050002, 0x00020005, 0x00000004, 0x00000000, 0x00000100, 0x00000200, 0x00000100, 0x00050000, 0x00070000, 0x00030000, 0x00000001, 0x00020000, 0x00020000, 0x00020100, 0x00030000, 0x000b0000, 0x00320d00, 0x008c4012, 0x00c2591b, 0x00c84e09, 0x00c84a01, 0x00c55108, 0x00b75416, 0x00985026, 0x00390700, 0x001c0000, 0x00543021, 0x007c4832, 0x0050210e, 0x00130000, 0x00100000, 0x00481c04, 0x009c562c, 0x00b45214, 0x00be4e08, 0x00be5009, 0x00bc4f0a, 0x00bc500e, 0x00af5018, 0x00914c27, 0x00380800, 0x001b0000, 0x0046271b, 0x0076472f, 0x0064341d, 0x00290a00, 0x00180200, 0x000c0000, 0x00060001, 0x00040005, 0x00020008, 0x00000008, 0x00000007, 0x00000004, 0x00050408, 0x00000004, 0x000c0000, 0x00583014, 0x008d5026, 0x00a95c31, 0x007f3108, 0x00541500, 0x007e3811, 0x00b65619, 0x00ba5109, 0x00b5520a, 0x00b6510c, 0x00bf4e0f, 0x00b8501a, 0x009c5429, 0x00440a00, 0x00521500, 0x00954c26, 0x00b55217, 0x00bc4d09, 0x00c05211, 0x00b14e13, 0x009c4d1b, 0x005a2604, 0x00110000, 0x00040000, 0x000a0100, 0x00230700, 0x007c3e19, 0x00ac5622, 0x00b55111, 0x00bd520c, 0x00bc5010, 0x00b45119, 0x00a7562b, 0x00591f04, 0x00160000, 0x00291510, 0x002e1408, 0x00320800, 0x00742d05, 0x00b05523, 0x00b85216, 0x00b24f15, 0x00a35323, 0x00602608, 0x001c0000, 0x00140000, 0x004d1d00, 0x00945121, 0x00aa5214, 0x00b85410, 0x00bd500c, 0x00c34e0a, 0x00c84f0a, 0x00c35515, 0x00a55220, 0x006a310e, 0x001e0000, 0x002e190d, 0x003a2113, 0x00422514, 0x004e2b15, 0x005c3014, 0x006e3514, 0x0079370f, 0x0084380d, 0x008d3e10, 0x00944518, 0x00984819, 0x00a04f22, 0x00a55123, 0x00ad5420, 0x00b2541c, 0x00b55418, 0x00b65114, 0x00b65212, 0x00b85211, 0x00b9500e, 0x00ba4e0d, 0x00bd5317, 0x00bd5315, 0x00b84e0c, 0x00b85009, 0x00b8530d, 0x00b05213, 0x00a4511f, 0x00883c13, 0x00652200, 0x00672400, 0x008c410c, 0x00a85314, 0x00b8530f, 0x00bd540c, 0x00b75308, 0x00b45408, 0x00b85409, 0x00ba540a, 0x00bb540b, 0x00bb540b, 0x00bc530c, 0x00bb530e, 0x00bb5310, 0x00ba5310, 0x00b85410, 0x00b8540e, 0x00b8540e, 0x00b9550d, 0x00bc550c, 0x00b35a1b, 0x0094582c, 0x002d0400, 0x001f0000, 0x00633414, 0x00a64f19, 0x00bd5510, 0x00bc550c, 0x00be580e, 0x00be5812, 0x00b55919, 0x009c521a, 0x00602c02, 0x001b0000, 0x00270600, 0x00834820, 0x00ab5c22, 0x00ba5c14, 0x00c35c0c, 0x00c55c05, 0x00c05600, 0x00c15a09, 0x00bf5c14, 0x00af551c, 0x007a2e03, 0x00490f00, 0x006e3419, 0x009d5124, 0x00ac5119, 0x00b45214, 0x00b14f11, 0x00a94e1c, 0x008b401d, 0x00562915, 0x00240500, 0x00180000, 0x00200000, 0x00461c02, 0x00854928, 0x00a95223, 0x00b24d12, 0x00b9500d, 0x00b7500c, 0x00ae5516, 0x00924d1e, 0x004c230c, 0x000f0000, 0x00030000, 0x000d0000, 0x00522007, 0x00a35324, 0x00c05811, 0x00c5570e, 0x00b0571d, 0x00682904, 0x001e0400, 0x00050000, 0x0018130e, 0x00706c69, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a8afae, 0x00515550, 0x00060000, 0x00200600, 0x00602600, 0x00ad5c20, 0x00bd5911, 0x00c55808, 0x00c25600, 0x00c96005, 0x00c96406, 0x00cc6808, 0x00cb6406, 0x00c8640c, 0x00c36617, 0x00a75c1e, 0x0067390d, 0x002e1000, 0x00280800, 0x004b2100, 0x00824810, 0x00b26623, 0x00be6010, 0x00c2600c, 0x00bd6011, 0x00b3621a, 0x009e5b21, 0x00733f14, 0x003e1b00, 0x00190400, 0x00080000, 0x00080300, 0x00050100, 0x00030000, 0x00040000, 0x00040000, 0x00020000, 0x00030000, 0x00060000, 0x000c0000, 0x00140400, 0x00140400, 0x000e0200, 0x00090000, 0x00080000, 0x00070000, 0x00050000, 0x00060200, 0x00030000, 0x00280c00, 0x00873b0c, 0x00bf5616, 0x00c95513, 0x00c54c08, 0x00c44c09, 0x00b75016, 0x00904c27, 0x00381000, 0x00130000, 0x00332014, 0x00583829, 0x00391b12, 0x000a0000, 0x00080000, 0x003b1804, 0x008a4c25, 0x00b4501c, 0x00c24c0e, 0x00c14d0b, 0x00c1500b, 0x00c0500a, 0x00b35013, 0x00985025, 0x00400d00, 0x00170000, 0x003e1c10, 0x00803f1b, 0x009c5429, 0x006e3416, 0x00360d00, 0x00100000, 0x00040004, 0x0000020c, 0x00000009, 0x00020000, 0x00040000, 0x00060000, 0x00030000, 0x00030000, 0x00130000, 0x00713515, 0x00a35225, 0x00ac5326, 0x00853209, 0x005d1d00, 0x007c3914, 0x00b35419, 0x00b85008, 0x00b85308, 0x00bb520c, 0x00bd4b0c, 0x00b4501d, 0x008a4925, 0x00380200, 0x00682101, 0x009c471c, 0x00be5418, 0x00bb4b07, 0x00b9500d, 0x00b0541c, 0x0086441c, 0x003c1400, 0x000f0000, 0x00030001, 0x000c0000, 0x00310c00, 0x009c502a, 0x00b04f18, 0x00b8500e, 0x00bd500a, 0x00be4f0e, 0x00b84f15, 0x00ae5627, 0x005d1f02, 0x00180000, 0x000b0000, 0x00130000, 0x00370e00, 0x00843a0c, 0x00b35218, 0x00ba5113, 0x00b45017, 0x00a45328, 0x005a2308, 0x00140000, 0x00100000, 0x003b1200, 0x00904d24, 0x00b25518, 0x00bc500b, 0x00bc4f0e, 0x00c04e0c, 0x00c64c08, 0x00c55615, 0x00a5511b, 0x00632c05, 0x00140000, 0x00050000, 0x00070000, 0x00060000, 0x000c0000, 0x00110000, 0x00190000, 0x00230000, 0x00300800, 0x003b1000, 0x00451b02, 0x0050240c, 0x0062321c, 0x006c3720, 0x007c3c22, 0x008a4323, 0x00964820, 0x00a24f1c, 0x00aa5419, 0x00b05518, 0x00b4511b, 0x00b6501c, 0x00b6501b, 0x00b85117, 0x00ba5110, 0x00bb5008, 0x00ba4e04, 0x00b74e08, 0x00b85518, 0x00ad531e, 0x009e4a1c, 0x0086350a, 0x007e2a00, 0x009b410c, 0x00b85618, 0x00b7500d, 0x00b8540e, 0x00b6510c, 0x00b8500b, 0x00bc520e, 0x00be5210, 0x00bb510f, 0x00bc5010, 0x00be5211, 0x00bd5110, 0x00bc5210, 0x00bc540f, 0x00b8540e, 0x00b6550e, 0x00b85410, 0x00bb5210, 0x00ae5721, 0x00804d2c, 0x00250100, 0x00350700, 0x0085451c, 0x00b0581e, 0x00bc5411, 0x00bd540c, 0x00bd560d, 0x00bb5610, 0x00b35c20, 0x008a4c20, 0x003f1500, 0x00180000, 0x00280800, 0x008c4c1f, 0x00b25a1b, 0x00c05c12, 0x00c15607, 0x00c45b0a, 0x00c25808, 0x00bd5308, 0x00c45c17, 0x00b8561c, 0x008d3b0c, 0x004c1200, 0x00592106, 0x009a4f25, 0x00ae5728, 0x00a64c1d, 0x009b4922, 0x00783b1e, 0x003c1200, 0x00150000, 0x00100000, 0x001c0000, 0x00380b00, 0x007f4317, 0x00a25621, 0x00a94c14, 0x00b65015, 0x00b84d13, 0x00b44c12, 0x00b0521c, 0x009d5028, 0x006a3720, 0x001a0000, 0x000c0000, 0x000e0000, 0x00380a00, 0x00a4582d, 0x00ba5512, 0x00be5a17, 0x00944f21, 0x00401700, 0x000e0000, 0x00010103, 0x00383230, 0x009a9490, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00757a78, 0x00181811, 0x00100000, 0x00401800, 0x00a0501b, 0x00be5914, 0x00c35909, 0x00c05400, 0x00cc6407, 0x00cb6606, 0x00c56302, 0x00c8680a, 0x00c86710, 0x00c16418, 0x00ab5b1c, 0x00763806, 0x00320c00, 0x00301000, 0x00603709, 0x0090571d, 0x00b4641c, 0x00bf610f, 0x00c76410, 0x00b75808, 0x00b4631f, 0x0092511c, 0x00532501, 0x00260900, 0x000a0000, 0x00030000, 0x00030102, 0x00020000, 0x00060000, 0x000c0000, 0x00120000, 0x00120000, 0x00170200, 0x00280d00, 0x00361400, 0x00401800, 0x00491f05, 0x004a210a, 0x00421d0a, 0x00341200, 0x00240600, 0x00190000, 0x000e0000, 0x000a0000, 0x00040000, 0x00281000, 0x00833a0c, 0x00bc5617, 0x00c1510d, 0x00c44d0a, 0x00c54c0c, 0x00b9521c, 0x0093502a, 0x00351000, 0x000c0000, 0x00180e03, 0x002b1810, 0x001b0806, 0x00050004, 0x00060000, 0x002e1200, 0x0079401f, 0x00b65321, 0x00c04a0f, 0x00bf4b0a, 0x00be4c08, 0x00c05009, 0x00b65212, 0x009f5326, 0x00441000, 0x00160000, 0x00381609, 0x00863d13, 0x00ac541f, 0x009c5024, 0x006c3114, 0x002e0c00, 0x00140403, 0x00000004, 0x00000004, 0x00050100, 0x00050000, 0x00040000, 0x00040000, 0x00080000, 0x00230700, 0x00843f18, 0x00ac5222, 0x00b15528, 0x00833007, 0x005c1d00, 0x007b3815, 0x00b3561c, 0x00b9500a, 0x00b95209, 0x00bc510c, 0x00be4b10, 0x00b34f20, 0x00763a1b, 0x00320000, 0x007b300d, 0x00a84b1c, 0x00bd5014, 0x00bc4c0a, 0x00b8500e, 0x00ac5821, 0x00703615, 0x002a0800, 0x00090000, 0x00030000, 0x00130000, 0x00421400, 0x00a65327, 0x00bc5319, 0x00bc500e, 0x00bf500a, 0x00be4f0c, 0x00b84f13, 0x00b15523, 0x00652303, 0x001c0300, 0x00080002, 0x00100000, 0x003d1500, 0x008e4110, 0x00b55314, 0x00bc4f10, 0x00b65018, 0x00a4542a, 0x00542007, 0x00100000, 0x000b0000, 0x00381000, 0x008e4b25, 0x00b45317, 0x00bf4f09, 0x00bc4f0e, 0x00bf4e0e, 0x00ca520c, 0x00c15413, 0x00a04e17, 0x005c2a01, 0x00120000, 0x00040000, 0x00020004, 0x0003010a, 0x00000003, 0x00020001, 0x00060000, 0x000a0000, 0x00100000, 0x00100000, 0x000e0000, 0x00140300, 0x00110000, 0x001b0000, 0x002c0800, 0x003f1101, 0x00531d06, 0x00682c0c, 0x007b3b12, 0x00884318, 0x0094471c, 0x00a04c22, 0x00a85426, 0x00ab5322, 0x00ae5018, 0x00b44f11, 0x00bc510d, 0x00c0530e, 0x00b64d0d, 0x00b35014, 0x00b15521, 0x00a84e1c, 0x00953c09, 0x00963a04, 0x00ac480d, 0x00b85314, 0x00b55110, 0x00b85410, 0x00be5413, 0x00bf5311, 0x00be5010, 0x00bc4f0e, 0x00bc5010, 0x00bc5210, 0x00bb5110, 0x00bc5210, 0x00bc520e, 0x00bb530c, 0x00ba540e, 0x00b9530d, 0x00ba5310, 0x00ab5722, 0x006b3c20, 0x00230000, 0x00592000, 0x00974c1b, 0x00b35618, 0x00bc5510, 0x00c0570f, 0x00bb540d, 0x00b85814, 0x00aa5c23, 0x00784421, 0x002b0b00, 0x00110000, 0x00290800, 0x00975221, 0x00b75a18, 0x00c05910, 0x00bf5507, 0x00c15a09, 0x00c1590b, 0x00c25409, 0x00c55814, 0x00be5517, 0x009e4614, 0x00571c00, 0x00501c00, 0x00894724, 0x00944c28, 0x008a4425, 0x00632a14, 0x00230000, 0x00110000, 0x000a0000, 0x00100000, 0x002a0400, 0x00743c1a, 0x00984e18, 0x00ab5114, 0x00b45015, 0x00b34a10, 0x00b74b14, 0x00b74e18, 0x00b24f1c, 0x00a55226, 0x007f4227, 0x002d0800, 0x000f0000, 0x000b0000, 0x00240000, 0x00904e28, 0x00b6591d, 0x00b1581f, 0x006d3614, 0x002c1001, 0x00040000, 0x0004060a, 0x00595552, 0x00b8b2ad, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009e9da1, 0x00403c38, 0x000c0000, 0x002e0c00, 0x007f441a, 0x00b55c20, 0x00be550c, 0x00c45905, 0x00c25900, 0x00cc6503, 0x00cc6804, 0x00cb6b08, 0x00bf6408, 0x00bc6618, 0x00ac6224, 0x0073380c, 0x003e0b00, 0x00440c00, 0x007d410c, 0x00a76226, 0x00b56521, 0x00c16115, 0x00c46114, 0x00b7621c, 0x00a35e20, 0x00824d1f, 0x00401c00, 0x00140000, 0x000d0400, 0x00040001, 0x00020000, 0x00060000, 0x000d0000, 0x00180000, 0x00280800, 0x003a1000, 0x00491800, 0x00612b05, 0x007e4015, 0x00964c1b, 0x00a45320, 0x00b05d2b, 0x00b46330, 0x00aa5b2c, 0x00904719, 0x00703007, 0x00552000, 0x003a1400, 0x00240b00, 0x000e0100, 0x00200500, 0x00723002, 0x00b85a1a, 0x00c05209, 0x00c75107, 0x00c24b08, 0x00b8521b, 0x0098532c, 0x00381000, 0x00100000, 0x00060000, 0x000a0000, 0x00070000, 0x00040002, 0x00060000, 0x001e0800, 0x00602e0f, 0x00b45524, 0x00bf4c10, 0x00be4d0d, 0x00be4f0c, 0x00bc500b, 0x00b45214, 0x00a4582c, 0x004c1900, 0x00180000, 0x002d0e02, 0x00833b11, 0x00b0561e, 0x00ac5520, 0x00a05327, 0x00753c1d, 0x002e0800, 0x00120000, 0x00050000, 0x00020003, 0x00000001, 0x00000001, 0x00020000, 0x00080000, 0x00341700, 0x008e481d, 0x00ac5320, 0x00af5728, 0x007a2c04, 0x00531600, 0x00753414, 0x00b2541d, 0x00ba500e, 0x00b8500d, 0x00bb5110, 0x00be4c15, 0x00b24f24, 0x0062270b, 0x00300000, 0x008d411b, 0x00ac501e, 0x00b94f11, 0x00bc4f0e, 0x00b35012, 0x00a15120, 0x005c270b, 0x00190000, 0x00080000, 0x00050000, 0x00200400, 0x0060290c, 0x00ac5424, 0x00bc5317, 0x00bc4f0e, 0x00bf500c, 0x00bd4e0c, 0x00b85011, 0x00b45420, 0x00712c09, 0x00230800, 0x00080000, 0x000f0000, 0x00471c03, 0x009b4c1c, 0x00b85416, 0x00bc4e10, 0x00b65018, 0x00a25428, 0x00501d01, 0x00100000, 0x000c0000, 0x00370e00, 0x008f4a24, 0x00b55217, 0x00bf4f09, 0x00bd500f, 0x00bf500d, 0x00ca540f, 0x00c05414, 0x009a4c1b, 0x00542200, 0x00140000, 0x00100200, 0x00080000, 0x00070005, 0x00000005, 0x00000005, 0x00040004, 0x00060000, 0x00060000, 0x00050000, 0x00020000, 0x00000000, 0x00010200, 0x00020000, 0x00080000, 0x000c0000, 0x00110000, 0x00180000, 0x00200000, 0x002c0600, 0x00461900, 0x005e2c0b, 0x00784021, 0x00894a29, 0x00974b26, 0x00a04b1e, 0x00ae4c18, 0x00b44e14, 0x00ba5215, 0x00b44f11, 0x00b45417, 0x00b5581c, 0x00b05317, 0x00a9490c, 0x00ae4809, 0x00b7500f, 0x00b45012, 0x00b45012, 0x00b64f0c, 0x00b84e0a, 0x00bd4f08, 0x00c0520c, 0x00be530f, 0x00ba5310, 0x00b55410, 0x00b85410, 0x00bc520e, 0x00c0500c, 0x00c04f0a, 0x00bd5109, 0x00b7540a, 0x00a85a1c, 0x005d2c0b, 0x002b0000, 0x007c3c11, 0x00a7531c, 0x00b85616, 0x00bc540d, 0x00be550f, 0x00b85410, 0x00b35818, 0x009c5422, 0x005c3113, 0x00180000, 0x000f0000, 0x002e0c00, 0x00a35b28, 0x00b85916, 0x00bc590f, 0x00bc5608, 0x00bf5907, 0x00c45b08, 0x00c55708, 0x00c5560a, 0x00c2550f, 0x00b0541a, 0x006b2e04, 0x003c0d00, 0x006a3a1d, 0x006c3e26, 0x003c1606, 0x001d0200, 0x000a0000, 0x00080100, 0x000c0000, 0x001e0300, 0x005c2a16, 0x00914c27, 0x00a45118, 0x00ad4e0e, 0x00b75014, 0x00b84f15, 0x00b44812, 0x00b84d16, 0x00b14b10, 0x00ab501d, 0x00924d28, 0x00461a02, 0x000c0000, 0x00060000, 0x001a0000, 0x007c4425, 0x00a55724, 0x009f5422, 0x004c2004, 0x00140000, 0x00020000, 0x001f2125, 0x007e7b78, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x001f1f20, 0x006c6a6e, 0x00160b08, 0x001c0300, 0x00572500, 0x00a55c26, 0x00b55314, 0x00c85a0f, 0x00c55a01, 0x00c96101, 0x00c66200, 0x00ca6804, 0x00c86b08, 0x00bb660f, 0x00ac641e, 0x007e420c, 0x003e1000, 0x00491800, 0x0089440b, 0x00b1601c, 0x00bf661c, 0x00c46619, 0x00bc580a, 0x00b86018, 0x00a4642c, 0x00784b20, 0x002c0c00, 0x00100000, 0x00080000, 0x00040000, 0x000c0400, 0x000e0000, 0x001c0200, 0x00351100, 0x00542604, 0x00753d14, 0x00965627, 0x00ac622c, 0x00af5e24, 0x00af5719, 0x00bc5b1c, 0x00bc5716, 0x00bc5513, 0x00bb5613, 0x00bc5814, 0x00b95a18, 0x00b25c20, 0x00a95d28, 0x008b4d20, 0x006d3e1c, 0x00422410, 0x00300c00, 0x00672500, 0x00b65d1e, 0x00c0540a, 0x00c45104, 0x00c04c09, 0x00b65019, 0x009e562c, 0x003c1200, 0x00140000, 0x00050000, 0x00030000, 0x00030004, 0x00030002, 0x00060000, 0x00130100, 0x00481c01, 0x00a85122, 0x00bc4f14, 0x00bc5011, 0x00be5210, 0x00ba4f0b, 0x00b35114, 0x00a85c2d, 0x005a2408, 0x001e0300, 0x00270500, 0x007d370f, 0x00b0551c, 0x00b35117, 0x00b1541c, 0x00a35324, 0x00793a18, 0x00300800, 0x00170100, 0x00040000, 0x00000004, 0x00000305, 0x00030000, 0x000a0000, 0x00482708, 0x00944c1c, 0x00ad541f, 0x00ac5728, 0x00752903, 0x00460c00, 0x006b2c0d, 0x00ad531c, 0x00ba5110, 0x00b7500d, 0x00b95012, 0x00be4c19, 0x00b05027, 0x00501600, 0x003a0600, 0x00954820, 0x00af511c, 0x00b84e12, 0x00bc5314, 0x00b2541a, 0x008e4318, 0x00491c04, 0x00100000, 0x00060000, 0x000a0000, 0x002f0a00, 0x0081401c, 0x00af531f, 0x00b94c10, 0x00bd5010, 0x00be4f0e, 0x00bc4d0b, 0x00ba5010, 0x00b4541c, 0x007f3610, 0x002e0f03, 0x000c0000, 0x00130000, 0x004e2308, 0x00a25222, 0x00b95317, 0x00bd4d10, 0x00b65018, 0x00a05428, 0x004a1c00, 0x00100000, 0x000c0000, 0x003b0e00, 0x00914823, 0x00b55217, 0x00c0500c, 0x00bc500f, 0x00bd500d, 0x00c7520d, 0x00bf5618, 0x0094481d, 0x004d1a00, 0x002a0800, 0x00382011, 0x001c0100, 0x000d0000, 0x00020004, 0x00000005, 0x00040004, 0x000a0203, 0x00080000, 0x00080000, 0x00090400, 0x00000000, 0x00000000, 0x00000000, 0x00030000, 0x00050000, 0x00080000, 0x00080000, 0x00080003, 0x000f0000, 0x00140000, 0x00160000, 0x00180000, 0x002c0600, 0x004e1c08, 0x0070341c, 0x008b4422, 0x00984a21, 0x00a04e1f, 0x00a5531e, 0x00a7531e, 0x00a8531b, 0x00b0561b, 0x00b45415, 0x00b8500e, 0x00bc5210, 0x00bc5415, 0x00ba5214, 0x00ba520d, 0x00bb520a, 0x00be520a, 0x00be520a, 0x00ba500c, 0x00b6510d, 0x00b55411, 0x00b55410, 0x00bc520e, 0x00bf500c, 0x00c05009, 0x00bd5109, 0x00b55509, 0x00a75918, 0x00582400, 0x00430f00, 0x00944818, 0x00b1571a, 0x00be5714, 0x00bc5009, 0x00ba520c, 0x00b75614, 0x00ad581d, 0x0088491c, 0x003e1b05, 0x000e0000, 0x00110000, 0x003e1a03, 0x00aa5e29, 0x00b85813, 0x00b95810, 0x00bb580c, 0x00be5907, 0x00c25904, 0x00c65805, 0x00c55605, 0x00c45408, 0x00b85c19, 0x007a3b0d, 0x00360c00, 0x002c0c00, 0x00251002, 0x000c0000, 0x00070000, 0x00060504, 0x00040000, 0x00140000, 0x004c2215, 0x00905036, 0x009e4d22, 0x00b05318, 0x00b55110, 0x00b34b0e, 0x00b54c12, 0x00b44a14, 0x00b84e17, 0x00b1490c, 0x00ad4f15, 0x009e4f21, 0x00622f10, 0x000b0000, 0x00040000, 0x00140000, 0x00592d15, 0x00985932, 0x00753a13, 0x002c0b00, 0x000b0000, 0x00030102, 0x00444749, 0x00a4a0a0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00101011, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0096989e, 0x00363237, 0x000b0000, 0x00331000, 0x00844518, 0x00ad571b, 0x00c25918, 0x00c6570b, 0x00c75a00, 0x00cb6404, 0x00ca6705, 0x00c46805, 0x00bc6407, 0x00b86b19, 0x00884f12, 0x00471800, 0x00421600, 0x00804915, 0x00b7661c, 0x00be6009, 0x00c25f05, 0x00c4630c, 0x00b86012, 0x00ab6528, 0x00684019, 0x001e0700, 0x00140200, 0x000e0000, 0x000d0000, 0x001c0700, 0x00240300, 0x00481c00, 0x00794017, 0x00985423, 0x00ac6129, 0x00ae5d1f, 0x00b05918, 0x00b85b15, 0x00c05c14, 0x00c25c13, 0x00bc5713, 0x00bc5713, 0x00be5812, 0x00be580f, 0x00c0580c, 0x00bf580c, 0x00ba570f, 0x00b45814, 0x00b66024, 0x00a85e2c, 0x007e4725, 0x00501b00, 0x005f1900, 0x00b35a21, 0x00c25710, 0x00c55309, 0x00c2500f, 0x00b65018, 0x00a5592b, 0x00491800, 0x00130000, 0x00060000, 0x00020106, 0x00000007, 0x00030002, 0x00060000, 0x000d0000, 0x00351100, 0x00934519, 0x00b45018, 0x00b85013, 0x00ba5110, 0x00b8500e, 0x00b25215, 0x00ab5928, 0x00662c0b, 0x00240400, 0x00210000, 0x0078330c, 0x00ae531b, 0x00ba5214, 0x00bb5110, 0x00b14c10, 0x00a8511e, 0x00824320, 0x002c0400, 0x00100000, 0x00050002, 0x00010103, 0x00040000, 0x00100000, 0x00603815, 0x009a4e1b, 0x00b0561e, 0x00a95527, 0x00722c07, 0x00380400, 0x00612608, 0x00a9521e, 0x00ba5312, 0x00b4500c, 0x00b85014, 0x00ba4e1b, 0x00ac4f28, 0x00420700, 0x004d1800, 0x009b4c1e, 0x00b25118, 0x00b84e12, 0x00b85216, 0x00b05724, 0x00783711, 0x00330f00, 0x000b0000, 0x00040000, 0x00110100, 0x00400f00, 0x009c5024, 0x00b5531b, 0x00bb4d0d, 0x00bf4f11, 0x00bd4d0e, 0x00bc4d0b, 0x00ba500e, 0x00b55315, 0x008e4217, 0x003b1505, 0x00100000, 0x001a0100, 0x0054250a, 0x00a55324, 0x00b95115, 0x00bf4f11, 0x00b55017, 0x009c5325, 0x00451b00, 0x000e0000, 0x000c0000, 0x003c0e00, 0x00934922, 0x00b75118, 0x00bf4f0b, 0x00bc500f, 0x00bd520e, 0x00c7540e, 0x00be581c, 0x0089431e, 0x00471300, 0x0050220a, 0x00774c35, 0x004f2312, 0x00210000, 0x00080000, 0x00030000, 0x000f0400, 0x001c0c03, 0x001a0500, 0x001b0400, 0x001d0700, 0x00170000, 0x00190400, 0x00150000, 0x00120000, 0x00120000, 0x00100000, 0x000a0000, 0x00050004, 0x00060001, 0x000c0000, 0x000c0000, 0x000e0000, 0x000e0000, 0x000d0000, 0x00100000, 0x00200100, 0x00310d00, 0x00522914, 0x00724225, 0x008a5331, 0x0096552b, 0x00a45624, 0x00ae531a, 0x00b54c0c, 0x00bc4c0a, 0x00bc4b09, 0x00bc4c08, 0x00be5008, 0x00be5409, 0x00bb5209, 0x00b74f08, 0x00b7500d, 0x00ba5312, 0x00b85014, 0x00b95113, 0x00ba5110, 0x00b9530d, 0x00b8520b, 0x00b7530b, 0x00b4540b, 0x00ac5718, 0x005b1d00, 0x006a2c04, 0x00a44e18, 0x00b85412, 0x00bc540d, 0x00bc5009, 0x00b9530d, 0x00b45818, 0x00a45824, 0x006f3915, 0x00200800, 0x000b0000, 0x00160300, 0x00552b11, 0x00ab5c24, 0x00b7560f, 0x00b85710, 0x00bc5a10, 0x00bd5807, 0x00c05702, 0x00c55804, 0x00c75805, 0x00c75505, 0x00bc5a15, 0x007f3e0c, 0x003b1400, 0x00130000, 0x00060200, 0x00000005, 0x00000005, 0x00000100, 0x000d0000, 0x00431a0b, 0x008c4d34, 0x00a4512d, 0x00af5020, 0x00b04d10, 0x00b5500d, 0x00b64d0f, 0x00b44c12, 0x00b44c16, 0x00b54f16, 0x00b44c0e, 0x00b35013, 0x00a44d18, 0x0080431e, 0x00140200, 0x00040000, 0x000e0000, 0x00311204, 0x00865b40, 0x00431b00, 0x00140000, 0x00090100, 0x00101113, 0x00707476, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00181818, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0064666c, 0x000c0a0e, 0x000d0000, 0x00300c00, 0x007f3f10, 0x00b35b1c, 0x00c25a17, 0x00c35409, 0x00c95e05, 0x00cb6606, 0x00c8680a, 0x00be6509, 0x00bd6c18, 0x00a15d14, 0x00532000, 0x00481800, 0x007e4711, 0x00a86222, 0x00be6413, 0x00c8650a, 0x00c36004, 0x00ba610d, 0x00a96422, 0x00703f11, 0x001c0400, 0x000c0000, 0x000d0000, 0x00160000, 0x00260300, 0x004a1c00, 0x0082481d, 0x00aa6230, 0x00af5d21, 0x00b75d1a, 0x00b85a12, 0x00b9570c, 0x00bf590d, 0x00c1590b, 0x00c05508, 0x00bf5406, 0x00c0570e, 0x00bf580f, 0x00be580e, 0x00be580a, 0x00c05706, 0x00c05704, 0x00bf5807, 0x00be570c, 0x00b6510c, 0x00b3581d, 0x00924a20, 0x005e1d00, 0x00520d00, 0x00a75524, 0x00c35c1b, 0x00c4540d, 0x00c05010, 0x00b45014, 0x00a95824, 0x00592300, 0x00160000, 0x00040000, 0x00030309, 0x00000007, 0x00020001, 0x00050000, 0x00080000, 0x00270900, 0x0074320c, 0x00ac5320, 0x00b45013, 0x00b8500e, 0x00bc5311, 0x00b45214, 0x00ab5421, 0x0073320e, 0x002a0500, 0x001f0000, 0x00712f0c, 0x00a9521e, 0x00ba5214, 0x00bc4c08, 0x00c0510d, 0x00b55014, 0x00a05020, 0x007f4424, 0x00280400, 0x000e0000, 0x00080000, 0x000a0000, 0x001c0100, 0x0074421c, 0x00a24e1a, 0x00b4551d, 0x00a75324, 0x006d2a05, 0x00300000, 0x00582206, 0x00a4501c, 0x00b85414, 0x00b5500d, 0x00b85213, 0x00b54e19, 0x00a24a23, 0x00370000, 0x00662d14, 0x00a24d1c, 0x00b55315, 0x00b74f12, 0x00b35018, 0x00a65327, 0x00652c0d, 0x001c0100, 0x00060000, 0x00040000, 0x001c0500, 0x00571c00, 0x00a85323, 0x00b85419, 0x00be5113, 0x00be4e12, 0x00bd4d10, 0x00bb4e0b, 0x00ba500c, 0x00b55010, 0x009c4c1c, 0x00481c09, 0x00150000, 0x00220400, 0x0058280c, 0x00a85425, 0x00b84e14, 0x00c04f14, 0x00b44f16, 0x00985324, 0x00411800, 0x000a0000, 0x000b0000, 0x003e0e00, 0x00944822, 0x00b65018, 0x00bd4e0c, 0x00bc510d, 0x00bf540e, 0x00c6550f, 0x00bc581d, 0x00813d1c, 0x003f0900, 0x00672d0f, 0x009a5e3e, 0x00874729, 0x00602a14, 0x00200000, 0x00140000, 0x000d0000, 0x0028160b, 0x00614c3c, 0x00735947, 0x006a4731, 0x006e452c, 0x0062331b, 0x005c2c13, 0x0051240c, 0x00441c04, 0x00381402, 0x002c0e00, 0x00240600, 0x001f0200, 0x001d0100, 0x00160000, 0x00120000, 0x00140000, 0x00140000, 0x00100000, 0x00100000, 0x00100000, 0x00110000, 0x001a0000, 0x002a0900, 0x004c2104, 0x007b401e, 0x009c5328, 0x00ab5424, 0x00b6541e, 0x00bb5116, 0x00ba4e0d, 0x00b84c0a, 0x00b74d09, 0x00b7500c, 0x00b8500d, 0x00b85110, 0x00ba5113, 0x00ba5012, 0x00ba5012, 0x00b8510f, 0x00b6520f, 0x00b4530e, 0x00b4520d, 0x00b6520f, 0x00af5418, 0x00681f00, 0x00904818, 0x00b05418, 0x00ba520d, 0x00ba4f08, 0x00bc530b, 0x00ba5511, 0x00af571b, 0x00955124, 0x0053260a, 0x000f0000, 0x00090000, 0x001d0600, 0x006b3c1c, 0x00ab581d, 0x00ba5510, 0x00b85410, 0x00bc5810, 0x00bc5709, 0x00bc5504, 0x00c45705, 0x00c85808, 0x00c85606, 0x00bc5814, 0x00964f1f, 0x00431900, 0x000b0000, 0x00000001, 0x0000030a, 0x00050507, 0x000c0100, 0x00371703, 0x00894b2e, 0x00a4502c, 0x00ae4d21, 0x00b14c16, 0x00af4a0c, 0x00b14c0c, 0x00b54d10, 0x00b85016, 0x00b04c16, 0x00b04d15, 0x00b44f10, 0x00b45010, 0x00ac4d12, 0x00975023, 0x00301300, 0x00060000, 0x000b0000, 0x00190500, 0x004c3021, 0x00210800, 0x00080000, 0x00000000, 0x00404143, 0x00a0a4a4, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00181818, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9a9b, 0x003b3d41, 0x00000003, 0x000b0101, 0x00180000, 0x004e1600, 0x00a85a20, 0x00b85714, 0x00c85e14, 0x00ca610c, 0x00cb660d, 0x00c2620a, 0x00bb6512, 0x00b06921, 0x00783b00, 0x004a1600, 0x0079410a, 0x00b36620, 0x00bd6414, 0x00be6009, 0x00c0620d, 0x00b76011, 0x00a6611f, 0x00714518, 0x00190100, 0x000c0100, 0x000a0000, 0x00180000, 0x004a1e00, 0x008b4d20, 0x00ad6028, 0x00b45c1b, 0x00b85710, 0x00c05b0f, 0x00c35909, 0x00c15706, 0x00c25807, 0x00c45809, 0x00c05708, 0x00be560b, 0x00c3580e, 0x00c3580c, 0x00c25709, 0x00bf570a, 0x00bc5607, 0x00bf5603, 0x00bf5601, 0x00be5705, 0x00be5609, 0x00c0550c, 0x00b9581a, 0x009b4c20, 0x006a2605, 0x00480800, 0x00934a24, 0x00b9581e, 0x00c05410, 0x00be4f0e, 0x00b64e11, 0x00ac541c, 0x006d3008, 0x00200900, 0x00020000, 0x00050308, 0x000c0a10, 0x000c070a, 0x00050000, 0x00080000, 0x001b0200, 0x004f1b00, 0x00a05428, 0x00b25117, 0x00b9500e, 0x00bc5210, 0x00b65114, 0x00ac521a, 0x00813b13, 0x00310800, 0x001e0000, 0x00692b0c, 0x00a35021, 0x00b14e14, 0x00bc4f0e, 0x00c0500c, 0x00bd5110, 0x00ac4e16, 0x009f5020, 0x00874b2b, 0x002c0100, 0x001a0000, 0x00140000, 0x00330a00, 0x00854720, 0x00ae501b, 0x00b45118, 0x00a75222, 0x006a2803, 0x002a0000, 0x004e1d04, 0x009d4c1a, 0x00b45111, 0x00b5500b, 0x00b85410, 0x00af4e17, 0x00954219, 0x00370000, 0x00804123, 0x00ab501a, 0x00b8510f, 0x00b55012, 0x00af501d, 0x00924621, 0x004e1b04, 0x000f0000, 0x00030000, 0x00070000, 0x00290c01, 0x00793611, 0x00ad5220, 0x00b45318, 0x00b44c0f, 0x00bc4d14, 0x00bc4c12, 0x00bb4e0b, 0x00bc500b, 0x00b54e0c, 0x00a55220, 0x0050220b, 0x001a0000, 0x00260500, 0x00602c10, 0x00ad5627, 0x00b74c13, 0x00c04f14, 0x00b45018, 0x00965224, 0x003c1600, 0x000a0000, 0x000c0000, 0x00401000, 0x00974a22, 0x00b65019, 0x00bc4d0b, 0x00bc510c, 0x00bf540c, 0x00c5550f, 0x00b45318, 0x00783417, 0x00400700, 0x0078320d, 0x00a5562a, 0x00a85428, 0x009b4d29, 0x006c3019, 0x00300600, 0x00130000, 0x00100000, 0x000d0100, 0x00362018, 0x00744b39, 0x008f5438, 0x009f532e, 0x00a65328, 0x00a45328, 0x009e5024, 0x009a5127, 0x009b5228, 0x009c5027, 0x00984f24, 0x008c4c20, 0x0085481f, 0x007d401b, 0x006f3314, 0x005f240a, 0x004a1400, 0x00350700, 0x00250000, 0x001a0000, 0x00140000, 0x00100000, 0x00110000, 0x001b0000, 0x00300800, 0x005a2618, 0x0086452d, 0x009f5024, 0x00ac531e, 0x00b5521f, 0x00b54e19, 0x00b64d14, 0x00ba5014, 0x00b95010, 0x00b74d0c, 0x00bc4e0e, 0x00bc4f0f, 0x00b95010, 0x00b75112, 0x00b45113, 0x00b55013, 0x00b84f13, 0x00b45118, 0x008a3602, 0x00a85420, 0x00b55314, 0x00ba500c, 0x00b85009, 0x00bb530e, 0x00b95514, 0x00a9561d, 0x007b4018, 0x00341000, 0x00080000, 0x00080000, 0x002b0a00, 0x00824924, 0x00ac561c, 0x00ba5510, 0x00bb5410, 0x00bc5510, 0x00bc560c, 0x00bc550a, 0x00c0560a, 0x00c5580b, 0x00c8560b, 0x00bc5716, 0x0094481a, 0x005c2c10, 0x00140000, 0x00050000, 0x000c0000, 0x00180100, 0x00391400, 0x00874b29, 0x00a95427, 0x00a84210, 0x00bc501d, 0x00b44a13, 0x00b55217, 0x00b04f13, 0x00af480c, 0x00b04a10, 0x00ae4c16, 0x00af4e17, 0x00b04e10, 0x00b14d0d, 0x00b55012, 0x00a4511f, 0x00582e13, 0x000e0000, 0x00090000, 0x00080000, 0x000f0000, 0x000c0000, 0x00000000, 0x00101416, 0x007c7c7e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00181818, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00747371, 0x00161618, 0x00000001, 0x00050000, 0x00110000, 0x00380c00, 0x008d4a18, 0x00b55c1a, 0x00c35d10, 0x00ca6611, 0x00c4630c, 0x00bf630e, 0x00bc6c20, 0x00904f12, 0x00571f00, 0x00763a04, 0x00a45c1e, 0x00c06414, 0x00c45d06, 0x00c4600d, 0x00b85d10, 0x00ad6020, 0x00773f0f, 0x00240400, 0x00130000, 0x00100000, 0x002b0f00, 0x0071401d, 0x009c5b2b, 0x00b05b1e, 0x00bc5b14, 0x00bf570c, 0x00c55809, 0x00c45707, 0x00c55807, 0x00c45806, 0x00c45705, 0x00c55808, 0x00c25709, 0x00c0550b, 0x00c1570e, 0x00c35409, 0x00c15408, 0x00bd550a, 0x00bc570b, 0x00bd5808, 0x00bc590b, 0x00ba580d, 0x00b85710, 0x00b85412, 0x00b45820, 0x009e532a, 0x00743517, 0x00400800, 0x00804020, 0x00b1561c, 0x00c45912, 0x00c0500e, 0x00bc5011, 0x00b05116, 0x007c3a0f, 0x002c1102, 0x00040000, 0x00090204, 0x0021181c, 0x001c1314, 0x000a0000, 0x00080000, 0x00120000, 0x00310900, 0x0094542e, 0x00ae5018, 0x00b94d0c, 0x00ba4e0d, 0x00b85011, 0x00b05118, 0x008d4217, 0x00380b00, 0x001f0000, 0x0063280c, 0x009a4e23, 0x00b1521c, 0x00b94f10, 0x00be4d0c, 0x00b94807, 0x00b85011, 0x00b85921, 0x009d4b1c, 0x00884524, 0x00340300, 0x00270000, 0x004e1400, 0x0094481f, 0x00b8521b, 0x00b74d14, 0x00a95321, 0x00692804, 0x00240000, 0x00461905, 0x00944718, 0x00b04e10, 0x00b75009, 0x00b85510, 0x00a84d17, 0x008c3c14, 0x003f0000, 0x00904b28, 0x00b15114, 0x00b84f08, 0x00b45013, 0x00ab5322, 0x007c3a1a, 0x00350c00, 0x000c0000, 0x00020000, 0x000b0000, 0x00341301, 0x00984c26, 0x00b0531d, 0x00ad5018, 0x00a14008, 0x00b84e18, 0x00bb4c13, 0x00bb4d0c, 0x00bc500b, 0x00b44d0a, 0x00aa5621, 0x0056250c, 0x001e0000, 0x00290400, 0x00662f10, 0x00b3582a, 0x00b84a12, 0x00c04e13, 0x00b4501a, 0x00945324, 0x00381200, 0x000b0000, 0x000f0000, 0x00461200, 0x009c4c24, 0x00b7511a, 0x00bc4c0a, 0x00bd500a, 0x00bf540c, 0x00c55710, 0x00a84a10, 0x006e2c0f, 0x00480c00, 0x00904014, 0x00af511c, 0x00b25019, 0x00af501f, 0x00a4512d, 0x007c3c22, 0x003f1302, 0x001b0000, 0x00150100, 0x00140000, 0x002c0400, 0x005a230c, 0x00904726, 0x00a14c23, 0x00aa5221, 0x00ac521c, 0x00ad521a, 0x00b2541c, 0x00b65019, 0x00b04d15, 0x00ac5218, 0x00aa541b, 0x00a7501c, 0x00a24d1d, 0x00a35025, 0x00a0542c, 0x00954e2b, 0x00824626, 0x00673518, 0x00471f04, 0x00280700, 0x001b0000, 0x00180000, 0x00170000, 0x001c0000, 0x002b0400, 0x00542004, 0x007f3d18, 0x00a05430, 0x00aa542c, 0x00ab4c1f, 0x00b14d18, 0x00ba5113, 0x00bd500d, 0x00bd4e0a, 0x00bc4f0a, 0x00ba5010, 0x00b85014, 0x00b65014, 0x00b85014, 0x00bc4d13, 0x00ba4f14, 0x00ae5016, 0x00b25519, 0x00b34f0f, 0x00b95210, 0x00bc5410, 0x00b85310, 0x00b55415, 0x00a55620, 0x00633010, 0x001c0100, 0x00050000, 0x00090000, 0x00371000, 0x00935226, 0x00b0581c, 0x00ba5511, 0x00be5410, 0x00bc520e, 0x00bb540d, 0x00bd570e, 0x00be550c, 0x00c1550c, 0x00c8550c, 0x00c05717, 0x00a75629, 0x00662e13, 0x00180000, 0x00150000, 0x001d0000, 0x00401300, 0x00864726, 0x00a45428, 0x00ab4814, 0x00bc4f17, 0x00b44510, 0x00b54b14, 0x00ad4c15, 0x00ad4f15, 0x00b44f14, 0x00b24c14, 0x00b04f19, 0x00b15019, 0x00b04d10, 0x00b14a09, 0x00bf5110, 0x00ad5018, 0x007c4424, 0x00190000, 0x000a0000, 0x00020000, 0x00040000, 0x00040000, 0x00000206, 0x00484c50, 0x00a8a8a8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00171718, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00acacac, 0x00514e4d, 0x00070000, 0x00060000, 0x00020000, 0x00080000, 0x00200400, 0x00602b04, 0x00b86624, 0x00c05f0e, 0x00c6660e, 0x00c1640d, 0x00be6716, 0x00af621c, 0x00642800, 0x00713602, 0x009e5417, 0x00bb641b, 0x00c7600e, 0x00c85b08, 0x00c45c0f, 0x00b75b1a, 0x00853c0f, 0x003d0900, 0x00190000, 0x00200000, 0x00532200, 0x008b4b1a, 0x00ac5d23, 0x00b35714, 0x00c05a10, 0x00c75c0e, 0x00c15608, 0x00c2580c, 0x00bd580c, 0x00bc580e, 0x00bf590d, 0x00c1590c, 0x00c3580a, 0x00c45609, 0x00c45408, 0x00c35409, 0x00c55510, 0x00c45412, 0x00be5613, 0x00b95512, 0x00b75712, 0x00b45816, 0x00b05b1e, 0x00af5c25, 0x00ac5a27, 0x009c5126, 0x00844828, 0x005d2b12, 0x00300500, 0x00652c09, 0x00b45a18, 0x00c65809, 0x00c8530e, 0x00ba4b0a, 0x00b25012, 0x00974e22, 0x00331202, 0x000c0000, 0x000c0000, 0x00302222, 0x00342420, 0x00100000, 0x000a0000, 0x000c0000, 0x002a0c00, 0x00743d1e, 0x00a94f1a, 0x00bd5010, 0x00bc4f0f, 0x00b85011, 0x00b15018, 0x0095491e, 0x003e1000, 0x001c0000, 0x0058240a, 0x00944c26, 0x00ad531e, 0x00b85013, 0x00bc4e0e, 0x00be4d0d, 0x00bc4d0c, 0x00b84e0f, 0x00b24f15, 0x00a85021, 0x00833c1e, 0x00500d00, 0x00752b08, 0x00a44c1d, 0x00bc4e14, 0x00ba4c13, 0x00a74f1e, 0x00672805, 0x00220000, 0x003b1404, 0x008b4017, 0x00b35219, 0x00b54f09, 0x00b4500c, 0x00a8521f, 0x00792c06, 0x005b1400, 0x009c4e27, 0x00b44f10, 0x00bc5009, 0x00b25014, 0x00a8572a, 0x0060250c, 0x00230100, 0x00080000, 0x00070300, 0x00180700, 0x004c240c, 0x00a5552c, 0x00ae521e, 0x00a5501f, 0x006e1800, 0x00b5511e, 0x00b74c13, 0x00bc500f, 0x00b84d08, 0x00b7500c, 0x00a95520, 0x005a2a0f, 0x00220000, 0x002d0800, 0x00682f0f, 0x00af5424, 0x00ba4c13, 0x00bc4c12, 0x00b4511b, 0x00975528, 0x00330c00, 0x000a0000, 0x00100000, 0x00572007, 0x009b4720, 0x00b8521b, 0x00be4f0c, 0x00bc4e07, 0x00c3570d, 0x00c15812, 0x009f430d, 0x00571800, 0x004e1100, 0x00a54e1f, 0x00b75014, 0x00bc4f10, 0x00b5480d, 0x00b04d1d, 0x00a85028, 0x00944824, 0x00682c0f, 0x00380b00, 0x001b0000, 0x00170000, 0x001e0000, 0x00350c00, 0x00602c12, 0x008c4a22, 0x00a25421, 0x00ac511b, 0x00b34d18, 0x00b84b19, 0x00bb4c1a, 0x00b95016, 0x00b24c0f, 0x00b14e13, 0x00b25118, 0x00ad5018, 0x00ad511c, 0x00ae521e, 0x00aa4d1c, 0x00a74c1c, 0x00a34a1e, 0x0095451d, 0x00783411, 0x004e1900, 0x00270100, 0x00140000, 0x00140000, 0x001c0000, 0x002a0600, 0x0049200c, 0x007f482f, 0x009d5433, 0x00a84d20, 0x00b95115, 0x00c0500c, 0x00bc4d04, 0x00bc5007, 0x00b74d0c, 0x00b74d11, 0x00bc5117, 0x00ba4c11, 0x00ba4809, 0x00c15211, 0x00b85010, 0x00b55111, 0x00b55314, 0x00b45113, 0x00b85414, 0x00b45214, 0x00b35516, 0x00984c1b, 0x004d2207, 0x00140000, 0x00060000, 0x000c0000, 0x00431400, 0x009f5725, 0x00b3591c, 0x00b85310, 0x00bd520e, 0x00be530d, 0x00bb540f, 0x00b8540e, 0x00bc550c, 0x00c1570e, 0x00c8540d, 0x00c05516, 0x00ad5628, 0x00702f10, 0x00260000, 0x00260000, 0x004f1800, 0x0089431c, 0x00a45026, 0x00ab4c1d, 0x00b14b17, 0x00b44b14, 0x00b24815, 0x00af4b18, 0x00aa501b, 0x00aa5019, 0x00b04c13, 0x00b24c14, 0x00af4c14, 0x00b04c13, 0x00b65010, 0x00b84d08, 0x00c4500b, 0x00c05a1e, 0x00904c28, 0x00290400, 0x000e0000, 0x00000001, 0x00000001, 0x00030407, 0x00191d22, 0x00898c8f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00181819, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00888888, 0x002e2a28, 0x000d0000, 0x001c0e04, 0x0019120b, 0x00060000, 0x00130100, 0x00431b00, 0x00b06322, 0x00c26410, 0x00c2650c, 0x00b9600a, 0x00be6c1e, 0x008a4200, 0x00733500, 0x008f4c14, 0x00b15e17, 0x00c46414, 0x00c55b07, 0x00c95c08, 0x00c55b0f, 0x00ae5011, 0x007d3305, 0x004a1000, 0x003f0f00, 0x005c2809, 0x009a501e, 0x00b45d1c, 0x00bd5d18, 0x00c0580d, 0x00c75a0b, 0x00c45607, 0x00bf5203, 0x00c1590c, 0x00bf5c14, 0x00b95914, 0x00b65812, 0x00b65812, 0x00b85814, 0x00bb5915, 0x00bb5714, 0x00b85517, 0x00b85721, 0x00b45825, 0x00ad5523, 0x00a4501e, 0x00944814, 0x00803806, 0x006c2800, 0x005e1c00, 0x004f0d00, 0x00480a00, 0x003a0600, 0x00310400, 0x00220000, 0x004b1800, 0x00b45c1b, 0x00c35607, 0x00cb540c, 0x00c04e0b, 0x00b65013, 0x009f5224, 0x004b200b, 0x00180000, 0x00100000, 0x002d1a17, 0x00442c24, 0x0029130a, 0x000a0000, 0x000b0000, 0x00180400, 0x00582b10, 0x00a85122, 0x00bc5013, 0x00bc4e0e, 0x00b74e10, 0x00b14f17, 0x00994d22, 0x003f1200, 0x001d0000, 0x00532009, 0x008c4723, 0x00ac511f, 0x00b74f13, 0x00bb4d0f, 0x00bd4c0c, 0x00be4c0b, 0x00bd4c0b, 0x00ba4d0f, 0x00b24f17, 0x00a64e24, 0x0098451c, 0x00a54d1e, 0x00b04e18, 0x00bf4f13, 0x00b84d13, 0x00a14c1e, 0x005c2201, 0x001c0000, 0x00330e02, 0x00823916, 0x00b0511c, 0x00b84f0f, 0x00b44f11, 0x00a44f20, 0x00742703, 0x00712401, 0x00a75023, 0x00b84e0c, 0x00b94c06, 0x00af5119, 0x00944a21, 0x004c1a06, 0x00180000, 0x00060000, 0x00090000, 0x00260c00, 0x006c391d, 0x00a85527, 0x00a84f1c, 0x0091461b, 0x00520600, 0x00ac4e1d, 0x00b64d15, 0x00bc4f10, 0x00ba4e0c, 0x00b7500d, 0x00a95721, 0x0058290e, 0x00210000, 0x00320a00, 0x006d3111, 0x00b05322, 0x00b94c12, 0x00ba4c11, 0x00b2501b, 0x00965428, 0x00330b00, 0x00100000, 0x00140000, 0x006c3014, 0x00a24c23, 0x00b85118, 0x00ba4b08, 0x00c05209, 0x00c2580f, 0x00bd5918, 0x00903c0a, 0x00490f00, 0x005c2107, 0x00a45020, 0x00af490c, 0x00bb4b0c, 0x00be4d0e, 0x00b84c14, 0x00b04a16, 0x00a84c1a, 0x009c4c20, 0x007e3c1c, 0x0054210b, 0x002d0800, 0x001a0000, 0x001a0000, 0x00240300, 0x00441500, 0x006c3009, 0x0096481c, 0x00b15728, 0x00b85226, 0x00b04416, 0x00b84a12, 0x00b74a0d, 0x00b84d10, 0x00b85013, 0x00b44e12, 0x00b34c10, 0x00b64d14, 0x00b84d14, 0x00b94a13, 0x00b94c15, 0x00b14a16, 0x00a54b1c, 0x00974d26, 0x007d4625, 0x00502c11, 0x002b0e00, 0x00180000, 0x00170000, 0x00180000, 0x00300f00, 0x005c2a11, 0x008c4622, 0x00ad5220, 0x00b04b0c, 0x00ba510b, 0x00bb5008, 0x00b64d0c, 0x00b64d0f, 0x00b94e14, 0x00bc4e14, 0x00bd4c0d, 0x00bc4c0a, 0x00bc500b, 0x00b8500c, 0x00b45315, 0x00b25215, 0x00b45214, 0x00b25013, 0x00b05317, 0x008e4616, 0x00411c05, 0x000c0000, 0x00060000, 0x00140000, 0x004d1800, 0x00a55926, 0x00b0561b, 0x00b85412, 0x00bd520e, 0x00bd520c, 0x00b85410, 0x00b6550e, 0x00ba560c, 0x00c0580c, 0x00c8550a, 0x00c25414, 0x00b55828, 0x00803714, 0x00350300, 0x00491700, 0x008a451c, 0x00aa5628, 0x00a84c1e, 0x00aa491c, 0x00ad4f1e, 0x00ac4e1d, 0x00a14013, 0x009c3d0c, 0x00a44a18, 0x00a84e18, 0x00ae4b11, 0x00b44e14, 0x00b04c10, 0x00b75114, 0x00b44b07, 0x00c4540c, 0x00cc550d, 0x00bd5418, 0x009c5530, 0x00401804, 0x000d0000, 0x00000001, 0x00040508, 0x0004070b, 0x0064686c, 0x00b0b4b4, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00141414, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00616163, 0x00150e0a, 0x001e0800, 0x00412814, 0x003f2d1c, 0x000d0000, 0x000c0000, 0x002c0c00, 0x00a96020, 0x00c3680e, 0x00c1660a, 0x00b9640c, 0x00ad6317, 0x00743000, 0x00904807, 0x00ad5f19, 0x00bc6313, 0x00c2610c, 0x00c25e08, 0x00c45e08, 0x00c45c0c, 0x00bb5a11, 0x00a85115, 0x00954811, 0x00934b18, 0x00a55820, 0x00b85f1d, 0x00bc5c13, 0x00bc5810, 0x00c05910, 0x00c45c13, 0x00c2580c, 0x00c05508, 0x00c35b0e, 0x00bc5810, 0x00b85815, 0x00b05b1c, 0x00ac5e25, 0x00a95e2b, 0x00a15929, 0x00954c1f, 0x0088441c, 0x006f3012, 0x0061280f, 0x00531e04, 0x00441400, 0x003a0c00, 0x00340900, 0x00300400, 0x00310200, 0x00320000, 0x003c0800, 0x00401000, 0x00481c08, 0x003d1908, 0x00370700, 0x00a3521a, 0x00be5610, 0x00c8520c, 0x00c4500c, 0x00b44f11, 0x00a65424, 0x006a3215, 0x002a0600, 0x00100000, 0x00240e08, 0x00513024, 0x00492a1e, 0x000e0000, 0x000b0000, 0x000c0000, 0x003a1400, 0x00a45127, 0x00b74c15, 0x00bb4d0f, 0x00b74c0f, 0x00b04f18, 0x009d5228, 0x00411504, 0x001e0000, 0x00491904, 0x0085421f, 0x00af511c, 0x00b94c10, 0x00bc4c0e, 0x00bc4c0c, 0x00be4c0b, 0x00be4c0c, 0x00bb4d0f, 0x00b74f13, 0x00b04c14, 0x00b4531c, 0x00b35115, 0x00b14c0e, 0x00ba4c10, 0x00b14c14, 0x009b4f22, 0x00582408, 0x00150000, 0x002d0b04, 0x007b3418, 0x00ad4e21, 0x00b54c13, 0x00b55017, 0x00a24c23, 0x00701f00, 0x008f3a12, 0x00b05220, 0x00bb4e0b, 0x00b54c08, 0x00ac5520, 0x007c3916, 0x00361000, 0x00100000, 0x00090000, 0x00100000, 0x003c1400, 0x008b502c, 0x00a65224, 0x00a14d1f, 0x007c3b18, 0x003a0000, 0x00a0481b, 0x00b24f17, 0x00b94f11, 0x00bb4e10, 0x00b44f10, 0x00a55622, 0x0053270e, 0x001f0000, 0x00380e00, 0x00743516, 0x00b05221, 0x00b94c12, 0x00b84c10, 0x00af511c, 0x00945228, 0x00340800, 0x00140000, 0x001c0000, 0x00814021, 0x00a74e21, 0x00b65015, 0x00b84c07, 0x00c4570c, 0x00bf580f, 0x00b0551b, 0x00783004, 0x003c0800, 0x006b3820, 0x00a85c2f, 0x00af5119, 0x00b44e14, 0x00b44a0e, 0x00b64c10, 0x00b44e12, 0x00b15016, 0x00ac541c, 0x00a35323, 0x008f4820, 0x006e3314, 0x00502008, 0x002b0600, 0x00180000, 0x00170000, 0x002e0b00, 0x00511f04, 0x00783818, 0x009d4d26, 0x00b05426, 0x00b04c18, 0x00b74d14, 0x00b74c11, 0x00b84c12, 0x00b94e14, 0x00b84d14, 0x00b64c14, 0x00b84d18, 0x00b64c14, 0x00ba5119, 0x00b7511a, 0x00ac4d17, 0x00a8501c, 0x00a35626, 0x00914d22, 0x007a3f1b, 0x005d2a0e, 0x00391100, 0x00160000, 0x00100000, 0x00220a00, 0x00492208, 0x00793b14, 0x00a65423, 0x00ae5014, 0x00b34d0c, 0x00b5500f, 0x00b65011, 0x00b44f11, 0x00b74f12, 0x00b94f10, 0x00b84c0b, 0x00bf500c, 0x00b84e0c, 0x00b45318, 0x00b05318, 0x00b25013, 0x00b25013, 0x00ac5319, 0x00843e13, 0x00381603, 0x000a0000, 0x00070000, 0x00180100, 0x00501a00, 0x00a75b26, 0x00ac5319, 0x00b65514, 0x00ba520d, 0x00bb530c, 0x00b6550e, 0x00b4550c, 0x00b85609, 0x00bf5807, 0x00c85606, 0x00c4540e, 0x00b75520, 0x0084370e, 0x00400900, 0x005d2909, 0x009e5728, 0x00a24f1c, 0x009f471c, 0x00a7502b, 0x00984a26, 0x00823410, 0x0087320c, 0x009b4216, 0x00a24a18, 0x00a84d15, 0x00b34e13, 0x00b2480c, 0x00b04809, 0x00b84c0a, 0x00be4f06, 0x00cb580d, 0x00c8540f, 0x00bc561f, 0x00985534, 0x00381300, 0x000a0000, 0x00020202, 0x00000001, 0x003c3c3e, 0x00a4a7a8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000c0c0c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00acacae, 0x00464648, 0x00100400, 0x00381800, 0x006b4424, 0x00603f25, 0x001e0500, 0x000a0000, 0x00270a00, 0x00a05c1c, 0x00bc640d, 0x00be6508, 0x00bc6910, 0x00924900, 0x00884000, 0x00aa5911, 0x00b96114, 0x00be620c, 0x00bc5f04, 0x00c16108, 0x00c05f06, 0x00c05c07, 0x00be5c0c, 0x00bc6016, 0x00bb621b, 0x00b66019, 0x00b45c14, 0x00bc5b12, 0x00bd5911, 0x00b95914, 0x00b55816, 0x00b55818, 0x00b75919, 0x00ba5b18, 0x00b85918, 0x00b05515, 0x00a34e13, 0x008d430d, 0x007a3608, 0x00692b04, 0x005b2000, 0x004f1400, 0x00450e00, 0x003c0900, 0x00370800, 0x00330500, 0x00340900, 0x003b1300, 0x0048200a, 0x00592a12, 0x00643014, 0x00723817, 0x007f4120, 0x00884a28, 0x00844c2f, 0x00683c26, 0x00360300, 0x00813404, 0x00bb591c, 0x00c5520c, 0x00c6510c, 0x00b44c0e, 0x00ab5420, 0x0088431d, 0x00400f00, 0x00140000, 0x00180100, 0x004e2a1b, 0x00603c2c, 0x00200b05, 0x000d0000, 0x000a0000, 0x00280700, 0x00954924, 0x00b14b18, 0x00b94c11, 0x00b84d10, 0x00b04f18, 0x00a2552c, 0x00441808, 0x001f0000, 0x00411300, 0x00803f1c, 0x00af511c, 0x00ba4d0f, 0x00bc4c0c, 0x00bc4c0c, 0x00bd4b0c, 0x00bc4c0c, 0x00ba4d10, 0x00b84e12, 0x00b85010, 0x00b44b09, 0x00b54d0a, 0x00b64d0d, 0x00b54f14, 0x00ab511f, 0x008c4c26, 0x00451b02, 0x00110000, 0x002c0c04, 0x00793218, 0x00ab4d23, 0x00b44b17, 0x00b8501c, 0x00a84c23, 0x00792300, 0x00a4481b, 0x00b4501a, 0x00bb4d0c, 0x00b44c0c, 0x00a95728, 0x00642b0c, 0x00250800, 0x000c0000, 0x000e0000, 0x001f0200, 0x005b2708, 0x009f572c, 0x00a3501d, 0x009c4e22, 0x00632c11, 0x00300000, 0x00944417, 0x00b04f18, 0x00b64b10, 0x00ba4d12, 0x00b44f14, 0x009f5222, 0x004a230b, 0x001a0000, 0x003c1100, 0x007b391b, 0x00b05020, 0x00b94c11, 0x00b64c10, 0x00ac511b, 0x0093502a, 0x00340500, 0x001a0000, 0x00300800, 0x008f4824, 0x00aa4d1c, 0x00b85013, 0x00bd500c, 0x00c4560b, 0x00ba5712, 0x009c4d19, 0x005d2200, 0x00300800, 0x005c3420, 0x008d5029, 0x009f5222, 0x00ac5424, 0x00ae4e1c, 0x00af4c10, 0x00b55111, 0x00b15012, 0x00ab4d10, 0x00aa5015, 0x00ac5620, 0x009f5020, 0x0089441c, 0x00703718, 0x004e200b, 0x002c0700, 0x001d0000, 0x00210000, 0x00380b00, 0x00622b0c, 0x008c4822, 0x00a55023, 0x00b35322, 0x00b44e18, 0x00b24810, 0x00b64b10, 0x00b84d13, 0x00b64c14, 0x00b54c14, 0x00b54e18, 0x00b44f16, 0x00b44f14, 0x00b24d12, 0x00b04e14, 0x00ae5016, 0x00ac521c, 0x00a85523, 0x00954c22, 0x00783e1c, 0x00542c12, 0x002a0f00, 0x00110000, 0x00180000, 0x003e1400, 0x00763b15, 0x00a05020, 0x00ac5018, 0x00b35014, 0x00b45012, 0x00b45113, 0x00b35012, 0x00b45010, 0x00b7500f, 0x00bc500c, 0x00b64c0b, 0x00b35218, 0x00b05218, 0x00b44f11, 0x00b45214, 0x00ad541c, 0x007f3c13, 0x00341504, 0x00080000, 0x00070000, 0x00160000, 0x004b1700, 0x00a45a28, 0x00a95319, 0x00b55616, 0x00b85310, 0x00b9530d, 0x00b5540d, 0x00b45409, 0x00b85607, 0x00bf5806, 0x00c85604, 0x00c5540b, 0x00bd581d, 0x0089380c, 0x00461000, 0x005c2d0d, 0x00945424, 0x00994e1d, 0x009e4d28, 0x00944526, 0x006d290c, 0x00682204, 0x00853411, 0x00a54d24, 0x00aa4f1c, 0x00ad4c14, 0x00b54d10, 0x00b44708, 0x00ba4e0d, 0x00bb4e0b, 0x00c5570e, 0x00c3570f, 0x00bd5416, 0x00a75020, 0x00662e13, 0x001b0000, 0x000b0000, 0x00000000, 0x00181818, 0x00898989, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00949094, 0x00312e2f, 0x00100000, 0x00502405, 0x0090562e, 0x007e4824, 0x003a1000, 0x00100000, 0x00290c00, 0x00945119, 0x00b86211, 0x00bc6208, 0x00bb640c, 0x008d4000, 0x00a65610, 0x00bc6013, 0x00c05f0b, 0x00be610a, 0x00bd6006, 0x00bf6003, 0x00c06104, 0x00c06008, 0x00b95b06, 0x00b65704, 0x00b85b08, 0x00b95f0d, 0x00b85e10, 0x00b85a14, 0x00b85c1b, 0x00b56026, 0x00ac5d28, 0x009e5322, 0x00904818, 0x00833b0b, 0x00742c00, 0x006d2600, 0x00682400, 0x005c1f00, 0x00541a00, 0x00501800, 0x00541a00, 0x005c2001, 0x00622703, 0x006c2c04, 0x00723104, 0x0079380c, 0x00804015, 0x00844722, 0x008e4c26, 0x009b5023, 0x00a5531e, 0x00b0571e, 0x00ae541b, 0x00b15821, 0x00a25223, 0x00854627, 0x00490b00, 0x00621500, 0x00b65a26, 0x00c45412, 0x00c85710, 0x00b64f0c, 0x00b0541c, 0x009e4e1f, 0x00591d00, 0x00200000, 0x00120000, 0x00442011, 0x00684333, 0x003b2014, 0x000f0000, 0x000b0100, 0x001d0400, 0x007d391a, 0x00ad4e21, 0x00b74d14, 0x00b84e12, 0x00b24f17, 0x00a5562a, 0x004c1e0b, 0x00200000, 0x00380c00, 0x007b3c1d, 0x00ac521d, 0x00b84e0f, 0x00ba4c0c, 0x00bc4c0c, 0x00bc4c0c, 0x00bc4c0c, 0x00b74d12, 0x00b74f13, 0x00bc5210, 0x00b84d09, 0x00bd500c, 0x00b64f0e, 0x00ad511d, 0x009c5028, 0x0068381b, 0x00280a00, 0x000f0000, 0x002b0900, 0x00742c11, 0x00ad5025, 0x00b54e1a, 0x00b54e18, 0x00af4f1f, 0x00943808, 0x00b04d1a, 0x00b34c14, 0x00b84c0d, 0x00b04e14, 0x009c5328, 0x004c1d04, 0x00170100, 0x00080000, 0x00130000, 0x00360e00, 0x007f3d15, 0x00a65421, 0x00a4501b, 0x00964e24, 0x00461806, 0x00280000, 0x008c4518, 0x00ac5018, 0x00b44912, 0x00ba4c14, 0x00b25019, 0x0094491e, 0x003f1c08, 0x00150000, 0x003f1302, 0x00803d20, 0x00b0501d, 0x00b84e10, 0x00b44f11, 0x00ac521d, 0x00934d29, 0x00360200, 0x00220000, 0x00502008, 0x009d4d25, 0x00b04e18, 0x00b95010, 0x00c1540e, 0x00c0540a, 0x00b85818, 0x00864118, 0x003e1000, 0x001f0400, 0x002d1404, 0x004a2206, 0x0065300e, 0x00844324, 0x009b4f28, 0x00ab541e, 0x00ae5114, 0x00ad5012, 0x00b05011, 0x00b15011, 0x00b05010, 0x00b04e10, 0x00ac4f17, 0x00a44c1d, 0x00944720, 0x00723013, 0x004e1803, 0x00340800, 0x001f0000, 0x00200400, 0x00431c02, 0x0079391c, 0x009b4a25, 0x00ac5224, 0x00af4d18, 0x00b34b0e, 0x00b44c0c, 0x00b44c0d, 0x00b44f12, 0x00b24f15, 0x00b04c13, 0x00b44d13, 0x00ba5216, 0x00ba5014, 0x00b54c0e, 0x00b44c0f, 0x00b45013, 0x00ac4f11, 0x00a04e17, 0x00944c22, 0x00713819, 0x00431d07, 0x00210400, 0x001b0000, 0x00391300, 0x00793e1a, 0x009c4f23, 0x00b0511e, 0x00b04c13, 0x00b45113, 0x00b45414, 0x00af5112, 0x00b25313, 0x00b85010, 0x00b34b0c, 0x00b35117, 0x00b25014, 0x00b84e0c, 0x00b75110, 0x00ad541c, 0x007d3d14, 0x00341607, 0x00080000, 0x00050000, 0x00100000, 0x00411200, 0x00985428, 0x00aa541c, 0x00b45314, 0x00b65212, 0x00b7520f, 0x00b6530c, 0x00b65409, 0x00b85507, 0x00bf5806, 0x00c75504, 0x00c75409, 0x00c2581c, 0x008f3b0d, 0x00411100, 0x00542c12, 0x008c5930, 0x0092542c, 0x00823e20, 0x00601900, 0x00541100, 0x007e3818, 0x009c4b28, 0x00a44b20, 0x00ae4f1a, 0x00b24c10, 0x00b34608, 0x00bc4d0c, 0x00be4f0e, 0x00c05410, 0x00bc5711, 0x00b45617, 0x00a55422, 0x00743412, 0x002c0600, 0x00120000, 0x00060000, 0x00080808, 0x00666564, 0x00afaeac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00766f71, 0x00231c1c, 0x00160100, 0x00632e08, 0x00a45d2d, 0x00974e22, 0x005b2101, 0x00150000, 0x00260900, 0x007d400f, 0x00b6651c, 0x00bd640e, 0x00b75d05, 0x00a54e02, 0x00b65d14, 0x00c05e11, 0x00c25d0c, 0x00bf5e0a, 0x00c06109, 0x00c15e03, 0x00bf5e04, 0x00be5f0c, 0x00be6112, 0x00bb5f14, 0x00b85f17, 0x00b35e18, 0x00aa5815, 0x00a15014, 0x0090410c, 0x007f3403, 0x00742c00, 0x006b2700, 0x00692700, 0x006e2c02, 0x00702e03, 0x00732f01, 0x00783407, 0x007e3c10, 0x00834114, 0x00884418, 0x008c481c, 0x00944c22, 0x009b5023, 0x00a85822, 0x00ac5a1e, 0x00b0591f, 0x00af581f, 0x00a95722, 0x00aa5420, 0x00b25215, 0x00b7520f, 0x00bb5410, 0x00b7520e, 0x00bc5c1b, 0x00ac5824, 0x0090502d, 0x005c2107, 0x00480700, 0x009e4e24, 0x00bf5718, 0x00c85811, 0x00ba520d, 0x00b45214, 0x00a9501b, 0x00743008, 0x00310c00, 0x00130000, 0x00381608, 0x00654130, 0x00573425, 0x00180100, 0x00070000, 0x00160100, 0x00612409, 0x00ac532b, 0x00b54c16, 0x00bb4e11, 0x00b44d13, 0x00a75426, 0x00592812, 0x00250000, 0x002f0500, 0x0073381a, 0x00aa5220, 0x00b64e11, 0x00b84d10, 0x00ba4c0e, 0x00bc4c0c, 0x00ba4c0e, 0x00b74d14, 0x00b64d14, 0x00b64c0c, 0x00b64a08, 0x00b84c07, 0x00b24d10, 0x00a24f24, 0x00733619, 0x00341200, 0x00170400, 0x000d0000, 0x002a0800, 0x0070280a, 0x00ae5025, 0x00b4501a, 0x00b0490f, 0x00b24c14, 0x00af4c12, 0x00b65015, 0x00b44c10, 0x00b84d13, 0x00ae501b, 0x00884721, 0x003b1300, 0x000d0000, 0x00070000, 0x00170000, 0x004e1d04, 0x009c4c1d, 0x00ab5118, 0x00a7531c, 0x008f4c24, 0x002e0700, 0x00220000, 0x0089471c, 0x00aa5118, 0x00b44a14, 0x00b84c18, 0x00b3511f, 0x00843c14, 0x00301200, 0x00120000, 0x00421605, 0x00854122, 0x00ae4f1a, 0x00b84e0f, 0x00b25010, 0x00aa531d, 0x00924c2c, 0x00380000, 0x00270000, 0x006f3418, 0x00a34e20, 0x00b44f14, 0x00ba500e, 0x00c2560e, 0x00c0540c, 0x00b1571a, 0x006c3110, 0x00200000, 0x000c0000, 0x00080000, 0x00180300, 0x00280800, 0x00431707, 0x005d260f, 0x007c3b14, 0x00904416, 0x00a35120, 0x00ad5420, 0x00b15018, 0x00b34e11, 0x00b54d0f, 0x00b64e10, 0x00ad480d, 0x00b1511f, 0x00a44e24, 0x008c4221, 0x006f341a, 0x00431801, 0x001e0100, 0x001b0000, 0x00380b00, 0x0064290f, 0x00904721, 0x00a75222, 0x00b15018, 0x00b34d10, 0x00b24c0f, 0x00b44f12, 0x00af4c10, 0x00b14e13, 0x00b55012, 0x00b64d0f, 0x00b5480a, 0x00b54808, 0x00b74a0c, 0x00b84d0e, 0x00b85110, 0x00ae4c0f, 0x00ab4f1c, 0x00a35228, 0x0087482a, 0x005c2d15, 0x00331000, 0x00280400, 0x00441100, 0x007b3815, 0x00a75325, 0x00b0521c, 0x00b15014, 0x00b15011, 0x00b05011, 0x00b25214, 0x00b45012, 0x00b24c0f, 0x00b35014, 0x00b44f10, 0x00bb4c06, 0x00b84e0a, 0x00ac531a, 0x007e4019, 0x00351809, 0x00090000, 0x00050000, 0x000c0000, 0x00360e00, 0x00864821, 0x00ac5620, 0x00b25012, 0x00b55014, 0x00b85014, 0x00b8500d, 0x00b85108, 0x00b85406, 0x00be5706, 0x00c75507, 0x00c7540b, 0x00c05519, 0x008c380c, 0x003b0f00, 0x004b2e1b, 0x00764f2f, 0x0064300e, 0x004e0f00, 0x004d0800, 0x00782f0e, 0x00984c25, 0x00a8512c, 0x00a6481d, 0x00ac4911, 0x00b4490c, 0x00b94808, 0x00c04e0c, 0x00be4f0c, 0x00bf5817, 0x00b45a1c, 0x00a25822, 0x006d3310, 0x00350d00, 0x00120000, 0x00060000, 0x00040203, 0x004c4e4d, 0x00aaa9a8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005d5053, 0x00170e0c, 0x00270e00, 0x00773a10, 0x00b05f28, 0x00a9511f, 0x007c330f, 0x001f0000, 0x001f0100, 0x00652d04, 0x00b06628, 0x00bd6615, 0x00ba5c04, 0x00c25d0b, 0x00c05b0f, 0x00be5d16, 0x00bf5c15, 0x00c05c0c, 0x00c25c06, 0x00c55c06, 0x00bc5704, 0x00b85810, 0x00b4591c, 0x00a3501d, 0x008e4318, 0x007b380f, 0x006d2f08, 0x00602400, 0x005c1f00, 0x005e1c00, 0x00682400, 0x00762d01, 0x00823608, 0x008f4211, 0x009c4e18, 0x00aa5820, 0x00ae591e, 0x00b35a1b, 0x00b55818, 0x00b55614, 0x00b65516, 0x00b75518, 0x00b85618, 0x00b55411, 0x00b95410, 0x00c05510, 0x00c25512, 0x00be5517, 0x00bc5415, 0x00c0520c, 0x00c1530c, 0x00b8510c, 0x00b15412, 0x00ac581b, 0x00985322, 0x00744428, 0x004a2210, 0x002d0100, 0x006e3213, 0x00b4571c, 0x00c3570f, 0x00c0540d, 0x00b8510f, 0x00ae5016, 0x008e4318, 0x00481d04, 0x00180000, 0x00270a00, 0x00583728, 0x006c442e, 0x00331500, 0x00050000, 0x00100000, 0x00481100, 0x00a7532f, 0x00b34c18, 0x00ba4d10, 0x00b54c10, 0x00a8501e, 0x00693218, 0x002a0400, 0x00240000, 0x00663116, 0x00a45224, 0x00b04e16, 0x00b44e14, 0x00b84d11, 0x00bc4c0c, 0x00bc4c0c, 0x00b84c12, 0x00b64d14, 0x00b85016, 0x00b84e12, 0x00b74b0a, 0x00b3501a, 0x008c4322, 0x00461504, 0x00100000, 0x000b0000, 0x00100100, 0x003c1804, 0x007c3410, 0x00ae5120, 0x00b15015, 0x00b04a09, 0x00b54d08, 0x00b9500c, 0x00b84e0f, 0x00b64c11, 0x00b84f17, 0x00ab5020, 0x00723616, 0x002c0b00, 0x00050000, 0x00060000, 0x00240500, 0x006b3014, 0x00a8511c, 0x00b04f11, 0x00a45118, 0x0084451f, 0x00210000, 0x001f0000, 0x0086481d, 0x00a75118, 0x00b44c15, 0x00b84b19, 0x00b05020, 0x00712c08, 0x00240800, 0x00100000, 0x00451909, 0x00894526, 0x00ad4e19, 0x00b74e0e, 0x00b0500f, 0x00a8521e, 0x00924a2c, 0x003b0000, 0x00360000, 0x00884525, 0x00a74c19, 0x00b74e10, 0x00bf540e, 0x00c0540c, 0x00c35810, 0x009e480e, 0x004e1e03, 0x00120000, 0x00040000, 0x00000000, 0x00050200, 0x00080000, 0x00130000, 0x001c0000, 0x00300a00, 0x004c1e0b, 0x0071341c, 0x008c4022, 0x009e4820, 0x00ac4d1f, 0x00b04e18, 0x00af4a0f, 0x00b34e11, 0x00b04c11, 0x00ae4c15, 0x00a94e1e, 0x00a15028, 0x008a4424, 0x005f270a, 0x00340b00, 0x00180000, 0x00280c00, 0x00542305, 0x00813c15, 0x00a1481c, 0x00b04c19, 0x00b34d16, 0x00b24c13, 0x00b24d12, 0x00b34e10, 0x00b44d0c, 0x00b44c0a, 0x00b84f0d, 0x00ba5111, 0x00b64e12, 0x00b04910, 0x00b34c15, 0x00b8511b, 0x00b44d17, 0x00ac4a14, 0x00a74c20, 0x009a4c26, 0x0077371c, 0x004c1500, 0x00380400, 0x00551e00, 0x00884119, 0x00a85422, 0x00b04f16, 0x00b24a0c, 0x00b74e10, 0x00b74f12, 0x00b44f14, 0x00b14e13, 0x00b55012, 0x00b84c0b, 0x00c04c02, 0x00bb4c06, 0x00ab5219, 0x00844621, 0x003b1d0f, 0x000b0000, 0x00040000, 0x00080000, 0x00290b00, 0x006e3715, 0x00a95520, 0x00b45013, 0x00b64f18, 0x00b84f15, 0x00bb4f0e, 0x00ba4f08, 0x00b95409, 0x00be560b, 0x00c5540b, 0x00c5540f, 0x00c4561c, 0x008a350d, 0x00350f00, 0x00382318, 0x00482912, 0x003a0f00, 0x00460900, 0x00772c12, 0x00a55026, 0x00a44818, 0x00a9491f, 0x00af4c1d, 0x00b0480e, 0x00ba4a0b, 0x00c5500e, 0x00c34e0c, 0x00c45716, 0x00b85819, 0x009c511c, 0x00703a13, 0x002c0b00, 0x000c0000, 0x00070000, 0x0008090b, 0x00404446, 0x009fa2a3, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00807879, 0x004a3a3c, 0x000f0000, 0x00381804, 0x008c4414, 0x00b85c20, 0x00b5531b, 0x008f3e13, 0x002a0200, 0x001a0000, 0x00502101, 0x00a86530, 0x00b56214, 0x00be5e06, 0x00c65f0c, 0x00c45c0d, 0x00c15e18, 0x00bd5a14, 0x00c45d0e, 0x00c25906, 0x00c55c08, 0x00c0590a, 0x00bb5917, 0x00a74d18, 0x007b2c05, 0x00571300, 0x004f1000, 0x00501500, 0x005b2000, 0x006d2f08, 0x00864114, 0x009c4f1e, 0x00ac5823, 0x00b15820, 0x00b3581d, 0x00b75a1c, 0x00b75818, 0x00b85612, 0x00bc540e, 0x00bf540a, 0x00c2540b, 0x00c2540b, 0x00c1530c, 0x00be510b, 0x00bf520c, 0x00c0520c, 0x00c45008, 0x00c44f0b, 0x00be5010, 0x00bb5214, 0x00bb5212, 0x00b65415, 0x00a85019, 0x00974c1a, 0x007a3a10, 0x005c2c0b, 0x003b1c0a, 0x00230c00, 0x00160000, 0x00441400, 0x00aa5724, 0x00bd5613, 0x00c15810, 0x00bc530c, 0x00b55010, 0x00a5511d, 0x005e2a0a, 0x00260400, 0x00190000, 0x004a2c20, 0x00784c31, 0x004d280d, 0x00080000, 0x000d0000, 0x00370700, 0x009c502e, 0x00b04d1a, 0x00b94c10, 0x00b74a0f, 0x00aa4f1d, 0x0073391b, 0x002d0700, 0x001e0000, 0x005c2b14, 0x00a15226, 0x00af4d18, 0x00b34d14, 0x00b64e12, 0x00bb4d0f, 0x00bc4c0f, 0x00b94c11, 0x00b84c14, 0x00b54b14, 0x00b64d15, 0x00b54d10, 0x00ac501e, 0x00703114, 0x002e0800, 0x00110200, 0x00080000, 0x00200800, 0x005c2c13, 0x0095451e, 0x00b35320, 0x00b04d14, 0x00b65010, 0x00b85009, 0x00b64b05, 0x00b84c0b, 0x00b54d11, 0x00b24e18, 0x00a35024, 0x005c2a0e, 0x001f0600, 0x00060000, 0x000b0000, 0x003b1402, 0x0084431f, 0x00ac5119, 0x00b25014, 0x009d4c17, 0x00783d19, 0x00190000, 0x001b0000, 0x00844820, 0x00a55019, 0x00b54c18, 0x00b54a18, 0x00a85023, 0x005e2200, 0x00190200, 0x000e0000, 0x00481b0b, 0x008d4727, 0x00ae4c18, 0x00b74c0f, 0x00b04e10, 0x00a8501e, 0x0094482a, 0x00400000, 0x00510d00, 0x00a0522e, 0x00ac4d15, 0x00b8500c, 0x00c3580e, 0x00bd560c, 0x00bc5a15, 0x00853600, 0x003f1000, 0x001b0300, 0x000f0400, 0x00050300, 0x00000100, 0x00020000, 0x00090003, 0x00080000, 0x000f0000, 0x00130000, 0x00280200, 0x004c1808, 0x00743119, 0x00904220, 0x00a04c20, 0x00ac511f, 0x00b04f16, 0x00ae4b10, 0x00b44e14, 0x00b24e18, 0x00aa4a1a, 0x00a85026, 0x00984922, 0x006c3112, 0x00351500, 0x00180000, 0x00200000, 0x004c1900, 0x007f3917, 0x00a04b23, 0x00ae4d21, 0x00af4816, 0x00b44b14, 0x00b44c10, 0x00b44e0d, 0x00b34f0c, 0x00b24d0a, 0x00b04b0c, 0x00b44b13, 0x00b54c18, 0x00b24a18, 0x00b44d19, 0x00b4490f, 0x00b84e12, 0x00b64c13, 0x00ae4c1a, 0x00a24e28, 0x00874022, 0x005e2208, 0x00480f00, 0x00652400, 0x00984c1d, 0x00ac501b, 0x00b24d10, 0x00ba500f, 0x00b74c0d, 0x00b44f14, 0x00b24f15, 0x00b85014, 0x00b94d0c, 0x00c14f05, 0x00b94c06, 0x00ad511c, 0x008c4b25, 0x00442213, 0x000f0100, 0x00040000, 0x00060000, 0x001e0700, 0x005a2a0d, 0x00a65423, 0x00b45116, 0x00b64f18, 0x00b84f15, 0x00b84e0f, 0x00b84f0b, 0x00b9510b, 0x00c0550c, 0x00c7540b, 0x00c5540f, 0x00c3591e, 0x0083330b, 0x002a0800, 0x00180600, 0x001f0000, 0x00401200, 0x006f2e17, 0x009c4d2e, 0x00a64a1c, 0x00ac4914, 0x00ad4916, 0x00b34915, 0x00b84b0c, 0x00c0500c, 0x00c55410, 0x00c25615, 0x00b7561c, 0x009d4f1c, 0x0069310a, 0x002c0900, 0x000f0000, 0x00080405, 0x00070707, 0x003f4241, 0x00a0a4a6, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a59ca0, 0x00403232, 0x00100000, 0x004c240b, 0x009f4b14, 0x00c25814, 0x00be5515, 0x009a4514, 0x00431700, 0x00180000, 0x002c0800, 0x00976137, 0x00b06117, 0x00bf620b, 0x00bc5c0b, 0x00c05f10, 0x00c25d0d, 0x00be5908, 0x00c15d08, 0x00bc5904, 0x00bf5c09, 0x00bc5a0d, 0x00b65513, 0x00973e05, 0x006c1e00, 0x005f1a00, 0x0073310b, 0x00874116, 0x00a75826, 0x00ae581f, 0x00b3581c, 0x00b85716, 0x00bc5512, 0x00c0540f, 0x00c0540d, 0x00c1540e, 0x00be530f, 0x00bc510d, 0x00bc510c, 0x00be530c, 0x00c0540d, 0x00c0540c, 0x00c0530c, 0x00c0530c, 0x00c0530e, 0x00be4f0c, 0x00c15010, 0x00c05316, 0x00b35018, 0x00a8511d, 0x00994c1c, 0x0084401b, 0x006a3217, 0x004d200e, 0x002b0c00, 0x00140000, 0x00090000, 0x00080000, 0x00100000, 0x00250000, 0x008d441b, 0x00b4551c, 0x00bd5815, 0x00c0570f, 0x00be510c, 0x00ad4d10, 0x00833f14, 0x00441700, 0x00140000, 0x0040221c, 0x007c482c, 0x006c3d1d, 0x00100300, 0x00080000, 0x00260000, 0x00904d2d, 0x00ab4f1b, 0x00b64b10, 0x00b84a16, 0x00ab4d22, 0x00793f1e, 0x00330d00, 0x001a0000, 0x004d220d, 0x0098481f, 0x00b34f19, 0x00b55015, 0x00b55012, 0x00b84d10, 0x00b84c0f, 0x00bb4c12, 0x00bb4c13, 0x00ba4c16, 0x00b44b14, 0x00b04f14, 0x00a85826, 0x005c270c, 0x00200100, 0x000d0000, 0x00140000, 0x00471a04, 0x008d4727, 0x00ab4d23, 0x00b44a18, 0x00b64f18, 0x00b14b10, 0x00b64c10, 0x00b84e10, 0x00b74c0f, 0x00b24c10, 0x00ac4e16, 0x009b5228, 0x00401d06, 0x00100000, 0x00100000, 0x00190000, 0x005e2a0c, 0x00974e22, 0x00ac511f, 0x00aa4e1a, 0x00994f21, 0x00612d0d, 0x00110000, 0x00190000, 0x00814422, 0x00a8501f, 0x00b34712, 0x00b44c18, 0x009a4f25, 0x00461800, 0x00110000, 0x00100000, 0x004a1c07, 0x00924926, 0x00af4d19, 0x00b4490f, 0x00b64f1a, 0x00aa4e20, 0x00934523, 0x00480000, 0x00843010, 0x00aa4d24, 0x00b14f11, 0x00bd560c, 0x00be5807, 0x00b8580c, 0x00a85516, 0x00682400, 0x00431000, 0x004d2414, 0x0039180a, 0x00190200, 0x000b0100, 0x00040200, 0x00000000, 0x00000001, 0x00000000, 0x00060000, 0x000a0000, 0x00120000, 0x00280600, 0x004b1d08, 0x00763819, 0x00954a21, 0x00a85021, 0x00ae501b, 0x00ae4c15, 0x00af4914, 0x00b14d18, 0x00b24f1c, 0x00ad4d1b, 0x00a24f23, 0x007a3f20, 0x00441c03, 0x00220200, 0x001b0000, 0x003e1300, 0x0073371d, 0x009d4828, 0x00b04b23, 0x00b44718, 0x00ba4e18, 0x00b35013, 0x00ac4f0c, 0x00af5210, 0x00b14f10, 0x00b44710, 0x00b64815, 0x00b34b19, 0x00b24c17, 0x00b54c10, 0x00b64c0b, 0x00b64c0a, 0x00b34d0e, 0x00ab5018, 0x00a45122, 0x00944b25, 0x00702c09, 0x00601a00, 0x007d3209, 0x00a65120, 0x00b1541a, 0x00b04c08, 0x00b6500a, 0x00b44e10, 0x00b34c12, 0x00b54c14, 0x00b74d11, 0x00b85009, 0x00b64f0c, 0x00ad4c19, 0x009b4d2b, 0x00512611, 0x00130000, 0x00060000, 0x00080100, 0x00140100, 0x00461d04, 0x00a4582c, 0x00b05218, 0x00b55014, 0x00b55111, 0x00b35013, 0x00b45010, 0x00bc500b, 0x00c45309, 0x00cb5406, 0x00c7560c, 0x00ba591a, 0x007c360b, 0x001d0000, 0x00180300, 0x00350d00, 0x0070361c, 0x00974a2a, 0x00a44d28, 0x00a34618, 0x00b14f19, 0x00b34910, 0x00bc4c0c, 0x00c7540e, 0x00c5540c, 0x00c05814, 0x00b3591e, 0x008f4a1c, 0x005a2809, 0x002a0c00, 0x00110100, 0x00050000, 0x000c0808, 0x0049443d, 0x00a3a098, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00928d8f, 0x00372827, 0x00130000, 0x0057280c, 0x00ad5218, 0x00c4540c, 0x00c45412, 0x00ac531c, 0x005d2c0c, 0x00160000, 0x00240500, 0x00724422, 0x00ac601e, 0x00b85d0c, 0x00be6011, 0x00be5c0d, 0x00c15c09, 0x00c05a04, 0x00c15f0c, 0x00bc5b07, 0x00bd5c09, 0x00bc5a0d, 0x00b6550e, 0x00a74b0b, 0x00984610, 0x00a0511f, 0x00ac5e28, 0x00af5d22, 0x00b05616, 0x00b75711, 0x00bc5810, 0x00c0570e, 0x00c3550a, 0x00c25307, 0x00c15007, 0x00c05008, 0x00c15410, 0x00c05410, 0x00bf540e, 0x00bd520c, 0x00bc510a, 0x00bb520c, 0x00bb530e, 0x00b85412, 0x00b75718, 0x00b0531b, 0x00ac501d, 0x00a04b1c, 0x008c4419, 0x00763814, 0x00552406, 0x00330b00, 0x00200000, 0x00110000, 0x000a0000, 0x00070004, 0x00030000, 0x000c0300, 0x001a0400, 0x00200000, 0x00551600, 0x00ab5728, 0x00b85618, 0x00c2560e, 0x00bf4f08, 0x00b7500f, 0x009f4c18, 0x00672b0b, 0x00250100, 0x0034120d, 0x00743c21, 0x00764220, 0x00281500, 0x000d0000, 0x00210000, 0x00814628, 0x00a7501c, 0x00b44c10, 0x00b84a18, 0x00ac4c22, 0x00844422, 0x00381100, 0x00160000, 0x00411b08, 0x008d3f19, 0x00b04d1a, 0x00b04d14, 0x00b44e10, 0x00b54d10, 0x00b64c10, 0x00b84c10, 0x00b84a10, 0x00b94a13, 0x00b44b13, 0x00ac5015, 0x00a05524, 0x00502007, 0x001b0000, 0x000d0000, 0x00240800, 0x00682d11, 0x00a04e27, 0x00b44f20, 0x00b84a18, 0x00b84e18, 0x00b44b11, 0x00b64c13, 0x00b54c10, 0x00b84b10, 0x00b14b10, 0x00ac521d, 0x00884820, 0x002d1401, 0x000d0000, 0x00130000, 0x00340e00, 0x00753710, 0x00a15121, 0x00ae501f, 0x00a84e20, 0x00914b23, 0x00512305, 0x00100000, 0x00150000, 0x00783c1c, 0x00a44d20, 0x00b54b17, 0x00b14d1a, 0x008b461f, 0x003a1100, 0x000e0000, 0x000e0000, 0x004c1c05, 0x00934a26, 0x00ae4c18, 0x00b64b10, 0x00b74d19, 0x00ae4c1c, 0x00a04b23, 0x006f1b00, 0x00ac4d25, 0x00b04918, 0x00be5210, 0x00c05509, 0x00c05b0d, 0x00b25912, 0x00853e09, 0x00490c00, 0x00581d00, 0x00884e34, 0x00834a32, 0x004c1d0a, 0x001f0400, 0x00090000, 0x00020000, 0x00000000, 0x00000103, 0x00040406, 0x00000001, 0x00030000, 0x000c0000, 0x00130000, 0x002d0700, 0x005f2a0f, 0x00884420, 0x009e4d20, 0x00ac5220, 0x00b04e18, 0x00b34d18, 0x00b44c16, 0x00b44b14, 0x00ab4b18, 0x009f4f25, 0x008a4c2b, 0x00461a01, 0x00240300, 0x001f0000, 0x00380c00, 0x006c2c14, 0x009c4829, 0x00ad4d24, 0x00ab4714, 0x00ac4b10, 0x00b05314, 0x00ab4d0e, 0x00ac490c, 0x00bc4e16, 0x00be4f1b, 0x00b44b18, 0x00b24c17, 0x00b44c10, 0x00b54c0c, 0x00b54d08, 0x00b44d0a, 0x00b04f10, 0x00ab5018, 0x00a45021, 0x0099481f, 0x00873710, 0x007f2e04, 0x00913a0b, 0x00aa4f17, 0x00b45314, 0x00b24d0a, 0x00b44e10, 0x00b34c12, 0x00b44c15, 0x00b54c13, 0x00b4500c, 0x00b45010, 0x00b04c1b, 0x00a04e2a, 0x005d2a14, 0x001b0000, 0x00080000, 0x00060000, 0x00100000, 0x003f1904, 0x009e552b, 0x00ad5018, 0x00b45012, 0x00b5500f, 0x00b25013, 0x00b45010, 0x00bd500a, 0x00c65407, 0x00cb5404, 0x00c5560a, 0x00ae5114, 0x00803c10, 0x00280200, 0x00351306, 0x00743b21, 0x009d542e, 0x00a44c1f, 0x00a84714, 0x00ad4713, 0x00b34a10, 0x00bc500f, 0x00c35611, 0x00c1540e, 0x00bc5814, 0x00ac561c, 0x00833f11, 0x00562809, 0x001b0000, 0x000a0000, 0x00030000, 0x000e0c0d, 0x00464544, 0x009d9994, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007c7778, 0x002a1c1a, 0x00180000, 0x00623013, 0x00b5581c, 0x00c35208, 0x00c55510, 0x00b75921, 0x0078411d, 0x001d0000, 0x001d0000, 0x00431b00, 0x00a8602c, 0x00b45c14, 0x00c15f12, 0x00c05a09, 0x00c25b09, 0x00bf5a08, 0x00bd5c0c, 0x00bc5b0c, 0x00be5908, 0x00c05b09, 0x00bc590b, 0x00b6560a, 0x00b55710, 0x00bb5c16, 0x00bb5a11, 0x00b65408, 0x00b8590e, 0x00b8590c, 0x00b8580c, 0x00b9550b, 0x00bb5509, 0x00bc560c, 0x00bc5810, 0x00bc5914, 0x00b4520e, 0x00b85411, 0x00bc540e, 0x00bc540c, 0x00bf540c, 0x00bc5410, 0x00b65516, 0x00aa541b, 0x00944d1d, 0x00854b22, 0x00764020, 0x00582a12, 0x00341000, 0x001b0100, 0x00140000, 0x00100000, 0x000c0000, 0x000c0000, 0x00060000, 0x00050000, 0x000c0000, 0x001a0500, 0x00341000, 0x004c1d05, 0x00340000, 0x008c4520, 0x00b65417, 0x00c5560d, 0x00c4540e, 0x00b9500e, 0x00ad4c12, 0x00873a11, 0x00421308, 0x002c0200, 0x00682c12, 0x00844c2d, 0x00462b15, 0x00130000, 0x00210000, 0x00753c24, 0x00a4501c, 0x00b04c0e, 0x00b84b13, 0x00ae4c1c, 0x00904d28, 0x00421700, 0x00140000, 0x00341000, 0x007e3414, 0x00ae4f20, 0x00af4c16, 0x00b44f12, 0x00b34e10, 0x00b44e10, 0x00b64c11, 0x00b64b10, 0x00b84a10, 0x00b44c10, 0x00ad5014, 0x009a5220, 0x00441900, 0x00150000, 0x00100000, 0x00381804, 0x007f411e, 0x00a55124, 0x00b34c1a, 0x00b74913, 0x00b74d12, 0x00b54c10, 0x00b84f10, 0x00b54b0d, 0x00bb4c10, 0x00b24b14, 0x00a95528, 0x006e3514, 0x001f0800, 0x000c0000, 0x00140000, 0x004e2009, 0x008d471f, 0x00aa5221, 0x00b04c1c, 0x00aa4d20, 0x008c4621, 0x003f1400, 0x000d0000, 0x00130000, 0x006c3612, 0x00a04c1c, 0x00b44c18, 0x00b04d1e, 0x00874420, 0x003c1300, 0x00100000, 0x000e0000, 0x004d200a, 0x00944e29, 0x00a94d18, 0x00b54c10, 0x00b54a10, 0x00b24913, 0x00af4f1e, 0x009e400e, 0x00b4501b, 0x00b4470a, 0x00c8500a, 0x00c8540a, 0x00bc5812, 0x00a8571d, 0x00622000, 0x004e0f00, 0x007f371b, 0x00954728, 0x00a25430, 0x00924c2f, 0x005b2a1b, 0x00280a01, 0x00120200, 0x00050000, 0x00060103, 0x00000003, 0x00020003, 0x00060205, 0x00030000, 0x00050000, 0x00110400, 0x001c0300, 0x004b2209, 0x00743a18, 0x00994d1f, 0x00a84f1c, 0x00ae4c16, 0x00b04b15, 0x00b04c19, 0x00b14e1c, 0x00ae4c1a, 0x00a64f20, 0x0098532a, 0x00562202, 0x002a0400, 0x001c0000, 0x00350f00, 0x00633018, 0x00914c27, 0x00a75423, 0x00aa4c15, 0x00af4c12, 0x00b44f16, 0x00b0490f, 0x00b3490e, 0x00b44b10, 0x00b54b14, 0x00b44c15, 0x00b44c14, 0x00b34c12, 0x00b34c10, 0x00b14c10, 0x00b04c13, 0x00af4c16, 0x00b04f1b, 0x00b2501e, 0x00ab4819, 0x009c3909, 0x009a3806, 0x00a94814, 0x00b3511c, 0x00b04d15, 0x00b34c12, 0x00b44c12, 0x00b44c14, 0x00b44c12, 0x00b34d0c, 0x00b34e10, 0x00b04e1c, 0x00a5512c, 0x00683018, 0x00230500, 0x00080000, 0x00040000, 0x000f0000, 0x00391300, 0x009c5328, 0x00ad4f17, 0x00b44d11, 0x00b74e10, 0x00b44f10, 0x00b7500d, 0x00bd5108, 0x00c45507, 0x00c85608, 0x00c1570e, 0x00b25920, 0x00722a02, 0x00340000, 0x00682f17, 0x00a05028, 0x00aa4b14, 0x00ae4408, 0x00b94808, 0x00c14c0a, 0x00c85510, 0x00c0540d, 0x00b95611, 0x00b35b1c, 0x009c511e, 0x00713811, 0x00431800, 0x00140000, 0x000e0000, 0x00060200, 0x00131414, 0x00454a4a, 0x00a7acac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00686566, 0x00221412, 0x001f0500, 0x006d3918, 0x00b85a1b, 0x00c75409, 0x00c8570f, 0x00b8571b, 0x008d4d23, 0x00381000, 0x00190000, 0x00230000, 0x008c4f24, 0x00b15c20, 0x00be5b0e, 0x00c45905, 0x00c35c08, 0x00bf5a08, 0x00ba580c, 0x00bc5a0f, 0x00bc5608, 0x00be5808, 0x00bd5a0c, 0x00be5c0d, 0x00bd5c0c, 0x00bb5606, 0x00be5403, 0x00c35808, 0x00bc5607, 0x00bb5809, 0x00bc580c, 0x00bc590e, 0x00ba5910, 0x00b85810, 0x00b35612, 0x00af5514, 0x00b05818, 0x00b25819, 0x00b25518, 0x00af5216, 0x00aa5118, 0x00a14f1a, 0x0092481a, 0x007e411a, 0x00572b0c, 0x00341500, 0x00190000, 0x000f0000, 0x000a0000, 0x00050000, 0x00030000, 0x00030000, 0x00090300, 0x00060000, 0x000a0000, 0x00140200, 0x00290c00, 0x0060351c, 0x008c5430, 0x008b4f2d, 0x00360200, 0x00551800, 0x00a95019, 0x00be5611, 0x00c65713, 0x00c2530f, 0x00b9500e, 0x00a24a18, 0x00642814, 0x00350300, 0x00591a01, 0x008c5236, 0x005c3b27, 0x00170000, 0x00230000, 0x00703823, 0x00a2501f, 0x00af4c0e, 0x00b84c10, 0x00ae4c16, 0x009c5229, 0x004c1c00, 0x00140000, 0x00250400, 0x006e2c10, 0x00a85028, 0x00ae4c18, 0x00b14e13, 0x00b04e10, 0x00b14f10, 0x00b44e14, 0x00b54c12, 0x00b64c10, 0x00b44e10, 0x00ac5016, 0x00975020, 0x003c1500, 0x00140000, 0x00130000, 0x004d2910, 0x008e4c24, 0x00a8501d, 0x00b04b14, 0x00b4490f, 0x00b54b0d, 0x00b54b0c, 0x00b84f0f, 0x00b54b0c, 0x00ba4c11, 0x00b24e1b, 0x009c522c, 0x00502108, 0x00180400, 0x000c0000, 0x00240300, 0x00683115, 0x009e5026, 0x00ae501e, 0x00b34918, 0x00ae4d23, 0x00874322, 0x00300700, 0x000b0000, 0x00100000, 0x0064300c, 0x009d4f1c, 0x00af4b18, 0x00ad4c1f, 0x00904929, 0x00461803, 0x00140000, 0x00130000, 0x004d1c05, 0x00924c25, 0x00a74c16, 0x00b44e10, 0x00b74c10, 0x00b6480f, 0x00b64d15, 0x00b54f14, 0x00b24909, 0x00c0520c, 0x00cc540b, 0x00c8510b, 0x00b65820, 0x00863b11, 0x00480b00, 0x0060200a, 0x00974424, 0x00ab4c24, 0x00ab4a1e, 0x00a64c26, 0x00954e34, 0x006b3422, 0x00371200, 0x00110000, 0x000a0000, 0x000a0104, 0x00060001, 0x00020001, 0x00010004, 0x00030206, 0x00000000, 0x00060000, 0x00100000, 0x00391400, 0x0067300e, 0x00874018, 0x009c4b1e, 0x00a44d20, 0x00a54e20, 0x00a84e20, 0x00ae4e1c, 0x00aa4c18, 0x009a4515, 0x00944d25, 0x005b290c, 0x002b0800, 0x00180000, 0x00270a00, 0x005a2c0e, 0x0091512a, 0x00a75020, 0x00ab4813, 0x00b54c16, 0x00b54c12, 0x00b44c10, 0x00b24a0d, 0x00b54c12, 0x00b54b14, 0x00b44c15, 0x00b34c15, 0x00b14c14, 0x00b14c14, 0x00b24b14, 0x00b24b14, 0x00b44b13, 0x00b34811, 0x00b54b15, 0x00b44a16, 0x00ad4612, 0x00af4816, 0x00b04d1c, 0x00b04c18, 0x00b34c14, 0x00b44c12, 0x00b44c14, 0x00b44c12, 0x00b34d0c, 0x00b24d10, 0x00b04e1c, 0x00a6522c, 0x0071351c, 0x002e0a00, 0x00090000, 0x00030000, 0x000e0000, 0x00350f00, 0x009d5228, 0x00b2511a, 0x00b54c13, 0x00b74c10, 0x00b74c0d, 0x00b84e0a, 0x00bd5108, 0x00c45507, 0x00c55708, 0x00be5714, 0x009f4b17, 0x006c2300, 0x00511000, 0x00904724, 0x00ab4c17, 0x00b44807, 0x00bf4f09, 0x00c7540e, 0x00c4510c, 0x00c25510, 0x00b55414, 0x00a6541b, 0x008b491b, 0x00562502, 0x00250400, 0x00110000, 0x000f0300, 0x00030000, 0x001c1c1e, 0x005a5e60, 0x00adb4b5, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005c595a, 0x001c0e0b, 0x00270b00, 0x00743e18, 0x00bb5c1a, 0x00ca5709, 0x00cb570c, 0x00bc5615, 0x00a05724, 0x005b2c08, 0x00150000, 0x00140000, 0x00572402, 0x00a25820, 0x00bc5a0b, 0x00c65b00, 0x00c15901, 0x00c15c09, 0x00bc580d, 0x00bd5911, 0x00c15a10, 0x00bd580d, 0x00b6570d, 0x00b7590f, 0x00b9580e, 0x00b8540a, 0x00bd530a, 0x00c7580f, 0x00c25307, 0x00c05205, 0x00bc5208, 0x00b9530c, 0x00b75511, 0x00b45616, 0x00b05619, 0x00ac561c, 0x00a9541c, 0x00a55420, 0x009c5025, 0x008c4b27, 0x00774025, 0x00592c18, 0x00361004, 0x00190000, 0x00130100, 0x00080000, 0x00040000, 0x00020000, 0x00010200, 0x00000000, 0x00000102, 0x00050706, 0x00010000, 0x000a0000, 0x001b0400, 0x00431d05, 0x007c4320, 0x009f562a, 0x00a95520, 0x00a35424, 0x005a2205, 0x00340000, 0x00873e12, 0x00b3591e, 0x00c0540f, 0x00c6540a, 0x00c2540c, 0x00af4e15, 0x00843d1d, 0x004e1300, 0x004c0c00, 0x00854c33, 0x006c442e, 0x00230100, 0x00270000, 0x006c3420, 0x00a05020, 0x00ae4d0e, 0x00b94c0e, 0x00b04a11, 0x00a35428, 0x00582204, 0x00180000, 0x00180000, 0x005b210d, 0x00984b28, 0x00ab4e1d, 0x00b04c13, 0x00ae4d0c, 0x00af4e0d, 0x00b24c14, 0x00b44c14, 0x00b54c10, 0x00b34e11, 0x00aa5019, 0x00924e22, 0x00371300, 0x00150000, 0x001f0300, 0x00603419, 0x009c5328, 0x00ac501b, 0x00b24c14, 0x00b74c10, 0x00b84b0e, 0x00b74a0c, 0x00b64d0d, 0x00b44b0c, 0x00b5480e, 0x00b05022, 0x0085472a, 0x00361000, 0x00100100, 0x000d0000, 0x00401800, 0x00814221, 0x00a85124, 0x00b14b17, 0x00b54715, 0x00b04d24, 0x007f3f21, 0x00240000, 0x00080000, 0x000c0000, 0x00592b04, 0x009e5321, 0x00ac4b18, 0x00ac4c20, 0x00984e2d, 0x00531c04, 0x001c0000, 0x00200000, 0x00571f04, 0x00924820, 0x00a64d16, 0x00b25011, 0x00b94f13, 0x00b94b0f, 0x00b6480c, 0x00b84b0b, 0x00b94c06, 0x00c5560c, 0x00cc580c, 0x00c05212, 0x00a6532a, 0x00581600, 0x004a0f00, 0x0077341b, 0x00a95026, 0x00b24a18, 0x00b84918, 0x00b64a1c, 0x00a74822, 0x009d4c2b, 0x007f4020, 0x00461800, 0x00180000, 0x000b0000, 0x00080000, 0x00080001, 0x00060207, 0x00000005, 0x00000005, 0x00050106, 0x00060000, 0x000d0000, 0x001a0000, 0x003c1400, 0x00683519, 0x00844c2a, 0x008f502a, 0x00965028, 0x009a4a20, 0x00a85225, 0x00ae5323, 0x00a34d20, 0x0098532c, 0x005a2b0b, 0x00280f00, 0x000e0000, 0x00270b00, 0x005a2c15, 0x00924824, 0x00ac5023, 0x00ae4710, 0x00b0460a, 0x00b85014, 0x00b14b0f, 0x00b44c12, 0x00b44c14, 0x00b34c15, 0x00b24b14, 0x00b24b16, 0x00b44a16, 0x00b44a14, 0x00b44a13, 0x00b54a11, 0x00b44910, 0x00b74c13, 0x00b64a14, 0x00b24812, 0x00b44b18, 0x00b74d1c, 0x00b04816, 0x00b44b13, 0x00b44c12, 0x00b44c12, 0x00b44c10, 0x00b44c0e, 0x00b24d10, 0x00af4d19, 0x00a55027, 0x007c3a1c, 0x00391100, 0x000b0000, 0x00020000, 0x000d0000, 0x00340e00, 0x009d5228, 0x00b3521b, 0x00b44c16, 0x00b64b10, 0x00b84b0c, 0x00b94c08, 0x00c05008, 0x00c45408, 0x00c4560d, 0x00bb5818, 0x009c4c1f, 0x00641f00, 0x00540900, 0x009a461a, 0x00b74f13, 0x00c45410, 0x00c2530f, 0x00c05814, 0x00b95a1a, 0x00ac5820, 0x009c5426, 0x00703714, 0x00320b00, 0x00130000, 0x000a0000, 0x00080300, 0x000e0c08, 0x00292827, 0x00707072, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00545054, 0x00180a07, 0x002c0e00, 0x00794018, 0x00bc5c17, 0x00c85404, 0x00ca5407, 0x00c45813, 0x00af5d22, 0x007c441b, 0x00160000, 0x00100000, 0x00240000, 0x0081471b, 0x00b45d15, 0x00c15d07, 0x00bc5600, 0x00c25c0a, 0x00bc580e, 0x00bb5610, 0x00bc5814, 0x00bb5915, 0x00b45c1a, 0x00b15c1a, 0x00b35a18, 0x00b65a19, 0x00b85719, 0x00b65416, 0x00be591c, 0x00ba5819, 0x00b65618, 0x00b0561b, 0x00aa5822, 0x00a45827, 0x009d5628, 0x00975429, 0x008a491f, 0x00713610, 0x004c1a00, 0x002d0500, 0x00170000, 0x000d0000, 0x000b0000, 0x00080000, 0x00060000, 0x00050100, 0x00020300, 0x00000200, 0x00000404, 0x00000203, 0x00000001, 0x00030000, 0x00080000, 0x00210900, 0x00592c0f, 0x00905028, 0x00aa5726, 0x00b4531a, 0x00b95113, 0x00ae5018, 0x0091502a, 0x00400900, 0x00511600, 0x009c5221, 0x00b85714, 0x00c4540a, 0x00c3540b, 0x00b45010, 0x009f4e23, 0x00702c0c, 0x00501000, 0x00743c20, 0x0078482f, 0x003a0f00, 0x002a0000, 0x006c321e, 0x00a05020, 0x00af4d10, 0x00b74d0c, 0x00b04b0d, 0x00a65123, 0x00682c0c, 0x00220500, 0x00120000, 0x00441607, 0x00823f22, 0x00a85024, 0x00ad4b13, 0x00af4e0f, 0x00b04d0d, 0x00b24c14, 0x00b34c15, 0x00b44a0f, 0x00b14c13, 0x00a74d1b, 0x008d4a24, 0x00341100, 0x00150000, 0x002d0c00, 0x006e3b1f, 0x00a15025, 0x00af4d18, 0x00b44d14, 0x00b74c10, 0x00b94b10, 0x00b84a10, 0x00b44c0f, 0x00b24c10, 0x00b24913, 0x00ab532a, 0x00683420, 0x00210600, 0x000c0000, 0x00170000, 0x005f2c10, 0x00974d26, 0x00ad4f1d, 0x00b44814, 0x00b94816, 0x00ac4b24, 0x0074381f, 0x001b0000, 0x00050000, 0x000b0000, 0x004d2200, 0x009c5422, 0x00ac4c1c, 0x00af4b1e, 0x00a04e2a, 0x00682508, 0x003c0700, 0x00491400, 0x007c3916, 0x009f5022, 0x00aa5018, 0x00ae4c0f, 0x00b44b0f, 0x00b8490d, 0x00b94809, 0x00bc4b06, 0x00c05004, 0x00c5560a, 0x00c2540d, 0x00bc5b24, 0x007a3013, 0x00440800, 0x0062250c, 0x00954c29, 0x00a84c19, 0x00b64c13, 0x00b5440f, 0x00b84614, 0x00b84d1b, 0x00af4c1d, 0x00a14c22, 0x00944e2c, 0x005a2b13, 0x00280800, 0x00130000, 0x000d0000, 0x00060000, 0x00020003, 0x0004040a, 0x00000006, 0x00050107, 0x00080003, 0x00080000, 0x000d0000, 0x00130000, 0x001f0000, 0x00381100, 0x0054250a, 0x00773c22, 0x00894727, 0x009b4d29, 0x00994c23, 0x00944a21, 0x00915632, 0x00542c12, 0x002c1000, 0x00150000, 0x00280400, 0x005c230b, 0x00924623, 0x00ac5120, 0x00b04b14, 0x00af4810, 0x00b14b10, 0x00b24c11, 0x00b24c11, 0x00b24c13, 0x00b24b14, 0x00b44a16, 0x00b44a16, 0x00b44a16, 0x00b44a14, 0x00b44c14, 0x00b44b11, 0x00b54c13, 0x00b54c13, 0x00b44a13, 0x00b44a14, 0x00b74b18, 0x00b54b17, 0x00b44a13, 0x00b44b11, 0x00b44c12, 0x00b44c10, 0x00b44c10, 0x00b24d12, 0x00ae4c18, 0x00a44f24, 0x00863f1f, 0x00451802, 0x000a0000, 0x00000000, 0x000d0000, 0x003a1100, 0x009d5126, 0x00b04f18, 0x00b34d18, 0x00b54c12, 0x00b84a0c, 0x00bc4c08, 0x00c24f08, 0x00c5540c, 0x00c45710, 0x00b8581c, 0x008c441c, 0x00511200, 0x00651c00, 0x00b35f30, 0x00b8561c, 0x00bc5719, 0x00b65820, 0x00ab5825, 0x009e5a2c, 0x00683009, 0x00360900, 0x00190000, 0x000e0000, 0x000b0200, 0x00070602, 0x000a0c08, 0x0042433f, 0x009c9c9b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004e4c4f, 0x00140701, 0x00311000, 0x007d4115, 0x00bc5a15, 0x00c85202, 0x00ca5204, 0x00c8580e, 0x00b75b1a, 0x00945425, 0x00260a00, 0x000a0000, 0x000d0000, 0x00472408, 0x0095551e, 0x00b15d14, 0x00b8580b, 0x00bf5a0a, 0x00ba560c, 0x00ba5712, 0x00b95819, 0x00b0571c, 0x00ac5b24, 0x00a95e2b, 0x00a75c2a, 0x00a85d2c, 0x00a95d32, 0x00a3582f, 0x009f5834, 0x00995630, 0x00945027, 0x00884821, 0x00743d1e, 0x00592e13, 0x003d1c06, 0x002e1000, 0x001b0000, 0x00180000, 0x00130000, 0x000f0000, 0x00080100, 0x00050000, 0x00090000, 0x000f0000, 0x00110000, 0x000f0000, 0x00050000, 0x00000000, 0x00010205, 0x00000001, 0x00080000, 0x00180000, 0x00381400, 0x007a441e, 0x00a65928, 0x00b05118, 0x00bb4c10, 0x00c04d0e, 0x00bc4c0c, 0x00b45116, 0x00aa5a2a, 0x00692900, 0x00350300, 0x006a300a, 0x00a85319, 0x00bf5a14, 0x00c1570e, 0x00bf5813, 0x00ae551e, 0x008f4318, 0x00682805, 0x00642b0c, 0x00824c2c, 0x00501d01, 0x002c0000, 0x00743821, 0x00a34f23, 0x00af4c12, 0x00b44c09, 0x00b14c0c, 0x00a9501d, 0x00783616, 0x00300e04, 0x00100000, 0x002a0800, 0x00643018, 0x00a2522a, 0x00aa4b16, 0x00b25012, 0x00b44e10, 0x00b44c14, 0x00b44b14, 0x00b34a12, 0x00b04c17, 0x00a44c21, 0x00894727, 0x00320e00, 0x00160000, 0x003e1506, 0x007c3f25, 0x00a44c21, 0x00b04a16, 0x00b24b14, 0x00b44910, 0x00ba4912, 0x00b94a14, 0x00b34a12, 0x00b14d18, 0x00ad4c19, 0x009d502c, 0x00441b10, 0x00160000, 0x000e0000, 0x00331300, 0x007a3c1c, 0x00a34f23, 0x00b04c16, 0x00b64810, 0x00b84817, 0x00a44820, 0x0064301a, 0x00140000, 0x00040000, 0x000c0000, 0x00461c00, 0x00985022, 0x00ad4d1d, 0x00b24b1c, 0x00a94d21, 0x008b3912, 0x00772e0a, 0x00823915, 0x00a35025, 0x00ac5121, 0x00af511a, 0x00ac4a10, 0x00af480e, 0x00b3480c, 0x00bd4d0e, 0x00c2510b, 0x00ca5506, 0x00c85b10, 0x00b45719, 0x00984a1e, 0x004c0c00, 0x00501400, 0x00803a14, 0x00a4521f, 0x00aa4d11, 0x00b04e10, 0x00b44c18, 0x00b44a16, 0x00b2440c, 0x00b44910, 0x00b75020, 0x00a84a1f, 0x00a2522b, 0x007c3b1b, 0x00451400, 0x001e0000, 0x00100000, 0x000a0000, 0x00020000, 0x00000001, 0x00000000, 0x00000000, 0x00000001, 0x00020000, 0x00080001, 0x00090000, 0x000c0000, 0x00140000, 0x001b0000, 0x001d0000, 0x00370f00, 0x0068381f, 0x008f5031, 0x00975332, 0x00975437, 0x00672e18, 0x002f0800, 0x00170000, 0x00240000, 0x00502009, 0x008c4423, 0x00ac5328, 0x00ad4916, 0x00b74e16, 0x00b14b0f, 0x00b14c0e, 0x00b14b0f, 0x00b44b11, 0x00b44a14, 0x00b44a16, 0x00b24b17, 0x00b04c17, 0x00af4c17, 0x00ac4b14, 0x00ac4c13, 0x00b25018, 0x00b55017, 0x00b24910, 0x00b4460e, 0x00ba4c14, 0x00b44b11, 0x00b34a10, 0x00b34a10, 0x00b34b0f, 0x00b24c11, 0x00b04d15, 0x00ac4d18, 0x00a54e20, 0x00904422, 0x00511e08, 0x000a0000, 0x00040100, 0x00110000, 0x00441808, 0x00a05327, 0x00ad4c15, 0x00ae4d16, 0x00b14c13, 0x00b84b0c, 0x00be4c09, 0x00c7500c, 0x00c95410, 0x00c55612, 0x00b55820, 0x00783913, 0x00400c00, 0x006f310c, 0x00a86439, 0x00a85c2c, 0x00aa5e33, 0x008c4b2b, 0x0058250c, 0x00260400, 0x00140000, 0x00100000, 0x000e0300, 0x00040000, 0x00000000, 0x00282828, 0x00757575, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004c4a4c, 0x00120400, 0x00341000, 0x00814215, 0x00bb5914, 0x00cc5604, 0x00cc5405, 0x00c95609, 0x00b9560e, 0x00a65f28, 0x003b1b06, 0x00090000, 0x00060000, 0x00140000, 0x0073411c, 0x00a05820, 0x00b65c18, 0x00ba560c, 0x00b7530b, 0x00bb5a18, 0x00a0480c, 0x00803000, 0x00692400, 0x00612300, 0x00561c00, 0x004e1700, 0x00491400, 0x00400f00, 0x00340900, 0x002e0400, 0x002b0000, 0x00260000, 0x001d0000, 0x00150000, 0x000c0000, 0x00080000, 0x000a0000, 0x00080000, 0x00050000, 0x00050000, 0x00050000, 0x000b0000, 0x00200800, 0x00321401, 0x00401e11, 0x00280f06, 0x000a0100, 0x00010000, 0x00040003, 0x00080000, 0x00220400, 0x004a1c05, 0x00874821, 0x00a1541d, 0x00b35114, 0x00bc4c0c, 0x00c54e0e, 0x00c44c0c, 0x00bc4b0c, 0x00ba5216, 0x00ac5018, 0x009e5322, 0x004e1700, 0x00400a00, 0x008a4212, 0x00b25a1e, 0x00b9540f, 0x00be570e, 0x00b45414, 0x00a6501a, 0x00873f14, 0x00632200, 0x008c4d27, 0x00602504, 0x002d0000, 0x007c4028, 0x00a54d26, 0x00b04b15, 0x00b34a08, 0x00b24c0c, 0x00ac501d, 0x00863c1d, 0x003a1408, 0x00100000, 0x00140000, 0x0049240f, 0x0098512c, 0x00a44918, 0x00b44e15, 0x00b54c10, 0x00b44814, 0x00b24814, 0x00b44c15, 0x00b04c1b, 0x00a44b24, 0x00884428, 0x00320c00, 0x00180000, 0x004c1b0a, 0x00864125, 0x00ab4d23, 0x00b64c18, 0x00b44c15, 0x00b24810, 0x00ba4815, 0x00b94918, 0x00b04814, 0x00ac4e1b, 0x00a24b1c, 0x008a4828, 0x00250500, 0x000d0000, 0x00140000, 0x00532811, 0x00904723, 0x00ab4e1d, 0x00b14b10, 0x00b54b0f, 0x00b64a17, 0x009b441d, 0x00582a17, 0x00100000, 0x00030000, 0x000e0000, 0x00481c00, 0x00934d23, 0x00ac4c1e, 0x00b4491a, 0x00ae4b19, 0x00a74b18, 0x00a34c1c, 0x00a85021, 0x00ad4d1d, 0x00aa4714, 0x00b14d18, 0x00b14c14, 0x00b44b13, 0x00b4490d, 0x00c05010, 0x00c4530b, 0x00ca5408, 0x00bf5710, 0x00a95b2a, 0x005e2000, 0x00410600, 0x0068280a, 0x00a25222, 0x00a74d12, 0x00aa4e0e, 0x00af5114, 0x00aa4b14, 0x00ad4914, 0x00b64b10, 0x00b6480e, 0x00b64815, 0x00b24818, 0x00ab4a1c, 0x00a34d24, 0x00954e2c, 0x0070381c, 0x003c1200, 0x00200400, 0x00140200, 0x000a0000, 0x00080000, 0x00070100, 0x00040000, 0x00020001, 0x00040004, 0x00030004, 0x00030005, 0x00050004, 0x00090000, 0x000c0000, 0x00100000, 0x00160000, 0x00330800, 0x00692f15, 0x008c462e, 0x0091503b, 0x00633224, 0x00280500, 0x00150000, 0x001e0100, 0x00491904, 0x008c482a, 0x00ac5028, 0x00ac4817, 0x00af4c12, 0x00b04c0f, 0x00b14b10, 0x00b34a12, 0x00b44b14, 0x00b44a16, 0x00b24c19, 0x00b04c19, 0x00ac4d17, 0x00ae5018, 0x00aa4c14, 0x00a94b10, 0x00b04e14, 0x00b34c12, 0x00b3480d, 0x00b54a10, 0x00b54b14, 0x00b34a12, 0x00b1480f, 0x00b24910, 0x00b24c13, 0x00b04c17, 0x00ac4d18, 0x00a64d20, 0x00974826, 0x0057210a, 0x000c0000, 0x00080200, 0x00180000, 0x0050200c, 0x00a65528, 0x00ad4c15, 0x00ac4c16, 0x00af4c14, 0x00b84b0c, 0x00bf4d0a, 0x00c9510c, 0x00cc5510, 0x00c45714, 0x00b15821, 0x00673110, 0x003c1500, 0x006b3c1e, 0x007d4b28, 0x00683210, 0x00431000, 0x00270000, 0x00190000, 0x00090000, 0x00030000, 0x00040100, 0x00000000, 0x00161815, 0x005d6060, 0x00a2a3a6, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0048484a, 0x00100400, 0x00371300, 0x00804013, 0x00bc5b14, 0x00ca5503, 0x00cc5304, 0x00cb5508, 0x00c25a0d, 0x00a45519, 0x00653e24, 0x000c0000, 0x00090000, 0x000d0000, 0x003a1400, 0x008e502c, 0x00b05a20, 0x00b85411, 0x00b8550f, 0x00b45818, 0x0091440d, 0x00642400, 0x003c0400, 0x002a0000, 0x00250000, 0x001c0000, 0x00140000, 0x00140000, 0x00100000, 0x00100000, 0x00100000, 0x000c0000, 0x000a0000, 0x00080000, 0x00050000, 0x00080100, 0x00060000, 0x00050000, 0x00060000, 0x000a0000, 0x001f0600, 0x0050280e, 0x00834921, 0x0090542f, 0x00845844, 0x002b0d06, 0x000a0000, 0x00070204, 0x00080000, 0x00230800, 0x00602c16, 0x00914921, 0x00a95319, 0x00b25110, 0x00b8500e, 0x00bc4e0e, 0x00be4c13, 0x00be4c14, 0x00ba4c13, 0x00b74f13, 0x00b34e11, 0x00b05820, 0x00863e14, 0x004a0b00, 0x00581a00, 0x00974e22, 0x00b85819, 0x00c05810, 0x00bf5811, 0x00b15210, 0x009d4913, 0x008b3e0e, 0x008b4014, 0x006a2803, 0x00300000, 0x00874b31, 0x00a84c28, 0x00b14816, 0x00b44c0d, 0x00b34f0f, 0x00a84817, 0x00994c2a, 0x0046180b, 0x00120000, 0x000a0000, 0x002d1502, 0x00753b1a, 0x00a34f23, 0x00b34f1c, 0x00b54713, 0x00bc4e1c, 0x00b24613, 0x00b64c18, 0x00ac4818, 0x00a94e26, 0x00823a1e, 0x00350800, 0x00200000, 0x00571e08, 0x00914424, 0x00ae4c1e, 0x00b34813, 0x00b54c16, 0x00b44a14, 0x00b84614, 0x00b84918, 0x00b04c18, 0x00a74f1e, 0x009e5529, 0x00521d01, 0x001c0300, 0x000d0000, 0x00240300, 0x00733c21, 0x00a24d25, 0x00af4b18, 0x00b64e12, 0x00b24a0d, 0x00b04c16, 0x0094471e, 0x004a2412, 0x000f0100, 0x00040000, 0x000d0000, 0x00441800, 0x00934e28, 0x00ac4c21, 0x00b64b1a, 0x00b24b14, 0x00b04a11, 0x00b25018, 0x00ac4813, 0x00b44a16, 0x00b54916, 0x00b44914, 0x00b64c14, 0x00b44810, 0x00b84b0c, 0x00c55510, 0x00c7560c, 0x00c5560c, 0x00bd5d20, 0x00713211, 0x003d0c00, 0x005c2408, 0x008a451e, 0x00a84d17, 0x00b04e10, 0x00af4e14, 0x00ab4e14, 0x00a74d12, 0x00a74c13, 0x00af4b15, 0x00b54c18, 0x00b64919, 0x00b14719, 0x00ad491c, 0x00aa4b1e, 0x00a74b1d, 0x00a04c1f, 0x00954a20, 0x007d3f1a, 0x005c2c0e, 0x00401c04, 0x00240800, 0x00180100, 0x00110000, 0x000f0000, 0x000c0000, 0x000a0000, 0x00090000, 0x00050003, 0x00040007, 0x00010004, 0x00020001, 0x00070000, 0x00110000, 0x001f0100, 0x00431506, 0x006b3526, 0x00814d3f, 0x005d3328, 0x002a140b, 0x000b0000, 0x00120000, 0x00441d0c, 0x00863f25, 0x00a84f2a, 0x00a94a15, 0x00ae4c12, 0x00b04d15, 0x00b14c16, 0x00b14a16, 0x00b14918, 0x00b04a18, 0x00ae4a15, 0x00af4c16, 0x00ae4d13, 0x00ac4e13, 0x00ac4f11, 0x00ae4e11, 0x00b04c11, 0x00b14c13, 0x00b24b14, 0x00b14a14, 0x00b34c14, 0x00b44c12, 0x00b24910, 0x00b04913, 0x00b04c16, 0x00ac4d18, 0x00a54c20, 0x00974826, 0x005d260f, 0x00110000, 0x00080000, 0x00230400, 0x0068331c, 0x00a04c1f, 0x00b2511a, 0x00ac4e17, 0x00ae4d14, 0x00b54b0c, 0x00c4520d, 0x00c54e06, 0x00cc5610, 0x00c05714, 0x00a14f1a, 0x00502408, 0x001e0400, 0x00240700, 0x00220500, 0x001f0300, 0x00150000, 0x000a0000, 0x00050001, 0x00020003, 0x00010002, 0x001b191a, 0x00585857, 0x009ea09d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0048484c, 0x00100400, 0x00341100, 0x007f4012, 0x00bc5a15, 0x00cb5605, 0x00cc5505, 0x00ca5506, 0x00c4590a, 0x00ac5818, 0x00784828, 0x00150000, 0x00080000, 0x000a0000, 0x00200300, 0x0064301a, 0x00a45424, 0x00ba591a, 0x00bb5811, 0x00b45713, 0x00a6581f, 0x00985324, 0x00894b24, 0x00784120, 0x00603118, 0x00411c04, 0x002b0b00, 0x001f0400, 0x00170000, 0x00110000, 0x000e0000, 0x000c0000, 0x000c0000, 0x000d0000, 0x00140300, 0x00221008, 0x0030231c, 0x001e0f09, 0x00110000, 0x00250800, 0x005a2d13, 0x00884b26, 0x00a45829, 0x009b552b, 0x005c2e1c, 0x00200600, 0x00100100, 0x000a0000, 0x00290e06, 0x005e301c, 0x00914822, 0x00ad531e, 0x00b5500d, 0x00b85008, 0x00b84f0c, 0x00b94f11, 0x00b94e15, 0x00b84c16, 0x00b84e13, 0x00b84e12, 0x00bb5013, 0x00b24c14, 0x00a44c1f, 0x00732904, 0x00450700, 0x00682704, 0x00a95320, 0x00bb5717, 0x00bc540c, 0x00c05810, 0x00b75414, 0x00a64b12, 0x009b4618, 0x00752c06, 0x003c0400, 0x00905134, 0x00aa4b28, 0x00b44819, 0x00b44c10, 0x00b14f10, 0x00ac4a1a, 0x009f4e2b, 0x00582412, 0x001f0200, 0x00080000, 0x00140600, 0x00502106, 0x00994f2c, 0x00a8481e, 0x00b24618, 0x00b34616, 0x00b54817, 0x00b44a16, 0x00ae4b19, 0x00a84c21, 0x00803311, 0x003c0700, 0x002f0000, 0x00632003, 0x0097431d, 0x00af4a19, 0x00b44812, 0x00b44c14, 0x00b44b13, 0x00b74814, 0x00b44815, 0x00ad4c19, 0x00a35021, 0x008f522a, 0x00360d00, 0x00120000, 0x00120000, 0x00481c0c, 0x00854224, 0x00a84b20, 0x00b34915, 0x00b34b0e, 0x00af4a0c, 0x00ab4d16, 0x008e461e, 0x0042200f, 0x000a0000, 0x00040000, 0x000f0000, 0x00441600, 0x00944c2b, 0x00ac4c24, 0x00b44a18, 0x00b44b11, 0x00b24a0d, 0x00b44f11, 0x00b2480d, 0x00b74810, 0x00b94712, 0x00b54610, 0x00b74810, 0x00b9480f, 0x00c15211, 0x00ca5b12, 0x00bf540c, 0x00b75615, 0x00974a1c, 0x00411300, 0x00280200, 0x006e3c21, 0x009c5832, 0x00a24715, 0x00b04b15, 0x00ac4b15, 0x00ab4d15, 0x00aa5011, 0x00ac4f13, 0x00ac4a14, 0x00ad4716, 0x00b04617, 0x00b24818, 0x00b04b1c, 0x00ae4b1b, 0x00ad4914, 0x00ac4a14, 0x00ab4d18, 0x00a54f1d, 0x00984c23, 0x00894824, 0x0080492a, 0x00704027, 0x005f321c, 0x004b2310, 0x00340f02, 0x00220200, 0x00180000, 0x000f0000, 0x00060000, 0x00050004, 0x00040102, 0x00010000, 0x00020000, 0x00060000, 0x00140000, 0x00290800, 0x00471f16, 0x00603f35, 0x0041312a, 0x00140c05, 0x000b0300, 0x00170000, 0x00411002, 0x007f3921, 0x00a35228, 0x00a84f1c, 0x00aa4c1b, 0x00ac4919, 0x00af4818, 0x00b24817, 0x00b34815, 0x00b34a14, 0x00b24c13, 0x00b04c11, 0x00af4d11, 0x00ae4d13, 0x00ae4d13, 0x00ae4d14, 0x00b04c16, 0x00b04c16, 0x00b14c16, 0x00b24b14, 0x00b34a12, 0x00b14b12, 0x00b14c14, 0x00b04d18, 0x00ae4c18, 0x00a54c20, 0x00964827, 0x005a240d, 0x00120000, 0x000c0000, 0x00300b00, 0x00814429, 0x00a44c1f, 0x00af4e17, 0x00ab4c15, 0x00b04f14, 0x00b64c0b, 0x00c1500a, 0x00c85005, 0x00c8560c, 0x00bc5a18, 0x00863e0e, 0x00381400, 0x00100000, 0x00100000, 0x000a0000, 0x00090000, 0x00040000, 0x00010004, 0x00040509, 0x00302f31, 0x00686768, 0x009e9c9d, 0x001f1f1f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004c4c50, 0x00130703, 0x00310e00, 0x007c3e11, 0x00ba5a15, 0x00c85506, 0x00cc5507, 0x00c95407, 0x00c65909, 0x00b45a17, 0x008f552d, 0x00280600, 0x000d0000, 0x000c0000, 0x000d0000, 0x00381101, 0x008e461e, 0x00b5581c, 0x00bc560d, 0x00bc560c, 0x00b05410, 0x00b0581a, 0x00b0571e, 0x00a9531f, 0x00a04f1d, 0x00984c1b, 0x00904917, 0x00864617, 0x00743a12, 0x0062300f, 0x004e2308, 0x00471c03, 0x00491c02, 0x0054270b, 0x00673921, 0x006d4531, 0x004f3022, 0x002a0b00, 0x002a0000, 0x0059240b, 0x00944f2b, 0x00a85830, 0x00ad5933, 0x008c482b, 0x002c0a00, 0x00100000, 0x00100000, 0x00200200, 0x00623217, 0x00944e28, 0x00ae521c, 0x00bb5413, 0x00b9500a, 0x00b9500a, 0x00b55010, 0x00b35014, 0x00b44f16, 0x00b54f14, 0x00b74f10, 0x00b84e0f, 0x00bb4c10, 0x00b74c13, 0x00b85120, 0x00a0471f, 0x00621a00, 0x00480700, 0x00782d0a, 0x00aa5422, 0x00bb5310, 0x00c8580c, 0x00c35208, 0x00b9500e, 0x00a44818, 0x007a2b09, 0x00460a00, 0x00955234, 0x00ac4926, 0x00b44718, 0x00b44c10, 0x00af4c0f, 0x00ad4b1b, 0x00a34d28, 0x006f331c, 0x002e0900, 0x00090000, 0x00080000, 0x00300d00, 0x00733619, 0x00a44e2c, 0x00ad4923, 0x00b0471a, 0x00b54c1a, 0x00af4914, 0x00ae4c16, 0x00a84b1a, 0x00923f16, 0x00702f0c, 0x006c2e0f, 0x008b3f1a, 0x00a64d20, 0x00af4914, 0x00b44b10, 0x00b44b11, 0x00b34a10, 0x00b54a11, 0x00b24913, 0x00a94c16, 0x009e5224, 0x00703f1c, 0x001e0000, 0x00100000, 0x00200000, 0x006e3621, 0x00994a28, 0x00af4b1e, 0x00b44813, 0x00af480c, 0x00ac4c0f, 0x00a84e19, 0x0087441c, 0x003c1d0c, 0x00080000, 0x00050000, 0x00100000, 0x00451500, 0x00954c2c, 0x00aa4c25, 0x00b0481a, 0x00b24c13, 0x00b04b0d, 0x00b24d10, 0x00b34b0f, 0x00b7460f, 0x00bc4812, 0x00b7440c, 0x00bd4a10, 0x00c75416, 0x00c4520f, 0x00c15408, 0x00bc5c17, 0x00a05528, 0x004c1800, 0x001a0000, 0x001c0100, 0x00411504, 0x00783b20, 0x009f4c2a, 0x00ac4d25, 0x00ab4a1e, 0x00ad4a17, 0x00b24c0f, 0x00b34d0e, 0x00b14c13, 0x00b04a14, 0x00b24817, 0x00b14918, 0x00b04a18, 0x00b04c17, 0x00b14c16, 0x00b04a13, 0x00ad4914, 0x00ad4b15, 0x00ac4c19, 0x00a94c1c, 0x00ab5022, 0x009f491c, 0x0097461b, 0x0090461f, 0x00854422, 0x00743c1f, 0x005c2b14, 0x00431b08, 0x00240300, 0x00190100, 0x000b0000, 0x00030000, 0x00010400, 0x00000300, 0x00020000, 0x00050000, 0x00110605, 0x001f1410, 0x00352d26, 0x00342c25, 0x00150904, 0x000c0000, 0x00190000, 0x00310b00, 0x0073371e, 0x00934826, 0x00a6522c, 0x00a84c20, 0x00ac4517, 0x00b64a17, 0x00bc4b14, 0x00b7460d, 0x00b74910, 0x00b44b11, 0x00b14c14, 0x00af4c16, 0x00ae4c17, 0x00ae4c17, 0x00b04c18, 0x00b04c17, 0x00b04c18, 0x00b04b15, 0x00b24911, 0x00b14b12, 0x00b04d15, 0x00af4c17, 0x00ad4c19, 0x00a74c20, 0x00904728, 0x0057220d, 0x00140000, 0x00140000, 0x00451800, 0x00995333, 0x00a64c1c, 0x00b04c14, 0x00ac4a14, 0x00b24d10, 0x00ba4d0a, 0x00c55308, 0x00cb5605, 0x00c2570b, 0x00b45c1f, 0x006e3108, 0x00210700, 0x00090000, 0x00070000, 0x00030000, 0x000f0d0e, 0x00242424, 0x005a5a58, 0x00878683, 0x00a7a39e, 0x00454443, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00545558, 0x00170b07, 0x002b0a00, 0x00773b0f, 0x00ba5b19, 0x00c55508, 0x00c85408, 0x00c85408, 0x00c45808, 0x00b55813, 0x00a05c2c, 0x003f1400, 0x00100000, 0x00150b06, 0x000a0000, 0x00200400, 0x006c3011, 0x00a1501c, 0x00b45610, 0x00bd580d, 0x00bb5a13, 0x00b95814, 0x00b85211, 0x00b55010, 0x00b85315, 0x00ba581a, 0x00b85818, 0x00ad5516, 0x00a5571c, 0x009a531e, 0x008b491b, 0x0088481c, 0x008a4a20, 0x008c502b, 0x00824e30, 0x00683a23, 0x003a1404, 0x002d0400, 0x00581c00, 0x008f4520, 0x00aa5325, 0x00a85124, 0x009d502f, 0x005f2712, 0x00150000, 0x000c0000, 0x001a0000, 0x005a2b11, 0x008f4a21, 0x00a8521e, 0x00b34e10, 0x00b84c08, 0x00bc500b, 0x00bb500c, 0x00b7500f, 0x00b44f11, 0x00b44f11, 0x00b44f11, 0x00b44f10, 0x00b84f0f, 0x00b84a0e, 0x00bd4f15, 0x00b84c19, 0x00b04f24, 0x008e401f, 0x00561400, 0x004c0f00, 0x00803a18, 0x00b4571c, 0x00c65a12, 0x00c45004, 0x00c45311, 0x00ad4b1d, 0x00832e0c, 0x005b1800, 0x009d5430, 0x00ac4920, 0x00b44718, 0x00b34a10, 0x00ae490e, 0x00ae4c1a, 0x00a54d26, 0x00843f23, 0x00401300, 0x000b0000, 0x00050000, 0x001c0300, 0x00411400, 0x0088422a, 0x00a54f30, 0x00aa4c24, 0x00ad4a1a, 0x00af4c16, 0x00af4c16, 0x00aa4b16, 0x00a34b1a, 0x009c4f26, 0x009b5027, 0x00a04c1f, 0x00a54917, 0x00af4912, 0x00b64c11, 0x00b24910, 0x00b04a10, 0x00b44c10, 0x00af4912, 0x00a74c18, 0x00985227, 0x00482004, 0x00140000, 0x00160000, 0x003b1106, 0x00864428, 0x00a64e27, 0x00b34b1c, 0x00b44511, 0x00b0490f, 0x00ac4d14, 0x00a7501c, 0x0085441d, 0x003c1d0c, 0x00090000, 0x00060000, 0x00130000, 0x004c1802, 0x00984d2c, 0x00ac4c26, 0x00b0481b, 0x00b14c16, 0x00ae4c0e, 0x00b04c0f, 0x00b44c0f, 0x00b6480e, 0x00bb480f, 0x00bc4a0d, 0x00c45113, 0x00c55414, 0x00c05413, 0x00bb5813, 0x00a8571f, 0x00582509, 0x001d0000, 0x000d0000, 0x00100000, 0x001c0000, 0x003c0e00, 0x00682812, 0x00914327, 0x00a44c2a, 0x00ab4c1f, 0x00b04812, 0x00b0470b, 0x00b1490d, 0x00b34c14, 0x00b44b18, 0x00b24817, 0x00ac4711, 0x00af4914, 0x00b24c17, 0x00b24c17, 0x00b14a14, 0x00b04810, 0x00b1460d, 0x00b1460c, 0x00b0450c, 0x00b04710, 0x00af4c17, 0x00ac501f, 0x00a45023, 0x009d5025, 0x00944b24, 0x00874421, 0x00763a21, 0x00582813, 0x00311400, 0x00180800, 0x00090300, 0x00020000, 0x00000000, 0x00060405, 0x00000000, 0x00000000, 0x000c0805, 0x001c140f, 0x00190d09, 0x000b0000, 0x00060000, 0x000f0000, 0x00310a00, 0x00642c18, 0x00904c31, 0x00a2502c, 0x00a94a1d, 0x00b34916, 0x00b94811, 0x00b6440b, 0x00b74810, 0x00b44814, 0x00b04a16, 0x00ae4b19, 0x00ae4b19, 0x00ae4b19, 0x00af4b18, 0x00af4b16, 0x00b04c18, 0x00b04915, 0x00b14812, 0x00b14a14, 0x00ae4c15, 0x00ac4a14, 0x00ac4918, 0x00a54c22, 0x00884428, 0x004e1e0b, 0x00150000, 0x00240700, 0x0061290c, 0x00a0542c, 0x00a74b18, 0x00b14c14, 0x00b14c13, 0x00b44b0c, 0x00be5009, 0x00ca580b, 0x00c85705, 0x00bb570c, 0x009e541c, 0x00572806, 0x00140100, 0x00030001, 0x00131016, 0x00515256, 0x00808387, 0x00989c9c, 0x00b0b1ac, 0x006c6a66, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005f6064, 0x00190e0c, 0x00240400, 0x0070380e, 0x00b85c1c, 0x00c4540a, 0x00c55309, 0x00c7560c, 0x00c3580a, 0x00b6570f, 0x00a95c25, 0x005c2700, 0x00160000, 0x001e1710, 0x001c1815, 0x00140400, 0x003d1600, 0x0084471f, 0x00aa5921, 0x00b45818, 0x00b35211, 0x00b65210, 0x00b85213, 0x00ba5214, 0x00bb5214, 0x00ba5113, 0x00b75112, 0x00b45210, 0x00b05410, 0x00ad5710, 0x00b05917, 0x00b05f20, 0x00a35c27, 0x00884e25, 0x005a3118, 0x002f0e00, 0x00240300, 0x004c1e06, 0x008e4519, 0x00ac521a, 0x00af4e14, 0x00a7531f, 0x00804428, 0x002b0700, 0x00100000, 0x00100000, 0x00401400, 0x0086441e, 0x00a14d18, 0x00b25215, 0x00b65011, 0x00b64d0d, 0x00bb4f0e, 0x00bc4e0d, 0x00bd4d09, 0x00bc4c07, 0x00ba4d08, 0x00b84e0c, 0x00b44f11, 0x00b44f11, 0x00bb4c10, 0x00ba4c11, 0x00b74d1a, 0x00ac4c20, 0x00a15028, 0x007c3a1c, 0x00451608, 0x00451401, 0x00894014, 0x00af5416, 0x00c15610, 0x00c65a19, 0x00ad4a20, 0x0087300c, 0x00742800, 0x00a25223, 0x00ac4a1b, 0x00b44816, 0x00b54a11, 0x00b14810, 0x00b04d1c, 0x00a64d21, 0x00964826, 0x00592209, 0x00140000, 0x000b0300, 0x000b0000, 0x00200400, 0x004d1c0b, 0x008c4830, 0x009e4d28, 0x00a64c1d, 0x00aa4b16, 0x00ae4c14, 0x00ac4a12, 0x00a94a14, 0x00a84d1d, 0x00a44c1c, 0x00a44816, 0x00ab4915, 0x00b04a13, 0x00b54c13, 0x00af4810, 0x00b04910, 0x00b14c11, 0x00ac4b14, 0x00a44c1c, 0x008d4c25, 0x00290800, 0x00130000, 0x00200000, 0x005e2b17, 0x00954926, 0x00aa4c21, 0x00b4481c, 0x00b54514, 0x00b04913, 0x00ac4c16, 0x00a74f1e, 0x00864420, 0x003f1e0e, 0x000d0000, 0x00070000, 0x00120000, 0x00562108, 0x009b4c28, 0x00ac4b24, 0x00b0481b, 0x00af4b16, 0x00ad4c11, 0x00ac4a0c, 0x00b14c0e, 0x00b84a0e, 0x00bc4b0c, 0x00c45311, 0x00c45513, 0x00b94f10, 0x00bc5c1f, 0x00a95720, 0x006b3008, 0x001c0200, 0x00060000, 0x00050000, 0x00050000, 0x000d0000, 0x00180000, 0x00280200, 0x00582213, 0x00823e25, 0x00984824, 0x00ab4b20, 0x00af4814, 0x00af460c, 0x00b1490d, 0x00b44914, 0x00b14814, 0x00b24815, 0x00b04915, 0x00b04a18, 0x00b04a16, 0x00b14a14, 0x00b24910, 0x00b74a0d, 0x00b84b0c, 0x00b64c10, 0x00b24c13, 0x00b04c19, 0x00ab4b1a, 0x00a64817, 0x00a94717, 0x00b04915, 0x00ac4a18, 0x00a85124, 0x00944a24, 0x00783f20, 0x005c3118, 0x00391c04, 0x001e0800, 0x00100000, 0x000a0000, 0x00060000, 0x000b0404, 0x00050000, 0x00030000, 0x000c0601, 0x00090400, 0x00030000, 0x00090000, 0x000e0000, 0x002c0904, 0x00582817, 0x00864628, 0x00a45028, 0x00aa4a19, 0x00af4610, 0x00b54810, 0x00b44813, 0x00b24817, 0x00b0481a, 0x00ad491b, 0x00ad491b, 0x00ae4918, 0x00b04915, 0x00b04a14, 0x00ae4b18, 0x00ae4a17, 0x00b24814, 0x00b04914, 0x00ac4b14, 0x00aa4b14, 0x00ae491a, 0x00a74d27, 0x007e3f26, 0x003e1201, 0x00160000, 0x00381300, 0x00803f1b, 0x00a04c1e, 0x00ab4b18, 0x00b24b14, 0x00b54d11, 0x00b74b0a, 0x00c3520a, 0x00c95809, 0x00c35405, 0x00b85b17, 0x007c4014, 0x00351400, 0x000c0000, 0x00040004, 0x003c3a40, 0x00a1a2a6, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x006d6e72, 0x00201414, 0x001c0000, 0x0069310a, 0x00b4591b, 0x00c2560c, 0x00c4540d, 0x00c75710, 0x00c2580d, 0x00b85710, 0x00ae581c, 0x007a3b0e, 0x001e0000, 0x00281b10, 0x003b322d, 0x00180900, 0x001e0100, 0x006b3918, 0x00a15726, 0x00b05518, 0x00b85616, 0x00ba5310, 0x00b95210, 0x00ba5310, 0x00ba500f, 0x00b84e0c, 0x00b84f0f, 0x00b85310, 0x00b7540d, 0x00b15208, 0x00b65812, 0x00a75215, 0x00823d10, 0x00542002, 0x00280600, 0x001b0000, 0x00431906, 0x007c411d, 0x00ab541b, 0x00b25010, 0x00b05416, 0x009c5020, 0x0054280f, 0x00130000, 0x000e0000, 0x00160000, 0x006f3515, 0x009d4e1f, 0x00b05014, 0x00b7500d, 0x00b55010, 0x00b85014, 0x00b84e14, 0x00bb4c12, 0x00c04c0b, 0x00bf4c06, 0x00bc4c06, 0x00b94e0a, 0x00b44f11, 0x00b44e12, 0x00bb4e10, 0x00b6490c, 0x00b6501b, 0x00ac5022, 0x00a3562d, 0x00824729, 0x003c180d, 0x00230100, 0x00481800, 0x00834010, 0x00b1581b, 0x00c05d22, 0x00ab4920, 0x008c3109, 0x00903c08, 0x00a55018, 0x00ab4c14, 0x00b04913, 0x00b54810, 0x00b24610, 0x00af4c18, 0x00a84c1e, 0x00a04c24, 0x00733315, 0x002b0c00, 0x00080000, 0x00060000, 0x000c0000, 0x001f0000, 0x00592815, 0x008d4928, 0x00a45026, 0x00a74a19, 0x00ad4b15, 0x00ae4b11, 0x00ae4b13, 0x00ae4a17, 0x00ac4817, 0x00ad4a17, 0x00b4501c, 0x00b04a14, 0x00b24c17, 0x00ae4713, 0x00b04a14, 0x00ae4b13, 0x00aa4c17, 0x00a14c1f, 0x007f401f, 0x001c0000, 0x00100000, 0x00300a00, 0x007c4026, 0x00a04d24, 0x00ad4a1a, 0x00b34618, 0x00b64718, 0x00b04915, 0x00ac4b18, 0x00a84d20, 0x00874420, 0x00421e0f, 0x000e0000, 0x00080000, 0x00140000, 0x00662f10, 0x009d4c24, 0x00ac481f, 0x00b14719, 0x00af4814, 0x00ad4a10, 0x00ad4b0d, 0x00b34d0e, 0x00b94c0b, 0x00c55511, 0x00c3540d, 0x00c05710, 0x00bd5d20, 0x00a4521f, 0x006b2c05, 0x002a0400, 0x000f0300, 0x00000004, 0x00000000, 0x00020000, 0x00030001, 0x00070000, 0x00110000, 0x001e0300, 0x00431706, 0x006c3017, 0x00954828, 0x00a84f27, 0x00ad4c18, 0x00b04a13, 0x00b04914, 0x00b04814, 0x00b44c18, 0x00b14b17, 0x00af4816, 0x00ae4814, 0x00ae4813, 0x00ae480f, 0x00b1480e, 0x00b2480f, 0x00b04913, 0x00ab4712, 0x00ab4818, 0x00af4c1d, 0x00b04c1b, 0x00b34c18, 0x00b74911, 0x00b4460e, 0x00aa440f, 0x00a74c1c, 0x00a2522a, 0x00944f2c, 0x007d4223, 0x00643418, 0x00481d07, 0x002a0800, 0x001c0000, 0x000e0000, 0x000c0000, 0x00080100, 0x00030000, 0x00020000, 0x00060504, 0x00020000, 0x00080004, 0x000c0000, 0x00230400, 0x0051240e, 0x00814220, 0x009f5024, 0x00aa4f1d, 0x00af4c18, 0x00af4816, 0x00b04818, 0x00af481a, 0x00af481a, 0x00af4819, 0x00af4818, 0x00b04814, 0x00af4914, 0x00ac4916, 0x00ad4a17, 0x00b14a16, 0x00b04914, 0x00ac4c14, 0x00ac4c16, 0x00b04b1c, 0x00a54c28, 0x0070341f, 0x002e0500, 0x001d0000, 0x0050260d, 0x00974f24, 0x00a44a15, 0x00af4c17, 0x00b04a11, 0x00b3490d, 0x00bb4e0b, 0x00c6540a, 0x00c65407, 0x00c25409, 0x00b15b1f, 0x00602e0f, 0x001a0300, 0x00080000, 0x00100d0e, 0x005c5b5c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00828288, 0x002a1f1e, 0x00180000, 0x005f2803, 0x00ac5215, 0x00c35810, 0x00c45511, 0x00c35610, 0x00bf560d, 0x00bc5911, 0x00b05414, 0x00964c1b, 0x002b0000, 0x002d1406, 0x005e493d, 0x002b1506, 0x001b0000, 0x00502003, 0x00924618, 0x00b15318, 0x00bc520e, 0x00bc5008, 0x00b8520b, 0x00b8540c, 0x00bc550c, 0x00bb540d, 0x00b7520f, 0x00b55111, 0x00b85314, 0x00b35013, 0x00b35824, 0x008d4219, 0x00521e08, 0x00280200, 0x00190000, 0x003b1408, 0x007e3c1c, 0x00a34f1b, 0x00b25010, 0x00b0500f, 0x00a25420, 0x00784018, 0x00270700, 0x00100000, 0x00100000, 0x003a1703, 0x008d4c25, 0x00aa501d, 0x00bc5415, 0x00b74908, 0x00b54d10, 0x00b44d17, 0x00b64c1b, 0x00b84b19, 0x00bc4b14, 0x00bc4b0e, 0x00ba4c0c, 0x00b94d0c, 0x00b84d11, 0x00b74d11, 0x00b94d0c, 0x00b74e0c, 0x00b25016, 0x00a45020, 0x00894b24, 0x00582c11, 0x00230500, 0x00170000, 0x00190400, 0x00442104, 0x00834111, 0x00ac5622, 0x00ac4e24, 0x00943406, 0x00a94f12, 0x00b25815, 0x00ad5111, 0x00af4c0f, 0x00b6480e, 0x00b44510, 0x00ad4916, 0x00a74a19, 0x00a34b1c, 0x00894220, 0x004a2015, 0x000c0000, 0x00040102, 0x00000000, 0x000c0000, 0x00280800, 0x00652d10, 0x00944820, 0x00a84e21, 0x00af4c1a, 0x00b04b14, 0x00b34a12, 0x00b44816, 0x00b44717, 0x00b04715, 0x00ad4714, 0x00ae4918, 0x00b04b1c, 0x00ae4618, 0x00b04a19, 0x00ac4916, 0x00a84c1b, 0x009f4a22, 0x006f3015, 0x00180000, 0x00130000, 0x00512412, 0x008d4b2b, 0x00a54e20, 0x00ad4713, 0x00b44717, 0x00b54618, 0x00b04817, 0x00ac4919, 0x00a84c21, 0x008b4424, 0x00441e0e, 0x00100000, 0x00090000, 0x00180100, 0x00783f1c, 0x00a04c1f, 0x00ac471b, 0x00b44819, 0x00b14814, 0x00b14b10, 0x00b34e10, 0x00b8510f, 0x00bf500a, 0x00c95a10, 0x00c05408, 0x00b95610, 0x00a8541c, 0x00713108, 0x00300b00, 0x00110000, 0x00040000, 0x00000000, 0x00030000, 0x00040100, 0x00000302, 0x00000303, 0x00000000, 0x00030000, 0x000f0000, 0x00301003, 0x005c2a16, 0x00834023, 0x00a04924, 0x00ac4c20, 0x00ac4c19, 0x00ac4b15, 0x00ac4c14, 0x00ac4913, 0x00ad4a12, 0x00b04b15, 0x00b14b17, 0x00af4a19, 0x00ad491c, 0x00ac491e, 0x00a8481f, 0x00a7471d, 0x00ab4a20, 0x00ae4d21, 0x00aa4818, 0x00a84414, 0x00ac4815, 0x00b04c18, 0x00b34c17, 0x00b14a16, 0x00ae4918, 0x00a8481a, 0x00a14821, 0x009c492a, 0x008c4128, 0x0071301e, 0x00572011, 0x00370c00, 0x001e0100, 0x00140200, 0x00090100, 0x00020000, 0x00000000, 0x00000004, 0x00030207, 0x00050000, 0x000b0000, 0x001e0400, 0x00471f04, 0x00743c1b, 0x00924c22, 0x00a04c1f, 0x00aa4c1b, 0x00b04918, 0x00b24817, 0x00b34817, 0x00b24815, 0x00b04915, 0x00ae4a15, 0x00ad4b15, 0x00ac4a16, 0x00ae4b19, 0x00b14918, 0x00b04814, 0x00ab4c14, 0x00ac4f18, 0x00af4819, 0x009d4420, 0x005c2410, 0x00240000, 0x00300e00, 0x006a3b21, 0x00a05323, 0x00aa4c14, 0x00b04c16, 0x00b24911, 0x00b44b0b, 0x00c0530c, 0x00c8540b, 0x00c6540a, 0x00c25711, 0x00984611, 0x00421a06, 0x000d0000, 0x00060000, 0x00302c29, 0x008e8a85, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00919499, 0x0031292a, 0x00140000, 0x00542100, 0x00a04c14, 0x00c05814, 0x00c35610, 0x00c2540c, 0x00be5409, 0x00c15b12, 0x00b2510f, 0x00a45622, 0x00310000, 0x002e0c00, 0x007b5643, 0x0045220c, 0x00210300, 0x00330a00, 0x0079340d, 0x00b05621, 0x00ba5110, 0x00be510b, 0x00ba540c, 0x00b7530b, 0x00b65007, 0x00b65008, 0x00b5520d, 0x00b75313, 0x00b75014, 0x00b25019, 0x00a95426, 0x006d2c0c, 0x002c0400, 0x00170000, 0x002c0700, 0x006f3924, 0x00a04f22, 0x00b45216, 0x00ba520f, 0x00b15416, 0x008a481e, 0x00592f14, 0x00110000, 0x000f0000, 0x001b0000, 0x00713f23, 0x009e5024, 0x00ad4c14, 0x00bb4f0e, 0x00b84908, 0x00c0541a, 0x00b44a17, 0x00b54b1d, 0x00b74b1c, 0x00b84c15, 0x00b84e12, 0x00b84f0f, 0x00b84f0f, 0x00b94c11, 0x00b94c10, 0x00b74d0b, 0x00b45210, 0x00a6521c, 0x008c491e, 0x00592b0c, 0x00280800, 0x00140000, 0x000c0000, 0x00080000, 0x00140200, 0x004b1d00, 0x0087461c, 0x00a04e28, 0x008e3405, 0x00b45515, 0x00bc5c14, 0x00b85614, 0x00b55010, 0x00ba4910, 0x00b6480e, 0x00af4912, 0x00aa4b16, 0x00a64a18, 0x009a4c24, 0x0065301d, 0x00280b04, 0x00050000, 0x00030303, 0x00050000, 0x000e0000, 0x002e0600, 0x00743819, 0x009c4b24, 0x00a94a1d, 0x00af4b18, 0x00b24814, 0x00b34412, 0x00b64815, 0x00b44a16, 0x00ae4814, 0x00ae4a17, 0x00ae491a, 0x00b04518, 0x00b34b1c, 0x00ac4818, 0x00a84c1e, 0x009c4821, 0x0064250b, 0x00190000, 0x001c0000, 0x00763d25, 0x00984a24, 0x00a94918, 0x00ae4410, 0x00b34b1b, 0x00ad4618, 0x00ae491a, 0x00ac491c, 0x00a94c25, 0x008e4427, 0x00441f0f, 0x000f0000, 0x000d0000, 0x00200400, 0x00884822, 0x00a84d1f, 0x00ae4719, 0x00b44917, 0x00b24a0e, 0x00b34d0c, 0x00bb5210, 0x00bf5511, 0x00c55710, 0x00bd520b, 0x00bb5b16, 0x00a95419, 0x00712c00, 0x00451100, 0x00341200, 0x00200c00, 0x000d0000, 0x00070000, 0x00060000, 0x00040100, 0x00000200, 0x00000401, 0x00000605, 0x00000302, 0x00050100, 0x000b0000, 0x00200600, 0x004c2010, 0x007e3c24, 0x009c4b29, 0x00a44e21, 0x00a74c19, 0x00ac4c16, 0x00ac4a12, 0x00ad4914, 0x00b04a16, 0x00b04917, 0x00ae4718, 0x00ab461d, 0x00a84822, 0x00983d1c, 0x008f3817, 0x00933c1b, 0x009f4825, 0x00a74f28, 0x00a74e24, 0x00a54c20, 0x00a74a19, 0x00b04817, 0x00b14512, 0x00b44814, 0x00b44a16, 0x00ae4618, 0x00ab481f, 0x00a84c28, 0x009e492a, 0x0094472b, 0x007b381d, 0x00602c14, 0x00441f0a, 0x002a1000, 0x00180600, 0x000f0000, 0x00080000, 0x00040000, 0x00070000, 0x00080000, 0x000b0000, 0x00180000, 0x003c1800, 0x006b3819, 0x008f4c27, 0x00a24e22, 0x00aa4c1b, 0x00b04915, 0x00b34813, 0x00b24814, 0x00b04914, 0x00ad4b15, 0x00ab4b18, 0x00aa4c1a, 0x00ac4c1c, 0x00ae491a, 0x00ac4814, 0x00ac4c14, 0x00ad4e19, 0x00a5451b, 0x00903e1e, 0x004b1705, 0x00220000, 0x004b200c, 0x0084492c, 0x00a44e1c, 0x00af4c12, 0x00ae4811, 0x00b34b0f, 0x00bb500c, 0x00c7580f, 0x00c8540a, 0x00c65610, 0x00b8571c, 0x006f2800, 0x00250700, 0x00060000, 0x000c0805, 0x004f4c47, 0x00b4b1aa, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a6acb4, 0x0039383d, 0x000e0000, 0x00411700, 0x008c4110, 0x00bb5a18, 0x00c1550d, 0x00c35004, 0x00c55405, 0x00c3580c, 0x00b4520e, 0x00a85a28, 0x00431300, 0x002c0400, 0x00874c30, 0x00743d20, 0x002d1000, 0x00190000, 0x005e2a0c, 0x009c5025, 0x00b2541a, 0x00b85010, 0x00b75310, 0x00b6510d, 0x00b84f0c, 0x00b9500c, 0x00b6500a, 0x00b5510e, 0x00b44f12, 0x00b0531c, 0x00a75828, 0x00531a00, 0x001a0000, 0x00220700, 0x0064301a, 0x00944c24, 0x00aa511a, 0x00b45214, 0x00b44f0e, 0x00a7501a, 0x007a4022, 0x002c0a00, 0x000b0000, 0x00130000, 0x00481700, 0x00904924, 0x00af5520, 0x00b34f0f, 0x00b94d0c, 0x00ba4a0b, 0x00bc4d19, 0x00b94a1b, 0x00b94b19, 0x00b64a15, 0x00b64e11, 0x00b4500f, 0x00b1500e, 0x00b4500e, 0x00b84d11, 0x00b84a0e, 0x00b84b0c, 0x00b0551b, 0x008c4c20, 0x00582e0f, 0x00230700, 0x000e0000, 0x00140300, 0x000a0000, 0x00090000, 0x00100000, 0x00220600, 0x003d1400, 0x00763b1d, 0x008f4219, 0x00b25215, 0x00c45915, 0x00c35314, 0x00c45215, 0x00c04f12, 0x00b5480c, 0x00b34b0e, 0x00b04d12, 0x00a94812, 0x00a54e20, 0x00864424, 0x0052240f, 0x00180200, 0x00060000, 0x00070300, 0x00050000, 0x00100000, 0x00350f00, 0x00803d1d, 0x00a44e27, 0x00a7481b, 0x00ac4517, 0x00b44917, 0x00ae440e, 0x00ae490e, 0x00ad4c0e, 0x00ad4a0f, 0x00b04b14, 0x00b04513, 0x00b34718, 0x00ab4618, 0x00a74b1f, 0x00994920, 0x00642503, 0x00270000, 0x00481906, 0x00893f1e, 0x00a9491f, 0x00b54715, 0x00b44813, 0x00a44816, 0x00a54f1d, 0x00a74a19, 0x00a94c1f, 0x00a54925, 0x008c4428, 0x003b180b, 0x000e0000, 0x000e0000, 0x00391300, 0x009a4c2a, 0x00aa471c, 0x00af4819, 0x00b14c14, 0x00b3520b, 0x00bb580c, 0x00c35810, 0x00c0510d, 0x00c35611, 0x00b85618, 0x009c4f1f, 0x006c2e09, 0x003b0800, 0x00380900, 0x00794827, 0x00623714, 0x003c1c00, 0x001b0500, 0x000d0000, 0x00030000, 0x00000103, 0x00000405, 0x00000000, 0x00050000, 0x00060103, 0x00020001, 0x00030000, 0x00140502, 0x003b1408, 0x006e331d, 0x00944c28, 0x00a14d20, 0x00ae4e1c, 0x00ac4814, 0x00ac4919, 0x00b04c1c, 0x00b34819, 0x00b14517, 0x00b14519, 0x00ae4921, 0x0090391a, 0x00702309, 0x00601b07, 0x006d2c17, 0x00834024, 0x00924828, 0x009c4e25, 0x00a44d20, 0x00ae4719, 0x00b44717, 0x00b24815, 0x00b04915, 0x00ae4a15, 0x00ad4c16, 0x00ab4c17, 0x00a94b19, 0x00a84c1b, 0x00a2491c, 0x009e4d24, 0x00924925, 0x00743818, 0x005a260c, 0x00481c06, 0x00371504, 0x00240c01, 0x00120000, 0x000b0000, 0x000e0000, 0x000c0000, 0x00110000, 0x00361201, 0x00633016, 0x008e4824, 0x009c481b, 0x00aa4814, 0x00b04a11, 0x00b14812, 0x00ae4712, 0x00ac4817, 0x00ab4c1c, 0x00a84b20, 0x00a5491d, 0x00aa4d20, 0x00ac4a1a, 0x00b04b15, 0x00ac4b18, 0x00a14d28, 0x00733017, 0x00330500, 0x00380c00, 0x0074381e, 0x009c4c27, 0x00ac491a, 0x00b64d15, 0x00ae490c, 0x00b44c09, 0x00c4560b, 0x00c65407, 0x00c45104, 0x00c05917, 0x009c4c1f, 0x00451300, 0x00110000, 0x00010004, 0x00201f20, 0x00787874, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0066696d, 0x0044474c, 0x00110301, 0x00300c00, 0x007a380c, 0x00b55c1f, 0x00c2580f, 0x00c95607, 0x00c95607, 0x00c05306, 0x00b75310, 0x00a85a28, 0x00582710, 0x00280000, 0x00874525, 0x00905230, 0x00391905, 0x001a0000, 0x00451b01, 0x00834420, 0x00ae5421, 0x00b75215, 0x00b55313, 0x00b65210, 0x00b94f10, 0x00ba500f, 0x00b64f0c, 0x00b6510e, 0x00b55014, 0x00ab4f19, 0x009d5220, 0x00481400, 0x001b0100, 0x002c1105, 0x00763b1c, 0x00a35323, 0x00ad5014, 0x00b35010, 0x00b25215, 0x009b4c1c, 0x00572714, 0x00140000, 0x000e0000, 0x001e0200, 0x00773719, 0x00a75124, 0x00b0521a, 0x00b44e0f, 0x00b9500e, 0x00b94b0f, 0x00bc4c17, 0x00b74715, 0x00ba4b17, 0x00b84d13, 0x00b75110, 0x00af4d09, 0x00b04f0c, 0x00b35010, 0x00b44a0e, 0x00b84e14, 0x00ae4c14, 0x009c5020, 0x005b2e10, 0x00200a00, 0x000e0000, 0x00080000, 0x00080000, 0x000d0000, 0x00140000, 0x00240700, 0x003c1b09, 0x003c1400, 0x00401000, 0x006f2e08, 0x00b35926, 0x00bc5318, 0x00c65617, 0x00c45210, 0x00c55510, 0x00c45610, 0x00b54a06, 0x00b2490b, 0x00af4912, 0x00a84918, 0x00a04d24, 0x007c3a1a, 0x00401500, 0x00140000, 0x000a0000, 0x00080000, 0x000c0000, 0x001e0000, 0x00541500, 0x00903e1a, 0x00a84b24, 0x00ae4a1f, 0x00b14b1a, 0x00ae4813, 0x00af4e14, 0x00ac4c10, 0x00ac4a10, 0x00af4912, 0x00b04311, 0x00b4471b, 0x00af461c, 0x00a8481f, 0x00a04c20, 0x007c350d, 0x00612608, 0x00743516, 0x009c471f, 0x00ac4818, 0x00b34412, 0x00b24814, 0x00a34917, 0x00a34e1c, 0x00a84918, 0x00aa4b1c, 0x00a14824, 0x00844027, 0x00321406, 0x000f0000, 0x001c0100, 0x00592610, 0x00a34b24, 0x00b04514, 0x00b84c17, 0x00bf5415, 0x00bc5806, 0x00bc5704, 0x00c35812, 0x00c45b1c, 0x00b5541c, 0x00994816, 0x00642806, 0x003c0c00, 0x00380a00, 0x00401100, 0x0074411c, 0x00986238, 0x00855126, 0x005a2c08, 0x002d0c00, 0x00130000, 0x00060000, 0x00030000, 0x00050000, 0x00050000, 0x00020000, 0x00020306, 0x00000405, 0x00000000, 0x00100000, 0x002d0700, 0x005c2812, 0x00874424, 0x009c481e, 0x00ab5020, 0x00aa4b1c, 0x00a54113, 0x00b04516, 0x00b84b1b, 0x00b5481a, 0x00ac461c, 0x00a34a26, 0x00853a1d, 0x00541702, 0x00350000, 0x00420d00, 0x00642c15, 0x007c4023, 0x008c4423, 0x00a24924, 0x00aa4820, 0x00aa4b1e, 0x00a84918, 0x00a74813, 0x00a84810, 0x00aa4810, 0x00ad480f, 0x00b04b14, 0x00b14c16, 0x00ad4b1b, 0x00a4481c, 0x00a04c24, 0x00a05430, 0x00914b2b, 0x00723518, 0x005b2810, 0x0049200c, 0x003b1609, 0x002f1006, 0x00200500, 0x00160000, 0x00200000, 0x00340700, 0x00602404, 0x00873d14, 0x00a74f20, 0x00ab4c17, 0x00aa4613, 0x00ae4a17, 0x00ae4b1b, 0x00a74417, 0x00ab4a1e, 0x00a8481c, 0x00ab4c1d, 0x00ac4a18, 0x00b04914, 0x00a8481a, 0x00974d2c, 0x005c240d, 0x00310400, 0x0053200a, 0x008f4424, 0x00a84c21, 0x00ad4818, 0x00b34910, 0x00b04908, 0x00bc510a, 0x00c55306, 0x00c55306, 0x00c75a14, 0x00b1561d, 0x006b2c0b, 0x002c0800, 0x000e0303, 0x00000007, 0x00474747, 0x00a2a39f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005b5a5e, 0x00180c0c, 0x001d0000, 0x00662c08, 0x00ac5922, 0x00bf5710, 0x00c95809, 0x00ca580a, 0x00bd5206, 0x00b85510, 0x00a85724, 0x00703c22, 0x00280000, 0x00773b1b, 0x00955b3a, 0x00552e16, 0x00260400, 0x002e0700, 0x006f3614, 0x00a95321, 0x00b55217, 0x00b45214, 0x00b55111, 0x00b95113, 0x00b85010, 0x00b5500d, 0x00b65010, 0x00b95114, 0x00ad5018, 0x00a05524, 0x00441100, 0x00170000, 0x00260900, 0x0074391a, 0x00a85526, 0x00b05116, 0x00b25112, 0x00ac5119, 0x0086411a, 0x00321003, 0x000e0000, 0x00180000, 0x00471b03, 0x009b5027, 0x00b05421, 0x00ac4d15, 0x00b04d12, 0x00b85013, 0x00b64c10, 0x00ba4c13, 0x00b74910, 0x00b94c12, 0x00b74c10, 0x00b64d0f, 0x00b34b0c, 0x00b75112, 0x00b85214, 0x00b0480e, 0x00af4d18, 0x00a15223, 0x00683110, 0x00280d01, 0x00080000, 0x00060000, 0x00080100, 0x00080000, 0x00170000, 0x00380c00, 0x00652e15, 0x00874924, 0x00773c14, 0x00481600, 0x00400800, 0x00752c06, 0x00a74f1e, 0x00b55614, 0x00c15b0d, 0x00c25100, 0x00ca5503, 0x00c45408, 0x00bf5110, 0x00b44a13, 0x00b34c1c, 0x00ae4a1c, 0x00a14920, 0x00743010, 0x00400c00, 0x00260400, 0x00260c00, 0x002e1000, 0x003b0e00, 0x005a1500, 0x00903a18, 0x00a34523, 0x00a5441e, 0x00ab471c, 0x00ab4819, 0x00ab4c1b, 0x00a54714, 0x00a94917, 0x00ad4819, 0x00af4317, 0x00b4471d, 0x00b1461d, 0x00aa451c, 0x00a84d22, 0x009a461a, 0x009c4c22, 0x009e4d22, 0x00a7501f, 0x00a74b17, 0x00ac4813, 0x00af4b18, 0x00a84a19, 0x00aa4a1a, 0x00ac4210, 0x00b04b1c, 0x00a45029, 0x007c4125, 0x00230c00, 0x000c0000, 0x00230000, 0x00793821, 0x00ac4c1c, 0x00be4c0c, 0x00c74e0c, 0x00c85005, 0x00c85300, 0x00c65805, 0x00be5716, 0x00ac5220, 0x008a451e, 0x00541f00, 0x003b0f00, 0x00542909, 0x00693817, 0x00481400, 0x003a0d00, 0x007d4928, 0x00a85d2e, 0x00a75828, 0x00823f1c, 0x00501c04, 0x00200400, 0x000c0000, 0x000a0100, 0x00040000, 0x00000000, 0x00000200, 0x00000200, 0x00030400, 0x000c0000, 0x000e0000, 0x001c0400, 0x00431f10, 0x007b4425, 0x008f491f, 0x00a75224, 0x00ae4e1d, 0x00a94110, 0x00af4411, 0x00b34b1b, 0x00aa4618, 0x00a8491b, 0x00a04c22, 0x00803a18, 0x00501800, 0x002b0000, 0x001d0000, 0x002f0c01, 0x00542719, 0x00753820, 0x008c4324, 0x009c4e2c, 0x00a04e27, 0x00a44c20, 0x00ab4c1d, 0x00af4c1a, 0x00af4814, 0x00af4814, 0x00ab4410, 0x00ad4818, 0x00b04d1e, 0x00a8481c, 0x00a3451a, 0x00a84c23, 0x00ad542c, 0x00a8512c, 0x009d4c28, 0x008b4424, 0x0078381c, 0x00642c12, 0x00501f06, 0x00421300, 0x003c0900, 0x00400900, 0x00612200, 0x00883c16, 0x009d481f, 0x00a4481d, 0x00ab481b, 0x00b14a1e, 0x00b54d1f, 0x00b24818, 0x00b04714, 0x00b34a14, 0x00af4811, 0x00ad4914, 0x00a14a1d, 0x0089472c, 0x004c1702, 0x00440d00, 0x00783820, 0x00a05029, 0x00a84d1c, 0x00ac4a14, 0x00b04a0e, 0x00b84c08, 0x00c6550c, 0x00cc5609, 0x00c2530a, 0x00bf5f22, 0x00904419, 0x003e0d00, 0x00170000, 0x00060000, 0x001c1c1d, 0x00787877, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00797878, 0x00241c1c, 0x00150000, 0x00522205, 0x009a5220, 0x00bc5814, 0x00c35305, 0x00c65608, 0x00c05509, 0x00ba5511, 0x00a8541d, 0x0084482b, 0x00310000, 0x005e2708, 0x00854f30, 0x00774a30, 0x00371000, 0x00220000, 0x005c280a, 0x009d4d1e, 0x00b25118, 0x00b25014, 0x00b25011, 0x00b85014, 0x00b74f10, 0x00b5500f, 0x00b65011, 0x00bb5115, 0x00ae4f18, 0x00a15929, 0x00441300, 0x00140000, 0x001c0000, 0x00703213, 0x00a65224, 0x00b05116, 0x00af5114, 0x009c4c1a, 0x00682e0e, 0x001d0300, 0x00120000, 0x00270200, 0x007b401e, 0x00a75220, 0x00b14f17, 0x00ae4c15, 0x00b35018, 0x00b44e14, 0x00b34b0e, 0x00b84f10, 0x00b74e0e, 0x00b74e10, 0x00b54c0e, 0x00b44a0c, 0x00b84d11, 0x00b84c12, 0x00b24c13, 0x00ae4c17, 0x00a14f20, 0x00743918, 0x002d0900, 0x000a0000, 0x00070308, 0x00020004, 0x00050000, 0x00140000, 0x00381101, 0x00703117, 0x009c4e27, 0x00a75423, 0x00a25524, 0x007f421a, 0x00501700, 0x00440200, 0x00651c00, 0x009b4d17, 0x00ac5410, 0x00be5608, 0x00cc5f0c, 0x00c55306, 0x00c75710, 0x00c25517, 0x00b54a10, 0x00b2470e, 0x00b14c16, 0x009b4215, 0x007c330d, 0x00692e12, 0x0068341c, 0x00743c22, 0x00834426, 0x00924321, 0x00a74d28, 0x00a74824, 0x00a94820, 0x00b04c21, 0x00ac4b1d, 0x00aa4d1e, 0x00a94c1c, 0x00a8491b, 0x00ad4b1d, 0x00ad4419, 0x00b1461c, 0x00b1461c, 0x00ac4418, 0x00ab4b1b, 0x00a84c1b, 0x00ab4c1d, 0x00a94b1a, 0x00a44b16, 0x00a44911, 0x00a84911, 0x00ac4a14, 0x00aa4717, 0x00ac4414, 0x00b74716, 0x00b2481a, 0x0099441c, 0x006c3011, 0x001d0200, 0x00140000, 0x003b0700, 0x009c4d30, 0x00b85218, 0x00ca540c, 0x00cc560c, 0x00cc5508, 0x00c95809, 0x00c05a13, 0x00a24c18, 0x007a3714, 0x00411200, 0x00280400, 0x00502802, 0x00916136, 0x00a26638, 0x007c431c, 0x00380d00, 0x00390c00, 0x00813c15, 0x00ab5b2c, 0x00ae5a2c, 0x00954a21, 0x00683310, 0x00351100, 0x00150000, 0x00080000, 0x00050200, 0x00030300, 0x00000100, 0x00020000, 0x00080000, 0x00080000, 0x00050001, 0x000f0000, 0x00301201, 0x00663619, 0x008f4c24, 0x009e4c1d, 0x00ab4c1b, 0x00af4c18, 0x00ac4817, 0x00ae4c1c, 0x00ac4c19, 0x00a24818, 0x009d5025, 0x0081401e, 0x00461500, 0x00270100, 0x001f0100, 0x00150000, 0x00270100, 0x00481c09, 0x006c3821, 0x00804428, 0x00904827, 0x009f4d27, 0x00a74c22, 0x00a64519, 0x00ae4a1c, 0x00ac4718, 0x00ad4618, 0x00b0481a, 0x00b0491b, 0x00af4818, 0x00ad4716, 0x00ab4414, 0x00ae4817, 0x00ad491b, 0x00a84a20, 0x00a04b23, 0x009b4f2a, 0x0096502e, 0x008c4b2b, 0x00834424, 0x00723010, 0x006c2704, 0x00772905, 0x00933e16, 0x00aa4e23, 0x00af4b20, 0x00ac4316, 0x00ac4012, 0x00b24514, 0x00b44612, 0x00b54810, 0x00b14710, 0x00ac4b17, 0x00a14e24, 0x0078381c, 0x00501501, 0x00692610, 0x0094482a, 0x00a74e21, 0x00a74811, 0x00aa4c10, 0x00b45010, 0x00c4540e, 0x00ca540a, 0x00c65306, 0x00c15916, 0x00a85828, 0x005c2405, 0x00250400, 0x000d0000, 0x00050000, 0x004d4c49, 0x00a4a5a1, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a29d9d, 0x00383434, 0x000f0000, 0x003a1500, 0x0082441b, 0x00b95d1d, 0x00bf5408, 0x00c35408, 0x00c6580d, 0x00ba540c, 0x00ac5319, 0x0093502d, 0x003a0500, 0x003f0f00, 0x0078482a, 0x008e593d, 0x004f1e05, 0x00230000, 0x00431800, 0x008e4319, 0x00ac501c, 0x00b15016, 0x00b25012, 0x00b65013, 0x00b44e10, 0x00b45010, 0x00b55012, 0x00b95014, 0x00aa4b14, 0x009e5626, 0x00441400, 0x00190000, 0x00200300, 0x00743212, 0x00a85122, 0x00ad4f15, 0x00a95018, 0x0086441c, 0x00401500, 0x000f0000, 0x00160000, 0x00501d01, 0x009c5224, 0x00af5017, 0x00b54d10, 0x00b44e17, 0x00b5511c, 0x00b44d14, 0x00b24c0f, 0x00b5500d, 0x00b34e0a, 0x00b24c0c, 0x00b85010, 0x00b7480c, 0x00bc4c12, 0x00b44710, 0x00ad4916, 0x00a85225, 0x007f401f, 0x00330f00, 0x000e0000, 0x00040000, 0x00020105, 0x00030001, 0x00100000, 0x003a1305, 0x0075381d, 0x009f4c21, 0x00b3541f, 0x00ac4b10, 0x00a94e15, 0x009f4f1f, 0x008f4822, 0x00642408, 0x00400400, 0x00440900, 0x0084401b, 0x00ab541e, 0x00b5500d, 0x00c05207, 0x00c85809, 0x00c25506, 0x00c55a0c, 0x00c2560c, 0x00bc530c, 0x00b24d10, 0x00ab4c15, 0x00a44c1d, 0x00a04b21, 0x00a14b24, 0x00a64e24, 0x00a84c1e, 0x00ac4c1c, 0x00a94718, 0x00ab4818, 0x00ac4a18, 0x00a44412, 0x00a34714, 0x00a74c19, 0x00a64918, 0x00ac4d1c, 0x00ab4818, 0x00ac4615, 0x00ae4616, 0x00ac4511, 0x00ac4812, 0x00ac4814, 0x00ac4417, 0x00ab4618, 0x00a74813, 0x00a74a10, 0x00aa4a0d, 0x00ac4910, 0x00ae4814, 0x00af4514, 0x00b44111, 0x00b24418, 0x009c431c, 0x006d2b09, 0x00260000, 0x00240000, 0x00500e00, 0x00b0572a, 0x00c15514, 0x00ca570a, 0x00ca560c, 0x00bf540e, 0x00af5216, 0x00964a1c, 0x00642d0e, 0x00330900, 0x001e0000, 0x00240400, 0x00693908, 0x00b07135, 0x00b5682b, 0x00a96434, 0x005b3018, 0x001a0000, 0x002c0500, 0x00754121, 0x00a45625, 0x00b35a21, 0x00ac5d23, 0x007e3e0d, 0x00411900, 0x001f0800, 0x00080000, 0x00060300, 0x00080400, 0x00040000, 0x00080000, 0x00080000, 0x00080009, 0x00030005, 0x00070000, 0x001e0800, 0x00532810, 0x00834824, 0x009a4d1f, 0x00a54d1b, 0x00a94e1c, 0x00a44815, 0x00a64918, 0x00a84c1f, 0x00a0471a, 0x009d4c24, 0x00904a2a, 0x00582008, 0x00240000, 0x001c0000, 0x000c0000, 0x000b0000, 0x001a0300, 0x00361709, 0x005b2e18, 0x007b4026, 0x0091492c, 0x009f4a28, 0x00a74825, 0x00ae4923, 0x00b04720, 0x00af4419, 0x00ae4618, 0x00b04917, 0x00ae4c15, 0x00ae4c15, 0x00af4816, 0x00ae491a, 0x00ac4a1c, 0x00a84a20, 0x00a54c24, 0x00a44e28, 0x00a34c27, 0x00a04924, 0x00a44b23, 0x00a84b22, 0x00aa4b1e, 0x00ac491a, 0x00ac4718, 0x00ad4716, 0x00b04818, 0x00b44c1a, 0x00b04614, 0x00b34814, 0x00b44710, 0x00b04811, 0x00a84a17, 0x00a24f23, 0x006e2809, 0x00652006, 0x00903d21, 0x00a44b24, 0x00a94814, 0x00ab480a, 0x00ad4e0c, 0x00b85410, 0x00cc5a13, 0x00c85109, 0x00bf4f08, 0x00b95c22, 0x007a3e1c, 0x002c0800, 0x00100000, 0x00050000, 0x0028231e, 0x0084817a, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00454443, 0x00504c4d, 0x000b0000, 0x00220600, 0x00653110, 0x00b25c23, 0x00c05910, 0x00c45509, 0x00c65809, 0x00bc530a, 0x00b15417, 0x00a0582d, 0x00440c00, 0x00270000, 0x006c4429, 0x008e5639, 0x006b3418, 0x002e0b00, 0x002c0500, 0x00773411, 0x00a34f21, 0x00b0531b, 0x00b25012, 0x00b55012, 0x00b34d10, 0x00b45012, 0x00b34e11, 0x00b84e14, 0x00ac4d18, 0x009d5829, 0x00451800, 0x00180000, 0x00240600, 0x00783210, 0x00aa5020, 0x00ab5018, 0x00a0501e, 0x006c381a, 0x00220400, 0x000e0000, 0x00240600, 0x00844621, 0x00a54f1b, 0x00b34e10, 0x00b54c0c, 0x00b54c14, 0x00b44c16, 0x00b44c12, 0x00b44f11, 0x00b4500c, 0x00af4d08, 0x00ae4c0a, 0x00b74f10, 0x00b7470b, 0x00bb4a13, 0x00b84c1c, 0x00ad5126, 0x00884522, 0x00401500, 0x00100000, 0x00030001, 0x00040102, 0x00060000, 0x00120000, 0x00431e11, 0x007c4028, 0x009f502b, 0x00ac4e1b, 0x00b85014, 0x00b64c0e, 0x00b74f13, 0x00ab4c17, 0x00aa5628, 0x00944d2c, 0x006f341a, 0x00390c00, 0x00300000, 0x005f1c00, 0x009b4819, 0x00ba5c1f, 0x00be5812, 0x00bd5508, 0x00c55b0a, 0x00c75a0b, 0x00c5580b, 0x00c2560e, 0x00c05412, 0x00bb5013, 0x00b54c10, 0x00b0470d, 0x00ac4309, 0x00af4610, 0x00b04811, 0x00ae4712, 0x00ad4611, 0x00ae4813, 0x00ac4914, 0x00a84914, 0x00a94b18, 0x00a74817, 0x00aa4a19, 0x00aa4818, 0x00a94414, 0x00ad4714, 0x00ae4712, 0x00ac450f, 0x00ac4510, 0x00af4418, 0x00b0471a, 0x00aa4812, 0x00ab490d, 0x00ad480a, 0x00ad4508, 0x00b24913, 0x00b44814, 0x00b84410, 0x00b74715, 0x00a74414, 0x00802f02, 0x004a0f00, 0x004c1200, 0x00762600, 0x00bb5c25, 0x00c05c18, 0x00b7520e, 0x00b45818, 0x00ab5821, 0x0080390c, 0x004b1000, 0x00380700, 0x003c1500, 0x00331405, 0x00290700, 0x00632f00, 0x00b06b27, 0x00b5601a, 0x00a85c23, 0x005a3016, 0x00130000, 0x000d0000, 0x00240500, 0x0072340d, 0x00ab5924, 0x00ac5718, 0x00b06024, 0x0099592a, 0x00572806, 0x002a0c00, 0x000d0000, 0x00060000, 0x000a0300, 0x000c0000, 0x00080000, 0x00040007, 0x00000008, 0x00010005, 0x00050000, 0x00170000, 0x00431b07, 0x00793f1e, 0x00944b22, 0x009c4a1c, 0x00a85020, 0x00a64c1d, 0x00a74c1c, 0x00a84b1c, 0x00a4491c, 0x00a04c24, 0x00984e2c, 0x0071341c, 0x003a0c00, 0x001e0600, 0x000b0000, 0x000c0000, 0x00100000, 0x001b0000, 0x002e0a00, 0x00522410, 0x007c4029, 0x0090482d, 0x009e492a, 0x00a44724, 0x00a9461d, 0x00ac481c, 0x00ad4a18, 0x00ab4a13, 0x00ad4b14, 0x00af4914, 0x00b04816, 0x00ad4819, 0x00ac481c, 0x00aa471d, 0x00a9461d, 0x00aa471e, 0x00ac481f, 0x00ad451c, 0x00af4619, 0x00af4415, 0x00ac4311, 0x00ae4413, 0x00b04915, 0x00af4816, 0x00a94512, 0x00ae4817, 0x00b04818, 0x00af4715, 0x00ad4916, 0x00a64a18, 0x00a04a1d, 0x00742703, 0x00803110, 0x00a44824, 0x00ab471c, 0x00af460c, 0x00b74f0c, 0x00b55109, 0x00bc550c, 0x00cc5b11, 0x00c2510b, 0x00c15d1d, 0x00984b1b, 0x00421702, 0x00100000, 0x00030003, 0x00030206, 0x00645e59, 0x00b5b0a8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00706e70, 0x001c1514, 0x00100000, 0x00491f05, 0x00994e1b, 0x00bc5b17, 0x00c8590b, 0x00c55404, 0x00c25408, 0x00b65412, 0x00a85828, 0x00571c00, 0x00200000, 0x00482814, 0x0081492e, 0x00874c30, 0x00411a00, 0x00230000, 0x005c2206, 0x00944a24, 0x00ad531e, 0x00b44f11, 0x00b74f10, 0x00b44c0e, 0x00b65014, 0x00b24d12, 0x00b44c16, 0x00af5320, 0x009c582c, 0x00411500, 0x00150000, 0x002e0c00, 0x00823611, 0x00ab4e1d, 0x00a8501d, 0x008d4820, 0x0048230e, 0x00150000, 0x00200300, 0x0054260f, 0x00a1562b, 0x00ab4d15, 0x00b34e10, 0x00b44c0d, 0x00b54a10, 0x00b44810, 0x00b74a0f, 0x00b74e10, 0x00b34f0d, 0x00b04f0c, 0x00af4c0c, 0x00b44c0f, 0x00b8480f, 0x00b74816, 0x00b05025, 0x00934826, 0x004d2109, 0x00100000, 0x00060000, 0x00030001, 0x00080000, 0x001d0400, 0x00481900, 0x00803e1c, 0x00a7552f, 0x00a84c1e, 0x00b04d18, 0x00b44b11, 0x00b44608, 0x00bc4d11, 0x00b64d17, 0x00ad4c19, 0x00a64e1f, 0x009a552e, 0x007c553d, 0x00331402, 0x00250000, 0x00370000, 0x006c2602, 0x009c4a1c, 0x00b5571d, 0x00bc5512, 0x00bf500a, 0x00c4530b, 0x00c95610, 0x00c95610, 0x00c6530c, 0x00c45309, 0x00c45406, 0x00c35307, 0x00ba490a, 0x00b7460d, 0x00b4440d, 0x00b0430b, 0x00b0440e, 0x00b14812, 0x00ad4612, 0x00ab4412, 0x00ac4818, 0x00a94616, 0x00aa4717, 0x00aa4516, 0x00ad4716, 0x00af4715, 0x00af4512, 0x00ad4514, 0x00ac4418, 0x00ad481a, 0x00ac4511, 0x00b1480e, 0x00b44509, 0x00b44408, 0x00b84a12, 0x00b84912, 0x00c34e12, 0x00c45010, 0x00c55815, 0x00bf5d1b, 0x00b06024, 0x00ae6027, 0x00b3561c, 0x00b95b21, 0x00b25b24, 0x00a75c2c, 0x00814922, 0x004c1d00, 0x00320000, 0x004b1100, 0x007f3c0a, 0x0098592c, 0x00512207, 0x002f0500, 0x005c2800, 0x00a96826, 0x00b96219, 0x00aa5c1f, 0x00542b0d, 0x000d0000, 0x000c0402, 0x00080000, 0x00210000, 0x005b2708, 0x009b5323, 0x00b66026, 0x00b45618, 0x00ac5620, 0x00773812, 0x003d1500, 0x000c0000, 0x00040000, 0x00080000, 0x00040000, 0x00000000, 0x00020200, 0x00020000, 0x00030000, 0x00060000, 0x000f0000, 0x00330c00, 0x006b311d, 0x00944927, 0x009d481e, 0x00a04819, 0x00a44a1a, 0x00a84e1e, 0x00a64c1d, 0x00a2461a, 0x00a44820, 0x00a24b2a, 0x0096482c, 0x0061250c, 0x003f1100, 0x00210000, 0x00140000, 0x00100000, 0x000b0000, 0x000d0000, 0x00180100, 0x00401c09, 0x006c3c20, 0x008f4d2d, 0x00984c25, 0x00a1491f, 0x00aa4b1c, 0x00ac481a, 0x00ac4614, 0x00b04812, 0x00af4811, 0x00b04814, 0x00b04918, 0x00af481a, 0x00ad451c, 0x00ae451c, 0x00b1461d, 0x00af4419, 0x00b2461a, 0x00b4481c, 0x00b44b19, 0x00b04817, 0x00ad4714, 0x00ac4815, 0x00ad4c19, 0x00ac491a, 0x00aa491d, 0x00a8481c, 0x00aa4b1c, 0x00a6491a, 0x009f4416, 0x0090380e, 0x009c4118, 0x00aa4820, 0x00ad4716, 0x00b5480c, 0x00c0510a, 0x00c25408, 0x00c35607, 0x00c7580c, 0x00bc5512, 0x00a85620, 0x005a2100, 0x00170000, 0x00030001, 0x0000010b, 0x0034363d, 0x009f9896, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00909092, 0x00383534, 0x000b0000, 0x00341300, 0x007e3d11, 0x00b4591b, 0x00ca5c10, 0x00c55000, 0x00c75708, 0x00b8520b, 0x00ac541f, 0x006c2d07, 0x00230600, 0x00200700, 0x00784028, 0x00985c40, 0x0050250a, 0x00280000, 0x00451500, 0x00844427, 0x00a85120, 0x00b24d10, 0x00b64f0e, 0x00b54c0c, 0x00b75014, 0x00b14c13, 0x00b34c18, 0x00ab5022, 0x00905028, 0x00380d00, 0x001a0000, 0x00451c08, 0x00934218, 0x00ad511f, 0x00a05125, 0x00783e1d, 0x002b0c00, 0x00130000, 0x00380d00, 0x008a4b28, 0x00a04c1a, 0x00b45218, 0x00b44f12, 0x00b64e11, 0x00ba4c13, 0x00b94b10, 0x00b84a10, 0x00b54b0f, 0x00b04b0d, 0x00b35012, 0x00b24c0f, 0x00b34a10, 0x00bb501b, 0x00ac481c, 0x00974623, 0x00642d14, 0x001a0000, 0x00060000, 0x00050000, 0x00100200, 0x00180000, 0x00471800, 0x008d471f, 0x00a85122, 0x00ac4c1c, 0x00b14d1a, 0x00b04a16, 0x00b54b14, 0x00b7480e, 0x00b9490d, 0x00b4470f, 0x00b34a14, 0x00b3501a, 0x009e5123, 0x007a5238, 0x00240900, 0x00381000, 0x00420e00, 0x003b0000, 0x004a0400, 0x007c3106, 0x00a3511e, 0x00b75c24, 0x00b85618, 0x00bf5415, 0x00c55413, 0x00c5540e, 0x00c75408, 0x00c85502, 0x00c45303, 0x00c95513, 0x00c45114, 0x00c45214, 0x00c35213, 0x00bd4d0e, 0x00b8480b, 0x00b4460c, 0x00b84b11, 0x00b44812, 0x00ac440d, 0x00ac450f, 0x00af4811, 0x00ae4710, 0x00b0470f, 0x00b0450c, 0x00b34710, 0x00b24714, 0x00b64c18, 0x00b64b10, 0x00be5211, 0x00c3530f, 0x00c2500d, 0x00c65618, 0x00c55417, 0x00cc5413, 0x00cb540e, 0x00c9570c, 0x00bd560d, 0x00b05a1a, 0x00ae5e22, 0x00b25f24, 0x00ac5b26, 0x008f471c, 0x00581e00, 0x002a0000, 0x00340a00, 0x0068330c, 0x00995828, 0x00b56424, 0x00ac6126, 0x00693411, 0x00270000, 0x00522000, 0x00a8692a, 0x00bc651c, 0x00a6591c, 0x004c2508, 0x000b0000, 0x00020000, 0x00080200, 0x00180100, 0x00260000, 0x00571c00, 0x00984918, 0x00b8571c, 0x00bc5b1f, 0x00ae5928, 0x008c4c26, 0x004b2611, 0x00170200, 0x000a0000, 0x00080100, 0x00040100, 0x00000000, 0x00020100, 0x00000000, 0x00020005, 0x00080004, 0x00100000, 0x00220000, 0x00521a06, 0x00844021, 0x009e5028, 0x00a04c20, 0x00a04819, 0x00a74a1b, 0x00ad4c1f, 0x00ab481c, 0x00a8441d, 0x00a54924, 0x009e502a, 0x008c4926, 0x006a3217, 0x00401300, 0x001e0000, 0x00130000, 0x000f0000, 0x000d0000, 0x00120000, 0x001d0100, 0x00370e00, 0x00632c10, 0x008c4a28, 0x009c4f2b, 0x009f4823, 0x00a84c20, 0x00a94918, 0x00ab4915, 0x00ac4815, 0x00ac4817, 0x00af4818, 0x00b0481a, 0x00b1471a, 0x00b0441a, 0x00b0471c, 0x00b0471c, 0x00ae471b, 0x00ab4618, 0x00ac4718, 0x00ad4a1a, 0x00ad4a18, 0x00aa4818, 0x00ab4a1c, 0x00a8481d, 0x00a5491e, 0x00a84c20, 0x00a84c1e, 0x009f4010, 0x00ab4c1c, 0x00ad4b1c, 0x00ad4a1a, 0x00b14812, 0x00b9490a, 0x00c15008, 0x00c9570a, 0x00c6580c, 0x00bd5710, 0x00b15b1f, 0x0073350a, 0x00230000, 0x00090000, 0x00000005, 0x000c131c, 0x007c7f86, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00585554, 0x000d0200, 0x00140000, 0x00612b07, 0x00ac5b23, 0x00c0580c, 0x00c85300, 0x00c95705, 0x00be5409, 0x00b05317, 0x00864418, 0x00240900, 0x00140000, 0x005c2a16, 0x00864c32, 0x00734124, 0x00390f00, 0x00300900, 0x00602c15, 0x00a9562a, 0x00b04d12, 0x00ba5111, 0x00b74d0c, 0x00b44c10, 0x00b44c16, 0x00b34f1c, 0x00a44d20, 0x00814724, 0x00360c00, 0x00200000, 0x00683319, 0x00a14a1d, 0x00a84c1c, 0x0094512e, 0x005c2d15, 0x00160000, 0x002a0800, 0x006a2c0b, 0x00a15122, 0x00b0521b, 0x00b04d14, 0x00b04e14, 0x00b34e13, 0x00ba4c13, 0x00bb4a10, 0x00b6480d, 0x00b74910, 0x00b74d14, 0x00b34a10, 0x00b34910, 0x00b34c15, 0x00ac4c1c, 0x00a04e28, 0x006d341b, 0x00240300, 0x00090000, 0x00000000, 0x00080000, 0x001a0000, 0x00511d04, 0x008e4520, 0x00a84e1b, 0x00af4c12, 0x00b34d14, 0x00b24b14, 0x00b44a17, 0x00b54916, 0x00b64711, 0x00b6480f, 0x00b44b10, 0x00b74f13, 0x00af460c, 0x00a85424, 0x005b2c10, 0x00250000, 0x007e411a, 0x00a2592d, 0x00833b10, 0x00521400, 0x00310300, 0x003b1000, 0x005c2a07, 0x00905025, 0x00ad5a29, 0x00b95822, 0x00c0581e, 0x00c25414, 0x00c55710, 0x00c4540c, 0x00c4540e, 0x00c55510, 0x00c5550f, 0x00c5540b, 0x00c75409, 0x00c8540a, 0x00c85308, 0x00c45008, 0x00c6530c, 0x00c4540d, 0x00c1540e, 0x00c15610, 0x00c15610, 0x00c25510, 0x00c3540e, 0x00c45310, 0x00c95415, 0x00c85413, 0x00c5560d, 0x00c25708, 0x00c45705, 0x00c45705, 0x00c4550c, 0x00c6530e, 0x00ca520e, 0x00cc5511, 0x00c04e09, 0x00b85515, 0x00ad612c, 0x009a5d2f, 0x007a4317, 0x004c1900, 0x00320000, 0x00350200, 0x00652c00, 0x00925019, 0x00ab5c22, 0x00ba6321, 0x00bb6017, 0x00b36423, 0x006f3814, 0x002e0400, 0x004c1c00, 0x00a06326, 0x00b5641c, 0x00a45c21, 0x00391a01, 0x00080000, 0x00050100, 0x00090000, 0x0058381e, 0x005f3010, 0x00360400, 0x004c1300, 0x00833c14, 0x00a95826, 0x00b3541b, 0x00b45a22, 0x009d5629, 0x006b3818, 0x00280a00, 0x000c0000, 0x000d0500, 0x00000000, 0x00000004, 0x00000108, 0x00040004, 0x00060001, 0x00070000, 0x000a0000, 0x00190000, 0x00360f03, 0x0070341d, 0x00924524, 0x00a84f24, 0x00ac491c, 0x00aa481a, 0x00ac481d, 0x00a94920, 0x00a1481e, 0x00a04d1f, 0x009a4d1f, 0x009a4d24, 0x00934c28, 0x007f4020, 0x005c250c, 0x00360a00, 0x001c0000, 0x00110000, 0x000f0000, 0x00110000, 0x00190000, 0x00300a00, 0x0053220c, 0x00793f23, 0x00955130, 0x009c4e28, 0x00a34d24, 0x00a74c20, 0x00a94919, 0x00ac4815, 0x00af4814, 0x00ae4814, 0x00ab4615, 0x00a9481c, 0x00a7491f, 0x00a74a23, 0x00a74a23, 0x00a94920, 0x00ac481f, 0x00ac4819, 0x00ac4818, 0x00aa4618, 0x00a9481b, 0x00a84c20, 0x00a84c20, 0x00a8481c, 0x00a74717, 0x00ab4814, 0x00ae4a14, 0x00b24c15, 0x00b85013, 0x00c1500f, 0x00c85510, 0x00c95812, 0x00bd5510, 0x00b45e20, 0x0080400f, 0x002c0800, 0x000d0000, 0x00070401, 0x00000005, 0x0060666c, 0x009b9ba0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007c7c7a, 0x0028201e, 0x00140000, 0x003c1000, 0x008d4819, 0x00bb5915, 0x00c85707, 0x00c85606, 0x00c25409, 0x00b45310, 0x00974f1f, 0x002d1000, 0x00140000, 0x003f1303, 0x007b452e, 0x00824e2e, 0x00481900, 0x00210000, 0x004b1f0e, 0x00984c26, 0x00b0531c, 0x00b24c0f, 0x00b54c0c, 0x00b44c10, 0x00b54e18, 0x00b04c18, 0x00a8542a, 0x006a3215, 0x002e0200, 0x00481500, 0x00803f20, 0x00aa5023, 0x00a75023, 0x007d4327, 0x003e1602, 0x00210000, 0x00481901, 0x008e4217, 0x00ac4e18, 0x00b35018, 0x00b04c13, 0x00b04e16, 0x00b04c14, 0x00b64c11, 0x00b84b11, 0x00b74911, 0x00b84b13, 0x00b84c15, 0x00b44812, 0x00b74b14, 0x00ae4b19, 0x00a35027, 0x007e4021, 0x003b1505, 0x000c0000, 0x00030000, 0x00040000, 0x00140000, 0x00502409, 0x008c4621, 0x00a54d1e, 0x00ac4913, 0x00b24c10, 0x00b44d13, 0x00b1480f, 0x00b44814, 0x00b74816, 0x00b74814, 0x00b74b14, 0x00b34a10, 0x00b34d14, 0x00ad4b15, 0x00984418, 0x00380400, 0x00532001, 0x00a0511f, 0x00b3591e, 0x00aa541c, 0x00a15a2a, 0x00724724, 0x003a1c00, 0x002b0c00, 0x002b0400, 0x004e1700, 0x007c3713, 0x009d4d25, 0x00b25a2b, 0x00ba5c24, 0x00b85618, 0x00b95815, 0x00bb5813, 0x00be5610, 0x00c1550c, 0x00c5560a, 0x00c95809, 0x00cc5708, 0x00ca5506, 0x00c95608, 0x00c65608, 0x00c55708, 0x00c45609, 0x00c45609, 0x00c4570a, 0x00c5580c, 0x00c8580c, 0x00ca540a, 0x00c85409, 0x00c15608, 0x00bf5808, 0x00c05a09, 0x00c05a0c, 0x00bc5814, 0x00bb5518, 0x00bd541a, 0x00bf5821, 0x00b85622, 0x009c4718, 0x00682502, 0x003f0800, 0x00320600, 0x00340800, 0x0068320c, 0x008d4e1f, 0x00a55d1f, 0x00b2611b, 0x00bc601a, 0x00bc5911, 0x00bd5b0e, 0x00b86421, 0x00733c15, 0x00310800, 0x00471b00, 0x00975f25, 0x00b3641d, 0x00a15b20, 0x00341701, 0x00080000, 0x00040000, 0x000e0000, 0x006c401b, 0x00945c2f, 0x0078441d, 0x00441100, 0x003c0500, 0x00743208, 0x00ab551f, 0x00b3561a, 0x00ab541e, 0x00a5592b, 0x00804a26, 0x00401800, 0x00180000, 0x000e0000, 0x00040000, 0x00020105, 0x00030002, 0x00020001, 0x00000004, 0x00020005, 0x00050004, 0x000d0000, 0x00270100, 0x00541d06, 0x00823c1d, 0x00994b25, 0x00a34e28, 0x00a44c23, 0x00a54a1f, 0x00a84d20, 0x00a44b1e, 0x00a14a1c, 0x00a1481c, 0x00a34c1f, 0x009f4c23, 0x00954824, 0x00854225, 0x00773f2a, 0x00502315, 0x00300d03, 0x001a0000, 0x00160000, 0x00180000, 0x001c0000, 0x002e0400, 0x00481700, 0x0074381e, 0x00884123, 0x00994c28, 0x00a14c23, 0x00a54818, 0x00a84612, 0x00ac4914, 0x00af4c18, 0x00a94919, 0x00a7491e, 0x00a64b21, 0x00a64b21, 0x00a84921, 0x00aa491f, 0x00ad481c, 0x00ae4719, 0x00af4c1c, 0x00aa4818, 0x00a64616, 0x00a84918, 0x00ac491a, 0x00ad4818, 0x00ae4710, 0x00b0460a, 0x00b44c0a, 0x00bd520e, 0x00c75713, 0x00c45414, 0x00bc5114, 0x00b35820, 0x00894818, 0x00360d00, 0x000e0000, 0x00020000, 0x00000000, 0x00484c4e, 0x00a1a4a8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a9a8a7, 0x004c4845, 0x000c0000, 0x00220200, 0x005d2400, 0x00b15b20, 0x00bf560d, 0x00c45408, 0x00c4570c, 0x00ba540e, 0x00a55723, 0x00441c04, 0x001c0200, 0x00210000, 0x00643522, 0x008b5434, 0x00602c10, 0x00240200, 0x00340f00, 0x007b3817, 0x00a95424, 0x00ae4d13, 0x00b65013, 0x00b64d14, 0x00b34c15, 0x00ae4c16, 0x00a85329, 0x004d1600, 0x00380600, 0x00773518, 0x009b4a25, 0x00ab5024, 0x00a15129, 0x0063321b, 0x00280400, 0x00380800, 0x00723312, 0x00ac5121, 0x00b24c13, 0x00b24d12, 0x00b04c13, 0x00b04e16, 0x00ae4b13, 0x00b24c13, 0x00b64c14, 0x00b54b15, 0x00b64a15, 0x00b84915, 0x00b64814, 0x00b44a17, 0x00a94f22, 0x00884524, 0x00491e09, 0x00100000, 0x00060000, 0x00070000, 0x00140100, 0x004e240a, 0x00844620, 0x00a95426, 0x00ad4d1b, 0x00ac4c1a, 0x00af4c18, 0x00af4912, 0x00b54c12, 0x00b6480f, 0x00b74911, 0x00b54916, 0x00b74c18, 0x00b04811, 0x00ac4c1a, 0x00a05026, 0x00702d0a, 0x00300000, 0x007d3c15, 0x00b0561c, 0x00c35b16, 0x00bd550f, 0x00b85c1b, 0x00a4602d, 0x0071401b, 0x00331200, 0x00140000, 0x00190000, 0x00250700, 0x00300900, 0x00501c02, 0x0074330c, 0x00914615, 0x00a95c25, 0x00af5d22, 0x00b65c21, 0x00ba5b1b, 0x00bb5612, 0x00bc540c, 0x00c1550c, 0x00c6580d, 0x00c25709, 0x00c25709, 0x00c1570b, 0x00c1570b, 0x00c1570b, 0x00c2580c, 0x00c2580d, 0x00c2580a, 0x00c45908, 0x00c05908, 0x00bd5a12, 0x00bc5c19, 0x00b95d1c, 0x00b35a21, 0x00a75425, 0x009c5028, 0x00813a1a, 0x00672407, 0x004e0c00, 0x00420200, 0x00390000, 0x00320000, 0x004c1c05, 0x008d542d, 0x00a35317, 0x00bd621b, 0x00b86013, 0x00b65b0e, 0x00c06018, 0x00c45d16, 0x00c35b0c, 0x00bb631f, 0x007a441a, 0x00361000, 0x003f1900, 0x008c5822, 0x00b1631c, 0x00a0581c, 0x00321000, 0x00080000, 0x00040000, 0x00140000, 0x00844d19, 0x00aa6323, 0x00a75e24, 0x00884814, 0x00562100, 0x003c0a00, 0x00591c00, 0x008e471a, 0x00b05c2a, 0x00b45a25, 0x00b25922, 0x00a35424, 0x00703113, 0x002b0100, 0x00120000, 0x00050000, 0x00020000, 0x00040307, 0x0000020c, 0x00000009, 0x00000005, 0x00080001, 0x00100000, 0x00180200, 0x002b0d00, 0x004e2814, 0x00794429, 0x0094502d, 0x00a04c20, 0x00a4481a, 0x00a94b23, 0x00a84b24, 0x00a74a21, 0x00a54a20, 0x00a44c21, 0x00a24c21, 0x009f4a20, 0x00994922, 0x00944824, 0x00894324, 0x007a3b22, 0x00642c18, 0x00481808, 0x002e0400, 0x00200000, 0x00200000, 0x002c0200, 0x00451401, 0x00672c13, 0x00844020, 0x009b4b23, 0x00a44c1d, 0x00a84817, 0x00a8440f, 0x00ae4815, 0x00ae4815, 0x00ac4818, 0x00ac481a, 0x00ac481a, 0x00ac481c, 0x00ad481a, 0x00ac481a, 0x00ac481a, 0x00ab4816, 0x00ad4812, 0x00b04a14, 0x00af4816, 0x00af4813, 0x00b6490c, 0x00be4f0b, 0x00c65608, 0x00c55508, 0x00c1510c, 0x00c45a1e, 0x00b45929, 0x00853f18, 0x00401600, 0x00100000, 0x00020000, 0x00020707, 0x002e302f, 0x00969696, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00757473, 0x0018100b, 0x00180100, 0x00380d00, 0x00904818, 0x00b55919, 0x00bc540d, 0x00c3580c, 0x00bd540c, 0x00ac561c, 0x00633014, 0x00290800, 0x00170000, 0x00441e0c, 0x0081472c, 0x00784125, 0x00361404, 0x00240200, 0x005b2308, 0x009b4f28, 0x00aa501d, 0x00b04e14, 0x00b34c14, 0x00b04b14, 0x00b04e18, 0x00974317, 0x00470b00, 0x005d220c, 0x00974624, 0x00a84f24, 0x00a44c22, 0x00924925, 0x004f220c, 0x002d0500, 0x00581d00, 0x00964820, 0x00b04d1c, 0x00b44a10, 0x00b0490f, 0x00b04d14, 0x00b14e16, 0x00ae4b13, 0x00b04b14, 0x00b44c16, 0x00b44a16, 0x00b44816, 0x00b74816, 0x00b44818, 0x00aa491c, 0x00994c26, 0x005d2b10, 0x00220600, 0x000b0000, 0x000c0000, 0x001b0300, 0x00451d09, 0x00894c2a, 0x00a05023, 0x00a74b18, 0x00ab4814, 0x00b05020, 0x00ae4c1c, 0x00ad4713, 0x00b74e16, 0x00b54b0f, 0x00b74910, 0x00b44813, 0x00b44b18, 0x00ad4716, 0x00a74e22, 0x008d4b2b, 0x004a0f00, 0x00500c00, 0x00a45122, 0x00bb5717, 0x00c7580d, 0x00c75709, 0x00bd5910, 0x00ae6028, 0x00723c13, 0x00280900, 0x000c0000, 0x00040000, 0x00040000, 0x00100000, 0x001d0300, 0x002e0400, 0x00410f00, 0x004a1400, 0x005b1c00, 0x00742c02, 0x008c3c10, 0x009e4718, 0x00a84e19, 0x00b0541c, 0x00b75a1e, 0x00b6591c, 0x00b75a1c, 0x00b95b20, 0x00bb5c21, 0x00bc5b20, 0x00bb5b1e, 0x00b85a1c, 0x00b55919, 0x00b35714, 0x00ab5213, 0x009e4814, 0x00903c10, 0x00813007, 0x00702200, 0x00601500, 0x00540e00, 0x00480600, 0x004a0800, 0x004f0800, 0x00580f0c, 0x005e1519, 0x00430000, 0x00400800, 0x00884a27, 0x00b45f20, 0x00bc5a0b, 0x00c05f0b, 0x00c05d0b, 0x00c05b10, 0x00c35a11, 0x00c45809, 0x00c0631d, 0x0085491b, 0x00431900, 0x003b1400, 0x0081501e, 0x00af641e, 0x009c561b, 0x002c0b00, 0x000a0000, 0x00080000, 0x00180000, 0x0094551c, 0x00b46118, 0x00b15b13, 0x00b46523, 0x00975822, 0x00642d00, 0x00451000, 0x004e1100, 0x00782d04, 0x00a85323, 0x00b95c22, 0x00b3551d, 0x00a45022, 0x008b4822, 0x004f2400, 0x00280c00, 0x000d0000, 0x00060000, 0x00030002, 0x00020005, 0x00040005, 0x00030000, 0x00000000, 0x00020000, 0x00080200, 0x00150700, 0x002f1000, 0x004c1d05, 0x00743310, 0x00944823, 0x00984824, 0x009c4a28, 0x00a04b28, 0x009f4824, 0x00a04720, 0x00a44920, 0x00a8481e, 0x00a8481c, 0x00a54619, 0x00a64b20, 0x009d4822, 0x008c3f1d, 0x00803e23, 0x007a422d, 0x006b3c2c, 0x005c2f21, 0x004b1d0d, 0x00481602, 0x00471000, 0x00521200, 0x006b2000, 0x0087330c, 0x009e4216, 0x00ac4919, 0x00ae4614, 0x00b04613, 0x00b04714, 0x00af4814, 0x00ae4815, 0x00ac4817, 0x00ab4818, 0x00aa4818, 0x00a94718, 0x00ab4714, 0x00b1480e, 0x00b44a0e, 0x00b2480f, 0x00b3480d, 0x00bd4e0c, 0x00c7560c, 0x00c85504, 0x00c55708, 0x00bb5310, 0x00b45620, 0x008f4019, 0x004b1000, 0x001a0000, 0x000d0000, 0x00010302, 0x00040a0c, 0x007c7c7a, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a3a3a4, 0x00484444, 0x000d0100, 0x00210400, 0x00582300, 0x00a45827, 0x00b85919, 0x00c0580f, 0x00c1560a, 0x00b15414, 0x00884723, 0x00340800, 0x00170000, 0x00280900, 0x006c341d, 0x00894f35, 0x004c2611, 0x00210000, 0x003e1000, 0x007e4124, 0x00a15226, 0x00a74b17, 0x00af4b15, 0x00b14c16, 0x00af4d18, 0x00842e01, 0x00642004, 0x00874026, 0x00a84b25, 0x00ad4c22, 0x00a45029, 0x007c3a1a, 0x003f1100, 0x00431400, 0x007f3812, 0x00aa5023, 0x00ae4817, 0x00b34814, 0x00b14c13, 0x00b04c13, 0x00b04c13, 0x00ae4b13, 0x00b14c14, 0x00b34d18, 0x00b34915, 0x00b44816, 0x00b44b19, 0x00ac4c1e, 0x009e4e26, 0x00753c1c, 0x00300e00, 0x00140000, 0x00120000, 0x001e0100, 0x00461804, 0x0089482a, 0x00a05024, 0x00a94e1c, 0x00ab4c19, 0x00ab4b18, 0x00ad4b1c, 0x00af4c1c, 0x00b04a18, 0x00b04913, 0x00b04a0e, 0x00b44b0f, 0x00b44810, 0x00b44a17, 0x00aa491f, 0x009e4d2c, 0x006f381f, 0x00320000, 0x00823001, 0x00bb581c, 0x00c35611, 0x00c45408, 0x00ca5c10, 0x00c05f1a, 0x00a45924, 0x00582502, 0x00130000, 0x00070000, 0x00000000, 0x00020403, 0x00040000, 0x000a0000, 0x002f190a, 0x00533727, 0x002c0b00, 0x00300700, 0x00370200, 0x00400300, 0x004c0800, 0x00540c00, 0x00581400, 0x005b1800, 0x00642101, 0x00652102, 0x00692104, 0x006b2104, 0x006c2004, 0x006a1f00, 0x00661f00, 0x00651e00, 0x00601900, 0x005c1500, 0x00551002, 0x00500a02, 0x004d0500, 0x004f0500, 0x00530600, 0x00580600, 0x006c1207, 0x0075140b, 0x00841712, 0x008d1d1e, 0x0090252e, 0x0070151c, 0x00430400, 0x004b1200, 0x009c5426, 0x00b45e1c, 0x00c3620f, 0x00c96109, 0x00c65c0c, 0x00c45a0c, 0x00c85c0c, 0x00bb5c14, 0x00944e17, 0x00552000, 0x003c0f00, 0x0078461b, 0x00aa6425, 0x00945520, 0x00270600, 0x000d0000, 0x00110000, 0x002b0400, 0x009a541f, 0x00b85f17, 0x00c05f14, 0x00bd5c12, 0x00b45b13, 0x00ac5c1a, 0x00843e05, 0x005c1e00, 0x00420b00, 0x00571c00, 0x00884315, 0x00ae5c24, 0x00bc5e20, 0x00b95c1e, 0x009b4a10, 0x00743404, 0x00481900, 0x00210400, 0x000e0000, 0x00090000, 0x00080000, 0x00020000, 0x00010204, 0x00020304, 0x00010000, 0x00050000, 0x000f0000, 0x001b0100, 0x002b0d00, 0x003e1906, 0x005a2a0d, 0x00713818, 0x00894628, 0x00994e30, 0x00a34e2f, 0x00a84b2a, 0x00a94520, 0x00a64118, 0x00ac481c, 0x00aa4818, 0x00a64918, 0x00a44c1d, 0x00a45024, 0x00a04f28, 0x00994825, 0x008f4220, 0x008c4524, 0x00854120, 0x00803a1a, 0x007f3516, 0x00823515, 0x008c3918, 0x0099401c, 0x00a3441c, 0x00ac461a, 0x00b04516, 0x00b04513, 0x00b04612, 0x00ad4612, 0x00ab4714, 0x00a84815, 0x00a74818, 0x00ab4b1b, 0x00aa4613, 0x00b04206, 0x00b74606, 0x00ba4c0c, 0x00bd500f, 0x00c2520c, 0x00c55509, 0x00c35406, 0x00c35c13, 0x00b1581e, 0x0087390d, 0x00541300, 0x00441200, 0x0044220e, 0x00180500, 0x00060000, 0x00000002, 0x00716e6d, 0x00a09d9b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007c7b7f, 0x00191414, 0x000d0000, 0x00300a00, 0x007b3e17, 0x00b55f25, 0x00bf5811, 0x00c45708, 0x00b95611, 0x00a3552c, 0x00440f00, 0x00170000, 0x00180000, 0x0057200e, 0x00894d36, 0x00683c23, 0x002e0a00, 0x00250000, 0x00592914, 0x00944f29, 0x00a85323, 0x00b04f1b, 0x00ae4a14, 0x00ac4c18, 0x00832b00, 0x008e3f1d, 0x00a14c2c, 0x00b04b22, 0x00ae4b21, 0x00a15230, 0x00642808, 0x003b0b00, 0x005d2805, 0x009d4c21, 0x00af4c1d, 0x00b24a1c, 0x00b24817, 0x00b4501b, 0x00ad4c11, 0x00af4c12, 0x00b04a11, 0x00b24c15, 0x00b34c15, 0x00b44914, 0x00b44b17, 0x00b14c1c, 0x00a34d22, 0x00844624, 0x004a210a, 0x00110000, 0x000d0000, 0x001f0300, 0x00451804, 0x00803b20, 0x00a8532e, 0x00aa4d1c, 0x00ac4914, 0x00b04c18, 0x00b34f1c, 0x00ae491a, 0x00ad4819, 0x00b24c18, 0x00af4912, 0x00b0490d, 0x00b24c10, 0x00b34a14, 0x00b14c1d, 0x00a94c25, 0x00904527, 0x00511d07, 0x00390100, 0x00a54c19, 0x00c05413, 0x00c55509, 0x00c45405, 0x00c35c0f, 0x00b35c19, 0x0088481b, 0x00471d00, 0x00140100, 0x00040000, 0x00000000, 0x00000504, 0x00000000, 0x00110a04, 0x003c2e28, 0x004c342d, 0x00280100, 0x003e090b, 0x00541316, 0x00611518, 0x00631011, 0x005d0c08, 0x00540901, 0x00500900, 0x004e0800, 0x004e0700, 0x00510400, 0x00530200, 0x00540100, 0x00540200, 0x00510400, 0x00500500, 0x00520400, 0x00540702, 0x0058080f, 0x005d0d15, 0x00651115, 0x00701618, 0x007d1b1c, 0x00851d1d, 0x00932120, 0x00991f1b, 0x00ac2523, 0x00ab2022, 0x009c1922, 0x00902029, 0x00681818, 0x003d0000, 0x00632405, 0x00a25b26, 0x00b85c0f, 0x00c05b02, 0x00c45d0a, 0x00c25b09, 0x00cc6112, 0x00b7560f, 0x009d5218, 0x00622600, 0x003a0800, 0x00703c19, 0x00a56429, 0x008c5420, 0x001f0200, 0x000c0000, 0x00120000, 0x00401500, 0x009f5520, 0x00b45811, 0x00c35f14, 0x00c45e0f, 0x00bf5808, 0x00be5e10, 0x00b05915, 0x00924812, 0x006c3110, 0x004b1600, 0x00491100, 0x006f2c00, 0x009c4910, 0x00b55b1c, 0x00b85e20, 0x00ac5920, 0x00904c1e, 0x0068320c, 0x00401600, 0x00260600, 0x00160000, 0x000c0000, 0x00040000, 0x00030000, 0x00040000, 0x00050000, 0x00090000, 0x00080000, 0x00060000, 0x000c0000, 0x001b0400, 0x002c0b00, 0x00411603, 0x00541f0a, 0x00682814, 0x007f361f, 0x00944429, 0x00a34e2f, 0x009f4924, 0x009e481f, 0x00a04a1d, 0x00a24b1c, 0x00a3481a, 0x00a14417, 0x00a8471c, 0x00ad4d24, 0x00a1461c, 0x00a04a20, 0x00a14c27, 0x00a04c2a, 0x009d4828, 0x009b4524, 0x009d4420, 0x00a24520, 0x00aa471d, 0x00ad4618, 0x00af4514, 0x00af4512, 0x00ad4612, 0x00ab4714, 0x00a94815, 0x00a84817, 0x00ab4818, 0x00b04713, 0x00b84808, 0x00be4b06, 0x00c0520c, 0x00c45710, 0x00c75810, 0x00c45910, 0x00c05c18, 0x00a95017, 0x007c3408, 0x004f1100, 0x00440c00, 0x00744020, 0x00825235, 0x0046210e, 0x00100000, 0x00050000, 0x0026201e, 0x00908c8a, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a8ac, 0x004f4e53, 0x000c0402, 0x001c0300, 0x00471700, 0x009a4b17, 0x00bc5814, 0x00c45808, 0x00c0580f, 0x00b25829, 0x0065260c, 0x001e0500, 0x00110000, 0x00400d00, 0x00783c27, 0x00804e2f, 0x004f280d, 0x001f0000, 0x00350f04, 0x0075391a, 0x00a45428, 0x00ae501e, 0x00ac4a14, 0x00aa4e1a, 0x00963c0c, 0x00a74c22, 0x00ad4d25, 0x00b3481d, 0x00af4b24, 0x008c4324, 0x00531800, 0x004c1700, 0x007d4016, 0x00a85021, 0x00ae491a, 0x00b44b20, 0x00b14a1c, 0x00b04e18, 0x00ab4c13, 0x00ad4c11, 0x00ae4b11, 0x00b24c13, 0x00b44912, 0x00b7480f, 0x00b64c14, 0x00a84c1b, 0x00904820, 0x00582c14, 0x00230a00, 0x000b0000, 0x00150000, 0x00421904, 0x007c3c20, 0x00a74e2c, 0x00ad4820, 0x00b0501d, 0x00ac4812, 0x00b4450e, 0x00bb4914, 0x00b44a18, 0x00af4816, 0x00b24c13, 0x00b34c10, 0x00b1490c, 0x00b04b12, 0x00ad4b1c, 0x00aa4e23, 0x00a44c24, 0x00833816, 0x003f0800, 0x00602404, 0x00ad5620, 0x00c45b14, 0x00c85804, 0x00c45802, 0x00be6112, 0x00b06628, 0x006a3c15, 0x00200600, 0x00080000, 0x00020000, 0x00000100, 0x00000100, 0x00000000, 0x00100707, 0x00291414, 0x00370e0c, 0x00520809, 0x00751418, 0x008f2128, 0x00982028, 0x00941820, 0x008c1419, 0x00851618, 0x00801818, 0x007b1715, 0x007c1516, 0x007e1114, 0x00800f14, 0x00820e14, 0x00821013, 0x00801313, 0x00801514, 0x00851717, 0x0088181b, 0x008d1c24, 0x00941f27, 0x00992123, 0x009e1f22, 0x00a21c23, 0x00a41b24, 0x00a41b22, 0x00a4171d, 0x00af181b, 0x00ae1519, 0x00a41018, 0x00a21f26, 0x008b2427, 0x00580902, 0x003d0100, 0x007c401b, 0x00b0601b, 0x00bc600c, 0x00b85b06, 0x00b85804, 0x00c25c0b, 0x00bc5d15, 0x00a2571f, 0x00692c04, 0x00360300, 0x00673319, 0x00a0602c, 0x00855020, 0x00150000, 0x00080000, 0x00110000, 0x00461e04, 0x00a05a20, 0x00b96017, 0x00b95a10, 0x00bc580e, 0x00c15b0a, 0x00c55c0b, 0x00c95f0e, 0x00b6530e, 0x00a24e20, 0x007e3b18, 0x00551e00, 0x00451400, 0x00542100, 0x00733814, 0x00a05426, 0x00ac5824, 0x00b05925, 0x00a85422, 0x00914719, 0x006e3009, 0x00481a00, 0x00300f00, 0x001b0400, 0x000f0000, 0x000a0000, 0x00080000, 0x00080000, 0x00080304, 0x00040006, 0x00040005, 0x00040000, 0x00060000, 0x000f0000, 0x00180400, 0x00250a03, 0x00341207, 0x00441c0f, 0x00502414, 0x00673620, 0x00733c21, 0x00814324, 0x00904827, 0x009d4b28, 0x00a44b26, 0x00a84721, 0x00a8411a, 0x00b04820, 0x00ad451c, 0x00a8441b, 0x00a8451c, 0x00a8461f, 0x00a7471d, 0x00a7491f, 0x00a84b20, 0x00a8471b, 0x00a94718, 0x00aa4717, 0x00aa4715, 0x00ab4615, 0x00ac4716, 0x00ac4818, 0x00ae4817, 0x00b04612, 0x00bb4c13, 0x00c5500e, 0x00c6520b, 0x00c4550c, 0x00c25910, 0x00bf5810, 0x00b35515, 0x00984817, 0x006f2e08, 0x00411100, 0x00360900, 0x00501a00, 0x00a05f32, 0x00a4592c, 0x00884723, 0x00300b00, 0x00100000, 0x00060000, 0x00585454, 0x00acb0b0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0087888c, 0x00241f1f, 0x000e0000, 0x00230200, 0x00642904, 0x00ad5c22, 0x00c05910, 0x00c4580e, 0x00b6551e, 0x0086401b, 0x002b0c00, 0x00100000, 0x002b0000, 0x00612b18, 0x00885130, 0x00704023, 0x002c0b00, 0x00240200, 0x00501d07, 0x008c4824, 0x00a44b1e, 0x00af501b, 0x00ac521c, 0x00aa4e1a, 0x00a94518, 0x00b34b21, 0x00ae461c, 0x00a94d28, 0x00712e11, 0x00481000, 0x00642804, 0x00985026, 0x00a54a1a, 0x00b04918, 0x00af4619, 0x00b34c1e, 0x00a94711, 0x00af4e15, 0x00af4c12, 0x00b14b12, 0x00b34a14, 0x00b24812, 0x00b5460f, 0x00b24b17, 0x009d481b, 0x007e401f, 0x00341400, 0x000e0000, 0x00190400, 0x00381400, 0x0074391a, 0x00a05028, 0x00ad4820, 0x00b4481c, 0x00ae4815, 0x00b44c15, 0x00bb4810, 0x00b8440f, 0x00b34916, 0x00b24c18, 0x00b24c11, 0x00b34b0e, 0x00b14b10, 0x00b04a13, 0x00ac4b18, 0x00a84d20, 0x00994922, 0x0075300d, 0x00390000, 0x0089441d, 0x00b5571c, 0x00c55a0e, 0x00c25401, 0x00c25c08, 0x00b35d12, 0x009a5c22, 0x004b290b, 0x00130400, 0x00060000, 0x00000000, 0x00000200, 0x00000000, 0x00070202, 0x000d0000, 0x001e0000, 0x004c0c10, 0x00821920, 0x009a1a22, 0x00a51c27, 0x00a61823, 0x00a51820, 0x00a71c23, 0x00a21e24, 0x009b1a1e, 0x009e1d21, 0x009e1d22, 0x009e1c28, 0x009e1c29, 0x00a01c27, 0x00a01d26, 0x009f1f25, 0x00a02024, 0x00a01b20, 0x00a21b20, 0x00a11920, 0x00a41920, 0x00a8191e, 0x00ab181e, 0x00ad1421, 0x00ad1322, 0x00ab1420, 0x00ae1821, 0x00ab1216, 0x00ae1618, 0x00b1181f, 0x00a51820, 0x00991e24, 0x00822021, 0x00420000, 0x004d1400, 0x00985219, 0x00b36316, 0x00b45e07, 0x00c0640b, 0x00b85503, 0x00ba5e17, 0x00a75a1f, 0x006e3007, 0x00330100, 0x005f2e18, 0x009d5d2e, 0x00824d1f, 0x00110000, 0x00070000, 0x00120000, 0x00522809, 0x00a2581b, 0x00b85d10, 0x00bb5a10, 0x00c15e11, 0x00c35c0c, 0x00c05604, 0x00c45400, 0x00c95c10, 0x00bb5a20, 0x00a45425, 0x008d5026, 0x00542606, 0x001d0000, 0x002d0c00, 0x005a2408, 0x00833e18, 0x00a35225, 0x00af5827, 0x00b45d2c, 0x00a95929, 0x008e481d, 0x00743912, 0x005a2905, 0x00461c00, 0x002e0b00, 0x001e0200, 0x00140000, 0x000b0000, 0x00080000, 0x00070000, 0x00080000, 0x00050000, 0x00050000, 0x00080000, 0x000a0000, 0x000e0000, 0x00140000, 0x001c0000, 0x00280700, 0x00370e00, 0x004b1907, 0x005c2009, 0x006c2207, 0x007f2908, 0x00983711, 0x00ac441b, 0x00b24219, 0x00b14118, 0x00b0441c, 0x00b0471d, 0x00ad461a, 0x00a94418, 0x00a84416, 0x00a94718, 0x00a94719, 0x00a94719, 0x00aa4618, 0x00ab4615, 0x00ae4614, 0x00b04714, 0x00b14814, 0x00b44811, 0x00bf4f13, 0x00c45213, 0x00c8530f, 0x00c5520c, 0x00c25711, 0x00bc5a16, 0x00aa5014, 0x00944511, 0x00642300, 0x00471400, 0x00421c06, 0x004f270c, 0x00581e00, 0x00b26630, 0x00b6591d, 0x00ad5925, 0x005e280c, 0x001c0000, 0x000c0000, 0x00121013, 0x00808585, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00aeadac, 0x006d6966, 0x00110804, 0x000c0000, 0x00270d00, 0x006f3c1a, 0x00b65b20, 0x00c35810, 0x00bf5815, 0x00a2531f, 0x003f1600, 0x00140000, 0x00160000, 0x004b1e10, 0x00804424, 0x008a4e2c, 0x00592e19, 0x00210000, 0x002b0500, 0x00602c14, 0x009e5028, 0x00a84c1a, 0x00ac5018, 0x00a74811, 0x00b24b1f, 0x00b04821, 0x00a94920, 0x00974621, 0x00541c01, 0x00481400, 0x00803e1e, 0x00994922, 0x00aa4e20, 0x00af4b18, 0x00b24815, 0x00b34915, 0x00b04a14, 0x00af4912, 0x00b14710, 0x00b64a15, 0x00ae4713, 0x00af4715, 0x00b44b19, 0x00a9481c, 0x00964826, 0x00552007, 0x001c0100, 0x00130000, 0x003a0f00, 0x00733718, 0x009b4c1e, 0x00a74b18, 0x00ac471b, 0x00b4481e, 0x00b84818, 0x00b84715, 0x00b64713, 0x00b34813, 0x00b04a16, 0x00af4b15, 0x00b34a10, 0x00b24910, 0x00b04c17, 0x00b04a13, 0x00b24808, 0x00b35219, 0x008f4a24, 0x004d1200, 0x00541000, 0x00ac5826, 0x00c35610, 0x00cb5808, 0x00c15608, 0x00b8580f, 0x00b36220, 0x00824916, 0x00301700, 0x00070000, 0x00000000, 0x00000100, 0x00000400, 0x00000100, 0x000c0100, 0x00190000, 0x004b0b12, 0x007a1c27, 0x00a01b2b, 0x00ad1828, 0x00ad1828, 0x00aa1623, 0x00a4181d, 0x00a4191c, 0x00a51b20, 0x00ab1b1d, 0x00b01716, 0x00ac1418, 0x00a71a2c, 0x009e182c, 0x00a01c28, 0x00a72328, 0x009d191f, 0x00a61d24, 0x00a9161c, 0x00ac161c, 0x00aa181c, 0x00aa171d, 0x00ac1721, 0x00ae1825, 0x00b01425, 0x00af1224, 0x00ac1621, 0x00a8181c, 0x00a61919, 0x00a61a18, 0x00a8181c, 0x00a8181f, 0x00a51823, 0x00981e28, 0x00651014, 0x00390000, 0x007c4014, 0x00a4601c, 0x00b05d04, 0x00bb5f01, 0x00be5f0d, 0x00b45912, 0x00ab5d1e, 0x00763708, 0x002d0100, 0x0053250e, 0x00a15c31, 0x0082451e, 0x00100000, 0x00060000, 0x00110000, 0x00673915, 0x00aa5c1d, 0x00b95a0a, 0x00be5806, 0x00bf5907, 0x00c05a09, 0x00c05908, 0x00c05908, 0x00bf580c, 0x00c05c18, 0x00b35818, 0x00ac5c20, 0x0082491e, 0x00120000, 0x00090000, 0x00170000, 0x00351001, 0x005c2c13, 0x007c3f1c, 0x009b4e26, 0x00b05928, 0x00b75d20, 0x00b35a19, 0x00a95418, 0x00944710, 0x007c360c, 0x00652908, 0x00532000, 0x00441900, 0x00331100, 0x00270800, 0x00240600, 0x001f0200, 0x00180100, 0x00180000, 0x001a0000, 0x001c0000, 0x00210000, 0x00270100, 0x002b0400, 0x002e0500, 0x00360900, 0x00471200, 0x005d1d01, 0x00782b04, 0x00933808, 0x00a64110, 0x00b24218, 0x00b3411b, 0x00ac421e, 0x00ab441f, 0x00ac461c, 0x00ad4618, 0x00ad4515, 0x00ac4414, 0x00aa4317, 0x00b0491d, 0x00b04819, 0x00af4411, 0x00b5480e, 0x00ba4c10, 0x00bb4e11, 0x00c05312, 0x00c8540b, 0x00cb540c, 0x00c55410, 0x00c05313, 0x00ba5418, 0x00a64c18, 0x007b3309, 0x00531900, 0x00451100, 0x00673810, 0x0073492c, 0x00643417, 0x00601e00, 0x00b86428, 0x00bf5b11, 0x00ba5814, 0x00984f1c, 0x003b0c00, 0x000d0000, 0x0005040b, 0x00424546, 0x00a4a9a6, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a7a3a0, 0x00403b36, 0x000d0600, 0x00070000, 0x00341704, 0x008c441a, 0x00b6581c, 0x00bc5914, 0x00b05a20, 0x005a2606, 0x00210200, 0x00150000, 0x00200200, 0x006d3518, 0x00915230, 0x00764125, 0x00431803, 0x00230000, 0x00340b00, 0x007d3c1c, 0x00a25124, 0x00a54c14, 0x00ab4a13, 0x00b34a1d, 0x00ac4720, 0x00a24e28, 0x0074310c, 0x00420d00, 0x005b2409, 0x00924525, 0x00a44b23, 0x00ac4c1e, 0x00af4816, 0x00b14814, 0x00b24913, 0x00b04a13, 0x00b04a13, 0x00b04610, 0x00b34814, 0x00b24c18, 0x00ac4a18, 0x00aa4a1a, 0x00a04c22, 0x00763618, 0x003b0e00, 0x00170000, 0x00301001, 0x00692d14, 0x00984820, 0x00ac5018, 0x00af4c12, 0x00ac4919, 0x00af481c, 0x00b44818, 0x00b54715, 0x00b24815, 0x00ae4a17, 0x00ac4b18, 0x00ad4a17, 0x00b34a14, 0x00b44a13, 0x00b04913, 0x00b44c12, 0x00be4f0b, 0x00b05116, 0x007c401f, 0x003e0900, 0x00742800, 0x00ba5a1d, 0x00c45104, 0x00cb5503, 0x00c2580d, 0x00b75b1a, 0x00a85d26, 0x0065340c, 0x001f0800, 0x00050000, 0x00030000, 0x00020400, 0x00000600, 0x00000000, 0x000e0000, 0x002f0000, 0x007f232d, 0x00941928, 0x00a61426, 0x00ac1223, 0x00ab1220, 0x00aa1520, 0x00a81a1f, 0x00a81b20, 0x00a8171e, 0x00a61016, 0x00b41718, 0x00aa1519, 0x009d1e2e, 0x00962434, 0x008b1c21, 0x00780a0a, 0x00750508, 0x008f161c, 0x00a52025, 0x00a81820, 0x00aa181c, 0x00ac171e, 0x00ad1421, 0x00ab1021, 0x00ad1022, 0x00b01524, 0x00a9141d, 0x00a7161c, 0x00a3181a, 0x00a21a1b, 0x00a4191b, 0x00a7171e, 0x00a81721, 0x00a01a28, 0x00821c25, 0x004a0000, 0x005b1f00, 0x0097581f, 0x00b2600d, 0x00b95c02, 0x00ba5c0c, 0x00b85c15, 0x00af5e1c, 0x00793907, 0x002c0400, 0x004b2008, 0x009c5833, 0x007c401e, 0x000e0000, 0x00060000, 0x00170000, 0x0074431d, 0x00ab5a1a, 0x00bb5809, 0x00c05906, 0x00c25904, 0x00bf5808, 0x00bd580a, 0x00bd5a0d, 0x00bc580c, 0x00c15c10, 0x00b8580f, 0x00b15a18, 0x00834618, 0x00110000, 0x00010000, 0x00050001, 0x000d0000, 0x00170000, 0x00381100, 0x00672c10, 0x007f370f, 0x009e4c14, 0x00b05818, 0x00b85c1c, 0x00b45a1d, 0x00b35c28, 0x00b05e2c, 0x009f5523, 0x00884416, 0x00783812, 0x00733715, 0x00682c0c, 0x005f2808, 0x0055230a, 0x0051210b, 0x0051210c, 0x0053220c, 0x0057210a, 0x005a230a, 0x005f2810, 0x00632c14, 0x006c331c, 0x007a3b22, 0x008a4020, 0x0097461c, 0x00a54a18, 0x00b04c19, 0x00b04415, 0x00b04418, 0x00ac461c, 0x00aa471c, 0x00ac4818, 0x00af4715, 0x00af4814, 0x00af4814, 0x00ae4817, 0x00b04714, 0x00b4470f, 0x00bc4b0e, 0x00c1500e, 0x00c2500c, 0x00c15410, 0x00c75b13, 0x00c55708, 0x00be540b, 0x00b7551b, 0x00ae5422, 0x00944011, 0x006c2300, 0x00531500, 0x00501800, 0x007a420b, 0x00935d27, 0x00855732, 0x005a2804, 0x00591800, 0x00b96728, 0x00c45f0f, 0x00bc5504, 0x00b86021, 0x006d3008, 0x00180000, 0x00030001, 0x00131112, 0x007f807c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00333231, 0x009a9490, 0x00221b15, 0x00050000, 0x00100000, 0x004d2207, 0x00914f24, 0x00b4581e, 0x00b45b21, 0x00783812, 0x00300800, 0x000e0000, 0x00140100, 0x004f240c, 0x00874e2c, 0x00935433, 0x0073381e, 0x002b0000, 0x00220000, 0x00451500, 0x00884828, 0x00a24f1c, 0x00ac4b15, 0x00b0481b, 0x00a74822, 0x00904b27, 0x00501800, 0x003f0b00, 0x00733411, 0x00a24c24, 0x00af4b1e, 0x00b04818, 0x00b04614, 0x00b04818, 0x00b04917, 0x00ac4a12, 0x00ad4b13, 0x00ad4914, 0x00ab4714, 0x00b05018, 0x00a74c16, 0x00a34e1e, 0x008f4820, 0x004d1e03, 0x00200000, 0x002c0800, 0x005c2c15, 0x00914a27, 0x00a8501f, 0x00ae4b11, 0x00af4a0f, 0x00aa4c18, 0x00a84b1a, 0x00ac4a18, 0x00ad4a17, 0x00ae4b19, 0x00ac4a1b, 0x00a9491f, 0x00aa491d, 0x00b04817, 0x00b64810, 0x00b9490c, 0x00bd4c0c, 0x00c15514, 0x00a64c18, 0x00652f13, 0x00390600, 0x00984610, 0x00c05a13, 0x00c45504, 0x00c45503, 0x00c2580d, 0x00b85d20, 0x00935129, 0x00451a04, 0x00130000, 0x00090000, 0x00070000, 0x00030000, 0x00000000, 0x00060000, 0x00220108, 0x00540f16, 0x009e242e, 0x00a3111b, 0x00aa1823, 0x00a91922, 0x00a8171c, 0x00a41418, 0x00a61319, 0x00a8141e, 0x00aa1424, 0x00a81524, 0x00a51821, 0x00961d23, 0x00761d24, 0x005d1418, 0x004b0800, 0x00400000, 0x00470603, 0x0054090a, 0x007c1c20, 0x00931f24, 0x00a51d24, 0x00ab1620, 0x00ac121e, 0x00b01420, 0x00ac1621, 0x00a9141f, 0x00a8141e, 0x00a8141e, 0x00a61620, 0x00a4171f, 0x00a41820, 0x00a4191e, 0x00a4181e, 0x00a01a20, 0x0099242c, 0x00680704, 0x00440000, 0x0089481b, 0x00b15c16, 0x00b95c09, 0x00b9580e, 0x00b95c17, 0x00b2601f, 0x007d3d0b, 0x002f0800, 0x003e1a03, 0x00905632, 0x006f3c1c, 0x000b0000, 0x00070000, 0x001a0000, 0x00834c27, 0x00aa581c, 0x00ba580c, 0x00c15a09, 0x00c25906, 0x00bf5807, 0x00c15b0d, 0x00be580e, 0x00bd580c, 0x00c3590b, 0x00bc580e, 0x00af5a1c, 0x007c4318, 0x00110000, 0x00010000, 0x00020005, 0x000a0305, 0x00100400, 0x00100000, 0x001c0000, 0x002f0a00, 0x0058280c, 0x00743915, 0x0090481e, 0x00a45321, 0x00b05924, 0x00b4591f, 0x00b85b1c, 0x00bc5b1c, 0x00bb581c, 0x00ba571d, 0x00b5531b, 0x00b0521a, 0x00a8501b, 0x00a3501d, 0x00a15121, 0x00a25324, 0x00a15223, 0x009e4f20, 0x009f4e21, 0x00a14d21, 0x00a44c20, 0x00a84c20, 0x00aa491f, 0x00a9461b, 0x00a8441b, 0x00a84416, 0x00a94710, 0x00a9480e, 0x00a84911, 0x00a84a10, 0x00ac490c, 0x00ad480c, 0x00ac4a10, 0x00ac4b10, 0x00b24f14, 0x00b84f0d, 0x00c45208, 0x00cc5608, 0x00cb5607, 0x00c75408, 0x00c4550c, 0x00be570d, 0x00bd5d11, 0x00ac5818, 0x008c4823, 0x00642e12, 0x00441200, 0x00400d00, 0x00642a00, 0x008f4c10, 0x00b26418, 0x00b86f28, 0x008b5626, 0x00471700, 0x00521900, 0x00b56c2c, 0x00c26414, 0x00bd5807, 0x00b45914, 0x009c5424, 0x00350f00, 0x000e0000, 0x00070000, 0x004f504c, 0x00a3a7a2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00333231, 0x0075706b, 0x00140e09, 0x00100400, 0x00100000, 0x0051270d, 0x009c5021, 0x00ac5924, 0x008b4822, 0x00441800, 0x000a0000, 0x000a0000, 0x00341200, 0x00733f20, 0x009b5630, 0x008d4928, 0x00522010, 0x00250000, 0x00200000, 0x00532510, 0x00964e26, 0x00a64e1f, 0x00a8481e, 0x00a14c26, 0x00713819, 0x00380a00, 0x00511c00, 0x00843e16, 0x00a84b1d, 0x00b34817, 0x00b24514, 0x00b14615, 0x00b0491b, 0x00ac4919, 0x00aa4912, 0x00ab4c13, 0x00ae4c1a, 0x00a84714, 0x00ac4d15, 0x00a34c16, 0x00a05226, 0x00733715, 0x00300b00, 0x00260400, 0x00582814, 0x00834328, 0x00a45026, 0x00ab4915, 0x00ae450d, 0x00b04812, 0x00a94b19, 0x00a64c1a, 0x00a74c14, 0x00ab4c15, 0x00ac4c1b, 0x00ac4b1d, 0x00aa491f, 0x00ac481b, 0x00b34814, 0x00b7480c, 0x00c1500c, 0x00c0500e, 0x00bc571a, 0x00994718, 0x004d1800, 0x004a1300, 0x00b25a1c, 0x00c05707, 0x00c85c08, 0x00c05501, 0x00bd560b, 0x00b35c23, 0x00723c1e, 0x002c0b00, 0x000e0000, 0x00090000, 0x00080000, 0x00040000, 0x00070306, 0x00080000, 0x00260008, 0x00681a24, 0x009b1820, 0x00b0161f, 0x00a4121c, 0x00a4161c, 0x00a61818, 0x00a7181a, 0x00a71720, 0x00a41826, 0x009c1a29, 0x00951c2a, 0x00871b20, 0x006d1212, 0x004c0600, 0x003f0600, 0x004e1400, 0x00602c17, 0x00542a1d, 0x00210000, 0x00440403, 0x006d161b, 0x0095222a, 0x00a41d28, 0x00a8141e, 0x00ab131c, 0x00a8151d, 0x00a5141c, 0x00a5151f, 0x00a61521, 0x00a41623, 0x00a41623, 0x00a31820, 0x00a3181f, 0x00a3171c, 0x00a0181c, 0x009c1f22, 0x00801715, 0x00410000, 0x00743212, 0x00a75418, 0x00b95a12, 0x00bc5610, 0x00bc5816, 0x00b65d1e, 0x00833e0d, 0x00340c00, 0x00351400, 0x00855133, 0x0063381b, 0x00080000, 0x00080000, 0x001f0000, 0x0090542d, 0x00ad5c20, 0x00b95a12, 0x00c0590e, 0x00bf5807, 0x00bf5507, 0x00c35b0e, 0x00be580e, 0x00bd560c, 0x00c45708, 0x00bd570e, 0x00aa5920, 0x00723d17, 0x00120000, 0x00040000, 0x00020000, 0x00040000, 0x002c1f13, 0x002a1809, 0x00140000, 0x00140000, 0x001c0000, 0x00260100, 0x00471600, 0x00692f0e, 0x00884119, 0x009a4a1a, 0x00ac541c, 0x00bc5a1e, 0x00c05618, 0x00be5010, 0x00c25713, 0x00c35915, 0x00c05916, 0x00bb5613, 0x00b65414, 0x00b45414, 0x00b25214, 0x00af4f10, 0x00b04d10, 0x00b04b0e, 0x00b1480c, 0x00b4470c, 0x00b4470f, 0x00b54713, 0x00b44818, 0x00b24b17, 0x00ad4c0d, 0x00ac4f09, 0x00b0500d, 0x00b3510d, 0x00b9510b, 0x00bc530c, 0x00bc5513, 0x00bc5814, 0x00be5812, 0x00c0560c, 0x00c85606, 0x00c45504, 0x00c0550b, 0x00c05b15, 0x00ba591a, 0x00a85010, 0x00944808, 0x00703100, 0x004a1400, 0x003c0b00, 0x00502100, 0x007a4517, 0x00a25d20, 0x00b8671d, 0x00bf6814, 0x00b4651a, 0x007c4818, 0x00380b00, 0x00542000, 0x00b06d28, 0x00c06413, 0x00c45f0b, 0x00b8560c, 0x00b16026, 0x00622c0c, 0x001c0000, 0x000c0000, 0x0020201c, 0x0080827c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a19e9b, 0x005e5a57, 0x00070000, 0x000b0402, 0x00160000, 0x005e2a0c, 0x0096542e, 0x00975b39, 0x004d220c, 0x000a0000, 0x00050000, 0x00200400, 0x00602d11, 0x00994e24, 0x00974a22, 0x00824931, 0x00360c01, 0x00170000, 0x001f0000, 0x006a3318, 0x0098512c, 0x00a24e28, 0x00944a28, 0x004c1f07, 0x002b0400, 0x00642c0b, 0x0094481d, 0x00aa4818, 0x00b44511, 0x00b44410, 0x00b24514, 0x00af4a1c, 0x00ab4819, 0x00a84913, 0x00ac4d15, 0x00ad4b1b, 0x00ab4818, 0x00ab4915, 0x00a44c1b, 0x00954c28, 0x00531a00, 0x002f0600, 0x00491f12, 0x0081402b, 0x009c492a, 0x00ac4c20, 0x00af4715, 0x00b44717, 0x00b34819, 0x00a9481b, 0x00a64a18, 0x00ac4b10, 0x00ac4c0f, 0x00ab4b18, 0x00ac481a, 0x00b04715, 0x00b64711, 0x00bc4b0c, 0x00bf4f0b, 0x00c35611, 0x00bc5718, 0x00b25824, 0x00894017, 0x00410700, 0x006b2a04, 0x00ba5d1b, 0x00c05604, 0x00c45c04, 0x00bc5701, 0x00bc590c, 0x00a4571e, 0x004a2108, 0x00160200, 0x00080000, 0x00050000, 0x00040003, 0x00040004, 0x00050104, 0x000c0001, 0x00240007, 0x006f252e, 0x00981c26, 0x00a6141e, 0x00a71720, 0x00a5141c, 0x00a51214, 0x00a41518, 0x00a01b24, 0x00901e29, 0x00721c21, 0x005c1716, 0x003c0000, 0x003b0000, 0x00521200, 0x00742e0e, 0x00984724, 0x00a55e3c, 0x00805538, 0x00200000, 0x001c0000, 0x00390204, 0x0068151b, 0x008f222a, 0x00a21d25, 0x00a31219, 0x00a31218, 0x00a71920, 0x00a0171e, 0x00a01822, 0x00a01724, 0x00a21624, 0x00a41522, 0x00a5151f, 0x00a4141d, 0x00a1171c, 0x009b1b1c, 0x008a231f, 0x00450500, 0x00581f07, 0x009b4c1a, 0x00b95a1a, 0x00be5211, 0x00c15415, 0x00bb581c, 0x008c3d10, 0x003e0f00, 0x00341000, 0x007a4932, 0x0059311c, 0x00090000, 0x000b0000, 0x002c0400, 0x00995930, 0x00b05c24, 0x00b75814, 0x00bc5913, 0x00bf590f, 0x00be5408, 0x00be5609, 0x00be580f, 0x00be550c, 0x00c65406, 0x00be570e, 0x00a35722, 0x00673514, 0x00130000, 0x00060000, 0x000b0300, 0x00100000, 0x00432510, 0x00664028, 0x00542c13, 0x002e0b00, 0x00130000, 0x00100000, 0x00130000, 0x00190000, 0x00290700, 0x00471805, 0x006c2f15, 0x008b401d, 0x00a14c1c, 0x00ae541b, 0x00ac5314, 0x00b45818, 0x00bb5c17, 0x00ba5814, 0x00ba560e, 0x00bc560f, 0x00bf5710, 0x00bf5710, 0x00c45811, 0x00c45811, 0x00c65610, 0x00c6550d, 0x00c5540e, 0x00c5540f, 0x00c4520f, 0x00c1530c, 0x00bd560b, 0x00bc580c, 0x00be580f, 0x00c0570e, 0x00c75409, 0x00ca5407, 0x00ca5408, 0x00c85508, 0x00c65608, 0x00c25708, 0x00c05a0c, 0x00b75a14, 0x00a7561e, 0x00995023, 0x0088431c, 0x006f320b, 0x00441300, 0x00390900, 0x00501500, 0x00823e13, 0x00a85c23, 0x00b4601b, 0x00bc5f10, 0x00c46614, 0x00bb6413, 0x00a55e1c, 0x00673c16, 0x002e0800, 0x005d2900, 0x00b16924, 0x00c06310, 0x00c96009, 0x00c75d0d, 0x00b35614, 0x00934c1f, 0x003a0d00, 0x000d0000, 0x00050300, 0x005c5d58, 0x00b5b6b1, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b1af, 0x0040403e, 0x0006070a, 0x00060000, 0x00200200, 0x00572c10, 0x0085563b, 0x0055301d, 0x00150905, 0x00090100, 0x00150000, 0x00471901, 0x00954a1f, 0x00a05021, 0x00904e2c, 0x0064321e, 0x001c0000, 0x00110000, 0x00300b00, 0x0077432b, 0x00945134, 0x007d3d21, 0x00370d00, 0x00310800, 0x006e3411, 0x00a05226, 0x00ac4919, 0x00b44813, 0x00b44511, 0x00b04612, 0x00ac4819, 0x00aa481a, 0x00aa4814, 0x00ae4c17, 0x00aa4816, 0x00ac4a18, 0x00ad4a18, 0x00a64c1f, 0x00803919, 0x00440b00, 0x00471608, 0x00743c2c, 0x009a4a2f, 0x00a74822, 0x00ac4818, 0x00b04714, 0x00b2481a, 0x00b0471c, 0x00ac4819, 0x00ac4916, 0x00b04b10, 0x00ad4a0f, 0x00a94917, 0x00ac4815, 0x00b5480e, 0x00bd4c0a, 0x00c45208, 0x00c8560b, 0x00c5570e, 0x00bd5b1c, 0x00a85527, 0x0077310d, 0x00440500, 0x008b4319, 0x00ba5814, 0x00c55904, 0x00bf5801, 0x00b95a07, 0x00b65f16, 0x00884814, 0x00280d00, 0x00080000, 0x00040000, 0x00030000, 0x00030000, 0x00040000, 0x00080000, 0x002b1713, 0x002c0502, 0x005a1516, 0x0090272c, 0x009b1f25, 0x009e1e24, 0x009e1f22, 0x009c201f, 0x0091201f, 0x007c1a23, 0x005b1019, 0x00330304, 0x001a0000, 0x00200000, 0x004a1a00, 0x008e4c24, 0x00af5f2f, 0x00b45826, 0x00a65728, 0x00774d27, 0x00140000, 0x00100000, 0x00160000, 0x00300001, 0x005b1314, 0x00882124, 0x00a02426, 0x00a51e22, 0x00a4181d, 0x00a01620, 0x009e1522, 0x009f1522, 0x00a11422, 0x00a41320, 0x00a4131f, 0x00a4141e, 0x00a2151d, 0x00a11c1e, 0x00902323, 0x004e0b09, 0x00460d00, 0x0095481c, 0x00b8581d, 0x00be5012, 0x00c25414, 0x00b9561b, 0x008c3f0f, 0x00401200, 0x002f0e00, 0x0069402c, 0x00502c1c, 0x000c0000, 0x000f0000, 0x003f1000, 0x009d582d, 0x00ae5820, 0x00ac4e0e, 0x00b15414, 0x00bc5c18, 0x00c0580f, 0x00bc5409, 0x00bd5710, 0x00be550c, 0x00c55405, 0x00be5610, 0x009c5423, 0x005a2d10, 0x00120000, 0x00080000, 0x00100200, 0x00301a09, 0x00321000, 0x006f442c, 0x00855738, 0x005c3014, 0x00301000, 0x00170000, 0x00080000, 0x00050000, 0x000b0000, 0x00180100, 0x00270000, 0x003c0800, 0x00561800, 0x00662100, 0x008a4313, 0x00954b15, 0x00a45319, 0x00af571b, 0x00b45719, 0x00b55818, 0x00b8581a, 0x00ba591a, 0x00ba5616, 0x00bd5614, 0x00bf5712, 0x00bf560e, 0x00bf560e, 0x00c0570e, 0x00c0570e, 0x00bf570c, 0x00bf580c, 0x00be580f, 0x00bc5815, 0x00be5818, 0x00c45817, 0x00c55614, 0x00c25510, 0x00be5410, 0x00b95512, 0x00ac5212, 0x00a15115, 0x008f4714, 0x006e3005, 0x004f1400, 0x00400400, 0x003b0200, 0x00481800, 0x00743e12, 0x00a45c29, 0x00b45d21, 0x00ba5b11, 0x00c5600d, 0x00cc600a, 0x00c15c08, 0x00b96417, 0x009a581c, 0x00542d0b, 0x002a0600, 0x00683000, 0x00b36821, 0x00c36513, 0x00c96009, 0x00c55803, 0x00bc550c, 0x00b15b21, 0x005c2100, 0x00180100, 0x00050100, 0x0030302c, 0x00949490, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b0aeaf, 0x0029282c, 0x00110c0e, 0x00090000, 0x00100000, 0x00462a18, 0x00503728, 0x00251714, 0x00080000, 0x00100000, 0x00330b00, 0x00823e13, 0x00a85722, 0x00994b1a, 0x00904e2b, 0x00401608, 0x00190000, 0x00100000, 0x003d2015, 0x00784936, 0x00622d18, 0x00310400, 0x004b1905, 0x007f3d1f, 0x00a2522a, 0x00a74c1c, 0x00af4b18, 0x00b04814, 0x00ad4611, 0x00ac4818, 0x00ac4819, 0x00ab4718, 0x00ac4918, 0x00ab4a13, 0x00a94811, 0x00af4b18, 0x00a64a1f, 0x00662203, 0x00531700, 0x0074321f, 0x00964a32, 0x00a54c24, 0x00a84818, 0x00ab4813, 0x00ab4813, 0x00a84617, 0x00aa4618, 0x00b04816, 0x00b34813, 0x00b24610, 0x00b14814, 0x00ad4c19, 0x00b05018, 0x00b9510c, 0x00c15404, 0x00c85700, 0x00ca5802, 0x00c75505, 0x00bf5815, 0x009c4920, 0x005f1800, 0x00541000, 0x00a45529, 0x00bc560d, 0x00c85804, 0x00be5705, 0x00b65a10, 0x00a55b1d, 0x005c2a00, 0x00130300, 0x00010200, 0x00000100, 0x00010000, 0x00040000, 0x00100200, 0x00331d0c, 0x0060402b, 0x00451804, 0x00390000, 0x00661814, 0x007f2524, 0x00842522, 0x007a211c, 0x00601810, 0x00410a04, 0x00250003, 0x00130002, 0x000c0000, 0x00110000, 0x00290000, 0x00652c0d, 0x00a55a28, 0x00b15b1f, 0x00b45817, 0x00a4591c, 0x006e491a, 0x00100000, 0x000f0000, 0x000c0000, 0x000a0000, 0x001d0100, 0x004d130c, 0x007d241f, 0x009b2324, 0x00a2171f, 0x00a71624, 0x00a81424, 0x00a61422, 0x00a4131f, 0x00a11420, 0x00a01420, 0x00a01420, 0x00a0141f, 0x00a81b23, 0x009a2128, 0x00590d12, 0x00440400, 0x0095441b, 0x00b6581c, 0x00bc5311, 0x00be5714, 0x00b35a19, 0x00874410, 0x003b1700, 0x00280f00, 0x00573626, 0x0045281b, 0x000e0000, 0x00140000, 0x00511c01, 0x00a05429, 0x00b0571e, 0x009e4104, 0x009c460c, 0x00ae5618, 0x00be5b14, 0x00bc550c, 0x00bd5711, 0x00be550d, 0x00c45406, 0x00bb5612, 0x00975224, 0x0051270d, 0x00110000, 0x000c0000, 0x00180300, 0x00513a2f, 0x001f0700, 0x00452819, 0x007f5538, 0x00895835, 0x00723f20, 0x00451a05, 0x001d0601, 0x00060000, 0x00020003, 0x0017100f, 0x002f1914, 0x00401f10, 0x00411700, 0x00300100, 0x00310000, 0x00390300, 0x004d0c00, 0x00621d00, 0x00782f09, 0x0089401c, 0x00944d2a, 0x009e5531, 0x00a4552e, 0x00a85829, 0x00ac5824, 0x00ad571d, 0x00ad571b, 0x00af591b, 0x00b05a18, 0x00b25918, 0x00b65516, 0x00b5531b, 0x00af5523, 0x00ab552a, 0x00a9552f, 0x00a5542d, 0x009f4f27, 0x00974d26, 0x00773817, 0x00592507, 0x003c0f00, 0x00300400, 0x00370300, 0x004b0d00, 0x006e2a00, 0x00924817, 0x00b0652e, 0x00b06022, 0x00b85c15, 0x00c25c0f, 0x00c55c09, 0x00c75904, 0x00cb5a06, 0x00c86010, 0x00b7641a, 0x00894c10, 0x00401700, 0x00300600, 0x007a3801, 0x00b86720, 0x00c16618, 0x00c5610c, 0x00c85904, 0x00c95b0a, 0x00b95815, 0x007b3405, 0x00270a00, 0x00080300, 0x000f0e0b, 0x00747473, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b0b4, 0x002a2629, 0x000b0807, 0x00050000, 0x000d0000, 0x0024150c, 0x00170c0b, 0x000c0002, 0x000a0000, 0x00280900, 0x00682c04, 0x00a75821, 0x00b0581c, 0x009a4815, 0x007d4226, 0x00220000, 0x00120000, 0x000e0000, 0x005d3e32, 0x00502414, 0x00340000, 0x00682b14, 0x00934828, 0x009e4b22, 0x00a4481a, 0x00aa4a18, 0x00ac4914, 0x00ab4712, 0x00ac4918, 0x00ae491b, 0x00ab4519, 0x00a84515, 0x00ac4e16, 0x00a4460e, 0x00ac481a, 0x00a34820, 0x00591300, 0x006f2c11, 0x00984930, 0x00a64c2c, 0x00a84818, 0x00ab4810, 0x00ae4d14, 0x00ab4c15, 0x00a74716, 0x00ac4918, 0x00b44912, 0x00b24409, 0x00b44308, 0x00b6480e, 0x00b35018, 0x00b85618, 0x00c4590f, 0x00c75906, 0x00c45801, 0x00c05604, 0x00bc580e, 0x00b0571d, 0x0084411c, 0x00450700, 0x00671e00, 0x00b65e2c, 0x00c0550e, 0x00c45407, 0x00be570e, 0x00ad5819, 0x008f5023, 0x00330e00, 0x00080000, 0x00000400, 0x00000100, 0x00030000, 0x000c0000, 0x00260b00, 0x00643d1d, 0x00916038, 0x00814821, 0x004c0c00, 0x003c0000, 0x003f0000, 0x00440000, 0x003e0000, 0x002d0000, 0x001b0000, 0x00090003, 0x00010008, 0x00000005, 0x000a0000, 0x003d1200, 0x007a3813, 0x00b15a24, 0x00b45411, 0x00bc5b14, 0x00a75718, 0x00684014, 0x00140100, 0x000c0000, 0x00080004, 0x00030102, 0x00080000, 0x00200000, 0x00440500, 0x00761712, 0x00982428, 0x00a1202c, 0x00a51b2a, 0x00a81723, 0x00a7151f, 0x00a2141d, 0x00a0141e, 0x00a01420, 0x00a01420, 0x00a41721, 0x009e242e, 0x00611017, 0x00470200, 0x00944014, 0x00b55818, 0x00bc5711, 0x00b85810, 0x00af5d1c, 0x00834713, 0x00361900, 0x00211000, 0x00483021, 0x003e241c, 0x000e0000, 0x00160000, 0x00602509, 0x00a65729, 0x00b55a21, 0x00943900, 0x00863804, 0x00994a14, 0x00b45815, 0x00b9540f, 0x00bb5612, 0x00bd550f, 0x00c25409, 0x00b85714, 0x00935124, 0x004a2309, 0x000f0000, 0x000c0000, 0x00280c00, 0x00715042, 0x00280e08, 0x00160000, 0x00300c00, 0x006a3f20, 0x008c593c, 0x00845138, 0x00522d20, 0x00210b02, 0x00080000, 0x00050000, 0x000c0000, 0x002a1810, 0x005c4433, 0x007d5d49, 0x006a4132, 0x005e2a18, 0x00501100, 0x00460000, 0x00400000, 0x003c0000, 0x00380000, 0x00380000, 0x00440c00, 0x004c1400, 0x00591f00, 0x00622701, 0x006b2e04, 0x00743508, 0x007a3905, 0x00803806, 0x00883506, 0x00842f05, 0x00782904, 0x006b2100, 0x005c1800, 0x004c0c00, 0x003e0000, 0x002f0000, 0x00200000, 0x00170000, 0x001c0300, 0x00432210, 0x007e4826, 0x00a15c2d, 0x00af5e26, 0x00b65e1f, 0x00b65b14, 0x00bc5c10, 0x00c35d0b, 0x00c55c05, 0x00c55c04, 0x00c85c05, 0x00cc5a07, 0x00c35c0f, 0x00b16620, 0x0077410b, 0x00290500, 0x00370c00, 0x008a440a, 0x00bc651b, 0x00c16412, 0x00c6620a, 0x00cc5e05, 0x00c65500, 0x00c1570e, 0x00a04f1a, 0x00381300, 0x00090000, 0x00040100, 0x00535353, 0x00797878, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00686667, 0x00292827, 0x00080804, 0x00080200, 0x00050000, 0x000c0506, 0x00070107, 0x00030004, 0x00100000, 0x004a1800, 0x00a45825, 0x00bb5a18, 0x00b55411, 0x009e4c1d, 0x00581e02, 0x00180000, 0x000c0000, 0x002c140e, 0x006c483b, 0x00652a13, 0x00863c1b, 0x009f4a24, 0x00a64b20, 0x00a74a1b, 0x00a94b19, 0x00aa4a18, 0x00ac4a18, 0x00ac4817, 0x00ac4818, 0x00ae471b, 0x00ac471b, 0x00aa4c18, 0x00ab4e1d, 0x00a4441c, 0x008e3412, 0x00803416, 0x008b4021, 0x00a24729, 0x00ac4821, 0x00ae4918, 0x00ac4810, 0x00a94810, 0x00ac4b14, 0x00ac4a14, 0x00ac4711, 0x00b04509, 0x00b64504, 0x00c34c04, 0x00c65209, 0x00c05715, 0x00c05614, 0x00c8540a, 0x00cb580b, 0x00c45811, 0x00b35818, 0x009a5420, 0x00602c04, 0x002a0500, 0x00340800, 0x007d3302, 0x00b8571b, 0x00cb5819, 0x00c45011, 0x00ba5418, 0x00af5f30, 0x005c2910, 0x001e0400, 0x00040000, 0x00000001, 0x00000000, 0x00090000, 0x001d0000, 0x005b2804, 0x00985626, 0x00a75c24, 0x00a55a20, 0x00a25623, 0x00873b14, 0x00722805, 0x006a2400, 0x006f310e, 0x00774837, 0x003e201c, 0x000e0208, 0x00000007, 0x00000206, 0x000c0000, 0x00502204, 0x009b5021, 0x00b8541c, 0x00c05313, 0x00c15411, 0x00ad541c, 0x00683617, 0x00180000, 0x000e0004, 0x00070008, 0x00080004, 0x001c0605, 0x00472010, 0x003f0c00, 0x003a0000, 0x00530b02, 0x007b2024, 0x0093252d, 0x00a01c24, 0x00ad1c22, 0x00b21f25, 0x00ac181f, 0x00ab1a21, 0x00a51a22, 0x00a4212a, 0x0095282d, 0x00540504, 0x00510b00, 0x0098420f, 0x00b85813, 0x00ba560c, 0x00b95a12, 0x00ac5c1a, 0x00844b18, 0x00341800, 0x001a0c00, 0x003a281b, 0x0037231d, 0x000c0000, 0x001c0000, 0x00723617, 0x00a85624, 0x00b45719, 0x00ac5217, 0x005d1800, 0x007d390c, 0x00aa551a, 0x00b55613, 0x00ba5814, 0x00bb540f, 0x00bf560d, 0x00b55818, 0x00945327, 0x00431c02, 0x000d0000, 0x000c0000, 0x00381000, 0x008c5d45, 0x00381104, 0x001d0000, 0x00140000, 0x00160000, 0x003e1c0c, 0x00714430, 0x00905b40, 0x006f3d1e, 0x00371400, 0x00140000, 0x00080000, 0x00040000, 0x00140800, 0x003c2415, 0x00805446, 0x009c5f48, 0x00a45630, 0x00ae5729, 0x00a14a1c, 0x0085380d, 0x006d3112, 0x00401200, 0x00200000, 0x00180000, 0x00110000, 0x00140000, 0x001a0000, 0x001e0000, 0x002b0000, 0x00340000, 0x00340000, 0x00390000, 0x003b0000, 0x003c0000, 0x00450900, 0x00531800, 0x00581d00, 0x004d1b00, 0x00240300, 0x00100000, 0x001b0500, 0x004a2711, 0x00a76535, 0x00af5918, 0x00bd6015, 0x00be5b0b, 0x00c25b08, 0x00c25c06, 0x00c05b03, 0x00c46008, 0x00bf5b03, 0x00c45e07, 0x00c75906, 0x00bd5c12, 0x009c5e22, 0x00583004, 0x001a0000, 0x00371300, 0x00a05a1b, 0x00bc6210, 0x00c46005, 0x00cc6304, 0x00cc6005, 0x00c85702, 0x00c45507, 0x00b25c22, 0x0051270d, 0x00120400, 0x00030000, 0x00343436, 0x00909092, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b0afac, 0x0041403d, 0x00080402, 0x00050200, 0x00000001, 0x00000004, 0x00010109, 0x000c0000, 0x00381300, 0x0088481d, 0x00b05313, 0x00bd550f, 0x00bb5b1e, 0x00974c20, 0x002a0000, 0x00120000, 0x00150300, 0x004e2f23, 0x00814326, 0x009c4920, 0x00a94c1f, 0x00aa4818, 0x00ad4a17, 0x00ac4a16, 0x00aa4a19, 0x00aa4a19, 0x00ac4918, 0x00ad4818, 0x00af4718, 0x00ac4718, 0x00a54515, 0x00a74a1c, 0x00a74620, 0x009c401d, 0x0096421e, 0x009d4823, 0x00ac4821, 0x00af4418, 0x00ae4410, 0x00b04810, 0x00b0490f, 0x00ae480d, 0x00b0470c, 0x00b84c0f, 0x00c05212, 0x00c6550f, 0x00ca5204, 0x00cc580a, 0x00c65a12, 0x00bd5410, 0x00c0530e, 0x00be5515, 0x00a74c18, 0x008a3f14, 0x00440d00, 0x00300900, 0x001c0000, 0x00381100, 0x00944812, 0x00b85413, 0x00c55314, 0x00c65618, 0x00b85620, 0x00984f29, 0x00380f04, 0x00110002, 0x00050005, 0x00010005, 0x00040100, 0x00100000, 0x004b1800, 0x00894111, 0x00ac5a1c, 0x00b25a16, 0x00b35b17, 0x00b05819, 0x00aa531d, 0x00a4501e, 0x009f561e, 0x009c6032, 0x0070402c, 0x002f100c, 0x000a0002, 0x00000003, 0x00000000, 0x00190800, 0x00683208, 0x00a8571d, 0x00bd5518, 0x00c25111, 0x00c05310, 0x00a95019, 0x00612f14, 0x00110000, 0x00050000, 0x00030001, 0x000c0000, 0x0032140b, 0x00794830, 0x0080492a, 0x0057260d, 0x00340300, 0x00320000, 0x0053070c, 0x00760f12, 0x00911a1c, 0x009c2020, 0x009e2122, 0x00a22728, 0x009e2728, 0x00942829, 0x00721410, 0x00430000, 0x00672002, 0x00a44f17, 0x00b85812, 0x00bb570f, 0x00b4520d, 0x00af5a1c, 0x00844818, 0x00341700, 0x00160800, 0x00302015, 0x002d1e18, 0x000a0000, 0x001b0000, 0x0080401e, 0x00aa5621, 0x00b65717, 0x00b2581d, 0x00622200, 0x005a1f00, 0x00924611, 0x00b55c1f, 0x00b75814, 0x00b8550f, 0x00bd5710, 0x00b25819, 0x00915024, 0x00401800, 0x000c0000, 0x000e0000, 0x00461800, 0x00985f3c, 0x00582b15, 0x00240300, 0x000d0000, 0x000a0000, 0x001b0500, 0x00250300, 0x00532004, 0x00804a28, 0x007c5030, 0x0045260d, 0x00140400, 0x00050000, 0x00080000, 0x000f0000, 0x002f0c00, 0x0078432d, 0x00a0542d, 0x00ac5421, 0x00b2571f, 0x00ab551f, 0x009b5628, 0x007c4725, 0x003d1804, 0x00120000, 0x000b0200, 0x00050000, 0x000c0000, 0x00391d0e, 0x007c4c2f, 0x00844925, 0x00844828, 0x008c4c2a, 0x00945024, 0x00975223, 0x009b5729, 0x009d5c2d, 0x009a582a, 0x008d5430, 0x0045200d, 0x00180000, 0x00100000, 0x003e1904, 0x009b5320, 0x00b3570e, 0x00c05b08, 0x00c55c03, 0x00c65900, 0x00c55a01, 0x00c05c06, 0x00be5d08, 0x00bc5e08, 0x00c0600a, 0x00c05808, 0x00bb631d, 0x00834e1e, 0x003c1d00, 0x00180000, 0x00441e00, 0x00aa601c, 0x00c0610b, 0x00c66205, 0x00ca6001, 0x00cc5f04, 0x00c95804, 0x00c65608, 0x00b85b1f, 0x00673415, 0x00200a00, 0x00050000, 0x001f1f20, 0x007c7c80, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b8b1af, 0x0053504f, 0x00141414, 0x00050608, 0x00000003, 0x00000005, 0x00020000, 0x00240e04, 0x00734328, 0x00ac5c2b, 0x00bf5c1c, 0x00bd5711, 0x00b0571c, 0x00642402, 0x00260000, 0x000e0000, 0x002c1102, 0x00804321, 0x00a14a1c, 0x00ab4712, 0x00af440b, 0x00b1460c, 0x00af460e, 0x00a94614, 0x00a94718, 0x00ab4816, 0x00ac4814, 0x00ac4511, 0x00ac4414, 0x00ac461a, 0x00ac481f, 0x00aa471e, 0x00a7441b, 0x00a74418, 0x00ab4718, 0x00af4715, 0x00b14310, 0x00b5430e, 0x00b8450d, 0x00bb490c, 0x00c14d0c, 0x00c84f0c, 0x00c9510d, 0x00c2530f, 0x00c0520b, 0x00cb5508, 0x00c55003, 0x00bc5208, 0x00bc5c17, 0x00b05c20, 0x008e4414, 0x005c1d00, 0x00380000, 0x00471100, 0x00572511, 0x003e1805, 0x00471700, 0x00a25621, 0x00b95a17, 0x00c45811, 0x00bc5411, 0x00ae5822, 0x00723310, 0x00200000, 0x000a0004, 0x00040006, 0x00030004, 0x000a0000, 0x00250700, 0x00743108, 0x00aa5419, 0x00b65714, 0x00b4550d, 0x00b65a13, 0x00b4540f, 0x00bc5514, 0x00bc5a1c, 0x00ac5c1c, 0x00a16330, 0x004c1e07, 0x00180000, 0x00080000, 0x000a0401, 0x00080000, 0x00361700, 0x0081420c, 0x00b15a16, 0x00b95611, 0x00ba540c, 0x00b7580e, 0x009f541a, 0x00582c14, 0x000d0000, 0x00000200, 0x00030700, 0x000d0000, 0x00401c00, 0x008c4c1f, 0x00a45c2e, 0x00854b2a, 0x004d1f0d, 0x00180000, 0x001d0000, 0x002e0000, 0x003f0000, 0x00480200, 0x00520800, 0x005c100a, 0x005a0c05, 0x00500400, 0x00480000, 0x004e0c00, 0x008a461a, 0x00ac581b, 0x00b55510, 0x00c15916, 0x00bd5517, 0x00b55820, 0x00894117, 0x00371300, 0x00140200, 0x0024160e, 0x00221811, 0x00080000, 0x001a0000, 0x008e4e27, 0x00ae581e, 0x00b75513, 0x00b35b1f, 0x00692e07, 0x003d0900, 0x00743304, 0x00ac5b23, 0x00b45818, 0x00b75510, 0x00bb5811, 0x00b1581b, 0x008f4e22, 0x003c1400, 0x000b0000, 0x00100000, 0x005a2800, 0x009c5e31, 0x00704128, 0x00260400, 0x00100000, 0x00090000, 0x000d0000, 0x000d0000, 0x00230600, 0x002c0b00, 0x004b2510, 0x00684432, 0x00573a30, 0x00230f09, 0x00080000, 0x000c0300, 0x000d0000, 0x00280c00, 0x00632f0d, 0x009b5422, 0x00ae581c, 0x00b05412, 0x00b45c1b, 0x00a65821, 0x00783e15, 0x00310c00, 0x00110200, 0x00050000, 0x000e0000, 0x00381500, 0x009f5a2b, 0x00ac561c, 0x00ac561c, 0x00b0591d, 0x00b75c17, 0x00b85c14, 0x00b45c15, 0x00b45d17, 0x00b15a18, 0x00a65b23, 0x00784220, 0x00320c00, 0x00150000, 0x00300800, 0x00823d0e, 0x00b45a17, 0x00bd5706, 0x00c65b02, 0x00c55800, 0x00c35903, 0x00c45d0e, 0x00bb590a, 0x00bc5f0b, 0x00bc5f0c, 0x00b9580e, 0x00b16027, 0x00683a1a, 0x00240800, 0x00200300, 0x005f320c, 0x00b4661b, 0x00c06006, 0x00c6620a, 0x00c45d06, 0x00c85f06, 0x00c95c06, 0x00c75708, 0x00b85919, 0x00824721, 0x00341301, 0x00080000, 0x00080809, 0x00616064, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b0b3, 0x006b6c6d, 0x00202120, 0x00040807, 0x00020608, 0x00000000, 0x000e0200, 0x003c1c0d, 0x00804320, 0x00b05f2a, 0x00bb5e1c, 0x00b1571a, 0x00965029, 0x00380800, 0x000e0000, 0x00160000, 0x00612a09, 0x009e4c1d, 0x00b24c17, 0x00b7480c, 0x00b64607, 0x00b24508, 0x00ac4510, 0x00aa4613, 0x00ab4711, 0x00ad4810, 0x00b0470d, 0x00b0450e, 0x00b14615, 0x00b04516, 0x00ac4413, 0x00ae4410, 0x00b4460e, 0x00b84a10, 0x00bb4e11, 0x00bc4f10, 0x00c65117, 0x00c44c10, 0x00c44d0a, 0x00c9520a, 0x00cc5108, 0x00ca5108, 0x00c15610, 0x00c05a14, 0x00c05813, 0x00c05b18, 0x00b75d1c, 0x00994b10, 0x00672500, 0x00430800, 0x00480d00, 0x0060240d, 0x00884830, 0x007b3d27, 0x00471501, 0x00582102, 0x00b05f28, 0x00b75711, 0x00bf570a, 0x00bc5b14, 0x00a15721, 0x00471400, 0x001b0000, 0x00060003, 0x00040004, 0x00070000, 0x00150000, 0x004f240b, 0x00964918, 0x00b85718, 0x00b95610, 0x00b8540c, 0x00b85813, 0x00b85510, 0x00bd500a, 0x00b8510f, 0x00a8571b, 0x0084481c, 0x00300800, 0x00110000, 0x00080000, 0x000a0200, 0x00100000, 0x00502606, 0x00964d14, 0x00b55a13, 0x00b5540d, 0x00b5540c, 0x00b35a10, 0x009c551c, 0x00502813, 0x000c0000, 0x00000300, 0x00000400, 0x000d0000, 0x00532903, 0x00994d17, 0x00ac5824, 0x00904f29, 0x00522410, 0x00100000, 0x001c0808, 0x00432015, 0x00582a17, 0x00501801, 0x00440900, 0x00440700, 0x00400200, 0x004f0b00, 0x00692304, 0x00864016, 0x00a85e28, 0x00ac5a1b, 0x00b15514, 0x00b35012, 0x00b55017, 0x00b55822, 0x00873f17, 0x00361100, 0x000e0000, 0x00150d05, 0x0018100b, 0x00070000, 0x00200300, 0x0099552a, 0x00b3581c, 0x00b85411, 0x00ad5519, 0x00703811, 0x00390b00, 0x005c2200, 0x00964f1f, 0x00b0581c, 0x00b75712, 0x00ba5712, 0x00b1581b, 0x008e4c20, 0x00390f00, 0x000b0000, 0x00130000, 0x00682e02, 0x00a05c28, 0x00875331, 0x00320c00, 0x0030150c, 0x0024100b, 0x00130000, 0x000c0000, 0x000d0000, 0x00100000, 0x001b0100, 0x002a1008, 0x003f241d, 0x0044302b, 0x002a1e1a, 0x00040000, 0x00050100, 0x000c0000, 0x002b0a00, 0x005f2a02, 0x00964f1a, 0x00b35d1f, 0x00b65513, 0x00b35414, 0x00a65420, 0x006e330f, 0x00240600, 0x000b0000, 0x00100000, 0x00260100, 0x008d4515, 0x00b15514, 0x00b75510, 0x00bb550b, 0x00bc5504, 0x00be5502, 0x00bb5503, 0x00ba5505, 0x00bb580b, 0x00b55c1a, 0x00995427, 0x005d280c, 0x00280200, 0x00240000, 0x00642601, 0x00b05d26, 0x00ba580d, 0x00c35703, 0x00c45704, 0x00c45806, 0x00c35b0e, 0x00bb580b, 0x00bc5c0c, 0x00b85d10, 0x00ba5e1c, 0x009c5221, 0x00512610, 0x00190000, 0x00300c00, 0x007d481f, 0x00b7641a, 0x00c05f04, 0x00c5610c, 0x00c45c09, 0x00c85f08, 0x00c85e07, 0x00c55507, 0x00b85614, 0x00995427, 0x00441a00, 0x000f0000, 0x00000000, 0x004a494d, 0x00b1b1b3, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00afb0b1, 0x00898b88, 0x00393b37, 0x000b0b09, 0x00000000, 0x00080104, 0x001e0b08, 0x003b1604, 0x005e2807, 0x008b4412, 0x00ad6230, 0x00a15f3c, 0x00542710, 0x00130200, 0x000f0000, 0x003c1200, 0x008c4622, 0x00b45623, 0x00b94c10, 0x00bf500d, 0x00bd4e0c, 0x00b84d10, 0x00b54d11, 0x00b64e11, 0x00b74f10, 0x00ba4d0f, 0x00bc4c0c, 0x00bc4c0c, 0x00bd4c0d, 0x00bc500c, 0x00be510b, 0x00c45008, 0x00c45006, 0x00c25308, 0x00c3540c, 0x00c4520d, 0x00c8530f, 0x00cb550b, 0x00cb5509, 0x00c95407, 0x00c35409, 0x00b85712, 0x00b25a1b, 0x00b1602a, 0x00904818, 0x00652800, 0x00481100, 0x00440d00, 0x005d2000, 0x00883a11, 0x00a44e23, 0x00a7522a, 0x007f3210, 0x00430700, 0x006f2e0c, 0x00b75d22, 0x00be570c, 0x00c15706, 0x00b55910, 0x00864918, 0x00270200, 0x00120000, 0x00060000, 0x00070000, 0x000c0000, 0x00301100, 0x00743e17, 0x00ac5822, 0x00b45210, 0x00b95512, 0x00b5540f, 0x00b15410, 0x00b95914, 0x00bc540d, 0x00b45214, 0x00a85b30, 0x005a230a, 0x001b0000, 0x000c0000, 0x00020000, 0x00060000, 0x00220500, 0x006a3614, 0x00a55620, 0x00b85918, 0x00b5540f, 0x00b4540f, 0x00b45a15, 0x00995320, 0x00482210, 0x000b0000, 0x00030200, 0x00020000, 0x00100000, 0x00653918, 0x00a5541f, 0x00af5420, 0x00894220, 0x00441403, 0x00100000, 0x00220907, 0x0064321e, 0x00924e2d, 0x0096461e, 0x00913e12, 0x00904518, 0x0093481e, 0x0097431f, 0x00a85028, 0x00af5522, 0x00ab541a, 0x00ac581e, 0x00a65318, 0x00903800, 0x009b410c, 0x00b05a27, 0x00814018, 0x002f1400, 0x00050000, 0x00070700, 0x000c0a04, 0x00090000, 0x002c0a00, 0x00a05828, 0x00b45617, 0x00ba5613, 0x00aa5418, 0x00783e18, 0x00401300, 0x00431100, 0x0080411a, 0x00ad5a21, 0x00b85716, 0x00b95410, 0x00b2581b, 0x00904c20, 0x00370c00, 0x000b0000, 0x00150000, 0x0079380c, 0x00ab5d26, 0x009c5e31, 0x00411000, 0x00492107, 0x005c3724, 0x00472314, 0x00230400, 0x00110000, 0x000f0000, 0x000b0205, 0x00040004, 0x000c0504, 0x001e1614, 0x00201513, 0x000b0200, 0x00030000, 0x00070000, 0x00120000, 0x00280700, 0x005f2c0f, 0x0098522a, 0x00b35721, 0x00ba5216, 0x00b64d14, 0x00a64f21, 0x005a240f, 0x00200000, 0x00140000, 0x00200100, 0x006c3212, 0x00ad5e2a, 0x00b85712, 0x00c05407, 0x00c25505, 0x00c45707, 0x00c25807, 0x00c05405, 0x00bf5408, 0x00b95813, 0x00ab5720, 0x008a4820, 0x004c1c06, 0x00210000, 0x00431200, 0x00975730, 0x00b45a1d, 0x00be550c, 0x00c45609, 0x00c45608, 0x00c5580c, 0x00c1590e, 0x00bb590a, 0x00b85c14, 0x00b86026, 0x00813910, 0x00390d00, 0x001c0000, 0x00481c04, 0x0097592e, 0x00b46118, 0x00bf5e08, 0x00c45e0c, 0x00c75e0b, 0x00c85f08, 0x00c65e06, 0x00c45506, 0x00bb5610, 0x00ac5b24, 0x00572000, 0x00180100, 0x00030000, 0x0039383c, 0x009e9fa2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00444443, 0x00a0a19d, 0x005e5d5a, 0x0024211f, 0x00030000, 0x00060000, 0x00140100, 0x00200200, 0x003e1300, 0x005b2809, 0x00754328, 0x00684330, 0x00180e00, 0x000c0300, 0x001e0000, 0x00632a12, 0x00a85328, 0x00bd571e, 0x00c25816, 0x00c35810, 0x00c35611, 0x00c15610, 0x00c05510, 0x00c05510, 0x00c45410, 0x00c6530e, 0x00c8540d, 0x00c8550c, 0x00c5580b, 0x00c7580a, 0x00cc5608, 0x00cb5406, 0x00c55708, 0x00c2580c, 0x00c1560f, 0x00c35812, 0x00c2550f, 0x00bc530c, 0x00b95611, 0x00b65a19, 0x00a8551c, 0x00974d1b, 0x00682700, 0x00511800, 0x00440d00, 0x00531900, 0x00733514, 0x00964b22, 0x00b0521c, 0x00b4521c, 0x00a74e21, 0x00782c08, 0x004a0c00, 0x00843d18, 0x00b75416, 0x00c55708, 0x00c35909, 0x00ab5613, 0x005a2a02, 0x00180000, 0x000a0000, 0x00070000, 0x00080000, 0x00140000, 0x005b2d09, 0x0094501d, 0x00b3591e, 0x00b24c0d, 0x00be5514, 0x00bb5410, 0x00b04f0a, 0x00b65610, 0x00b8540e, 0x00ae551c, 0x00914f2d, 0x002e0400, 0x000c0000, 0x00040000, 0x00020000, 0x000b0000, 0x003f1901, 0x0083441e, 0x00ad5723, 0x00b65516, 0x00b7540f, 0x00b5540f, 0x00b65917, 0x009b5020, 0x00441d0b, 0x000b0000, 0x00040002, 0x00050000, 0x00180100, 0x006f4020, 0x00a3501c, 0x00ac521d, 0x0083401f, 0x00401303, 0x00160000, 0x00270c04, 0x00703417, 0x00a8582b, 0x00b95a24, 0x00b6551b, 0x00ab541a, 0x00a8521c, 0x00b45625, 0x00b65422, 0x00b55315, 0x00ae5212, 0x00a95b22, 0x00883d0c, 0x006f2000, 0x00924011, 0x00ac5a2b, 0x007e4019, 0x002c1403, 0x00020000, 0x00000200, 0x00050300, 0x000c0000, 0x003b1300, 0x00a65928, 0x00b45312, 0x00bb5714, 0x00ad571c, 0x007f441e, 0x00401400, 0x002c0200, 0x006f3917, 0x00aa5825, 0x00b75617, 0x00b8510e, 0x00b45719, 0x00904a20, 0x00350900, 0x000c0000, 0x00190000, 0x008e461c, 0x00ad561f, 0x00a8602e, 0x00591c00, 0x004c1500, 0x007d482c, 0x00885338, 0x0063321b, 0x00330c00, 0x00180000, 0x00060000, 0x00020105, 0x00000302, 0x00010200, 0x00090100, 0x000a0200, 0x00070401, 0x00020000, 0x00080000, 0x00110000, 0x00260500, 0x005d2910, 0x00994c21, 0x00b75520, 0x00b94c10, 0x00b5521a, 0x00904824, 0x004e1c0a, 0x001a0000, 0x00140000, 0x003d1200, 0x0096562d, 0x00b25818, 0x00be5409, 0x00bf5408, 0x00c25307, 0x00c45406, 0x00c25307, 0x00be540b, 0x00bb540f, 0x00b55616, 0x00aa5824, 0x00763813, 0x00390700, 0x00330800, 0x0075401e, 0x00af5c23, 0x00bc5812, 0x00c1560f, 0x00c3550a, 0x00c45608, 0x00c45b0b, 0x00b9590c, 0x00b45d19, 0x00a45524, 0x005f2000, 0x00240000, 0x00280100, 0x00662f0e, 0x00a8602e, 0x00b55e14, 0x00c05e09, 0x00c45c09, 0x00c75e09, 0x00c65e06, 0x00c65e06, 0x00c45806, 0x00c05910, 0x00b75c20, 0x006a2900, 0x00210400, 0x00050000, 0x002c2a2c, 0x0088888c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b2b3, 0x00888583, 0x004d4642, 0x0019100c, 0x00070000, 0x00050000, 0x00100401, 0x00130000, 0x002c1208, 0x003f2a1e, 0x000d0b00, 0x00040100, 0x000d0000, 0x00380d04, 0x00883c1c, 0x00b65826, 0x00b85718, 0x00be580f, 0x00c4590c, 0x00c75809, 0x00c65808, 0x00c65608, 0x00c8540d, 0x00cb540e, 0x00c75308, 0x00c45406, 0x00c25408, 0x00c3550a, 0x00c8550c, 0x00c8570f, 0x00c45710, 0x00bf5813, 0x00b85b18, 0x00b55c1d, 0x00b75c23, 0x00af5824, 0x0098501f, 0x007c3c10, 0x00622100, 0x004d0f00, 0x00491000, 0x005a1d00, 0x007c3106, 0x009c4818, 0x00ad511d, 0x00b24f15, 0x00b85010, 0x00b6551b, 0x009b5228, 0x005f2303, 0x00460c00, 0x00944b24, 0x00c05413, 0x00c45003, 0x00b9530c, 0x00a25724, 0x002e0b00, 0x000c0000, 0x00050000, 0x00080001, 0x000a0000, 0x002c1100, 0x00814517, 0x00aa581c, 0x00b6541a, 0x00bb5014, 0x00c45414, 0x00c55410, 0x00bd5108, 0x00b95409, 0x00b25510, 0x00a25820, 0x00643618, 0x00180000, 0x00010100, 0x00000500, 0x00050000, 0x00180200, 0x00602e0d, 0x00954c20, 0x00af541e, 0x00b65212, 0x00b8530d, 0x00b8540c, 0x00b85515, 0x009b4e1d, 0x00401b06, 0x000c0000, 0x00060000, 0x000a0000, 0x00200300, 0x00784624, 0x00a85822, 0x00ac5e25, 0x00743f1b, 0x002c0b00, 0x000d0000, 0x002b0e01, 0x00793c14, 0x00ac571d, 0x00b55412, 0x00b7520e, 0x00b55315, 0x00ba581e, 0x00b45118, 0x00b55013, 0x00be5810, 0x00b85c18, 0x009b541f, 0x00601f00, 0x00641c00, 0x00954820, 0x00ab582c, 0x00803e1b, 0x002c1405, 0x00020000, 0x00000000, 0x00040000, 0x00140000, 0x004d1e06, 0x00ac5924, 0x00b5510e, 0x00b85614, 0x00ad581e, 0x00874a23, 0x003d1000, 0x00210000, 0x005f2f12, 0x00a45526, 0x00b55416, 0x00b9500d, 0x00b75519, 0x008e481e, 0x00320500, 0x000d0000, 0x001e0000, 0x00984a20, 0x00b1531b, 0x00b15e2c, 0x00782c01, 0x00500a00, 0x00803a1a, 0x00a0582e, 0x00944c20, 0x007d3d13, 0x00501e00, 0x00200200, 0x000a0000, 0x00000000, 0x00000400, 0x00020200, 0x00000000, 0x00000004, 0x0007060b, 0x00080000, 0x000b0000, 0x00170100, 0x00321100, 0x00653111, 0x009f5425, 0x00b7591a, 0x00b35211, 0x00a7531c, 0x007c3c13, 0x003a1100, 0x00170000, 0x00240300, 0x00704023, 0x00a75923, 0x00b65513, 0x00bc540f, 0x00c0510a, 0x00c45006, 0x00c4530b, 0x00bf5714, 0x00bc5814, 0x00bc550c, 0x00b85812, 0x009e4e12, 0x006d2d00, 0x003f1000, 0x00582500, 0x00ab591d, 0x00bc5812, 0x00bc5914, 0x00bd560c, 0x00c45802, 0x00c15b03, 0x00b55c0d, 0x00a85d1f, 0x00783a15, 0x003c0b00, 0x001c0000, 0x00401600, 0x008b4818, 0x00b45f1d, 0x00bc5e0c, 0x00c25f05, 0x00c45f04, 0x00c65e04, 0x00c55d02, 0x00c75d04, 0x00c55807, 0x00c45a10, 0x00ba5814, 0x007f3404, 0x002c0800, 0x00080000, 0x001f1b1e, 0x00737477, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a7a09a, 0x00757069, 0x00434343, 0x000c0e12, 0x00000008, 0x00010006, 0x00060000, 0x00080000, 0x00000100, 0x00000100, 0x00080000, 0x001d0000, 0x00541b07, 0x0088401a, 0x00a05421, 0x00a9581c, 0x00b45a17, 0x00ba5c15, 0x00bb5c14, 0x00bc5914, 0x00bf5718, 0x00c05819, 0x00bd5b1b, 0x00bc5c1b, 0x00b85b1c, 0x00b7581d, 0x00b75820, 0x00b15520, 0x00a7501a, 0x009a4b17, 0x00884410, 0x0078390c, 0x006f2d07, 0x00612505, 0x00461800, 0x00380800, 0x004a1000, 0x00642405, 0x007b3810, 0x00924818, 0x00a9521c, 0x00b45017, 0x00ba4d0f, 0x00c0500e, 0x00c0510f, 0x00b0521a, 0x00864825, 0x0057240c, 0x00501600, 0x00994d20, 0x00c35812, 0x00cc590e, 0x00b45312, 0x00874318, 0x001b0000, 0x00040002, 0x00020003, 0x00060000, 0x00150000, 0x00582e0e, 0x009c511a, 0x00b35515, 0x00b65014, 0x00c05418, 0x00bc4a0d, 0x00c04e0c, 0x00c2530a, 0x00b75008, 0x00af5615, 0x009a5828, 0x00391600, 0x000b0000, 0x00000400, 0x00000300, 0x00080000, 0x00250600, 0x00783c14, 0x00a85520, 0x00b3561c, 0x00b65212, 0x00bc5410, 0x00b9530d, 0x00b85316, 0x00984b1f, 0x003c1801, 0x000a0000, 0x00070000, 0x000d0000, 0x002f0c00, 0x00885028, 0x00ab5a20, 0x00a65821, 0x00673514, 0x00240700, 0x000f0000, 0x00321502, 0x00824012, 0x00af5617, 0x00b95410, 0x00bc520e, 0x00b7500d, 0x00b75110, 0x00b95515, 0x00b5500d, 0x00b85209, 0x00ad5412, 0x00803f12, 0x00470d00, 0x006e2800, 0x009c4f26, 0x00a8572d, 0x007d3e1f, 0x002d1307, 0x00040000, 0x00010000, 0x00050000, 0x001b0000, 0x005c2710, 0x00ae5824, 0x00b85310, 0x00b45310, 0x00aa541b, 0x008c4d26, 0x003d0e00, 0x00230000, 0x0055250f, 0x009f5125, 0x00b35218, 0x00b8500d, 0x00b7571a, 0x008c481f, 0x002f0400, 0x00100000, 0x00230100, 0x009f5024, 0x00bc5a22, 0x00b35824, 0x00802d00, 0x00500600, 0x00803512, 0x00a85523, 0x00b15b20, 0x00a9561c, 0x00904514, 0x00632c0b, 0x00340f00, 0x00110000, 0x00040000, 0x00060000, 0x00040100, 0x00000108, 0x00000007, 0x00100504, 0x0027140e, 0x00180500, 0x00140000, 0x003c1600, 0x00743c17, 0x00a5541a, 0x00b45814, 0x00b05414, 0x00a2531c, 0x006e3410, 0x002e0500, 0x001c0000, 0x003a1400, 0x0097542b, 0x00ad541c, 0x00ba5415, 0x00c1520e, 0x00c45108, 0x00c3520a, 0x00bc5414, 0x00b85412, 0x00c05509, 0x00b85004, 0x00b95b13, 0x009d4f13, 0x00581f00, 0x004d1300, 0x00ab561b, 0x00b85813, 0x00bb5a18, 0x00b9550c, 0x00c45a04, 0x00bd5701, 0x00b25b12, 0x00a05a23, 0x00532306, 0x00240000, 0x00260100, 0x00582804, 0x00a55b1d, 0x00b85c0f, 0x00c05e09, 0x00c15c04, 0x00c56005, 0x00c45c01, 0x00c55d02, 0x00c65e04, 0x00c55807, 0x00c4580c, 0x00bb540f, 0x008c3d0b, 0x00320d00, 0x000b0000, 0x00151012, 0x00666768, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9c9c, 0x006e6f70, 0x00404044, 0x001a191d, 0x00010002, 0x00000000, 0x00000000, 0x00000100, 0x00040000, 0x000b0000, 0x00210400, 0x003b1601, 0x0050250a, 0x005c2d0c, 0x006c3510, 0x00763911, 0x007d3c10, 0x00844014, 0x00894117, 0x00874117, 0x0084431d, 0x0082441f, 0x00803f1b, 0x00773817, 0x006c3216, 0x00612c13, 0x0054250d, 0x00472008, 0x00361601, 0x00280c00, 0x00200200, 0x001a0000, 0x00160000, 0x00210000, 0x00682c0c, 0x009f4f20, 0x00b75a20, 0x00b75617, 0x00b25214, 0x00b35010, 0x00bc4d09, 0x00c04f0c, 0x00c04f12, 0x00a6491a, 0x006c341f, 0x00390c00, 0x00531700, 0x00a75826, 0x00bc5b16, 0x00bd570e, 0x00af5418, 0x006c2a02, 0x00160000, 0x00030000, 0x00030004, 0x000c0000, 0x00381300, 0x007c3c12, 0x00ae541b, 0x00bb5413, 0x00b95210, 0x00b95010, 0x00bc5214, 0x00ba5012, 0x00b8500c, 0x00b75614, 0x00a95319, 0x008d4d26, 0x00200100, 0x00070000, 0x00000100, 0x00000100, 0x000c0000, 0x00441f02, 0x008f4717, 0x00b0551b, 0x00b25415, 0x00b65210, 0x00bc500f, 0x00bb5013, 0x00b24f1c, 0x00984f29, 0x00311000, 0x000a0000, 0x00050002, 0x000c0000, 0x00482004, 0x008c4c1c, 0x00ac561c, 0x00ab5824, 0x00602d11, 0x001d0000, 0x000f0000, 0x00381800, 0x00904817, 0x00b35316, 0x00b64c11, 0x00bd5315, 0x00b54f09, 0x00b8550f, 0x00b65516, 0x00b15012, 0x00b4500f, 0x00ad561f, 0x005a2100, 0x003f0900, 0x007f3202, 0x00a55220, 0x00a3582e, 0x007b4326, 0x002c1204, 0x00060000, 0x00000000, 0x00060000, 0x001b0000, 0x006e371e, 0x00ac5422, 0x00b95211, 0x00b85412, 0x00a95318, 0x008c4c22, 0x00401000, 0x00200000, 0x0050200c, 0x00984a20, 0x00b3541b, 0x00b65210, 0x00b0561b, 0x00884922, 0x002c0300, 0x00160000, 0x002e0900, 0x00a45526, 0x00bb591d, 0x00b4561c, 0x00933e0c, 0x004a0600, 0x0074310e, 0x00ac5420, 0x00b45214, 0x00b85517, 0x00b25418, 0x00a34c19, 0x007d3a14, 0x00481c06, 0x001c0200, 0x00100000, 0x000d0000, 0x00020108, 0x00000003, 0x00190400, 0x00593c2c, 0x004c2e1d, 0x002c0b00, 0x001c0000, 0x00481a02, 0x008c4416, 0x00ac5217, 0x00b85817, 0x00b05214, 0x009f4f1d, 0x00662b07, 0x00200000, 0x00210000, 0x00682e10, 0x00a5562a, 0x00b6541a, 0x00c05410, 0x00c4550c, 0x00ba4e04, 0x00ba5512, 0x00b95512, 0x00be5409, 0x00c4590d, 0x00b85209, 0x00b15514, 0x00974715, 0x006e2000, 0x00913800, 0x00b85919, 0x00b65714, 0x00bc5911, 0x00c05306, 0x00bd530a, 0x00b95e24, 0x00803c10, 0x00351100, 0x00140000, 0x003c1400, 0x007f441c, 0x00ab5c17, 0x00b75b06, 0x00c2600b, 0x00c05a04, 0x00c75c08, 0x00c45b04, 0x00c55d05, 0x00c35b03, 0x00c55905, 0x00c4590d, 0x00b95410, 0x008f4211, 0x00381300, 0x00080000, 0x000b0808, 0x005a5c5b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009e9e9e, 0x00727473, 0x0048494b, 0x002a2d2e, 0x000f1010, 0x00030301, 0x00030000, 0x00050000, 0x00080000, 0x000c0000, 0x00130000, 0x00180100, 0x001f0300, 0x00250400, 0x002c0800, 0x00350e00, 0x003d1300, 0x003e1500, 0x00391400, 0x00371200, 0x00340c00, 0x002a0400, 0x00200100, 0x001a0000, 0x00140000, 0x00100000, 0x00090000, 0x00080100, 0x00080000, 0x00080000, 0x000b0000, 0x00290c00, 0x0084441b, 0x00b0571d, 0x00be5410, 0x00c1530c, 0x00b54d07, 0x00bc5512, 0x00bd520e, 0x00b54b0d, 0x00b14b17, 0x008b3713, 0x00441206, 0x00320500, 0x005e1c00, 0x00ae5c23, 0x00bb5b15, 0x00ba5a14, 0x00a7541f, 0x004b1200, 0x00110000, 0x00030000, 0x00040000, 0x00130000, 0x00592807, 0x00964b19, 0x00b35115, 0x00bb4f0d, 0x00bb5310, 0x00b7500d, 0x00b85014, 0x00b65014, 0x00b4500f, 0x00b25415, 0x00a4501c, 0x00753718, 0x00180000, 0x00070006, 0x00030300, 0x00040000, 0x00180400, 0x005f3010, 0x00a1501c, 0x00b45414, 0x00b35412, 0x00b45310, 0x00bc4f0f, 0x00bc5014, 0x00b24f1f, 0x00974e2a, 0x00301000, 0x00090000, 0x00050004, 0x000e0000, 0x00592b0b, 0x0096501d, 0x00b0541a, 0x00a85323, 0x005a2710, 0x001b0000, 0x00100000, 0x003e1c00, 0x00974c1a, 0x00b45116, 0x00b74c15, 0x00bc5117, 0x00b65008, 0x00b7540c, 0x00b35414, 0x00af5015, 0x00b1541c, 0x00984819, 0x00461300, 0x00410e00, 0x008c3a05, 0x00b0581f, 0x00a4582c, 0x00794223, 0x00301203, 0x00080000, 0x00020000, 0x00080000, 0x001f0000, 0x007a4025, 0x00ac5220, 0x00b85010, 0x00b85412, 0x00ac551b, 0x008c4c23, 0x003e0f00, 0x001e0000, 0x004e1e0b, 0x00964820, 0x00b2541c, 0x00b45212, 0x00ad571c, 0x00844a21, 0x002c0400, 0x00180000, 0x00381000, 0x00a85623, 0x00bc5817, 0x00b85618, 0x0098410e, 0x00480900, 0x006d2f10, 0x00a8501c, 0x00b75112, 0x00bb4f0d, 0x00bd520e, 0x00bc5313, 0x00ac511b, 0x00884724, 0x00602f18, 0x00380f00, 0x00180000, 0x00070000, 0x00070000, 0x001a0300, 0x00573320, 0x00764d36, 0x005f341d, 0x00310c00, 0x002d0200, 0x00612400, 0x009f5020, 0x00af5114, 0x00b85618, 0x00a84e16, 0x0092491f, 0x004f1e08, 0x001f0000, 0x00370700, 0x00854722, 0x00a34c16, 0x00b85410, 0x00bd520b, 0x00c0540c, 0x00bf5814, 0x00b8510e, 0x00be510b, 0x00bc5008, 0x00c25711, 0x00bb5514, 0x00ac4d14, 0x009c3e06, 0x00973600, 0x00b45414, 0x00b85814, 0x00b9550d, 0x00c0540b, 0x00bc5412, 0x00b05926, 0x00642601, 0x00200000, 0x00210600, 0x005a2808, 0x009b5824, 0x00af5b12, 0x00bf610c, 0x00bc5906, 0x00be5806, 0x00c55e0d, 0x00c45a0a, 0x00c45d08, 0x00c45b04, 0x00c65a06, 0x00c45a0c, 0x00bb5612, 0x00934615, 0x003b1604, 0x00090000, 0x00070404, 0x00525453, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b4b2, 0x008c8c8b, 0x0060605f, 0x0041403f, 0x002b2a28, 0x001c1c1a, 0x00100c0c, 0x00020000, 0x00040000, 0x00050000, 0x00060000, 0x000a0000, 0x000c0000, 0x000c0000, 0x000b0000, 0x000c0000, 0x000c0000, 0x000d0000, 0x00120000, 0x00120000, 0x000c0000, 0x00080000, 0x00080000, 0x00050000, 0x00020000, 0x00040400, 0x000e0c08, 0x000f0806, 0x000a0000, 0x00290900, 0x00924d1c, 0x00b75919, 0x00c05510, 0x00c04f05, 0x00c65407, 0x00bd4d07, 0x00b85216, 0x00ac501f, 0x0082310c, 0x0064240c, 0x00401308, 0x003a0c00, 0x006a2100, 0x00b65c1f, 0x00bb570f, 0x00b65917, 0x00985328, 0x002c0000, 0x000d0000, 0x00040000, 0x00080000, 0x00200600, 0x0078411d, 0x00a55723, 0x00b35014, 0x00ba4e0c, 0x00bc5410, 0x00b64f0c, 0x00b85014, 0x00b85014, 0x00b65212, 0x00b05418, 0x00a15121, 0x00581d01, 0x00120000, 0x00040003, 0x00030000, 0x00090000, 0x002d1100, 0x00794420, 0x00ab5420, 0x00b55013, 0x00b35211, 0x00b6520f, 0x00bb4f0d, 0x00bc4f12, 0x00b34f1c, 0x00984c27, 0x002d0d00, 0x00080000, 0x00080000, 0x00120000, 0x006d3b18, 0x009f5523, 0x00af541b, 0x00a14f20, 0x0050200b, 0x00160000, 0x00120000, 0x00442005, 0x009d5221, 0x00b45218, 0x00b84f18, 0x00b95014, 0x00b8510c, 0x00b5520a, 0x00b25313, 0x00ad531b, 0x00ac5828, 0x0078340e, 0x00330400, 0x004d1a00, 0x0096440f, 0x00b4551a, 0x00ac5725, 0x00803f1b, 0x00341300, 0x000b0000, 0x00050000, 0x000a0000, 0x00250100, 0x008a4c2f, 0x00ac501e, 0x00b84f0f, 0x00b85211, 0x00ac561c, 0x00854821, 0x003a1000, 0x001b0000, 0x004b1c0b, 0x0095481d, 0x00b25118, 0x00b45111, 0x00ac561c, 0x00844821, 0x002c0400, 0x001b0000, 0x00481c03, 0x00ae551c, 0x00c25710, 0x00bc5817, 0x009b4814, 0x00450d00, 0x00632c10, 0x009f4c1d, 0x00b45214, 0x00bd500c, 0x00c35008, 0x00c45108, 0x00bd5413, 0x00ae5b28, 0x0098542c, 0x00753816, 0x004c1d05, 0x00180000, 0x00100000, 0x00100000, 0x003c1c0c, 0x007b482e, 0x008e5434, 0x00652f11, 0x00370400, 0x00380500, 0x00743818, 0x00a6521e, 0x00b4551c, 0x00af541e, 0x00ab5b2b, 0x00874420, 0x00400c00, 0x00250000, 0x00401400, 0x00955220, 0x00a85010, 0x00bf5714, 0x00bd4e0a, 0x00b84b06, 0x00c0540f, 0x00c05310, 0x00bc4e0d, 0x00c25414, 0x00bf5214, 0x00b8500d, 0x00bb5613, 0x00a64404, 0x00b75414, 0x00bb5811, 0x00b9530a, 0x00c1560f, 0x00b75818, 0x00975020, 0x00441200, 0x001c0000, 0x003f1701, 0x00814817, 0x00ac6121, 0x00b85d17, 0x00bd5b10, 0x00bc5909, 0x00bc5808, 0x00bb580e, 0x00be5a10, 0x00c15c0b, 0x00c45c07, 0x00c65a06, 0x00c4580b, 0x00bd5711, 0x00994918, 0x00411907, 0x000c0000, 0x00040000, 0x004a4c4b, 0x0020201f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9c9b, 0x008c8c8c, 0x0068686a, 0x004f5053, 0x003c3c40, 0x00303034, 0x00242428, 0x0017181c, 0x000f1014, 0x00090a0e, 0x00040509, 0x00030207, 0x00040304, 0x00050300, 0x00060300, 0x000b0400, 0x000f0901, 0x00110f0b, 0x00171612, 0x0024221c, 0x002e2e28, 0x00393b37, 0x00444845, 0x00474745, 0x002c2825, 0x000d0100, 0x002a0500, 0x00a45521, 0x00c05b15, 0x00c2550f, 0x00be4d04, 0x00c45104, 0x00b84c08, 0x00ae5320, 0x008d401a, 0x005c1a00, 0x00602814, 0x005e3124, 0x00471400, 0x00702400, 0x00b95c1c, 0x00bc560f, 0x00b45719, 0x00884b28, 0x00210000, 0x000b0000, 0x00080000, 0x000d0000, 0x003b1908, 0x008b4e26, 0x00a8561f, 0x00b45013, 0x00bc5010, 0x00bb5310, 0x00b54e0c, 0x00b85011, 0x00b95114, 0x00b65212, 0x00ae541b, 0x009e5328, 0x003d0b00, 0x00100000, 0x00030001, 0x00040000, 0x00100000, 0x004d270a, 0x008e4e27, 0x00ac521d, 0x00b85214, 0x00b45111, 0x00b6520f, 0x00b84f0c, 0x00ba5010, 0x00b5501a, 0x00984b23, 0x00290c00, 0x00080000, 0x000b0000, 0x001c0000, 0x00804824, 0x00a55724, 0x00ad531b, 0x009b4c1e, 0x00461b08, 0x00130000, 0x00140000, 0x004c250b, 0x00a35827, 0x00b25016, 0x00b65017, 0x00b74f13, 0x00b8520c, 0x00b5500b, 0x00b45111, 0x00ad541d, 0x00a0552c, 0x005a1f01, 0x002a0000, 0x00602c10, 0x00a04c17, 0x00b05012, 0x00b05621, 0x00833c14, 0x00391400, 0x000b0000, 0x00060000, 0x000b0000, 0x002b0200, 0x00965434, 0x00b15320, 0x00b84f10, 0x00b5500f, 0x00ab551d, 0x007b421f, 0x00340f00, 0x00190000, 0x004a1d0b, 0x0096471b, 0x00b15016, 0x00b45210, 0x00ac561c, 0x00844821, 0x002e0500, 0x001c0000, 0x0058280f, 0x00b05518, 0x00c3550a, 0x00be5915, 0x009f4c18, 0x00441000, 0x005d2a0e, 0x0098491a, 0x00b45214, 0x00bf500a, 0x00c45004, 0x00c34d01, 0x00bb4b04, 0x00b35115, 0x00ae5824, 0x00a35323, 0x008e4c24, 0x00522108, 0x00220000, 0x00140000, 0x001c0000, 0x00612f14, 0x00884b28, 0x00975530, 0x00602404, 0x00330600, 0x00441400, 0x008f441b, 0x00ac5320, 0x00b2541d, 0x00b25620, 0x00a34f20, 0x007c3916, 0x002a0100, 0x00240000, 0x00622c06, 0x009a5220, 0x00ae5018, 0x00bb5212, 0x00c3540e, 0x00bf4f09, 0x00bd500d, 0x00c05715, 0x00ba5012, 0x00bc5112, 0x00bb530c, 0x00ba540c, 0x00b85410, 0x00bb5714, 0x00bc550e, 0x00bc560d, 0x00bd5711, 0x00b0591d, 0x00743c10, 0x00330800, 0x00320500, 0x00642f13, 0x00a15b20, 0x00b05c13, 0x00bb5a13, 0x00bb5610, 0x00bb5a11, 0x00ba5c14, 0x00a04400, 0x00bb5c16, 0x00bd5a0c, 0x00c25b08, 0x00c65805, 0x00c45708, 0x00bf5610, 0x009d4c18, 0x00441a07, 0x000c0000, 0x00040000, 0x00454746, 0x00434443, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00aeb0b4, 0x0097999f, 0x0085888d, 0x006d7075, 0x005a5c62, 0x004b4d53, 0x00404248, 0x00383b40, 0x0037393d, 0x00343736, 0x00383935, 0x003f403c, 0x004c4d4b, 0x00595c5d, 0x006d7071, 0x00878785, 0x00989897, 0x00adb0b1, 0x001f2020, 0x009fa0a3, 0x004b4646, 0x000f0000, 0x00340800, 0x00b35a23, 0x00c05009, 0x00c2540c, 0x00bc5009, 0x00b54805, 0x00b7541c, 0x00904420, 0x00581900, 0x005d2206, 0x007e452c, 0x00703d27, 0x00480e00, 0x00742700, 0x00b95e24, 0x00bf5815, 0x00b45a20, 0x00784021, 0x001a0000, 0x000b0000, 0x00090000, 0x00140000, 0x005d331a, 0x00975325, 0x00a95017, 0x00b85315, 0x00bb4f0e, 0x00b7500d, 0x00b44d0b, 0x00b84e10, 0x00b95012, 0x00b45012, 0x00a9521b, 0x0094502b, 0x002a0000, 0x000c0000, 0x00040000, 0x00060000, 0x001a0200, 0x006e3a18, 0x009f5326, 0x00b14f19, 0x00bb5214, 0x00b55110, 0x00b75310, 0x00b8500c, 0x00b95010, 0x00b75018, 0x0097491f, 0x00270800, 0x00090000, 0x000e0000, 0x00300c00, 0x008e4d28, 0x00a75522, 0x00ac521c, 0x0094481d, 0x003d1705, 0x00120000, 0x00180100, 0x00562c10, 0x00a55828, 0x00b05015, 0x00b55017, 0x00b44f11, 0x00b9520f, 0x00b6500a, 0x00b54e0c, 0x00af541c, 0x008f4c28, 0x00420f00, 0x002d0400, 0x006f3b1c, 0x00a7531f, 0x00b25013, 0x00b3541d, 0x00873c12, 0x003b1601, 0x000b0000, 0x00060000, 0x000b0000, 0x00340800, 0x009c5532, 0x00b45421, 0x00b94f11, 0x00b44f0e, 0x00aa5620, 0x006f3c1c, 0x002f0e00, 0x00160000, 0x00491e0b, 0x0097481a, 0x00b15012, 0x00b5510e, 0x00ac561c, 0x00844924, 0x00320700, 0x00200000, 0x00683418, 0x00af5418, 0x00c05509, 0x00c05914, 0x00a14d17, 0x00481000, 0x005f280b, 0x009a4817, 0x00b75313, 0x00bc4d06, 0x00c25004, 0x00c45006, 0x00c05008, 0x00b9500c, 0x00b85213, 0x00b65416, 0x00ae551e, 0x009a4f24, 0x005e2708, 0x00260000, 0x001c0000, 0x00380b00, 0x0073391b, 0x009f572d, 0x008e4922, 0x0054240f, 0x00340800, 0x005c1e00, 0x009f5024, 0x00b55218, 0x00bb5214, 0x00ae4d16, 0x00a8582c, 0x0060290f, 0x002d0100, 0x002c0000, 0x006c341a, 0x00964b20, 0x00b0551b, 0x00bd520e, 0x00c04f07, 0x00ba4f09, 0x00be5714, 0x00b4520e, 0x00b75614, 0x00bb5917, 0x00b1500c, 0x00bb5915, 0x00b8540e, 0x00bc530b, 0x00c05811, 0x00b55711, 0x00a65b23, 0x00512200, 0x00290200, 0x00541f04, 0x008a4820, 0x00b05c19, 0x00b95b0e, 0x00ba530a, 0x00c25b18, 0x00b35618, 0x00a64d14, 0x008c3700, 0x00b85e1b, 0x00ba5a0e, 0x00c15a09, 0x00c55804, 0x00c45506, 0x00c0550e, 0x009f4c18, 0x00461b04, 0x000d0000, 0x00060000, 0x00444547, 0x00787a79, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a2a4aa, 0x003f3b3e, 0x000b0000, 0x00380b00, 0x00bc5b24, 0x00c65209, 0x00c1530c, 0x00b85010, 0x00b5541d, 0x009c481c, 0x00611f04, 0x004f1400, 0x007b3919, 0x009b5a36, 0x00733a18, 0x00480b00, 0x00772b00, 0x00b75e27, 0x00bc5615, 0x00b25820, 0x006f381b, 0x00180000, 0x000a0000, 0x000a0000, 0x00220100, 0x007a4628, 0x00a15624, 0x00ad5014, 0x00bc5417, 0x00b84b0c, 0x00b85010, 0x00b85010, 0x00b94f10, 0x00ba5113, 0x00b44f11, 0x00a5511c, 0x00864a2a, 0x001f0000, 0x00080000, 0x00060300, 0x000c0000, 0x002c0c00, 0x0085451e, 0x00ac5423, 0x00b64f18, 0x00bb4e13, 0x00b5500f, 0x00b75310, 0x00b4500c, 0x00b85110, 0x00b85115, 0x0096481c, 0x00240600, 0x000a0000, 0x00120000, 0x004a1f08, 0x00985028, 0x00a95320, 0x00ac521d, 0x008c441b, 0x00371405, 0x00100000, 0x00240800, 0x00613116, 0x00a85828, 0x00b25016, 0x00b35013, 0x00b55010, 0x00ba520f, 0x00b74f0a, 0x00b8500c, 0x00b05620, 0x00793b1c, 0x00330400, 0x003d1000, 0x007a4020, 0x00a85420, 0x00b45318, 0x00b2531c, 0x00893e14, 0x003b1704, 0x00090000, 0x00040000, 0x000d0000, 0x00401100, 0x00a15530, 0x00b4521e, 0x00b94f13, 0x00b5500f, 0x00ab5a24, 0x00623519, 0x00260c00, 0x00160000, 0x004c210c, 0x009c4c1c, 0x00b35012, 0x00b5500d, 0x00ad541b, 0x00864b25, 0x00370b00, 0x00250000, 0x00784025, 0x00ae5417, 0x00c0550c, 0x00be5915, 0x00a04c16, 0x00491000, 0x0063290b, 0x009f4815, 0x00b95211, 0x00be5008, 0x00bf4e04, 0x00bf4f08, 0x00c1510c, 0x00c0520c, 0x00bd500c, 0x00ba4f0b, 0x00b44f0e, 0x00b3551d, 0x009d5124, 0x0059250d, 0x002a0400, 0x001e0000, 0x0054210b, 0x008c4620, 0x00a35b31, 0x007c452b, 0x004a1903, 0x00400800, 0x007b3410, 0x00b6541c, 0x00bc5010, 0x00bc5417, 0x00af531f, 0x009f552e, 0x005b2007, 0x00290000, 0x002c0000, 0x006a3416, 0x00995023, 0x00ac4f10, 0x00c05811, 0x00bd540e, 0x00b8520b, 0x00b8550f, 0x00b4530c, 0x00bc5714, 0x00b7520f, 0x00b95611, 0x00b9530d, 0x00be510c, 0x00bd5613, 0x00ac5717, 0x0094521d, 0x003d1100, 0x00330800, 0x0074360f, 0x00a75822, 0x00b45814, 0x00c05a10, 0x00bf580f, 0x00b95717, 0x00a5501f, 0x007a2a00, 0x00944207, 0x00b45c1a, 0x00ba5b11, 0x00c05a0b, 0x00c75807, 0x00c65608, 0x00c1560f, 0x00a04c17, 0x00461a02, 0x000f0000, 0x00050000, 0x00444547, 0x009b9fa0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00989ba4, 0x0037343a, 0x00100101, 0x003d1000, 0x00b95720, 0x00cc5610, 0x00be5412, 0x00ad5018, 0x00a2522b, 0x00672206, 0x004a0c00, 0x00753519, 0x009b4b1c, 0x00aa5825, 0x007b380d, 0x00501000, 0x00742c02, 0x00b05b29, 0x00bc5415, 0x00b1541c, 0x006d3617, 0x00180000, 0x000c0000, 0x000d0000, 0x003b1300, 0x008c4e29, 0x00a8561f, 0x00b25112, 0x00bb5214, 0x00b84c0d, 0x00b85010, 0x00ba5312, 0x00bb4e10, 0x00bb5013, 0x00b25011, 0x00a45320, 0x00784127, 0x00180000, 0x00050000, 0x00040100, 0x00100000, 0x004b2307, 0x0094491e, 0x00b3511d, 0x00b94d17, 0x00b84b11, 0x00b55010, 0x00b55411, 0x00b34f0d, 0x00b55110, 0x00b85214, 0x0094471b, 0x00200400, 0x00090000, 0x00180000, 0x00673418, 0x00a05228, 0x00ac5120, 0x00ac5320, 0x00844018, 0x00301304, 0x00100000, 0x002f0e00, 0x006e381a, 0x00aa5525, 0x00b45114, 0x00b45010, 0x00b8510f, 0x00ba500e, 0x00b84f0b, 0x00b8510f, 0x00ac5520, 0x005e2307, 0x002b0000, 0x00582408, 0x00894823, 0x00a85420, 0x00b0521a, 0x00af531f, 0x0088411b, 0x0038190a, 0x00080000, 0x00030000, 0x00110000, 0x00501c03, 0x00a4562d, 0x00b3501c, 0x00b94e14, 0x00b65011, 0x00a85824, 0x00542b12, 0x001c0600, 0x00180000, 0x00552911, 0x00a2501f, 0x00b65212, 0x00b4500c, 0x00ac541a, 0x008b4c28, 0x003f0e00, 0x002e0000, 0x00884a2d, 0x00ae531a, 0x00be5812, 0x00bb5818, 0x009c4a15, 0x00480e00, 0x00672b0b, 0x00a44a15, 0x00ba500f, 0x00c0500b, 0x00be4e08, 0x00b84c0c, 0x00b84e0c, 0x00bc4f0c, 0x00bf500d, 0x00bd500d, 0x00bc500e, 0x00b54c0b, 0x00b2571e, 0x0098512b, 0x004c1700, 0x002b0500, 0x00270000, 0x006c3314, 0x00924f29, 0x00985530, 0x00783918, 0x004c1800, 0x00501400, 0x009c4411, 0x00b44f11, 0x00c05819, 0x00b34b0e, 0x00b04d12, 0x00a15121, 0x004f1c04, 0x00240100, 0x002a0800, 0x0067381c, 0x009c5221, 0x00ae5414, 0x00bc5810, 0x00ba5005, 0x00bf5309, 0x00bd4f06, 0x00bf4e06, 0x00c1510c, 0x00bc5010, 0x00be5113, 0x00c0500e, 0x00b95414, 0x00a7581e, 0x00783b0c, 0x003f0d00, 0x00582300, 0x00964c17, 0x00b35a19, 0x00ba5512, 0x00be5613, 0x00be5b16, 0x00a84f12, 0x00843910, 0x005d1500, 0x00a6551c, 0x00b35b15, 0x00ba5b13, 0x00c0580d, 0x00c65706, 0x00c85606, 0x00c0550e, 0x009c4814, 0x00441700, 0x000f0000, 0x00060000, 0x0048494c, 0x00787b7c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00999fa5, 0x002f3034, 0x000c0000, 0x00401400, 0x00b5571f, 0x00c8540f, 0x00bc5414, 0x00a8501c, 0x00783013, 0x00460600, 0x005e1c04, 0x009a4e2b, 0x00b2541c, 0x00ae5417, 0x0080390b, 0x00501300, 0x006c2600, 0x00b05c2c, 0x00c05818, 0x00b25117, 0x00703516, 0x00180000, 0x000c0000, 0x00110000, 0x0053240a, 0x00944e23, 0x00ad5418, 0x00b44f0e, 0x00b94f11, 0x00bc5013, 0x00b54e0d, 0x00b95211, 0x00b84b0c, 0x00b84e10, 0x00b04e10, 0x00a25222, 0x006c3b24, 0x00130000, 0x00060200, 0x00030000, 0x00140000, 0x006b391a, 0x00a14d1f, 0x00b84f18, 0x00bc4c17, 0x00ba4c14, 0x00b44f11, 0x00b55314, 0x00b0500f, 0x00b35010, 0x00b55315, 0x0092461b, 0x001f0200, 0x000a0000, 0x001c0000, 0x007b4220, 0x00a75327, 0x00b05120, 0x00ac5423, 0x007e3c17, 0x002c1102, 0x000f0000, 0x00381200, 0x00783a18, 0x00ad5421, 0x00b75114, 0x00b44f0e, 0x00b9520f, 0x00b8500d, 0x00b7500f, 0x00b05015, 0x009e4f20, 0x00450e00, 0x00270000, 0x00713515, 0x009b5226, 0x00ae5723, 0x00b0521b, 0x00ae5321, 0x0088431f, 0x0036180a, 0x00070000, 0x00030000, 0x00140200, 0x005c2508, 0x00a7562b, 0x00b3501c, 0x00b95016, 0x00b45012, 0x00a25524, 0x0048230e, 0x00140100, 0x001a0000, 0x00613018, 0x00a65320, 0x00b85211, 0x00b54e0b, 0x00ac5318, 0x008e4c26, 0x00451000, 0x00360000, 0x0094502f, 0x00b05217, 0x00bf5813, 0x00b9591b, 0x00984816, 0x00470c00, 0x006a2c0c, 0x00a54c18, 0x00b94f10, 0x00bd4c08, 0x00c0500c, 0x00bc5214, 0x00b95012, 0x00bb4d0d, 0x00bd4e0d, 0x00be5010, 0x00be5210, 0x00c05310, 0x00b55010, 0x00ab5421, 0x00904d28, 0x00431500, 0x001c0000, 0x00411100, 0x00753c1c, 0x009f552c, 0x009d552c, 0x00682e12, 0x003e0400, 0x00702400, 0x00ab511e, 0x00b55015, 0x00bc5210, 0x00c05511, 0x00aa4d11, 0x0092542f, 0x004d220c, 0x00210000, 0x002a0200, 0x00642b08, 0x00944c1c, 0x00a65318, 0x00b45414, 0x00bb5310, 0x00c4550f, 0x00bd4c03, 0x00c05108, 0x00bb5110, 0x00b95012, 0x00c05010, 0x00b85318, 0x00a45928, 0x00602400, 0x004b1000, 0x00814013, 0x00b05e1c, 0x00b5560e, 0x00bc5414, 0x00b85416, 0x00ad5418, 0x009c501c, 0x00591700, 0x005f1d00, 0x00ac5c20, 0x00b55c15, 0x00b95a12, 0x00bf580c, 0x00c75505, 0x00c75507, 0x00bd540e, 0x00984712, 0x00411500, 0x000e0000, 0x00080000, 0x004c4d50, 0x00545758, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00969ea0, 0x00303535, 0x00080300, 0x00371300, 0x00b15820, 0x00c65913, 0x00ba5616, 0x0099410f, 0x00470000, 0x00581300, 0x0092411e, 0x00ae5323, 0x00b34d0e, 0x00b35414, 0x00813c0f, 0x004f1400, 0x00662000, 0x00b05928, 0x00c55614, 0x00b65114, 0x00743818, 0x001a0000, 0x000c0000, 0x00100000, 0x00713b1d, 0x00994c1c, 0x00b05213, 0x00b74f0c, 0x00b74c0f, 0x00b94f13, 0x00b74f10, 0x00b85010, 0x00bc4f12, 0x00b84d10, 0x00b14f11, 0x00a05122, 0x00603420, 0x00100000, 0x00030000, 0x00060000, 0x001c0000, 0x007c4422, 0x00b05423, 0x00b94c14, 0x00bb4c16, 0x00b94e15, 0x00b45014, 0x00b25013, 0x00b05012, 0x00b05012, 0x00b15016, 0x008f461c, 0x001d0000, 0x000e0000, 0x002b0400, 0x008d4c27, 0x00ab5225, 0x00b04e1e, 0x00aa5324, 0x00783914, 0x00281001, 0x00100000, 0x00431500, 0x008c4520, 0x00ae501b, 0x00b54c0c, 0x00bc5410, 0x00b8510e, 0x00ad4605, 0x00b6551c, 0x00a45424, 0x00793816, 0x00300000, 0x003a0700, 0x008b441c, 0x00a4521d, 0x00ae531b, 0x00ae5019, 0x00ac501f, 0x0089421f, 0x003b1c0e, 0x00090000, 0x00040000, 0x001c0600, 0x00692e0f, 0x00a55124, 0x00b3501c, 0x00b44c12, 0x00b45216, 0x00994d1f, 0x00371502, 0x000e0000, 0x00280800, 0x006a3519, 0x00a95320, 0x00b85010, 0x00b54e0c, 0x00ac5016, 0x00904a22, 0x00501300, 0x00440500, 0x00a0532c, 0x00b75313, 0x00c05710, 0x00b75a20, 0x008d4116, 0x00430c00, 0x00682d11, 0x00a64f20, 0x00b84f13, 0x00bf4d0a, 0x00c14e09, 0x00be5012, 0x00b84e10, 0x00bb4b0c, 0x00bf4f10, 0x00be5114, 0x00b74c0f, 0x00bc500f, 0x00b74e0c, 0x00b35114, 0x00a7531f, 0x0080411f, 0x003e0e00, 0x001e0000, 0x004b1e08, 0x008c471e, 0x00a4582a, 0x00904c27, 0x00632504, 0x00430700, 0x0086401b, 0x00ab501c, 0x00b85214, 0x00b95113, 0x00b04f14, 0x00a95826, 0x0095502b, 0x005e240a, 0x00320000, 0x00280000, 0x00491802, 0x007d4528, 0x0095532b, 0x00ab5723, 0x00b35414, 0x00b85209, 0x00bc560c, 0x00b35610, 0x00b15412, 0x00bc5314, 0x00b3501a, 0x00a0552c, 0x004b0900, 0x007a3202, 0x00a45418, 0x00ae520b, 0x00b9570c, 0x00ba5614, 0x00b0551d, 0x009f562c, 0x00642702, 0x00440a00, 0x007d3e11, 0x00a85819, 0x00b85c15, 0x00bc5b14, 0x00bf560d, 0x00c75404, 0x00c55507, 0x00bc5713, 0x008e4110, 0x003b1200, 0x000d0000, 0x00070000, 0x00505154, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00969d9b, 0x00343834, 0x00070200, 0x00331000, 0x00b05d26, 0x00be5611, 0x00b75313, 0x00903500, 0x005c0e00, 0x00803310, 0x00ac5024, 0x00b55018, 0x00b44a08, 0x00b35314, 0x00823e13, 0x00501400, 0x00631e00, 0x00b05a28, 0x00c45511, 0x00b95414, 0x007c3e1c, 0x001b0000, 0x000d0000, 0x00140000, 0x00793f1e, 0x00a14e1c, 0x00b35213, 0x00b8500c, 0x00b84d11, 0x00ba4f14, 0x00b74f10, 0x00b7500f, 0x00b94f11, 0x00b84e12, 0x00b04f13, 0x009d5022, 0x005c3020, 0x000e0000, 0x00020000, 0x00080000, 0x00310e00, 0x0085441f, 0x00b0511e, 0x00bb4c13, 0x00bc4c15, 0x00b84c16, 0x00b45014, 0x00b25014, 0x00b05014, 0x00ae5014, 0x00ac4f17, 0x008c441c, 0x001d0000, 0x00100000, 0x00441400, 0x00965026, 0x00ae5122, 0x00b14e1e, 0x00a85124, 0x00743614, 0x00270e00, 0x00110000, 0x00501c03, 0x0091441c, 0x00b3511c, 0x00b74e0e, 0x00b14906, 0x00b85310, 0x00b65318, 0x00a6501e, 0x00985734, 0x00441100, 0x002a0000, 0x00562009, 0x00924517, 0x00af541b, 0x00ac4c11, 0x00b35018, 0x00af501d, 0x008c421c, 0x00401c0c, 0x000e0000, 0x00080000, 0x00200500, 0x00743613, 0x00a85023, 0x00b24f1c, 0x00b34d14, 0x00b15016, 0x008e4518, 0x00311000, 0x00100000, 0x00381202, 0x00783c1c, 0x00aa501d, 0x00b74f10, 0x00b7500d, 0x00ae5117, 0x00964b21, 0x00601c00, 0x00581000, 0x00a85427, 0x00bd5411, 0x00c0550e, 0x00b55b24, 0x00833b13, 0x00430c00, 0x006e3317, 0x00a85023, 0x00b74f13, 0x00bf4e0c, 0x00ba4807, 0x00b84c0f, 0x00bd5317, 0x00bf4f11, 0x00ba4a0b, 0x00ba4c0e, 0x00bd5110, 0x00bb4f0d, 0x00b84f0c, 0x00ba5110, 0x00b35419, 0x009a4e20, 0x00632909, 0x00290400, 0x00280300, 0x00642807, 0x009c542a, 0x00a2582a, 0x008c451d, 0x00521800, 0x00470b00, 0x00a25327, 0x00ae541d, 0x00b35115, 0x00b85518, 0x00b8571c, 0x00ac5320, 0x009b4d23, 0x00723010, 0x00400a00, 0x002a0000, 0x002e0000, 0x00511e08, 0x007d3e1c, 0x009a5124, 0x00a8571d, 0x00a95415, 0x00aa5414, 0x00b45919, 0x00b75214, 0x00b4521e, 0x008b3c17, 0x006a2000, 0x0094410a, 0x00b25614, 0x00b8560c, 0x00bc5810, 0x00b25415, 0x00aa5a2a, 0x00793e20, 0x003e0c00, 0x00440d00, 0x00975420, 0x00b45f1f, 0x00b4540c, 0x00bb5610, 0x00c0560d, 0x00c85506, 0x00c55708, 0x00bb5a19, 0x00823b0c, 0x00310c00, 0x000b0000, 0x000d0607, 0x005c5b5f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009d9e98, 0x003e3c33, 0x00060000, 0x002e0c00, 0x00aa5b27, 0x00b95210, 0x00bc5411, 0x00a13c00, 0x008c3000, 0x00a74b1d, 0x00b44f19, 0x00b95014, 0x00b64e10, 0x00ac5018, 0x0088431a, 0x00551800, 0x005c1800, 0x00ab5827, 0x00be5412, 0x00bb5618, 0x00894824, 0x00200000, 0x000e0000, 0x00190000, 0x00834421, 0x00a7501c, 0x00b35010, 0x00b74e0c, 0x00b74d12, 0x00b95014, 0x00b85011, 0x00b54d0f, 0x00b84e12, 0x00b74f13, 0x00b15014, 0x009b4e20, 0x00562c1b, 0x000d0000, 0x00040000, 0x000b0000, 0x0050250a, 0x00914920, 0x00af4d19, 0x00bb4d14, 0x00bb4d15, 0x00b64c14, 0x00b44f16, 0x00b15015, 0x00b05015, 0x00ad5016, 0x00a74d18, 0x0088431d, 0x001f0000, 0x00140000, 0x00642d0e, 0x00a05327, 0x00af4f1e, 0x00b14e1c, 0x00a85024, 0x00703311, 0x00260c00, 0x00140000, 0x00592104, 0x009e4d22, 0x00b2511a, 0x00b85011, 0x00b44f0e, 0x00b04f11, 0x00ab501c, 0x009b512a, 0x00643721, 0x00260100, 0x00260000, 0x0070361c, 0x00a44f1d, 0x00b55315, 0x00b44e10, 0x00b44e12, 0x00b4501a, 0x00914118, 0x00471e08, 0x00130000, 0x000d0000, 0x00240700, 0x0083411c, 0x00aa5020, 0x00b14e1b, 0x00b24e18, 0x00ac4f17, 0x0081390f, 0x002c0b00, 0x00130000, 0x004e200b, 0x00894621, 0x00ac501b, 0x00b74f10, 0x00b65011, 0x00af5017, 0x009a4a1b, 0x00742800, 0x00701e00, 0x00ac501e, 0x00c45410, 0x00c15410, 0x00b45c28, 0x0077300a, 0x00460b00, 0x007a381a, 0x00a95223, 0x00b44e14, 0x00bd5011, 0x00bd5011, 0x00b85016, 0x00b74e14, 0x00bb4c10, 0x00bf4e0e, 0x00c14d0b, 0x00c04d08, 0x00c0500c, 0x00bc500c, 0x00ba5110, 0x00b35114, 0x00ac5521, 0x008c481f, 0x004b1d06, 0x001e0000, 0x00390c00, 0x00783c1a, 0x00a55524, 0x00a75522, 0x007c3b15, 0x00420700, 0x00642404, 0x009d542a, 0x00ad5316, 0x00b8530f, 0x00b64f0c, 0x00b14c0b, 0x00b95a1a, 0x00a64f18, 0x00873c12, 0x00632305, 0x00360100, 0x00270000, 0x00200000, 0x00340800, 0x00531d06, 0x0072300e, 0x00954210, 0x00b1541a, 0x00b45116, 0x00b3541f, 0x007b2400, 0x00903c12, 0x00ac5014, 0x00b85710, 0x00bc560d, 0x00b85612, 0x00ad5820, 0x00904d25, 0x00471a08, 0x00280000, 0x005d2500, 0x00a85e20, 0x00b55c18, 0x00b8550f, 0x00bb540d, 0x00c1550c, 0x00c95607, 0x00c4560b, 0x00b85d1f, 0x00723107, 0x00240500, 0x000b0000, 0x00140f10, 0x0068686c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00aba59d, 0x00494439, 0x00080000, 0x002b0c00, 0x00995225, 0x00bc5b20, 0x00bd5615, 0x00b34a0a, 0x00ae4b13, 0x00b4501b, 0x00b0460b, 0x00b84e12, 0x00b85014, 0x00ab4f1b, 0x00944a23, 0x005f1e00, 0x00531200, 0x009c5021, 0x00b85312, 0x00bb581a, 0x00965128, 0x002b0000, 0x00100000, 0x001d0000, 0x00894724, 0x00ab511c, 0x00b25011, 0x00b54e0d, 0x00b74d14, 0x00b84f15, 0x00b85011, 0x00b44c0d, 0x00b74d12, 0x00b74e14, 0x00b15015, 0x00984c1d, 0x00522615, 0x000e0000, 0x00060000, 0x00100000, 0x006b3718, 0x009c4c1f, 0x00ae4d16, 0x00b94e14, 0x00b84d14, 0x00b64c13, 0x00b44e15, 0x00b14e14, 0x00b04f14, 0x00ad5018, 0x00a44e1b, 0x0084401d, 0x00200000, 0x001c0000, 0x00804320, 0x00a85424, 0x00af4c18, 0x00b24e1b, 0x00a85124, 0x006e3010, 0x00280b00, 0x001a0000, 0x00602404, 0x00a65425, 0x00b1501a, 0x00b34c10, 0x00b45114, 0x00ac5119, 0x009e4f21, 0x00844829, 0x00300a00, 0x001c0000, 0x003d0f00, 0x00864424, 0x00ac531e, 0x00b85011, 0x00b85010, 0x00b44b0f, 0x00b54f16, 0x00964216, 0x004e2008, 0x00140000, 0x000d0000, 0x00270700, 0x00904a22, 0x00ac501e, 0x00b14e1b, 0x00b04f19, 0x00a94f18, 0x00773308, 0x00280700, 0x00180000, 0x00622c10, 0x009a4d24, 0x00af501b, 0x00b74f12, 0x00b65013, 0x00b04f14, 0x00a04c1a, 0x008b3709, 0x008b3002, 0x00b04c17, 0x00c55510, 0x00c15612, 0x00b15e2d, 0x006a2500, 0x004b0c00, 0x00833c18, 0x00ac5220, 0x00b45014, 0x00b2480c, 0x00b84f14, 0x00b4511c, 0x00af4d18, 0x00b44f16, 0x00bd5315, 0x00c1500f, 0x00c04c08, 0x00bf4d08, 0x00bd4e0c, 0x00b85010, 0x00b14f11, 0x00b0531b, 0x00a55627, 0x00723818, 0x00380c00, 0x00230000, 0x004c1c03, 0x008f4314, 0x00a6521d, 0x009b5024, 0x00763513, 0x00340000, 0x00713515, 0x00a95624, 0x00b35213, 0x00b84f0d, 0x00bc4f0a, 0x00bb5008, 0x00b44f0b, 0x00b2571e, 0x009b4c1e, 0x0083401f, 0x00693219, 0x004a1d09, 0x003a0d00, 0x003b0600, 0x00500c00, 0x00812a00, 0x00ad4c14, 0x00b45116, 0x00b3521b, 0x00842800, 0x00a74c1c, 0x00b55415, 0x00b6510c, 0x00b8540e, 0x00b05618, 0x009e5424, 0x00683010, 0x00250100, 0x00300a00, 0x00824412, 0x00ab5a18, 0x00b3540f, 0x00c05912, 0x00be550d, 0x00c4560b, 0x00c85407, 0x00c0550b, 0x00b45e24, 0x00622802, 0x00190000, 0x00080001, 0x001c181c, 0x0078777c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b7afa7, 0x00585047, 0x00080100, 0x00240c00, 0x007a3c1c, 0x00b35e30, 0x00b95820, 0x00b34d10, 0x00b34c10, 0x00b85115, 0x00b44c10, 0x00b44c12, 0x00b34910, 0x00b3511d, 0x00a04f25, 0x006a2400, 0x004c1000, 0x008b451b, 0x00b75617, 0x00bc5b18, 0x00a15527, 0x003d0a00, 0x00120000, 0x00200100, 0x008c4824, 0x00ac511c, 0x00b04f11, 0x00b34d10, 0x00b54c14, 0x00b74e16, 0x00b84e12, 0x00b44b0c, 0x00b74d14, 0x00b44d14, 0x00b25016, 0x00984b1c, 0x00502310, 0x00100000, 0x000c0000, 0x00180000, 0x007e401d, 0x00a34e1c, 0x00af4e17, 0x00b74f13, 0x00b64c11, 0x00b74d12, 0x00b64d14, 0x00b44d13, 0x00b24d12, 0x00af5019, 0x00a34f20, 0x007d3c1a, 0x00230000, 0x00300400, 0x00945028, 0x00ac5320, 0x00b04a14, 0x00b44e1a, 0x00aa5326, 0x006b2c0c, 0x00280800, 0x00210300, 0x00682a07, 0x00a45022, 0x00af511c, 0x00ad4c15, 0x00aa4c15, 0x00aa5828, 0x008c4c29, 0x004f1c05, 0x00200000, 0x00220000, 0x0070351b, 0x009c5028, 0x00a94c14, 0x00b54e0d, 0x00b54c0e, 0x00b64c10, 0x00b64d15, 0x00994417, 0x0055240c, 0x00140000, 0x000d0000, 0x002a0800, 0x00985025, 0x00ae501b, 0x00b14f19, 0x00ad4e19, 0x00a8511c, 0x00712f05, 0x00270500, 0x00230200, 0x00743212, 0x00a65123, 0x00b14f19, 0x00b54c13, 0x00b44d13, 0x00b04f14, 0x00aa5019, 0x00a24813, 0x00a5440e, 0x00b85014, 0x00c4540f, 0x00bf5817, 0x00ac5d30, 0x005d1a00, 0x00571000, 0x008e3e14, 0x00af5019, 0x00b75014, 0x00b75014, 0x009e3c05, 0x008b3000, 0x00944011, 0x00a85021, 0x00ac501c, 0x00b24c10, 0x00be5010, 0x00bc4b08, 0x00bb4c09, 0x00b74f12, 0x00b25016, 0x00b05218, 0x00ae5723, 0x0090481d, 0x005e2708, 0x00210000, 0x002c0500, 0x00692804, 0x009d4e1f, 0x00a55221, 0x00994c24, 0x00541c04, 0x003d0800, 0x00874020, 0x00a85023, 0x00b65116, 0x00c05310, 0x00bc4c08, 0x00ba4d0a, 0x00b75311, 0x00ac5010, 0x00ae581e, 0x00a04f1a, 0x00944417, 0x00904114, 0x00964413, 0x009a4410, 0x00a64710, 0x00b24f15, 0x00b55014, 0x00b04f13, 0x00a0400a, 0x00ad4e18, 0x00b55315, 0x00b55111, 0x00b45515, 0x00a95721, 0x00793e1a, 0x003f1300, 0x00200000, 0x00471c00, 0x009c5520, 0x00af5514, 0x00b85410, 0x00be550f, 0x00c2560e, 0x00c4550b, 0x00c75507, 0x00be570e, 0x00aa5c26, 0x00542200, 0x00100000, 0x00030002, 0x0029282c, 0x008a898d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00bdb6af, 0x00646158, 0x00000000, 0x00110300, 0x00471805, 0x00843e1e, 0x00af5b2c, 0x00b2541c, 0x00b24f14, 0x00b44f11, 0x00b65014, 0x00b64d14, 0x00b54810, 0x00b64f1b, 0x00a74e22, 0x00752c08, 0x004a1000, 0x00783810, 0x00ba5b19, 0x00bf5a14, 0x00a95722, 0x00561c00, 0x00170000, 0x00200100, 0x008c4622, 0x00ab501c, 0x00b05015, 0x00b34e11, 0x00b44c16, 0x00b64d17, 0x00b74d11, 0x00b44a0e, 0x00b74e16, 0x00b24c15, 0x00b05015, 0x009a4b1d, 0x004f200d, 0x00130000, 0x00100000, 0x00270400, 0x008c4720, 0x00a84e19, 0x00b05017, 0x00b34e13, 0x00b44c10, 0x00b64c10, 0x00b54c10, 0x00b64d14, 0x00b44b11, 0x00b04f19, 0x00a04f22, 0x00773515, 0x00280000, 0x004d1c06, 0x009f5428, 0x00af511a, 0x00b34a12, 0x00b44e1a, 0x00aa5326, 0x00672507, 0x00250400, 0x00280700, 0x0070320d, 0x00a55221, 0x00aa4f1c, 0x00ac501e, 0x00ac5424, 0x00964b22, 0x005a250c, 0x00220000, 0x00300300, 0x005b2409, 0x00984f29, 0x00a7501f, 0x00ae4d13, 0x00b24c0d, 0x00b55012, 0x00b34c12, 0x00b34c15, 0x009b471b, 0x00592a12, 0x00130000, 0x000c0000, 0x00301000, 0x009e5227, 0x00b05018, 0x00b04e18, 0x00ac4e18, 0x00a85420, 0x006c2b03, 0x00290500, 0x00340f00, 0x00823915, 0x00ac501f, 0x00b24e19, 0x00b44d14, 0x00b14c13, 0x00b04e14, 0x00ae5018, 0x00ae4d14, 0x00b34c12, 0x00bc500f, 0x00c4540d, 0x00bd5818, 0x00a0552a, 0x00511000, 0x00641c00, 0x00964414, 0x00b04f16, 0x00b85214, 0x00b14c10, 0x00ac4e17, 0x00883406, 0x00621500, 0x00671e00, 0x00893e15, 0x00a14e1d, 0x00ac4c16, 0x00b94f13, 0x00bc4f10, 0x00b64e12, 0x00b45014, 0x00b45013, 0x00b35219, 0x00a34e1c, 0x00803f19, 0x003b1203, 0x001a0000, 0x003e0b00, 0x007a3814, 0x00a95527, 0x00a04c20, 0x0086482b, 0x00410a00, 0x00460800, 0x00873d1c, 0x00a9511f, 0x00b45214, 0x00b94c0e, 0x00bd500f, 0x00b74d09, 0x00bc5510, 0x00b34f0c, 0x00b45212, 0x00b45318, 0x00b45318, 0x00b65417, 0x00b55314, 0x00b65014, 0x00b85315, 0x00b7500f, 0x00b24e0c, 0x00b75518, 0x00b04f13, 0x00b65116, 0x00b8561c, 0x00b0551d, 0x00974e20, 0x00522308, 0x00200000, 0x002a0400, 0x0064310c, 0x00ab5c26, 0x00b15212, 0x00bc5411, 0x00bf520c, 0x00c3540b, 0x00c45408, 0x00c85608, 0x00bd5813, 0x009b511f, 0x00461900, 0x000b0000, 0x00000004, 0x003a393e, 0x009d9ea1, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00585854, 0x00747b72, 0x00000404, 0x00000000, 0x001c0100, 0x00451400, 0x007f3d1d, 0x009c4d20, 0x00ad521a, 0x00b04d10, 0x00b34c12, 0x00b84e13, 0x00bd4c10, 0x00b74913, 0x00ad4e21, 0x0080340f, 0x00491300, 0x00662800, 0x00bd5a14, 0x00c2570b, 0x00b0581f, 0x00753814, 0x001a0000, 0x001e0000, 0x0088421e, 0x00a84d1b, 0x00af5017, 0x00b14e14, 0x00b24c17, 0x00b54c16, 0x00b64c10, 0x00b34b0e, 0x00b64f18, 0x00af4b15, 0x00b05017, 0x009c4c1d, 0x0050200c, 0x00170000, 0x00130000, 0x003c1304, 0x00964b21, 0x00ab4d15, 0x00af5017, 0x00af4d11, 0x00b54d10, 0x00b54c0e, 0x00b44b10, 0x00b94e14, 0x00b4490f, 0x00b04d18, 0x009c4c23, 0x006c2d0e, 0x002f0000, 0x006f381f, 0x00a35324, 0x00b04f16, 0x00b44b11, 0x00b44e18, 0x00a95024, 0x00612001, 0x00230000, 0x002f0c00, 0x00783812, 0x00a65424, 0x00a74f1e, 0x00a64e1f, 0x009b481d, 0x00682403, 0x002e0200, 0x002c0600, 0x00602608, 0x009a5127, 0x00aa4f1c, 0x00af4c12, 0x00b45116, 0x00b04c11, 0x00b45318, 0x00af4c16, 0x00af4c18, 0x00994921, 0x005a2d19, 0x00100000, 0x000d0000, 0x003a1c08, 0x00a05324, 0x00b15015, 0x00b04f18, 0x00a94d19, 0x00a85422, 0x00662600, 0x002a0500, 0x004b2110, 0x0090421b, 0x00b14e1b, 0x00b44d18, 0x00b44d17, 0x00b14c14, 0x00b04c13, 0x00b04d14, 0x00b04c0f, 0x00b74c0d, 0x00bd4d09, 0x00c6540a, 0x00bb5715, 0x00904921, 0x00440800, 0x006f2802, 0x009d4b1c, 0x00b05017, 0x00b65011, 0x00b45012, 0x00b0531b, 0x00984818, 0x00742f09, 0x004e1400, 0x003d0800, 0x005f2404, 0x0098502a, 0x00a84c1a, 0x00ba5119, 0x00b74d12, 0x00b64c0e, 0x00bb4d0c, 0x00b74e0e, 0x00b0521b, 0x009b5027, 0x0064301b, 0x00240000, 0x001d0000, 0x00441504, 0x00914824, 0x00a45024, 0x009f5029, 0x00773312, 0x00300000, 0x00531e04, 0x0087441f, 0x00a65424, 0x00b35219, 0x00b74f10, 0x00b44b09, 0x00bb4f0e, 0x00b64c0e, 0x00b95114, 0x00b75217, 0x00b24f15, 0x00b44f14, 0x00b44e12, 0x00b84f0f, 0x00bb510d, 0x00ba4f08, 0x00b75009, 0x00b65611, 0x00b25313, 0x00b45015, 0x00b55621, 0x00a04c1d, 0x0070310c, 0x00300d00, 0x00180000, 0x00441800, 0x0086481c, 0x00af5b26, 0x00b45114, 0x00bb510f, 0x00c1530c, 0x00c35208, 0x00c55508, 0x00c85708, 0x00ba5814, 0x00853e0e, 0x00360e00, 0x00090000, 0x00000209, 0x004e4e54, 0x00b0b1b5, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00889088, 0x00000b0b, 0x00010405, 0x00120000, 0x00220000, 0x00400c00, 0x0071300e, 0x00984c20, 0x00aa531f, 0x00b04d15, 0x00b4490f, 0x00bf4d12, 0x00b74911, 0x00b05020, 0x00883912, 0x004b1300, 0x00591c00, 0x00b85918, 0x00bc5409, 0x00b8581c, 0x00924a22, 0x001f0000, 0x001e0000, 0x00823f1a, 0x00a44c18, 0x00ad5018, 0x00b04d15, 0x00b14a15, 0x00b44b14, 0x00b54c10, 0x00b34b0e, 0x00b45119, 0x00ad4b14, 0x00b05017, 0x009d4c20, 0x0051200c, 0x00190000, 0x00170000, 0x004c1f0b, 0x009d4e22, 0x00ac4c13, 0x00b04f16, 0x00ae4c10, 0x00b74f10, 0x00b44c0c, 0x00b34b0e, 0x00b85014, 0x00b44a10, 0x00ac4c1a, 0x00974a22, 0x00672808, 0x00350000, 0x008b4929, 0x00a54f1d, 0x00b04c11, 0x00b44b0f, 0x00b14d18, 0x00a55028, 0x005c1c02, 0x00230000, 0x00341001, 0x00783c18, 0x009d5227, 0x00a2552c, 0x00924823, 0x00672302, 0x003c0200, 0x00330600, 0x005c2c15, 0x0098502c, 0x00a54d1c, 0x00af4910, 0x00b85013, 0x00b04c10, 0x00b04e14, 0x00ad4b13, 0x00b04e18, 0x00ac4c1a, 0x00984b22, 0x005c2f19, 0x00130000, 0x00120200, 0x0046230f, 0x00a25325, 0x00b34d14, 0x00b04e18, 0x00a94e1c, 0x00a45526, 0x00602200, 0x002e0300, 0x00602e15, 0x009d491d, 0x00b34d18, 0x00b44a14, 0x00b64d17, 0x00b34c15, 0x00b24c14, 0x00b34c12, 0x00b44c0d, 0x00bd4e0d, 0x00c2500c, 0x00c7540c, 0x00b75617, 0x0083411b, 0x003c0200, 0x00793108, 0x00a54f1c, 0x00b44f14, 0x00b84d0e, 0x00b34d0e, 0x00b15016, 0x00aa5220, 0x009b4e26, 0x006f3215, 0x003c0800, 0x00350400, 0x005b2407, 0x0087401c, 0x00a55124, 0x00ae501b, 0x00b44d11, 0x00bb4f0e, 0x00b74c0d, 0x00b25018, 0x00a55124, 0x00804122, 0x00441805, 0x00180000, 0x00250300, 0x0062280e, 0x00a1552f, 0x00a85425, 0x009e4f21, 0x005a2304, 0x00300000, 0x00551e04, 0x00894725, 0x00a45123, 0x00af5019, 0x00bc5217, 0x00b84a0e, 0x00b94c10, 0x00bb5014, 0x00b95014, 0x00b54f13, 0x00b65015, 0x00b85013, 0x00ba4e0c, 0x00bc4f08, 0x00bc5009, 0x00bb530c, 0x00ad4c07, 0x00b55614, 0x00b05116, 0x00ab5423, 0x0088421e, 0x00471400, 0x00190000, 0x00250500, 0x00662e07, 0x00a15623, 0x00ae551c, 0x00b85616, 0x00ba520f, 0x00bd500a, 0x00c35409, 0x00c6560a, 0x00c8580a, 0x00b55614, 0x00703005, 0x00270500, 0x00080100, 0x00020910, 0x005c5f63, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009a9c97, 0x001c1b17, 0x00070000, 0x00180400, 0x004c2d24, 0x00250000, 0x00380800, 0x005e2b0f, 0x008a4823, 0x00ad511d, 0x00b2480c, 0x00ba5014, 0x00b24c10, 0x00ac4e16, 0x00954516, 0x005e2305, 0x004d1300, 0x009c4a15, 0x00b55616, 0x00c25a1c, 0x00a85424, 0x00340700, 0x00240000, 0x00783410, 0x00a34e1c, 0x00a84e19, 0x00b04e18, 0x00b54c18, 0x00b54913, 0x00b54c10, 0x00b04c0e, 0x00ac4c13, 0x00ad5018, 0x00b05018, 0x009c481c, 0x005a2512, 0x001b0000, 0x00180000, 0x0069391e, 0x009f4c20, 0x00ad4b15, 0x00b3501b, 0x00b04b12, 0x00b74c0f, 0x00b64c0c, 0x00b14f10, 0x00af4f10, 0x00b04d15, 0x00a94f1f, 0x008f4824, 0x00591b00, 0x00541100, 0x009c5025, 0x00a84c17, 0x00b44f11, 0x00b34a08, 0x00b04f18, 0x009e5130, 0x00561d0c, 0x001e0000, 0x003d190a, 0x00794324, 0x00945935, 0x007b4024, 0x00521e08, 0x00350800, 0x00350500, 0x00682c12, 0x00994f2e, 0x00a74d25, 0x00af4c1c, 0x00b24b14, 0x00b24c11, 0x00b04c14, 0x00b04d15, 0x00b34c14, 0x00b24c14, 0x00ad4c15, 0x009f5020, 0x00613114, 0x001a0000, 0x001f0400, 0x00532610, 0x00a75228, 0x00b44c18, 0x00b04915, 0x00ab4e1d, 0x009d552c, 0x005f2400, 0x003e0800, 0x00773814, 0x00aa5020, 0x00b24913, 0x00b84b13, 0x00b84a12, 0x00b44c14, 0x00b34c14, 0x00b44c10, 0x00b74a0d, 0x00c04c0d, 0x00c75210, 0x00c3530f, 0x00bc6025, 0x005c2000, 0x00430d00, 0x00873a0c, 0x00b04f18, 0x00c05014, 0x00bc4a0c, 0x00b84e12, 0x00b24d10, 0x00b84f15, 0x00b04f1b, 0x009d4923, 0x00733010, 0x003d0a00, 0x002c0100, 0x00431908, 0x005f2c12, 0x00944c21, 0x00a7511b, 0x00ad5018, 0x00b5531b, 0x00af4c16, 0x00ad511f, 0x00a05324, 0x00692f0e, 0x00280500, 0x00180000, 0x00340c00, 0x00793e22, 0x00a85420, 0x00aa5118, 0x0090481c, 0x00541900, 0x00330300, 0x0057240e, 0x008c4626, 0x00a75128, 0x00b45120, 0x00b54a11, 0x00ba4d12, 0x00bb4e10, 0x00bb4f0e, 0x00b94f10, 0x00b55014, 0x00b55012, 0x00bb500a, 0x00bc500b, 0x00bc4f10, 0x00b74e10, 0x00b5510e, 0x00b25513, 0x00ac5218, 0x009a4f25, 0x0055250f, 0x00220000, 0x00180000, 0x003f1400, 0x008c4317, 0x00af551a, 0x00af5210, 0x00b65610, 0x00b85411, 0x00ba520d, 0x00c2560e, 0x00c6580f, 0x00c4570c, 0x00b05618, 0x00551e00, 0x001b0200, 0x00000003, 0x00171f27, 0x00797c7f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a8a7a3, 0x003d3630, 0x000b0000, 0x001c0804, 0x00614338, 0x00582b15, 0x00370600, 0x00300400, 0x005a250c, 0x0091441c, 0x00a14814, 0x00ac4e16, 0x00b25117, 0x00b2541a, 0x009f4c19, 0x00692c0a, 0x00470c00, 0x0083380c, 0x00b55b23, 0x00c05714, 0x00b65720, 0x00541e08, 0x00260000, 0x006d2e0c, 0x009b4c1c, 0x00a94e1c, 0x00b14d18, 0x00b44914, 0x00b64b12, 0x00b44c10, 0x00b04e10, 0x00ac4e13, 0x00ae5016, 0x00b04d17, 0x009c481e, 0x005c2817, 0x001c0000, 0x00200000, 0x00744020, 0x00a24c21, 0x00b04c18, 0x00b14f19, 0x00b04b14, 0x00b84c10, 0x00b64c0c, 0x00af4e0f, 0x00ae5114, 0x00ac4c16, 0x00a44d20, 0x008a4625, 0x00501100, 0x006e2400, 0x00a75222, 0x00b04e16, 0x00b64e10, 0x00b24b0a, 0x00a84e18, 0x00944d30, 0x004d1909, 0x00210000, 0x00422012, 0x0070442c, 0x0066371d, 0x00471a08, 0x00320600, 0x00350c00, 0x005f2b11, 0x00964c29, 0x00a74c22, 0x00af4b1c, 0x00b24b17, 0x00b44b13, 0x00b24c11, 0x00b14c14, 0x00b14c13, 0x00b54c12, 0x00b44c12, 0x00ae4c14, 0x00a05020, 0x00673415, 0x00200000, 0x00260400, 0x00602c16, 0x00a65027, 0x00b44a18, 0x00b44a17, 0x00ac4c1e, 0x009d5730, 0x005f2400, 0x00501500, 0x00843c13, 0x00ab4f1c, 0x00b44c14, 0x00b74910, 0x00b54a10, 0x00b24c13, 0x00b14c13, 0x00b44b0f, 0x00b84b0b, 0x00c24f09, 0x00c7540e, 0x00c25614, 0x00aa531d, 0x00481400, 0x004d1b00, 0x0092451c, 0x00b04d18, 0x00ba480d, 0x00c04c0e, 0x00b64c11, 0x00b34c10, 0x00b94c0e, 0x00b64c11, 0x00a94c1d, 0x009d4f28, 0x00753816, 0x00380b00, 0x001a0000, 0x002e0a00, 0x00562000, 0x00874318, 0x00a25021, 0x00a84d1b, 0x00b4521c, 0x00b04e18, 0x00a54c15, 0x008f471c, 0x004d200c, 0x001c0000, 0x001d0000, 0x004a1c08, 0x009b4f20, 0x00a95018, 0x00a95423, 0x00883e15, 0x004c1500, 0x003d0a00, 0x0064270c, 0x00914520, 0x00b05022, 0x00b84f17, 0x00b84e0f, 0x00ba4e0c, 0x00bb4f0e, 0x00b94f10, 0x00b74f13, 0x00b55012, 0x00b8500d, 0x00b9500d, 0x00b84d13, 0x00b95014, 0x00b7520f, 0x00ae5211, 0x00a25621, 0x006e3512, 0x00311003, 0x00170000, 0x00290400, 0x0061280f, 0x009f4b1c, 0x00b55416, 0x00b5540f, 0x00b8550f, 0x00b8530f, 0x00bc5410, 0x00c4560f, 0x00c1550d, 0x00bd5711, 0x009a4913, 0x00401400, 0x000d0000, 0x00000004, 0x0030373e, 0x00919294, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b2b1ad, 0x00615c57, 0x00080000, 0x00180401, 0x00603f30, 0x00915734, 0x006a2904, 0x003b0500, 0x002f0000, 0x00521f08, 0x00804122, 0x00a05024, 0x00ab4f1b, 0x00ac4c14, 0x00a8511d, 0x007d3c17, 0x00480e00, 0x00671e00, 0x00b55d2b, 0x00c05410, 0x00ba5819, 0x007b3f1f, 0x002a0000, 0x00592000, 0x00924820, 0x00ac4e1c, 0x00b54c16, 0x00b14812, 0x00b44d14, 0x00af4c0e, 0x00b04f10, 0x00b14f11, 0x00b04c13, 0x00b14a14, 0x009d481f, 0x005f301d, 0x001a0000, 0x002a0200, 0x00844a2a, 0x00a54e21, 0x00b04c19, 0x00b04c19, 0x00b14c16, 0x00b84b11, 0x00b74a0f, 0x00ae4c0e, 0x00b05116, 0x00ab4c17, 0x00a44d20, 0x0087411f, 0x004b0900, 0x008a3d15, 0x00a95120, 0x00b24c11, 0x00b44c0d, 0x00b04e12, 0x00a45020, 0x008e4c2f, 0x00441302, 0x001c0000, 0x0033160b, 0x0045271c, 0x00331104, 0x00210000, 0x00340400, 0x00672c0c, 0x00964d28, 0x00aa5429, 0x00ac4e1c, 0x00b04c14, 0x00b24c10, 0x00b44c0d, 0x00b44c0d, 0x00b24c11, 0x00b44b11, 0x00b74911, 0x00b54913, 0x00b14a15, 0x00a55023, 0x0070381b, 0x00250000, 0x002c0700, 0x006c3820, 0x00a44f24, 0x00b14a16, 0x00b64b1a, 0x00ab4a1c, 0x00a05731, 0x00602200, 0x00662803, 0x008e441c, 0x00ab4c1c, 0x00b44d14, 0x00b34b0e, 0x00b14c0f, 0x00ae4e11, 0x00af4d11, 0x00b24c0d, 0x00b84d06, 0x00c15201, 0x00c45806, 0x00bd5c14, 0x008f430e, 0x00340600, 0x00471c0e, 0x00884626, 0x00aa5124, 0x00b44b11, 0x00bb4d0f, 0x00b54f14, 0x00b44f16, 0x00b44c0e, 0x00b55014, 0x00ab4f19, 0x00aa5527, 0x00a15129, 0x00723010, 0x00370a00, 0x001c0000, 0x00280000, 0x00542006, 0x00843f1b, 0x00a55022, 0x00b04e18, 0x00b65014, 0x00b35218, 0x00a04d1e, 0x00763c1e, 0x00330c00, 0x00150000, 0x002a0500, 0x006c300e, 0x00a55428, 0x00ae501f, 0x00b25526, 0x00873e14, 0x00581a00, 0x00501400, 0x00702c06, 0x00a04614, 0x00b65014, 0x00b94e0a, 0x00ba4f0b, 0x00b74f12, 0x00b74e14, 0x00b84d14, 0x00b84d13, 0x00b45012, 0x00b45113, 0x00b55014, 0x00b44e0f, 0x00b6520a, 0x00aa5414, 0x00854b20, 0x003f1901, 0x00150000, 0x00160000, 0x00471503, 0x0086401e, 0x00ac5421, 0x00b45214, 0x00ba5310, 0x00b9500c, 0x00bc4f0c, 0x00c4540e, 0x00c9570d, 0x00c0540d, 0x00b75c21, 0x00743207, 0x00290600, 0x00080000, 0x00030304, 0x00505457, 0x00b0b0b0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00323231, 0x00837c7a, 0x000b0000, 0x00100000, 0x00401e0f, 0x00a06037, 0x00a05426, 0x00793715, 0x00400800, 0x002c0100, 0x004c1e0c, 0x007c391c, 0x009e4b22, 0x00aa4e1c, 0x00aa5220, 0x008c461c, 0x005a1c00, 0x00501000, 0x00a35428, 0x00bc5410, 0x00bb5613, 0x009c582c, 0x003c0800, 0x00410c00, 0x00894623, 0x00ac4c1c, 0x00b64b12, 0x00b04812, 0x00b04d14, 0x00ac4c0e, 0x00ae4d0e, 0x00b34d10, 0x00b34b0f, 0x00b34a12, 0x00a04c20, 0x00653824, 0x00190000, 0x00380a00, 0x00915030, 0x00a84d20, 0x00b14d1a, 0x00af4c18, 0x00b14c16, 0x00b94a14, 0x00b74910, 0x00b04b10, 0x00af5017, 0x00ab4b18, 0x00a54e21, 0x007f3814, 0x00530f00, 0x009d4c24, 0x00a94c1d, 0x00b14810, 0x00b3490e, 0x00af4e17, 0x00a15122, 0x00854a2c, 0x003c1200, 0x00160000, 0x001d0500, 0x001c0400, 0x001c0000, 0x00310800, 0x00642b13, 0x00994d27, 0x00ab5322, 0x00a84816, 0x00b24f17, 0x00b14b0f, 0x00b34b0c, 0x00b44c0c, 0x00b44c0d, 0x00b24c11, 0x00b44b13, 0x00b74913, 0x00b54914, 0x00b24b17, 0x00a85124, 0x00783c1c, 0x002e0200, 0x00320800, 0x007c4529, 0x00a44f20, 0x00b34c15, 0x00b84917, 0x00ad4819, 0x00a2542c, 0x00621f00, 0x007b3410, 0x009c4a23, 0x00ac491a, 0x00b44c15, 0x00b14c10, 0x00b04e10, 0x00ac4e14, 0x00ad4c14, 0x00b44c0f, 0x00ba4f09, 0x00c25403, 0x00c05908, 0x00b55e1c, 0x006c2d00, 0x00210000, 0x00290b04, 0x00602c16, 0x00954c28, 0x00ac501e, 0x00b04d14, 0x00b04e16, 0x00b35014, 0x00b44c0d, 0x00b55010, 0x00b04f16, 0x00a74815, 0x00a94c1d, 0x00a4522b, 0x00773c1c, 0x00360a00, 0x001c0000, 0x00240000, 0x00531c04, 0x0089421f, 0x00a04816, 0x00b04d14, 0x00b85115, 0x00a94c16, 0x00914921, 0x005c290d, 0x00230200, 0x001c0000, 0x003c0d00, 0x008d4c2d, 0x00a84c20, 0x00b24f1d, 0x00ac5522, 0x00944818, 0x00702c03, 0x00732900, 0x009c4310, 0x00b04e10, 0x00b74f0a, 0x00b74f0a, 0x00b45013, 0x00b44f16, 0x00b84c15, 0x00b84c14, 0x00b45014, 0x00b35013, 0x00b65414, 0x00ad4c09, 0x00b2520d, 0x00a1561c, 0x00562f0e, 0x00200a00, 0x00100000, 0x00280400, 0x006a2b10, 0x00a04d23, 0x00b0551f, 0x00b35013, 0x00b95010, 0x00bc4c0c, 0x00c3500b, 0x00c7530c, 0x00c85409, 0x00be5714, 0x00a75a2a, 0x004c1b00, 0x00180000, 0x000a0200, 0x000f0d0e, 0x00717274, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009d9a98, 0x001e1614, 0x000d0000, 0x00260700, 0x00905028, 0x00ad5c27, 0x00ab5825, 0x00813813, 0x00461404, 0x002c0200, 0x00461000, 0x00783518, 0x009f4e24, 0x00a65123, 0x00984a20, 0x00722f0a, 0x00410b00, 0x00803d1a, 0x00b95718, 0x00c05815, 0x00ae5f29, 0x005b1c00, 0x00300000, 0x007c4124, 0x00a84918, 0x00b64b10, 0x00b24b16, 0x00ad4b14, 0x00ae4d13, 0x00ad4c0d, 0x00b54c0e, 0x00b4490c, 0x00b44912, 0x00a34d22, 0x006d402a, 0x001d0000, 0x004a1400, 0x0099502d, 0x00a84c1e, 0x00b04c18, 0x00ae4b18, 0x00b14b17, 0x00b84814, 0x00b74812, 0x00b34c15, 0x00ae4c17, 0x00aa4a19, 0x00a24b1e, 0x00752c08, 0x006c2300, 0x00a65028, 0x00ab4a1c, 0x00b24b17, 0x00b14a14, 0x00ad4b14, 0x009e4d20, 0x00784428, 0x00351406, 0x00100000, 0x00120000, 0x00180000, 0x002c0700, 0x0064301b, 0x00945031, 0x00a74e22, 0x00ac4814, 0x00b24910, 0x00b54b0f, 0x00b4490f, 0x00b4490f, 0x00b44a0e, 0x00b44a0f, 0x00b24b14, 0x00b24b17, 0x00b54916, 0x00b44917, 0x00b14b18, 0x00a55023, 0x007c3f1d, 0x00390900, 0x00380b00, 0x00864d2a, 0x00a44e1a, 0x00b44c10, 0x00b9480e, 0x00b44815, 0x00a85124, 0x006d1f00, 0x008e3a16, 0x00a84c27, 0x00b0481b, 0x00b54817, 0x00b14c16, 0x00af4d18, 0x00ac4c1c, 0x00ad4a1a, 0x00b54a18, 0x00be5015, 0x00c2560e, 0x00bc5a15, 0x00a55926, 0x00441100, 0x00130000, 0x000b0000, 0x002e0d00, 0x00653118, 0x00904820, 0x00a65120, 0x00ab5018, 0x00b04d10, 0x00b94d0c, 0x00b84a0a, 0x00b74c15, 0x00b44d18, 0x00b04812, 0x00ae521e, 0x009b5224, 0x00703715, 0x00360a00, 0x001c0000, 0x00240000, 0x004f1f0c, 0x008b441e, 0x00a84f1a, 0x00b1480c, 0x00bb5317, 0x00a74f1c, 0x0089441d, 0x00481c01, 0x00180000, 0x001d0000, 0x00542719, 0x00a0532c, 0x00a74b17, 0x00ac4f18, 0x00b15520, 0x00a44a1a, 0x009f4414, 0x00ab4c19, 0x00af4d13, 0x00b34f0d, 0x00b4500c, 0x00b25010, 0x00b24f14, 0x00b44d17, 0x00b64d17, 0x00b84c14, 0x00b84e12, 0x00b8510f, 0x00b0500f, 0x00ab561b, 0x007e4015, 0x00291400, 0x000a0000, 0x00170000, 0x00471b0b, 0x0090421e, 0x00ad511d, 0x00b15318, 0x00b45214, 0x00b85011, 0x00bf4e0e, 0x00cc540e, 0x00c95207, 0x00c55205, 0x00bd5d1f, 0x007f4420, 0x002c0c00, 0x000c0000, 0x00040102, 0x00302d2c, 0x00989494, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00060606, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00afaeac, 0x00443d3c, 0x000a0000, 0x001a0000, 0x00733816, 0x00a85621, 0x00ba5c1f, 0x00b0551f, 0x00844024, 0x00581f0f, 0x00430a00, 0x00480c00, 0x00712a08, 0x0094461f, 0x00a3532b, 0x00843d18, 0x003e0a00, 0x005e2404, 0x00b15821, 0x00bd5919, 0x00b65c21, 0x00803808, 0x00340200, 0x006d371b, 0x00a04515, 0x00b44b13, 0x00b34c18, 0x00ac4916, 0x00b04f18, 0x00ae4b10, 0x00b54c0c, 0x00b44a0c, 0x00b34a10, 0x00a34d20, 0x0079452d, 0x00270000, 0x00642508, 0x009e4d28, 0x00aa4c1b, 0x00b04c17, 0x00af4c17, 0x00b14b17, 0x00b74715, 0x00b84816, 0x00b64c18, 0x00ad4a17, 0x00a84818, 0x009c4317, 0x00702400, 0x00873b14, 0x00a94e24, 0x00b04c1e, 0x00b14b1a, 0x00b24c18, 0x00af4b16, 0x00a05023, 0x00693c20, 0x002b1204, 0x000c0000, 0x00100000, 0x00310a00, 0x00642e18, 0x00904d30, 0x00a4522b, 0x00ac491a, 0x00b44914, 0x00b84d11, 0x00b4480b, 0x00b6480f, 0x00b44910, 0x00b44910, 0x00b34a12, 0x00b04a16, 0x00b04a18, 0x00b24b17, 0x00b24b17, 0x00ae4b18, 0x00a54e20, 0x0082401c, 0x004c1500, 0x00420d00, 0x00904f2b, 0x00a74c18, 0x00b44b0f, 0x00b9480b, 0x00b64b12, 0x00a94f1f, 0x00802b01, 0x009c401a, 0x00b04d24, 0x00b44819, 0x00b54916, 0x00b04b15, 0x00af4c17, 0x00af4a19, 0x00b24817, 0x00bc4b18, 0x00c55219, 0x00c35812, 0x00b4591b, 0x00854722, 0x00220000, 0x000b0000, 0x00030000, 0x00100000, 0x00300f00, 0x00602d11, 0x00914f27, 0x00aa5823, 0x00ab4b0e, 0x00bc4f0e, 0x00bd4b0c, 0x00b64810, 0x00bb4f18, 0x00b64c10, 0x00b04b10, 0x00a9541c, 0x00985025, 0x00703720, 0x00370c02, 0x00160000, 0x00240000, 0x005f280d, 0x00974a21, 0x00b24e18, 0x00b64c10, 0x00b45318, 0x00a24f1c, 0x007a3c18, 0x00340b00, 0x00130000, 0x00230200, 0x007a3f21, 0x00a15224, 0x00af5019, 0x00b14b12, 0x00b65019, 0x00b24e18, 0x00af4d18, 0x00b25118, 0x00b34e11, 0x00b44e0f, 0x00b44f11, 0x00b44f12, 0x00b34e13, 0x00b54c13, 0x00ba4c12, 0x00b94c10, 0x00b44d0c, 0x00b1581b, 0x00954e21, 0x004b1c00, 0x00140500, 0x00080000, 0x002a0b00, 0x006c341c, 0x00a65025, 0x00b24f17, 0x00b05111, 0x00b45210, 0x00b85010, 0x00c1500f, 0x00cc550a, 0x00c85205, 0x00c45810, 0x00b05c24, 0x004f2208, 0x001a0801, 0x00050000, 0x00000003, 0x005d5957, 0x00b5b1ae, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x001b1b1c, 0x000c0c0c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000c0c0c, 0x007b7676, 0x00070000, 0x00130000, 0x00481800, 0x009b5323, 0x00bc5815, 0x00c0540f, 0x00b15120, 0x009e4825, 0x00783014, 0x00531200, 0x00501300, 0x00702d12, 0x00934724, 0x008d4421, 0x00541f04, 0x00440e00, 0x0093481c, 0x00b45923, 0x00ba581b, 0x00a44f17, 0x00481300, 0x005b2707, 0x00944115, 0x00b04c1b, 0x00b24b1c, 0x00b0481a, 0x00b04d1a, 0x00ac4911, 0x00b54c0e, 0x00b44c0c, 0x00b04b12, 0x00a44f20, 0x00884b2e, 0x003a0100, 0x00803514, 0x00a24a21, 0x00ae4c1a, 0x00af4b15, 0x00ae4d16, 0x00b04c17, 0x00b54715, 0x00b94918, 0x00b44b18, 0x00b04c18, 0x00a94919, 0x00983e11, 0x00732300, 0x009e4d24, 0x00aa4b1e, 0x00b14c1d, 0x00ae491a, 0x00b04c1b, 0x00b04a16, 0x00a55428, 0x005c3419, 0x001e0c00, 0x000d0000, 0x00240500, 0x005f240b, 0x00984b27, 0x00a75126, 0x00a8491b, 0x00b34c1d, 0x00b64b18, 0x00b44b11, 0x00b2480d, 0x00b44a10, 0x00b44912, 0x00b34a12, 0x00b04b14, 0x00ae4c16, 0x00ad4c16, 0x00ae4c15, 0x00ae4c15, 0x00ac4c18, 0x00a64f20, 0x008c431f, 0x00642406, 0x00541100, 0x009b4e2c, 0x00ad491b, 0x00b64810, 0x00b6490c, 0x00b34e13, 0x00a64e1c, 0x00933d10, 0x00a4461b, 0x00b14d1f, 0x00b34814, 0x00b54a11, 0x00b04a11, 0x00b04c10, 0x00b6480f, 0x00bb480c, 0x00c64c0d, 0x00cc5310, 0x00c1560f, 0x00a8561c, 0x0051240c, 0x000f0000, 0x00060101, 0x00020202, 0x00060000, 0x000d0000, 0x002c1000, 0x005f3013, 0x00934c1f, 0x00a74c13, 0x00bc4e0e, 0x00bf4b0c, 0x00b64810, 0x00b44912, 0x00b74a0f, 0x00b64d0f, 0x00b05011, 0x00a6501a, 0x009b512c, 0x00682c17, 0x00300b04, 0x001d0000, 0x002c0300, 0x00682d13, 0x00a24e22, 0x00a8450f, 0x00b54f13, 0x00ac4e14, 0x009f5020, 0x006d3213, 0x002c0902, 0x00140000, 0x003c1805, 0x00844928, 0x00ae5424, 0x00b2480f, 0x00b34b0e, 0x00af4a0d, 0x00ac4b10, 0x00b35018, 0x00b64a14, 0x00b94a14, 0x00b94c14, 0x00b74c10, 0x00b64d0c, 0x00b64e0b, 0x00b84c0d, 0x00b84d11, 0x00b14b0f, 0x00a75423, 0x00642f15, 0x00210400, 0x00100000, 0x001a0300, 0x0055240e, 0x00904824, 0x00ad5220, 0x00b14e13, 0x00b2500e, 0x00b3500b, 0x00b8500d, 0x00c4550e, 0x00c95304, 0x00c65407, 0x00be5c1a, 0x008c4517, 0x002c0b00, 0x000c0303, 0x00000003, 0x001d1c20, 0x008b8784, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00181818, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00aca9aa, 0x000c0708, 0x00100000, 0x001c0000, 0x00844821, 0x00b85612, 0x00c75407, 0x00be4d0d, 0x00b34c18, 0x00a44e28, 0x00904627, 0x0067240b, 0x00571400, 0x00702402, 0x008f4826, 0x00743d23, 0x00340100, 0x0070300c, 0x00ad5b2c, 0x00bc581a, 0x00ba5c1f, 0x005e2000, 0x00531a00, 0x008c4015, 0x00aa4e20, 0x00b04a1e, 0x00b1481c, 0x00af4c1c, 0x00aa4611, 0x00b54c10, 0x00b44c0d, 0x00ae4b11, 0x00a64e1f, 0x00964f2d, 0x004d0700, 0x0094401a, 0x00a6491c, 0x00b04d1a, 0x00ae4b13, 0x00af4e15, 0x00b04c16, 0x00b34616, 0x00b94a1b, 0x00b24714, 0x00b34c1a, 0x00ac4a1b, 0x00983c0f, 0x00792600, 0x00ab5528, 0x00ab4818, 0x00b04818, 0x00b0481a, 0x00b04b1c, 0x00ad4818, 0x00a4542a, 0x00522a10, 0x001c0500, 0x001f0400, 0x00471c07, 0x008c411e, 0x00a94e1e, 0x00ac4b17, 0x00b44d19, 0x00b44918, 0x00af4411, 0x00b44e17, 0x00b04b12, 0x00b34915, 0x00b44915, 0x00b14a15, 0x00b04b15, 0x00ae4c16, 0x00ad4c16, 0x00ae4c14, 0x00ae4c12, 0x00af4e15, 0x00ab501d, 0x0094471e, 0x0078300c, 0x00611600, 0x00a44f2c, 0x00b14a1c, 0x00b54810, 0x00b34a0c, 0x00b04c11, 0x00a64b1b, 0x00a4481d, 0x00aa491c, 0x00b14b1a, 0x00b0470f, 0x00b34b0f, 0x00ae4b11, 0x00b24c10, 0x00b94809, 0x00c04805, 0x00ca4e06, 0x00ca560d, 0x00b75712, 0x00995320, 0x00260200, 0x000c0000, 0x00010004, 0x00000104, 0x00010101, 0x00040000, 0x000b0000, 0x00290b00, 0x0066300e, 0x009d5221, 0x00b04d15, 0x00b1470b, 0x00ba5018, 0x00b74c17, 0x00b7480f, 0x00b84b0e, 0x00b24b0a, 0x00b05014, 0x00a8501f, 0x009a512e, 0x00703c28, 0x00360c00, 0x00250000, 0x00400e00, 0x007c3818, 0x00a75325, 0x00ac4a12, 0x00b14e13, 0x00ab501a, 0x00954c23, 0x00602c1b, 0x00200000, 0x001e0000, 0x005d3119, 0x009c4a23, 0x00b14d18, 0x00b34c10, 0x00b34f0f, 0x00b25013, 0x00b04b12, 0x00b84817, 0x00bc4818, 0x00bb4914, 0x00b94b10, 0x00b74d09, 0x00b64e08, 0x00b64d0f, 0x00b44e15, 0x00ab4f1c, 0x00904825, 0x00351003, 0x00120000, 0x00160000, 0x003a1200, 0x00803e1c, 0x00a75325, 0x00ac4f19, 0x00b25012, 0x00b7520e, 0x00b44d04, 0x00bc530a, 0x00c7590e, 0x00c55204, 0x00c45811, 0x00ae5a24, 0x00602a06, 0x001b0400, 0x00020001, 0x00000003, 0x00474748, 0x00a9a6a5, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x001c1c1c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9b9d, 0x00504c50, 0x00050000, 0x00100200, 0x00481d00, 0x00b05317, 0x00cc560a, 0x00c75008, 0x00b84a0a, 0x00b04d1e, 0x00a64e27, 0x00a5502b, 0x0093421d, 0x00732600, 0x00692603, 0x007a432a, 0x004a1600, 0x00430800, 0x00a2572d, 0x00b45214, 0x00bb581a, 0x008f4412, 0x00510f00, 0x00853913, 0x00a65028, 0x00ac461c, 0x00b2491c, 0x00ac481c, 0x00ae4b19, 0x00b44a0f, 0x00b44b0f, 0x00ae4813, 0x00ac4f20, 0x0099451f, 0x006c1b00, 0x00a5491e, 0x00ac4919, 0x00af4b15, 0x00ae4b11, 0x00aa4c10, 0x00ad4b14, 0x00b44818, 0x00b54818, 0x00b34916, 0x00b04a16, 0x00a44111, 0x0096390a, 0x00984112, 0x00a74d1b, 0x00b24c19, 0x00b24814, 0x00b54a18, 0x00af4717, 0x00ab4a1c, 0x00a1542e, 0x00481c00, 0x00200000, 0x00431600, 0x007a3c1b, 0x00a34c1f, 0x00b04c18, 0x00b24c17, 0x00b44914, 0x00b64713, 0x00b74816, 0x00b04d18, 0x00ad4c18, 0x00b3481b, 0x00b34519, 0x00b24618, 0x00b24818, 0x00b04a18, 0x00b14c16, 0x00b14b10, 0x00b04b0d, 0x00b0490d, 0x00af4e17, 0x00a34c1c, 0x008e3d12, 0x00752400, 0x00a85026, 0x00ac4813, 0x00b44a0f, 0x00b54d10, 0x00b24c14, 0x00ad4a1f, 0x00ad4a21, 0x00b0491c, 0x00b14a16, 0x00b14b12, 0x00af4c10, 0x00ae4d16, 0x00ae4810, 0x00be4f0c, 0x00c34f06, 0x00c85407, 0x00bc550c, 0x00a8581c, 0x00622a00, 0x001d0000, 0x00080000, 0x00000003, 0x00000308, 0x00000004, 0x00040001, 0x00080000, 0x00100000, 0x002b0b00, 0x00653411, 0x00985022, 0x00aa501c, 0x00b04c17, 0x00b54914, 0x00b54811, 0x00b7480f, 0x00b64c0c, 0x00b34d10, 0x00ab4c14, 0x00a85020, 0x00a3532c, 0x007e391d, 0x00471102, 0x00280000, 0x00501d09, 0x00844627, 0x00a85323, 0x00ae4d16, 0x00b04e18, 0x00a34818, 0x009d542e, 0x005b2409, 0x001e0000, 0x00280300, 0x00864326, 0x00a54d24, 0x00a84710, 0x00bc5818, 0x00ab480a, 0x00b54f14, 0x00bc4c1a, 0x00b74413, 0x00bc4913, 0x00bb4c10, 0x00b8510f, 0x00ad4906, 0x00b34e13, 0x00ac501f, 0x00a05532, 0x00511c08, 0x001c0100, 0x00100000, 0x002f0700, 0x00703415, 0x00a24e22, 0x00ac4f19, 0x00af5019, 0x00b35014, 0x00b44c08, 0x00bd5206, 0x00c45808, 0x00c45506, 0x00c4550b, 0x00b65618, 0x00925127, 0x002c0600, 0x000c0000, 0x00050203, 0x000b090a, 0x00838182, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00908f91, 0x00030000, 0x00030000, 0x00240700, 0x00934817, 0x00ba5312, 0x00cc5c15, 0x00bb4c08, 0x00b7501b, 0x00a94718, 0x00a84719, 0x00a84d20, 0x00a04c20, 0x00964c25, 0x00814022, 0x006f331a, 0x00370000, 0x00722f0a, 0x00bb6028, 0x00b65416, 0x00ac5822, 0x00601400, 0x0082350f, 0x009f4b25, 0x00b14c21, 0x00ac4416, 0x00ac491e, 0x00ac4a1a, 0x00b2480f, 0x00b54a10, 0x00b04814, 0x00af4c1d, 0x00a44a1d, 0x00882e01, 0x00aa4818, 0x00ae4a17, 0x00b24c17, 0x00b04d15, 0x00ac4d12, 0x00ac4b12, 0x00af4715, 0x00b04617, 0x00b14a16, 0x00b04c17, 0x00a84515, 0x009f4010, 0x00a24714, 0x00ac4e18, 0x00b34c17, 0x00b44813, 0x00b54811, 0x00b14814, 0x00ad4e21, 0x008e411b, 0x00420c00, 0x00411000, 0x00783914, 0x009b4d23, 0x00ab4c1c, 0x00b04a16, 0x00b04915, 0x00b14814, 0x00b74510, 0x00b64713, 0x00ad4a17, 0x00aa4a18, 0x00b34c1d, 0x00b44a1d, 0x00b34a1d, 0x00b1491b, 0x00b04918, 0x00b04914, 0x00b1490d, 0x00b2480c, 0x00b44b0f, 0x00ac460d, 0x00ac4d1c, 0x00a44c1f, 0x00984015, 0x00ae5427, 0x00ab4915, 0x00ae4b11, 0x00aa480e, 0x00a94814, 0x00aa4620, 0x00ac4824, 0x00ae481e, 0x00af4a19, 0x00ab4c15, 0x00a84c16, 0x00a74c1c, 0x00ac4d1c, 0x00b34b0e, 0x00c05511, 0x00c05910, 0x00b45b19, 0x00925020, 0x00330400, 0x00200000, 0x00180000, 0x00050000, 0x00000003, 0x00040006, 0x00090108, 0x00060001, 0x00080000, 0x000e0000, 0x00280c00, 0x0063320f, 0x00985228, 0x00ac5124, 0x00b24c1b, 0x00b84e1a, 0x00b84c12, 0x00b84b0e, 0x00b64d0d, 0x00b45116, 0x00ae4d14, 0x00ab4915, 0x00a64e24, 0x00843c23, 0x004e1504, 0x002c0000, 0x005d2a14, 0x00964c24, 0x00a74c1a, 0x00b34f19, 0x00b14d18, 0x00a44b18, 0x009a522a, 0x0054240c, 0x002c0200, 0x004b1000, 0x008e4423, 0x00af5422, 0x00ac480d, 0x00ac470a, 0x00b75016, 0x00b44a16, 0x00b84a16, 0x00bc4c13, 0x00b4490d, 0x00b04d10, 0x00b5571d, 0x00a84713, 0x00a8532b, 0x00753c26, 0x00280200, 0x00110000, 0x00230500, 0x005b2308, 0x00984b22, 0x00ae501c, 0x00b14e14, 0x00b25118, 0x00b04e10, 0x00bb4e08, 0x00be4e00, 0x00c45503, 0x00c55809, 0x00ba5310, 0x00b3602f, 0x00502002, 0x00150000, 0x000c0200, 0x00030000, 0x00484442, 0x00a6a5a2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00343334, 0x00040000, 0x000d0000, 0x00542408, 0x009f5428, 0x00b4561b, 0x00b85010, 0x00b85018, 0x00b04a14, 0x00b34f1c, 0x00ab4917, 0x00b05422, 0x00a34c1b, 0x009d481f, 0x00954c29, 0x004d1400, 0x003d0200, 0x00a35323, 0x00af541b, 0x00bb6027, 0x00862c00, 0x0087330c, 0x009a441f, 0x00b04c1d, 0x00ae4614, 0x00aa4c1b, 0x00ab4b1a, 0x00b24810, 0x00b74913, 0x00b34918, 0x00ae491a, 0x00ac4c1c, 0x00a44411, 0x00ae4a17, 0x00b04a16, 0x00b04a16, 0x00ae4c15, 0x00ac4c13, 0x00ac4b14, 0x00ae4918, 0x00b14b1a, 0x00b04915, 0x00b04c17, 0x00ac4818, 0x00a94717, 0x00ab4c17, 0x00af4e17, 0x00b14a14, 0x00b34811, 0x00b5460f, 0x00b24812, 0x00aa4b1c, 0x0086330a, 0x00601c00, 0x00783610, 0x00a05124, 0x00a94f1f, 0x00ac4c1b, 0x00ac4919, 0x00a94919, 0x00ae4918, 0x00b64814, 0x00b74812, 0x00b04b15, 0x00ad4c16, 0x00a94a15, 0x00aa4a18, 0x00aa4a19, 0x00ac4919, 0x00ac4918, 0x00b04a14, 0x00b44b11, 0x00b64c11, 0x00b84d14, 0x00ac430f, 0x00ac481a, 0x00ab4b21, 0x00a54a22, 0x00a64b21, 0x00a74c1c, 0x00a84d18, 0x00a9501b, 0x00a94f20, 0x00a84c29, 0x00a94b2c, 0x00aa4c25, 0x00a84d20, 0x00a34e20, 0x009f4e21, 0x00a04f2a, 0x00a4532c, 0x00b15728, 0x00b55b24, 0x00b66025, 0x00a15825, 0x00582102, 0x002d0000, 0x0077412a, 0x004b1e0a, 0x001d0800, 0x00080000, 0x00050000, 0x00040004, 0x00080008, 0x00050005, 0x00020000, 0x00080000, 0x002d1000, 0x00663419, 0x00984e2d, 0x00ab5028, 0x00ac4a16, 0x00b0490d, 0x00b84b0e, 0x00b14708, 0x00b04c11, 0x00af4d11, 0x00b0470c, 0x00b6501c, 0x00a94e26, 0x0082381b, 0x00471400, 0x00421200, 0x00773817, 0x00a45328, 0x00b04c17, 0x00b44b11, 0x00aa470f, 0x00ad5524, 0x00924c28, 0x005b2006, 0x00350000, 0x0062230a, 0x009b461e, 0x00ac4b17, 0x00b55018, 0x00ae4810, 0x00af4c14, 0x00b14e13, 0x00b64d0d, 0x00b24c0f, 0x00a64a18, 0x00ab5225, 0x00a54a20, 0x009a4f30, 0x003c1308, 0x00140000, 0x00180000, 0x0058290c, 0x00914921, 0x00a84f1c, 0x00b14f17, 0x00b44d11, 0x00ae4b10, 0x00bc5415, 0x00bd4c06, 0x00c85306, 0x00c75602, 0x00be560b, 0x00b35723, 0x00823e1d, 0x00200000, 0x000c0000, 0x00070000, 0x00150f0c, 0x00888280, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008a8a8c, 0x00080809, 0x00070000, 0x001f0300, 0x00734021, 0x009e4f20, 0x00ac4f18, 0x00a84610, 0x00b5541e, 0x00ae4c18, 0x00ab4914, 0x00b04e18, 0x00a74813, 0x00b05421, 0x009c4c22, 0x0074341c, 0x00360000, 0x006a2400, 0x00aa5825, 0x00b55a21, 0x00a84812, 0x00872e04, 0x009e4319, 0x00b14a16, 0x00b44c14, 0x00a94c16, 0x00ab4d18, 0x00b24913, 0x00b64814, 0x00b34718, 0x00b04819, 0x00af4b18, 0x00b04e18, 0x00b04a16, 0x00af4814, 0x00ac4815, 0x00ac4a14, 0x00ac4c13, 0x00ac4c14, 0x00ac4a1a, 0x00ae4b1b, 0x00ac4916, 0x00ae4a17, 0x00ad4819, 0x00ae491a, 0x00b04c18, 0x00af4c14, 0x00ae4811, 0x00b24911, 0x00b44810, 0x00b44b14, 0x00ab4917, 0x008f3609, 0x00924218, 0x00a15025, 0x00a84e1c, 0x00a94917, 0x00ad4c19, 0x00ac491a, 0x00a84b1d, 0x00ac4c1c, 0x00b44a16, 0x00b44811, 0x00b04814, 0x00ad4b14, 0x00ad4c14, 0x00ac4e16, 0x00ac4d1a, 0x00ac4d1c, 0x00ac4c1b, 0x00ab4b18, 0x00ab4915, 0x00a94814, 0x00ae4c1c, 0x00a94a1d, 0x00a84c27, 0x00a34c29, 0x009e4d2c, 0x009a4c2a, 0x009f532c, 0x00985328, 0x008c4b23, 0x00884724, 0x00833d25, 0x007d3520, 0x00783015, 0x00702e0e, 0x00692c0a, 0x00652a0b, 0x00622711, 0x00672b14, 0x00743417, 0x00763813, 0x007a3d15, 0x006c3714, 0x002f0100, 0x004b1a0b, 0x00965437, 0x008b4c2c, 0x00582a12, 0x00240800, 0x00100000, 0x00080000, 0x00030003, 0x00010004, 0x00000001, 0x00080100, 0x000e0000, 0x002c0900, 0x006a321d, 0x0098502f, 0x00a65224, 0x00ab4c14, 0x00b64c10, 0x00b44a0e, 0x00ae4b11, 0x00b24f15, 0x00b84c12, 0x00b44810, 0x00af4715, 0x00a85025, 0x007b3c1e, 0x00471200, 0x00511600, 0x00914822, 0x00ad4d1c, 0x00b34811, 0x00b54f16, 0x00a94814, 0x00a85024, 0x009a502d, 0x0062260d, 0x00450900, 0x00782a06, 0x00a44c20, 0x00ac4c1b, 0x00b14f18, 0x00ac4e13, 0x00ad4d0f, 0x00b14c0c, 0x00b44f14, 0x00a94c1f, 0x00a14b25, 0x00a5502f, 0x006a280e, 0x001e0000, 0x001d0000, 0x00572a0c, 0x0084471d, 0x00a65322, 0x00b3511c, 0x00a94308, 0x00b85014, 0x00b1490c, 0x00be5413, 0x00c35008, 0x00ca580b, 0x00c05407, 0x00b85817, 0x009a4d27, 0x003f0c00, 0x000f0000, 0x00060200, 0x00040000, 0x00514c47, 0x00aeaaa7, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0034373b, 0x00080404, 0x000d0000, 0x003a1701, 0x008c4b28, 0x0096461c, 0x0088380c, 0x00903e10, 0x00a24c1a, 0x00b15523, 0x00ac4815, 0x00b04d18, 0x00a94c16, 0x00a14c1e, 0x00924829, 0x005f1c01, 0x003d0000, 0x0089441c, 0x00b05a26, 0x00b65820, 0x008d2f00, 0x00a74412, 0x00bc4f14, 0x00b64c0e, 0x00ab4a10, 0x00ac4d15, 0x00b14a14, 0x00b14713, 0x00b2481a, 0x00b04819, 0x00ac4815, 0x00b04c17, 0x00ae4814, 0x00ac4614, 0x00ab4617, 0x00ad4a18, 0x00ae4c17, 0x00ab4c15, 0x00a84918, 0x00a64718, 0x00ac4a16, 0x00ad4a17, 0x00af481a, 0x00b0481a, 0x00b14a16, 0x00af4811, 0x00ad4812, 0x00af4b15, 0x00b04b15, 0x00b04b15, 0x00b04c17, 0x00a3410f, 0x00aa4e20, 0x00a94d21, 0x00a64615, 0x00ad4c19, 0x00af4c1a, 0x00ad4b1b, 0x00aa4b1e, 0x00aa4b1c, 0x00ad4916, 0x00ae4813, 0x00ae4814, 0x00af4912, 0x00b44e12, 0x00b04c10, 0x00ac4914, 0x00aa4a1a, 0x00a84c1f, 0x00a85024, 0x00a45125, 0x00a15129, 0x00984c28, 0x00944b2c, 0x00854028, 0x00793924, 0x00652c18, 0x0054210b, 0x00481b00, 0x00371200, 0x002b1000, 0x00270e00, 0x00260900, 0x00240600, 0x00220400, 0x00200400, 0x001d0400, 0x001d0400, 0x001c0100, 0x001c0200, 0x001c0200, 0x00240b00, 0x00200600, 0x00220500, 0x00200000, 0x004f1e0f, 0x00964d29, 0x009f4e23, 0x00994d2a, 0x00703418, 0x00320f00, 0x000f0000, 0x00040200, 0x00000000, 0x000a0004, 0x000b0000, 0x000c0000, 0x00100000, 0x002b0d00, 0x0064381d, 0x0097542c, 0x00a7501f, 0x00ae4b13, 0x00b54c13, 0x00b04d17, 0x00ad4b15, 0x00b04b15, 0x00b14812, 0x00b4470f, 0x00b04d1a, 0x00994921, 0x00733010, 0x004a0d00, 0x00682403, 0x00a54c20, 0x00b04d1a, 0x00b04c19, 0x00af4b18, 0x00b34c1d, 0x00a4471c, 0x00994d27, 0x0072300c, 0x00571400, 0x0079300a, 0x00a24c20, 0x00ae501c, 0x00ac4b12, 0x00b04d12, 0x00b04910, 0x00b14b17, 0x00b14d22, 0x00a54c27, 0x00874020, 0x00370000, 0x002c0000, 0x005e2f17, 0x00894820, 0x00a1521e, 0x00ab4f19, 0x00ae4b13, 0x00b84f15, 0x00b5480c, 0x00c05010, 0x00ba4a04, 0x00c8590f, 0x00c2580f, 0x00b55613, 0x00a25623, 0x005f280f, 0x001a0000, 0x000b0000, 0x00000000, 0x0024201d, 0x0095918e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008c8f91, 0x00131313, 0x00080100, 0x00180000, 0x00602c12, 0x008c4928, 0x0089441f, 0x006c2400, 0x0080340b, 0x0096451a, 0x00a34a1d, 0x00ac4f20, 0x00a74815, 0x00aa4f1f, 0x00a44f28, 0x00883f20, 0x003e0400, 0x00501400, 0x009e5121, 0x00b85d25, 0x00a9470f, 0x00af450a, 0x00c2500f, 0x00bc4d09, 0x00af4b0b, 0x00ac4c0f, 0x00ae4b13, 0x00ad4713, 0x00af4819, 0x00b0491c, 0x00ab4714, 0x00ac4814, 0x00af4b18, 0x00ac4718, 0x00a84418, 0x00aa4618, 0x00ab4915, 0x00a94917, 0x00a84c1f, 0x00ab4f21, 0x00aa4c18, 0x00ad4a18, 0x00ae471b, 0x00b1471a, 0x00b44915, 0x00b04811, 0x00ac4814, 0x00af4d19, 0x00ac4b17, 0x00a84610, 0x00b14e16, 0x00af4914, 0x00ad4819, 0x00aa4619, 0x00af4a1b, 0x00ad4818, 0x00ae4918, 0x00ad4a18, 0x00ac491a, 0x00ab4819, 0x00ab4915, 0x00ad4c16, 0x00ae4c1a, 0x00ae4c1a, 0x00a84814, 0x00a74b17, 0x00a64d21, 0x00a25029, 0x00984e2b, 0x00874423, 0x00723616, 0x00632b0e, 0x00531f05, 0x004b1802, 0x003b0700, 0x00380600, 0x002f0000, 0x00290000, 0x00200000, 0x001a0000, 0x00120000, 0x00100000, 0x00130000, 0x00130000, 0x00100000, 0x000f0000, 0x000d0000, 0x000c0000, 0x000c0000, 0x00080000, 0x00040000, 0x00050100, 0x00090000, 0x00110000, 0x002b0400, 0x00723923, 0x00a45428, 0x00ac501e, 0x00ab4a1e, 0x009f4924, 0x00783e1e, 0x003a1900, 0x000d0100, 0x00090300, 0x000b0000, 0x000b0003, 0x000a0004, 0x000a0000, 0x000d0000, 0x002d1100, 0x00683317, 0x0099502a, 0x00a94e1c, 0x00ac4a14, 0x00af4c18, 0x00ae4b18, 0x00ac4612, 0x00b34a14, 0x00b84c10, 0x00ae450d, 0x00a84d1f, 0x00974925, 0x0066260a, 0x00501000, 0x00853812, 0x00a85024, 0x00ab4818, 0x00b24a18, 0x00b14614, 0x00b04a18, 0x00a84d1d, 0x0097491d, 0x007b3511, 0x006b2503, 0x0083320d, 0x00a2491d, 0x00ab4c17, 0x00b04d15, 0x00b04812, 0x00b14a16, 0x00ae491b, 0x0099411a, 0x00601d00, 0x00460c00, 0x00723415, 0x008b4420, 0x00a75425, 0x00a64c15, 0x00ac4c14, 0x00b75016, 0x00b4470d, 0x00bd4c0d, 0x00c8530f, 0x00c35007, 0x00c3580a, 0x00bd5e16, 0x00a85a21, 0x006d340d, 0x00260400, 0x000e0000, 0x00030000, 0x00080808, 0x006c6866, 0x00565554, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004f4e4c, 0x00100a08, 0x00100000, 0x00300800, 0x00743e1f, 0x0095542e, 0x007d3814, 0x00591800, 0x00602102, 0x00844121, 0x00984c27, 0x00ab4f23, 0x00a84617, 0x00ab4a1c, 0x009c4a24, 0x00612914, 0x00340300, 0x00702e03, 0x00a5541a, 0x00bb5818, 0x00bc4c08, 0x00c75008, 0x00c8510b, 0x00ba4e0c, 0x00ac4a0a, 0x00ac4c11, 0x00a84913, 0x00ac4919, 0x00ae4a1c, 0x00ab4617, 0x00ad4818, 0x00b04b1a, 0x00ac481a, 0x00aa451c, 0x00a74418, 0x00a44210, 0x00a04210, 0x00a1471a, 0x00a84d20, 0x00a84c19, 0x00ac4b18, 0x00af461c, 0x00b1441b, 0x00b64816, 0x00b24812, 0x00ac4914, 0x00ac4d1a, 0x00a84c19, 0x00a64813, 0x00ab4a13, 0x00b04a14, 0x00b2481a, 0x00b04619, 0x00b44c1d, 0x00ac4514, 0x00ae4815, 0x00b04917, 0x00b04816, 0x00ad4713, 0x00ac4a14, 0x00ac4f19, 0x00a64c1f, 0x009b461e, 0x00a0542d, 0x008f4927, 0x0077381d, 0x005f2712, 0x00481c09, 0x00381300, 0x002b0c00, 0x00230900, 0x001c0000, 0x001c0000, 0x001e0000, 0x00280000, 0x00300000, 0x003a0c00, 0x003e1300, 0x00481e05, 0x0054240c, 0x00532209, 0x004f1e05, 0x00471901, 0x003c1300, 0x00300b00, 0x00270300, 0x00200000, 0x001a0000, 0x000f0000, 0x000b0500, 0x00020000, 0x00070000, 0x001c0200, 0x004f1800, 0x00a15832, 0x00a4501c, 0x00a84810, 0x00b04514, 0x00af491d, 0x009d4c21, 0x007f451d, 0x004c2b0c, 0x001e0a00, 0x000d0000, 0x00070006, 0x00030004, 0x00040000, 0x000c0400, 0x00130000, 0x00361000, 0x00703821, 0x009c4c24, 0x00a84c1b, 0x00ae4e1e, 0x00b24d1c, 0x00b44c15, 0x00b54c12, 0x00b54c10, 0x00b04b12, 0x00ab4c1c, 0x009d4923, 0x00833f21, 0x005b1e04, 0x005c1d00, 0x00924824, 0x00af4e20, 0x00b24814, 0x00b04c17, 0x00ae4c15, 0x00aa4810, 0x00ac4e1b, 0x009e4a24, 0x00853816, 0x00823215, 0x008b3614, 0x00a4481c, 0x00ac4916, 0x00b34a12, 0x00b14a14, 0x00a94815, 0x008e380d, 0x00662201, 0x007f3c18, 0x00a64f21, 0x00b04f1b, 0x00a84614, 0x00ae4c18, 0x00b3501a, 0x00af480e, 0x00bb4b0f, 0x00c54e0e, 0x00ca4f07, 0x00cc580c, 0x00b95304, 0x00ad5a14, 0x007e4113, 0x00300b00, 0x000c0000, 0x00030000, 0x00010000, 0x00444442, 0x00a4a3a1, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a5a5a4, 0x002c2829, 0x000d0000, 0x00180000, 0x003e1500, 0x007c4224, 0x00945536, 0x006a2f11, 0x00491300, 0x004b1700, 0x00703519, 0x00994c2a, 0x00a44921, 0x00ae4d20, 0x00a04b21, 0x00884b33, 0x004d1901, 0x00470c00, 0x00843c0c, 0x00ab5116, 0x00c15916, 0x00c7530a, 0x00ca540a, 0x00c3540d, 0x00b14a07, 0x00ac4c0e, 0x00a94c12, 0x00aa4b16, 0x00ac4a1a, 0x00ab4617, 0x00b04b1c, 0x00ac4817, 0x00ad4819, 0x00ae4a1f, 0x00aa471c, 0x009f3e10, 0x00933709, 0x008d3710, 0x00903c15, 0x00a04c20, 0x00a44c22, 0x00a74825, 0x00ab4722, 0x00b0491d, 0x00ae4918, 0x00a94918, 0x00a84c1b, 0x00a64b1b, 0x00ad5220, 0x00a74813, 0x00ab4714, 0x00b54b1e, 0x00ae4417, 0x00ad4618, 0x00af4b1c, 0x00aa4818, 0x00ab4b1b, 0x00aa491c, 0x00a5491c, 0x00a24d1f, 0x009c4e24, 0x008c4423, 0x0077381c, 0x00582108, 0x00491904, 0x00380c00, 0x00270100, 0x001c0000, 0x001a0000, 0x001b0000, 0x00200400, 0x00341203, 0x00471e0d, 0x00602c1c, 0x0069301e, 0x00743621, 0x007c3c24, 0x007c4024, 0x00834728, 0x00894526, 0x008b4422, 0x0089441f, 0x0086441c, 0x0082421b, 0x007d3f1a, 0x00793c1a, 0x00743a1c, 0x0064351d, 0x00523120, 0x002f241b, 0x000a0800, 0x00080000, 0x00280c00, 0x00824627, 0x00ac5b2e, 0x00ac5119, 0x00b45017, 0x00b74814, 0x00b34614, 0x00ac4c1c, 0x009e4e1f, 0x007d431a, 0x00603518, 0x00331309, 0x00170000, 0x00080000, 0x000a0300, 0x00060000, 0x00080000, 0x00150200, 0x002e0c00, 0x00753a1c, 0x009d5028, 0x00a84d22, 0x00a74414, 0x00b54c18, 0x00b44a13, 0x00ac450c, 0x00b25019, 0x00ac4b18, 0x00a64d21, 0x00994c2c, 0x0076341a, 0x00490d00, 0x00773417, 0x00a44c21, 0x00ac4817, 0x00ad4c16, 0x00ac4a12, 0x00b24c11, 0x00ae4813, 0x00a84b20, 0x00a14b26, 0x00903c1c, 0x00893412, 0x00993c11, 0x00aa4516, 0x00b54c18, 0x00b04814, 0x00ad4b1b, 0x00984014, 0x0092451f, 0x00a05026, 0x00ab4712, 0x00b54a11, 0x00b04a16, 0x00ad4916, 0x00b04c13, 0x00b74e10, 0x00c04e0f, 0x00ca520e, 0x00ca5309, 0x00c3540c, 0x00b25814, 0x008b4810, 0x00421800, 0x00110000, 0x00080100, 0x00000305, 0x001f1f1f, 0x00969594, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00777777, 0x00241d1c, 0x000a0000, 0x001a0000, 0x004c200d, 0x00844d31, 0x008d5332, 0x0065300e, 0x00330800, 0x003d1200, 0x005e2815, 0x0086422b, 0x00a04e28, 0x00a14c23, 0x009c4f2b, 0x00833f20, 0x00440900, 0x00501400, 0x0090481f, 0x00b05b24, 0x00b85009, 0x00c8580a, 0x00c35607, 0x00bb5308, 0x00b3500b, 0x00ae4d0e, 0x00ad4a10, 0x00ac4a14, 0x00ac4819, 0x00ac481a, 0x00b04816, 0x00ad4514, 0x00ac4718, 0x00ac4a1c, 0x00a74b20, 0x0098421b, 0x00823311, 0x00702709, 0x006c280a, 0x00773216, 0x008a4025, 0x00994b2f, 0x00a34d2c, 0x00a84c24, 0x00a84a1f, 0x00a8491c, 0x00a64a1f, 0x00a74b20, 0x00a94a1d, 0x00aa481a, 0x00ac481c, 0x00ad491e, 0x00ad4a1f, 0x00a84a20, 0x00a54c24, 0x00a04e28, 0x00984d2b, 0x00894829, 0x00743d21, 0x00592c14, 0x00401a08, 0x00301001, 0x001e0000, 0x001b0000, 0x00190000, 0x00200100, 0x00300d00, 0x00451c0c, 0x005c2c15, 0x006d3318, 0x00833c20, 0x008e3f1e, 0x009b4421, 0x00a44824, 0x00a44b24, 0x00a44c25, 0x00a14d27, 0x00a24e28, 0x00a44b27, 0x00a44a24, 0x00a44c1d, 0x00a64f19, 0x00aa5118, 0x00b2571c, 0x00b75820, 0x00ad5524, 0x009d542f, 0x00825035, 0x00352012, 0x00100900, 0x00080000, 0x00200500, 0x00743c20, 0x00a7592f, 0x00b3551e, 0x00b85014, 0x00b84c17, 0x00b74c19, 0x00ac4414, 0x00a84818, 0x00a85122, 0x0093461d, 0x007a3b1c, 0x00511e08, 0x00260400, 0x00110000, 0x00080000, 0x00000000, 0x00000100, 0x00050000, 0x00321404, 0x0070391f, 0x009c4d28, 0x00a94a1c, 0x00b24c19, 0x00b34c18, 0x00ab4814, 0x00ac4d17, 0x00a94811, 0x00ad511f, 0x00a04924, 0x00904228, 0x006a2513, 0x00510c00, 0x00914724, 0x00a04c20, 0x00a94b1a, 0x00ae4a15, 0x00b14c16, 0x00b04c17, 0x00ae4c1a, 0x00aa4c1b, 0x00a54619, 0x00a34218, 0x009f3b10, 0x00a94216, 0x00b2491e, 0x00b34a1f, 0x00ad481c, 0x00a94719, 0x00a84b1d, 0x00ad4f1e, 0x00ac4916, 0x00b14d18, 0x00ac4b17, 0x00ac4913, 0x00b55010, 0x00bf540e, 0x00c65208, 0x00c85508, 0x00c35610, 0x00b4581a, 0x008c4818, 0x004c1d00, 0x00180000, 0x00080000, 0x00060304, 0x000b0c0f, 0x007b7b7b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b2b2b2, 0x00545050, 0x001c1518, 0x000c0000, 0x00210400, 0x00512610, 0x00834c2a, 0x00915834, 0x0059290c, 0x002c0000, 0x002f0500, 0x0050200f, 0x0078381c, 0x009f5432, 0x00a0512c, 0x00914724, 0x00723216, 0x00420600, 0x005a1c00, 0x008e481e, 0x00b45e28, 0x00b95a1a, 0x00bf5c15, 0x00bd5710, 0x00b5500c, 0x00b04a09, 0x00ad480c, 0x00ac4813, 0x00ad4a18, 0x00ae491a, 0x00b04818, 0x00b34b1b, 0x00b14a1c, 0x00ab471a, 0x00a7491e, 0x00a24a23, 0x00904120, 0x007d3518, 0x00591900, 0x00541800, 0x00551804, 0x005f210b, 0x006c2b13, 0x00783317, 0x00853c1c, 0x00904321, 0x00934826, 0x00984b29, 0x009b4d2b, 0x009b4d2b, 0x009a4b29, 0x00984828, 0x00924423, 0x008c4022, 0x007f381c, 0x00733318, 0x00622913, 0x004e1c08, 0x003a1000, 0x00290500, 0x001c0000, 0x00180000, 0x00270500, 0x00351006, 0x00482114, 0x005d301e, 0x006f3b23, 0x007f4426, 0x00904b28, 0x009f4e29, 0x00a14820, 0x00a8471c, 0x00ac461a, 0x00ae4719, 0x00af4819, 0x00ac4919, 0x00ac4919, 0x00ac491c, 0x00af4a21, 0x00ac471b, 0x00ac4911, 0x00b04b0a, 0x00b84f06, 0x00c2560c, 0x00c55817, 0x00b85620, 0x00a0552c, 0x005d2b10, 0x00200b00, 0x00050000, 0x00070000, 0x00180300, 0x003b0e00, 0x007b3817, 0x00b45c28, 0x00bc581d, 0x00af4912, 0x00b04812, 0x00b84d19, 0x00b04713, 0x00ae4814, 0x00ac4e1c, 0x00a04c20, 0x008b4420, 0x00673017, 0x003c1505, 0x00180100, 0x00080000, 0x00020300, 0x00080501, 0x000e0000, 0x003b1505, 0x0078381e, 0x009b4824, 0x00a4471c, 0x00ab4818, 0x00ae4c18, 0x00ab4a13, 0x00b04d15, 0x00ab4915, 0x00a94920, 0x00a44a2a, 0x0087381f, 0x005e1700, 0x00642104, 0x00984f29, 0x00a64b20, 0x00ac481a, 0x00ab4816, 0x00a94613, 0x00ac4815, 0x00ae4b18, 0x00af4a19, 0x00ad4819, 0x00ac4718, 0x00ac471b, 0x00ad481c, 0x00b0481b, 0x00b04a19, 0x00b04915, 0x00b04913, 0x00b04a13, 0x00ae4a14, 0x00ac4911, 0x00b04b10, 0x00ba5312, 0x00c2550f, 0x00c15208, 0x00c25307, 0x00c45d14, 0x00b2581c, 0x00853e10, 0x00512104, 0x001b0000, 0x000b0000, 0x00030000, 0x000e0e10, 0x00606163, 0x009b9b9c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a69fa0, 0x00443d40, 0x00100707, 0x000a0000, 0x00240800, 0x00612e10, 0x0094532d, 0x00904f29, 0x005f2404, 0x00260000, 0x001e0000, 0x00411504, 0x00693420, 0x008f4d2f, 0x0099502c, 0x00944a27, 0x00692200, 0x00460800, 0x00581d03, 0x00703519, 0x0084421f, 0x00a1501e, 0x00b1541a, 0x00be5819, 0x00bf5616, 0x00b75014, 0x00b04b12, 0x00af4811, 0x00ad4612, 0x00ab4415, 0x00ac471b, 0x00ae4719, 0x00aa4517, 0x00ac4819, 0x00ad4e20, 0x00a64d21, 0x00984820, 0x0087401e, 0x00632609, 0x003f0b00, 0x00300100, 0x00300700, 0x00351004, 0x003d1b0e, 0x00482414, 0x004c2410, 0x00522710, 0x00552a15, 0x00562c19, 0x00552c1a, 0x00532918, 0x004e2415, 0x004a2013, 0x00401508, 0x00380c00, 0x002c0000, 0x00240000, 0x00250000, 0x00320400, 0x00441502, 0x0055200b, 0x006d2a15, 0x007e341b, 0x00904323, 0x009c4c24, 0x00a14d20, 0x00a44c1b, 0x00a64c1a, 0x00a84d1c, 0x00a94e1e, 0x00a94c1f, 0x00a74a1c, 0x00a8491c, 0x00ab4818, 0x00ac4916, 0x00ae4813, 0x00af4813, 0x00af4717, 0x00b04613, 0x00b64c0e, 0x00be520a, 0x00c75404, 0x00c85608, 0x00be5613, 0x00aa5420, 0x006c3418, 0x002c0d00, 0x000b0000, 0x00040100, 0x00050000, 0x000c0000, 0x00190000, 0x003b0e00, 0x0082390d, 0x00b0571e, 0x00ba5d20, 0x00b35213, 0x00b44c0e, 0x00b34b0e, 0x00b14812, 0x00ac4716, 0x00a94c1f, 0x00a24c23, 0x00944926, 0x007b3c1d, 0x0059270e, 0x00350f00, 0x001c0000, 0x00110000, 0x00120000, 0x00140000, 0x003f1108, 0x00773827, 0x009b4a28, 0x00aa4d1e, 0x00b04f14, 0x00ae490c, 0x00b04b12, 0x00ad4714, 0x00b0481b, 0x00af4c22, 0x00a1461e, 0x00843612, 0x00571500, 0x00722f11, 0x009f4824, 0x00ab4b21, 0x00af4e22, 0x00ad4b1d, 0x00ac4919, 0x00ae491a, 0x00ae4b19, 0x00ac4918, 0x00ae4c1a, 0x00aa4a18, 0x00a84913, 0x00aa4910, 0x00ae4b10, 0x00b04c0c, 0x00b24b08, 0x00b04907, 0x00b24c10, 0x00b2490b, 0x00bc4b04, 0x00c65004, 0x00cb5404, 0x00c85708, 0x00bc5713, 0x00ab551d, 0x0088481f, 0x004c1f04, 0x001f0100, 0x000e0000, 0x00090100, 0x000e0c0f, 0x004c4c50, 0x00acadaf, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008b8888, 0x00322e2c, 0x00100b04, 0x000d0000, 0x002c0700, 0x005f280c, 0x00955130, 0x0093522e, 0x00512202, 0x00240000, 0x00200100, 0x002d0800, 0x0065301c, 0x00904f31, 0x009b4d29, 0x00924621, 0x00602004, 0x00380300, 0x002c0300, 0x003e1504, 0x005c2509, 0x0075330b, 0x00944213, 0x00a64c18, 0x00ac511c, 0x00ae501c, 0x00ae4c16, 0x00ac4814, 0x00af4a1c, 0x00ac471b, 0x00ae4719, 0x00b0481a, 0x00b04917, 0x00ad4818, 0x00a94918, 0x00a44c1d, 0x00a05026, 0x008b4521, 0x00703417, 0x00502109, 0x00300c00, 0x00190000, 0x00110000, 0x00140000, 0x001a0000, 0x001c0000, 0x001b0000, 0x001b0000, 0x00190000, 0x001a0000, 0x001a0000, 0x001c0000, 0x00250000, 0x002d0400, 0x003a0c00, 0x004a1701, 0x005c240d, 0x0070341a, 0x00844126, 0x00944a2c, 0x00a24b2c, 0x00a84927, 0x00ab4b21, 0x00ad4b1b, 0x00ae4a14, 0x00ac4910, 0x00ab4810, 0x00a94811, 0x00a84916, 0x00a54a18, 0x00a5491c, 0x00a74a1b, 0x00ab4818, 0x00ac4814, 0x00b04810, 0x00b1480e, 0x00b0440d, 0x00b74a0d, 0x00c0500a, 0x00c35305, 0x00ca5708, 0x00c65c11, 0x00a64c13, 0x0078360e, 0x00300900, 0x00110100, 0x00020000, 0x00080a09, 0x0017140f, 0x00130c06, 0x00080000, 0x00140000, 0x003c0800, 0x00763206, 0x00a85a24, 0x00b75f21, 0x00b45210, 0x00b8500e, 0x00b95014, 0x00af4610, 0x00af4a19, 0x00a74819, 0x00a0491c, 0x009d4d24, 0x00904a25, 0x0075371a, 0x00551c0b, 0x003a0c00, 0x001c0000, 0x00140000, 0x001b0000, 0x00461810, 0x007c3c24, 0x009b4b23, 0x00a84a14, 0x00ad480f, 0x00ac4814, 0x00af4a1b, 0x00ad4716, 0x00ae4918, 0x00a44412, 0x00a44c20, 0x007c3414, 0x00631c00, 0x007c2905, 0x00923810, 0x00a4481d, 0x00ab4a1e, 0x00ac4819, 0x00ac4818, 0x00ad4818, 0x00ac4916, 0x00aa4814, 0x00a94a14, 0x00aa4c14, 0x00ac4b10, 0x00ac4a0c, 0x00b04908, 0x00b44807, 0x00b74a07, 0x00b74b0a, 0x00c3530f, 0x00cc580b, 0x00cc5201, 0x00c85304, 0x00c45c14, 0x00a9561d, 0x0080411a, 0x00421902, 0x001c0300, 0x000b0000, 0x00080000, 0x00100c0d, 0x00464648, 0x009c9fa1, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00808078, 0x0028251e, 0x000a0200, 0x00120100, 0x00280800, 0x005a2610, 0x008c4c2f, 0x00904f2f, 0x00521b00, 0x00170000, 0x00170000, 0x002f0800, 0x00673321, 0x00904c2c, 0x00944926, 0x00854321, 0x004f1a00, 0x00260700, 0x00100000, 0x00100000, 0x00200600, 0x00401800, 0x00632c0c, 0x00833d19, 0x00994921, 0x00a44c21, 0x00a94a1d, 0x00ac4819, 0x00ac4517, 0x00ad4515, 0x00af4715, 0x00ae4614, 0x00ac4410, 0x00ac4511, 0x00ac4916, 0x00a24614, 0x00a24d1f, 0x009c5025, 0x00894620, 0x006e3514, 0x00522204, 0x003f1400, 0x00340c00, 0x00340700, 0x00320400, 0x00300300, 0x00310400, 0x00350800, 0x003c0e00, 0x00441500, 0x004b1900, 0x005b2504, 0x00682c0b, 0x007b3a16, 0x008c4421, 0x00984a26, 0x009c4c27, 0x00a04a27, 0x00a24824, 0x00aa4924, 0x00a9481e, 0x00a84618, 0x00a94717, 0x00ac4a14, 0x00ac4c14, 0x00ac4c14, 0x00aa4b14, 0x00a84816, 0x00a94b19, 0x00ab4b1b, 0x00ac4919, 0x00ac4817, 0x00ae4713, 0x00b04713, 0x00b3480f, 0x00bb4d0d, 0x00c1510b, 0x00c65305, 0x00c45204, 0x00c0570e, 0x00af551a, 0x0078340f, 0x00380c00, 0x00170000, 0x00030001, 0x00000307, 0x00212829, 0x005c605f, 0x00505250, 0x000c0d0b, 0x00050000, 0x00160000, 0x00300800, 0x00672e09, 0x009c5220, 0x00b45a1d, 0x00bc5412, 0x00bc5011, 0x00ba4d12, 0x00b04510, 0x00af4b16, 0x00ab4c17, 0x00a44a18, 0x00a14d20, 0x00a05028, 0x008f4425, 0x0078341e, 0x004f190c, 0x00381007, 0x00190000, 0x00170000, 0x00411804, 0x00783c1f, 0x009f4924, 0x00aa4821, 0x00ac4821, 0x00a8481d, 0x00a84918, 0x00aa4c15, 0x00a4450c, 0x00a84c18, 0x00a34c28, 0x00893817, 0x00742700, 0x00863709, 0x009a4517, 0x00a6491a, 0x00ab4818, 0x00ae4817, 0x00b04816, 0x00ad4714, 0x00ac4815, 0x00ad4a17, 0x00ae4c16, 0x00ae4a14, 0x00b04811, 0x00b44710, 0x00bb4812, 0x00c04c10, 0x00c6510d, 0x00c85208, 0x00ca5405, 0x00c85508, 0x00bd5813, 0x00a8561c, 0x00743a14, 0x00391400, 0x00150200, 0x00070000, 0x00080102, 0x000a0507, 0x00423f40, 0x009a9a9c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b7ac, 0x0074716a, 0x00282422, 0x00050107, 0x00080000, 0x00260300, 0x0057230c, 0x008f4c2f, 0x0082452c, 0x00401d10, 0x00170000, 0x00140000, 0x002b0400, 0x00653017, 0x008a4b2a, 0x00965430, 0x007e4426, 0x00441d0c, 0x00190200, 0x000a0002, 0x00040000, 0x000b0000, 0x00180000, 0x00320700, 0x00531b00, 0x00743416, 0x008f4524, 0x00984620, 0x00a24a21, 0x00a84c21, 0x00a8491c, 0x00aa4818, 0x00ae4918, 0x00b04a16, 0x00ae4814, 0x00ae4b18, 0x00a94b19, 0x00a24a19, 0x009e4c1d, 0x009b5024, 0x00955028, 0x00884620, 0x0078391a, 0x0070331e, 0x006f3121, 0x006e311f, 0x0072341e, 0x0078391f, 0x00804021, 0x00884822, 0x00904d25, 0x00985026, 0x009b5024, 0x009f5024, 0x00a24d24, 0x00a34b20, 0x00a54a20, 0x00a74820, 0x00a94920, 0x00a8481d, 0x00a9481b, 0x00aa4a1a, 0x00ab4917, 0x00aa4814, 0x00a94812, 0x00a94812, 0x00a94814, 0x00ab4917, 0x00ac4919, 0x00ac4919, 0x00ac4817, 0x00b04613, 0x00b14711, 0x00b74911, 0x00bb4d0f, 0x00c45610, 0x00c15408, 0x00c7590e, 0x00c6601a, 0x00a85118, 0x00733007, 0x003b1000, 0x00140000, 0x00050000, 0x0008080e, 0x00181c20, 0x0062686b, 0x00313333, 0x00a6adab, 0x00494e4c, 0x000e100d, 0x00050000, 0x000e0000, 0x002a0600, 0x00572304, 0x008e471a, 0x00b05924, 0x00b8551a, 0x00bd5416, 0x00b54b0d, 0x00b54c10, 0x00b04a11, 0x00a94811, 0x00a74815, 0x00a84c1c, 0x00a54a1f, 0x009c4722, 0x00954b30, 0x00723723, 0x004d2513, 0x00341200, 0x00310800, 0x00561c01, 0x008b391b, 0x00a44524, 0x00ac4824, 0x00a84419, 0x00ac4f19, 0x00a84a12, 0x00aa4c12, 0x00a94a15, 0x00a6481e, 0x00a74d27, 0x009a471b, 0x009c491b, 0x00a2491c, 0x00a8481a, 0x00ad4819, 0x00b04818, 0x00b04715, 0x00ae4411, 0x00ae4814, 0x00ac4813, 0x00ac4711, 0x00af4811, 0x00b44812, 0x00bd4c15, 0x00c44e17, 0x00c75114, 0x00cc5712, 0x00c4530b, 0x00c1560f, 0x00b95a1a, 0x00984c18, 0x00662e07, 0x002f0d00, 0x000c0000, 0x00050000, 0x00000003, 0x00100c10, 0x00494446, 0x00999695, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000d0c0c, 0x00727073, 0x001b1e28, 0x0006060e, 0x00130302, 0x00200000, 0x004d1706, 0x00824a36, 0x0076503e, 0x00381e10, 0x001a0800, 0x00100000, 0x002a0900, 0x0063361c, 0x00834522, 0x0093512c, 0x006f3416, 0x004b1e0c, 0x00150100, 0x00050006, 0x00000005, 0x00030002, 0x000b0000, 0x00130000, 0x00220600, 0x00341000, 0x0062341f, 0x00743c22, 0x00874528, 0x00944926, 0x00a04b21, 0x00a84c1e, 0x00ac491a, 0x00aa4516, 0x00a84515, 0x00a94718, 0x00a8491c, 0x00a84b1d, 0x00a84c1c, 0x00a84c1b, 0x00a74a19, 0x00a34818, 0x00a04c22, 0x009c4b24, 0x009c4a23, 0x009e4a24, 0x009e4b22, 0x009f4a20, 0x00a04b21, 0x00a44c21, 0x00a44c21, 0x00a44b20, 0x00a44920, 0x00a44920, 0x00a44820, 0x00a54821, 0x00a64922, 0x00a64920, 0x00a2481b, 0x00a54a1a, 0x00aa4c1b, 0x00ab4b18, 0x00ac4916, 0x00ac4814, 0x00ae4a17, 0x00b04b1a, 0x00aa4618, 0x00aa4618, 0x00ab4617, 0x00ae4713, 0x00b44810, 0x00bb4b0d, 0x00c34f0c, 0x00c6530d, 0x00c55710, 0x00bb540f, 0x00b85819, 0x00a2531f, 0x006b3210, 0x002e0a00, 0x000c0000, 0x00070204, 0x00040406, 0x00191a1d, 0x00656668, 0x00313232, 0x00000000, 0x00000000, 0x00b2b4b0, 0x004c4c48, 0x001a1517, 0x000a0104, 0x00080000, 0x00180000, 0x00411b0b, 0x00783e1e, 0x009d4f1e, 0x00b35518, 0x00c45c18, 0x00be530f, 0x00b64c10, 0x00b34c14, 0x00ae4a15, 0x00aa4611, 0x00ae4811, 0x00b24e19, 0x00a84a1f, 0x009c4822, 0x00944e24, 0x0083451c, 0x00652702, 0x005d1600, 0x007c2506, 0x009b3c19, 0x00ac461a, 0x00ac4612, 0x00b04d15, 0x00a8470e, 0x00ac4d18, 0x00ac4c1c, 0x00a44317, 0x00a9481e, 0x00ac4c22, 0x00a8471e, 0x00a9441b, 0x00ac4418, 0x00b04418, 0x00b14518, 0x00b14615, 0x00b14814, 0x00ae4712, 0x00ae4810, 0x00b04a0e, 0x00b44d0c, 0x00bb5110, 0x00c25310, 0x00c85410, 0x00c75510, 0x00c0530e, 0x00bc5a1a, 0x00ac5822, 0x00864519, 0x004e2304, 0x001d0400, 0x00080000, 0x00090605, 0x00000001, 0x00171518, 0x00494444, 0x00a09a98, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00757b83, 0x00191c24, 0x00060103, 0x00100000, 0x00180000, 0x00381101, 0x00664535, 0x00705645, 0x00362010, 0x001e0a00, 0x00100000, 0x00230200, 0x005a2a0f, 0x00854929, 0x00965531, 0x00713819, 0x003e1808, 0x001e0a04, 0x00050002, 0x00010004, 0x00040100, 0x00050000, 0x00080000, 0x000e0000, 0x00130000, 0x00270800, 0x00471f0c, 0x006a3720, 0x00844528, 0x00904726, 0x00984824, 0x009f4924, 0x00a54c28, 0x00a34923, 0x00a34721, 0x00a4471e, 0x00a5451b, 0x00a54417, 0x00a94616, 0x00aa4a1a, 0x00a54b1e, 0x00a24b1e, 0x00a34b20, 0x00a34d24, 0x00a24d25, 0x009e4a24, 0x009c4823, 0x009c4824, 0x009b4624, 0x009b4624, 0x009a4622, 0x009a4622, 0x00994520, 0x0098441f, 0x0097421c, 0x00954018, 0x00984014, 0x009c4114, 0x00a04416, 0x00a64616, 0x00ac4818, 0x00ac4817, 0x00ad4716, 0x00ac4615, 0x00ad4716, 0x00ad4714, 0x00af4813, 0x00b44a10, 0x00ba4c0c, 0x00c1510c, 0x00c85409, 0x00c7560c, 0x00bc5512, 0x00b65c23, 0x009a5022, 0x005f2809, 0x00240500, 0x000b0000, 0x00040405, 0x00000407, 0x00141818, 0x00646867, 0x009c9c9b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00606062, 0x0018191d, 0x00000007, 0x00080007, 0x000d0000, 0x00290700, 0x00612c09, 0x00904a18, 0x00ac551b, 0x00b85818, 0x00be591c, 0x00be551c, 0x00b95016, 0x00b84a10, 0x00b44707, 0x00b14406, 0x00ad440e, 0x00b14f19, 0x00a74c14, 0x009f4814, 0x00a04f22, 0x0098461f, 0x00903a15, 0x009c3d15, 0x00ad4716, 0x00b04713, 0x00ae4710, 0x00ac4812, 0x00a84817, 0x00a84818, 0x00ae4b1b, 0x00ae491b, 0x00aa4418, 0x00a94418, 0x00ad4418, 0x00b24818, 0x00b34614, 0x00b1430f, 0x00b1440c, 0x00b4480c, 0x00b6490c, 0x00ba4e0d, 0x00be5412, 0x00c05811, 0x00c25711, 0x00c0550e, 0x00c1550d, 0x00bd5613, 0x00b1571a, 0x009e5120, 0x006d330f, 0x00340c00, 0x00130000, 0x00080100, 0x00020202, 0x00000104, 0x00171718, 0x00585758, 0x00aaa5a5, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007f7d7e, 0x00272320, 0x00080300, 0x00070200, 0x00080000, 0x00150600, 0x00462f20, 0x00785740, 0x004f2d19, 0x00200800, 0x00100000, 0x001c0100, 0x0047210c, 0x007c4521, 0x0095582e, 0x008b5028, 0x005c2d0c, 0x002a0d00, 0x00140400, 0x00100806, 0x00100808, 0x00110301, 0x000f0000, 0x000c0000, 0x000a0000, 0x000e0000, 0x00180000, 0x00280800, 0x00492013, 0x006c3a2c, 0x007f4532, 0x008c4b34, 0x00914a30, 0x0094482c, 0x00944627, 0x00984727, 0x009b4828, 0x009a4825, 0x00964524, 0x00984727, 0x00954729, 0x0092472a, 0x0090482d, 0x008c4a32, 0x00874933, 0x00814630, 0x007c442f, 0x00743c28, 0x006f3820, 0x00682d14, 0x00612408, 0x005d1e00, 0x005b1800, 0x00581400, 0x005a0e00, 0x00742000, 0x008b3008, 0x00a04119, 0x00a94920, 0x00aa471d, 0x00a84418, 0x00ac4416, 0x00af4715, 0x00b44a14, 0x00b0450b, 0x00b94c0e, 0x00c45813, 0x00c4560d, 0x00c05105, 0x00c45405, 0x00c05910, 0x00b35a23, 0x0088421d, 0x004c1c05, 0x00190000, 0x00060000, 0x00000103, 0x00010604, 0x00131a16, 0x00696f69, 0x00b4b8b3, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0078807f, 0x00232324, 0x000b0403, 0x000c0100, 0x000f0000, 0x00150000, 0x00331000, 0x006c3814, 0x00975224, 0x00b15722, 0x00be551c, 0x00c65418, 0x00c75111, 0x00c65211, 0x00bc4c0c, 0x00b44c0d, 0x00b0480c, 0x00b24a0e, 0x00b04b14, 0x00a44815, 0x00a1491a, 0x00a34c1f, 0x00a4481b, 0x00ac4718, 0x00ae4614, 0x00ac4612, 0x00ab4714, 0x00a84817, 0x00a84817, 0x00ad4714, 0x00ad4714, 0x00ac4817, 0x00aa4814, 0x00ab4810, 0x00ac480b, 0x00b14808, 0x00b74a05, 0x00bd4c04, 0x00c24e04, 0x00c85206, 0x00c85206, 0x00ca580e, 0x00c85a13, 0x00c05710, 0x00bc5714, 0x00b85716, 0x00a55219, 0x0084431b, 0x00461800, 0x001e0000, 0x00100000, 0x00030000, 0x00000001, 0x00040708, 0x001c1d1f, 0x00717070, 0x00444343, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0095938f, 0x002f3029, 0x00000800, 0x00000200, 0x00090400, 0x000d0000, 0x00290c00, 0x005e402f, 0x00553f36, 0x00281512, 0x00140000, 0x00140000, 0x00360a00, 0x00743b18, 0x009e5d33, 0x009c5e34, 0x00734120, 0x00320e00, 0x00190200, 0x00392722, 0x00412d29, 0x001e0a04, 0x000c0000, 0x00140800, 0x000a0000, 0x000b0000, 0x000f0000, 0x00130000, 0x00140000, 0x00280400, 0x003c1004, 0x00501c0e, 0x00642c18, 0x006c331f, 0x006c311d, 0x00662c18, 0x00642c18, 0x00642c18, 0x005c210c, 0x00581d08, 0x00501703, 0x00451000, 0x003c0800, 0x00340000, 0x002e0000, 0x002c0000, 0x002e0000, 0x00340000, 0x00400700, 0x00501400, 0x00642506, 0x007b3815, 0x008e4924, 0x009c502a, 0x00a34b24, 0x00a64820, 0x00a6461e, 0x00a6461e, 0x00ab481e, 0x00af4a1c, 0x00b04814, 0x00b0450c, 0x00b34505, 0x00c45410, 0x00c2540c, 0x00ba4e04, 0x00c05910, 0x00c05d17, 0x00b85814, 0x00b05a20, 0x007b3810, 0x003c0c00, 0x00140000, 0x00080000, 0x00040408, 0x00000005, 0x00181d1d, 0x0070746f, 0x00787b78, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009e9f9b, 0x003c3834, 0x00130c06, 0x00050000, 0x00080000, 0x00120400, 0x001a0000, 0x003d1200, 0x00783710, 0x00a85426, 0x00b85720, 0x00bf551a, 0x00c55b1d, 0x00c05413, 0x00c35715, 0x00c05310, 0x00c04f0d, 0x00bd4d0e, 0x00b54d11, 0x00b04f14, 0x00ac4d17, 0x00ab4914, 0x00ae4712, 0x00b04610, 0x00b04710, 0x00ad4810, 0x00ac4813, 0x00ae4811, 0x00b2470e, 0x00b4460c, 0x00b0480e, 0x00b14c10, 0x00b65010, 0x00bb540f, 0x00be550c, 0x00c15608, 0x00c45406, 0x00c85405, 0x00cc5a0c, 0x00c14f04, 0x00c0540f, 0x00bb5717, 0x00ac531a, 0x00a85824, 0x008c4718, 0x00541c00, 0x00200000, 0x00130000, 0x00080000, 0x00020000, 0x00010407, 0x00010508, 0x00323536, 0x008d8f8e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00acaea7, 0x004a4f45, 0x00020400, 0x00000000, 0x00030000, 0x00060000, 0x00100400, 0x00331f19, 0x004d3630, 0x00402825, 0x00230806, 0x00180000, 0x00230000, 0x00511c04, 0x00814324, 0x00a1603b, 0x00935532, 0x005a280c, 0x00280000, 0x00301304, 0x0065493a, 0x006b4a32, 0x00381700, 0x001d0100, 0x001c0600, 0x000d0000, 0x000c0000, 0x00100000, 0x000e0000, 0x00140000, 0x00160000, 0x00160000, 0x00160000, 0x00150000, 0x00140000, 0x00110000, 0x00110000, 0x00140000, 0x00170000, 0x00190000, 0x001d0000, 0x00280000, 0x003b0600, 0x00501300, 0x00601c08, 0x007e351e, 0x00893c21, 0x00944428, 0x009d4b2a, 0x00a04d29, 0x009f4d26, 0x009e4c25, 0x00a04b21, 0x00a6461c, 0x00aa471c, 0x00aa471c, 0x00a84518, 0x00a84515, 0x00b04a13, 0x00ba5010, 0x00c4540e, 0x00cc580c, 0x00ca5708, 0x00c95b0c, 0x00c05910, 0x00b55b1c, 0x00b0612d, 0x008c481d, 0x00501b00, 0x00230000, 0x00130000, 0x000a0000, 0x00080303, 0x00000003, 0x0028292d, 0x00878588, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008e8e89, 0x00716e67, 0x001e1812, 0x00040000, 0x00050000, 0x00080000, 0x00100000, 0x001d0100, 0x00340c00, 0x00662d08, 0x00985024, 0x00af5b27, 0x00ba581c, 0x00c0540f, 0x00cb570c, 0x00cc570c, 0x00c8540a, 0x00c7540c, 0x00c4540d, 0x00c35411, 0x00c45514, 0x00c25213, 0x00c15114, 0x00bf5214, 0x00bc5213, 0x00be5211, 0x00c15211, 0x00c6510f, 0x00c8500d, 0x00c8530f, 0x00c65410, 0x00c4540e, 0x00c3550a, 0x00c05508, 0x00c05707, 0x00c35808, 0x00c25a0f, 0x00b8520c, 0x00c05e20, 0x00b6602c, 0x009d542a, 0x00773e1c, 0x00411700, 0x00180000, 0x00100000, 0x000d0100, 0x00040000, 0x00040203, 0x00000001, 0x000e1112, 0x005e605f, 0x00acacaa, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b4b0, 0x00787874, 0x00181513, 0x00020001, 0x00000107, 0x00000003, 0x000b0000, 0x001b0703, 0x002d1716, 0x003a2326, 0x002f1b20, 0x001e0405, 0x001f0000, 0x003c0c00, 0x00612809, 0x008a4e2c, 0x00986041, 0x006c3c21, 0x00360d00, 0x00250000, 0x00482004, 0x00754d31, 0x007b5740, 0x00573723, 0x00391c0c, 0x00240900, 0x00180000, 0x00180000, 0x00180000, 0x00180000, 0x00180000, 0x001c0000, 0x001c0000, 0x00180000, 0x00170000, 0x00180000, 0x00301400, 0x00401d01, 0x00572d10, 0x006b3b1d, 0x007d4425, 0x00894727, 0x00944828, 0x009c4826, 0x009f4421, 0x00a44620, 0x00aa4820, 0x00ac481f, 0x00a8451a, 0x00a44416, 0x00a44315, 0x00a64414, 0x00ab4410, 0x00b04812, 0x00b64d17, 0x00b95018, 0x00bd5418, 0x00c15514, 0x00c3540d, 0x00c15206, 0x00c35304, 0x00bf5507, 0x00bb5810, 0x00b25c20, 0x00985024, 0x00642b0b, 0x00330800, 0x001b0000, 0x00100000, 0x00060000, 0x00050100, 0x00080503, 0x00424043, 0x009d9ca0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00323231, 0x00a4a29e, 0x004c4848, 0x00121013, 0x00030206, 0x00000001, 0x00030000, 0x000a0000, 0x001b0100, 0x00300800, 0x004c1500, 0x007c360b, 0x00a5511c, 0x00b5581c, 0x00bb5a1b, 0x00bc5816, 0x00c15817, 0x00c15815, 0x00bf5513, 0x00c25816, 0x00c15815, 0x00c05715, 0x00c05614, 0x00c05414, 0x00c15413, 0x00c45412, 0x00c65410, 0x00c85510, 0x00cb5813, 0x00c75713, 0x00c35814, 0x00be5915, 0x00bb5a18, 0x00b65c1b, 0x00b25c1e, 0x00af5d24, 0x00a55724, 0x00833d13, 0x00581c00, 0x00350600, 0x001f0000, 0x00110000, 0x00060000, 0x00000001, 0x00000004, 0x00000004, 0x00040709, 0x003b3e3f, 0x00949594, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00201f20, 0x00a49a95, 0x00534c48, 0x00010108, 0x0000020c, 0x00000005, 0x00040001, 0x000b0104, 0x0014080b, 0x001b0f11, 0x00201414, 0x001b0c0b, 0x00160400, 0x00200600, 0x00341404, 0x005a301d, 0x00865640, 0x0088543b, 0x00602e15, 0x00300800, 0x00320d00, 0x00502810, 0x0076492f, 0x008c593b, 0x008c5735, 0x00814825, 0x00733a15, 0x00683009, 0x00652c04, 0x00622900, 0x00662a00, 0x00703001, 0x007d3c0a, 0x008c4814, 0x0099501a, 0x009c4c18, 0x00a04c18, 0x00a24c18, 0x00a34c18, 0x00a54b16, 0x00a84b15, 0x00ac4a14, 0x00ae4a14, 0x00b04812, 0x00b04810, 0x00b1460d, 0x00b3450d, 0x00b4470f, 0x00b94a13, 0x00bf5018, 0x00c25418, 0x00c25312, 0x00c2540d, 0x00c45009, 0x00c45007, 0x00c75004, 0x00c95405, 0x00c95809, 0x00c4590d, 0x00b95811, 0x00b56120, 0x0098501e, 0x00652d06, 0x003c1000, 0x00210300, 0x00130000, 0x00080000, 0x00040001, 0x00000000, 0x0014110a, 0x006a6860, 0x00b5b2b0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0087878d, 0x003e4046, 0x00111418, 0x00000402, 0x00000300, 0x00040100, 0x000c0200, 0x00100000, 0x001b0200, 0x00270900, 0x003f1800, 0x005a2809, 0x00783b16, 0x00974d24, 0x00a65627, 0x00aa5822, 0x00ae5b20, 0x00b05b1b, 0x00b45a1a, 0x00bb581b, 0x00c0581c, 0x00c2571c, 0x00c1581c, 0x00bc5a18, 0x00ba5918, 0x00bb5619, 0x00b9571f, 0x00b55a28, 0x00aa5a2a, 0x00985228, 0x007c411c, 0x00602c0c, 0x004c1f04, 0x00330b00, 0x00260400, 0x001c0000, 0x00170000, 0x00100000, 0x00060000, 0x00020000, 0x00050408, 0x00030408, 0x0035383b, 0x007e7e80, 0x00b1b1b0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b2aca8, 0x00878788, 0x00313439, 0x0003050b, 0x00040408, 0x00020003, 0x00030000, 0x000b0606, 0x00080404, 0x000b090a, 0x00030102, 0x000a0200, 0x00130400, 0x00190000, 0x00351000, 0x0061341e, 0x00784a34, 0x00714c3d, 0x004d291a, 0x00330b00, 0x00390c00, 0x00582408, 0x007b4422, 0x00935832, 0x009d5d34, 0x009a582c, 0x009d5626, 0x00a05520, 0x00a4551b, 0x00ac5718, 0x00b65a18, 0x00bb5c14, 0x00be5a12, 0x00c35814, 0x00c45513, 0x00c25310, 0x00c05310, 0x00be530f, 0x00be530d, 0x00bf540e, 0x00c0530e, 0x00bd500c, 0x00c0500c, 0x00c2520c, 0x00c4520d, 0x00c65210, 0x00c75210, 0x00c7500e, 0x00c44f0b, 0x00c4540a, 0x00c5560a, 0x00c8580c, 0x00c7560c, 0x00c6550d, 0x00c15610, 0x00b95514, 0x00ae561a, 0x00914814, 0x00602600, 0x003c1100, 0x00260800, 0x00120000, 0x00080000, 0x00070006, 0x00000007, 0x00000004, 0x003a3d3c, 0x008c8e87, 0x00b5b7ae, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00adb0b5, 0x007c8083, 0x00424648, 0x00141818, 0x00000100, 0x00000000, 0x00000000, 0x00040301, 0x00020000, 0x000b0200, 0x00180500, 0x00250700, 0x00360900, 0x00431000, 0x00501b00, 0x00602800, 0x006a3002, 0x00713203, 0x007c3307, 0x00823408, 0x0085340b, 0x00813408, 0x00793404, 0x00763303, 0x00722c01, 0x00692400, 0x00571900, 0x00451000, 0x00360b00, 0x00280700, 0x001c0300, 0x00140000, 0x000c0000, 0x000a0000, 0x00050000, 0x00040000, 0x00060302, 0x00000000, 0x000c0b0d, 0x00353438, 0x00808084, 0x00a4a4a6, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a49d, 0x006e6f6b, 0x00323431, 0x00090909, 0x00000000, 0x00000201, 0x00000000, 0x00000001, 0x00040504, 0x00010000, 0x00040000, 0x000c0000, 0x00140300, 0x001d0800, 0x002d1208, 0x004c291f, 0x005c372c, 0x00553229, 0x003b1b13, 0x002a0a02, 0x002d0c00, 0x00441d0b, 0x005f3016, 0x00864c29, 0x009c572c, 0x00b1602b, 0x00b85e23, 0x00b85817, 0x00bc5411, 0x00be550f, 0x00c0540c, 0x00c4540c, 0x00c6540a, 0x00c7540b, 0x00c6560a, 0x00c6570b, 0x00c5580b, 0x00c55809, 0x00c55809, 0x00c6590a, 0x00c6590a, 0x00c65809, 0x00c65608, 0x00c85508, 0x00c85508, 0x00cb5509, 0x00c8560b, 0x00c6580d, 0x00c0570f, 0x00bb5514, 0x00b8581d, 0x00b05826, 0x009b4d24, 0x00773515, 0x00562208, 0x00320c00, 0x00230800, 0x000c0000, 0x00060000, 0x00070300, 0x00010000, 0x00040404, 0x00181618, 0x006c666c, 0x00a7a5a9, 0x00434546, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00abaaae, 0x008c8b8f, 0x00646064, 0x002a2629, 0x00080405, 0x00040301, 0x00030200, 0x00020000, 0x00040000, 0x000b0200, 0x000c0000, 0x000e0000, 0x00120000, 0x00180200, 0x001b0400, 0x001f0600, 0x00240800, 0x00280a00, 0x00290b00, 0x00280a00, 0x00250800, 0x00230700, 0x001f0500, 0x001b0200, 0x00150000, 0x00100000, 0x000c0000, 0x00070000, 0x00040000, 0x00020000, 0x00010200, 0x00000000, 0x00000200, 0x00080905, 0x001c1e1c, 0x00515151, 0x008a8a8c, 0x00a6a4a7, 0x000c0c0c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007c7c78, 0x009e9f9b, 0x00777876, 0x00404443, 0x00121516, 0x00000304, 0x00000203, 0x00000201, 0x00000100, 0x00010000, 0x00040000, 0x00040000, 0x00040000, 0x000a0000, 0x001b0300, 0x00270b06, 0x002b1311, 0x00210e0e, 0x000f0000, 0x000b0000, 0x00180200, 0x00260800, 0x003c1100, 0x00541e00, 0x00702e06, 0x00883c0e, 0x00a04d18, 0x00b35c26, 0x00b85f28, 0x00b75a20, 0x00bc5818, 0x00bf5815, 0x00c05814, 0x00bf5814, 0x00bc5812, 0x00bc5810, 0x00bc580f, 0x00bd5910, 0x00bc580f, 0x00bd5911, 0x00bd5911, 0x00bc5812, 0x00bc5812, 0x00bc5814, 0x00bd5815, 0x00ba5918, 0x00b15b20, 0x00a3541e, 0x008f4415, 0x0076340c, 0x005d2405, 0x00441400, 0x002c0700, 0x00180000, 0x000d0000, 0x00050000, 0x00040203, 0x00030404, 0x00000000, 0x00151916, 0x00585a58, 0x00959493, 0x00585457, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b5b0b5, 0x009e989e, 0x00807c7f, 0x00555454, 0x002b2b29, 0x00101010, 0x00000003, 0x00000001, 0x00000000, 0x00030200, 0x00050300, 0x00040000, 0x00030000, 0x00030000, 0x00030000, 0x00030000, 0x00040000, 0x00040000, 0x00050000, 0x00050000, 0x00020000, 0x00000000, 0x00010000, 0x00000000, 0x00000003, 0x00000003, 0x00000104, 0x00000305, 0x00090e0e, 0x00242b28, 0x00494e4b, 0x006f7470, 0x00949895, 0x00afb0b0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a5a4, 0x00808180, 0x00606261, 0x00343635, 0x00161817, 0x00000000, 0x00000000, 0x00040301, 0x00010000, 0x00000000, 0x00040000, 0x00070000, 0x00080000, 0x00080001, 0x00050002, 0x00030000, 0x00020000, 0x00040000, 0x00090000, 0x000c0000, 0x00170100, 0x00270a00, 0x00341000, 0x00411800, 0x0051240a, 0x00603116, 0x00703819, 0x00864018, 0x00924418, 0x009c4c1f, 0x00a15121, 0x00a75524, 0x00aa5825, 0x00ac5924, 0x00ab5823, 0x00ac5924, 0x00a95824, 0x00a55525, 0x009f5222, 0x00984c1f, 0x008b4218, 0x007f370f, 0x006f310e, 0x00512609, 0x0041200a, 0x00341702, 0x00280c00, 0x00190200, 0x00100000, 0x000c0000, 0x00060000, 0x00030000, 0x00000000, 0x00070708, 0x00222423, 0x00535454, 0x00868885, 0x00afafad, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b0b0b0, 0x00949494, 0x00838383, 0x00686869, 0x004c4c4c, 0x00343434, 0x0020201e, 0x00100f0d, 0x00050403, 0x00000000, 0x00000000, 0x00010000, 0x00010000, 0x00010000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x000d0d0d, 0x001a1a1c, 0x002f2f30, 0x004b4c4d, 0x00616264, 0x007f8080, 0x00909190, 0x00a8aaa9, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b0b0b0, 0x00949494, 0x007e7e7e, 0x00616161, 0x00444444, 0x00292929, 0x00101010, 0x00020202, 0x00000000, 0x00000002, 0x00000001, 0x00000003, 0x00000001, 0x00000001, 0x00000102, 0x00000201, 0x00020200, 0x00000000, 0x00040000, 0x00060000, 0x000b0000, 0x000f0000, 0x00130000, 0x001c0400, 0x00280a00, 0x00391000, 0x00441500, 0x004d1b00, 0x00521f02, 0x00572003, 0x005b2403, 0x005e2504, 0x005e2504, 0x005e2504, 0x00582203, 0x00532003, 0x004e1e03, 0x00481a02, 0x003f1400, 0x00340c00, 0x00280700, 0x00170500, 0x000a0000, 0x00060000, 0x00050000, 0x00060200, 0x00040100, 0x00000000, 0x00000000, 0x00101113, 0x00303133, 0x005c5c5e, 0x00878889, 0x00aeaeae, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00787878, 0x00a7a7a7, 0x00989898, 0x00888888, 0x00787878, 0x006d6d6d, 0x00606060, 0x005a5a5a, 0x00525252, 0x004b4b4b, 0x00484848, 0x00494949, 0x004d4d4d, 0x00505050, 0x00585858, 0x005e5e5e, 0x006b6b6b, 0x00797979, 0x00858585, 0x00939393, 0x00a5a5a5, 0x00acacac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009b9b9b, 0x00a0a0a0, 0x008a8a8a, 0x00757575, 0x00636363, 0x00585858, 0x00454444, 0x003b3b3b, 0x002f2f30, 0x00262728, 0x00212224, 0x00202022, 0x001f2020, 0x0020211f, 0x00242422, 0x0014110f, 0x00060000, 0x00060000, 0x00090000, 0x000c0000, 0x000c0000, 0x000c0000, 0x000c0000, 0x000c0000, 0x000e0000, 0x000e0000, 0x00100000, 0x00120000, 0x00140000, 0x00160000, 0x00140000, 0x00100000, 0x000d0000, 0x000c0000, 0x000a0000, 0x00090000, 0x00080000, 0x00070000, 0x00060000, 0x00080000, 0x00080000, 0x00050000, 0x00050100, 0x000f0c09, 0x00292827, 0x004a4a4a, 0x006a6b6c, 0x008f9091, 0x009b9c9d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00313131, 0x00898989, 0x00afafaf, 0x00a8a8a8, 0x00a6a6a6, 0x00a6a6a6, 0x00a9a9a9, 0x00acacac, 0x00b0b0b0, 0x00898989, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b3b3b3, 0x00a6a5a4, 0x009c9b99, 0x008f8f8d, 0x00868686, 0x00818382, 0x00808082, 0x00808082, 0x00818382, 0x00797979, 0x006a6a68, 0x00555251, 0x003e3a38, 0x0028231e, 0x00150e08, 0x000b0200, 0x00060000, 0x00000000, 0x00000000, 0x00000000, 0x00020100, 0x00040200, 0x00050100, 0x00040000, 0x00030000, 0x00040000, 0x00040100, 0x00030200, 0x00020200, 0x00000203, 0x00000003, 0x00000104, 0x00000001, 0x00030000, 0x00130c08, 0x00241e19, 0x00373330, 0x00524f4c, 0x006a6968, 0x00888888, 0x00a9a9a9, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009b9b9c, 0x009b9b9b, 0x007f7d7e, 0x00646462, 0x004e4d4c, 0x00403f3d, 0x00373538, 0x002d2c30, 0x00222023, 0x0019181a, 0x00161314, 0x00131010, 0x00100d0e, 0x000e0b0a, 0x00100c0d, 0x00120f10, 0x00141315, 0x0018181c, 0x001f1e23, 0x0028282f, 0x0033353b, 0x003d3e41, 0x00504d4c, 0x0066625f, 0x007c7875, 0x00969390, 0x00b5b2b1, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00acadaf, 0x009c9ca0, 0x00908e92, 0x007d7c7e, 0x00706e70, 0x00686668, 0x00646264, 0x00616062, 0x00616062, 0x00605e62, 0x00626064, 0x00666569, 0x006c6c70, 0x0078777c, 0x0089888d, 0x009c9da1, 0x00abaaae, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000}; \ No newline at end of file diff --git a/include/utils/command_structure/auto_command.h b/include/utils/command_structure/auto_command.h index 532fcbe..c8f1cbf 100644 --- a/include/utils/command_structure/auto_command.h +++ b/include/utils/command_structure/auto_command.h @@ -33,6 +33,6 @@ class AutoCommand { * - a command that waits until something is up to speed that never gets up to speed because of battery voltage * - something else... */ - double timeout_seconds; + double timeout_seconds = 10.0; }; \ No newline at end of file diff --git a/include/utils/command_structure/command_controller.h b/include/utils/command_structure/command_controller.h index a78abbf..3d270d7 100644 --- a/include/utils/command_structure/command_controller.h +++ b/include/utils/command_structure/command_controller.h @@ -20,7 +20,7 @@ class CommandController { * @param cmd the AutoCommand we want to add to our list * @param timeout_seconds the number of seconds we will let the command run for. If it exceeds this, we cancel it and run on_timeout. if it is <= 0 no time out will be applied */ - void add(AutoCommand *cmd, double timeout_seconds = 0); + void add(AutoCommand *cmd, double timeout_seconds = 10.0); /** * Add multiple commands to the queue. No timeout here. From 227982abb80ffde7ffaf23035b6640d22fd0bab2 Mon Sep 17 00:00:00 2001 From: cowsed Date: Mon, 20 Feb 2023 20:24:32 -0500 Subject: [PATCH 178/243] use splash.h rather than intense_milk.h --- include/splash.h | 5 +++++ 1 file changed, 5 insertions(+) create mode 100644 include/splash.h diff --git a/include/splash.h b/include/splash.h new file mode 100644 index 0000000..bc02f97 --- /dev/null +++ b/include/splash.h @@ -0,0 +1,5 @@ +#include +// file: clu.png +int intense_milk_width = 420; +int intense_milk_height = 246; +uint32_t intense_milk[103320] = {0x00152021, 0x00141f21, 0x00141d20, 0x00131d1f, 0x00131e1e, 0x00131e1e, 0x00141f1f, 0x00141f1f, 0x00141e20, 0x00131d1f, 0x00131d1f, 0x00131d1e, 0x00121c1c, 0x00111c1c, 0x00111c1a, 0x00111c1a, 0x00111c1a, 0x00111b19, 0x00111b19, 0x00111b19, 0x00111b19, 0x00101918, 0x00101918, 0x00101918, 0x00101918, 0x00101916, 0x00101916, 0x00101818, 0x00101817, 0x00101817, 0x00101817, 0x00101817, 0x00101817, 0x000f1817, 0x000f1816, 0x000e1816, 0x000d1714, 0x000d1714, 0x000d1714, 0x000c1613, 0x000c1512, 0x000c1512, 0x000e1611, 0x000e1611, 0x000e1611, 0x000e1511, 0x000d1410, 0x000c1410, 0x000c1410, 0x000c1410, 0x000c1410, 0x000c1410, 0x000c1410, 0x000c140f, 0x000c140e, 0x000c140d, 0x000c140d, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000f1310, 0x000d140e, 0x000d140e, 0x000c140c, 0x000c140c, 0x000c140c, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140f, 0x000b1410, 0x000b1510, 0x000c1510, 0x000c1511, 0x000c1512, 0x000c1610, 0x000c1611, 0x000c1710, 0x000f1610, 0x00101811, 0x000f1814, 0x00101914, 0x00101a17, 0x00101a17, 0x00101916, 0x00101915, 0x00101918, 0x00101918, 0x00101918, 0x000f1a18, 0x000f1b18, 0x000e1c19, 0x000c1d19, 0x000c1c19, 0x000d1c19, 0x000d1c19, 0x000d1c19, 0x000f1c19, 0x000e1b18, 0x000e1918, 0x000f1a18, 0x000f1a18, 0x00111c1a, 0x00121b18, 0x00111c18, 0x00101b17, 0x00141c19, 0x002d3030, 0x00454545, 0x00403e3e, 0x00444040, 0x00484446, 0x004a4649, 0x004a484b, 0x00494448, 0x004a4244, 0x004b4040, 0x004a3d3b, 0x004c3e3a, 0x0050403c, 0x004c3b35, 0x00493833, 0x00473530, 0x00473630, 0x0045322e, 0x00473430, 0x00413831, 0x0039322c, 0x00342c26, 0x00322b25, 0x0038332c, 0x00372e26, 0x003a2a22, 0x00412c23, 0x003e1e15, 0x00401b10, 0x003d1c0d, 0x003a1e09, 0x00462812, 0x0050301a, 0x004c2c16, 0x004e2c1a, 0x004f2c1c, 0x00492515, 0x00442210, 0x004c2e18, 0x00573a1f, 0x005e3419, 0x0064391c, 0x00673b1a, 0x00633914, 0x00643a18, 0x00532b0a, 0x004e2508, 0x00532a10, 0x005c3418, 0x005e3818, 0x00603a1a, 0x005c3515, 0x00573113, 0x00593417, 0x00583416, 0x005a3414, 0x005d3716, 0x00613819, 0x00643c1c, 0x006c4220, 0x00673d18, 0x00653c16, 0x00633a16, 0x00603414, 0x00633815, 0x00683c18, 0x006e441c, 0x006e421b, 0x00643910, 0x006a3f18, 0x005b320b, 0x00643c15, 0x00633b16, 0x00613b16, 0x00603a16, 0x005d3818, 0x00583414, 0x005b3518, 0x004c280b, 0x004a2508, 0x00502b0c, 0x005c3416, 0x00613719, 0x0061371a, 0x005e3716, 0x00502c0b, 0x003c220c, 0x00311c0c, 0x00261810, 0x00201414, 0x0017140d, 0x00141509, 0x0015160c, 0x001a1a10, 0x0018170f, 0x00191910, 0x0018180f, 0x0016160d, 0x0016160d, 0x0016160d, 0x0016160d, 0x0015170c, 0x0018160c, 0x001a160c, 0x00201810, 0x00281d16, 0x00342720, 0x00302a24, 0x00312924, 0x00302b24, 0x00282a20, 0x001b2420, 0x00182623, 0x00182824, 0x00152824, 0x00152824, 0x00152724, 0x00172625, 0x00182627, 0x00182627, 0x00182627, 0x00172526, 0x00162424, 0x00162425, 0x00172526, 0x00182526, 0x00172524, 0x00162423, 0x00152420, 0x00142320, 0x00152220, 0x0013201d, 0x00131f1e, 0x0013201f, 0x00121f1e, 0x00101d1d, 0x00101c1c, 0x000f1c1b, 0x00101b1b, 0x00101a1a, 0x000f1819, 0x000f1818, 0x000e1814, 0x000e1611, 0x000e170f, 0x000e170e, 0x000e1610, 0x00101610, 0x00101610, 0x00101610, 0x00101510, 0x0010140f, 0x000e140e, 0x000d140e, 0x000c140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000e140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1417, 0x000b1517, 0x00091416, 0x000a1417, 0x000b1616, 0x000c1716, 0x000c1716, 0x000c1717, 0x000c1718, 0x000c1819, 0x000d1819, 0x000d1818, 0x000c1818, 0x000c1716, 0x000c1715, 0x000c1715, 0x000c1715, 0x000c1514, 0x000c1514, 0x000c1514, 0x000c1514, 0x000b1413, 0x000b1413, 0x000b1413, 0x000b1413, 0x000a1410, 0x000a1410, 0x00091211, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081010, 0x0008100f, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00040e0b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d07, 0x00050d07, 0x00050d06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c08, 0x00060c07, 0x00060c07, 0x00050d05, 0x00050d05, 0x00050d05, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040f09, 0x00040f0a, 0x00040f0b, 0x00050f0a, 0x0005100a, 0x00061008, 0x00070f08, 0x00070f08, 0x0005100a, 0x0006100b, 0x0006100c, 0x0007110d, 0x0008120f, 0x0008120f, 0x00091311, 0x00091311, 0x00091311, 0x00081311, 0x00081412, 0x00071512, 0x00051612, 0x00061612, 0x00061512, 0x00061512, 0x00071512, 0x00081412, 0x00081411, 0x00081311, 0x00081311, 0x00081311, 0x000a1613, 0x000b1411, 0x000c1613, 0x000c1310, 0x001c2220, 0x00343734, 0x00343433, 0x00302c2c, 0x003a3436, 0x00464042, 0x00403c3d, 0x00393436, 0x003b3537, 0x003e3536, 0x003c3130, 0x003a2d2a, 0x003e2f29, 0x0044352f, 0x00483831, 0x003e2d26, 0x0032211a, 0x002d1c14, 0x00301d16, 0x0033241c, 0x0034271f, 0x00332820, 0x00342920, 0x002e241c, 0x00281e15, 0x00302219, 0x00342118, 0x00341e13, 0x00402216, 0x00472515, 0x00452513, 0x00371802, 0x00381802, 0x003a1a06, 0x00452410, 0x004c2c14, 0x004d2b14, 0x00502d15, 0x004c2a10, 0x00432304, 0x004c2d0e, 0x005d3315, 0x00603415, 0x00603514, 0x00623814, 0x005f3612, 0x005a320f, 0x004f2708, 0x00482001, 0x004c2406, 0x005b3414, 0x005a3413, 0x00552f10, 0x004f280b, 0x00441f04, 0x004d280b, 0x00583113, 0x005b3414, 0x005f3715, 0x00613a16, 0x00694019, 0x00643c14, 0x00653c14, 0x00633915, 0x00582e0d, 0x00582e0d, 0x00613612, 0x00683d18, 0x00633811, 0x00643813, 0x00603610, 0x005b320c, 0x00603711, 0x005d3510, 0x005d3611, 0x005d3814, 0x005c3616, 0x00583314, 0x00542f11, 0x00462104, 0x00421d00, 0x00553013, 0x005b3416, 0x00633a1c, 0x005c3416, 0x00542f10, 0x00472407, 0x00341904, 0x002c1709, 0x0021120a, 0x001b100d, 0x0016110b, 0x00151409, 0x00141309, 0x0018170e, 0x00131108, 0x00121007, 0x00121007, 0x00111108, 0x00111108, 0x00111108, 0x00111108, 0x00101206, 0x00101105, 0x00100e04, 0x00161007, 0x00191008, 0x001e140c, 0x00241c15, 0x00251c16, 0x0028211a, 0x0026271e, 0x0018201c, 0x0014201d, 0x0010201d, 0x000f211c, 0x000f201d, 0x0010201f, 0x0010201f, 0x00101f20, 0x00112020, 0x00112020, 0x00122021, 0x00112020, 0x00101f20, 0x00101e1f, 0x000f1d1e, 0x000f1d1c, 0x000d1c1b, 0x000c1c18, 0x000c1b18, 0x000d1a18, 0x000a1814, 0x000a1716, 0x000a1716, 0x00091615, 0x00081514, 0x00081414, 0x00071413, 0x00071313, 0x00071212, 0x00061111, 0x00061010, 0x00050f0c, 0x00060e09, 0x00060e06, 0x00060e06, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c07, 0x00050c06, 0x00050c06, 0x00040c06, 0x00040c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060b06, 0x00060b06, 0x00060b06, 0x00060b06, 0x00060b06, 0x00060b06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000b1517, 0x000b1517, 0x00091416, 0x00081415, 0x000a1414, 0x000a1414, 0x000a1414, 0x000a1414, 0x000b1516, 0x000b1517, 0x000b1517, 0x000b1516, 0x000b1515, 0x000a1414, 0x000a1513, 0x000b1413, 0x000b1413, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x00091211, 0x00091211, 0x0008120f, 0x0008120f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0006100e, 0x0006100d, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x00050c0a, 0x00060d0b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c09, 0x00070d08, 0x00070d08, 0x00060e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d09, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00060e09, 0x00060e09, 0x0005100a, 0x0005100a, 0x0006100c, 0x0007110d, 0x0007110d, 0x0008120f, 0x00091211, 0x00091211, 0x000a1412, 0x00081412, 0x00081413, 0x00081613, 0x00061512, 0x00061512, 0x00061512, 0x00061512, 0x00061512, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x000a1410, 0x000c1310, 0x00171b19, 0x00292c2b, 0x002e2d2c, 0x002c2828, 0x00393433, 0x00484041, 0x004e4545, 0x00474040, 0x003f3838, 0x00372e2d, 0x00312524, 0x00322420, 0x0034241e, 0x0034241c, 0x00312319, 0x003b2b22, 0x0044332a, 0x00402f25, 0x002e1e14, 0x002c190e, 0x0028170c, 0x0029180d, 0x002a190d, 0x002c1b10, 0x00312015, 0x00342219, 0x002c1910, 0x002c180c, 0x00341f10, 0x00381e0e, 0x00482816, 0x0052311c, 0x00502f17, 0x0041200b, 0x003d1c08, 0x003e1c08, 0x0045250e, 0x00503017, 0x004e2c11, 0x00502d10, 0x00563114, 0x004a2404, 0x00522808, 0x005e3214, 0x00592d0c, 0x00603611, 0x00643b14, 0x00633a14, 0x005c3411, 0x00502808, 0x00502808, 0x00542c0c, 0x005c3414, 0x00532c0c, 0x00451f04, 0x0048210c, 0x00462007, 0x00552f12, 0x005c3516, 0x005e3713, 0x00623b13, 0x00653c13, 0x00643c11, 0x00613810, 0x00623814, 0x00552c0a, 0x00522807, 0x00613817, 0x00653c18, 0x00582f0c, 0x005e3411, 0x005c330e, 0x005c340e, 0x005c340f, 0x005a330d, 0x0058310d, 0x005c3513, 0x00583112, 0x00583315, 0x00502b0f, 0x00462003, 0x00512c0f, 0x00563013, 0x005e3819, 0x0060391b, 0x005b3518, 0x0049260d, 0x003c1a03, 0x00301707, 0x00281307, 0x0023140b, 0x001d130c, 0x0019140c, 0x0019160c, 0x0018140c, 0x0016120a, 0x0014110a, 0x00141109, 0x00121008, 0x00131209, 0x0013130a, 0x00131209, 0x00131209, 0x00111308, 0x00101207, 0x000f1004, 0x00131006, 0x00161008, 0x00181108, 0x001c130c, 0x00271a15, 0x00251b15, 0x00242119, 0x001d231e, 0x00141d1c, 0x00121f1c, 0x0010201c, 0x0010201d, 0x0010201f, 0x00112020, 0x00122021, 0x00122021, 0x00112020, 0x00101f20, 0x00101e1f, 0x00101e1f, 0x00101e1f, 0x00101e1f, 0x000f1d1c, 0x000e1c1b, 0x000c1b18, 0x000b1a17, 0x000b1816, 0x000a1814, 0x00091615, 0x00091615, 0x000a1514, 0x000a1414, 0x00081414, 0x00081313, 0x00081212, 0x00071010, 0x00061010, 0x0006100f, 0x00050f0c, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000b1517, 0x000b1517, 0x00091416, 0x00081414, 0x000a1414, 0x000a1513, 0x000a1414, 0x000a1414, 0x000b1515, 0x000b1515, 0x000b1515, 0x000b1515, 0x000b1515, 0x000a1414, 0x000a1513, 0x000b1413, 0x000b1413, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091310, 0x00091310, 0x00091310, 0x0008120f, 0x0008120f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0006100e, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00040e09, 0x00050d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d08, 0x00070d08, 0x00060e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d09, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100c, 0x0007110d, 0x0007110d, 0x0008120f, 0x00091310, 0x00091310, 0x000a1412, 0x00081412, 0x00081413, 0x00081613, 0x00061512, 0x00061512, 0x00061512, 0x00061512, 0x00061512, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081410, 0x000a1410, 0x000c1210, 0x00101512, 0x001e201d, 0x00323030, 0x00464340, 0x00554d4c, 0x004f4645, 0x00443c3b, 0x00423838, 0x00403837, 0x003d3331, 0x003b2e2c, 0x00382924, 0x0034241c, 0x0034271c, 0x00392c22, 0x002f2217, 0x0034261a, 0x00433428, 0x00443428, 0x00312014, 0x00281608, 0x002b170a, 0x002a1808, 0x002b1708, 0x002c1609, 0x00331a10, 0x00371f14, 0x00321b0e, 0x002e1607, 0x00311905, 0x00442810, 0x004a2810, 0x00553218, 0x0058351a, 0x0046240c, 0x00391802, 0x003d1c07, 0x0043220e, 0x004f2c16, 0x00522e14, 0x004c260a, 0x005b3013, 0x0054280c, 0x00532909, 0x005d3210, 0x005c330d, 0x00623912, 0x00643b14, 0x00603813, 0x0059310d, 0x00532b09, 0x00532a09, 0x00583110, 0x00563010, 0x00452005, 0x00401905, 0x00442008, 0x0049240a, 0x00583114, 0x00643c15, 0x00633a11, 0x00653d11, 0x00643c10, 0x005e350c, 0x005e3510, 0x00512908, 0x004d2505, 0x00593210, 0x0055300e, 0x00542c0b, 0x005c3410, 0x00552e0a, 0x005f3713, 0x00562f0a, 0x0056300a, 0x0056300c, 0x00583210, 0x00542f10, 0x00553013, 0x004c280c, 0x00482306, 0x004e2b0d, 0x004f2c0e, 0x005b3718, 0x00573311, 0x00502c0e, 0x003c1a03, 0x00331604, 0x002d1408, 0x00251207, 0x0024140b, 0x001d140a, 0x00191309, 0x00181108, 0x001b150d, 0x001a150e, 0x00141009, 0x00100e06, 0x000f0e05, 0x000e0e05, 0x000e0e05, 0x000e0f06, 0x00101007, 0x00121107, 0x00131308, 0x00111308, 0x00141308, 0x00151308, 0x00181108, 0x001c120b, 0x0022150f, 0x00251b13, 0x00211d15, 0x0020241f, 0x00141e1b, 0x00101d1a, 0x0010201c, 0x0010201d, 0x0011201f, 0x00112020, 0x00122021, 0x00122021, 0x00112020, 0x00101f20, 0x00101e1f, 0x00101e1f, 0x00101e1d, 0x00101e1d, 0x000f1d1c, 0x000e1c1b, 0x000c1b18, 0x000b1a17, 0x000b1816, 0x000a1814, 0x00091615, 0x00091615, 0x000a1514, 0x000a1414, 0x00081414, 0x00081313, 0x00081212, 0x00071011, 0x00061010, 0x0006100e, 0x00050f0c, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1414, 0x00091414, 0x00081414, 0x00081313, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00091413, 0x000a1513, 0x000a1414, 0x000b1414, 0x000b1413, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x00091211, 0x00091310, 0x00091310, 0x00091310, 0x0008120f, 0x0008120f, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100d, 0x0006100e, 0x0006100d, 0x0006100c, 0x0006100c, 0x0008100c, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d05, 0x00040d07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008120d, 0x0008120d, 0x0007130f, 0x0007130f, 0x00081311, 0x00081311, 0x00081412, 0x00071512, 0x00061512, 0x00071512, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081510, 0x00081510, 0x00091410, 0x000f1514, 0x00101514, 0x00171c18, 0x00323633, 0x00424340, 0x004a4b48, 0x00424040, 0x00312e2c, 0x00302a28, 0x00342c2c, 0x00383132, 0x00413837, 0x003c3330, 0x003d342f, 0x00383128, 0x002f291e, 0x002f271d, 0x003c3128, 0x0033271e, 0x0035261d, 0x00403227, 0x00403126, 0x002c1c10, 0x00271708, 0x00291807, 0x002a1604, 0x002e1806, 0x00301709, 0x00351a0d, 0x00412718, 0x003e2411, 0x003e200c, 0x00401d08, 0x004c2910, 0x00512c10, 0x00543011, 0x00563315, 0x00462409, 0x00411f08, 0x003b1905, 0x003f1c0c, 0x004b2814, 0x004d2a10, 0x004c2807, 0x00553010, 0x00583212, 0x00562e0b, 0x005c320d, 0x0060350d, 0x00643b12, 0x00633a13, 0x00582f0b, 0x00552c0a, 0x00522b09, 0x00502a0b, 0x004e290c, 0x0045240a, 0x00351700, 0x003f1e09, 0x004b2813, 0x004c260c, 0x0068401b, 0x00623911, 0x00643b10, 0x00643c10, 0x005c350c, 0x005b3410, 0x004c2607, 0x00442105, 0x004c2a0e, 0x00462406, 0x004d280a, 0x00583212, 0x0055300f, 0x005a3412, 0x004d2804, 0x00542d0b, 0x004f2704, 0x00532c0c, 0x00522c0e, 0x00502c10, 0x00452409, 0x00482810, 0x00412008, 0x00492810, 0x004c2c11, 0x004a2c0f, 0x003e2106, 0x002e1300, 0x002c1404, 0x00291409, 0x0024120a, 0x0022150b, 0x001c140a, 0x00191408, 0x0018140b, 0x001e1a10, 0x00130f06, 0x00120f07, 0x00100f06, 0x000e0c04, 0x00121008, 0x0016140c, 0x0016140c, 0x00141309, 0x00141208, 0x00141208, 0x00141208, 0x00161409, 0x00161208, 0x0018140b, 0x001b130b, 0x001e130c, 0x00241b13, 0x00201f14, 0x0020251d, 0x0017211d, 0x00101e1b, 0x00111f1d, 0x00121f1e, 0x0013201f, 0x0013201f, 0x0013201f, 0x0011201f, 0x0011201f, 0x000f201e, 0x000f1d1d, 0x000f1d1d, 0x000f1d1c, 0x000f1d1c, 0x00101c1c, 0x000f1c1b, 0x000c1918, 0x000c1918, 0x000c1716, 0x000b1515, 0x000b1515, 0x000a1414, 0x00091414, 0x00081414, 0x00081313, 0x00081313, 0x00081211, 0x0007100f, 0x0006100e, 0x0006100e, 0x00050f0c, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1414, 0x00091414, 0x00081414, 0x00081311, 0x00081412, 0x00081410, 0x00081410, 0x00081410, 0x00081411, 0x00081412, 0x00091412, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x00081110, 0x0008120f, 0x00091310, 0x0009130e, 0x0008120d, 0x0007110c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0008100c, 0x00070f0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040d08, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008120d, 0x0008120d, 0x0007130f, 0x0007130f, 0x00081410, 0x00081410, 0x00081411, 0x00071512, 0x00061512, 0x00071512, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081513, 0x00061510, 0x00071510, 0x000c1410, 0x000c130f, 0x00121714, 0x002d312e, 0x00454845, 0x004c4d4b, 0x003d3e3c, 0x00333130, 0x00353231, 0x00373333, 0x00353130, 0x00332d2d, 0x00322d2c, 0x003d3635, 0x003e3935, 0x003c3833, 0x0037342d, 0x00342e28, 0x00312821, 0x00382c24, 0x00362822, 0x0031241c, 0x0041342a, 0x00403228, 0x00302015, 0x002b1a0b, 0x002c1807, 0x00301b08, 0x00341b0a, 0x00371c0c, 0x00371b09, 0x003c1f0c, 0x004b2914, 0x0048230d, 0x004c250c, 0x004f280c, 0x00502a09, 0x00583410, 0x005a3718, 0x004d2810, 0x00421e0c, 0x003e1a0c, 0x003f1d0b, 0x00482710, 0x004e2f12, 0x00442406, 0x004e2b0a, 0x005c3512, 0x0058300d, 0x005b300b, 0x00643a15, 0x00643b15, 0x005e3411, 0x00532a08, 0x004e2807, 0x00492507, 0x00442207, 0x0040230c, 0x00371d07, 0x00351a06, 0x00482915, 0x0044200a, 0x00673e1f, 0x00623b17, 0x005b340d, 0x005c350e, 0x0058330d, 0x00502a0a, 0x00462208, 0x00402008, 0x0041220d, 0x00402008, 0x004c280f, 0x004d280e, 0x00583315, 0x00512e0e, 0x004c2909, 0x004e290a, 0x004f2809, 0x00522c0c, 0x00502c0f, 0x00472509, 0x003f2008, 0x003d200a, 0x00391c08, 0x003c1f0a, 0x0040240c, 0x003e240c, 0x00311804, 0x002a1403, 0x00291408, 0x0028170c, 0x00231208, 0x0021140a, 0x001e1408, 0x001c1509, 0x001e180b, 0x00191208, 0x00171107, 0x00140e04, 0x00120e04, 0x00141007, 0x00151108, 0x00141006, 0x00140f06, 0x00151006, 0x00151005, 0x00181207, 0x00191408, 0x001a1409, 0x00181308, 0x00191408, 0x001a140a, 0x001f140b, 0x0021180f, 0x00211f14, 0x0023251d, 0x0018211c, 0x00101e1a, 0x00101f1d, 0x00111f1e, 0x00121f1e, 0x0013201f, 0x0013201f, 0x0011201f, 0x0011201f, 0x000f201e, 0x000f1d1c, 0x000f1d1c, 0x000f1d1c, 0x000f1d1c, 0x00101c1c, 0x000d1a19, 0x000c1918, 0x000b1818, 0x000c1716, 0x000b1515, 0x000b1614, 0x000a1513, 0x00081412, 0x00081311, 0x00081311, 0x00081311, 0x00081210, 0x0007100d, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081414, 0x00081414, 0x00081313, 0x00081311, 0x00081311, 0x00081410, 0x00081410, 0x00081410, 0x00081311, 0x00081311, 0x00081311, 0x00091211, 0x00091211, 0x00091211, 0x00091211, 0x000a1211, 0x000a1211, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0008120f, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x00060f0c, 0x00070e0c, 0x00060e09, 0x00050d08, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00050e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f0b, 0x00030f0b, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007130f, 0x0007130f, 0x0008120f, 0x0008120f, 0x00081310, 0x00081412, 0x00081412, 0x00081412, 0x00081513, 0x00081513, 0x00081412, 0x000c1816, 0x000c1816, 0x00081513, 0x00071711, 0x00081610, 0x000c1510, 0x000d1411, 0x00292c2b, 0x00444443, 0x004e4c4c, 0x004c4a48, 0x003c3c3a, 0x0041403f, 0x002e2c2b, 0x00201c1b, 0x00201d1c, 0x00252322, 0x002f2d2c, 0x00343031, 0x00353334, 0x003c3b3b, 0x003c3839, 0x00332c2c, 0x00342c27, 0x002e231d, 0x00382b24, 0x00342720, 0x0033251f, 0x00453830, 0x0044362c, 0x00322215, 0x002e1b0b, 0x002f1a08, 0x00311b08, 0x00341908, 0x003b1e09, 0x003f1f08, 0x0045230e, 0x004b250f, 0x004e2810, 0x0051280c, 0x00502807, 0x00522c08, 0x00593313, 0x00613b1e, 0x0059341c, 0x00441f08, 0x003c1b04, 0x003a1c07, 0x0041260f, 0x004d3115, 0x00472708, 0x00543010, 0x005f3817, 0x00552c0b, 0x005c3110, 0x00653a19, 0x00603614, 0x00542a0b, 0x00482405, 0x00422104, 0x003c1e04, 0x00381d08, 0x0039200d, 0x00301705, 0x003a1e0c, 0x003b1907, 0x005a341b, 0x005c3418, 0x00542d0c, 0x00542f0d, 0x00512d0e, 0x00472409, 0x00401f0a, 0x003b1d0c, 0x00381b0d, 0x00402212, 0x00401f0d, 0x0045220d, 0x0049270e, 0x004b290e, 0x0048250b, 0x004b290e, 0x004c290c, 0x00502d0f, 0x004d2c0d, 0x003e1e03, 0x00391d06, 0x00311a06, 0x00301806, 0x002e1805, 0x003a2311, 0x00311c0b, 0x00281506, 0x00241205, 0x00221407, 0x00201208, 0x00201409, 0x00201108, 0x00211309, 0x0022150b, 0x001d1006, 0x001a0d03, 0x001f1408, 0x0021160b, 0x0020160b, 0x001e150a, 0x001e150a, 0x001b1207, 0x001b1206, 0x001b1207, 0x0020170b, 0x0020170b, 0x0020170b, 0x001f160b, 0x001a1207, 0x00181105, 0x001a1308, 0x001f140b, 0x0021140c, 0x00251c13, 0x0026221a, 0x001b201a, 0x00101d18, 0x00101f1c, 0x00101e1d, 0x00101e1d, 0x00101e1d, 0x00101e1d, 0x00101e1d, 0x00111f1e, 0x00101e1d, 0x000e1c1b, 0x000e1c1b, 0x000e1c1b, 0x000e1c1b, 0x000f1c1b, 0x000d1a19, 0x000c1918, 0x000b1818, 0x000b1614, 0x000a1514, 0x000a1513, 0x00091412, 0x00091310, 0x00091310, 0x00081310, 0x0008120f, 0x0008120f, 0x0007100d, 0x0006100c, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081414, 0x00081414, 0x00081313, 0x00081311, 0x00081311, 0x00081410, 0x00081410, 0x00081410, 0x00081310, 0x00081311, 0x00081211, 0x00091211, 0x00091211, 0x00091211, 0x00091211, 0x000a1211, 0x000a1211, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0008120f, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x00070e0c, 0x00060e09, 0x00040c08, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f0b, 0x00030f0b, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007130f, 0x0007130f, 0x00081310, 0x0008120f, 0x00081310, 0x00081412, 0x00081412, 0x00081412, 0x00081513, 0x00081513, 0x00091513, 0x00101c1a, 0x000f1c19, 0x00081513, 0x00061711, 0x00081610, 0x000e1712, 0x001e2321, 0x00404442, 0x004f4d4c, 0x004f4949, 0x004b4646, 0x00413e3d, 0x003c3a39, 0x003c3a39, 0x00363434, 0x002e2c2a, 0x00262623, 0x00282827, 0x00303030, 0x00323135, 0x00333137, 0x003b363c, 0x003e363a, 0x00332a28, 0x00322623, 0x002e201b, 0x003c2f2a, 0x003a2c28, 0x00342720, 0x0044342c, 0x00433126, 0x00362213, 0x00351f0c, 0x00341c09, 0x00381e09, 0x00381904, 0x00422009, 0x0048230c, 0x004a240e, 0x00502911, 0x00542b10, 0x00532b0e, 0x00512b0b, 0x00552f0e, 0x005c3514, 0x0065401c, 0x0054300e, 0x00401f00, 0x00371b01, 0x00341a02, 0x00472d13, 0x0054341a, 0x004e2c0e, 0x00593415, 0x005c3314, 0x00522606, 0x005a2f0e, 0x005f3414, 0x00583012, 0x004b270a, 0x00442409, 0x003c1e07, 0x00321905, 0x00301b0a, 0x00341d0d, 0x00371c0d, 0x00371809, 0x004e2b16, 0x00543018, 0x00492509, 0x00452306, 0x00432205, 0x003c1c06, 0x00371808, 0x00381c10, 0x0031180c, 0x00361b0e, 0x00351608, 0x003e1d0c, 0x00442510, 0x0046280f, 0x003f2006, 0x004a2910, 0x004e2c11, 0x00533113, 0x0048290c, 0x00391c02, 0x00341a04, 0x00281605, 0x002c1a09, 0x002b1808, 0x00301d0f, 0x002b1a0c, 0x00231306, 0x00201305, 0x001e1407, 0x001d1408, 0x001f1308, 0x001e0f04, 0x0026150b, 0x0028170d, 0x002a180e, 0x002d1c11, 0x002d1c11, 0x002b1b10, 0x0028180e, 0x0024150a, 0x0024160b, 0x0026190e, 0x0026190e, 0x0025180c, 0x0022170b, 0x0022170a, 0x00201609, 0x00201609, 0x0021160a, 0x001f1408, 0x0020170b, 0x0024170e, 0x0024140c, 0x00281813, 0x00291f18, 0x001e1f18, 0x00111d18, 0x000e1e1c, 0x00101d1c, 0x00101c1c, 0x00101c1c, 0x00101c1c, 0x000f1d1c, 0x00101e1d, 0x000f1d1c, 0x000e1c1b, 0x000e1c1b, 0x000c1c1a, 0x000c1c1a, 0x000e1b1a, 0x000c1918, 0x000c1918, 0x000a1814, 0x000b1614, 0x000a1512, 0x00081411, 0x00081410, 0x0009140f, 0x0009130e, 0x0009120e, 0x0008120d, 0x0008120d, 0x0007110c, 0x0006100b, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091413, 0x00091413, 0x00081412, 0x00081311, 0x00071210, 0x00071310, 0x00071310, 0x00071310, 0x00081211, 0x00081211, 0x00091211, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00091110, 0x00091110, 0x00081010, 0x0008110e, 0x0007110e, 0x0007110c, 0x0008110c, 0x0007110c, 0x0005100b, 0x0005100a, 0x0005100b, 0x0005100b, 0x0004100b, 0x0004100b, 0x0005100b, 0x00060f0b, 0x00060e0a, 0x00050e0a, 0x00060e0a, 0x00060e0a, 0x00060e0a, 0x00060e0a, 0x00060e09, 0x00050e09, 0x00050e08, 0x00060d08, 0x00060d08, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00050d09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e08, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0005100a, 0x0004100a, 0x0006120c, 0x0008110d, 0x0008110d, 0x0008120f, 0x00091410, 0x00091210, 0x00091210, 0x00091211, 0x00081311, 0x00081412, 0x00081412, 0x00091412, 0x00091512, 0x000c1613, 0x0016201d, 0x00101c19, 0x00081612, 0x00091813, 0x000b1713, 0x0018201c, 0x003d3f3e, 0x004d4a4b, 0x00494645, 0x003f3a3a, 0x00332f2f, 0x002a2626, 0x00312f2e, 0x00393837, 0x00444442, 0x003e3e3c, 0x002c2d2b, 0x00222421, 0x00272828, 0x002c2f32, 0x002c2f34, 0x0036383c, 0x00383437, 0x00393030, 0x00372b28, 0x00352924, 0x00362a24, 0x00392c28, 0x003a2d27, 0x00332119, 0x00412d22, 0x00422d1d, 0x0038210d, 0x00381e09, 0x00442913, 0x003c1e08, 0x003c1903, 0x0049260e, 0x00512d15, 0x00532c13, 0x00562e14, 0x00583114, 0x00542c0e, 0x00502a08, 0x0058330c, 0x0058340f, 0x005f3a16, 0x00523011, 0x003b1d04, 0x00311703, 0x00381c09, 0x004d3018, 0x00543419, 0x004f2c0d, 0x00593112, 0x00572e0e, 0x004c2000, 0x00552c0c, 0x00552f10, 0x004c2b0f, 0x0048260e, 0x00381904, 0x00311804, 0x002d1809, 0x002c1508, 0x002d1608, 0x002e1504, 0x003c200c, 0x00462813, 0x003c2008, 0x00391c05, 0x00381b07, 0x00341807, 0x0030160a, 0x00331b10, 0x002c140a, 0x002d1408, 0x00351a0f, 0x0034190c, 0x00402511, 0x00391d05, 0x003b1d05, 0x00482910, 0x004e2e12, 0x004c2c10, 0x0044270c, 0x00341904, 0x002e1806, 0x00231406, 0x00251608, 0x002c1b0d, 0x002c1a0c, 0x00251608, 0x001e1103, 0x001d1203, 0x00201408, 0x0021170c, 0x00201409, 0x002b1b10, 0x002e1c10, 0x002f1a0d, 0x00361f11, 0x00382114, 0x00341f10, 0x002f1b0c, 0x002d190c, 0x0029180b, 0x0027170a, 0x00241509, 0x0024150a, 0x0024180c, 0x0022180b, 0x00201608, 0x001f1408, 0x00201408, 0x0022170c, 0x0023180c, 0x0022190e, 0x0028180e, 0x002c140c, 0x002c160e, 0x002c1c16, 0x001f1d18, 0x00121c18, 0x000e1e1b, 0x00101d1c, 0x000f1c1b, 0x000f1c1b, 0x00101c1c, 0x00101c1c, 0x00101d1c, 0x000e1c1b, 0x000d1c1a, 0x000c1c1a, 0x000c1b19, 0x000d1b19, 0x000d1a19, 0x000c1918, 0x000c1716, 0x000b1715, 0x000b1514, 0x00091414, 0x00081411, 0x00081510, 0x00081410, 0x0008140f, 0x0008120c, 0x0007100b, 0x0006100a, 0x0006100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d0a, 0x00050d09, 0x00050d09, 0x00050d07, 0x00050d06, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1513, 0x00091413, 0x00081412, 0x00081311, 0x00071210, 0x00071210, 0x00071210, 0x00071210, 0x00081211, 0x00091211, 0x00091211, 0x00081110, 0x00081010, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0007110d, 0x0007110c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00040f09, 0x00040f09, 0x00060f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x0005110b, 0x0007110d, 0x0007110d, 0x0007110d, 0x00091310, 0x00091211, 0x00091211, 0x00091211, 0x00081311, 0x00081412, 0x00081412, 0x00091412, 0x000a1511, 0x000c1613, 0x001b2420, 0x0018211e, 0x00091511, 0x000c1814, 0x0016201c, 0x00343938, 0x004d4c4c, 0x00443e40, 0x003b3736, 0x002c2828, 0x00252221, 0x001f1e1c, 0x00242221, 0x002a2b28, 0x00373836, 0x0040423f, 0x003c3d3b, 0x002d2e2c, 0x00232422, 0x00272827, 0x00282a29, 0x00353736, 0x003d3a39, 0x00352b2a, 0x003b2e2b, 0x00423530, 0x003f322c, 0x00392c27, 0x003e312a, 0x00402c24, 0x00342013, 0x00442b1c, 0x004b301c, 0x0041240f, 0x00472812, 0x004c2b15, 0x0045230d, 0x003c1801, 0x004c2810, 0x00532c14, 0x00573016, 0x00593217, 0x00563011, 0x00502c08, 0x00542f0a, 0x00512c08, 0x00502c0c, 0x00553315, 0x0043240e, 0x00341808, 0x002f1405, 0x003b1c0b, 0x0053321b, 0x00512d13, 0x004c2607, 0x00562f10, 0x00512a0b, 0x00482001, 0x004a2407, 0x0048250c, 0x0045240d, 0x00391b06, 0x00311706, 0x002a1508, 0x002a1608, 0x002c1608, 0x002c1606, 0x00341d0c, 0x003a2310, 0x00351c09, 0x00321906, 0x00301808, 0x002c1508, 0x002a1409, 0x002d170c, 0x002b150b, 0x002b1408, 0x00321a0e, 0x002f180a, 0x0037200e, 0x00331a04, 0x00351b04, 0x00482a13, 0x0047280f, 0x0045270d, 0x003c1e09, 0x002e1607, 0x00241206, 0x00201408, 0x0025180c, 0x002a1b0e, 0x00281808, 0x00211202, 0x001e1001, 0x00211406, 0x0024170a, 0x00281a10, 0x0026180c, 0x002a180c, 0x00301b0e, 0x00392213, 0x003a2010, 0x00381e0e, 0x00371c0c, 0x0031190b, 0x002e180a, 0x00291508, 0x00241409, 0x0024140c, 0x0022130b, 0x00201309, 0x001c1208, 0x001a1107, 0x001a1006, 0x00191005, 0x001a1005, 0x001a1006, 0x001c1308, 0x0026140c, 0x002f170f, 0x00341b11, 0x002c1c15, 0x00201c18, 0x00131c16, 0x000e1d1b, 0x00101d1c, 0x000f1c1b, 0x000e1b1a, 0x000e1b1a, 0x000e1b1a, 0x000e1b1a, 0x000d1c1a, 0x000c1c1a, 0x000c1c1a, 0x000d1a19, 0x000d1a19, 0x000c1918, 0x000b1818, 0x000c1716, 0x000c1716, 0x000b1515, 0x00081414, 0x00081412, 0x00081510, 0x00081410, 0x0007130e, 0x0007120c, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1513, 0x00091413, 0x00081412, 0x00081311, 0x00071210, 0x00071210, 0x00081210, 0x00081110, 0x00081110, 0x00091110, 0x00091110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0006100c, 0x0005100a, 0x00040e09, 0x00040e08, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x00030e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x0005110b, 0x0007110d, 0x0007110d, 0x0007110d, 0x0008120f, 0x00091110, 0x00091110, 0x00091211, 0x00091211, 0x00091312, 0x00091412, 0x00091412, 0x000b1411, 0x000c1613, 0x00202725, 0x00202724, 0x000d1411, 0x00171c1a, 0x00303534, 0x00464b48, 0x00454445, 0x00373435, 0x002c2b2a, 0x001d1c1b, 0x00141311, 0x000f100e, 0x000c0e0c, 0x0010110f, 0x00181a18, 0x002c2e2c, 0x003c3d3b, 0x003f3d3c, 0x0034302c, 0x00302a24, 0x003b332d, 0x0038302a, 0x00413833, 0x00423632, 0x003a2c27, 0x00473930, 0x0044372c, 0x0042342a, 0x00403127, 0x00493328, 0x00442c1d, 0x003e2411, 0x004f311c, 0x0054341d, 0x00502e18, 0x004c2813, 0x00512e16, 0x004a250d, 0x004b240b, 0x00542e14, 0x00573014, 0x00583114, 0x00593412, 0x0054300c, 0x00522e09, 0x00502c08, 0x00442000, 0x00462407, 0x00482813, 0x003b1f0f, 0x0034180c, 0x0036190c, 0x00442412, 0x00513018, 0x0049270c, 0x00482408, 0x00522c10, 0x00482106, 0x00432004, 0x00412008, 0x00432410, 0x003c1f0c, 0x00311909, 0x00241204, 0x00281608, 0x00281606, 0x00291605, 0x002f1a0b, 0x00321c0c, 0x00301a08, 0x002e1807, 0x002d1807, 0x00281406, 0x00271408, 0x0028150a, 0x00281509, 0x002a1508, 0x002c180b, 0x002c1709, 0x00301b0c, 0x00311a08, 0x00321804, 0x00452814, 0x003f2009, 0x003c2008, 0x00331906, 0x00291405, 0x00231308, 0x001c1409, 0x00241a0e, 0x0026180b, 0x00221404, 0x00201101, 0x00201203, 0x00241608, 0x00281a0c, 0x002b1b0f, 0x0028180c, 0x00301c0f, 0x00341c0c, 0x003d2211, 0x003c1f0e, 0x00371a09, 0x00381d0c, 0x00341909, 0x002d1709, 0x00291409, 0x0026140c, 0x0023140c, 0x0021110a, 0x0020120a, 0x001e140b, 0x001f150c, 0x001f140c, 0x001f140c, 0x001e140b, 0x001c1209, 0x001a1007, 0x001f1007, 0x00231208, 0x002a180c, 0x002c1c14, 0x00241c16, 0x00181a14, 0x00101b17, 0x000e1c1a, 0x000e1b1a, 0x000d1a19, 0x000d1918, 0x000d1919, 0x000d1919, 0x000c1a18, 0x000c1b19, 0x000d1c1a, 0x000d1a19, 0x000c1818, 0x000b1818, 0x000a1716, 0x000b1515, 0x000b1515, 0x000a1414, 0x00081414, 0x00071411, 0x00061410, 0x0006130f, 0x0006120d, 0x0007120c, 0x0006100b, 0x00050f0a, 0x0005100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e0a, 0x00060e09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091513, 0x00091413, 0x00081412, 0x00081311, 0x00071210, 0x00071210, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0007100d, 0x0005100a, 0x00040e09, 0x00040d08, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x00030f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x0005110b, 0x0007110d, 0x0008120e, 0x0008120f, 0x0008110e, 0x00091010, 0x00091010, 0x00091211, 0x000a1311, 0x00091312, 0x00091412, 0x000a1412, 0x000b1411, 0x000d1613, 0x00272e2c, 0x002c2f2e, 0x001f201f, 0x00393939, 0x004c4c4c, 0x00474848, 0x003a3939, 0x002e2f2f, 0x001f2020, 0x00111413, 0x000c100c, 0x000e110e, 0x000e100e, 0x00101210, 0x00101310, 0x00181b18, 0x00302f2d, 0x0044403e, 0x004a403c, 0x0040322a, 0x00403126, 0x0044372b, 0x003c2e24, 0x00463730, 0x00483830, 0x00403024, 0x004a3c2d, 0x00463829, 0x00443426, 0x00493124, 0x004c3322, 0x004c311c, 0x00472810, 0x004f2e15, 0x0058361c, 0x00573219, 0x00583017, 0x005c371b, 0x00532c0f, 0x00492204, 0x00502a0c, 0x005c3515, 0x005a3312, 0x0058310f, 0x0054300a, 0x00522d08, 0x004e2a08, 0x00432002, 0x003b1b04, 0x00371b0c, 0x00341910, 0x00301509, 0x003c200e, 0x00442510, 0x00472610, 0x00422009, 0x0047230d, 0x0047240d, 0x003d1d06, 0x00381a04, 0x003b1e0c, 0x00361c0a, 0x00301b0c, 0x00251506, 0x00241606, 0x00261506, 0x00261606, 0x002b1809, 0x002e1c0c, 0x002b1707, 0x002c1808, 0x002a1606, 0x00261406, 0x00261408, 0x00261408, 0x00271609, 0x00281809, 0x00291609, 0x002a1809, 0x002c1809, 0x002f1909, 0x00341d0c, 0x003c2210, 0x00381e08, 0x00371c08, 0x002c1504, 0x0029160a, 0x001f1108, 0x001c140a, 0x00241a0f, 0x0024180b, 0x00211406, 0x00201304, 0x00201304, 0x00241608, 0x00281a0c, 0x002a180c, 0x00331e10, 0x00341c0d, 0x00381e0d, 0x003c200c, 0x00381905, 0x003e200c, 0x003c1f0b, 0x00331806, 0x002d1407, 0x002b150a, 0x0026140c, 0x0021100a, 0x0021100a, 0x0022140c, 0x001f140c, 0x001e140b, 0x00221710, 0x001c120b, 0x001f140b, 0x001e140b, 0x0020130b, 0x001f160b, 0x001c1305, 0x00221708, 0x00281c0f, 0x00271d14, 0x001c1a14, 0x00101914, 0x000c1b17, 0x000d1a19, 0x000d1918, 0x000d1818, 0x000c1918, 0x000d181a, 0x000c1918, 0x000b1a18, 0x000d1c1a, 0x000c1918, 0x000a1817, 0x000b1817, 0x00091615, 0x000a1414, 0x000a1414, 0x00081414, 0x00081313, 0x00051310, 0x0005130f, 0x0006120e, 0x0006120c, 0x0008120c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081412, 0x00081412, 0x00081411, 0x00081311, 0x00081311, 0x00081311, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0006100e, 0x0007100d, 0x0008120e, 0x0007110b, 0x0005100a, 0x00040f09, 0x00050f0a, 0x00050f0a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x00060f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00040d08, 0x00040d08, 0x00050d09, 0x00050d09, 0x00060d09, 0x00060d09, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00060e08, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00050e09, 0x00040e09, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x00040f09, 0x0005110b, 0x0007110d, 0x0008130f, 0x00091310, 0x00091310, 0x0009110f, 0x0009120f, 0x00091210, 0x00081411, 0x00081412, 0x00091412, 0x000c1412, 0x000c1411, 0x000f1514, 0x002c3130, 0x00383a39, 0x00403e3d, 0x00534f4f, 0x004c4949, 0x003c3c3c, 0x00343434, 0x00292c2b, 0x001e2322, 0x00191d1d, 0x00181c1a, 0x00161917, 0x00111310, 0x00101110, 0x00101210, 0x00121311, 0x001b1918, 0x00342c2a, 0x004b3e37, 0x00534036, 0x004c3729, 0x004b3728, 0x0048372b, 0x003c2c23, 0x004e3e32, 0x00463428, 0x00463224, 0x004e392b, 0x004c3828, 0x004c3424, 0x004d3320, 0x00563823, 0x0053321b, 0x004c2a10, 0x00532e14, 0x005c351a, 0x005c3518, 0x005e3618, 0x005d3716, 0x00563010, 0x00462000, 0x00542d0d, 0x005c3414, 0x005b3410, 0x0058320c, 0x00542d0a, 0x00542e0a, 0x004b2708, 0x0043220b, 0x00371b09, 0x002f160b, 0x0030170a, 0x002f1504, 0x00381f0d, 0x003f2110, 0x003c1d0c, 0x00391a09, 0x00412310, 0x003c1e0a, 0x00361905, 0x00321804, 0x00321906, 0x00301a09, 0x0029190b, 0x00211304, 0x00241607, 0x00241606, 0x00261807, 0x00291a0a, 0x00271607, 0x00291909, 0x00281707, 0x00271708, 0x00241408, 0x00241508, 0x0027170a, 0x0028180a, 0x00281608, 0x002a1808, 0x002b1707, 0x002c1808, 0x00372010, 0x00341d0c, 0x00341b0a, 0x002e1807, 0x00281404, 0x0027170a, 0x001a0f04, 0x001c150a, 0x0022190d, 0x00201609, 0x00201407, 0x00211306, 0x00211307, 0x00251609, 0x0029180c, 0x00331e10, 0x00382011, 0x00361c0b, 0x003b1f0a, 0x0040210c, 0x003f1f0b, 0x00442410, 0x00381a05, 0x00331706, 0x0031190e, 0x002f1810, 0x0024140c, 0x0021130c, 0x001e1109, 0x001c1108, 0x00181007, 0x00140f04, 0x00150e06, 0x00150f06, 0x00150f06, 0x00150f06, 0x00180e06, 0x00161107, 0x00141305, 0x00191508, 0x0020180c, 0x00241a10, 0x001e1c14, 0x00141b11, 0x000f1a14, 0x000f1917, 0x000e1918, 0x000d1919, 0x000d191a, 0x000c181a, 0x000c1918, 0x000b1a18, 0x000c1c18, 0x000c1918, 0x000a1816, 0x000a1816, 0x00091614, 0x00091414, 0x00091414, 0x00081413, 0x00081312, 0x00051310, 0x0006130f, 0x0007120e, 0x0006110c, 0x0008120d, 0x0008120d, 0x0006100b, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f09, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050d09, 0x00040d07, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00061411, 0x00061411, 0x00071411, 0x00071411, 0x00081311, 0x00091311, 0x00091211, 0x00081110, 0x00081210, 0x0008120d, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110d, 0x0008110e, 0x0008120e, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0005100a, 0x00061009, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0007100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x0004100a, 0x0004100a, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110f, 0x0009130f, 0x00081410, 0x00081510, 0x00091511, 0x000a1511, 0x000c1411, 0x000e1513, 0x00151b19, 0x00303332, 0x00444444, 0x004c4b49, 0x004d4a49, 0x00423f3e, 0x00373735, 0x00333434, 0x002e3232, 0x00283030, 0x00262c2c, 0x00292c2b, 0x00222422, 0x00191817, 0x00131410, 0x00131310, 0x00151412, 0x001b1715, 0x002c2421, 0x003d3028, 0x0048372c, 0x00543e31, 0x004b3728, 0x004c3b2c, 0x00402f22, 0x00443428, 0x004f3b2f, 0x004a3426, 0x004a3023, 0x00543929, 0x00503524, 0x00513521, 0x00533620, 0x00583820, 0x00553418, 0x00522d10, 0x00552d10, 0x005d3415, 0x00663e1c, 0x00613a18, 0x00603917, 0x00552d0c, 0x00482000, 0x0057300e, 0x00643c19, 0x00603a16, 0x005c3410, 0x0058300b, 0x005b3515, 0x00502f15, 0x003f200d, 0x00301608, 0x002f1606, 0x002c1604, 0x002f1908, 0x00381d10, 0x00351b0c, 0x0034180a, 0x0036190c, 0x003a200e, 0x00341a06, 0x002f1604, 0x00311805, 0x00311c0b, 0x002d190c, 0x00241304, 0x00241406, 0x00231606, 0x00241808, 0x00281a0b, 0x00261708, 0x002b1b0c, 0x0028180c, 0x0028180a, 0x00241408, 0x00241407, 0x0028180b, 0x002a1a0c, 0x00271506, 0x002c1808, 0x002b1604, 0x002e1808, 0x00321b0c, 0x00311a0a, 0x002f180a, 0x002b1606, 0x00261505, 0x00211405, 0x001c1103, 0x001d1609, 0x001f1608, 0x00201408, 0x00221408, 0x00241508, 0x0026170b, 0x0028150b, 0x002b160c, 0x00321709, 0x00361b0b, 0x00381c09, 0x003c1f09, 0x0043230c, 0x00482810, 0x0041210c, 0x003a1c08, 0x00361a0b, 0x0031180e, 0x0028130c, 0x0023120c, 0x001c100a, 0x00161008, 0x00110f04, 0x000e0d03, 0x000c0d02, 0x000d0d02, 0x000d0d02, 0x000d0c04, 0x000c0c03, 0x000e0b04, 0x00090c02, 0x00060c02, 0x000a0e04, 0x00140d07, 0x0018120a, 0x001b1910, 0x001a1e12, 0x00131a12, 0x00101814, 0x00101818, 0x000e1819, 0x000d181a, 0x000c181a, 0x000a1819, 0x000a1916, 0x000a1916, 0x000a1814, 0x000a1814, 0x00081613, 0x00081412, 0x00081510, 0x00081510, 0x00081510, 0x00071410, 0x00051310, 0x0007130f, 0x0006100c, 0x0006100c, 0x0006100b, 0x0006100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00070f09, 0x00060e08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00051411, 0x00051411, 0x00071411, 0x00071411, 0x00081412, 0x000a1412, 0x00091211, 0x00081110, 0x0008120f, 0x0008120d, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0006100c, 0x00040e0b, 0x00040e09, 0x00051008, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x0004100a, 0x0004100a, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110d, 0x0009130e, 0x00081410, 0x00081510, 0x00081611, 0x000a1511, 0x000c1511, 0x00131816, 0x00202422, 0x00343534, 0x004e4e4e, 0x004e4c4d, 0x00444244, 0x00383839, 0x00343636, 0x00303535, 0x002d3434, 0x00272e30, 0x00252a2c, 0x00202224, 0x00242120, 0x00282724, 0x00201d1b, 0x00191513, 0x00181412, 0x0015120e, 0x001d1912, 0x002f241b, 0x003d2e22, 0x00443324, 0x004b3a2a, 0x004f3e30, 0x004a3a2c, 0x00412f23, 0x00453126, 0x00503b2e, 0x00472e21, 0x00493120, 0x004f3824, 0x004e3721, 0x00533720, 0x0054371d, 0x005e3f24, 0x005b381a, 0x00522c0e, 0x00542c0b, 0x005c3513, 0x006e4622, 0x00653d1a, 0x00603817, 0x00542c0c, 0x00482201, 0x005b3614, 0x00643e1c, 0x00643c1a, 0x00552e0b, 0x00573210, 0x005a381c, 0x0051311a, 0x0040230e, 0x00311502, 0x002c1403, 0x002e1708, 0x00321b0d, 0x0030180a, 0x002f1508, 0x00301809, 0x00371f0e, 0x00331c0a, 0x002f1605, 0x00301808, 0x00321b0c, 0x002e1909, 0x00291607, 0x00261406, 0x00241506, 0x00261708, 0x002b180b, 0x00281608, 0x002c190c, 0x002a180c, 0x0029180a, 0x00271408, 0x00261406, 0x0028180b, 0x002c1c0d, 0x00281506, 0x002c1707, 0x002c1504, 0x00301908, 0x00321b0b, 0x002f1809, 0x002e1709, 0x00281505, 0x00241404, 0x00201403, 0x00201406, 0x00211609, 0x00211408, 0x00241408, 0x00271509, 0x00271408, 0x0029170b, 0x002c180c, 0x002e160b, 0x0033180b, 0x0036190a, 0x00381c08, 0x003c200a, 0x00492912, 0x004c2b12, 0x0044240f, 0x0040240f, 0x003a2010, 0x002f170d, 0x0026130b, 0x001f1009, 0x00140d04, 0x000f0f04, 0x000c0d01, 0x00090f04, 0x00090f04, 0x000a0f04, 0x000b0e04, 0x000a0e05, 0x00080d05, 0x00080d04, 0x00060d04, 0x00050c04, 0x00050c02, 0x00090902, 0x000c0b03, 0x00111008, 0x00191912, 0x00181c15, 0x00101814, 0x000e1716, 0x000c1717, 0x000b1618, 0x00081717, 0x00091816, 0x00091814, 0x00091813, 0x000a1714, 0x000a1814, 0x00081412, 0x00051310, 0x00081510, 0x00081510, 0x00081410, 0x00071410, 0x00051310, 0x0006110e, 0x0005100c, 0x0005100b, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071411, 0x00071411, 0x00071411, 0x00071411, 0x00081412, 0x000a1412, 0x00091211, 0x00081110, 0x0008110e, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0007110d, 0x00050f0c, 0x0005100a, 0x00051008, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x0004100a, 0x0004100a, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110d, 0x0009130e, 0x0008140f, 0x00081410, 0x00081611, 0x000a1510, 0x000b120e, 0x00111512, 0x002c2e2b, 0x00484847, 0x004a4a4a, 0x00404244, 0x00363839, 0x00303335, 0x002e3234, 0x002c3234, 0x002b3434, 0x002b3235, 0x00292e30, 0x00292b2c, 0x00272524, 0x002a2622, 0x002a2521, 0x0025201c, 0x001c1713, 0x001b1813, 0x001e1a14, 0x00272014, 0x0034281c, 0x00392a1b, 0x003c2d1d, 0x00463628, 0x004f3d2f, 0x00473428, 0x003a281c, 0x00453224, 0x004a3427, 0x00422c1b, 0x004c3622, 0x004d3821, 0x004d361f, 0x0053391f, 0x00563a1d, 0x00604022, 0x005a3818, 0x00593413, 0x00562f0d, 0x00623a18, 0x0068401f, 0x005d3715, 0x005b3414, 0x004f2809, 0x00482103, 0x00563113, 0x00653e20, 0x0060381b, 0x00502a0c, 0x004c280c, 0x004c2c11, 0x004e2e15, 0x003f220c, 0x00341807, 0x002d1405, 0x002c1508, 0x002d160a, 0x002d160a, 0x002d1608, 0x002e1909, 0x00331e0e, 0x00301c0c, 0x002d1709, 0x0030190b, 0x00301c0d, 0x002c1809, 0x00271507, 0x00241506, 0x002a170a, 0x002a1609, 0x002c190c, 0x002e180c, 0x002b180c, 0x002b170c, 0x002c180b, 0x00271406, 0x0028170a, 0x002c1c0d, 0x002b1808, 0x002d1908, 0x00301a08, 0x00331c0c, 0x00341c0c, 0x0030190a, 0x002e1809, 0x002a1808, 0x00261404, 0x00231505, 0x00241709, 0x0025170b, 0x00241409, 0x00281509, 0x002c180d, 0x002c170c, 0x002f1a0e, 0x00392014, 0x00371b10, 0x00381b0d, 0x00351808, 0x00351905, 0x003f220d, 0x004b2a14, 0x004b2a12, 0x00492814, 0x00402410, 0x00311808, 0x00281308, 0x00221008, 0x00190f06, 0x00130d04, 0x000d0f03, 0x000c0f03, 0x00091003, 0x00081004, 0x00091008, 0x00091008, 0x00080f07, 0x00080f07, 0x00040f06, 0x00060e06, 0x00070e06, 0x00070e06, 0x00060e06, 0x00080d04, 0x000a0c04, 0x0014120d, 0x00181914, 0x00101714, 0x000c1414, 0x000c1515, 0x000b1517, 0x00091617, 0x00091615, 0x00091714, 0x00091712, 0x00081513, 0x00081513, 0x00081412, 0x00081412, 0x00081510, 0x00081510, 0x00071410, 0x0005130f, 0x0004120f, 0x0005100d, 0x0005100c, 0x0005100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00060e09, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071411, 0x00071411, 0x00071411, 0x00071411, 0x00081311, 0x00091211, 0x00081110, 0x00081110, 0x0008110e, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007100c, 0x0006100c, 0x0006100c, 0x00040d0a, 0x00040e0a, 0x0006100c, 0x00050f0c, 0x0005100a, 0x00051008, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c08, 0x00060c08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x0004100a, 0x0004100a, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110d, 0x0009130e, 0x0008140f, 0x00081410, 0x00081610, 0x000a1510, 0x00101713, 0x002d302e, 0x0050514f, 0x003e3c3c, 0x00313031, 0x002c2d2f, 0x00222426, 0x0024282b, 0x00282d2f, 0x00283032, 0x00263032, 0x00252d30, 0x0024292b, 0x00242628, 0x00252422, 0x0025231e, 0x0027201c, 0x0029231d, 0x002c261f, 0x001e1812, 0x001c180e, 0x0021180e, 0x002c2010, 0x00322616, 0x0037291a, 0x00372718, 0x00443224, 0x00443327, 0x00402f22, 0x00352315, 0x00473324, 0x0045301f, 0x003f2b18, 0x004d3823, 0x004e3822, 0x004a331a, 0x00563c20, 0x00543519, 0x005f3d1f, 0x005c3a1a, 0x005d3817, 0x0058300f, 0x005d3614, 0x005e3715, 0x00532c0c, 0x005c3517, 0x004a2408, 0x00401a00, 0x00532e13, 0x005d361c, 0x00593318, 0x004c280e, 0x00432107, 0x003c1c02, 0x003f2209, 0x00371c09, 0x0032190a, 0x002c1708, 0x002c170a, 0x002c180b, 0x002b1809, 0x002b1808, 0x002d190b, 0x00321e0f, 0x00311c0d, 0x002d180a, 0x00301a0d, 0x002e190c, 0x00281608, 0x00251406, 0x002d180b, 0x002d180b, 0x002e180c, 0x002e180c, 0x002d180c, 0x002c180c, 0x002c190c, 0x00291607, 0x00281708, 0x002e1d0d, 0x002f1a0b, 0x00321c0a, 0x00321c0a, 0x00331c0c, 0x00341d0d, 0x0030190a, 0x002f190a, 0x002d190a, 0x00281808, 0x00281809, 0x0028180b, 0x0028160c, 0x00281308, 0x0030170c, 0x00341b0d, 0x00361d0e, 0x00392010, 0x00432617, 0x00391c0c, 0x003a1c0c, 0x00361807, 0x003b1f0b, 0x00452812, 0x004a2a13, 0x004b2b13, 0x00472712, 0x00381c08, 0x002c1404, 0x00241306, 0x00201207, 0x00191007, 0x00140f06, 0x00121006, 0x00101008, 0x000c0f04, 0x000c1006, 0x000c0e08, 0x000c0e08, 0x000b0d07, 0x000a0e07, 0x00051008, 0x00070d08, 0x00090c08, 0x00080c08, 0x00050f06, 0x00060e06, 0x00080b04, 0x000e0e09, 0x00161814, 0x00101614, 0x000c1414, 0x000c1616, 0x000b1517, 0x00091617, 0x00091615, 0x00091714, 0x00091712, 0x00091513, 0x000a1513, 0x00081412, 0x00081412, 0x00081410, 0x00081410, 0x00081410, 0x0007130f, 0x0004120f, 0x0005100d, 0x0005100c, 0x0005100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00060e09, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071411, 0x00071411, 0x00071210, 0x00071210, 0x00081311, 0x00081311, 0x00081110, 0x0007100f, 0x0007100f, 0x0007110e, 0x0007110d, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0005100a, 0x00040e09, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040d09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00041008, 0x00031008, 0x00041008, 0x00041009, 0x00050f0c, 0x0007110d, 0x0008120f, 0x0008120f, 0x0008120f, 0x0008120f, 0x00081310, 0x0007140f, 0x0008150f, 0x000c1510, 0x00202622, 0x00484c48, 0x0040413d, 0x0032302f, 0x001e1d1e, 0x0019181b, 0x0027282c, 0x00292e30, 0x002a2f33, 0x00293034, 0x002a3537, 0x00283034, 0x00262b2d, 0x00242627, 0x00252422, 0x0024201e, 0x00201c18, 0x00231c17, 0x002b241c, 0x002b241b, 0x00231a10, 0x00271c0f, 0x002b1c0e, 0x002c1f0f, 0x00312415, 0x00312316, 0x00302014, 0x003f2f22, 0x00433125, 0x003e2c20, 0x003a2618, 0x003d2a1b, 0x003f2c1b, 0x003f2c1a, 0x004d3824, 0x004c3521, 0x00462e17, 0x00543921, 0x0054351c, 0x00614024, 0x005c381a, 0x00593314, 0x00593214, 0x00583010, 0x00572e0f, 0x005a3013, 0x005b3216, 0x00482107, 0x00441e06, 0x0048240d, 0x004f2b14, 0x004f2a14, 0x0044230c, 0x00391c01, 0x00371b04, 0x00371c0c, 0x00321a0c, 0x002f1a0c, 0x002c180b, 0x002d180b, 0x002c170a, 0x002c170a, 0x002e190b, 0x00331d0f, 0x00331d0f, 0x00301a0b, 0x0030180a, 0x002d180a, 0x002b1607, 0x002a1304, 0x0030180a, 0x00321b0d, 0x0030180a, 0x002e180c, 0x0030180c, 0x002e180c, 0x002f1a0b, 0x002c190a, 0x002f1b0b, 0x00321a0a, 0x00341809, 0x00361809, 0x00351c0a, 0x00341c09, 0x00331c0a, 0x00321c0b, 0x00321c0c, 0x00301909, 0x002d1808, 0x002e1a0b, 0x002e180b, 0x0030180c, 0x00361a0e, 0x003c1d0f, 0x0043200f, 0x00472510, 0x004a2810, 0x0048260f, 0x0043210a, 0x0043200c, 0x003c1c07, 0x0042230e, 0x00452811, 0x00482811, 0x0044210c, 0x003e1e09, 0x00381b08, 0x002e1807, 0x00271607, 0x00211407, 0x001c1207, 0x00181108, 0x00140f08, 0x00141008, 0x00141109, 0x00101007, 0x0013120b, 0x00111009, 0x00101009, 0x000c0d08, 0x000e100a, 0x000c0d08, 0x000b0d07, 0x00080c05, 0x00080c04, 0x00080c03, 0x00080b02, 0x000c1007, 0x00141814, 0x000f1514, 0x000b1514, 0x000c1714, 0x000c1614, 0x00091615, 0x00091615, 0x00081513, 0x00091513, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x000a1410, 0x000a1410, 0x0008120f, 0x0008120f, 0x00071210, 0x0006110d, 0x0004100c, 0x0004100b, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00040e07, 0x00030c06, 0x00030c06, 0x00030c06, 0x00040c09, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071411, 0x00071411, 0x00071210, 0x00071210, 0x00071210, 0x00071210, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007110e, 0x0008120e, 0x00050f0b, 0x00030d08, 0x0005100a, 0x0005100a, 0x00040e09, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040d09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00041008, 0x00031008, 0x00041008, 0x00041009, 0x00050f0c, 0x0007110d, 0x0008120f, 0x0008120f, 0x0008120f, 0x0008120f, 0x00081310, 0x0008140f, 0x0009140f, 0x000f1813, 0x003c403d, 0x003c403c, 0x0021231f, 0x00181817, 0x00202020, 0x002c2b2e, 0x00292b2e, 0x002c2f31, 0x002a2f33, 0x00283033, 0x002b3537, 0x002c3437, 0x00282d2f, 0x00252728, 0x00262424, 0x0023201e, 0x00241f1d, 0x00271f1c, 0x00282018, 0x00342a20, 0x002c2014, 0x002b1c0e, 0x002e1d0e, 0x002f1e0f, 0x002f2011, 0x002f2013, 0x002c1d10, 0x002e2013, 0x003a2a1d, 0x00433226, 0x00413022, 0x00352416, 0x00362415, 0x003b2a19, 0x00402e1d, 0x00483423, 0x0047321f, 0x0049301c, 0x00573c24, 0x00513318, 0x00603e22, 0x00543014, 0x00583216, 0x00573114, 0x00542d0f, 0x00562e10, 0x00573014, 0x00502c12, 0x00432009, 0x00401e09, 0x0044220c, 0x00482711, 0x00482810, 0x003c1f06, 0x00371c07, 0x00341b0b, 0x00311b0c, 0x002f1b0d, 0x002c190c, 0x002a1408, 0x002d180b, 0x002d180b, 0x002d180a, 0x00331c0e, 0x00341c0f, 0x00321b0c, 0x002e1809, 0x002d1809, 0x002c1708, 0x002c1406, 0x0030180a, 0x00321b0d, 0x0030190b, 0x002f190c, 0x0030180c, 0x002e180c, 0x002f190b, 0x00331e0d, 0x00361e0d, 0x00381d0c, 0x003a1c0c, 0x003e1e0e, 0x003a1c08, 0x003b1f08, 0x003b1f0a, 0x00391e09, 0x00381e0a, 0x00361c08, 0x00341907, 0x00341c0a, 0x00371c0a, 0x003f2010, 0x00442310, 0x0047230f, 0x004c260e, 0x00502a0f, 0x00542e10, 0x00542e10, 0x00502a0c, 0x004c280c, 0x00462108, 0x004c2b14, 0x0044240d, 0x0044240c, 0x003f1f07, 0x003a1a05, 0x00381c08, 0x00301a07, 0x00281608, 0x00241408, 0x00201308, 0x001b1008, 0x00181008, 0x00171009, 0x00161109, 0x00120f07, 0x00100c04, 0x00131008, 0x0015130b, 0x00121008, 0x0014110a, 0x00111009, 0x00111009, 0x00101008, 0x000f0f06, 0x000f0f06, 0x000e0e04, 0x00111108, 0x00151811, 0x000f1511, 0x000a1410, 0x000a1511, 0x000b1412, 0x000a1514, 0x000a1414, 0x00081412, 0x00081412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x000a1410, 0x00091310, 0x0008120f, 0x0008120f, 0x00071210, 0x0006110e, 0x0005100c, 0x0004100b, 0x00060f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00040e07, 0x00030c06, 0x00030c06, 0x00030c06, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00071210, 0x00071210, 0x00071210, 0x00071210, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007110e, 0x0007110d, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00041008, 0x00041008, 0x00051109, 0x00041008, 0x00040e0b, 0x0006100c, 0x0007110d, 0x00091310, 0x0008120f, 0x0007110d, 0x0008120e, 0x0008130e, 0x0008140e, 0x00202923, 0x003b403b, 0x002b2e29, 0x001f1f1b, 0x00242221, 0x002c2c2d, 0x0029292c, 0x0026272c, 0x0025282c, 0x00272c30, 0x00262e31, 0x002c3437, 0x002d3438, 0x002e3334, 0x002c2e30, 0x00282828, 0x00201d1c, 0x001f1a18, 0x00211815, 0x00251c14, 0x002c2116, 0x00362819, 0x00342212, 0x00301c0c, 0x00301d0d, 0x002e1f10, 0x002c1f11, 0x002c1d10, 0x002c1e11, 0x00312416, 0x00372a1c, 0x003c2d20, 0x003a2b1e, 0x00362819, 0x00382a1b, 0x003c2c1d, 0x003f2e20, 0x00402e1d, 0x00432e1b, 0x004c331e, 0x0052371f, 0x0054351c, 0x0058381d, 0x00512e15, 0x00543216, 0x00583417, 0x00542e0f, 0x00502c0f, 0x004b280e, 0x0044240c, 0x0040200a, 0x0040200c, 0x0040200c, 0x0043240d, 0x0041240e, 0x00391e0a, 0x00341c0b, 0x0030190b, 0x002e1a0c, 0x002e1a0e, 0x002c170a, 0x002d180b, 0x002c170a, 0x002d180b, 0x002f180c, 0x0030190c, 0x00361f10, 0x002d1608, 0x002e180a, 0x00301b0c, 0x002d1608, 0x0030180b, 0x00321b0d, 0x0030190b, 0x0030180c, 0x0030180c, 0x0030180c, 0x00311a0a, 0x00361f0d, 0x0039200d, 0x003c1f0a, 0x00422110, 0x00401d0b, 0x00401d06, 0x0044220a, 0x00402008, 0x00402009, 0x0040220a, 0x0040200b, 0x003c1e08, 0x003e200b, 0x0044240e, 0x00492810, 0x004c2810, 0x00572f14, 0x005c3114, 0x005d3310, 0x00603611, 0x005f340f, 0x005a300b, 0x00512907, 0x00492405, 0x00462309, 0x0044210a, 0x0044220b, 0x00401d06, 0x0040200c, 0x00351804, 0x00321807, 0x002c1608, 0x00281409, 0x0024140c, 0x0024150d, 0x001e140c, 0x001a110b, 0x00170f08, 0x0017100a, 0x001a140c, 0x0018130c, 0x0018120c, 0x0019140c, 0x001a150c, 0x00181209, 0x00161008, 0x00151108, 0x00151109, 0x0014110a, 0x0014120c, 0x0017140f, 0x00151610, 0x000d140d, 0x000b150e, 0x000a140e, 0x000a1410, 0x000a1412, 0x000a1412, 0x00091311, 0x00091311, 0x00091211, 0x00091211, 0x00081110, 0x00081110, 0x00091310, 0x000a1410, 0x0007110d, 0x0007110d, 0x0006110f, 0x0005100d, 0x0004100c, 0x0004100b, 0x00060f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00040e07, 0x00030c06, 0x00030c06, 0x00030c06, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00071210, 0x00071210, 0x00071210, 0x0007130f, 0x0007110d, 0x0007110d, 0x0007100e, 0x0007110e, 0x0007110d, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00050e08, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00041008, 0x00041008, 0x00051109, 0x00041008, 0x00040e0a, 0x0006100c, 0x0007110d, 0x00091310, 0x0008120f, 0x0007110d, 0x0008120e, 0x0008130e, 0x000b1610, 0x002b342e, 0x00313731, 0x00242621, 0x0022231f, 0x002b2b29, 0x00242526, 0x00242528, 0x0026282d, 0x0022252a, 0x00242a2c, 0x00262e2f, 0x00262e2f, 0x002a3034, 0x002f3334, 0x00323436, 0x00313233, 0x002a2827, 0x0024201c, 0x00211915, 0x00251d14, 0x002b1c11, 0x003a281a, 0x003b2715, 0x00321d0b, 0x00311c0b, 0x002c1c0d, 0x002b1c0f, 0x002b1c0f, 0x002b1e10, 0x002c2113, 0x00332819, 0x0033281a, 0x00372b1c, 0x003c2f21, 0x00382c1e, 0x00392d1f, 0x003d2f22, 0x00403021, 0x003f2d1e, 0x00432f1d, 0x00452f1b, 0x004b301b, 0x0052351e, 0x0053341d, 0x004d2f16, 0x004f2f13, 0x00523013, 0x004a2a0c, 0x004a2b12, 0x00462810, 0x0042250e, 0x003e200c, 0x003c1e09, 0x003d200a, 0x0040230e, 0x003f2410, 0x00381f0e, 0x00311a0c, 0x002f1b0c, 0x002f1b0f, 0x002f190c, 0x002c1709, 0x002b1507, 0x002c1709, 0x00311c0e, 0x00301a0b, 0x00341e10, 0x00301a0b, 0x00301b0c, 0x00301b0c, 0x002d1608, 0x0030190c, 0x00331c0e, 0x00311a0c, 0x00311a0d, 0x0030180c, 0x0030180c, 0x00321908, 0x00381e0c, 0x00402510, 0x0043240e, 0x0044230d, 0x0046220d, 0x00452007, 0x004d280c, 0x004c280c, 0x004c280d, 0x004b280d, 0x0048260d, 0x0046240b, 0x0048260c, 0x004d290f, 0x00542f14, 0x005c3517, 0x00633817, 0x00633512, 0x00653811, 0x00693c12, 0x0064370e, 0x00603309, 0x00582e06, 0x004e2804, 0x00482205, 0x0048240e, 0x0045240d, 0x0043220c, 0x00452510, 0x00381c09, 0x00341b08, 0x002d1507, 0x00291408, 0x0027160c, 0x0025160e, 0x0021160f, 0x001d140e, 0x001b130c, 0x001a130c, 0x0019120c, 0x001a130c, 0x0019120a, 0x0019120a, 0x00181008, 0x00160e06, 0x00181008, 0x00181008, 0x00171208, 0x00151208, 0x0015120a, 0x0017140d, 0x0015150f, 0x000e140c, 0x000b140c, 0x0009140d, 0x0008140f, 0x00091311, 0x00091311, 0x00091211, 0x00091211, 0x00091310, 0x00091310, 0x00081210, 0x00081210, 0x00091310, 0x000a1410, 0x0007110d, 0x0007110d, 0x0006100d, 0x00050f0c, 0x00050f0c, 0x0005100b, 0x00060f09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e08, 0x00040f08, 0x00051009, 0x00051008, 0x00040e07, 0x00030c06, 0x00030c06, 0x00030c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00081110, 0x0008120f, 0x0008120f, 0x0008120f, 0x0007110d, 0x0007110d, 0x0007100e, 0x0007110e, 0x0007110d, 0x0006100c, 0x0005100a, 0x0005100a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00040d06, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00050c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00030e07, 0x00020e07, 0x00020e07, 0x00020e07, 0x0005100a, 0x0005100a, 0x00040e09, 0x0006100b, 0x0007110d, 0x0007110d, 0x0008120e, 0x0008120e, 0x00101a14, 0x002b342c, 0x00282d27, 0x00242620, 0x0023241f, 0x00282827, 0x002a2c2c, 0x00282a2d, 0x00272a2c, 0x0024292c, 0x00202728, 0x00202728, 0x001d2425, 0x00212628, 0x00282c30, 0x002c2f32, 0x00303032, 0x0031302d, 0x00302c28, 0x002e2721, 0x002c2319, 0x002e1f14, 0x00341f10, 0x003b2414, 0x003c2513, 0x0035210f, 0x002f1d0f, 0x002d1d0e, 0x002c1e0e, 0x002f2211, 0x00322514, 0x00342817, 0x00352818, 0x00352818, 0x0038291a, 0x003b2c1d, 0x003b2c1e, 0x003c2c1f, 0x003c2c20, 0x003b2a1c, 0x003d2b1b, 0x0041301c, 0x0044311f, 0x0047311f, 0x004c3422, 0x0049301d, 0x00482e19, 0x004b2c18, 0x0050311b, 0x00482c13, 0x00442710, 0x00432510, 0x003e230d, 0x003b1f09, 0x00381c08, 0x00381c08, 0x0039200d, 0x00381f0f, 0x00311a0c, 0x00301a0d, 0x00301a0d, 0x00301b0d, 0x002e1b0c, 0x002f1c0c, 0x002c1809, 0x002c190a, 0x002e1c0c, 0x002d1c0c, 0x002f1c0d, 0x00311c0d, 0x00301a0c, 0x0030190b, 0x00331b0d, 0x00341c0e, 0x00331b0d, 0x00331a0e, 0x0033190d, 0x0034180c, 0x00351906, 0x0040200a, 0x0046270e, 0x0047280c, 0x0049280b, 0x004f2a0b, 0x004d2705, 0x00552d0c, 0x00542b09, 0x00562c0b, 0x00592f0f, 0x00582d0e, 0x00552b0c, 0x005a2e10, 0x005d3311, 0x00603713, 0x00663b14, 0x006c3d14, 0x006e3d14, 0x006f3d10, 0x006e3d10, 0x006e3c0f, 0x0068380b, 0x0060330b, 0x00582c07, 0x00542a0b, 0x004d250c, 0x0046240a, 0x0046240c, 0x0045240e, 0x00401f0c, 0x003a1c09, 0x00331808, 0x002c1708, 0x0028180a, 0x0026180d, 0x0024150c, 0x0020140b, 0x0020140c, 0x001c1209, 0x001f140c, 0x0020140c, 0x001f140c, 0x001f140c, 0x001e150c, 0x001e150c, 0x001e150b, 0x001c1309, 0x001c1309, 0x001c140a, 0x001c140b, 0x001a150c, 0x0018140d, 0x0014110e, 0x000d120d, 0x0009140c, 0x0006120c, 0x00081110, 0x00091211, 0x00091211, 0x00091310, 0x0009130d, 0x0008120c, 0x0009140d, 0x0009140d, 0x0007110c, 0x0008100c, 0x0007100b, 0x0007100b, 0x0007100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0a, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00081110, 0x0008120f, 0x0008120f, 0x0008120d, 0x0007110c, 0x0007110c, 0x0007110e, 0x0007110e, 0x0007110d, 0x0005100b, 0x0005100a, 0x0005100a, 0x00040e09, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00050c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00030e07, 0x00020e07, 0x00020e07, 0x00020e07, 0x0005100a, 0x0005100a, 0x00040e09, 0x0006100b, 0x0006100c, 0x0007110d, 0x0008120f, 0x0008120e, 0x000f1812, 0x00212822, 0x002a2e27, 0x002d3029, 0x002d2e28, 0x002c2f2c, 0x002c2f30, 0x002a2d30, 0x00282d31, 0x00292e31, 0x002b3234, 0x00282e30, 0x00242b2c, 0x00202426, 0x001f2126, 0x00232628, 0x00282a2c, 0x002b2a27, 0x002a2520, 0x002c241f, 0x0030271d, 0x0034251b, 0x00372316, 0x00372111, 0x0037200e, 0x00392210, 0x00342011, 0x00342111, 0x00342513, 0x00382815, 0x00382816, 0x003a2917, 0x003a2917, 0x003a2917, 0x003a2817, 0x003a2717, 0x003d2b1b, 0x003e2c1c, 0x003e2b1d, 0x003c281b, 0x003c2818, 0x003d2b18, 0x00402d1a, 0x00402f1b, 0x00402f1a, 0x00402f19, 0x004c3622, 0x00472a17, 0x00492c18, 0x00492c17, 0x00462b14, 0x00412611, 0x003d230d, 0x003a200a, 0x003a1f0b, 0x00381c09, 0x00351b0a, 0x00361d0e, 0x00321b0f, 0x00301a0d, 0x00321b0f, 0x00331c0f, 0x00331d0c, 0x00301b0a, 0x002e1808, 0x002d1808, 0x002f1c0a, 0x002f1c0a, 0x00301c0c, 0x00311b0b, 0x00321a0a, 0x0034190a, 0x00361b0c, 0x00371c0d, 0x00341a0c, 0x00351a0c, 0x00371b0d, 0x00391b0c, 0x003c1c08, 0x0047240a, 0x004c290c, 0x004e2909, 0x00552f0d, 0x005b320f, 0x00582c08, 0x005f320d, 0x005f300c, 0x0061320e, 0x00643510, 0x0062340e, 0x0061320c, 0x0065350f, 0x00693813, 0x006a3c12, 0x006d3d10, 0x00703c0f, 0x00733e0d, 0x0075400c, 0x0076400e, 0x0075400e, 0x00703c0a, 0x0069380c, 0x0061320b, 0x005b2c0c, 0x00512809, 0x004a2608, 0x0049260a, 0x0049250c, 0x0046220b, 0x00401f09, 0x00391c07, 0x00311a07, 0x002b1908, 0x00281809, 0x00251508, 0x00211307, 0x001f1205, 0x00201508, 0x0024170c, 0x0024170c, 0x00201509, 0x00201509, 0x0020140a, 0x0020140a, 0x001f150a, 0x0021170c, 0x0020160b, 0x0020150a, 0x001e150a, 0x001c1509, 0x001a150f, 0x00171410, 0x0010140d, 0x0008140c, 0x0006120c, 0x00081110, 0x00081110, 0x00091211, 0x00091310, 0x0008120c, 0x0008120c, 0x0008120b, 0x0008120b, 0x0009100c, 0x000a100c, 0x00090f0b, 0x00090f0b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00040c07, 0x00040c06, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00081110, 0x0008120f, 0x0008120f, 0x0008120d, 0x0008100c, 0x0008100c, 0x0008110c, 0x0007110d, 0x0006100c, 0x00050f0b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c05, 0x00040c04, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00050c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00030e07, 0x00020e07, 0x00020e07, 0x00020e07, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x00040e0b, 0x0007110d, 0x000a140f, 0x0009130d, 0x000f1710, 0x001f2720, 0x002b2f28, 0x0031332d, 0x0031302c, 0x002f302e, 0x00303434, 0x00303335, 0x002d3236, 0x002b3034, 0x00282f34, 0x00272b30, 0x00272c30, 0x00282c2e, 0x0025282b, 0x0026292c, 0x00242627, 0x00252320, 0x0024201a, 0x00271f18, 0x002c2118, 0x00392c20, 0x00413022, 0x00463020, 0x00432a18, 0x003b2210, 0x00371d0c, 0x00382310, 0x003d2a17, 0x0044301c, 0x0046301d, 0x00472f1d, 0x00452e1c, 0x00432b18, 0x00422b18, 0x00442c1a, 0x00442c1a, 0x00442c1c, 0x00422b1c, 0x0040281a, 0x00402917, 0x00402b16, 0x00402d17, 0x00402e18, 0x00402d16, 0x0043301a, 0x00442e19, 0x004a3320, 0x00442a18, 0x00442b17, 0x00442a16, 0x00402712, 0x003b240f, 0x0039220c, 0x0038200b, 0x003a1e0d, 0x00331809, 0x0031180b, 0x00311a0d, 0x00321a0e, 0x00341b10, 0x00351c0f, 0x00341c0c, 0x00331a09, 0x00321a08, 0x00311a08, 0x00301a08, 0x002f1908, 0x00301a08, 0x00321b09, 0x00341808, 0x00371b0b, 0x00371a0b, 0x00371a0b, 0x00361909, 0x00371a0b, 0x00391b0b, 0x003c1c0c, 0x00401f09, 0x004f2a10, 0x00573010, 0x00552c08, 0x005c310c, 0x0061340c, 0x00603009, 0x0067360f, 0x0068340d, 0x006c3810, 0x006e3b12, 0x006b3810, 0x006b370d, 0x006c380e, 0x006d390d, 0x00713e0f, 0x0074400e, 0x0079420e, 0x007e440f, 0x007e440e, 0x007e440f, 0x007d4410, 0x007a400d, 0x00713d0d, 0x0067350c, 0x0060300c, 0x00592e0c, 0x00502909, 0x004e2909, 0x004c2609, 0x00462108, 0x0044220b, 0x0041230e, 0x00371c0a, 0x002c1808, 0x00281808, 0x00251305, 0x00231205, 0x00231407, 0x00231608, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x0020160b, 0x0020160b, 0x001f1409, 0x001f1409, 0x00201409, 0x0020140a, 0x001f1409, 0x001d1409, 0x001c140e, 0x00181411, 0x00141610, 0x0009140c, 0x0005110c, 0x00091010, 0x00081110, 0x0008120f, 0x0009110f, 0x0008120c, 0x0008110b, 0x0007110a, 0x0008110a, 0x00090f0b, 0x00090f0b, 0x00080e0a, 0x00080e0a, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070c0b, 0x00070c0b, 0x00070c0b, 0x00070c0b, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00091211, 0x0008120f, 0x0008120f, 0x0007110c, 0x0008100b, 0x0008100c, 0x0007100c, 0x0006100c, 0x00050f0c, 0x00050f0b, 0x0005100a, 0x00050f0a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c05, 0x00040c04, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00050c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00030e07, 0x00020e07, 0x00020e07, 0x00020e07, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x00040e0b, 0x0006100c, 0x0008120d, 0x0009140d, 0x00131c14, 0x001f261f, 0x00282b24, 0x0031312c, 0x00353530, 0x00313130, 0x002d3132, 0x00303335, 0x002e3337, 0x002d3238, 0x002c3338, 0x002e3338, 0x00292e33, 0x00292f30, 0x00292c2f, 0x00252829, 0x00242424, 0x00252220, 0x002a241f, 0x002c241e, 0x002b2018, 0x0034281c, 0x003d2d20, 0x00463020, 0x004c3120, 0x00492d1b, 0x00432917, 0x00442e1a, 0x0049331c, 0x004c341f, 0x00503420, 0x00523521, 0x00513420, 0x004d311d, 0x004b301c, 0x004b311c, 0x004b311c, 0x004c311f, 0x00482f1d, 0x00452c1b, 0x00442c18, 0x00452d17, 0x00442e16, 0x00432d15, 0x00412b14, 0x00422c16, 0x00402814, 0x00442b18, 0x00452d1a, 0x00422a18, 0x003f2915, 0x003d2713, 0x003a250f, 0x0038230c, 0x0037200c, 0x00371c0c, 0x00351b0c, 0x0031180b, 0x0030180c, 0x0031180c, 0x0034180c, 0x0035180c, 0x00371b0c, 0x00371c0b, 0x00371c0a, 0x00361c0a, 0x00341c09, 0x00331c08, 0x00341c08, 0x00381c0a, 0x00351806, 0x00381a09, 0x00371908, 0x00381a09, 0x003a1b0a, 0x003b1c0b, 0x00422210, 0x0043210e, 0x0048240d, 0x00563014, 0x005c3210, 0x0060340d, 0x00683811, 0x006c3c12, 0x006b370d, 0x00733c12, 0x00703a0f, 0x00733b10, 0x00743d11, 0x00723b0e, 0x00703a0c, 0x00773e10, 0x0077400f, 0x007b4411, 0x00804812, 0x00844a11, 0x00874a11, 0x00884a11, 0x00884912, 0x00854811, 0x0080430c, 0x00753f0e, 0x006b370a, 0x0063320b, 0x005d310e, 0x00562d0c, 0x00532c0c, 0x0050280b, 0x004f270d, 0x004d2810, 0x0044220c, 0x00391c0b, 0x00301807, 0x002a1607, 0x00281509, 0x0028170b, 0x00241406, 0x00201305, 0x001f1408, 0x001f1408, 0x00201609, 0x00201508, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201408, 0x001f1408, 0x001d140c, 0x00181411, 0x0014160f, 0x000a140c, 0x0006110c, 0x00091010, 0x00081110, 0x0008120f, 0x0008100d, 0x0008110b, 0x0007110a, 0x0007110a, 0x0007110a, 0x0006100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00080c0b, 0x00080c0b, 0x00080c0b, 0x00080c0b, 0x00070b07, 0x00060b06, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x00091310, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0a, 0x00040e09, 0x00050f0a, 0x00040e09, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d0a, 0x00070e0d, 0x00040c0a, 0x00040c0a, 0x00040c08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00070f08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060d08, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e0b, 0x00060d0b, 0x0008100c, 0x0008100d, 0x000b130d, 0x00182018, 0x001d231c, 0x00252923, 0x0033342e, 0x00343530, 0x00323432, 0x00303434, 0x002f3335, 0x002c3034, 0x002c3036, 0x002e3338, 0x0032373c, 0x0033363b, 0x00323538, 0x00303334, 0x002a2c2d, 0x00262626, 0x0024211f, 0x0028211e, 0x002e241f, 0x002c2118, 0x00322619, 0x003a2c1c, 0x00442f1e, 0x004a301d, 0x004e3320, 0x004f3520, 0x004e331e, 0x0050351d, 0x0053341c, 0x0054341c, 0x00593820, 0x00583821, 0x00593822, 0x00573720, 0x00573821, 0x00563820, 0x0054341e, 0x0050331c, 0x0050321b, 0x0050331c, 0x004c2f18, 0x00442a13, 0x00442b12, 0x00452c14, 0x00442913, 0x00412813, 0x003e2610, 0x003f2613, 0x00422a17, 0x003f2713, 0x003d2610, 0x003c2510, 0x003a2310, 0x0038210d, 0x00371f0d, 0x00341c0c, 0x00331c0c, 0x00301909, 0x00351c0c, 0x00371c0c, 0x003a200d, 0x003c220e, 0x003d220e, 0x003a1e0a, 0x003d220e, 0x00381c08, 0x003a1e0a, 0x00402410, 0x003d200c, 0x003a1a08, 0x003b1b08, 0x003c1c09, 0x003e1e0b, 0x00401e0b, 0x0044230f, 0x004b2711, 0x004f2a10, 0x00562f0f, 0x005d330f, 0x0064360f, 0x006b380f, 0x00713c10, 0x00753f12, 0x00763e0f, 0x00763e0d, 0x00753d0c, 0x00783f0f, 0x007b4110, 0x00783f0c, 0x007c4210, 0x007f4512, 0x00824814, 0x00874912, 0x00884910, 0x00874910, 0x008b4c13, 0x008b4c14, 0x008b4c14, 0x008a4a14, 0x00874810, 0x007c410c, 0x00703c08, 0x0067350a, 0x0060300c, 0x005c2c0c, 0x00582c0d, 0x0054280c, 0x00562d12, 0x004c240b, 0x0047220c, 0x003a1a07, 0x00321808, 0x002d1608, 0x002a160b, 0x00281609, 0x00271609, 0x00221407, 0x0022170a, 0x0023180b, 0x00221509, 0x00221509, 0x00221509, 0x00211408, 0x00241509, 0x00201207, 0x00211308, 0x00231409, 0x0023150a, 0x0023170a, 0x0020180c, 0x001a170f, 0x0015160f, 0x000f110c, 0x0009100b, 0x00091010, 0x0007130f, 0x0007110d, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x00040e09, 0x0005100a, 0x0007100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x000a1410, 0x0007110d, 0x0007110d, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x00050f0c, 0x0005100b, 0x00040f0a, 0x00040e09, 0x0006100b, 0x00040e09, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00080d08, 0x00080d0a, 0x00070e0c, 0x00040c0a, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00080f0b, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e0b, 0x00070e0c, 0x00070e0c, 0x0008100c, 0x000b130d, 0x00182018, 0x001f241d, 0x002b2c26, 0x0032332d, 0x0033342f, 0x00303230, 0x002f3233, 0x002c2f32, 0x00282c30, 0x00282d31, 0x002c3034, 0x002e3337, 0x00303338, 0x00303335, 0x002c3030, 0x002c2d2d, 0x002b2b29, 0x00282420, 0x0027201d, 0x002c211e, 0x002f241c, 0x0034281a, 0x00382819, 0x00422d1c, 0x00472e1b, 0x004b301e, 0x004e3420, 0x00523620, 0x00563820, 0x0059381d, 0x005e3b1f, 0x00633e22, 0x00664027, 0x00674228, 0x00603c22, 0x005f3b20, 0x005e3a20, 0x005d3a20, 0x005a381d, 0x0057351a, 0x00563419, 0x00533018, 0x004c2e14, 0x00492d12, 0x00482c12, 0x00492c15, 0x00472c14, 0x00442813, 0x00432812, 0x00412511, 0x003e240e, 0x003f250f, 0x003f2510, 0x003e2410, 0x003c220e, 0x003b210d, 0x003a200d, 0x00381e0c, 0x00351b0a, 0x00371c0a, 0x003b1f0b, 0x0040240d, 0x0041240d, 0x0040240c, 0x003e1f08, 0x0042230c, 0x0040200a, 0x0045240e, 0x00472610, 0x0042210c, 0x00401d08, 0x00401d08, 0x0044220c, 0x0046240e, 0x0048240e, 0x004c2710, 0x00512b10, 0x00562e0f, 0x00603511, 0x00683a10, 0x006c3a0e, 0x00713c10, 0x00784112, 0x007c4313, 0x00804412, 0x00804412, 0x007f440f, 0x00824712, 0x00844814, 0x00804510, 0x00834811, 0x00844a13, 0x00874b13, 0x008c4c14, 0x008b4c11, 0x008b4c11, 0x008e4e14, 0x008e4f16, 0x008e4f16, 0x008c4c14, 0x008a4b12, 0x0081450e, 0x0074400a, 0x006b380b, 0x0061310b, 0x005f2e0d, 0x005d3010, 0x005c3013, 0x00582c11, 0x0052280e, 0x0049230b, 0x00401f0b, 0x003a1d0e, 0x002e1508, 0x002c180c, 0x002b180c, 0x0027170a, 0x00221407, 0x00201408, 0x00201609, 0x00201609, 0x0022170a, 0x0023160c, 0x0022150b, 0x00201308, 0x001d1005, 0x001c1005, 0x00201208, 0x00201308, 0x001f1308, 0x001d150a, 0x001d1810, 0x00191710, 0x0011100c, 0x000c100c, 0x00091012, 0x0007130f, 0x0006110d, 0x0005100a, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x00050f0a, 0x00010c06, 0x00060f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x000a1410, 0x0008110e, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x0006100b, 0x00040e09, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00080d08, 0x00080d0a, 0x00070e0c, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00071007, 0x00071007, 0x00051008, 0x00051008, 0x00040f08, 0x00050f08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00050c06, 0x00040b04, 0x00040b04, 0x00030c04, 0x00030c04, 0x00040d07, 0x00040d07, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040e09, 0x0005100a, 0x00050f0c, 0x00070e0c, 0x00070e0c, 0x0008100c, 0x000b110c, 0x0019201a, 0x001f241e, 0x00242622, 0x002a2b27, 0x0030302c, 0x00313431, 0x00303434, 0x002d3034, 0x00292e32, 0x002d3236, 0x002d3236, 0x002b2e32, 0x00292c30, 0x002c2e30, 0x002c2e2f, 0x00282828, 0x002a2827, 0x002b2824, 0x002b2421, 0x002a201c, 0x0030241c, 0x003a2c20, 0x003c2c1c, 0x00412c1b, 0x0048301e, 0x004b3020, 0x004d3320, 0x00523420, 0x005d3c27, 0x00603c23, 0x00664023, 0x006a4224, 0x006c4426, 0x006d4528, 0x006b4425, 0x00684224, 0x00653f20, 0x00633c1e, 0x00603a19, 0x005d3717, 0x00593314, 0x00593214, 0x00563313, 0x00513010, 0x004d2c0f, 0x004c2b0f, 0x004c2b0f, 0x004a2b0f, 0x0048290e, 0x0045250e, 0x0042220a, 0x0046270f, 0x0040230b, 0x0041220c, 0x0042230c, 0x0042230d, 0x0041220d, 0x003f200c, 0x0040200c, 0x0044240e, 0x00482810, 0x0049270d, 0x0048270b, 0x004a280c, 0x0049260a, 0x00482409, 0x004b260b, 0x004f2a0f, 0x004e290d, 0x00492408, 0x00482106, 0x004a2409, 0x004d250b, 0x004c240b, 0x0050280d, 0x00582d12, 0x005e3113, 0x00633512, 0x00693910, 0x006d3b0f, 0x00744010, 0x007b4411, 0x007e4411, 0x00824710, 0x00854911, 0x0086480f, 0x00884a10, 0x00894c13, 0x008a4c13, 0x008b4d12, 0x008b4d13, 0x008a4d12, 0x008b4d12, 0x008d4e11, 0x008d4e11, 0x008e4f12, 0x00905116, 0x00905016, 0x008f5015, 0x008f4f14, 0x008d4f14, 0x00874c12, 0x007b440e, 0x006e3c0d, 0x0062320a, 0x0060300d, 0x00603210, 0x00603516, 0x00572c0f, 0x00542a0e, 0x00492309, 0x00482710, 0x00351806, 0x00341c0d, 0x002c180c, 0x0029180c, 0x0028180b, 0x00231508, 0x00201408, 0x001d1205, 0x001e1308, 0x001f1407, 0x001f1408, 0x001f1408, 0x001f1308, 0x001d1106, 0x001c1107, 0x001d1208, 0x001e1209, 0x001b1108, 0x00181005, 0x00171209, 0x0018160e, 0x0014130c, 0x000c100c, 0x00081010, 0x0006110d, 0x0006100c, 0x00070f0a, 0x0006100b, 0x0008120c, 0x0006100b, 0x0005100a, 0x0007110c, 0x0007110c, 0x00050e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x000a1410, 0x0008110e, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x0006100b, 0x00040e09, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00080d08, 0x00080d08, 0x00070f0a, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040e09, 0x0005100a, 0x00050f0c, 0x00050f0c, 0x00070e0c, 0x0008100c, 0x000a100b, 0x00171d18, 0x001a201a, 0x00212520, 0x00292a26, 0x0030302c, 0x00313433, 0x00313437, 0x00313438, 0x002f3438, 0x002c3034, 0x00282d31, 0x0026282d, 0x00222529, 0x00242627, 0x00272928, 0x00272725, 0x00272623, 0x002e2926, 0x00362e2a, 0x002e221c, 0x002d2218, 0x003a2c20, 0x00423122, 0x00442f1d, 0x00493120, 0x004d3423, 0x00503623, 0x00543623, 0x0063422c, 0x006b462d, 0x0072492b, 0x00774c2d, 0x00764a2b, 0x00714726, 0x00704724, 0x006b4420, 0x0069421f, 0x00683e1b, 0x00663c18, 0x00643c17, 0x00623815, 0x00633715, 0x00603814, 0x005b3511, 0x0058310f, 0x00563010, 0x0054300f, 0x00532e10, 0x00522d0f, 0x004d280c, 0x00482509, 0x004c280d, 0x004b280d, 0x004a260e, 0x004a260e, 0x0049260e, 0x0047240b, 0x004c2810, 0x004c2810, 0x004d2a10, 0x00502b10, 0x00502c0e, 0x00532d0d, 0x00542d0d, 0x00542c0c, 0x00522a0b, 0x00562c0c, 0x00582d0f, 0x00572c0d, 0x00512708, 0x00532708, 0x0055290b, 0x0054290b, 0x0054290b, 0x005c2e10, 0x00623414, 0x00653613, 0x006a3912, 0x00703d10, 0x00794311, 0x00804813, 0x00824a12, 0x00844a10, 0x00884c10, 0x00894c0e, 0x00894c0d, 0x008c4c0f, 0x008d5010, 0x008c4e10, 0x008d4e10, 0x008d4e10, 0x008d4e10, 0x008d4e10, 0x00905013, 0x008f5011, 0x008f5011, 0x00905214, 0x00905114, 0x008f5014, 0x008f5013, 0x008e4f12, 0x00884e10, 0x007c470d, 0x006f3c0b, 0x0068380d, 0x0062320c, 0x0060320d, 0x005c330f, 0x0059300f, 0x00562c0d, 0x0050290c, 0x00422009, 0x0040240f, 0x00341b0a, 0x002b170c, 0x00281709, 0x00251508, 0x00221406, 0x00201308, 0x001c1104, 0x001b1005, 0x001b1104, 0x001a1105, 0x00191105, 0x00181105, 0x00181004, 0x00191006, 0x001c1208, 0x001c140a, 0x001e140b, 0x001c140a, 0x00181007, 0x0016120b, 0x0013130c, 0x000d100c, 0x00080f0e, 0x0005100c, 0x0006100b, 0x00080f0a, 0x0007100b, 0x0009130d, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00050d09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0007130f, 0x00081410, 0x0008130f, 0x0007110d, 0x0006100d, 0x0006100d, 0x0006100c, 0x0006100c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c09, 0x00040c08, 0x00040d08, 0x00040e07, 0x00040d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c07, 0x00060d06, 0x00050c06, 0x00050c05, 0x00050c05, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00060d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060f09, 0x00040e0a, 0x0005100a, 0x0005100b, 0x0008100c, 0x00080f09, 0x00161b16, 0x001c211c, 0x00212520, 0x002c2e2a, 0x0030322f, 0x00303232, 0x002e3134, 0x00303237, 0x002d3036, 0x002c2f34, 0x002b3034, 0x00272a2f, 0x0024282a, 0x00242525, 0x00222421, 0x0021221f, 0x0022201c, 0x0027221e, 0x00342c28, 0x00392e27, 0x0032261b, 0x0037291a, 0x00423120, 0x004a3424, 0x004a3422, 0x004c3422, 0x00503825, 0x005a3d2c, 0x00684834, 0x006f4932, 0x00754c2d, 0x007b4f2e, 0x007d4f2d, 0x007b4c29, 0x00784823, 0x0074441f, 0x0073441d, 0x0071421c, 0x006c3e18, 0x006a3c15, 0x00683b14, 0x00683a14, 0x00653a12, 0x00633910, 0x005f360c, 0x005e360d, 0x005c340f, 0x00593110, 0x00572f0d, 0x00542d0d, 0x00522c0c, 0x00512c0c, 0x00522e0e, 0x00512d0d, 0x00512d0d, 0x00512c0e, 0x00512a0c, 0x00542e10, 0x00542e0f, 0x00512b0b, 0x00542c0c, 0x00572f0e, 0x0059300d, 0x005b3210, 0x005c3110, 0x005c310f, 0x005d300f, 0x005e3110, 0x005f3210, 0x005e300f, 0x005c2e0d, 0x005d2f0c, 0x005e2f0c, 0x005e2f0b, 0x0062340d, 0x00673810, 0x006c3c10, 0x00713e11, 0x00774011, 0x007f4513, 0x00844910, 0x00874c10, 0x008c5013, 0x008e5014, 0x008e5010, 0x008c4d0e, 0x00904f0e, 0x00925010, 0x00935010, 0x00935010, 0x00925010, 0x00925010, 0x00925010, 0x00905311, 0x00905310, 0x00905110, 0x00905212, 0x00905111, 0x00905111, 0x00905010, 0x008f5010, 0x008a4c0e, 0x0081460c, 0x00743e09, 0x006d380c, 0x006a3911, 0x00633610, 0x005d310e, 0x005c3310, 0x005a300f, 0x00552b0d, 0x004c280d, 0x0040200b, 0x00341906, 0x002c1709, 0x002a170a, 0x00261408, 0x00211205, 0x001e1205, 0x001c1106, 0x001c1206, 0x001a1106, 0x001a1208, 0x001b1409, 0x001b1409, 0x001c140a, 0x001a1208, 0x00191208, 0x001c140a, 0x001e160d, 0x001f170e, 0x001c140c, 0x001c140c, 0x0018140d, 0x0011130d, 0x00080f0e, 0x0004100c, 0x0005100c, 0x00080e0a, 0x0006100b, 0x0006100b, 0x0007100a, 0x0007100a, 0x00050e09, 0x00050e09, 0x00040c08, 0x00040c08, 0x00040d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00060d08, 0x00060c08, 0x00050c08, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c08, 0x00070d09, 0x00060d08, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006130f, 0x0006130f, 0x0006110d, 0x0006110d, 0x0006110d, 0x0006110d, 0x0006100c, 0x0006100c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x0004100a, 0x0005100a, 0x000c120e, 0x000c130d, 0x00161c16, 0x00212520, 0x00282c28, 0x00303430, 0x002e322d, 0x00262828, 0x00232629, 0x00272a2e, 0x002c2f35, 0x0033353c, 0x0033383c, 0x002e3035, 0x002b2e30, 0x00292b2a, 0x00262825, 0x00242521, 0x00252420, 0x0026211d, 0x002a211d, 0x00352b21, 0x003c2e21, 0x00382819, 0x00433020, 0x004c3826, 0x004e3826, 0x004e3827, 0x00543e2d, 0x00624634, 0x006c4b38, 0x00704b34, 0x00795033, 0x007f5234, 0x00825231, 0x0080502c, 0x007d4a25, 0x007c4821, 0x007a4820, 0x0078461e, 0x0076441c, 0x0073421a, 0x00703f18, 0x006c3d13, 0x006c3d13, 0x006c3c11, 0x00683b10, 0x0066380d, 0x00643810, 0x00633610, 0x005f340f, 0x005c330e, 0x005c330e, 0x005b340e, 0x005b340e, 0x0058310d, 0x0058310d, 0x0059310d, 0x005a310d, 0x005c3410, 0x005e340f, 0x005c320c, 0x005f340f, 0x00623811, 0x00643813, 0x00643812, 0x00663812, 0x00673812, 0x00683812, 0x00683813, 0x00693914, 0x00683812, 0x00683711, 0x00683711, 0x00683810, 0x0068380e, 0x006c3c0e, 0x00704010, 0x00744110, 0x00794410, 0x00804710, 0x00874b14, 0x008b4e11, 0x008e5011, 0x008f5012, 0x00905113, 0x00905112, 0x00915010, 0x00935010, 0x00965111, 0x00975111, 0x00965211, 0x00955211, 0x00955211, 0x00945110, 0x00905110, 0x00905210, 0x00905111, 0x00905111, 0x00915110, 0x00915110, 0x0090500e, 0x0090500e, 0x008c4d10, 0x0086490d, 0x007c400d, 0x0070380b, 0x006b3810, 0x00663610, 0x00633410, 0x005d3310, 0x005a2f0d, 0x00562b0c, 0x004f280e, 0x0043200b, 0x00371906, 0x002d1808, 0x002b170a, 0x0029180c, 0x00251508, 0x00211408, 0x00201409, 0x001f150a, 0x001c140a, 0x001c140a, 0x001c140a, 0x001c1409, 0x001c1409, 0x00181207, 0x00181106, 0x00181108, 0x001b140c, 0x001c150c, 0x001d140c, 0x0020140e, 0x001c140e, 0x0014130c, 0x00080f0c, 0x0004100c, 0x00050f0c, 0x00080e0a, 0x0006100a, 0x0005100a, 0x0008100b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c08, 0x00080e08, 0x00070d07, 0x00070e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d02, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071410, 0x00071410, 0x0007120e, 0x0006120e, 0x0006110d, 0x0005110c, 0x0006100c, 0x0006100c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x0004100a, 0x0005100a, 0x0009120d, 0x000c130e, 0x00181c18, 0x00262924, 0x002c302b, 0x002c2f2a, 0x002c2e2a, 0x002c2e2d, 0x002c2f32, 0x00313438, 0x0035383e, 0x0034373d, 0x0033363b, 0x00303136, 0x00282c2d, 0x002a2c2b, 0x002a2c2a, 0x002a2b28, 0x002c2a25, 0x002c2723, 0x002d2520, 0x002f2419, 0x003c2f21, 0x003e2e1f, 0x00443021, 0x004c3627, 0x004e3827, 0x004e3828, 0x00543c2c, 0x00614535, 0x006d4c3b, 0x0075503c, 0x0080573a, 0x00845739, 0x00835433, 0x0084512f, 0x00824e28, 0x00804c25, 0x007e4b23, 0x007c4a21, 0x007c4920, 0x007b481e, 0x0078451c, 0x00754218, 0x00734016, 0x00714014, 0x006e3c10, 0x006c3910, 0x006c3b10, 0x00693a0e, 0x0067370c, 0x0064370c, 0x0063370c, 0x0062350f, 0x0061360f, 0x0061370e, 0x0062370f, 0x0063360d, 0x0063370e, 0x00683810, 0x00673810, 0x0067380e, 0x00693c10, 0x006c3c12, 0x006c3c12, 0x006e3d12, 0x006f3d11, 0x00703d12, 0x00713e13, 0x00713e14, 0x00723e14, 0x00713d13, 0x00703c11, 0x00703c11, 0x00703c10, 0x00713c0e, 0x0075400f, 0x0079440f, 0x007d450e, 0x00834810, 0x00884a0f, 0x008c4c10, 0x008f4f10, 0x00925013, 0x00935113, 0x00935113, 0x00935112, 0x00945112, 0x00965011, 0x00985011, 0x00985111, 0x00975210, 0x00975211, 0x00965111, 0x00955211, 0x00935311, 0x00905210, 0x00905111, 0x00915111, 0x0090500e, 0x0090500e, 0x0090500f, 0x0090500e, 0x008d4e10, 0x00884a10, 0x007d420e, 0x00743c0e, 0x006c380d, 0x0068380f, 0x00683811, 0x0060330e, 0x00592c0a, 0x00562b0c, 0x004f280e, 0x0044200c, 0x00391c09, 0x00301b0b, 0x00291508, 0x0028170b, 0x00271709, 0x0024150a, 0x0021140a, 0x0020160c, 0x001e170d, 0x001d150c, 0x001d150c, 0x001b1409, 0x00181107, 0x00181208, 0x00141006, 0x00130e04, 0x00171108, 0x0018130a, 0x001b130c, 0x001f140e, 0x001c150f, 0x0015140d, 0x000c110d, 0x0007110c, 0x00050f0c, 0x00080e0b, 0x0006100a, 0x0005100a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050c08, 0x00050c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d06, 0x00050c05, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060c05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c08, 0x00080e08, 0x00070e05, 0x00070e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d02, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x0007130f, 0x0007130f, 0x0006110d, 0x0005110b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00030f09, 0x00050e09, 0x00070d09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x0004100a, 0x0005100a, 0x0009120c, 0x000e1610, 0x001e241e, 0x00282b27, 0x002a2c28, 0x002d302c, 0x002d302c, 0x002c2e2d, 0x002a2d30, 0x002a2d32, 0x002d3037, 0x002c3036, 0x002d3034, 0x002e2f34, 0x002d2f32, 0x002b2c2d, 0x002a2c2b, 0x002b2c28, 0x002c2b26, 0x002d2824, 0x00302622, 0x0035291f, 0x003b2c20, 0x00413021, 0x00493526, 0x004a3426, 0x004c3426, 0x00503829, 0x005c4335, 0x006b4e40, 0x00755445, 0x007b5644, 0x0080563a, 0x00835538, 0x00855434, 0x00875431, 0x0086512c, 0x00845028, 0x00824e25, 0x00804c24, 0x007f4b22, 0x007d481f, 0x007c481d, 0x007c471c, 0x007c4519, 0x007a4317, 0x00784013, 0x00753e10, 0x00743f10, 0x00723c0e, 0x006e3b0b, 0x006d3c0b, 0x006c3b0c, 0x006b3a0f, 0x006b3a10, 0x006b3a0e, 0x006c3c0f, 0x006c3c0e, 0x006d3b0e, 0x00703e10, 0x00713e0f, 0x00734010, 0x00764311, 0x00774413, 0x00784313, 0x00784312, 0x007a4311, 0x007a4412, 0x007c4312, 0x007c4313, 0x007c4313, 0x007b4211, 0x007c4010, 0x007c4010, 0x007c410f, 0x007c420d, 0x0080460f, 0x0082480f, 0x00874b11, 0x008c4d14, 0x00914f14, 0x00945013, 0x00965114, 0x00965415, 0x00975415, 0x00975414, 0x00985414, 0x00995312, 0x009b5212, 0x009c5212, 0x009c5211, 0x00985411, 0x00985412, 0x00985414, 0x00985414, 0x00945412, 0x00915110, 0x00915111, 0x00915111, 0x00945110, 0x00945211, 0x00915210, 0x00915110, 0x008d4e10, 0x00884910, 0x007d420e, 0x00753c0f, 0x006e380d, 0x006c380e, 0x006b3810, 0x0064350f, 0x005e300d, 0x00582c0e, 0x004c240b, 0x0046210c, 0x003a1d0a, 0x002e1808, 0x00281406, 0x00261408, 0x00231407, 0x00201307, 0x001d1106, 0x001a1007, 0x00181008, 0x00181006, 0x00171005, 0x001b1409, 0x001b140b, 0x001c160d, 0x0018140b, 0x00151208, 0x00120f06, 0x00130e06, 0x001a110b, 0x001f140e, 0x001d150f, 0x0016140e, 0x0010130f, 0x0009110d, 0x00070f0c, 0x00080e0c, 0x0006100a, 0x0005100a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d06, 0x00050d05, 0x00060d03, 0x00060d03, 0x00060d03, 0x00060d04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c06, 0x00080f06, 0x00070e04, 0x00070e04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d02, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x0008130f, 0x0008120e, 0x0006110c, 0x0006110b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051009, 0x00040f08, 0x00040d08, 0x00030d08, 0x00040d08, 0x00040d08, 0x00040e08, 0x00040e08, 0x00050d08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050c08, 0x00050c08, 0x00050d07, 0x00050d06, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00050c07, 0x00050c06, 0x00050c06, 0x00040c06, 0x00040c06, 0x00050c07, 0x00050c07, 0x00050c06, 0x00040c06, 0x00050c06, 0x00050c07, 0x00050c07, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040d09, 0x00040d09, 0x00040d09, 0x00040d09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040f09, 0x00050e09, 0x00060e09, 0x00080c09, 0x00060e09, 0x00050e09, 0x00050e08, 0x00040e08, 0x00041009, 0x00051009, 0x000b140d, 0x00161e18, 0x00242a24, 0x00252823, 0x001c1f1a, 0x001c1e19, 0x001a1c18, 0x001c1f1e, 0x00202325, 0x00292c30, 0x00303439, 0x00313439, 0x00313438, 0x002f3034, 0x002b2c30, 0x002a2c2d, 0x00282b29, 0x00262624, 0x00282722, 0x002d2824, 0x00312721, 0x0033271d, 0x003a2c1f, 0x00443323, 0x004c3728, 0x0050382b, 0x00543c2e, 0x00563f30, 0x005c4436, 0x006c5042, 0x00775748, 0x007c5847, 0x00825a40, 0x00865a3e, 0x00885838, 0x008a5734, 0x0088542e, 0x0086512b, 0x00855028, 0x00854f26, 0x00834c23, 0x00814b20, 0x0080491f, 0x0080481c, 0x0081481a, 0x00834918, 0x00834a18, 0x007e4612, 0x007c4410, 0x007a420f, 0x0076400c, 0x0074400c, 0x0074400b, 0x00723d0d, 0x00723f0c, 0x00723f0c, 0x0073400c, 0x00743f0c, 0x00743f0b, 0x0078420d, 0x0078420c, 0x007c4610, 0x007e4811, 0x00804811, 0x00804911, 0x00814810, 0x00814810, 0x00834810, 0x00844911, 0x00844911, 0x00844810, 0x00834810, 0x0083460f, 0x00844610, 0x0084470e, 0x0084480f, 0x0085490c, 0x00874a0d, 0x008e4d12, 0x00925014, 0x00975314, 0x00995414, 0x00995412, 0x00995411, 0x009a5412, 0x009a5412, 0x009a5411, 0x009b5411, 0x009c5310, 0x009c5210, 0x009c5310, 0x00995410, 0x009a5411, 0x009b5414, 0x00995515, 0x00945212, 0x0091500f, 0x00915111, 0x00935111, 0x00955312, 0x00965413, 0x00955413, 0x00935311, 0x008e5011, 0x00874b11, 0x007d420e, 0x00773c0e, 0x00703a0d, 0x006e380e, 0x006c380f, 0x0067360f, 0x0061330f, 0x00592e0e, 0x004f280c, 0x0046220b, 0x003c1c09, 0x002c1705, 0x002a1707, 0x00241407, 0x00201204, 0x001d1205, 0x001b1005, 0x00160c04, 0x00140c04, 0x00130c02, 0x00120b01, 0x00130c03, 0x00140d04, 0x00130f06, 0x00121108, 0x00141309, 0x0017150d, 0x0019140d, 0x001c110c, 0x00201410, 0x001f1711, 0x0018150f, 0x0010130e, 0x0009110c, 0x0008100c, 0x00080d0c, 0x00050f09, 0x00050f09, 0x00060e09, 0x00060e08, 0x00050d09, 0x00050d09, 0x00060d08, 0x00060d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c06, 0x00070e07, 0x00070d05, 0x00070d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c04, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x0008120f, 0x0008120d, 0x0007110c, 0x0007110c, 0x0006100b, 0x0005100a, 0x00051009, 0x00040f08, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c09, 0x00040c09, 0x00060e0b, 0x00060e0a, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050c07, 0x00060d07, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00041008, 0x0008110a, 0x00121b14, 0x00222822, 0x00191c18, 0x000b0d08, 0x0010130e, 0x00161814, 0x00222424, 0x00282c2e, 0x00272a2e, 0x002b2e32, 0x002d3034, 0x002e3035, 0x002d2e33, 0x002c2e31, 0x002a2c2c, 0x00272828, 0x00242423, 0x00282724, 0x002f2823, 0x00312721, 0x0034281e, 0x003d2d21, 0x00443022, 0x004d3628, 0x00543c2e, 0x00583f31, 0x005a4134, 0x005e4738, 0x00684d3f, 0x00735344, 0x007a5546, 0x00855c48, 0x00885d42, 0x0089593a, 0x008a5734, 0x0088532e, 0x0087512b, 0x00885129, 0x00885027, 0x00875026, 0x00864f24, 0x00885023, 0x00884e20, 0x00864c1b, 0x00864a16, 0x00864c15, 0x00884c15, 0x00834a12, 0x00814810, 0x007e450f, 0x007e440f, 0x007d440e, 0x007c430d, 0x007c430c, 0x007e450d, 0x007e450c, 0x007e440d, 0x007f440c, 0x0082480e, 0x0082480f, 0x00844a12, 0x00874a12, 0x00884c10, 0x00884c10, 0x00884d10, 0x008a4c10, 0x008a4c12, 0x00894b11, 0x00894b10, 0x00884b0f, 0x00884b0f, 0x008a4c10, 0x008a4c12, 0x008a4c12, 0x008b4d12, 0x008d5012, 0x008f5111, 0x00945010, 0x00955210, 0x009a5612, 0x009c5711, 0x009f5612, 0x00a05713, 0x009e5511, 0x009e5511, 0x009e5512, 0x009e5513, 0x009e5512, 0x009d5411, 0x009d5510, 0x009c5712, 0x009c5714, 0x00995412, 0x00995414, 0x00955213, 0x00915010, 0x00915010, 0x00945010, 0x00945211, 0x00965413, 0x00965413, 0x00935311, 0x008e5011, 0x00884c13, 0x007e430e, 0x00773d0e, 0x00743c0e, 0x006f390c, 0x006c380d, 0x006b3810, 0x0063350f, 0x005b300d, 0x0050290b, 0x0048240a, 0x003c1d07, 0x00301907, 0x002a1707, 0x00251406, 0x00201305, 0x001c1304, 0x001c1307, 0x001a1308, 0x001a1209, 0x00191209, 0x00181109, 0x00171008, 0x00140f06, 0x00100d04, 0x00100e05, 0x00121008, 0x00141109, 0x0017110a, 0x001c100c, 0x00201410, 0x00201812, 0x0018150f, 0x0010120c, 0x0008110a, 0x0008100b, 0x00070c0b, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x0008120f, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100a, 0x0005100a, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040c04, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c08, 0x00040c08, 0x0008100b, 0x0008100b, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0004100a, 0x0005100b, 0x000c160f, 0x001e241f, 0x001c1f1a, 0x00171914, 0x001c1e1a, 0x002c2e2a, 0x00303330, 0x002f3333, 0x002b2d31, 0x002b2e32, 0x002c3034, 0x002d3034, 0x002e2f34, 0x002e2f32, 0x002c2d2f, 0x00292b2c, 0x00292a28, 0x002f2d2a, 0x002a241f, 0x00302520, 0x00372a20, 0x003f3023, 0x00453224, 0x004d3729, 0x00543c2e, 0x00583e31, 0x00583f32, 0x005c4436, 0x006b5042, 0x0078574b, 0x00805c4e, 0x00885f4b, 0x00895c44, 0x008a593a, 0x008a5634, 0x0089532c, 0x00875128, 0x008a5328, 0x008a5328, 0x00895227, 0x00885224, 0x008a5223, 0x00895221, 0x008b501c, 0x008c4f18, 0x008b4f17, 0x008c5015, 0x008c5015, 0x008a4e14, 0x00884c11, 0x00874b10, 0x00874a10, 0x00854a0f, 0x00854a0f, 0x00884c12, 0x00884c12, 0x008a4c10, 0x008a4c10, 0x008c4e13, 0x008c4f14, 0x008f4f15, 0x00905017, 0x00905014, 0x00905011, 0x00905011, 0x00905112, 0x00905113, 0x00905113, 0x00905213, 0x00905113, 0x00905112, 0x00905013, 0x00905015, 0x00905016, 0x00905114, 0x00905212, 0x00925311, 0x00965110, 0x00985310, 0x009d5811, 0x009f5810, 0x00a15812, 0x00a25914, 0x00a05813, 0x00a05713, 0x00a05713, 0x00a05713, 0x009f5612, 0x009f5612, 0x009e5611, 0x009d5712, 0x009c5713, 0x00995412, 0x00985313, 0x00965211, 0x00935010, 0x00925010, 0x0094500f, 0x00945010, 0x00955412, 0x00955412, 0x00935211, 0x008e5013, 0x00884d14, 0x00804410, 0x00783e0e, 0x00743c0d, 0x00703b0c, 0x00703c0f, 0x006e3c11, 0x0064370d, 0x005b300b, 0x00502a09, 0x00482509, 0x003d1d06, 0x00331a08, 0x00291304, 0x00271407, 0x00221306, 0x001e1405, 0x001e1308, 0x001d1108, 0x001c110a, 0x001c120b, 0x001c130c, 0x001d140c, 0x001b130a, 0x00191209, 0x00181109, 0x00140d06, 0x00140d06, 0x00170e08, 0x001a1009, 0x001f140e, 0x001e1710, 0x0018140c, 0x0011110c, 0x0008100a, 0x0007110c, 0x00080f0b, 0x00081009, 0x00081009, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x0008120e, 0x0007110c, 0x0006100b, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040c03, 0x00040c06, 0x00040d07, 0x00050e08, 0x00050d08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00050f0c, 0x0004100c, 0x00040f0c, 0x00050f0a, 0x00151a16, 0x00242520, 0x00252621, 0x00282824, 0x002d2f2b, 0x00303230, 0x00303334, 0x00303436, 0x00313438, 0x00323539, 0x00323539, 0x00313236, 0x002e2f32, 0x002e2f32, 0x002b2c2f, 0x002a2a2a, 0x00282623, 0x002c231f, 0x00302520, 0x00372821, 0x003f3024, 0x00453224, 0x004d382b, 0x00584034, 0x005e4238, 0x005f4438, 0x00684f44, 0x0075584c, 0x007f6054, 0x00815d52, 0x00885f4b, 0x008a5d44, 0x008c5b3c, 0x008a5533, 0x008a542d, 0x00895429, 0x00895325, 0x00895324, 0x00895324, 0x008a5322, 0x008a5320, 0x008a5320, 0x008c511b, 0x008f5018, 0x00915318, 0x00905116, 0x00905113, 0x00905113, 0x008f5011, 0x00905010, 0x00915013, 0x00915013, 0x00915012, 0x00905011, 0x00904f10, 0x00915011, 0x00914f11, 0x00935013, 0x00945214, 0x00945116, 0x00975215, 0x00965414, 0x00965413, 0x00965411, 0x00965411, 0x00945410, 0x0092520f, 0x00925210, 0x00935210, 0x00935211, 0x00935313, 0x00935214, 0x00935214, 0x00935314, 0x00985817, 0x009b5a16, 0x009e5814, 0x009f5812, 0x00a05910, 0x00a1590f, 0x00a05810, 0x00a05811, 0x00a15812, 0x00a15812, 0x00a15813, 0x00a05713, 0x009f5712, 0x009f5612, 0x009d5511, 0x009c5611, 0x009c5513, 0x009a5311, 0x0096500f, 0x0094500c, 0x0094500c, 0x0094500e, 0x0094510f, 0x0096500f, 0x00955210, 0x00955312, 0x00925112, 0x008e5013, 0x00884c14, 0x00844814, 0x007b4110, 0x00763e0e, 0x00713d0c, 0x00703c0d, 0x006e3c10, 0x00673a0e, 0x005d340b, 0x00522b08, 0x004a2507, 0x00401d05, 0x00381c0c, 0x002f1508, 0x002c180b, 0x0029190c, 0x0026190c, 0x0026190f, 0x0023160d, 0x0023150f, 0x0020150e, 0x0020150e, 0x0022160f, 0x0022160f, 0x0020150c, 0x0020140c, 0x001e1309, 0x001e1309, 0x001e140a, 0x001f140b, 0x0020150c, 0x001f160c, 0x0019140b, 0x0013110c, 0x00080f08, 0x00051008, 0x00070f0a, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x0008120e, 0x0007110c, 0x0006100b, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c05, 0x00040c04, 0x00040c06, 0x00040d07, 0x00050e08, 0x00050d07, 0x00040c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050f0c, 0x00050f0c, 0x0004100c, 0x0005100c, 0x0005100d, 0x0007110e, 0x00101611, 0x001c1d18, 0x00272824, 0x002c2c28, 0x002c2c2b, 0x00303231, 0x00303335, 0x00303337, 0x00303338, 0x00303338, 0x00303438, 0x00323438, 0x002f3034, 0x002c2e31, 0x00282a2b, 0x00282827, 0x002e2c29, 0x002c2420, 0x00302420, 0x003a2b24, 0x00423228, 0x00453427, 0x00503c2f, 0x005c4438, 0x005c4238, 0x005f4439, 0x006c5246, 0x0074584c, 0x007d5d53, 0x00836054, 0x008c6450, 0x008b5e47, 0x008c5a3b, 0x008a5731, 0x008b552c, 0x008b5629, 0x008c5526, 0x008b5524, 0x008b5322, 0x008c5220, 0x008b521e, 0x008b521c, 0x008c5018, 0x00925318, 0x0097581c, 0x0097561a, 0x00945415, 0x00945211, 0x00945110, 0x00945211, 0x00965413, 0x00965413, 0x00965413, 0x00945110, 0x00945110, 0x00955211, 0x00955211, 0x00955211, 0x00955211, 0x00975013, 0x00985212, 0x00985414, 0x00995614, 0x00995611, 0x00995610, 0x00995610, 0x00995610, 0x00985512, 0x00985412, 0x00985412, 0x00985413, 0x00985414, 0x00985414, 0x00995515, 0x009a5713, 0x009c5813, 0x009f5812, 0x009f5811, 0x00a0580e, 0x00a35a0f, 0x00a25a10, 0x00a25a11, 0x00a15810, 0x00a15810, 0x00a15811, 0x00a15812, 0x009f5810, 0x009f5710, 0x009d5610, 0x009c5611, 0x009c5613, 0x00995311, 0x0096500f, 0x0095500b, 0x0094510c, 0x0094510d, 0x0094510d, 0x00975110, 0x00975310, 0x00955312, 0x00925212, 0x008e4f13, 0x00884c13, 0x00834811, 0x007f4514, 0x007b4310, 0x0076400f, 0x00723e0f, 0x006e3c0e, 0x00693b0d, 0x0060360c, 0x00542d08, 0x004c2605, 0x00401f04, 0x003a1d0b, 0x00311809, 0x002b1408, 0x00281609, 0x0024160a, 0x0023160b, 0x00201409, 0x0020120a, 0x001d1209, 0x001c1108, 0x001c1108, 0x001d1108, 0x001e1107, 0x00201409, 0x0022150b, 0x00201409, 0x001e1409, 0x001e1308, 0x001d1308, 0x001c1309, 0x001a140c, 0x0013120b, 0x000a0f08, 0x00050f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x0008120e, 0x0007110d, 0x0007110c, 0x0005100a, 0x00040f08, 0x00051008, 0x00051008, 0x00060f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050e06, 0x00060e06, 0x00050e06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x0005100a, 0x0005110b, 0x0005100c, 0x0004110c, 0x0006100e, 0x00091110, 0x000d130e, 0x0020221e, 0x002f302c, 0x00343433, 0x00343434, 0x002f3132, 0x002b2e30, 0x002b2e32, 0x002d3037, 0x00303238, 0x0032343b, 0x0034353a, 0x00323437, 0x002e3033, 0x002c2d30, 0x002b2b2c, 0x002a2827, 0x002c2320, 0x002e211f, 0x00372822, 0x00423229, 0x004c3a2e, 0x00544033, 0x005b4438, 0x005d4439, 0x0062483c, 0x00684d43, 0x0074574d, 0x0085645c, 0x0089645b, 0x008c6453, 0x008c624a, 0x008c5c3c, 0x008c5934, 0x008d582e, 0x008d572a, 0x008c5625, 0x008d5423, 0x00915523, 0x008f531f, 0x008e521c, 0x008f531a, 0x008f5218, 0x00905418, 0x0096561a, 0x0098561a, 0x00985616, 0x00995514, 0x00985413, 0x00975312, 0x00975312, 0x00985414, 0x00985414, 0x00985414, 0x00985414, 0x00965411, 0x00965510, 0x0098540e, 0x0098540e, 0x0098540e, 0x00985410, 0x009a5512, 0x009c5713, 0x009c5813, 0x009c5812, 0x009c5711, 0x009c5711, 0x009c5711, 0x009c5711, 0x009c5711, 0x009c5812, 0x009c5812, 0x009c5812, 0x009c5812, 0x00a05914, 0x00a35c17, 0x00a25c13, 0x00a35c14, 0x00a45a10, 0x00a45a10, 0x00a35b10, 0x00a15c10, 0x00a05b10, 0x00a05b10, 0x00a0580f, 0x009f570f, 0x009f5810, 0x009c5510, 0x009a530e, 0x009a530f, 0x009a5310, 0x0098530f, 0x0096500d, 0x0096510c, 0x0096500d, 0x0097520e, 0x0097520e, 0x0098530f, 0x00975311, 0x00955314, 0x00925212, 0x008c4d10, 0x00884c13, 0x00844912, 0x00804711, 0x007f4713, 0x007c4514, 0x00784413, 0x00713d10, 0x0069390c, 0x0064340c, 0x005a2d08, 0x004d2404, 0x00482408, 0x00381c07, 0x002f1704, 0x002a1406, 0x00241307, 0x00231509, 0x00211408, 0x00201409, 0x00201408, 0x001d1205, 0x001b1004, 0x001c1205, 0x001d1307, 0x001e1308, 0x001e1407, 0x001f1408, 0x001e1408, 0x001e1508, 0x001f150b, 0x0020160c, 0x00231710, 0x00201713, 0x0014130d, 0x000b0f08, 0x00071007, 0x00051008, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c07, 0x00080e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0008120e, 0x0007110d, 0x0007110d, 0x0007110c, 0x0005100a, 0x00040f08, 0x00051008, 0x00051008, 0x00060f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050e06, 0x00060e06, 0x00050e06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040d08, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x0005100a, 0x0005110b, 0x0004110b, 0x0004130c, 0x0006100b, 0x000a100d, 0x0010140f, 0x00272824, 0x00353633, 0x002e2e2e, 0x00272728, 0x002a2b2e, 0x002f3234, 0x00303237, 0x002c2f35, 0x00282a30, 0x0024272c, 0x00242529, 0x0028292c, 0x002a2c2f, 0x002e2f31, 0x002c2c2c, 0x002b2926, 0x002e2722, 0x00312522, 0x00372823, 0x00423229, 0x004c3a2f, 0x00544034, 0x005c4439, 0x005d453a, 0x0063493d, 0x006f5449, 0x007f6159, 0x008a6a62, 0x008a665d, 0x008e6656, 0x008f644d, 0x008f5f40, 0x00905c38, 0x00905c30, 0x00905a2c, 0x008f5828, 0x00905624, 0x00925523, 0x00915420, 0x0090541d, 0x0091551b, 0x0090541a, 0x0093561c, 0x0097571c, 0x00985819, 0x009a5718, 0x009b5815, 0x009a5714, 0x00995614, 0x00995614, 0x009a5615, 0x00995515, 0x009a5515, 0x009a5616, 0x00995614, 0x00995613, 0x00995610, 0x009b5711, 0x009c5711, 0x009c5613, 0x009c5714, 0x009c5814, 0x009c5814, 0x009c5812, 0x009c5712, 0x009c5711, 0x009c5711, 0x009c5711, 0x009c5711, 0x009d5813, 0x009d5813, 0x009d5813, 0x009c5812, 0x00a15a15, 0x00a35c17, 0x00a25c14, 0x00a35c14, 0x00a45a11, 0x00a45a10, 0x00a45c13, 0x00a45d13, 0x00a05b10, 0x009f580e, 0x009f570e, 0x009d540f, 0x009c5510, 0x009b540f, 0x009b5410, 0x009b540f, 0x00995310, 0x00985410, 0x0096500d, 0x0097520e, 0x0097520e, 0x0097520e, 0x0096500d, 0x0096500d, 0x0094500f, 0x00935011, 0x00904f0f, 0x008c4d10, 0x00884d13, 0x00844912, 0x00804711, 0x007e4510, 0x007b4310, 0x0075400e, 0x00713d0e, 0x006c3b0c, 0x0064340b, 0x005b2d08, 0x00502506, 0x00472207, 0x00371a04, 0x00301603, 0x002b1306, 0x00251207, 0x00231308, 0x00231308, 0x00231208, 0x00221208, 0x00201207, 0x00241509, 0x0025170c, 0x00221509, 0x00211509, 0x00201609, 0x0022170a, 0x0022170a, 0x0020180b, 0x0020170c, 0x0022160e, 0x00231710, 0x00201712, 0x0014130d, 0x000c0f08, 0x00071007, 0x00051007, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c07, 0x00080e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0008120e, 0x0007110d, 0x0007110d, 0x0007110c, 0x0005100a, 0x00040f08, 0x00070f08, 0x00070f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040f06, 0x00040f08, 0x00020e08, 0x0004100a, 0x00041009, 0x00030e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00041008, 0x00051109, 0x00051109, 0x00071009, 0x000a110b, 0x00141711, 0x002c2f29, 0x00313330, 0x002b2b2c, 0x002c2c2e, 0x002f3033, 0x00303335, 0x00303336, 0x002c3034, 0x002c2f33, 0x00282c30, 0x0027282a, 0x00282a2c, 0x002d2f30, 0x002e3031, 0x002b2b2b, 0x002c2926, 0x00302824, 0x00342822, 0x00392a24, 0x0043332b, 0x004c3a30, 0x00554335, 0x00584236, 0x0060473c, 0x00684e44, 0x00745b51, 0x0084665e, 0x00886862, 0x0088655f, 0x008d6457, 0x00906451, 0x00916045, 0x00905c3b, 0x00905a30, 0x008f582b, 0x008f5827, 0x00905624, 0x00915422, 0x00905420, 0x0091541f, 0x0092561d, 0x0092561c, 0x0095581e, 0x0098581c, 0x0099581a, 0x009e5a18, 0x009e5914, 0x009e5814, 0x009c5613, 0x009c5714, 0x009c5614, 0x009a5412, 0x009a5513, 0x009b5514, 0x009c5516, 0x009c5614, 0x009c5612, 0x009c5610, 0x009c5814, 0x009b5514, 0x00995412, 0x009c5715, 0x009c5814, 0x009c5814, 0x009c5814, 0x009c5814, 0x009d5814, 0x009d5814, 0x009e5915, 0x009d5814, 0x009e5915, 0x009d5814, 0x009f5a16, 0x00a05917, 0x00a15b17, 0x00a35c14, 0x00a35c15, 0x00a45a12, 0x00a45a12, 0x00a25a10, 0x00a45c12, 0x00a45c12, 0x00a35b10, 0x00a05810, 0x009f5712, 0x009e5613, 0x009c5412, 0x009b5411, 0x009c5512, 0x009c5512, 0x00995410, 0x009a5411, 0x009a5411, 0x009a5411, 0x00985410, 0x00985410, 0x00995412, 0x00965210, 0x00945112, 0x008d4d10, 0x008a4c10, 0x00874b11, 0x00834811, 0x00814611, 0x00804712, 0x007c430f, 0x00753f0d, 0x00713c0c, 0x006c3b0d, 0x0066380c, 0x005c300b, 0x00502607, 0x00472005, 0x003b1905, 0x00331604, 0x0030160a, 0x002d170c, 0x0029170d, 0x00261409, 0x0027140a, 0x0028150b, 0x0027170c, 0x0028180c, 0x0025140c, 0x0024150c, 0x0024150c, 0x0023160c, 0x0023160a, 0x0022160a, 0x00201508, 0x001e1408, 0x00190e04, 0x001c1008, 0x001d140e, 0x0015130c, 0x000d1009, 0x00080f07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c06, 0x00060c07, 0x00080e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0008120e, 0x0007110d, 0x0007110d, 0x0007110c, 0x0005100a, 0x00040f08, 0x00070f08, 0x00070f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040e06, 0x00040e06, 0x00040e06, 0x00040f07, 0x00040f08, 0x00020f09, 0x00020f08, 0x00020e08, 0x00020e08, 0x00020e08, 0x00020e08, 0x00030f09, 0x00030f09, 0x00040f08, 0x00040f08, 0x00051008, 0x00041008, 0x00041007, 0x00041007, 0x00071008, 0x000e150d, 0x001a1f18, 0x00222520, 0x00252724, 0x002e2e2e, 0x002d2d30, 0x002a2c2f, 0x00282c2e, 0x002b2e30, 0x00282b30, 0x00282d31, 0x00292d31, 0x0028292c, 0x0028292b, 0x002c2d2f, 0x002d2d30, 0x002b2b2a, 0x002d2a26, 0x00312823, 0x00342822, 0x003c2c28, 0x0047372e, 0x00503f34, 0x005a483b, 0x005a4438, 0x0060483d, 0x006c5248, 0x00755b51, 0x007f6159, 0x00866761, 0x008b6861, 0x008f675b, 0x00936756, 0x00906046, 0x008e5b3b, 0x008d5830, 0x008d5629, 0x008e5524, 0x008f5523, 0x00925523, 0x0090541f, 0x0091541f, 0x0092561d, 0x0092561c, 0x0095581e, 0x0098581c, 0x009b591b, 0x009e5a18, 0x009e5913, 0x009e5914, 0x009e5914, 0x009e5914, 0x009c5711, 0x009b5610, 0x009b5512, 0x009c5714, 0x009d5515, 0x009e5715, 0x009e5714, 0x009c5611, 0x009e5713, 0x009b5512, 0x00995410, 0x009c5714, 0x009c5813, 0x009c5812, 0x009c5812, 0x009c5813, 0x009e5915, 0x00a15c18, 0x00a05b18, 0x009e5915, 0x009f5a16, 0x009f5a14, 0x009e5914, 0x009f5813, 0x009f5813, 0x00a05911, 0x00a05a13, 0x00a35a11, 0x00a45a12, 0x00a0590f, 0x00a25a10, 0x00a45c12, 0x00a25a10, 0x009f5710, 0x009e5510, 0x009c5412, 0x009c5411, 0x009b5410, 0x009c5412, 0x009b5412, 0x00995410, 0x009a5511, 0x009c5713, 0x009c5713, 0x009a5511, 0x009a5411, 0x009b5514, 0x00985412, 0x00935112, 0x008e4e10, 0x0087490d, 0x0085490f, 0x00834810, 0x0080460f, 0x00804610, 0x007c4510, 0x00753f0d, 0x00713c0c, 0x006c3a0c, 0x00643409, 0x00592c08, 0x004f2506, 0x004a2409, 0x003e1d09, 0x00361907, 0x002f1509, 0x002c160c, 0x0029160c, 0x00261409, 0x002a180d, 0x0029180d, 0x0028170c, 0x0029170d, 0x0028170e, 0x0028180f, 0x00271910, 0x0022150b, 0x00201308, 0x001f1407, 0x001e1306, 0x001e1408, 0x001b0f04, 0x001b0f06, 0x001a100b, 0x00121009, 0x000a0c06, 0x00080f07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c07, 0x00080e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0007110c, 0x0007110c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00071009, 0x000e150f, 0x00181f17, 0x001f241c, 0x001f211e, 0x00272928, 0x00262828, 0x00242527, 0x00242428, 0x00242729, 0x002a2f33, 0x00282d30, 0x00262c2f, 0x002c3031, 0x002e302f, 0x00302f31, 0x002e2c2c, 0x002d2c2a, 0x002d2a26, 0x002d2820, 0x00342824, 0x003c2d28, 0x00493830, 0x00564438, 0x00574438, 0x00594238, 0x0061493f, 0x006c544b, 0x00735851, 0x007c5e58, 0x00856560, 0x0088655f, 0x008e675c, 0x008d6353, 0x008d5d45, 0x008c593a, 0x008d5730, 0x008d5528, 0x00905525, 0x008f5422, 0x00915321, 0x00945623, 0x00945620, 0x0094571d, 0x0094571d, 0x0096571d, 0x0098581b, 0x009c5819, 0x009d5817, 0x009d5814, 0x009d5813, 0x00a05b15, 0x00a05b15, 0x009d5813, 0x009c5711, 0x009d5612, 0x009f5715, 0x009e5716, 0x009f5816, 0x009e5714, 0x009d5611, 0x009c5611, 0x009c5611, 0x009d5612, 0x009d5614, 0x009d5712, 0x009c5812, 0x009c5712, 0x009c5614, 0x009c5614, 0x009a5714, 0x009a5814, 0x009d5a15, 0x009d5a15, 0x009e5914, 0x009f5a14, 0x009d5811, 0x009c5710, 0x00a05910, 0x00a05912, 0x00a05810, 0x00a05810, 0x00a15a10, 0x00a45c12, 0x00a35b12, 0x00a25a11, 0x009f5710, 0x009f5710, 0x009d5611, 0x009c5510, 0x009c5511, 0x009c5512, 0x009c5611, 0x009b5610, 0x009b5610, 0x009c5613, 0x009c5613, 0x009c5614, 0x00985411, 0x00985310, 0x00945111, 0x00935011, 0x008e4f0f, 0x008b4e10, 0x0085490e, 0x0084480f, 0x0080450f, 0x007f4610, 0x007d4511, 0x0078400f, 0x00723d0d, 0x006c390c, 0x00653409, 0x005d300c, 0x004f2407, 0x00452005, 0x003b1a07, 0x00341706, 0x002e150a, 0x002c160d, 0x0029160a, 0x00261408, 0x00261408, 0x00261408, 0x00271509, 0x0026150c, 0x0026160c, 0x0024170f, 0x0023160d, 0x0020140a, 0x001d1308, 0x001c1005, 0x001c1204, 0x001f1609, 0x0020140a, 0x001f120a, 0x001c130c, 0x0013100a, 0x000b0d07, 0x00091009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0c, 0x00060d0b, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d07, 0x00060e07, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0007110c, 0x0007110c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100b, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00040f08, 0x00051008, 0x00071008, 0x000e150e, 0x00181d16, 0x0020241d, 0x0020221e, 0x00212421, 0x00282a2a, 0x002e3031, 0x002f3033, 0x002e2f32, 0x002a2d31, 0x00252a2e, 0x002a2f32, 0x00353738, 0x00363535, 0x00353134, 0x00332e30, 0x00302c2b, 0x002c2823, 0x002d2720, 0x00342824, 0x003c2c27, 0x00493830, 0x00514035, 0x00544034, 0x005a4338, 0x00614940, 0x006c544b, 0x00745952, 0x007b5e58, 0x0084645f, 0x0088645e, 0x00906860, 0x008c6153, 0x008b5b45, 0x008a573a, 0x008c5530, 0x008d5427, 0x00905625, 0x00945827, 0x00965826, 0x00975824, 0x00975823, 0x00965820, 0x0096581f, 0x0095571d, 0x0098561a, 0x00995717, 0x009b5814, 0x009c5812, 0x009c5812, 0x009b5610, 0x009b5610, 0x009a5510, 0x009b5610, 0x009c5510, 0x009c5612, 0x009e5513, 0x009e5513, 0x009e5511, 0x009c530d, 0x009e5610, 0x009e5610, 0x00a15812, 0x00a05813, 0x00a05812, 0x009e5713, 0x009d5712, 0x009c5612, 0x009c5612, 0x009c5613, 0x009c5712, 0x009c5814, 0x009d5812, 0x009e5813, 0x00a05913, 0x00a35c16, 0x00a76017, 0x00a75f16, 0x00a75e18, 0x00a75c15, 0x00a75c15, 0x00a55d14, 0x00a55d14, 0x00a35b12, 0x00a25a11, 0x009f570f, 0x009f570f, 0x009d5610, 0x009c5610, 0x009c5611, 0x009c5611, 0x009c5611, 0x009b5610, 0x009c5711, 0x009c5613, 0x009c5613, 0x009c5614, 0x00985411, 0x00985310, 0x00955111, 0x00915010, 0x008e500f, 0x00884b0d, 0x00874c10, 0x00864a10, 0x00834810, 0x00804611, 0x00804815, 0x007c4414, 0x00743f10, 0x006f3c0f, 0x0068380d, 0x005c2f0b, 0x004d2306, 0x00441e05, 0x003b1b08, 0x00331707, 0x002c140a, 0x002a160c, 0x00241407, 0x00211104, 0x00241508, 0x00241408, 0x00231407, 0x00201309, 0x001f1308, 0x001d130a, 0x001d140a, 0x001c1308, 0x001d1409, 0x001e1508, 0x001f1608, 0x001f1509, 0x0020150b, 0x0022160d, 0x00201610, 0x0017140d, 0x000e110b, 0x00091009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0c, 0x00060d0b, 0x00040c09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d07, 0x00060e08, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006100b, 0x0006100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070e0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00050f0a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00051008, 0x00040f08, 0x00040f08, 0x00051008, 0x00070f08, 0x00070f08, 0x00070e08, 0x000e140c, 0x00181e17, 0x0021251e, 0x00252724, 0x002b2c2a, 0x002c2e2d, 0x002c2e2f, 0x002e3030, 0x00303134, 0x00333437, 0x0034383a, 0x00333437, 0x00323032, 0x00322e30, 0x00332c2e, 0x00342c2e, 0x00322b29, 0x00302924, 0x00332a23, 0x003a2e28, 0x0040322b, 0x00493830, 0x004e3c33, 0x00523f35, 0x005a433a, 0x00644c44, 0x006d544c, 0x00745c53, 0x00795d56, 0x0082635c, 0x00886660, 0x008e665f, 0x008a5f53, 0x008b5b47, 0x008b583c, 0x008c5531, 0x008f5728, 0x00915826, 0x00945828, 0x00975826, 0x00975824, 0x00975823, 0x00995c22, 0x009a5c23, 0x009b5c22, 0x009d5c1f, 0x009e5c1b, 0x00a05c17, 0x00a15b14, 0x00a15b14, 0x009f5812, 0x009f5812, 0x00a05912, 0x00a05912, 0x00a45b14, 0x00a45c17, 0x00a65b17, 0x00a65c17, 0x00a65c15, 0x00a35911, 0x00a35910, 0x00a35911, 0x00a15710, 0x009e540d, 0x009d540c, 0x009d550f, 0x009d540d, 0x009e560f, 0x009f5811, 0x009f5814, 0x00a05914, 0x00a05a15, 0x00a35c16, 0x00a45c16, 0x00a86017, 0x00a86018, 0x00a86016, 0x00a85f15, 0x00a85e16, 0x00a85c14, 0x00a85c14, 0x00a75d14, 0x00a55c12, 0x00a35911, 0x00a35911, 0x00a35b12, 0x00a05810, 0x009e5810, 0x009c5610, 0x009c550f, 0x009c5510, 0x009c5611, 0x009c5711, 0x009c5712, 0x009e5915, 0x009c5814, 0x009c5614, 0x009a5413, 0x00985213, 0x00955111, 0x00915010, 0x008e4f0f, 0x00884b0d, 0x00884c10, 0x00864a10, 0x00834710, 0x00804511, 0x00804714, 0x00804718, 0x00774012, 0x00703b0d, 0x0068360b, 0x0060330e, 0x00502609, 0x00441f05, 0x00391906, 0x00301605, 0x002c1409, 0x0028130a, 0x00251408, 0x00261509, 0x0028180b, 0x00241408, 0x00231508, 0x00201409, 0x00191007, 0x00150d05, 0x00150e06, 0x00181007, 0x00191208, 0x001b1407, 0x001d1507, 0x001c1307, 0x0020140a, 0x0020120b, 0x00201813, 0x00191710, 0x000c0f08, 0x00080e08, 0x00060e09, 0x00050e08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0c, 0x00060d0b, 0x00040c09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d07, 0x00060e08, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006100b, 0x0006100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e07, 0x00030d06, 0x00040f08, 0x00051008, 0x00070f08, 0x00081009, 0x00070e08, 0x000d140c, 0x00181e17, 0x00242821, 0x002d2e2b, 0x0030302f, 0x00303231, 0x002f3032, 0x00303133, 0x00313334, 0x00323437, 0x00333337, 0x00313034, 0x00322e30, 0x00362f31, 0x00382e31, 0x0034282b, 0x00342828, 0x00352b27, 0x00362c24, 0x00392f28, 0x003f322a, 0x00483930, 0x004f3e34, 0x00544338, 0x005c473e, 0x00665047, 0x0070584f, 0x00755d54, 0x00795d57, 0x0080625c, 0x00886661, 0x008e6660, 0x00895f54, 0x008c5c49, 0x008e5b42, 0x008f5834, 0x0091592c, 0x00925927, 0x00945825, 0x00955624, 0x00955623, 0x00955721, 0x00975920, 0x00995c22, 0x009b5c22, 0x009d5c20, 0x009e5c1b, 0x00a15b17, 0x00a25c14, 0x00a25c14, 0x00a45e15, 0x00a45d14, 0x00a35d14, 0x00a45c14, 0x00a45b14, 0x00a45b13, 0x00a85f17, 0x00a96017, 0x00aa5e14, 0x00a75c11, 0x00a95e14, 0x00aa5e15, 0x00aa5e15, 0x00a85c13, 0x00a45b10, 0x00a45b10, 0x00a55c11, 0x00a75d13, 0x00a65d14, 0x00a55c18, 0x00a55d17, 0x00a55d17, 0x00a65d15, 0x00a85e16, 0x00a96017, 0x00a96016, 0x00a96015, 0x00ac6017, 0x00ac6018, 0x00ab6016, 0x00ab6014, 0x00a95d14, 0x00a65b12, 0x00a45a12, 0x00a35b12, 0x00a35b12, 0x00a15910, 0x009e5710, 0x009f5811, 0x00a05913, 0x009f5813, 0x009f5814, 0x009d5813, 0x009d5813, 0x009e5915, 0x009d5814, 0x009c5715, 0x009b5614, 0x00995414, 0x00975312, 0x00915010, 0x008d4f0f, 0x00884c0e, 0x00874c10, 0x0085490f, 0x0083470f, 0x00804510, 0x00804714, 0x007f4617, 0x00794214, 0x00703c0e, 0x0068360b, 0x0060330f, 0x0052280b, 0x00452007, 0x003a1a08, 0x00321706, 0x002c1409, 0x00281309, 0x00251408, 0x00251709, 0x00261609, 0x0026180c, 0x00231709, 0x001e1409, 0x00171005, 0x00130d04, 0x00100c03, 0x00130d04, 0x00181208, 0x00191408, 0x001a1405, 0x001b1306, 0x001c1107, 0x00180c04, 0x001b140d, 0x00161710, 0x000d110a, 0x00080e08, 0x00060e08, 0x00040d07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0c, 0x00060d0b, 0x00040c09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d07, 0x00060e08, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e07, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c08, 0x00080c08, 0x00080c07, 0x00080c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040a04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x000a120a, 0x00181f18, 0x00282a24, 0x0032302d, 0x00343433, 0x00343534, 0x00353738, 0x00323435, 0x00383839, 0x0038383a, 0x00373538, 0x00312f31, 0x00342c30, 0x00383033, 0x002e2528, 0x002e2426, 0x00382c2d, 0x00372d29, 0x00332b23, 0x00382f28, 0x0040332d, 0x00493b34, 0x0053433b, 0x005c4b42, 0x005f4942, 0x00675048, 0x006c554d, 0x00755c55, 0x007c5f58, 0x0082645e, 0x00856560, 0x0089675f, 0x008a6457, 0x00895e48, 0x008c5c41, 0x008f5835, 0x00935a30, 0x00935929, 0x00935824, 0x00945524, 0x00925420, 0x00975924, 0x00985a21, 0x00985b21, 0x00995b20, 0x009d5b1e, 0x009f5c1c, 0x009f5a14, 0x00a05b10, 0x00a05b10, 0x00a25a10, 0x00a1590f, 0x00a25a11, 0x00a15910, 0x00a35910, 0x00a65c13, 0x00a65c12, 0x00a85e13, 0x00a95e13, 0x00aa5f12, 0x00aa5f14, 0x00aa5f14, 0x00a95e13, 0x00a95e13, 0x00a96014, 0x00a85f13, 0x00a85e14, 0x00a75d14, 0x00a45c13, 0x00a45c14, 0x00a45c14, 0x00a85f17, 0x00a85e16, 0x00a95d14, 0x00ac6018, 0x00a95d14, 0x00ab6017, 0x00ab6015, 0x00ac6018, 0x00ac5f14, 0x00ab5e14, 0x00ab5e14, 0x00a95e13, 0x00a45b11, 0x00a45c12, 0x00a35b10, 0x00a1590f, 0x00a25a11, 0x00a25a11, 0x00a15a13, 0x00a05a13, 0x00a05912, 0x009f5813, 0x009f5813, 0x00a05814, 0x009f5814, 0x009c5514, 0x00995210, 0x00965010, 0x00945010, 0x00915010, 0x008f5010, 0x008c4f10, 0x00864b0c, 0x0084490e, 0x0082460e, 0x00814610, 0x00814813, 0x007f4714, 0x007a4312, 0x00703c0c, 0x00673509, 0x005c300b, 0x00512709, 0x00462008, 0x003a1a08, 0x002f1404, 0x002b1208, 0x002a170d, 0x00241507, 0x00231508, 0x00201409, 0x001c1408, 0x001c1408, 0x001b1408, 0x001a140a, 0x00181308, 0x00161106, 0x00131004, 0x00120f04, 0x00141005, 0x00151105, 0x00181106, 0x001b1108, 0x001b110a, 0x0018120b, 0x000e1008, 0x00090e07, 0x00060e06, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00060e09, 0x00060d0a, 0x00060e09, 0x00060e08, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e07, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c08, 0x00080c08, 0x00080c07, 0x00080c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040a04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00081109, 0x001d231c, 0x002d2d28, 0x0032302e, 0x00353434, 0x00343636, 0x00353738, 0x00323435, 0x0038383a, 0x0038383a, 0x00383638, 0x00383437, 0x00363034, 0x00342e30, 0x00342e31, 0x00362f30, 0x00342d2c, 0x00322925, 0x00322c25, 0x00383029, 0x003a2f2a, 0x00483b36, 0x0056473f, 0x0055443c, 0x005c4840, 0x00665149, 0x006f5850, 0x007b615b, 0x007f635c, 0x0081645d, 0x00856560, 0x0089665d, 0x008a6457, 0x00895f49, 0x008c5c42, 0x00905a38, 0x00925832, 0x0093582c, 0x00935726, 0x00955725, 0x00985925, 0x00985b25, 0x00985b22, 0x00985b21, 0x00995b20, 0x009d5c1f, 0x009f5c1c, 0x009f5914, 0x00a05a0f, 0x00a05a0f, 0x00a0580e, 0x00a1590f, 0x00a15810, 0x00a15810, 0x00a35910, 0x00a65c13, 0x00a75d14, 0x00a85e14, 0x00a95e13, 0x00aa5f14, 0x00aa5f14, 0x00aa5f14, 0x00a95e13, 0x00a95e13, 0x00a96014, 0x00a85f13, 0x00a85e14, 0x00a75d14, 0x00a45c12, 0x00a45c12, 0x00a35b11, 0x00a65c14, 0x00a75c15, 0x00a75d14, 0x00a65c13, 0x00a75c13, 0x00aa5e15, 0x00ac6016, 0x00ac6018, 0x00ac5f14, 0x00ab5e14, 0x00ac5f14, 0x00a95e13, 0x00a55c12, 0x00a25c12, 0x00a25b10, 0x00a25a10, 0x00a25a10, 0x00a25a11, 0x00a15a12, 0x00a05a13, 0x00a05a13, 0x00a05814, 0x00a05814, 0x00a05814, 0x00a05814, 0x009c5514, 0x009a5311, 0x00965011, 0x00945110, 0x00915010, 0x008f5010, 0x00894c0d, 0x00874c0e, 0x00864a0e, 0x0084480e, 0x0081470e, 0x007f460f, 0x007e4611, 0x007a4310, 0x00703c0b, 0x00673509, 0x005c300b, 0x00512709, 0x00452008, 0x00381908, 0x00321708, 0x002c140b, 0x0027140a, 0x00241508, 0x00221409, 0x001f150b, 0x001c140a, 0x001a140a, 0x00191407, 0x001a140a, 0x00181308, 0x00181207, 0x00181308, 0x00181308, 0x00181309, 0x00181308, 0x00171208, 0x00181109, 0x001a110c, 0x0016130c, 0x000d1209, 0x00091008, 0x00060e06, 0x00070e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060d0a, 0x00060d0a, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e07, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c07, 0x00080c07, 0x00080c05, 0x00080c04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00060f08, 0x00081008, 0x001b201a, 0x002e2e28, 0x0033302d, 0x00353434, 0x00343535, 0x00313436, 0x00303334, 0x00363839, 0x0037383a, 0x00323134, 0x00302f32, 0x002f2b30, 0x002f2a2f, 0x00353134, 0x00332f30, 0x00312d2b, 0x00322d28, 0x00312c25, 0x0038312c, 0x003f3530, 0x004e403c, 0x00574944, 0x0052433c, 0x00604d48, 0x0069544e, 0x00705953, 0x007c635e, 0x007e625c, 0x00846660, 0x00866660, 0x0089675e, 0x008a6558, 0x008c614d, 0x008c5d44, 0x0090583a, 0x00945a35, 0x0094592e, 0x00935828, 0x00925521, 0x00975823, 0x00985b24, 0x00985b21, 0x00985c20, 0x00995b1f, 0x009d5c1f, 0x009f5c1c, 0x009e5914, 0x009c570c, 0x009d570c, 0x009f580d, 0x00a0590f, 0x00a05810, 0x00a05810, 0x00a55b13, 0x00a55b14, 0x00a75b14, 0x00a85c15, 0x00a85c14, 0x00a95d14, 0x00aa5e15, 0x00aa5f14, 0x00a75c11, 0x00a75c11, 0x00a75c11, 0x00a85c12, 0x00a85d13, 0x00a65c13, 0x00a45a10, 0x00a35b10, 0x00a35b10, 0x00a25a11, 0x00a45c14, 0x00a85e14, 0x00a55c12, 0x00a55c12, 0x00a55c12, 0x00ac6016, 0x00ac6018, 0x00ad6016, 0x00ad6016, 0x00ac5f14, 0x00ac6016, 0x00a75d14, 0x00a25c11, 0x00a25a0f, 0x00a25a0e, 0x00a35b10, 0x00a35b10, 0x00a35b12, 0x00a35b12, 0x00a25913, 0x00a15812, 0x00a05912, 0x009f5811, 0x009d5711, 0x009c5412, 0x00995411, 0x00985210, 0x00965211, 0x00945313, 0x00905110, 0x00894c0d, 0x00874c0e, 0x00864a0e, 0x0084480e, 0x0081470c, 0x0080480f, 0x00804912, 0x007a4410, 0x00703c0b, 0x006c3a0d, 0x0062340f, 0x004f2406, 0x00462007, 0x00391a07, 0x002f1404, 0x002c160b, 0x00241108, 0x00201208, 0x001d1006, 0x001b100a, 0x001c120c, 0x00191408, 0x00191407, 0x001a140a, 0x0019140b, 0x00151005, 0x00151005, 0x00171006, 0x00181108, 0x00181208, 0x00181108, 0x0018100a, 0x001a120c, 0x0016140e, 0x000e110b, 0x000a0f08, 0x00070e06, 0x00070e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060d0a, 0x00060d0a, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e07, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c05, 0x00080c05, 0x00080c04, 0x00080c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00060f08, 0x00081008, 0x0010140d, 0x00282824, 0x0033322f, 0x00353434, 0x00343536, 0x00303436, 0x002f3234, 0x002e3134, 0x002d3032, 0x00303134, 0x002d2e31, 0x00333337, 0x00343337, 0x00343335, 0x00313131, 0x0031302e, 0x0035322d, 0x00312d27, 0x0038322c, 0x00443a36, 0x004a3c39, 0x0050423e, 0x00544642, 0x0064514e, 0x0069554f, 0x00715a54, 0x00785f5b, 0x007c605a, 0x00846660, 0x00876761, 0x0088655d, 0x00886357, 0x008c614e, 0x008d5e45, 0x0090593d, 0x00915636, 0x0090552c, 0x00925628, 0x00945723, 0x00985924, 0x00985b24, 0x00985b21, 0x00985c20, 0x00995b1f, 0x009c5b1e, 0x009c5a1a, 0x009c5813, 0x009c570e, 0x009c570e, 0x009e560e, 0x00a1590f, 0x00a35b12, 0x00a35b12, 0x00a55b14, 0x00a55b14, 0x00a75b14, 0x00a95d16, 0x00a85c15, 0x00aa5e16, 0x00ac5f16, 0x00ab5e14, 0x00a85b11, 0x00a85b11, 0x00a85c11, 0x00a85d12, 0x00a85e14, 0x00a65c13, 0x00a45a10, 0x00a45b10, 0x00a55c12, 0x00a55b14, 0x00a65c14, 0x00a85e14, 0x00a85e14, 0x00a85f15, 0x00aa6017, 0x00ab6118, 0x00ac6118, 0x00ad6016, 0x00ad6016, 0x00ad6016, 0x00ac6016, 0x00a85f15, 0x00a45e14, 0x00a45d11, 0x00a45d11, 0x00a45c11, 0x00a35b10, 0x00a35b11, 0x00a35b12, 0x00a25a11, 0x00a15812, 0x00a05912, 0x00a05912, 0x009d5711, 0x009c5412, 0x00995410, 0x00985411, 0x00975312, 0x00945314, 0x00905111, 0x008a4d0e, 0x00874c0f, 0x0085490f, 0x0084480e, 0x0082480d, 0x0081480e, 0x007f4810, 0x007a440e, 0x00713d0a, 0x006a380a, 0x0062340f, 0x00522808, 0x00452006, 0x00391906, 0x00321707, 0x002c160b, 0x00241208, 0x00201208, 0x001c0f07, 0x00190e08, 0x00180e09, 0x00181008, 0x001a140a, 0x0019140b, 0x001b150c, 0x00171108, 0x00151005, 0x00160f06, 0x00181008, 0x00181008, 0x00161008, 0x0018110a, 0x0019110c, 0x0016140e, 0x000f120c, 0x000a0f08, 0x00080f07, 0x00080f07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e0a, 0x00060d0a, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050c07, 0x00060c07, 0x00060d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00050d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040d07, 0x00070e08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060d08, 0x00060d08, 0x00060c07, 0x00040c05, 0x00050c06, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00051009, 0x00051008, 0x00081008, 0x000a1108, 0x000c0f0a, 0x00202020, 0x00383639, 0x003d3b40, 0x00393b40, 0x00323739, 0x002f3234, 0x002c3032, 0x002c2f31, 0x002e3134, 0x00303335, 0x00313437, 0x00313436, 0x00313334, 0x00303332, 0x00313330, 0x0034342e, 0x0034312b, 0x0038312d, 0x00403733, 0x00493e3a, 0x00514340, 0x005c4e4a, 0x0063504c, 0x00685450, 0x00705a54, 0x00745b56, 0x007c5f5c, 0x00846660, 0x0084655e, 0x0087645c, 0x00886357, 0x008c614f, 0x008d5e46, 0x0090593c, 0x00905736, 0x0090562c, 0x0093582a, 0x00975a25, 0x00985b24, 0x00985a22, 0x00995922, 0x0098591f, 0x009a591e, 0x009c5a1b, 0x009c5817, 0x009c5713, 0x009e5710, 0x009f5710, 0x00a15810, 0x00a45b11, 0x00a75d14, 0x00a75d14, 0x00a55a11, 0x00a55a11, 0x00a85c14, 0x00a95d15, 0x00ac6018, 0x00ab6016, 0x00ac5f14, 0x00ad5f15, 0x00ac5e14, 0x00ac5e14, 0x00ab5f14, 0x00aa5f14, 0x00a85d14, 0x00a75c13, 0x00a75c13, 0x00a55a10, 0x00a85c14, 0x00a95e17, 0x00a95e17, 0x00a85e15, 0x00a85f16, 0x00ab6018, 0x00ac611a, 0x00ac6218, 0x00ac6118, 0x00ac5f14, 0x00ad6014, 0x00ad6014, 0x00ad6115, 0x00ac5f14, 0x00aa5e14, 0x00a85f14, 0x00a85f13, 0x00a75e13, 0x00a75d12, 0x00a65c14, 0x00a45a12, 0x00a35912, 0x00a25a14, 0x00a25a14, 0x00a15913, 0x009e5810, 0x009a540f, 0x00995410, 0x00985411, 0x00955210, 0x00925313, 0x00905112, 0x008a4d10, 0x00874a10, 0x00864910, 0x00854810, 0x00874c13, 0x00824810, 0x007e4610, 0x0079430f, 0x006f3b08, 0x006a3808, 0x0063330c, 0x00552b0b, 0x00462006, 0x003a1b06, 0x00341806, 0x002c1508, 0x00251408, 0x00211409, 0x0020140b, 0x00180c07, 0x00170d08, 0x00150d07, 0x00150f08, 0x0019120b, 0x001c140c, 0x001b140b, 0x00191209, 0x00181108, 0x00181008, 0x00181008, 0x00161007, 0x00160f08, 0x0019130c, 0x00181610, 0x0010100b, 0x000a0e07, 0x00070e06, 0x00080d06, 0x00080e08, 0x00060d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d08, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00050d07, 0x00060d08, 0x00060d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00050c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x0005100a, 0x00051008, 0x00050f07, 0x00091008, 0x00181b16, 0x00303030, 0x003c3b40, 0x0038383e, 0x002e3034, 0x00252a2c, 0x0025282b, 0x00292c2f, 0x00292c2f, 0x002b2e30, 0x002f3234, 0x00303436, 0x00303335, 0x00303234, 0x00313433, 0x00333432, 0x00363730, 0x00383530, 0x003b3430, 0x003e3432, 0x00463a38, 0x00504240, 0x005e504c, 0x0064524e, 0x006b5852, 0x00705b55, 0x0079605c, 0x00806460, 0x00846661, 0x0085665e, 0x0088665e, 0x008b6559, 0x008f6450, 0x008f6049, 0x00905b3e, 0x00905837, 0x00915930, 0x00955c2d, 0x00975c28, 0x00985c24, 0x009a5a24, 0x009a5a24, 0x00995a21, 0x009c5c20, 0x009f5b1d, 0x009f5a19, 0x00a05916, 0x00a15814, 0x00a15812, 0x00a45a11, 0x00a65c12, 0x00a45b0e, 0x00a45b0d, 0x00a55a0e, 0x00a55a0e, 0x00a85c11, 0x00aa5f14, 0x00ad6018, 0x00ad6016, 0x00ad6014, 0x00af6116, 0x00ae6116, 0x00ae6116, 0x00ad6116, 0x00ac6014, 0x00ab6014, 0x00ab6015, 0x00ab6015, 0x00a95e14, 0x00ab6017, 0x00a95d14, 0x00a85c14, 0x00a85f15, 0x00ab6118, 0x00ac6219, 0x00b0651c, 0x00b0651c, 0x00af651a, 0x00af6418, 0x00af6417, 0x00af6315, 0x00af6315, 0x00af6315, 0x00af6215, 0x00ae6318, 0x00ac6318, 0x00ab6116, 0x00ab6015, 0x00ab6018, 0x00a85f17, 0x00a65c15, 0x00a45c16, 0x00a45c16, 0x00a35b14, 0x00a05811, 0x009d5812, 0x009c5814, 0x009a5714, 0x00965412, 0x00935413, 0x008f5214, 0x008c4e13, 0x00894c12, 0x00874911, 0x00884914, 0x00874a13, 0x00834913, 0x00804814, 0x007b4412, 0x00703c0a, 0x006c3809, 0x0063330c, 0x00552b0a, 0x00482207, 0x003c1c08, 0x00341805, 0x002b1508, 0x00251408, 0x00221408, 0x0020160a, 0x001e120a, 0x00191008, 0x00150e08, 0x00140d06, 0x00160e08, 0x001a120a, 0x001c140c, 0x001c140c, 0x001a130a, 0x00181008, 0x00171007, 0x00160f07, 0x00160f07, 0x00171109, 0x0016140e, 0x0010100b, 0x000a0d07, 0x00070e06, 0x00080d06, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00050c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060d08, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x0004100a, 0x00041008, 0x00030c04, 0x00091007, 0x00262a23, 0x003a3b38, 0x00343435, 0x0027262b, 0x001b1c1f, 0x00181d1e, 0x00202526, 0x002a2f30, 0x00292e2f, 0x00282b2d, 0x002e3134, 0x00303336, 0x00303236, 0x00323336, 0x00323434, 0x00343735, 0x00333330, 0x00302f2a, 0x0036312e, 0x00433b38, 0x004a3e3c, 0x00504341, 0x005e504e, 0x0064534e, 0x006b5852, 0x00745e58, 0x007d6461, 0x007f625f, 0x00826460, 0x0084655d, 0x0088655c, 0x008c655b, 0x00906454, 0x0090624c, 0x00915d40, 0x00905a38, 0x00935c32, 0x00945d2e, 0x00965c26, 0x00985c24, 0x009c5c26, 0x009d5d26, 0x009c5c24, 0x009d5d22, 0x00a05d1f, 0x00a25e1c, 0x00a55e1a, 0x00a65e18, 0x00a86017, 0x00ab6117, 0x00ac6417, 0x00ad6416, 0x00ad6416, 0x00ac6114, 0x00ac6114, 0x00ac6214, 0x00b06518, 0x00b06416, 0x00b06416, 0x00ae6114, 0x00ae6114, 0x00ac5f12, 0x00aa5c10, 0x00aa5e10, 0x00ab5f11, 0x00aa5e12, 0x00a95d11, 0x00a85d11, 0x00a75c10, 0x00aa6014, 0x00ac6218, 0x00ae641a, 0x00b1691e, 0x00b36b20, 0x00b46c21, 0x00b66e23, 0x00b46c21, 0x00b36a1e, 0x00b1681b, 0x00b36a1b, 0x00b36a1a, 0x00b36a19, 0x00b56a1b, 0x00b4691b, 0x00b2681a, 0x00ae6418, 0x00ab6116, 0x00aa6014, 0x00a95d14, 0x00a65b13, 0x00a55a12, 0x00a45c14, 0x00a45c14, 0x00a25a13, 0x00a05811, 0x009e5913, 0x009f5a14, 0x009c5814, 0x00965413, 0x00945414, 0x00905314, 0x008f5114, 0x008c4f14, 0x008a4c14, 0x00884a14, 0x00864913, 0x00824812, 0x00824a18, 0x00804817, 0x0074400e, 0x006c380a, 0x0064340b, 0x00552908, 0x00452003, 0x003c1b05, 0x00331704, 0x00291405, 0x00241406, 0x00231708, 0x0021170b, 0x001f140b, 0x001e140c, 0x001b130c, 0x0018110a, 0x00160e07, 0x00170f06, 0x00191209, 0x001c140c, 0x001e150d, 0x001e150d, 0x001c140c, 0x001b140c, 0x001c150d, 0x001c150e, 0x0019180f, 0x0012120c, 0x000b0d07, 0x00080d06, 0x00080d06, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00050c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060d08, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x0004100a, 0x00041008, 0x00040e08, 0x00151c15, 0x0030342c, 0x00282b26, 0x001a1c19, 0x00151818, 0x00141818, 0x00181c1c, 0x00212625, 0x00252a2a, 0x00292f2f, 0x002e3134, 0x00313539, 0x0033363c, 0x0034373c, 0x0036383b, 0x00343638, 0x00343635, 0x00323331, 0x00323230, 0x00383434, 0x003e3836, 0x00443a39, 0x00514644, 0x00625453, 0x00615350, 0x00685650, 0x00715e58, 0x0079605e, 0x007e6060, 0x00836460, 0x0085655e, 0x0087645e, 0x008b655b, 0x00906454, 0x0090614c, 0x00905f40, 0x00905c3a, 0x00915d32, 0x00935e2e, 0x00945e26, 0x009a5e26, 0x009d5d26, 0x009e5e27, 0x009e5e26, 0x009e5e22, 0x00a15d20, 0x00a35e1c, 0x00a55e18, 0x00a86016, 0x00aa6218, 0x00ad6418, 0x00ae6415, 0x00ad6414, 0x00ac6414, 0x00ae6314, 0x00ad6314, 0x00b36919, 0x00b66c1d, 0x00b56b1b, 0x00b56b1b, 0x00b56a1b, 0x00b5691a, 0x00b66b1c, 0x00b26617, 0x00b06516, 0x00b36818, 0x00b36818, 0x00b3681a, 0x00b3681a, 0x00b36b1c, 0x00b56d1f, 0x00b66e21, 0x00b46c1f, 0x00b36c20, 0x00b36d20, 0x00b56f21, 0x00b56f21, 0x00b26c1d, 0x00ad6717, 0x00b16a19, 0x00b46c1b, 0x00b46d1a, 0x00b46c1a, 0x00b66c1c, 0x00b46c1b, 0x00b46a1b, 0x00b06718, 0x00ac6418, 0x00ab6015, 0x00a95e14, 0x00a85c14, 0x00a65b12, 0x00a45b13, 0x00a15910, 0x00a05810, 0x009e560e, 0x009d5810, 0x009e5a11, 0x009b5813, 0x00945310, 0x00945414, 0x00905314, 0x00905214, 0x008c5013, 0x008c4e14, 0x00894b13, 0x00874913, 0x00804811, 0x00804816, 0x007e4715, 0x00754110, 0x00703c0c, 0x0068360e, 0x00582c0a, 0x00462102, 0x003c1a04, 0x00321602, 0x00281404, 0x00231404, 0x00221808, 0x0022170b, 0x001e140b, 0x001e140c, 0x001c150b, 0x001c150a, 0x001c140a, 0x00191208, 0x00181007, 0x00181108, 0x001b130a, 0x001c140c, 0x001c140c, 0x001c140c, 0x001c150d, 0x001c170f, 0x0019170f, 0x00100f09, 0x00090c06, 0x00080d06, 0x00080d06, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c06, 0x00050c06, 0x00050d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c09, 0x00050d08, 0x00050d08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050e08, 0x00060d07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040d09, 0x00050e09, 0x00040e09, 0x0004100a, 0x00041009, 0x00060f08, 0x00101710, 0x001c211b, 0x001a1e18, 0x001b1f1b, 0x001c1f1d, 0x00181b1a, 0x001c201f, 0x00252928, 0x002c3131, 0x00303636, 0x0034383a, 0x0034373c, 0x0036383e, 0x0034383c, 0x00343438, 0x00303234, 0x00303332, 0x00323432, 0x00303030, 0x00313030, 0x003c3636, 0x00484040, 0x00544a49, 0x005a4e4d, 0x005b4e4a, 0x00665651, 0x00715e59, 0x00785f5c, 0x007e6160, 0x00856763, 0x00866760, 0x0088655c, 0x008a645a, 0x008e6454, 0x008e624e, 0x008f5e44, 0x008e5c3c, 0x00915d35, 0x00935e2f, 0x00955f29, 0x00995e28, 0x009c5f28, 0x009f5f27, 0x009f5e25, 0x009f5e23, 0x00a05f20, 0x00a35e1d, 0x00a46019, 0x00a86116, 0x00ab6417, 0x00ae6416, 0x00b06414, 0x00b16614, 0x00b26714, 0x00ac6210, 0x00ad6411, 0x00b06815, 0x00b36b18, 0x00b66c1a, 0x00b66c1a, 0x00b66c1a, 0x00b66c1a, 0x00b56b18, 0x00b86d1b, 0x00b86e1c, 0x00b86e1c, 0x00b86f1d, 0x00ba701f, 0x00b86f1e, 0x00b46e1c, 0x00b6701e, 0x00b46e1e, 0x00b36c1c, 0x00b06c1b, 0x00b06c1b, 0x00b46f1f, 0x00b46f1f, 0x00b46f1f, 0x00b26d1b, 0x00b36d1c, 0x00b06b18, 0x00b26c18, 0x00b36c18, 0x00b66f1c, 0x00b46c19, 0x00b16718, 0x00ae6418, 0x00ac6117, 0x00aa6018, 0x00a85f15, 0x00a55c13, 0x00a35a10, 0x00a05910, 0x009f580f, 0x009f570e, 0x009d570d, 0x009d580f, 0x009c5810, 0x00995713, 0x00955412, 0x00955513, 0x00925313, 0x00905213, 0x008e5012, 0x008c4f13, 0x00894c12, 0x00854b12, 0x00804710, 0x007d4510, 0x007c4513, 0x0074400f, 0x00703d0d, 0x006c3a11, 0x005c300c, 0x00492405, 0x003d1c05, 0x00331603, 0x00281404, 0x00231405, 0x00211708, 0x00211609, 0x001f150a, 0x001e140b, 0x001c1409, 0x001b1407, 0x001e170d, 0x001e180d, 0x001c150a, 0x00181207, 0x00171007, 0x00181108, 0x00181008, 0x00181209, 0x00181109, 0x00141009, 0x0014120b, 0x000c0d08, 0x00080c06, 0x00070e07, 0x00070e07, 0x00060e08, 0x00050d07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00050c07, 0x00050d07, 0x00050d07, 0x00050c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00080c09, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00060f08, 0x00060e07, 0x000f140f, 0x00131812, 0x001d2220, 0x00202423, 0x00252928, 0x002c302f, 0x00303432, 0x002d3334, 0x002e3435, 0x00303437, 0x00313437, 0x00313438, 0x002f3234, 0x00303235, 0x002e3031, 0x002d302f, 0x002b2d2c, 0x002c2c2d, 0x00303030, 0x00383434, 0x00443d3e, 0x004d4545, 0x00534948, 0x005a4f4c, 0x00645752, 0x0074615c, 0x007a605e, 0x007f6260, 0x00856763, 0x00866760, 0x0088655c, 0x008a645b, 0x008c6457, 0x008e6352, 0x008e604a, 0x008e5d41, 0x00905e38, 0x00945e33, 0x00965e2c, 0x009a602c, 0x009c6029, 0x009e6028, 0x009f5e26, 0x009f5e24, 0x00a05f22, 0x00a25f20, 0x00a4601b, 0x00a56116, 0x00a96215, 0x00ae6416, 0x00b06515, 0x00b16414, 0x00b26514, 0x00b16715, 0x00b26b18, 0x00b36b18, 0x00b36b18, 0x00b56c1b, 0x00b56c1b, 0x00b46c19, 0x00b46c19, 0x00b56b19, 0x00b66c19, 0x00b56c19, 0x00b66c1a, 0x00b66d1c, 0x00b76d1c, 0x00b56d1c, 0x00b46d1c, 0x00b46c1c, 0x00b36c1c, 0x00b36c1c, 0x00b26d1d, 0x00b36e1d, 0x00b36e1e, 0x00b36e1e, 0x00b36e1e, 0x00b46f1d, 0x00b46f1d, 0x00b4701d, 0x00b46e1c, 0x00b46e1c, 0x00b46d1b, 0x00b36c19, 0x00af6718, 0x00ae6319, 0x00ab6018, 0x00a96018, 0x00a76017, 0x00a15c11, 0x009e580e, 0x00a0580f, 0x009f580f, 0x009f580f, 0x009f580f, 0x009f5810, 0x009c570f, 0x00995715, 0x00985614, 0x00955513, 0x00945212, 0x00915211, 0x008e5010, 0x008c5011, 0x00894d11, 0x00874c14, 0x00814810, 0x007c4410, 0x007c4511, 0x0073400c, 0x006e390b, 0x0069380f, 0x005d310c, 0x004c2808, 0x00401e09, 0x00331604, 0x00291407, 0x00241407, 0x001f1404, 0x001e1406, 0x001e140a, 0x001f140c, 0x001d160b, 0x001c1409, 0x00191408, 0x001b150a, 0x001a140a, 0x001a140a, 0x001a140c, 0x0019140a, 0x00171008, 0x00161008, 0x00141008, 0x0014100b, 0x0014130e, 0x000d0e0a, 0x00080d08, 0x00040f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00050d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00081009, 0x00080f0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00080c09, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00051009, 0x0005100a, 0x0008100a, 0x00080f09, 0x000d140f, 0x00161b17, 0x00222623, 0x00242827, 0x00323634, 0x00313534, 0x00303433, 0x002d3334, 0x002e3335, 0x00303337, 0x002f3234, 0x00303435, 0x002d3033, 0x002b2c30, 0x00282a2c, 0x002a2c2c, 0x00292b2c, 0x002a2c2d, 0x00313132, 0x003e3b3c, 0x00464141, 0x00484241, 0x004d4544, 0x005a4e4c, 0x00645853, 0x0075625d, 0x007b625f, 0x007f6461, 0x00856762, 0x00876760, 0x0087655c, 0x0089665d, 0x008d665b, 0x008c6557, 0x008e614d, 0x008d5f44, 0x00905f3c, 0x00936034, 0x00966030, 0x0099602e, 0x009b602c, 0x009d602b, 0x009f6028, 0x009f6025, 0x00a06022, 0x00a16020, 0x00a2601a, 0x00a46118, 0x00a86218, 0x00ad6418, 0x00b06417, 0x00b16616, 0x00b36818, 0x00b56d1c, 0x00b6701e, 0x00b36b19, 0x00b36b19, 0x00b36b19, 0x00b36b19, 0x00b46a19, 0x00b36918, 0x00b46918, 0x00b56a19, 0x00b46a19, 0x00b46b19, 0x00b46c1a, 0x00b46c1a, 0x00b46c1b, 0x00b36c1c, 0x00b36c1c, 0x00b46c1c, 0x00b46d1e, 0x00b46f1f, 0x00b46f1f, 0x00b46e1e, 0x00b36d1d, 0x00b36d1d, 0x00b46e1e, 0x00b67020, 0x00b67020, 0x00b56f1f, 0x00b46c1c, 0x00b16b1b, 0x00b06819, 0x00ae6518, 0x00ac6218, 0x00a75e15, 0x00a55e17, 0x00a45e17, 0x00a15b13, 0x009e5811, 0x009f5811, 0x009f5811, 0x009f5812, 0x00a05913, 0x009f5912, 0x009b5610, 0x009a5715, 0x00985514, 0x00955413, 0x00945210, 0x00905010, 0x008c4d0f, 0x008b4e10, 0x00884d11, 0x00884e14, 0x00844b13, 0x007e4611, 0x007c4511, 0x00733f0c, 0x006d390a, 0x00663409, 0x005d300a, 0x004f2a09, 0x00401e09, 0x00331705, 0x00291507, 0x00241408, 0x001d1205, 0x001c1105, 0x001c1209, 0x001c110b, 0x001b130b, 0x001c140d, 0x001c160e, 0x00171108, 0x00161008, 0x0019140b, 0x001a140b, 0x00181208, 0x00161008, 0x00151008, 0x00141008, 0x0015110c, 0x0014140f, 0x000c0f0b, 0x00080d08, 0x00050f08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00050d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00060c08, 0x00080c08, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00070f08, 0x00070f08, 0x00080e09, 0x00080f0b, 0x000f1410, 0x00151a17, 0x00222624, 0x00313534, 0x00343837, 0x00313534, 0x00303433, 0x002a3030, 0x002a3030, 0x00292c2e, 0x0025282a, 0x00242828, 0x00242828, 0x00262829, 0x00252728, 0x00282a2b, 0x002c2d2f, 0x002f3032, 0x00333334, 0x003a3738, 0x00403b3c, 0x00464040, 0x004e4644, 0x005b4f4d, 0x00645853, 0x0073605c, 0x007b625f, 0x007f6462, 0x00836761, 0x00886862, 0x0085665d, 0x00896860, 0x008d6961, 0x008c645c, 0x008c6250, 0x008c6046, 0x0090603d, 0x00916036, 0x00956031, 0x00996130, 0x009c602e, 0x009c602b, 0x009d6029, 0x009e6026, 0x009d6022, 0x009e601e, 0x009f601b, 0x00a3611a, 0x00a7621b, 0x00aa6218, 0x00ac6216, 0x00b16718, 0x00b46c1a, 0x00b46d1b, 0x00b06a18, 0x00b06918, 0x00b46c1a, 0x00b36918, 0x00b36918, 0x00b56b1a, 0x00b36918, 0x00b26515, 0x00b26515, 0x00b26718, 0x00b46918, 0x00b46a19, 0x00b46a19, 0x00b46a1a, 0x00b36a1b, 0x00b46b1c, 0x00b46b1c, 0x00b46c1c, 0x00b36c1c, 0x00b36c1c, 0x00b16b1b, 0x00b16b1b, 0x00b26b1b, 0x00b46d1e, 0x00b46c1d, 0x00b36c1c, 0x00b26b1c, 0x00b0681b, 0x00b0681b, 0x00ad6618, 0x00ac6418, 0x00a75f14, 0x00a35c12, 0x00a05c13, 0x00a05c15, 0x009e5813, 0x009e5712, 0x009f5813, 0x009f5813, 0x009f5813, 0x00a05914, 0x009e5814, 0x009b5512, 0x009a5714, 0x00985412, 0x00965413, 0x00945211, 0x00935111, 0x008e4e10, 0x008a4d10, 0x00884d11, 0x00884d14, 0x00854b13, 0x00814814, 0x007c4612, 0x0074400f, 0x00703b0c, 0x006b380d, 0x005d2f0a, 0x00502a09, 0x00401f08, 0x00341805, 0x002a1508, 0x00241409, 0x0021150c, 0x0020140c, 0x001c120c, 0x00190f0b, 0x00170f09, 0x0018100a, 0x0019130c, 0x001a140d, 0x0018130a, 0x00181309, 0x00181108, 0x00181108, 0x00181108, 0x00181109, 0x0018120c, 0x0018140f, 0x00181611, 0x000d100c, 0x00080e08, 0x00050f08, 0x00040c06, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00050d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e05, 0x00040d05, 0x00060c05, 0x00060c05, 0x00080c05, 0x00060c05, 0x00060c05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00060c08, 0x00060c08, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00060f08, 0x00070f08, 0x00080e09, 0x00080f0a, 0x00101611, 0x00171c18, 0x002c302e, 0x00313534, 0x00323534, 0x00303433, 0x002e3130, 0x00262b2c, 0x00212526, 0x00242726, 0x00232625, 0x00212526, 0x00242728, 0x00252728, 0x00282a2b, 0x00303133, 0x002d2f30, 0x002d2f30, 0x00313134, 0x00393838, 0x00403b3d, 0x00484243, 0x00534b48, 0x005d5250, 0x00655954, 0x00705d59, 0x007a605e, 0x007e6360, 0x00846863, 0x00876b64, 0x00876a60, 0x008b6a63, 0x008b6861, 0x008d6760, 0x008f6556, 0x008f624c, 0x00906040, 0x00926038, 0x00956032, 0x00986031, 0x009b602d, 0x009c6029, 0x009d6028, 0x009d6025, 0x009c5e20, 0x009b5d1c, 0x009d5d19, 0x00a2601a, 0x00a7621c, 0x00a66017, 0x00a86015, 0x00ab6214, 0x00ae6516, 0x00ac6616, 0x00aa6414, 0x00ab6414, 0x00ae6516, 0x00ae6314, 0x00ae6414, 0x00b16717, 0x00b16717, 0x00b26616, 0x00b36616, 0x00b16616, 0x00b16718, 0x00b06517, 0x00af6416, 0x00b06618, 0x00b36a1c, 0x00b3691c, 0x00b2681c, 0x00b1681b, 0x00af681a, 0x00ae6618, 0x00af6719, 0x00ae6719, 0x00af681a, 0x00b16b1c, 0x00af681a, 0x00af681c, 0x00af681c, 0x00af681c, 0x00ae681c, 0x00ab6418, 0x00a96115, 0x00a55e14, 0x00a05b12, 0x009e5a11, 0x009e5912, 0x009d5812, 0x009e5712, 0x009f5813, 0x009f5813, 0x009e5712, 0x009c5510, 0x009d5714, 0x009e5714, 0x009c5815, 0x00995513, 0x00985413, 0x00965312, 0x00945212, 0x00904f10, 0x008c4d10, 0x008a4c11, 0x00884c13, 0x00854a13, 0x00844815, 0x00804815, 0x0076400e, 0x00703c0c, 0x006d380d, 0x005e2f09, 0x00502a0a, 0x0043200b, 0x00341805, 0x002a1508, 0x0024140a, 0x0021150c, 0x0020150e, 0x001e140f, 0x001a0f0b, 0x00160e09, 0x00150f0a, 0x0015100a, 0x0018130c, 0x0018120b, 0x0018120b, 0x0018110a, 0x00171009, 0x00181208, 0x00181208, 0x001a140c, 0x001d1710, 0x001a1913, 0x000d100c, 0x00080e08, 0x00050f08, 0x00040c06, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c06, 0x00060c06, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060c05, 0x00060c05, 0x00080c05, 0x00060c05, 0x00060c05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00090d0a, 0x00060c08, 0x00060c07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100a, 0x00040c08, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00040c06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00070f0a, 0x0008100c, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00070f08, 0x00080e08, 0x00080f09, 0x00101410, 0x00262b25, 0x0030332f, 0x00343734, 0x002f3130, 0x00282c2b, 0x00222624, 0x00232627, 0x00202424, 0x00252928, 0x001d2020, 0x001e2222, 0x00272a2b, 0x0028292b, 0x00313334, 0x002c2d2f, 0x002a2c2f, 0x002d3032, 0x00313334, 0x00363536, 0x003e3a3c, 0x00494244, 0x00534b4b, 0x005d5150, 0x00685c56, 0x00725f59, 0x007b605c, 0x007e6360, 0x00846764, 0x00856c64, 0x00876a60, 0x008b6a62, 0x008b6861, 0x008c6660, 0x0090645b, 0x00906150, 0x00905f42, 0x00935e39, 0x00965f35, 0x00985f32, 0x009a5f2c, 0x009c5f28, 0x009c5f26, 0x009c5f24, 0x009c5d20, 0x009b5c1b, 0x009c5c18, 0x009e5c16, 0x00a15c17, 0x00a15b16, 0x00a35a14, 0x00a55e14, 0x00a55e14, 0x00a55d13, 0x00a96014, 0x00a96014, 0x00a96014, 0x00aa5f14, 0x00ac6014, 0x00b06418, 0x00ac6214, 0x00b06617, 0x00b3681c, 0x00b2681b, 0x00af6417, 0x00ac6316, 0x00ac6217, 0x00ac6317, 0x00ac6418, 0x00ac6318, 0x00ac6318, 0x00ac6318, 0x00ac6217, 0x00ab6116, 0x00aa6115, 0x00ac6217, 0x00ab6218, 0x00ab6118, 0x00a86016, 0x00a96118, 0x00a96118, 0x00aa6218, 0x00a86117, 0x00a65f14, 0x00a55e14, 0x00a25b12, 0x009f5a12, 0x009e5a12, 0x009c5811, 0x009c5812, 0x009e5912, 0x00a05814, 0x00a05814, 0x009e5712, 0x009f5813, 0x009f5814, 0x009f5814, 0x009c5816, 0x009c5614, 0x00985412, 0x00985411, 0x00955312, 0x00905010, 0x008d4e11, 0x00894b11, 0x00874b13, 0x00864912, 0x00844814, 0x00804714, 0x00784210, 0x0075400f, 0x006f3a0f, 0x0062300a, 0x00582c0c, 0x0048220a, 0x003a1a08, 0x002b1507, 0x0024140a, 0x0020140c, 0x001f140d, 0x001f130e, 0x001e130e, 0x0018120d, 0x0014100a, 0x0015100b, 0x0014100a, 0x0017120c, 0x0016120a, 0x00151008, 0x00171008, 0x00181308, 0x001a1409, 0x001d170d, 0x001f1810, 0x00191710, 0x000c0e09, 0x00070d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c06, 0x00060d04, 0x00060d04, 0x00060d03, 0x00060e01, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00090d0a, 0x00060c08, 0x00060c07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100a, 0x00040c08, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c0a, 0x00040c08, 0x00060e09, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00070f0a, 0x0008100c, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00070f08, 0x00080e08, 0x00080f08, 0x00121711, 0x00252a24, 0x002d312d, 0x002d2f2c, 0x00222422, 0x00202422, 0x00202422, 0x001b1f20, 0x00222526, 0x00242828, 0x00262a2a, 0x002a2d30, 0x002d3034, 0x002f3034, 0x002e2f32, 0x002a2c2d, 0x002b2c30, 0x002d3132, 0x00313334, 0x00363435, 0x00413e40, 0x004c4648, 0x00504848, 0x005a4f4c, 0x006c5d58, 0x0074615c, 0x007b605c, 0x007d635f, 0x00846865, 0x00856c64, 0x00876a60, 0x008b6a63, 0x008b6861, 0x008b645f, 0x0090645c, 0x00906150, 0x00905f42, 0x00935e39, 0x00955e34, 0x00985d31, 0x009b5e2c, 0x009c5e28, 0x009d5e26, 0x009d5d24, 0x009c5c20, 0x009b5b19, 0x009a5a16, 0x009b5914, 0x009c5815, 0x009f5814, 0x00a05814, 0x009f5912, 0x00a05911, 0x00a35b14, 0x00a55d16, 0x00a65e16, 0x00a65e16, 0x00a45b12, 0x00a75d14, 0x00a85f15, 0x00a65d11, 0x00a75e12, 0x00aa6016, 0x00aa6218, 0x00a96118, 0x00ab6419, 0x00a96119, 0x00a55d15, 0x00a75f16, 0x00a86017, 0x00a86017, 0x00a86018, 0x00a65e15, 0x00a96119, 0x00a96118, 0x00a55d14, 0x00a45c14, 0x00a45c15, 0x00a55f18, 0x00a45e17, 0x00a45e17, 0x00a45e17, 0x00a45f17, 0x00a45d16, 0x00a15c14, 0x00a05912, 0x009e5813, 0x009c5814, 0x009b5814, 0x009c5812, 0x009c5913, 0x009d5814, 0x009e5915, 0x009f5a16, 0x009f5a16, 0x009e5916, 0x009d5816, 0x009d5816, 0x009c5614, 0x00985412, 0x00985411, 0x00955412, 0x00915111, 0x008f5013, 0x00894d13, 0x00874b13, 0x00854811, 0x00844814, 0x00804714, 0x00794210, 0x00784311, 0x00703c0f, 0x0066340d, 0x00582b0a, 0x004b2208, 0x0041200a, 0x002d1506, 0x00251408, 0x001e120b, 0x001c130c, 0x001e140c, 0x001e160d, 0x001e160e, 0x001c140e, 0x00150f08, 0x00171009, 0x0018120b, 0x0018100a, 0x0018110a, 0x0019140b, 0x001b150c, 0x001c170c, 0x00201910, 0x001c160f, 0x0013110b, 0x00080c07, 0x00040b05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d03, 0x00060d03, 0x00060d04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00090d0a, 0x00060c08, 0x00060c07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100a, 0x00040c08, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00060e08, 0x00051007, 0x00051007, 0x00051007, 0x00040e05, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070d08, 0x00070d08, 0x00080c08, 0x000a0e09, 0x00151915, 0x00242823, 0x00292d29, 0x002a2c2a, 0x00222422, 0x00212524, 0x00202423, 0x00272b2b, 0x00292c2d, 0x002b2e2f, 0x002c3030, 0x002b2e30, 0x00272a2c, 0x00292b2e, 0x0025282b, 0x0026282b, 0x002b2c30, 0x002c2f31, 0x002e3030, 0x003a383b, 0x00434043, 0x00484243, 0x0052494a, 0x00605452, 0x006c5d58, 0x0074605c, 0x007b605c, 0x007d625e, 0x00836864, 0x00866b64, 0x00886a62, 0x008c6b64, 0x008c6864, 0x008c6660, 0x008f645b, 0x00906150, 0x008f5d41, 0x00925d3a, 0x00955e34, 0x00985d31, 0x009b5e2c, 0x009c5e29, 0x009d5e25, 0x009a5b20, 0x0099591b, 0x00995918, 0x00995915, 0x00995817, 0x009a5716, 0x009b5415, 0x009c5414, 0x009c5614, 0x009b5613, 0x009c5714, 0x009e5815, 0x009e5814, 0x009f5814, 0x009d5712, 0x00a05813, 0x00a05913, 0x00a05a12, 0x00a05911, 0x00a05912, 0x00a05912, 0x00a45c15, 0x00a75f18, 0x00a65e18, 0x00a55d17, 0x00a45b15, 0x00a45c15, 0x00a55c16, 0x00a65e18, 0x00a65e18, 0x00a75f18, 0x00a45c16, 0x00a35a14, 0x00a45b17, 0x00a45c18, 0x00a35c18, 0x00a45c18, 0x00a35c17, 0x00a35c17, 0x00a15c17, 0x00a05914, 0x009f5813, 0x009c5411, 0x009a5412, 0x00995513, 0x00995514, 0x009a5714, 0x009a5614, 0x009a5513, 0x009c5614, 0x009c5815, 0x009e5817, 0x009e5818, 0x009c5716, 0x009b5514, 0x00995412, 0x00955210, 0x00955210, 0x00945110, 0x00925212, 0x008f5013, 0x00894d12, 0x00874b13, 0x00844912, 0x00814814, 0x007f4814, 0x007e4816, 0x007a4413, 0x00743f12, 0x00683710, 0x00633413, 0x00502409, 0x003f1a04, 0x00301404, 0x00261407, 0x001f130c, 0x001d110b, 0x001c120a, 0x001e140c, 0x001f150c, 0x0020160c, 0x001c140b, 0x001b1308, 0x001b1208, 0x001a1008, 0x001b1309, 0x001c140a, 0x001c140b, 0x001c140d, 0x001b130e, 0x0017120d, 0x0011100c, 0x00080c08, 0x00050c06, 0x00040d07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c08, 0x00060c05, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c08, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080e0a, 0x00060c08, 0x00060c07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100a, 0x00040c08, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00040c08, 0x00040c08, 0x00040d07, 0x00061007, 0x00051007, 0x00051007, 0x00040e05, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x0004100a, 0x0004100a, 0x0004100a, 0x0005100a, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d08, 0x0009100a, 0x00151a14, 0x00242822, 0x00272b28, 0x00272927, 0x00282b29, 0x00242827, 0x002e3131, 0x002f3334, 0x002c3030, 0x00242829, 0x00222526, 0x00272a2c, 0x00242729, 0x0027282b, 0x002a2c2e, 0x002d2f32, 0x002a2c2f, 0x002c2f31, 0x00343537, 0x003c3a3c, 0x00434041, 0x00484344, 0x00554c4d, 0x00645858, 0x006f5f5c, 0x0076605c, 0x007c615d, 0x007d625f, 0x00836864, 0x00856a64, 0x00886a63, 0x008c6b64, 0x008c6964, 0x008d6760, 0x008f6459, 0x00906150, 0x008f5d41, 0x00925d3a, 0x00955c34, 0x00975c30, 0x00995c2b, 0x009a5c28, 0x009a5c23, 0x0098581c, 0x00955718, 0x00965515, 0x00965714, 0x00955714, 0x00965515, 0x00985314, 0x00985314, 0x00985413, 0x00985413, 0x00985414, 0x009a5615, 0x00995513, 0x00995413, 0x00995413, 0x009c5814, 0x009d5814, 0x009d5814, 0x009d5814, 0x009d5814, 0x009f5813, 0x009f5813, 0x009f5813, 0x009f5813, 0x009d5712, 0x009c5512, 0x009c5612, 0x009d5713, 0x009f5814, 0x00a05814, 0x00a05915, 0x00a05915, 0x00a05814, 0x009f5916, 0x00a05a18, 0x00a05c18, 0x009f5a18, 0x009e5a15, 0x009d5814, 0x009c5815, 0x009a5513, 0x00985310, 0x00985311, 0x00985313, 0x00975414, 0x00955414, 0x00945413, 0x00965412, 0x00955213, 0x00965314, 0x00985515, 0x00995718, 0x009a5718, 0x00985414, 0x00985413, 0x00985413, 0x00945210, 0x00945110, 0x00945110, 0x00925212, 0x00905114, 0x008b4e11, 0x00884c14, 0x00834a12, 0x007f4611, 0x007c4512, 0x007c4814, 0x007d4816, 0x00764012, 0x006f3c13, 0x00643411, 0x00582a0c, 0x00472108, 0x00301503, 0x00271306, 0x001f140c, 0x001c120b, 0x00181008, 0x00180f07, 0x001a1208, 0x001c1409, 0x001d150b, 0x0020180c, 0x001d140b, 0x001b1308, 0x001c1208, 0x001c1309, 0x001b120b, 0x0018120c, 0x0018110c, 0x00171210, 0x0010110d, 0x00080c08, 0x00050c06, 0x00040d07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00070e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c08, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c09, 0x00060c08, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060c08, 0x000b110d, 0x00101612, 0x00141916, 0x00212423, 0x00242625, 0x00252726, 0x00282c2c, 0x00303434, 0x002d3033, 0x00232628, 0x00242729, 0x002a2d30, 0x00242729, 0x0024282a, 0x0025272a, 0x002c2c30, 0x002c2d30, 0x002c2e31, 0x0034383a, 0x0035383b, 0x00383639, 0x00403c3d, 0x00444041, 0x005a5252, 0x00675959, 0x00705e5c, 0x00755f5d, 0x007b605e, 0x007f6460, 0x00846764, 0x00836864, 0x00886a66, 0x008f6d6c, 0x00906c68, 0x00906a65, 0x0091665c, 0x00926451, 0x00916044, 0x00925d3a, 0x00945c31, 0x00985c30, 0x0096592a, 0x00955826, 0x00955920, 0x00935619, 0x00915416, 0x00905113, 0x008d5010, 0x008e5010, 0x00905010, 0x00914e0f, 0x00914d0e, 0x00904e0c, 0x00925010, 0x00955311, 0x00965514, 0x00975514, 0x00955412, 0x00945211, 0x00955412, 0x00985412, 0x00985311, 0x00995412, 0x00995412, 0x009a5411, 0x009b5410, 0x009a5310, 0x009a5310, 0x009a5412, 0x00985311, 0x0096500f, 0x00985311, 0x009a5513, 0x009c5614, 0x009b5514, 0x009a5413, 0x00995413, 0x00975514, 0x00985716, 0x00985716, 0x00975614, 0x00975614, 0x00965413, 0x00945414, 0x00935013, 0x00914e11, 0x00924e11, 0x00935014, 0x00904f13, 0x008a4b0f, 0x00884c0e, 0x008b4e10, 0x008c4d10, 0x008b4c0e, 0x008c4d10, 0x008e5012, 0x00905013, 0x00915113, 0x00925012, 0x00915012, 0x00945314, 0x00975618, 0x00965517, 0x00925214, 0x008f5010, 0x008b4d0f, 0x00884c13, 0x00834914, 0x007e4613, 0x007c4514, 0x007d4814, 0x007d4612, 0x00794211, 0x00723e10, 0x006c3c12, 0x005a2c0a, 0x004a2306, 0x00341804, 0x00281305, 0x001e1408, 0x001c1308, 0x00191208, 0x00151009, 0x00130d08, 0x00140f08, 0x0019130c, 0x001b140e, 0x001d140c, 0x001e140c, 0x0020140d, 0x0024140f, 0x00191008, 0x0015110a, 0x0016110c, 0x00181310, 0x0010120c, 0x00070e06, 0x00040c04, 0x00040e05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e07, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040c06, 0x00030c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040f08, 0x00040f08, 0x00060e08, 0x00070f0a, 0x0008100c, 0x000a0f0c, 0x00141815, 0x001c1e1d, 0x00222424, 0x002b2e2f, 0x002c2f30, 0x0025282b, 0x002b2e30, 0x00282c2e, 0x00232628, 0x001d2023, 0x0025272a, 0x00282a2d, 0x002f3033, 0x002c2d30, 0x002c2d31, 0x00313435, 0x00323437, 0x00353435, 0x003b3838, 0x00484444, 0x00595150, 0x00645756, 0x00725f5c, 0x0078605d, 0x007c615d, 0x00806561, 0x00846865, 0x00846965, 0x00896c69, 0x0090706f, 0x00916d6a, 0x00916b67, 0x0094685c, 0x00946654, 0x00946248, 0x00945f3c, 0x00985f36, 0x0094592e, 0x00905628, 0x00905624, 0x00905620, 0x008d541a, 0x008c5217, 0x008a4e14, 0x00884d11, 0x008a4e10, 0x008c4c10, 0x008c4b0f, 0x008c4b0e, 0x008c4c0e, 0x008f4e10, 0x00905011, 0x00915112, 0x00915011, 0x00905010, 0x00904f10, 0x00915112, 0x00955111, 0x00975011, 0x00975011, 0x00975011, 0x00965010, 0x00965010, 0x00965010, 0x0095500f, 0x00965110, 0x00955112, 0x00945010, 0x00945010, 0x00945111, 0x00965212, 0x00945111, 0x00945010, 0x00945010, 0x00905112, 0x00925414, 0x008e5011, 0x008e5011, 0x008e5010, 0x008d5012, 0x008c4e14, 0x00884b11, 0x00884810, 0x00884910, 0x00874a12, 0x007f440c, 0x00753c05, 0x00764006, 0x00784108, 0x00773e05, 0x00773d04, 0x00794006, 0x007c4409, 0x0080440a, 0x00804409, 0x00854a0e, 0x00884c10, 0x008c4f13, 0x00905215, 0x008f5114, 0x008b4e11, 0x008a4e11, 0x00894d11, 0x00874c13, 0x00834914, 0x00804814, 0x007e4817, 0x007f4814, 0x007c4511, 0x007a4312, 0x00754013, 0x00703f13, 0x0063330c, 0x00522a0a, 0x003a1c04, 0x002e1807, 0x00201305, 0x001d1406, 0x001a1308, 0x00171208, 0x00161008, 0x00140e08, 0x00160f08, 0x0019120b, 0x001b1109, 0x001e140b, 0x00251810, 0x002c1a13, 0x0020140c, 0x001a140a, 0x00171109, 0x0019150f, 0x0011130c, 0x00080f07, 0x00040c04, 0x00040e05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00030c06, 0x00030c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050d09, 0x00060c08, 0x00080e0b, 0x00181c19, 0x00282828, 0x002d2d2d, 0x002b2c2e, 0x00282c2c, 0x00272a2c, 0x00212728, 0x00212427, 0x00232628, 0x002a2b2e, 0x002c2e31, 0x002c2c30, 0x002c2d30, 0x002c2e30, 0x00333435, 0x00303437, 0x002e3031, 0x00353334, 0x003e3a3a, 0x004c4646, 0x005d5453, 0x00675956, 0x0073605c, 0x0078615c, 0x007b625d, 0x007e6360, 0x00846865, 0x00856b67, 0x008d706d, 0x00937372, 0x00916e6c, 0x008f6a65, 0x0092675c, 0x00926451, 0x00936248, 0x00945f3d, 0x00915a34, 0x008d562d, 0x008c5428, 0x00885021, 0x00834e1c, 0x00804c18, 0x00824d18, 0x00844e18, 0x00834c15, 0x00844b13, 0x00864a14, 0x00884a14, 0x00884912, 0x00894b10, 0x008c4d12, 0x008c4d12, 0x008b4c11, 0x008c4c11, 0x008a4c10, 0x008c4d11, 0x008d4e13, 0x00914f14, 0x00935014, 0x00945014, 0x00945015, 0x00945114, 0x00945114, 0x00935013, 0x00935013, 0x00925014, 0x00914f14, 0x00904e11, 0x00904e11, 0x00904e11, 0x008f4d10, 0x008f4d10, 0x008f4d10, 0x008e4d11, 0x00894d10, 0x00894e12, 0x00894f11, 0x00864c0f, 0x00844b10, 0x00824810, 0x007d4410, 0x007c4211, 0x007c4312, 0x00784010, 0x00703b0c, 0x006c380a, 0x006a380b, 0x0067380a, 0x00653408, 0x00673508, 0x00673506, 0x00683706, 0x006c3a07, 0x00713d09, 0x0077400d, 0x00743f0b, 0x00763f0a, 0x007a420d, 0x00804610, 0x007c430d, 0x007c420c, 0x00814812, 0x00844b15, 0x00854b14, 0x00844b14, 0x00834b18, 0x007e4918, 0x007d4714, 0x007c4410, 0x00794211, 0x00764214, 0x00724011, 0x006b3a0d, 0x00582e08, 0x00412105, 0x00311904, 0x00251605, 0x00201404, 0x001c1104, 0x00191206, 0x001a1207, 0x001a1209, 0x001b1109, 0x001c1208, 0x001c1107, 0x001e1006, 0x0025140c, 0x0027140a, 0x0025150c, 0x0020150c, 0x001c140c, 0x0019160d, 0x0010140b, 0x00071007, 0x00051008, 0x00040f08, 0x00040f08, 0x00060e06, 0x00060e06, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00080f0a, 0x000c110e, 0x001e2120, 0x00303131, 0x002b2b2b, 0x00282a2b, 0x0025282a, 0x0026292c, 0x00272c2e, 0x002b2e30, 0x002b2e30, 0x002c2e31, 0x002e2d31, 0x00292b2e, 0x002d2f32, 0x00303233, 0x00303234, 0x002d3030, 0x00303334, 0x00333032, 0x00403c3c, 0x00514a49, 0x00615856, 0x006b5d5a, 0x0074605c, 0x007c6460, 0x007c635f, 0x007e635f, 0x00846a66, 0x00886c69, 0x00927572, 0x00937373, 0x0091706c, 0x00906c67, 0x0090665a, 0x0090614f, 0x00906045, 0x00905d3c, 0x008b5632, 0x00804c26, 0x007d4920, 0x007a461c, 0x00764516, 0x00714210, 0x006f3f0e, 0x00754413, 0x007a4815, 0x007b4612, 0x007c4512, 0x007f4513, 0x00804411, 0x0081460f, 0x00844810, 0x00854912, 0x00844810, 0x00844910, 0x00834710, 0x00844910, 0x00864b12, 0x008a4c13, 0x008c4c13, 0x008c4c13, 0x008c4c14, 0x008c4d13, 0x008c4e13, 0x008d4e13, 0x008f4e14, 0x008d4e13, 0x008a4b12, 0x00884911, 0x00884911, 0x00884911, 0x00884810, 0x00884810, 0x00884810, 0x00864810, 0x00824a10, 0x007f480f, 0x007d470e, 0x007a440c, 0x0075400c, 0x00723d0c, 0x00703c0d, 0x006c380a, 0x00663409, 0x00613108, 0x005c2d05, 0x00582b04, 0x00542a04, 0x00542c08, 0x00582d09, 0x00582d08, 0x00582d06, 0x005b3006, 0x00603408, 0x00643409, 0x0068380c, 0x0068380a, 0x00683808, 0x00683607, 0x00673303, 0x006c3808, 0x00723f0e, 0x007b4515, 0x007d4816, 0x007f4813, 0x00844c16, 0x00844d1a, 0x007e4917, 0x007c4614, 0x007b4310, 0x00784110, 0x00774213, 0x00764314, 0x006e3c0c, 0x0062350c, 0x00492606, 0x00351901, 0x00291604, 0x00231405, 0x00211406, 0x00201407, 0x00201408, 0x00201409, 0x0023170c, 0x0023170c, 0x0024150c, 0x0026150b, 0x0029150b, 0x002e180c, 0x00321e13, 0x00291910, 0x0020140b, 0x0018140b, 0x000b1007, 0x00071007, 0x00051008, 0x00031008, 0x00040f08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e06, 0x00060e06, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0009100c, 0x00151a17, 0x00232524, 0x00282828, 0x00222222, 0x00242726, 0x00242728, 0x00262b2d, 0x00282d2f, 0x0024282b, 0x00232428, 0x0029292c, 0x002c2b2f, 0x002c2e30, 0x002d2f30, 0x002f3032, 0x002e3030, 0x002d2f30, 0x002f2f2f, 0x00323031, 0x00433e3d, 0x00514a49, 0x00635958, 0x006d605c, 0x0076645f, 0x007e6761, 0x007d6460, 0x007d625e, 0x00856b67, 0x00886e6b, 0x00917572, 0x00917471, 0x00906f6a, 0x008c6963, 0x008d6758, 0x008b6250, 0x00865940, 0x00845637, 0x00825534, 0x00764926, 0x006e411e, 0x006c3f1d, 0x00714421, 0x006d401c, 0x00683b18, 0x00683a16, 0x006c3f14, 0x006e3f10, 0x00713f10, 0x00733e10, 0x00743d0f, 0x00753c0d, 0x00783e0f, 0x007b4112, 0x007f4515, 0x007b420f, 0x007b420d, 0x007e450f, 0x0080480f, 0x00834910, 0x00834910, 0x00844910, 0x00844910, 0x0084490f, 0x00884c11, 0x0084480d, 0x00874a0e, 0x00894c11, 0x00884812, 0x00854712, 0x00814411, 0x00824513, 0x00844713, 0x00834411, 0x007f440f, 0x007a410c, 0x0077400c, 0x0077400d, 0x0074400f, 0x006c3a0c, 0x0065360b, 0x0060330b, 0x005d330c, 0x0058300b, 0x00542b0a, 0x00522b0b, 0x004f2908, 0x004c2907, 0x004c2906, 0x004f2808, 0x00502808, 0x00542807, 0x00542805, 0x00542806, 0x005d320e, 0x00643814, 0x00643712, 0x005f340e, 0x005e320b, 0x0060310b, 0x0060320c, 0x0064340c, 0x0067380e, 0x006e3e12, 0x00744114, 0x00784413, 0x007d4815, 0x007f4918, 0x007e4918, 0x007b4714, 0x00794310, 0x00784211, 0x00784212, 0x00764212, 0x00743d0d, 0x006d3a10, 0x00542b09, 0x00381800, 0x002c1304, 0x00281408, 0x00251509, 0x00261507, 0x00261508, 0x002a190d, 0x002e190f, 0x002c150c, 0x002c150c, 0x00311b10, 0x00341d10, 0x00331b0d, 0x003c2518, 0x002c1a0f, 0x001e1308, 0x00131006, 0x00080d04, 0x00060e08, 0x00040f08, 0x00031008, 0x00040f08, 0x00070f09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060d0b, 0x00060d0b, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00080f08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040c06, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x000f130b, 0x000f130b, 0x0014180d, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130b, 0x000f130b, 0x000f130b, 0x0014180f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e06, 0x00060f04, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x000b110d, 0x00181e1a, 0x00242624, 0x00282828, 0x00242424, 0x00242625, 0x00242527, 0x001c2124, 0x001b2021, 0x001f2324, 0x00282a2d, 0x002d2c30, 0x00323135, 0x00323234, 0x00303133, 0x002d2f30, 0x002c2e2f, 0x00262828, 0x002c2c2c, 0x00373333, 0x003f3a3a, 0x00544d4e, 0x00665c5c, 0x00716260, 0x00796864, 0x007e6764, 0x00806863, 0x00806561, 0x00846865, 0x00856c68, 0x008c726e, 0x008f706e, 0x00886864, 0x0084645c, 0x007c594a, 0x00795441, 0x007c563e, 0x00754d33, 0x00704729, 0x00684020, 0x00643c1c, 0x00633a1c, 0x00653d1e, 0x00673d1e, 0x0064391a, 0x00603414, 0x005e330e, 0x0063370d, 0x0065370c, 0x0067380d, 0x0069360c, 0x006a360b, 0x006c360b, 0x006e380c, 0x00713b0f, 0x00733c0c, 0x00733d0b, 0x0077400b, 0x0078420c, 0x0078420c, 0x0078410c, 0x007c430d, 0x007c440c, 0x0080450f, 0x00844910, 0x0081460e, 0x0083480e, 0x00854911, 0x00844711, 0x00804510, 0x007b400f, 0x007b4010, 0x007a3f10, 0x00763d0d, 0x00733c0c, 0x006e3b09, 0x006c3808, 0x006b3909, 0x0068390c, 0x0060340a, 0x00592f08, 0x00552c09, 0x00502909, 0x004c2809, 0x004a270a, 0x004a270c, 0x0049280c, 0x004a280a, 0x004b2a09, 0x004c2909, 0x004f2809, 0x00512708, 0x00522807, 0x00532908, 0x00572d0a, 0x00582e0b, 0x005c3310, 0x005c340e, 0x0059300a, 0x00582d08, 0x00582c08, 0x005c2f09, 0x0060340c, 0x0064360c, 0x00693a0c, 0x006f3f10, 0x00754312, 0x007a4516, 0x007c4617, 0x007a4513, 0x00784210, 0x00784212, 0x00794314, 0x00784414, 0x00784010, 0x00733d10, 0x005c300e, 0x003b1b02, 0x002b0f01, 0x00261105, 0x00261409, 0x002c180c, 0x002f1b0d, 0x00321e10, 0x0030180c, 0x0034180d, 0x0031180c, 0x00371d11, 0x00382012, 0x00301808, 0x00381f13, 0x00301d12, 0x001a0f04, 0x00100c03, 0x00080d04, 0x00060e08, 0x00040f08, 0x00031008, 0x00040f08, 0x00070f0a, 0x00050d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060f08, 0x00070e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x000f130b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00071007, 0x00040e04, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x000a110c, 0x001b201c, 0x00242624, 0x00242323, 0x00201f20, 0x001d1e1e, 0x00202123, 0x00202426, 0x00222729, 0x00272a2c, 0x00303134, 0x002e2d31, 0x00303033, 0x00323032, 0x00303032, 0x002b2b2b, 0x002a2b2b, 0x00282828, 0x002b2b2a, 0x00343030, 0x003e3939, 0x00565050, 0x006b5f60, 0x00756665, 0x007b6864, 0x007e6864, 0x00816864, 0x00806664, 0x00816866, 0x00846d68, 0x008c736f, 0x008a6e6c, 0x007c5f59, 0x00785950, 0x006d503f, 0x006c4d3a, 0x00694834, 0x006b4630, 0x00654328, 0x00664428, 0x00634225, 0x005c3b1e, 0x00603c1f, 0x00603d20, 0x00603c1e, 0x005c3818, 0x005c3613, 0x005c3612, 0x005c340e, 0x005b310c, 0x00643711, 0x0063360f, 0x0061340b, 0x0063340c, 0x0063350c, 0x00693b0f, 0x006d3e10, 0x006c3d0d, 0x006f3f0c, 0x00723e0e, 0x00743e0c, 0x0075400e, 0x00794110, 0x007b4310, 0x007b420f, 0x007b420e, 0x007c430e, 0x007c440e, 0x007d4410, 0x007a4210, 0x00743d0e, 0x006f390c, 0x006e3810, 0x0069360f, 0x0068380e, 0x0061340a, 0x005e3207, 0x005d3308, 0x005d350c, 0x005a340f, 0x00552f0e, 0x00522c0f, 0x004e2a10, 0x004b2910, 0x0046240b, 0x0045230c, 0x0045240c, 0x0048280e, 0x004b2910, 0x00502c14, 0x00522a10, 0x00502809, 0x00532909, 0x00542808, 0x00552908, 0x005d310f, 0x00643816, 0x005c300d, 0x00572c09, 0x00562c08, 0x005b300c, 0x005c300d, 0x005a2f0a, 0x005d330b, 0x00603409, 0x0064390c, 0x006c3e10, 0x00754416, 0x00794418, 0x00794314, 0x00784112, 0x00784112, 0x00794314, 0x00794412, 0x0078410f, 0x00703b0b, 0x00633711, 0x00442509, 0x002f1301, 0x00261106, 0x0027140c, 0x0029140a, 0x002c160b, 0x002f170b, 0x00321708, 0x00371b09, 0x00341808, 0x003f2517, 0x00351c0e, 0x00301609, 0x00381f14, 0x00342016, 0x00180c02, 0x000f0c04, 0x00080e07, 0x00051008, 0x0005100a, 0x0004100a, 0x0005100a, 0x00070f08, 0x00050d06, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040d07, 0x00050d07, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180b, 0x00191c0b, 0x0014180a, 0x00191c0a, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x00191c0a, 0x00141809, 0x00191c0b, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00071007, 0x00040e04, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e06, 0x00060e06, 0x00060e06, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00080f0a, 0x00121714, 0x00212321, 0x00232222, 0x00222222, 0x00262827, 0x00292b2c, 0x002c2f31, 0x002d3334, 0x00323538, 0x00343538, 0x00323034, 0x00323134, 0x00353336, 0x002c2b2d, 0x002b2b2b, 0x002b2b2b, 0x00282928, 0x002c2c2a, 0x00363332, 0x00413d3c, 0x00595352, 0x006e6262, 0x00796866, 0x007c6864, 0x007f6864, 0x00806964, 0x00806664, 0x00826967, 0x00846d68, 0x00846c69, 0x007c615e, 0x00755953, 0x006f5348, 0x006e5440, 0x006e5440, 0x00674a37, 0x0061422d, 0x005b3e25, 0x00573a20, 0x005a3c20, 0x005c3e22, 0x005a3c1e, 0x00583a1c, 0x0058391b, 0x00573718, 0x00583817, 0x00583513, 0x00573211, 0x00593412, 0x00583210, 0x0057300d, 0x0058320e, 0x005c3410, 0x005c3410, 0x005e350f, 0x00613810, 0x0063380d, 0x00643a0c, 0x0069380e, 0x006c380e, 0x006c3910, 0x00703b12, 0x00723d0f, 0x00743e0c, 0x0075400f, 0x00773f0f, 0x0076400c, 0x0074400c, 0x00713f0c, 0x006d3c0d, 0x0066370c, 0x00623410, 0x005c310e, 0x005a300d, 0x0059340c, 0x00573109, 0x00553209, 0x00563610, 0x00563614, 0x004d2d0f, 0x004a2a0e, 0x0044240c, 0x003d2009, 0x003c1d06, 0x003c1b04, 0x003c1d04, 0x003f2008, 0x0041220c, 0x00482511, 0x0049240c, 0x004e2708, 0x00542a08, 0x005b2f0d, 0x005c2f0d, 0x005a2e0c, 0x005a2f0c, 0x005c300c, 0x005d320d, 0x005d330c, 0x00603410, 0x005c3310, 0x00542b05, 0x005b310b, 0x005d340a, 0x0062390d, 0x00693f11, 0x00734317, 0x00754117, 0x00784014, 0x00774011, 0x00784112, 0x007a4414, 0x007b4514, 0x007b440d, 0x00733d0a, 0x00693c15, 0x004a2b0c, 0x00321701, 0x00271105, 0x0028150d, 0x0029140d, 0x002e160d, 0x0033190d, 0x00381c0b, 0x003b1e08, 0x003d230f, 0x003a2111, 0x002c1406, 0x002c1408, 0x00361f14, 0x00382419, 0x00140b00, 0x00100c06, 0x00081008, 0x00051008, 0x0005100a, 0x0004100a, 0x0005100a, 0x00071008, 0x00050e04, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00040c06, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050f08, 0x00050f08, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180e, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x001d200a, 0x00191c09, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2008, 0x00202309, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d200a, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c0a, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d08, 0x00040d08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00050e06, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00070e09, 0x000a100c, 0x00181c1a, 0x00252726, 0x00292b2a, 0x002c2d2c, 0x002a2e2c, 0x002b2e2f, 0x002e3132, 0x00353738, 0x0039393b, 0x00353235, 0x00343033, 0x002f2d2e, 0x002c2a2b, 0x00302f2f, 0x00302f2e, 0x00302e2d, 0x00323030, 0x00383735, 0x00413e3e, 0x005c5454, 0x00736464, 0x007b6967, 0x007d6964, 0x007f6964, 0x00816866, 0x00806865, 0x00816a67, 0x00846d6b, 0x00836b6a, 0x007a615d, 0x00735a50, 0x006a5345, 0x0067503c, 0x0068503b, 0x00664c39, 0x00604530, 0x0062472f, 0x00604429, 0x005d4024, 0x005a3b1d, 0x00533517, 0x00503314, 0x004e3214, 0x00513415, 0x00523412, 0x00583714, 0x005b3918, 0x00543314, 0x004d2c0d, 0x004e2c0c, 0x00523010, 0x00523010, 0x00543412, 0x0054340f, 0x0058350e, 0x0059360c, 0x005b360b, 0x005f340a, 0x0063340a, 0x0065360b, 0x006a390d, 0x006c3a10, 0x00703c12, 0x00764214, 0x007a4514, 0x00794311, 0x00743e0d, 0x00703c0c, 0x006b3c0e, 0x0062360a, 0x0059310b, 0x00552f0a, 0x00573410, 0x00573411, 0x00573310, 0x00502d0c, 0x004c2a0c, 0x00442609, 0x003b2007, 0x00381c08, 0x00341a08, 0x00331a09, 0x00361c0c, 0x00341a08, 0x00391e0b, 0x00391f0b, 0x00442917, 0x00482c18, 0x0050331a, 0x00503111, 0x0054340e, 0x005a340e, 0x005c340e, 0x005c320d, 0x005e3410, 0x005e350e, 0x005e350e, 0x005e350e, 0x0060340f, 0x005b310c, 0x005b310c, 0x005c320d, 0x005d340c, 0x005e3710, 0x00643c14, 0x006b3e15, 0x006e3f14, 0x00734012, 0x00784112, 0x00794314, 0x007b4516, 0x007d4816, 0x007e4711, 0x007a4310, 0x006f3f15, 0x00562d0f, 0x00381700, 0x002b1304, 0x0025140c, 0x0027130d, 0x002e170c, 0x00351c0f, 0x003e200e, 0x0040200c, 0x00412713, 0x00301808, 0x00281104, 0x00281007, 0x00382016, 0x00372418, 0x00130d03, 0x000a1007, 0x00051008, 0x0005100a, 0x00060f0a, 0x0005100a, 0x0004100a, 0x00051007, 0x00040e04, 0x00040f04, 0x00040f06, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00050e07, 0x00050e07, 0x00060e08, 0x00050e07, 0x00040f06, 0x00050f07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00030c08, 0x00030c08, 0x00030c08, 0x00030c08, 0x00040e08, 0x00040e08, 0x00040d08, 0x00040d08, 0x00040e08, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060f09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00060e08, 0x00060e07, 0x00060e08, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00030c04, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00060d07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00050c06, 0x00040c07, 0x00070e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2009, 0x001d2008, 0x001d2008, 0x00202308, 0x00202308, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202308, 0x00202308, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c09, 0x00191c0a, 0x00191c0a, 0x00191c0c, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d05, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x000b100d, 0x001c201f, 0x002c302f, 0x00323534, 0x00303434, 0x00303334, 0x00333737, 0x00343536, 0x00313032, 0x002c282a, 0x00292528, 0x002e2c2c, 0x00333030, 0x00343231, 0x00353432, 0x00333130, 0x00353432, 0x00393836, 0x00413e3e, 0x005f5454, 0x00746463, 0x007c6966, 0x007d6a64, 0x00806964, 0x00816866, 0x00826967, 0x00806966, 0x00806865, 0x007a6261, 0x00745c58, 0x006f584f, 0x00695445, 0x0066503d, 0x0068503c, 0x00664c38, 0x00614630, 0x005e4129, 0x005d4024, 0x00604022, 0x00684427, 0x00644121, 0x005c3c1d, 0x00563818, 0x00543716, 0x00543714, 0x00563816, 0x005a3c1c, 0x0056381b, 0x00503114, 0x0046290d, 0x00422509, 0x0043260a, 0x00452a0c, 0x004c3210, 0x00533612, 0x00583914, 0x005a3912, 0x005c360e, 0x005d340c, 0x0062380c, 0x0064380c, 0x0068380e, 0x006d3c14, 0x00733f13, 0x00764010, 0x0078400f, 0x00753c0c, 0x00703b0d, 0x0068380c, 0x005f340a, 0x0059310a, 0x00542f0a, 0x00522f0e, 0x00502f10, 0x004c2b0c, 0x00462408, 0x00402108, 0x00371a03, 0x00341c07, 0x002f1907, 0x00291707, 0x00271708, 0x00261609, 0x00281708, 0x00281507, 0x002e1b0b, 0x002f1c0c, 0x0034200d, 0x003c240f, 0x00442c10, 0x004c3112, 0x00533313, 0x00563312, 0x00583210, 0x005b3512, 0x005b3611, 0x005c3710, 0x005c3510, 0x005e3410, 0x005c320d, 0x005c320d, 0x005b310c, 0x005b310c, 0x005b330f, 0x00603614, 0x00673b14, 0x006c3f13, 0x00734113, 0x007a4414, 0x007b4514, 0x007c4516, 0x007e4817, 0x007e4713, 0x007c4411, 0x00724016, 0x00603213, 0x00401c04, 0x002c1403, 0x00241309, 0x0024130a, 0x002b1609, 0x00331c0c, 0x003f2010, 0x00472615, 0x00381b09, 0x002c1301, 0x002b1003, 0x002c1108, 0x003d2418, 0x00362317, 0x00121005, 0x00081209, 0x0004110b, 0x0006100c, 0x00080f0b, 0x0005100a, 0x0004100a, 0x00040f08, 0x00040e05, 0x00040f05, 0x00040f06, 0x00040d07, 0x00040c08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00050e07, 0x00040f05, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00060d07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00040c06, 0x00030d06, 0x00051008, 0x00040f08, 0x00040f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180e, 0x0014180b, 0x0014180b, 0x00191c0b, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2008, 0x001d2008, 0x00202308, 0x00202309, 0x00202309, 0x0024250b, 0x0024250b, 0x0024250b, 0x0024250c, 0x0024250c, 0x0026280c, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280c, 0x0026280c, 0x0024250c, 0x0024250c, 0x0024250b, 0x0024250b, 0x0024250b, 0x0024250b, 0x00202309, 0x00202309, 0x00202308, 0x001d2008, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c09, 0x00191c0a, 0x00191c0c, 0x0014180b, 0x0014180c, 0x0014180d, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00050d08, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00070f0b, 0x00111815, 0x00282d2b, 0x00343936, 0x00313534, 0x00303334, 0x00363638, 0x00373838, 0x00302e30, 0x00322e30, 0x00332f30, 0x00333030, 0x00343030, 0x003a3535, 0x00393635, 0x003b3938, 0x00363433, 0x00353331, 0x00403c3b, 0x00605456, 0x00746363, 0x007d6966, 0x00806a64, 0x00816965, 0x00826967, 0x00826868, 0x007e6764, 0x007a6460, 0x00735c59, 0x006d5652, 0x006e5850, 0x00685348, 0x00654e3f, 0x00674e3c, 0x00674d38, 0x00644830, 0x005f4226, 0x005e3d20, 0x00623e1e, 0x00643e1e, 0x00623c1c, 0x005d3b1c, 0x005a381a, 0x0059391a, 0x00563919, 0x004d3214, 0x004a2e14, 0x00442a10, 0x00402510, 0x003c230d, 0x00381f0c, 0x0038200c, 0x0039220b, 0x003b250b, 0x0040270a, 0x00472c0e, 0x004e3112, 0x00553412, 0x005a3511, 0x00623c17, 0x00603810, 0x0063350c, 0x006c3c11, 0x00744012, 0x00774310, 0x007a4310, 0x00743c0c, 0x006f3a0c, 0x0067380a, 0x005e3408, 0x00583008, 0x00522c0a, 0x004b270b, 0x0048260c, 0x00402209, 0x003a1d08, 0x00351a06, 0x002c1503, 0x00261403, 0x00221302, 0x001d1104, 0x001a1105, 0x00191407, 0x001c170b, 0x00160f03, 0x00180e02, 0x00140b00, 0x00190f02, 0x00201104, 0x00261606, 0x0033210e, 0x003f2812, 0x00472c16, 0x004c3017, 0x00513518, 0x00533414, 0x00523410, 0x00563412, 0x005a3413, 0x005a3311, 0x005b3210, 0x0059300e, 0x00582f0c, 0x0058300f, 0x005e3412, 0x00663a14, 0x006c3f13, 0x00714011, 0x00774012, 0x00784313, 0x007b4415, 0x007d4718, 0x007c4716, 0x007b4412, 0x00734014, 0x00663714, 0x00462105, 0x002e1402, 0x00261509, 0x00241409, 0x002a1508, 0x00321809, 0x003f2011, 0x004a2819, 0x00381808, 0x00341405, 0x00341405, 0x00321404, 0x00422518, 0x00332015, 0x00110e05, 0x0008120c, 0x0004120c, 0x0008100c, 0x00090f0c, 0x0008100b, 0x0005100b, 0x00051009, 0x00040f07, 0x00051008, 0x00051008, 0x00050d09, 0x00040c09, 0x00060d0a, 0x00060d0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f07, 0x00070f08, 0x00070f08, 0x00060f08, 0x00040f05, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00041008, 0x00041008, 0x00041008, 0x00050f08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00050d07, 0x00050d07, 0x00040c07, 0x00040c07, 0x00040d07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x00202308, 0x0024250b, 0x0024250b, 0x0024250c, 0x0026280c, 0x0026280b, 0x0026280b, 0x00292b0b, 0x0026280a, 0x00292b0b, 0x00292b0b, 0x00292b0a, 0x002c2d0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x002c2d0a, 0x002c2d0b, 0x00292b0b, 0x00292b0b, 0x0026280a, 0x00292b0b, 0x0026280a, 0x00292b0b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280c, 0x0024250c, 0x0024250b, 0x0024250b, 0x00202309, 0x001d2008, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c09, 0x00040c09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d09, 0x0008100d, 0x00161d1a, 0x002c322e, 0x00383d3c, 0x00383a3c, 0x003d3d3f, 0x00363636, 0x00323031, 0x00343032, 0x00383435, 0x00383434, 0x00363130, 0x00383232, 0x00393535, 0x003b3838, 0x00343332, 0x00343130, 0x00433f3e, 0x00645758, 0x00756162, 0x007f6966, 0x00816a65, 0x00836a66, 0x00826967, 0x00826968, 0x00806868, 0x007d6663, 0x006e5851, 0x0068514b, 0x00665048, 0x00644d44, 0x0061493c, 0x00644938, 0x00654b34, 0x00654b2f, 0x00634425, 0x00613f1e, 0x0065401c, 0x00663d1b, 0x00643b1a, 0x005f381a, 0x005c3819, 0x00593718, 0x00513415, 0x00442d12, 0x003c260e, 0x00301905, 0x002e1807, 0x002b1808, 0x002b1809, 0x002d190b, 0x002d1a0a, 0x00301e0a, 0x00341f08, 0x00372008, 0x003d240c, 0x0046290c, 0x004f2f0f, 0x005c3a19, 0x005e3815, 0x00683c14, 0x00714013, 0x00744110, 0x0076400b, 0x0078400c, 0x00743b0b, 0x006e390c, 0x006a3b0d, 0x0061360b, 0x00593109, 0x00542d0c, 0x0049240c, 0x00401f0b, 0x00381c08, 0x00311a06, 0x00291504, 0x00241303, 0x00201304, 0x001e1406, 0x001b1206, 0x00181208, 0x0017140b, 0x0018160f, 0x00141009, 0x00110d04, 0x000f0e07, 0x000a0a03, 0x000d0c06, 0x00140f09, 0x0018100b, 0x00170c01, 0x00231407, 0x002c1c08, 0x0038230b, 0x00442c10, 0x004c3113, 0x004c2e11, 0x00523113, 0x00543010, 0x00542e0f, 0x00542f0f, 0x00563010, 0x00593210, 0x005f3513, 0x00643911, 0x006c4013, 0x00744314, 0x00794314, 0x00794313, 0x007c4517, 0x007e481b, 0x007d4719, 0x007c4414, 0x00733f12, 0x006a3b14, 0x004b2708, 0x00341a04, 0x002c1a0b, 0x00281709, 0x002b1609, 0x0032180b, 0x00402011, 0x004c2819, 0x00421d10, 0x003e190c, 0x003c1808, 0x003d1907, 0x004c2b1c, 0x002f1c10, 0x00121008, 0x0008120e, 0x0005130c, 0x0008100d, 0x0009100c, 0x0008100b, 0x0005110b, 0x0006100b, 0x00041009, 0x00051009, 0x00051009, 0x00060d0b, 0x00050d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060f07, 0x00060f08, 0x00060e08, 0x00060f08, 0x00040f05, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040f08, 0x00021008, 0x00021008, 0x00021008, 0x00041008, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040d06, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c09, 0x00191c09, 0x001d2008, 0x00202308, 0x00202308, 0x0020230a, 0x0024250b, 0x0024250b, 0x0026280b, 0x00292b0b, 0x00292b0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x002d2f0b, 0x0030310c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x002d2f0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x00292b0a, 0x00292b0a, 0x002c2d0a, 0x00292b0b, 0x00292b0b, 0x0026280b, 0x0026280c, 0x0024250c, 0x0024250b, 0x00202309, 0x00202308, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f09, 0x00060e08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c09, 0x00040c09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00040d08, 0x00040d08, 0x00040d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d06, 0x00050d06, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00070c07, 0x00070c07, 0x00050c07, 0x00050c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00060e0a, 0x00060e0a, 0x00060e0a, 0x00060f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050e08, 0x00050e08, 0x00050d09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d09, 0x00040d09, 0x00040d09, 0x00040d09, 0x00040d09, 0x00040d09, 0x00050e0a, 0x000b1410, 0x00141c18, 0x00272f2a, 0x00383d39, 0x00393c3c, 0x00404040, 0x00393838, 0x00343132, 0x00343032, 0x00373233, 0x003d3836, 0x003d3836, 0x003b3735, 0x003d3a39, 0x00373534, 0x00383635, 0x00373332, 0x00454040, 0x0066595b, 0x00766363, 0x007f6866, 0x00826b66, 0x00846c67, 0x00826968, 0x00836a69, 0x00846c6a, 0x007d6560, 0x006e5850, 0x00654f47, 0x00644d45, 0x00614b43, 0x0060483a, 0x00624834, 0x0064472e, 0x00634526, 0x00654420, 0x00603f1a, 0x005e3a15, 0x005f3b14, 0x005e3816, 0x00583416, 0x004d2d11, 0x0043250c, 0x00341c04, 0x00241400, 0x00231304, 0x001a0b00, 0x00201105, 0x00211207, 0x00231409, 0x0025160b, 0x0027180b, 0x00281909, 0x002c1b08, 0x00301c08, 0x00341e0a, 0x00381e07, 0x0043240a, 0x00543113, 0x00613c19, 0x006f421a, 0x00784417, 0x00784210, 0x007b410b, 0x007c420c, 0x00783f0c, 0x00743d0a, 0x00703e0b, 0x00693908, 0x0062340c, 0x0059300d, 0x0049240b, 0x003e1d0b, 0x00301a07, 0x00281403, 0x00241304, 0x00221207, 0x0022150b, 0x001d1108, 0x001c1109, 0x001f150d, 0x00231a14, 0x002c231c, 0x00211811, 0x001d140d, 0x0014100c, 0x0010110f, 0x00292825, 0x00120f0c, 0x001c130f, 0x0020140d, 0x002c1d14, 0x00261507, 0x00200d00, 0x00281300, 0x00321b04, 0x0039200c, 0x003f240c, 0x0042250c, 0x0045270c, 0x0049280c, 0x004e2c10, 0x00563011, 0x00603712, 0x00643910, 0x006c3f10, 0x00754312, 0x00794210, 0x007a4312, 0x007c4517, 0x007e471b, 0x007d461b, 0x007c4315, 0x00713c10, 0x006d3d13, 0x00522d09, 0x003a1d02, 0x00311c09, 0x002c190b, 0x002c170b, 0x0031180a, 0x003f1f10, 0x004c2819, 0x004f2618, 0x00471d0d, 0x00431908, 0x004d2412, 0x00533020, 0x0028170e, 0x0010110d, 0x0009110f, 0x0008110f, 0x00081010, 0x0009100f, 0x0007100c, 0x0005110b, 0x0006110b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f0b, 0x00050d0a, 0x00050d0a, 0x00050d0a, 0x00050d09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040f07, 0x00040f07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d09, 0x00040d09, 0x00040e0a, 0x00040e0a, 0x0005100a, 0x00050f0a, 0x00040f09, 0x00040e08, 0x00040f08, 0x00041008, 0x00041008, 0x00041008, 0x00040f08, 0x00060e09, 0x00050d09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060d08, 0x00060d08, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d06, 0x00050d06, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e08, 0x00040e08, 0x00040e08, 0x00040e08, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c04, 0x00060c04, 0x00060c04, 0x00060c05, 0x00050c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x0020230a, 0x0024250c, 0x0026280c, 0x0026280b, 0x00292b0a, 0x00292b0a, 0x002d2f0a, 0x002d2f0b, 0x0030310c, 0x0030310c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0034350c, 0x0034350c, 0x0032330c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0b, 0x0026280a, 0x0026280b, 0x0024250b, 0x0024250b, 0x00202309, 0x00202308, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c09, 0x0014180a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e0b, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x0008100c, 0x000d1510, 0x001c2420, 0x00323834, 0x0030322f, 0x00383735, 0x003f3a3c, 0x00342e30, 0x00363031, 0x00363030, 0x00403837, 0x00413c39, 0x00373430, 0x00393837, 0x003a3837, 0x00393535, 0x00383333, 0x00464040, 0x0066595b, 0x00776464, 0x007f6867, 0x00836b66, 0x00856c68, 0x00836a68, 0x00836a69, 0x00806766, 0x00765e58, 0x0071594f, 0x006b5248, 0x00674e44, 0x00644c3f, 0x00644a39, 0x00634631, 0x0064452b, 0x00634224, 0x0060401c, 0x00593916, 0x00553713, 0x00563815, 0x00482b0d, 0x00381f05, 0x00291502, 0x001c0d00, 0x00140900, 0x00130b03, 0x00140c04, 0x00171007, 0x001c140a, 0x0024170e, 0x0023150c, 0x0021140a, 0x0021140a, 0x00241409, 0x0028170b, 0x002b170a, 0x00311b0d, 0x00391e0d, 0x00462711, 0x00543114, 0x0068401f, 0x00784822, 0x00824c1f, 0x00884c1a, 0x008f5018, 0x00915118, 0x008c4f15, 0x00884c13, 0x00844c11, 0x007b440d, 0x006b370a, 0x005f300b, 0x00512a0c, 0x00432109, 0x00331b07, 0x00291502, 0x00281404, 0x00251508, 0x0023140b, 0x00201009, 0x0022110b, 0x00281810, 0x00302015, 0x003d2d21, 0x00372619, 0x002e1c10, 0x002c1f14, 0x00251d14, 0x002c2118, 0x002c1e12, 0x002d1c0d, 0x003b2113, 0x00482e1c, 0x00402814, 0x0037200b, 0x002c1401, 0x00291000, 0x002f1705, 0x00321a06, 0x00341a06, 0x00391d06, 0x0048270f, 0x004f2c12, 0x005a3310, 0x00653b14, 0x006a3d10, 0x00704010, 0x00774410, 0x007b4410, 0x007b4313, 0x007c4417, 0x007f471a, 0x007d461b, 0x007b4216, 0x00713c0f, 0x006d3c10, 0x005c330c, 0x00401f00, 0x00361b05, 0x002e1909, 0x002f190d, 0x0033190c, 0x0040200f, 0x004e2916, 0x00562c18, 0x004c200d, 0x00491d09, 0x005d311c, 0x004e2c1a, 0x001f120c, 0x000e1311, 0x000a120f, 0x000c1010, 0x00091111, 0x00091110, 0x0008110e, 0x0006120b, 0x0006120a, 0x0004100a, 0x0005110b, 0x0005110b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040f07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060d03, 0x00060d04, 0x00060c06, 0x00040b04, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280c, 0x0026280b, 0x00292b0a, 0x002c2d0a, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0034350c, 0x0036370c, 0x0036370c, 0x0036370c, 0x0036370c, 0x0036370b, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0036370c, 0x0036370c, 0x0036370c, 0x0038380c, 0x0038380c, 0x0036370c, 0x0034350c, 0x0034350c, 0x0034350c, 0x0032330c, 0x0034350c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x00292b0a, 0x00292b0b, 0x0026280b, 0x0024250b, 0x0024250b, 0x00202309, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e0b, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040c08, 0x00040c08, 0x00050e09, 0x0008100b, 0x0009110c, 0x00141c17, 0x002b302c, 0x0030332e, 0x00343330, 0x00423b3b, 0x00312828, 0x00322828, 0x00322928, 0x00372e2c, 0x00403935, 0x003d3938, 0x003c3a39, 0x003c3c3b, 0x003b3838, 0x00373131, 0x00484142, 0x00655658, 0x00796464, 0x00806a68, 0x00846b67, 0x00866c69, 0x00846a68, 0x00826868, 0x007c6262, 0x00735954, 0x00705649, 0x006c5345, 0x00684d40, 0x00654a3b, 0x00644837, 0x005e432f, 0x00593d24, 0x00553920, 0x0054381c, 0x004c3316, 0x0041280c, 0x002e1500, 0x00261200, 0x001c0d01, 0x00170c03, 0x00100a04, 0x001d1a19, 0x001f1c1c, 0x00120e08, 0x00181104, 0x00241a0a, 0x002d2011, 0x0028170c, 0x0026160e, 0x0022130c, 0x00211108, 0x00261409, 0x00281409, 0x002d180b, 0x003c2010, 0x004b2a14, 0x00553315, 0x006e4623, 0x00825029, 0x008a5226, 0x0092551f, 0x009a581a, 0x009c5b18, 0x00985615, 0x00945314, 0x00905014, 0x00844a10, 0x00733a09, 0x00633206, 0x00562c09, 0x00482407, 0x003a1c04, 0x00301701, 0x002f1804, 0x002c1706, 0x002b1608, 0x002c1508, 0x002d1408, 0x002e1508, 0x00331b0b, 0x003f2414, 0x00402715, 0x00361e0c, 0x003b2310, 0x00402812, 0x004a3017, 0x004f3217, 0x00543418, 0x00613c20, 0x00654224, 0x00613f1e, 0x00583816, 0x004e2c11, 0x0046250c, 0x00412008, 0x0044240a, 0x00442309, 0x004a2409, 0x004e2608, 0x00582c0d, 0x0062340d, 0x006c3d0f, 0x00744012, 0x00774310, 0x007b4511, 0x007c4511, 0x007c4512, 0x007c4416, 0x007d4519, 0x007d461b, 0x007c4318, 0x00733c10, 0x006f3c10, 0x0061340c, 0x00482300, 0x00391c04, 0x00301907, 0x00311b0e, 0x00351b0c, 0x003f1f0c, 0x004d2811, 0x00583017, 0x0050240c, 0x004b2006, 0x005f341a, 0x00462512, 0x001c130c, 0x000c1513, 0x00081310, 0x000c1210, 0x00091213, 0x000a1211, 0x0008120f, 0x0007130c, 0x0006120b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040f07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060d04, 0x00060c06, 0x00060c07, 0x00040b05, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280b, 0x00292b0b, 0x002c2d0a, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0032330c, 0x0034350c, 0x0038380c, 0x0038380c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x003b3c0d, 0x003b3c0d, 0x003b3c0c, 0x003b3c0d, 0x003b3c0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003b3c0d, 0x003b3c0d, 0x003c3e0d, 0x003b3c0c, 0x003c3e0d, 0x003b3c0d, 0x003b3c0d, 0x00393b0d, 0x003b3c0d, 0x00393b0c, 0x0038380c, 0x0038380c, 0x0036370c, 0x0036370c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x002c2d0a, 0x00292b0b, 0x0026280b, 0x0024250b, 0x0020230a, 0x00202309, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e0b, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00050d09, 0x00050d08, 0x0009110d, 0x000c140f, 0x0020241f, 0x0032332f, 0x00312f2b, 0x00443938, 0x00302423, 0x00281d1a, 0x002a1f1b, 0x0028201c, 0x0038302d, 0x0045403f, 0x00403e3f, 0x00404040, 0x003d3a3b, 0x00383133, 0x004c4444, 0x00645555, 0x00796564, 0x00806967, 0x00846b68, 0x00866c6a, 0x00846b68, 0x00836768, 0x007e6363, 0x00745954, 0x006c5144, 0x00674c3c, 0x00684b3c, 0x00634537, 0x005e402f, 0x00543925, 0x004d3420, 0x00432c17, 0x0034200b, 0x002b1904, 0x002e1c08, 0x00301e09, 0x0033200f, 0x00291b0c, 0x0022170d, 0x0019140c, 0x0022201f, 0x00242322, 0x00261f17, 0x00231808, 0x003a2b16, 0x003a2a15, 0x002a1706, 0x00251207, 0x00210f06, 0x00211006, 0x00271408, 0x002c1709, 0x002e1808, 0x003e2110, 0x004e2d18, 0x005b3518, 0x00724926, 0x0085532c, 0x008c5526, 0x00985c24, 0x00a3621e, 0x00a7641a, 0x00a45e15, 0x00a15a18, 0x00995415, 0x008c4b10, 0x00783e09, 0x00683505, 0x005a2e07, 0x004f2806, 0x00432005, 0x00381900, 0x003b1d06, 0x003a1e0a, 0x003c1d0b, 0x003e1e0c, 0x003f1e0c, 0x003f1d0b, 0x003e1d09, 0x0046240f, 0x004d2c15, 0x0054321b, 0x0058361c, 0x005e3a1b, 0x00653e1c, 0x006a421e, 0x00683f1a, 0x00623813, 0x00613810, 0x00643b10, 0x0060380d, 0x005d3410, 0x005d3412, 0x005c3512, 0x005f3814, 0x00643816, 0x00693c16, 0x006b3a13, 0x006e3c13, 0x00744110, 0x007c4814, 0x00804915, 0x00824914, 0x00814813, 0x007f4812, 0x00804615, 0x007c4413, 0x007b4215, 0x007b4419, 0x00794318, 0x00723c12, 0x00703c11, 0x0064370b, 0x00502803, 0x00422106, 0x00371c08, 0x0033190a, 0x00341908, 0x003f1e08, 0x004d280e, 0x00583014, 0x005a2f10, 0x00502506, 0x005d3414, 0x003e2008, 0x001a140d, 0x00081311, 0x00071512, 0x000b1410, 0x00091213, 0x00091213, 0x00071310, 0x0007130d, 0x0006130c, 0x0005110b, 0x0005110b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040f07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c08, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280b, 0x00292b0b, 0x002d2f0a, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0036370c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x003c3e0d, 0x003e400d, 0x003e400c, 0x003e400c, 0x0040400d, 0x0040400d, 0x0041420d, 0x0040400d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0040400d, 0x0040400d, 0x0040400d, 0x0040400d, 0x0041420d, 0x0040400d, 0x0040400e, 0x0040400d, 0x003e400c, 0x003e400c, 0x003e400c, 0x003e400d, 0x003c3e0d, 0x003b3c0d, 0x00393b0d, 0x00393b0c, 0x0038380c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002c2d0a, 0x002c2d0b, 0x0026280b, 0x0026280b, 0x0024250c, 0x00202309, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c07, 0x0008100c, 0x0008100b, 0x00141a14, 0x002a2d28, 0x002c2924, 0x00413633, 0x00302520, 0x001e120c, 0x0021150f, 0x00231a13, 0x0038302c, 0x004a4545, 0x00444244, 0x00404042, 0x003e3a3b, 0x003e3738, 0x004f4544, 0x00655754, 0x00796765, 0x00806a68, 0x00846c6b, 0x00866c6c, 0x00846969, 0x00836664, 0x007f6360, 0x00765851, 0x006c503d, 0x00664834, 0x005d402c, 0x00583826, 0x004d311d, 0x00432a16, 0x003a2410, 0x00301d0b, 0x00332111, 0x00342313, 0x00392614, 0x0044301b, 0x004b341f, 0x00402912, 0x0034200b, 0x00312010, 0x00302416, 0x0038291c, 0x00342414, 0x0035200c, 0x00402811, 0x003c240b, 0x00301801, 0x00311a07, 0x00321c0a, 0x00301b0a, 0x00351e0c, 0x0038200c, 0x003a200a, 0x0044240f, 0x00543019, 0x005f3618, 0x00744826, 0x0087542e, 0x008f5728, 0x009c6025, 0x00a6661f, 0x00ab6618, 0x00a85f12, 0x00a55b14, 0x009e5414, 0x00924b10, 0x007c410a, 0x006d3807, 0x00633309, 0x00592f0a, 0x0050290a, 0x00482305, 0x004a260c, 0x004b280f, 0x004c2810, 0x004e2810, 0x004f2710, 0x00502810, 0x004f270c, 0x00502a0d, 0x00542c0d, 0x00582f10, 0x005c3312, 0x005f3510, 0x005e340d, 0x0060350c, 0x0063380f, 0x0060350c, 0x0063380e, 0x00653c0f, 0x0064380c, 0x0064370c, 0x0068390f, 0x006c3c11, 0x00714014, 0x007a4819, 0x00804b1b, 0x00804a17, 0x00854c17, 0x008a5118, 0x008c5218, 0x008b5017, 0x00884c16, 0x00864b14, 0x00824913, 0x00814814, 0x007c4414, 0x007a4113, 0x00784115, 0x00744014, 0x00703d12, 0x006e3c11, 0x0065380c, 0x00512802, 0x00452407, 0x003b1e08, 0x00341909, 0x00341909, 0x003c1c08, 0x004a260c, 0x00583012, 0x00643817, 0x005c3010, 0x005c3412, 0x00341901, 0x0016140b, 0x00081514, 0x00071614, 0x000b1510, 0x000a1314, 0x00081412, 0x00071410, 0x0008140f, 0x0004130c, 0x0005110b, 0x0005110b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00040e09, 0x00040d08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0a, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c08, 0x00060c08, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250c, 0x0026280b, 0x00292b0b, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003b3c0d, 0x003c3e0d, 0x003e400c, 0x0040400d, 0x0041420d, 0x0043440e, 0x0043440e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0043440e, 0x0043440e, 0x0041420e, 0x0041420e, 0x0040400d, 0x0040400d, 0x003e400c, 0x003c3e0c, 0x003c3e0d, 0x00393b0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0b, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0024250c, 0x00202308, 0x00202308, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x0006100a, 0x000c130e, 0x0020241c, 0x002c2c24, 0x003e3731, 0x003e342e, 0x0024180f, 0x001f1208, 0x00281c14, 0x00382d2c, 0x00494444, 0x00464448, 0x00444146, 0x00403b3f, 0x003f3736, 0x004e4340, 0x006d5e5b, 0x007c6b67, 0x007f6a68, 0x00846c6c, 0x00886d70, 0x00866b6c, 0x00846865, 0x0081645c, 0x00765548, 0x006c4b34, 0x0066422c, 0x005c3822, 0x0054321b, 0x0043270f, 0x003e240f, 0x00462e1b, 0x004e3826, 0x00533b2c, 0x00593f2e, 0x005b3e28, 0x005e4025, 0x00614223, 0x00644424, 0x00644524, 0x00634122, 0x00603f20, 0x005c3c1f, 0x0059381f, 0x00512f18, 0x004c2813, 0x0048220e, 0x00442009, 0x00422108, 0x00442509, 0x0045260c, 0x004c2810, 0x00502c12, 0x004e290d, 0x004f2a0d, 0x005f381a, 0x00683c1c, 0x00784725, 0x008b5632, 0x0094592d, 0x00a06228, 0x00a86822, 0x00ab6619, 0x00ac6417, 0x00ae6119, 0x00a95c1a, 0x009c5417, 0x00874a13, 0x00773f0d, 0x006b380c, 0x0063350d, 0x005c330d, 0x00592f0d, 0x00592e10, 0x005e3116, 0x005f3318, 0x005e3116, 0x005c3015, 0x00603419, 0x00603413, 0x00592e0a, 0x00582d07, 0x005a2f09, 0x005c300a, 0x005d300b, 0x005e320c, 0x005c340c, 0x005c360d, 0x005c350d, 0x005c340c, 0x0061350f, 0x00663710, 0x006f3c11, 0x00784415, 0x007c4414, 0x00844918, 0x008b4c17, 0x008e5015, 0x00945418, 0x00985719, 0x00985919, 0x00975718, 0x00935418, 0x008d5017, 0x00884d14, 0x00854913, 0x00834815, 0x007d4412, 0x007b4214, 0x00764114, 0x00713d11, 0x006c3c10, 0x00683a10, 0x0062370c, 0x00502904, 0x003f1d00, 0x00371802, 0x0034180a, 0x00341910, 0x00391a0c, 0x0048240e, 0x00562e10, 0x00663918, 0x00653816, 0x00603718, 0x00331a04, 0x0013130c, 0x00071615, 0x00081517, 0x000c1411, 0x000a1414, 0x00081412, 0x00071411, 0x0005130f, 0x0004130c, 0x0005120c, 0x0007110c, 0x0007110c, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00021009, 0x00021009, 0x00021009, 0x00030f09, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00051007, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0b, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0045470e, 0x0047480e, 0x0047480e, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0047480e, 0x0048490e, 0x0047480e, 0x0047480e, 0x0045470e, 0x0045470e, 0x0044450e, 0x0043440e, 0x0041420e, 0x0041420e, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x00292b0a, 0x0026280b, 0x0024250c, 0x00202308, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040d08, 0x00040f09, 0x0006100b, 0x00121911, 0x00242820, 0x0038342f, 0x00463e37, 0x0031241c, 0x00231208, 0x00291811, 0x003c302e, 0x004d4446, 0x0048444a, 0x00464148, 0x00423c40, 0x00403837, 0x004f4440, 0x006c5d58, 0x007b6a66, 0x00806b6a, 0x00846c6f, 0x00886e71, 0x00886e6f, 0x008a6c66, 0x00846257, 0x00744e3c, 0x006e4629, 0x00643c1f, 0x005d3518, 0x00542c0f, 0x00532f12, 0x005e3d23, 0x006c4c35, 0x006c4d39, 0x00694836, 0x0065412d, 0x00664027, 0x00653c20, 0x00643915, 0x00643a13, 0x00653c14, 0x00643c14, 0x00603810, 0x005c340f, 0x00593010, 0x00542b10, 0x00522911, 0x00522810, 0x00552c10, 0x0058300f, 0x00593311, 0x005a3210, 0x00603414, 0x00643716, 0x00623412, 0x00613713, 0x006b401c, 0x00734623, 0x007c4c29, 0x008e5834, 0x00985f33, 0x00a0642c, 0x00a86826, 0x00ad681d, 0x00af671a, 0x00af651a, 0x00aa5e19, 0x009c5514, 0x008d4d14, 0x007d420c, 0x00763f10, 0x006e3b0f, 0x00693b10, 0x0065390f, 0x0062340e, 0x00633411, 0x00673817, 0x006c3c1c, 0x006f401f, 0x006e401c, 0x0070411b, 0x006a3c14, 0x0063340d, 0x0060300a, 0x005f2e08, 0x005e3009, 0x005d300b, 0x005b300b, 0x005b320a, 0x0060350d, 0x0065380f, 0x006a3a12, 0x006f3d13, 0x00774415, 0x00804a18, 0x00874d1a, 0x008d501c, 0x00935417, 0x00955414, 0x00995716, 0x009b5915, 0x009c5915, 0x009a5616, 0x00945315, 0x008f5014, 0x008b4d13, 0x00864912, 0x00834815, 0x007e4514, 0x007b4214, 0x00754013, 0x00703d10, 0x0069390e, 0x0064380e, 0x005a3209, 0x004e2805, 0x003e1d02, 0x00381b07, 0x00321709, 0x0031180e, 0x00381c0d, 0x0046240f, 0x00562e0f, 0x00663a15, 0x00683c18, 0x005f3818, 0x002f1801, 0x0013140c, 0x00081716, 0x00081517, 0x000c1410, 0x000a1513, 0x00081412, 0x00051411, 0x0004140f, 0x0004130c, 0x0005130c, 0x0006100b, 0x0006100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00021009, 0x00021009, 0x00021009, 0x00030f09, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d04, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00060e08, 0x00070f08, 0x00050e08, 0x00040d07, 0x00050e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00051007, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180b, 0x00191c0a, 0x00191c08, 0x001d2008, 0x0024250b, 0x0024250b, 0x00292b0b, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0040400d, 0x0043440e, 0x0044450e, 0x0047480e, 0x0048490f, 0x0048490f, 0x00494a0f, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d10, 0x004c4d10, 0x004c4d10, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004c4d10, 0x004c4d10, 0x004c4d10, 0x004c4d10, 0x004d4e10, 0x004c4d10, 0x004c4d0f, 0x004c4d0f, 0x004b4c0f, 0x004b4c0f, 0x004b4c0f, 0x004b4c10, 0x00494a0f, 0x00494a0f, 0x0048490f, 0x0047480e, 0x0045470e, 0x0045470e, 0x0043440e, 0x0041420e, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x003b3c0d, 0x0038380c, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0a, 0x0026280b, 0x0024250c, 0x00202308, 0x001d2008, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040d09, 0x0002100b, 0x00030f09, 0x0008120b, 0x00181d16, 0x002c2c24, 0x00474039, 0x0043342c, 0x002d1911, 0x0028140f, 0x00402f2f, 0x00504449, 0x004a444c, 0x0048404a, 0x00433c42, 0x00413737, 0x004f433f, 0x006b5c57, 0x007a6964, 0x007f6a6a, 0x00826c6f, 0x00866e72, 0x008a6e70, 0x008d6c67, 0x00896152, 0x007e5038, 0x007b4c27, 0x00774721, 0x00764620, 0x0074441f, 0x00774826, 0x007b4e31, 0x007b5036, 0x00795038, 0x00774e36, 0x0071472e, 0x006f4123, 0x006c3e1b, 0x006b3c12, 0x006a3c0e, 0x00673b0c, 0x0064390b, 0x0064390c, 0x0064390d, 0x00643810, 0x00603311, 0x005d3010, 0x005d2f0c, 0x00653610, 0x006a3910, 0x006c3c10, 0x006b3b0f, 0x00703d11, 0x00733e11, 0x00703c0e, 0x00704010, 0x00734417, 0x00794920, 0x00815028, 0x00905c37, 0x00986034, 0x00a0642c, 0x00a96824, 0x00af691f, 0x00b0681c, 0x00b0671a, 0x00ae6418, 0x00a25a12, 0x00944e10, 0x0088470c, 0x00804411, 0x0078400f, 0x00713e0b, 0x006e3c0b, 0x006e3a0c, 0x006e3a10, 0x00703b12, 0x00744017, 0x00754018, 0x00784318, 0x007b471b, 0x007a461b, 0x00774318, 0x00744015, 0x00713e14, 0x006c390f, 0x0068380f, 0x0067390f, 0x00683b0e, 0x006a3b0d, 0x006d3c0e, 0x00723c10, 0x00764010, 0x007f4714, 0x00874e16, 0x008e5118, 0x00935418, 0x00975515, 0x00995714, 0x009d5915, 0x009e5914, 0x009e5914, 0x009c5713, 0x00985412, 0x00915012, 0x008c4e13, 0x00874912, 0x00844815, 0x007d4412, 0x00784012, 0x00743e12, 0x006e3b10, 0x0068380f, 0x0063370f, 0x0058310a, 0x00472404, 0x003c1e04, 0x00391d0b, 0x00301809, 0x00301a0e, 0x00341a0b, 0x0040210b, 0x00542d0c, 0x00673912, 0x006a3d15, 0x00603814, 0x002f1801, 0x0014140c, 0x00081716, 0x00091618, 0x000c1410, 0x00081412, 0x00061514, 0x00071411, 0x0006130f, 0x0004140f, 0x0006120e, 0x0006100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00021009, 0x00021009, 0x00021009, 0x00030f09, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040e04, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00051007, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x0048490f, 0x00494a0f, 0x004b4c0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00515110, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00515110, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x004f5010, 0x004f5010, 0x004d4e0f, 0x004d4e0f, 0x004c4d0f, 0x004c4d0f, 0x004b4c0f, 0x00494a0f, 0x0048490f, 0x0047480e, 0x0045470e, 0x0044450e, 0x0041420e, 0x0040400d, 0x003e400d, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0a, 0x0026280c, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040d09, 0x00030f0b, 0x00030f09, 0x00041008, 0x000d160d, 0x0020211b, 0x003c3630, 0x0050423b, 0x003c271f, 0x002f1813, 0x00463434, 0x0055484c, 0x004d464e, 0x0048414b, 0x00443c41, 0x00403536, 0x004c403c, 0x00695b54, 0x00796865, 0x007e696c, 0x00826c70, 0x00886e73, 0x008c6e70, 0x008f6c65, 0x008a5e4d, 0x00855437, 0x008a582c, 0x008b572c, 0x00885429, 0x00865128, 0x00844f28, 0x0084502f, 0x00835233, 0x00825335, 0x007e5034, 0x00784a2c, 0x00704320, 0x006c3f16, 0x00683c10, 0x00653c0d, 0x00653d0e, 0x00673d10, 0x00653c10, 0x0062380d, 0x0060360c, 0x0061350d, 0x00663810, 0x006f3e13, 0x00784417, 0x00784111, 0x007c4514, 0x007a4511, 0x007d4812, 0x007b440d, 0x007e4810, 0x00804c16, 0x00824f1d, 0x00825022, 0x0088562c, 0x00925d38, 0x00975f33, 0x00a0642b, 0x00aa6924, 0x00af681c, 0x00af6718, 0x00b36a1c, 0x00b1671a, 0x00a65d13, 0x00995110, 0x008e480c, 0x0088480f, 0x0080430c, 0x007b4109, 0x00784008, 0x007c430e, 0x007b4210, 0x00794210, 0x007c4614, 0x007c4412, 0x007c4413, 0x007b4412, 0x007d4714, 0x00814a18, 0x00854e1e, 0x00865120, 0x00824f1c, 0x007c4b18, 0x007b4c19, 0x007a4c18, 0x007c4a18, 0x007f4815, 0x00804814, 0x00854b16, 0x008b5016, 0x0094571a, 0x00935415, 0x00965414, 0x00985413, 0x009f5a18, 0x00a05a17, 0x00a05a14, 0x009e5914, 0x009c5713, 0x00975412, 0x00905111, 0x008d4f14, 0x00894c16, 0x00844917, 0x007e4413, 0x00784213, 0x00743f14, 0x006e3c11, 0x00683810, 0x00623710, 0x0055300a, 0x00442102, 0x003a1c05, 0x00371c0b, 0x0030180a, 0x00301a0c, 0x00341c0c, 0x0040220c, 0x00552d0b, 0x00683910, 0x006c3d14, 0x00603814, 0x00301801, 0x0014140c, 0x00081817, 0x00091618, 0x000b1510, 0x00081412, 0x00061514, 0x00071411, 0x0006130f, 0x0004140f, 0x0005130f, 0x0008130f, 0x0009120e, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040e04, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00051007, 0x00040e05, 0x00040e05, 0x00040d05, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004b4c0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00525310, 0x00535410, 0x00535410, 0x00535410, 0x00545510, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00545510, 0x00545510, 0x00545510, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00525310, 0x00525310, 0x00515110, 0x00515110, 0x00505010, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004c4d0f, 0x004b4c0f, 0x00494a0f, 0x0047480e, 0x0045470e, 0x0043440e, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0024250c, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x00141810, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060c0b, 0x00080c0b, 0x00080d08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00070c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00051008, 0x0008110b, 0x0010140c, 0x002c2821, 0x0051443c, 0x0048352c, 0x0039221c, 0x004c3735, 0x00584b4c, 0x004a4549, 0x00484348, 0x00423a3e, 0x00403534, 0x004b3f3a, 0x00685953, 0x00796867, 0x007d686e, 0x00826b71, 0x00886f74, 0x008d6f71, 0x00906b67, 0x00906454, 0x00946143, 0x00946031, 0x00955f2e, 0x00945b29, 0x00925525, 0x00905425, 0x0090542a, 0x008e542e, 0x008a512d, 0x0085502a, 0x007d4b22, 0x0077441b, 0x00703e14, 0x006c3b0e, 0x006b3a0d, 0x006a3b0c, 0x006a3a0d, 0x006a3a0d, 0x006a3a0e, 0x006a3c0e, 0x00734414, 0x007e4c1b, 0x008a531d, 0x00885019, 0x008c531c, 0x008c531c, 0x008a4f16, 0x00884c10, 0x008a4d0e, 0x00894d11, 0x00874d14, 0x00885020, 0x0089542b, 0x008d5b34, 0x00936039, 0x00955e33, 0x00a0642a, 0x00ac6a23, 0x00af681c, 0x00af6718, 0x00b2691c, 0x00b06419, 0x00a45b10, 0x009a5010, 0x0090490b, 0x008c490d, 0x008a4910, 0x00864810, 0x0080440e, 0x00814510, 0x00814512, 0x00844814, 0x00874c18, 0x00874d18, 0x00844a15, 0x00824814, 0x00824814, 0x00844916, 0x00844a19, 0x00884d1b, 0x00844b17, 0x00834b15, 0x00844c16, 0x00844c17, 0x00854c18, 0x00884c16, 0x008c4e17, 0x00935118, 0x00985418, 0x009b5618, 0x009c5816, 0x009e5b17, 0x00a05a18, 0x00a05c19, 0x00a15c18, 0x009e5915, 0x009c5814, 0x00985410, 0x00945310, 0x00905111, 0x008d4e14, 0x00874c15, 0x00834815, 0x007e4715, 0x00784214, 0x00703c14, 0x006c3911, 0x0066370f, 0x005f340c, 0x00512907, 0x00441f03, 0x003a1a04, 0x00371b0b, 0x0035190d, 0x00321809, 0x00371c0a, 0x00472412, 0x005f3313, 0x006c3c10, 0x00714115, 0x006a401c, 0x00331803, 0x0014140c, 0x00081817, 0x00091618, 0x000c1610, 0x00081513, 0x00071614, 0x00081413, 0x00081410, 0x00051310, 0x00061411, 0x00061311, 0x0005110f, 0x0008110d, 0x0008100d, 0x00070e0c, 0x00060d0b, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f0a, 0x00050e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x0049490f, 0x00605710, 0x00645a10, 0x00645b10, 0x00665d10, 0x00685e10, 0x00685e11, 0x00685f11, 0x00686011, 0x00696012, 0x00696012, 0x00696011, 0x00696111, 0x00696112, 0x00696112, 0x00696011, 0x00696011, 0x00686011, 0x00686012, 0x00686012, 0x00686012, 0x00685f12, 0x00685f11, 0x00686011, 0x00686011, 0x00686012, 0x00685f12, 0x00665e12, 0x00665f11, 0x00655e11, 0x00655e11, 0x00645d11, 0x00645c10, 0x00635b10, 0x00605810, 0x00545210, 0x004d4e10, 0x004d4e10, 0x004c4d0f, 0x004b4c10, 0x0048490f, 0x0045470e, 0x0044450e, 0x0041420e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0024250b, 0x0020230a, 0x001d2008, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060d09, 0x00080c09, 0x00080d09, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00080c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x000c100c, 0x00282620, 0x0041372e, 0x00524138, 0x00402a21, 0x0045322c, 0x004f4140, 0x00484042, 0x00494245, 0x0040393b, 0x00403534, 0x004b3f3a, 0x00665852, 0x00786867, 0x007c696f, 0x00816c72, 0x00897074, 0x008d7074, 0x008f6c6a, 0x00906557, 0x00946344, 0x00976336, 0x00996232, 0x00985f2b, 0x00995c28, 0x00995a28, 0x0097592a, 0x00915628, 0x008c5426, 0x00885325, 0x00814c1e, 0x007d481a, 0x007e4819, 0x007d4a19, 0x00784413, 0x00754210, 0x00774412, 0x00784514, 0x007e4b1b, 0x00855220, 0x008c5924, 0x00915d24, 0x00945d23, 0x00915b20, 0x00945b20, 0x00945c20, 0x0093571c, 0x00925516, 0x008f5213, 0x008e5115, 0x008c501b, 0x008c5426, 0x008c5732, 0x00905d3b, 0x0094603b, 0x00935d32, 0x009e6028, 0x00a86720, 0x00ae681b, 0x00ad6617, 0x00b2681d, 0x00af641b, 0x00a45a14, 0x0098510f, 0x00904a0c, 0x008c490e, 0x008a4910, 0x00884a13, 0x00884a13, 0x00884912, 0x00864811, 0x008a4d16, 0x008f521b, 0x0092541e, 0x008f521b, 0x008c5018, 0x008b4e16, 0x00894c17, 0x00874814, 0x00864a15, 0x00864b15, 0x00874c15, 0x00874c15, 0x00884c16, 0x008c5019, 0x008d5017, 0x00935219, 0x0098541b, 0x009a5619, 0x00a25c1d, 0x00a4601d, 0x00a5601c, 0x00a6601d, 0x00a6611d, 0x00a35e1a, 0x009f5a16, 0x00995512, 0x00945110, 0x00935212, 0x00905014, 0x008c4e17, 0x00874a18, 0x00834718, 0x007c4316, 0x00774015, 0x006d3912, 0x00683610, 0x0063340d, 0x005c310c, 0x004f2708, 0x00421c04, 0x00391906, 0x00371b0d, 0x00381c10, 0x00371b0b, 0x003a1a07, 0x00502813, 0x00673814, 0x00734010, 0x00784717, 0x00794c25, 0x00371c05, 0x0014140c, 0x00081817, 0x00091618, 0x000c1610, 0x00081513, 0x00071614, 0x00081413, 0x00081410, 0x00051310, 0x00071411, 0x00061411, 0x0005120f, 0x0008110d, 0x0008100d, 0x00070e0c, 0x00060d0b, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x0014180f, 0x0014180b, 0x0014180a, 0x001d200a, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x00494a10, 0x00836f10, 0x00c39c15, 0x00c69d15, 0x00c69e15, 0x00c69e15, 0x00c59f15, 0x00c59f15, 0x00c59f16, 0x00c59f16, 0x00c59f16, 0x00c59f16, 0x00c49f16, 0x00c49f16, 0x00c49f16, 0x00c49f16, 0x00c49f17, 0x00c49f17, 0x00c49e17, 0x00c49e17, 0x00c49e17, 0x00c49e17, 0x00c49e17, 0x00c49e16, 0x00c49e16, 0x00c49e16, 0x00c49e16, 0x00c39d17, 0x00c39d17, 0x00c39d17, 0x00c39d16, 0x00c29c16, 0x00c29c16, 0x00c29c15, 0x00c19c15, 0x00bd9815, 0x00b19014, 0x00967c13, 0x00665d10, 0x00505010, 0x004d4e0f, 0x004b4c0f, 0x00494a10, 0x0047480e, 0x0044450d, 0x0041420e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060d09, 0x00080c09, 0x00080d09, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00080c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x0008100a, 0x00252620, 0x00322b24, 0x00504238, 0x00543f34, 0x004c362f, 0x004f3f3b, 0x004a3e3e, 0x004c4343, 0x00403838, 0x00403634, 0x00483d3a, 0x00625653, 0x00736766, 0x00786870, 0x00806d74, 0x00877378, 0x008d727a, 0x00906e6f, 0x0091665c, 0x00936349, 0x0098633b, 0x009a6334, 0x00995f29, 0x009b5e25, 0x009d5e28, 0x00985823, 0x0093561f, 0x00915620, 0x008c551e, 0x008c5420, 0x008a511e, 0x00874f1a, 0x00854d18, 0x00854c16, 0x00864e17, 0x0089511b, 0x008b521d, 0x008b531d, 0x008d541f, 0x0090561d, 0x0090571c, 0x00905719, 0x0091581a, 0x0094591c, 0x00975c1e, 0x00965a1c, 0x00945616, 0x00935618, 0x0093551c, 0x00945826, 0x00925830, 0x008e5838, 0x00905c3f, 0x00935f3d, 0x00945e33, 0x009c6027, 0x00a8651e, 0x00ad681b, 0x00aa6314, 0x00b3691f, 0x00af641c, 0x00a25b14, 0x0095500e, 0x008e4c0e, 0x008a4c0f, 0x00894c10, 0x00884b10, 0x00884b10, 0x008a4b11, 0x008b4c12, 0x008d4e12, 0x00915217, 0x0095561a, 0x0098591d, 0x00995a1d, 0x00955619, 0x00925318, 0x008d4d16, 0x00884a14, 0x00884912, 0x00884a12, 0x008a4c15, 0x008f5019, 0x00905019, 0x00925018, 0x00975418, 0x009a5619, 0x009c561a, 0x00a05a1b, 0x00a15c1a, 0x00a4601c, 0x00a86320, 0x00a5601c, 0x00a35e1a, 0x00a05b18, 0x00995514, 0x00935012, 0x00925015, 0x008c4d14, 0x00874914, 0x00814514, 0x007d4214, 0x00784014, 0x00753f15, 0x006c3810, 0x0068350e, 0x0062350c, 0x005c330d, 0x004e280a, 0x003f1c04, 0x00351806, 0x00341c0f, 0x00381c0f, 0x003c1e0e, 0x00421f09, 0x005b2d13, 0x00734018, 0x00834d18, 0x00804b16, 0x007b4b20, 0x00402309, 0x0014150d, 0x00081818, 0x000a1719, 0x000c1713, 0x00091714, 0x00081717, 0x000b1415, 0x00091411, 0x00071411, 0x00081412, 0x00061411, 0x0005120f, 0x0008110d, 0x0008100d, 0x0008100c, 0x00050c0a, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280c, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x00645810, 0x00c49c14, 0x00cca215, 0x00cba116, 0x00caa216, 0x00caa216, 0x00cba216, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba216, 0x00cba217, 0x00cca316, 0x00cca316, 0x00cba216, 0x00c49d16, 0x00987e12, 0x005c5710, 0x004f5010, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450d, 0x0041420e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002d2f0b, 0x00292b0a, 0x0026280b, 0x0020230a, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130d, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00060d08, 0x00080d08, 0x00080d08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00080c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f0a, 0x0005100b, 0x00232721, 0x0028251d, 0x0042382c, 0x005e4a3f, 0x00523c32, 0x0054403c, 0x00504040, 0x004e4441, 0x00403835, 0x003d3434, 0x00433a38, 0x005c5452, 0x006f6466, 0x0074666e, 0x007c6c72, 0x00847177, 0x008c737c, 0x00907074, 0x00906a60, 0x0090644c, 0x0094603a, 0x00966032, 0x00996029, 0x009c5f24, 0x009f5d25, 0x009e5d24, 0x009c5d20, 0x00955818, 0x008f5416, 0x008f5419, 0x0090541c, 0x0092551c, 0x008f5118, 0x008e5017, 0x008e5016, 0x00905218, 0x0092541c, 0x0093541c, 0x0094551c, 0x00905417, 0x00905415, 0x00905314, 0x0096581a, 0x00995c1c, 0x009c5f20, 0x009c5f1f, 0x009a5c1b, 0x0096591c, 0x00965822, 0x00965a2f, 0x00945b39, 0x008f583c, 0x00905c44, 0x00915f3f, 0x00935e33, 0x009c6128, 0x00aa6821, 0x00b16b1e, 0x00ab6316, 0x00b0651c, 0x00ac631c, 0x00a05b14, 0x0093500c, 0x008d4c0d, 0x00884a0d, 0x00874b0f, 0x00884b0f, 0x00884b10, 0x0088480c, 0x008e5011, 0x00935214, 0x00985718, 0x009a591a, 0x009d5c1d, 0x009c5c1b, 0x009b5a19, 0x009a581a, 0x0097561a, 0x00935219, 0x00905017, 0x008e4d14, 0x008d4d14, 0x00905017, 0x00905118, 0x00935016, 0x00985318, 0x009c5519, 0x009c5718, 0x00a05a1a, 0x00a15c1a, 0x00a45f1b, 0x00a35e18, 0x00a05a17, 0x009d5814, 0x00995513, 0x00955211, 0x00904e10, 0x008f4e13, 0x00894a12, 0x00834613, 0x007f4212, 0x007b4013, 0x00773f15, 0x00744015, 0x006b3910, 0x0068360e, 0x0063350c, 0x005d330e, 0x004b270b, 0x00391a04, 0x00311706, 0x00321b0f, 0x00381c0f, 0x003d1f0d, 0x004d260e, 0x00663416, 0x00814c1e, 0x0090581f, 0x00854e15, 0x00804e1f, 0x0046280d, 0x0014150d, 0x00081818, 0x000a1719, 0x000c1713, 0x00091714, 0x00081717, 0x000a1415, 0x00091411, 0x00071411, 0x00081412, 0x00061411, 0x0005120f, 0x0008110d, 0x0008100d, 0x0008100c, 0x0008100c, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f0a, 0x00050e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c10, 0x006c5f10, 0x00cca215, 0x00c59e15, 0x00927b13, 0x00927c13, 0x00927c14, 0x00927c14, 0x00937d14, 0x00947e14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f15, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00937d14, 0x00937d14, 0x00937d14, 0x00988014, 0x00a68914, 0x00bc9815, 0x00c9a116, 0x00cca316, 0x00cba216, 0x00b69315, 0x006f6210, 0x004f5010, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450d, 0x0041420e, 0x003c3e0c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050c06, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x0020241e, 0x00292a22, 0x00302b1e, 0x005c4c40, 0x00584139, 0x005d413f, 0x00593f40, 0x0054403f, 0x00433634, 0x003d3534, 0x00443b3c, 0x00514a4b, 0x006a6365, 0x0072676e, 0x007a6d73, 0x00817077, 0x00846d77, 0x00896c72, 0x008d6a67, 0x008e6454, 0x00915f41, 0x00925c37, 0x009a6030, 0x009c6027, 0x009e5e25, 0x00a36228, 0x00a66625, 0x00a36421, 0x009b5c1c, 0x0096581a, 0x0098581d, 0x0099581e, 0x0099581c, 0x00975519, 0x00965418, 0x00965519, 0x0096541a, 0x00945318, 0x00905013, 0x00905112, 0x00905212, 0x00975718, 0x009c5c1c, 0x009f5e1f, 0x00a26121, 0x00a1601e, 0x009c5e1c, 0x00995c20, 0x00965c2a, 0x00945d3b, 0x00935d46, 0x008e5a49, 0x008e5e4c, 0x00905f44, 0x00915c34, 0x009a5f28, 0x00a66520, 0x00ab641a, 0x00ab6119, 0x00aa6218, 0x00a96119, 0x00a05c14, 0x0092500c, 0x008b4a0b, 0x0087480c, 0x00864a0f, 0x00864a10, 0x00884a10, 0x008c4c11, 0x00905013, 0x00965314, 0x009b5815, 0x009d5a15, 0x00a05c16, 0x00a3601a, 0x00a35f1c, 0x00a15d1c, 0x009f5c1c, 0x009e5b1f, 0x009c591d, 0x009b581c, 0x00985519, 0x00985418, 0x0099561a, 0x009d581c, 0x00a15d20, 0x009e5a1c, 0x009f5919, 0x00a35d1c, 0x00a15c1a, 0x00a05b18, 0x00a05917, 0x009b5514, 0x00975411, 0x0092500e, 0x00904e0c, 0x008b4b0c, 0x0088480c, 0x0084450f, 0x007f4412, 0x007b4213, 0x00774114, 0x00723f15, 0x006d3c13, 0x00683910, 0x0064360e, 0x00633410, 0x005d3210, 0x004a260c, 0x00351802, 0x002e1605, 0x0030190c, 0x00381c0e, 0x00472411, 0x00592e11, 0x0074401c, 0x00904f20, 0x009c581b, 0x008f5213, 0x00814c1b, 0x004c2d12, 0x0013140b, 0x00091818, 0x00091618, 0x000c1512, 0x000a1714, 0x00071518, 0x00081416, 0x00081411, 0x00071411, 0x00051310, 0x00051310, 0x00061310, 0x0008120e, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0a, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003e400d, 0x0041420d, 0x0044450d, 0x0048490f, 0x004c4d0f, 0x006d6011, 0x00cca215, 0x00c29c15, 0x00595711, 0x00585810, 0x00595a12, 0x005b5b12, 0x005c5d11, 0x005c5d11, 0x005d5e12, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005e5f13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e13, 0x005d5e12, 0x005d5e12, 0x005c5d12, 0x005c5d12, 0x005c5d11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x00615e12, 0x007e7013, 0x00af8f14, 0x00caa216, 0x00cca316, 0x00c09a15, 0x00786911, 0x004f5010, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0043440e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x002c2d0b, 0x0026280c, 0x0020230a, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050c06, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c08, 0x00202420, 0x00252720, 0x00262418, 0x0052433a, 0x00644d46, 0x00684c48, 0x00583b3a, 0x00503938, 0x00423431, 0x00423a38, 0x00433c3b, 0x004c4645, 0x00696266, 0x00736870, 0x00796d74, 0x00807077, 0x00836d78, 0x00886c74, 0x008c6c6a, 0x008c6557, 0x008f5f48, 0x00905c3c, 0x009a6035, 0x009c602d, 0x009e5f29, 0x009d5d24, 0x00a05f20, 0x00a36420, 0x00a46424, 0x00a26123, 0x009c5b1d, 0x009c5a1c, 0x009c591c, 0x00985518, 0x00965416, 0x00955315, 0x00965416, 0x00935214, 0x00925114, 0x00945416, 0x00955414, 0x009b5a1a, 0x009d5c1c, 0x00a05f1d, 0x00a26220, 0x00a2601c, 0x009d5e1d, 0x00955920, 0x0092592c, 0x00945c40, 0x00915d4b, 0x0089584c, 0x008b5c4e, 0x008d5d44, 0x008e5a33, 0x00945b24, 0x00a05f1b, 0x00a65f17, 0x00a75d17, 0x00a65e16, 0x00a55e16, 0x009d5813, 0x00904e0b, 0x00874708, 0x0087480c, 0x0085480f, 0x00854910, 0x00884b13, 0x008c4c12, 0x00925014, 0x00975312, 0x009b5814, 0x009d5a14, 0x00a05d15, 0x00a36018, 0x00a3601a, 0x00a35f1d, 0x00a35f1f, 0x00a35f20, 0x00a05c1e, 0x00a05c1d, 0x00a05c1e, 0x00a05c1e, 0x00a25d1f, 0x00a25d1f, 0x00a15d1d, 0x009e5a1a, 0x009f5a18, 0x009d5816, 0x009a5413, 0x00995410, 0x00985311, 0x00924f0e, 0x0090500e, 0x008c4e0c, 0x00894c09, 0x00864808, 0x0084470c, 0x00824610, 0x007d4413, 0x00784314, 0x00764116, 0x00703f15, 0x006b3c14, 0x00653910, 0x0063360f, 0x00623411, 0x005c3111, 0x004c250f, 0x00341802, 0x002c1402, 0x0030180a, 0x00341908, 0x004a260f, 0x00653716, 0x007d451e, 0x0093501c, 0x009e5818, 0x008e500f, 0x007f4818, 0x004c2b10, 0x0014140b, 0x000a1818, 0x00091619, 0x000c1512, 0x000b1614, 0x00071518, 0x00081416, 0x00081511, 0x00071411, 0x00051310, 0x00051310, 0x00061310, 0x0008120e, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x006e6011, 0x00cca215, 0x00c29c16, 0x005c5910, 0x00595a12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5c11, 0x005b5b12, 0x005d5c12, 0x008b7713, 0x00c39c16, 0x00cca316, 0x00c29b15, 0x00746611, 0x004f5010, 0x004c4d0f, 0x0048490f, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130d, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050c06, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060d07, 0x001c1f1a, 0x00272821, 0x00232118, 0x00443831, 0x006f5853, 0x00694b46, 0x005a3936, 0x004d3732, 0x00483a34, 0x003b352f, 0x00403b38, 0x00454040, 0x00676164, 0x00736971, 0x00776b73, 0x007d6f76, 0x00806e7a, 0x00856c75, 0x00886b69, 0x00896558, 0x008e604e, 0x00905c42, 0x00965f3a, 0x009a5f31, 0x009f602e, 0x009f5f28, 0x009e5d22, 0x009d5d1c, 0x009e5e1c, 0x009f5f1d, 0x00a05e1f, 0x009e5c1d, 0x009c5819, 0x009a5618, 0x00985515, 0x00985515, 0x00975414, 0x009a5617, 0x009e5a1b, 0x00a25f1e, 0x00a05d1c, 0x00a05c1b, 0x00a05c1a, 0x00a05c1a, 0x00a05d1a, 0x009e5d1a, 0x009c5e1e, 0x00985d28, 0x00945c34, 0x00946047, 0x00936150, 0x00895c50, 0x00865b4f, 0x008c5c46, 0x008c5834, 0x00925824, 0x009c5c1a, 0x00a45d16, 0x00a65e17, 0x00a86018, 0x00a45c16, 0x0098540d, 0x008c4b08, 0x00874708, 0x0085460b, 0x0084480d, 0x0084490f, 0x00894c12, 0x008d4d13, 0x00935014, 0x00985413, 0x009a5713, 0x009d5a14, 0x009e5c13, 0x00a15e18, 0x00a25f19, 0x00a25e1d, 0x00a46020, 0x00a66221, 0x00a4601f, 0x00a5601f, 0x00a4611f, 0x00a76120, 0x00a76220, 0x00a66320, 0x00a25f1c, 0x00a05c1a, 0x009f5a16, 0x009c5614, 0x00985414, 0x00975111, 0x00945011, 0x008e4e0e, 0x008c4e0d, 0x00884c0c, 0x0086490a, 0x0084480a, 0x0081470f, 0x007e4511, 0x00784213, 0x00744014, 0x00704016, 0x006c3e17, 0x00653a14, 0x00623811, 0x00613612, 0x005e3413, 0x00593012, 0x004a230d, 0x00341501, 0x002a1201, 0x00301609, 0x003d1f09, 0x00542f10, 0x00703d18, 0x00854b1e, 0x00934f18, 0x0097510f, 0x00894809, 0x007b4417, 0x00482810, 0x0011130a, 0x00091715, 0x00081517, 0x000b1413, 0x00081514, 0x00081415, 0x00071314, 0x00051411, 0x00071411, 0x00051310, 0x00051310, 0x00061310, 0x0008120e, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x00494a0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005c5c12, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00606013, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x007a6c13, 0x00c09a15, 0x00cca316, 0x00bc9815, 0x00655d10, 0x004d4e10, 0x004b4c0f, 0x0048490f, 0x0044450e, 0x0040400d, 0x003c3e0c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x00292b0a, 0x0026280c, 0x00202309, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050c06, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050c07, 0x001b1e19, 0x00272822, 0x0023211a, 0x00362d28, 0x006e5754, 0x00674642, 0x00593531, 0x00533b32, 0x00473930, 0x0037322a, 0x003b3833, 0x00403c3a, 0x00605c5e, 0x0070666c, 0x0074696f, 0x00776b70, 0x007c6c75, 0x00826d74, 0x00836865, 0x00856458, 0x008c6053, 0x008e5d47, 0x00915c3b, 0x00945c32, 0x00995c2c, 0x009c5c28, 0x009c5b23, 0x009c5c1e, 0x009c5c1b, 0x009c5c19, 0x009d5c19, 0x009f5d1b, 0x00a05d1c, 0x009e5a18, 0x009e5a18, 0x00a05d1b, 0x00a05d1b, 0x00a25e1c, 0x00a25e1c, 0x00a6601f, 0x00a7621f, 0x00a4601c, 0x00a25d19, 0x009f5c18, 0x009f5c17, 0x009c5c1a, 0x009b5c1e, 0x00975c2a, 0x00945b37, 0x00915f46, 0x00905f50, 0x008c5f54, 0x00845b50, 0x00885a47, 0x008a5636, 0x00915627, 0x009c5a1d, 0x00a55d18, 0x00a9611b, 0x00ac641c, 0x00a15913, 0x0094500a, 0x008c4a08, 0x0088470a, 0x0085460c, 0x0084470d, 0x00854910, 0x008b4c13, 0x008e4c12, 0x00944f13, 0x00985314, 0x00975310, 0x009a5811, 0x009c5b12, 0x009e5c16, 0x00a05c18, 0x00a05c1c, 0x00a25e1d, 0x00a4601e, 0x00a4601e, 0x00a6601d, 0x00a5611d, 0x00a7611e, 0x00a7611e, 0x00a5621e, 0x00a4611d, 0x00a25f1a, 0x009f5a16, 0x009c5715, 0x00985414, 0x00945011, 0x00935013, 0x008d4e10, 0x00884c0e, 0x0084480a, 0x00824709, 0x00804508, 0x007e450e, 0x007b4311, 0x00764114, 0x00703e15, 0x006c3c15, 0x00683c16, 0x00643814, 0x00603712, 0x005e3412, 0x005c3414, 0x00583013, 0x0049220d, 0x00331401, 0x00281001, 0x002f1608, 0x0048280f, 0x00613818, 0x00764117, 0x00874919, 0x008d490e, 0x00904a06, 0x00864608, 0x007c4219, 0x00482710, 0x0011130b, 0x000b1615, 0x00081417, 0x000b1413, 0x00081514, 0x00081415, 0x00071314, 0x00051412, 0x00071411, 0x00051310, 0x00051310, 0x00061310, 0x0008120f, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x007c6e13, 0x00c49e16, 0x00cca316, 0x00ab8c14, 0x00545210, 0x004d4e0f, 0x00494a10, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d08, 0x00040d08, 0x00040d08, 0x00040c09, 0x00040c0a, 0x00060d0b, 0x00060d0a, 0x00070d09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080d09, 0x00080c09, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00060d09, 0x00060d09, 0x00060d09, 0x00060d09, 0x00060d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060d07, 0x00070d08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040c06, 0x00171c15, 0x00282b24, 0x0021201a, 0x002d2824, 0x006c5657, 0x00684642, 0x00653f2c, 0x00644431, 0x004c382c, 0x003c342f, 0x003b3833, 0x003c3836, 0x005a5458, 0x006b6268, 0x0073686d, 0x0073666b, 0x00786970, 0x007c696e, 0x007f6463, 0x00826259, 0x00886053, 0x008b5c48, 0x008d5a3d, 0x008e5833, 0x0093582a, 0x00945623, 0x00985822, 0x0098581f, 0x00975818, 0x00995c17, 0x009f5f19, 0x00a2601b, 0x00a35d1c, 0x00a35e1c, 0x00a45f1d, 0x00a35c1a, 0x00a05c18, 0x00a4601c, 0x00a6601d, 0x00a7611e, 0x00a4601c, 0x00a45f1b, 0x00a35f1b, 0x009f5c1a, 0x009c5918, 0x00995a19, 0x00985920, 0x00965c2d, 0x00935c38, 0x00905c44, 0x008d5c4d, 0x008b5d52, 0x00875c52, 0x00885a48, 0x008a5638, 0x00905628, 0x009c5c1f, 0x00a5601b, 0x00ac641c, 0x00ab631b, 0x00a15813, 0x00944f09, 0x008c4a08, 0x0088470a, 0x0087480c, 0x0084480e, 0x00854910, 0x008a4c11, 0x008d4c11, 0x00934e12, 0x00975113, 0x00975312, 0x00975411, 0x009a5814, 0x009d5c17, 0x009f5c19, 0x00a05c1a, 0x00a15d1c, 0x00a45f1c, 0x00a4601c, 0x00a7611d, 0x00a7621c, 0x00a5601b, 0x00a6601d, 0x00a6601d, 0x00a4601c, 0x00a05c18, 0x009d5915, 0x009a5714, 0x00975312, 0x00935011, 0x00905113, 0x008c4f11, 0x00864a0e, 0x0083480c, 0x0082450a, 0x0080440b, 0x007c4410, 0x00784212, 0x00724016, 0x006e3d17, 0x006c3d18, 0x00653917, 0x00603513, 0x00603514, 0x005e3413, 0x005d3414, 0x00593013, 0x0049220d, 0x00331403, 0x00281001, 0x00301807, 0x00533012, 0x006c3f18, 0x007c4415, 0x00864814, 0x008c4b10, 0x008c4806, 0x0087460c, 0x007c421a, 0x0044250e, 0x0011130a, 0x000a1614, 0x00081516, 0x000a1513, 0x00081513, 0x000a1414, 0x00081414, 0x00071412, 0x00081210, 0x00081110, 0x00081110, 0x0006100f, 0x0005100e, 0x0005100e, 0x0005100e, 0x0005100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0a, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e08, 0x00040e08, 0x00040d08, 0x00040d08, 0x00050e08, 0x00060e08, 0x00050e08, 0x00040e08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00050c08, 0x00060c08, 0x00060c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c09, 0x00040c09, 0x00040c08, 0x00040e08, 0x00040e08, 0x00040e08, 0x00040e08, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005d5b12, 0x005c5c11, 0x005c5d11, 0x00606013, 0x00606012, 0x00606012, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00626313, 0x00626313, 0x00626313, 0x00626313, 0x00626313, 0x00626313, 0x00626312, 0x00626312, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x00937c14, 0x00cba216, 0x00caa116, 0x00857212, 0x004d4e10, 0x004b4c0f, 0x0048490f, 0x0044450e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050f08, 0x00031008, 0x00031008, 0x00031008, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c09, 0x00060e0a, 0x00060e09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d07, 0x00060e06, 0x00060e06, 0x00040f06, 0x00031008, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00080d09, 0x00080d09, 0x00080d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040c06, 0x000e130c, 0x002b2c27, 0x00282621, 0x00282320, 0x00634f51, 0x0075524e, 0x00754c34, 0x006e4830, 0x00593e2e, 0x0044362e, 0x003f3831, 0x003c3836, 0x00534e50, 0x006c6368, 0x0073686c, 0x0071656a, 0x00786970, 0x007c686d, 0x007e6363, 0x007f6058, 0x00845d51, 0x00875b48, 0x0088573d, 0x00895534, 0x008d542a, 0x008f5322, 0x0091531f, 0x0092541c, 0x00925516, 0x00965816, 0x009c5a17, 0x009d5a17, 0x009e5917, 0x00a25c1b, 0x00a45e1c, 0x00a55e1c, 0x00a6601c, 0x00a6601d, 0x00a6601d, 0x00a4601c, 0x00a25c19, 0x009d5814, 0x009c5916, 0x009c5919, 0x00985619, 0x00955719, 0x00945620, 0x0094592f, 0x00935c38, 0x00905c43, 0x008e5c4c, 0x008a5c51, 0x00885e52, 0x008a5c49, 0x008b5839, 0x0091582a, 0x009c5c20, 0x00a6601c, 0x00ab641c, 0x00ab621b, 0x00a25812, 0x00954e0b, 0x00904c0c, 0x008b490d, 0x0088480d, 0x0085480f, 0x00854a0f, 0x00894c10, 0x008c4c10, 0x00904c13, 0x00944f13, 0x00955114, 0x00955412, 0x00985614, 0x009c5a17, 0x009e5c18, 0x00a05c18, 0x00a15c18, 0x00a35d1a, 0x00a45d1a, 0x00a4601c, 0x00a55f1a, 0x00a35e19, 0x00a4601c, 0x00a4601c, 0x00a3601b, 0x00a3601b, 0x009c5914, 0x009a5713, 0x00965212, 0x00915010, 0x008d4f11, 0x00894c10, 0x00874a0e, 0x0084470c, 0x0084440c, 0x0080430d, 0x007b4111, 0x00764014, 0x00703f16, 0x006b3c18, 0x00683916, 0x00623714, 0x005e3210, 0x005e3311, 0x005f3312, 0x005d3412, 0x005a3012, 0x0048230c, 0x00331405, 0x002b1104, 0x003a1f0e, 0x00593411, 0x0078481c, 0x00824915, 0x00834712, 0x0085470e, 0x008d4b0e, 0x00884811, 0x007a431a, 0x0040220b, 0x0012140a, 0x000b1514, 0x00091516, 0x000a1513, 0x00081513, 0x000a1414, 0x00081414, 0x00071412, 0x00081110, 0x00081110, 0x00081110, 0x0006100e, 0x00051010, 0x0005100e, 0x0005100e, 0x0005100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050c08, 0x00070c08, 0x00080c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005c5c12, 0x005c5d11, 0x00606013, 0x00606012, 0x00606012, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00626314, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00626313, 0x00626312, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x005e5f13, 0x005c5d11, 0x005c5c11, 0x00605c12, 0x00b79515, 0x00cca316, 0x00b69315, 0x00595510, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00141809, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050f08, 0x00031008, 0x00031008, 0x00031008, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d07, 0x00060e06, 0x00060e06, 0x00040f06, 0x00031008, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00050d07, 0x00040e08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040d07, 0x00090e08, 0x00232620, 0x0024241e, 0x0024201a, 0x005a4a49, 0x007c5d58, 0x00754c38, 0x0070472d, 0x0066432d, 0x00523929, 0x0045372c, 0x00403935, 0x004c484a, 0x00686265, 0x0070666a, 0x0070646a, 0x0075656c, 0x0078656a, 0x007d6264, 0x007f605c, 0x00825c52, 0x00845948, 0x0085563d, 0x00865432, 0x00885128, 0x00894f20, 0x008d501d, 0x008f501c, 0x00935519, 0x00945717, 0x00985616, 0x00985513, 0x009b5614, 0x009f5816, 0x00a05a17, 0x00a15b14, 0x00a45d18, 0x00a45f1a, 0x00a45f1b, 0x00a35e1a, 0x00a25c19, 0x00a15c18, 0x00a05c1b, 0x009a5818, 0x00975618, 0x0094571b, 0x00945621, 0x0092592f, 0x00935c3a, 0x008f5b41, 0x008e5c49, 0x008b5d50, 0x00885f50, 0x008c5e49, 0x008c5a3c, 0x0092592c, 0x009f6024, 0x00aa641f, 0x00af681f, 0x00b06820, 0x00a95f19, 0x009b5410, 0x00945010, 0x008e4d10, 0x008b4c12, 0x00874a10, 0x0083490e, 0x00864c10, 0x008a4c11, 0x008d4c14, 0x008f4d14, 0x00904f14, 0x00935013, 0x00965414, 0x009a5815, 0x009e5a18, 0x00a05a17, 0x00a05916, 0x00a15a17, 0x00a35b18, 0x00a45c18, 0x00a55c18, 0x00a45c18, 0x00a45e1b, 0x00a45f1b, 0x00a05d18, 0x009b5814, 0x009c5913, 0x00995512, 0x00955312, 0x00915011, 0x008d4e12, 0x008a4c10, 0x00874a0e, 0x0084460b, 0x0082420c, 0x00804110, 0x007a4014, 0x00743d15, 0x006e3d18, 0x00683b16, 0x00623713, 0x00603513, 0x005e3210, 0x005c3211, 0x005d3311, 0x005c3311, 0x00593010, 0x0049240c, 0x00351404, 0x00301404, 0x004c2c1a, 0x006c421e, 0x007b491b, 0x007d4411, 0x00783e0c, 0x007d420e, 0x008c4c14, 0x00894b15, 0x0078431a, 0x003a1e06, 0x0013140c, 0x000b1413, 0x00081415, 0x00081513, 0x00081513, 0x000a1414, 0x00081413, 0x00071412, 0x00081210, 0x00081110, 0x00081110, 0x0006100e, 0x00051010, 0x0005100e, 0x0004100d, 0x0004100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00050c08, 0x00070c08, 0x00080c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006e6011, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00626314, 0x00626313, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x005d5e12, 0x005c5d11, 0x005b5b12, 0x008c7914, 0x00caa116, 0x00cba216, 0x007b6a11, 0x004d4e10, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0036370c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0024250b, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040f08, 0x00031008, 0x00031008, 0x00031008, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d07, 0x00060e06, 0x00060e06, 0x00040f06, 0x00031008, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00080f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00061008, 0x00061008, 0x00050f08, 0x00050f08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00050e08, 0x00070d08, 0x001b1f18, 0x0022261f, 0x00222018, 0x004c423e, 0x007e6760, 0x00704937, 0x007d5034, 0x007a4f33, 0x0064422a, 0x004c3727, 0x00403833, 0x00474446, 0x00645e62, 0x006b6268, 0x0071656c, 0x0073656c, 0x00736165, 0x00786061, 0x007d605b, 0x00805b53, 0x00805748, 0x0082543c, 0x00825132, 0x00844f29, 0x00884f21, 0x008c501e, 0x008e501d, 0x0092541b, 0x00935518, 0x00955417, 0x00975414, 0x009b5514, 0x009e5814, 0x00a15c16, 0x00a45e16, 0x00a45f18, 0x00a15c18, 0x00a15c18, 0x00a05b18, 0x00a05b18, 0x009d5814, 0x009c5817, 0x00995718, 0x00955417, 0x0094541b, 0x00915423, 0x00905730, 0x00915b3c, 0x008e5a3f, 0x008e5c48, 0x008c5f4e, 0x0088604e, 0x008c5e48, 0x008f5c3d, 0x00945a2d, 0x00a16125, 0x00af6924, 0x00b46e23, 0x00b26a20, 0x00ab601b, 0x009c5411, 0x00965413, 0x00905012, 0x008c4e14, 0x00864c11, 0x0081490e, 0x0082490d, 0x00874c10, 0x00894c14, 0x00894c14, 0x00894d13, 0x008d4d12, 0x00945114, 0x00995314, 0x009e5616, 0x00a15818, 0x00a15816, 0x00a15815, 0x00a35a16, 0x00a45c18, 0x00a45c18, 0x00a25c17, 0x00a35c18, 0x00a25c18, 0x00a05b18, 0x009e5a15, 0x009c5812, 0x00985512, 0x00955312, 0x00925012, 0x008c4d11, 0x00894b10, 0x00874a0e, 0x00824509, 0x0080400c, 0x007f3e10, 0x00783e13, 0x00723b15, 0x006c3b16, 0x00653c15, 0x00633914, 0x00603513, 0x005e3410, 0x005c3311, 0x005c3311, 0x005c3110, 0x00582f0f, 0x004d280e, 0x003a1804, 0x003a1909, 0x0055301c, 0x006f421c, 0x00713d0f, 0x00713807, 0x006f3808, 0x00763c0d, 0x00854614, 0x00884a18, 0x00724016, 0x00331a01, 0x0013160e, 0x000b1413, 0x00081415, 0x00081412, 0x000a1513, 0x000b1412, 0x00081411, 0x00081412, 0x00081210, 0x00081110, 0x00081110, 0x0007100f, 0x00051010, 0x0005100e, 0x0004100d, 0x0004100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d06, 0x00040d06, 0x00050d06, 0x00070c06, 0x00080c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0047480e, 0x00494a10, 0x004d4e0f, 0x006e6011, 0x00cca216, 0x00c39d16, 0x00685f11, 0x00656012, 0x00686112, 0x00696412, 0x006a6414, 0x006b6513, 0x006b6513, 0x006b6513, 0x006c6613, 0x006c6613, 0x006c6613, 0x006c6613, 0x006c6613, 0x006c6713, 0x006c6813, 0x006c6713, 0x006c6713, 0x006c6713, 0x006c6713, 0x006c6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006d6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006a6614, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00616112, 0x00606012, 0x005e5f13, 0x005c5d11, 0x005c5c11, 0x00646012, 0x00c49e16, 0x00cca316, 0x009f8213, 0x004c4d10, 0x004c4d0f, 0x0048490f, 0x0044450d, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f09, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d06, 0x00040d06, 0x00050e07, 0x00050e07, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00050d07, 0x00050e06, 0x00050e06, 0x00050e06, 0x00050e08, 0x00050d09, 0x00050d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x0004100a, 0x0004100a, 0x00040f0a, 0x00040f0a, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f09, 0x00060e08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050e08, 0x00040e08, 0x00040f08, 0x00031008, 0x00040f09, 0x00050f08, 0x00050f08, 0x00050f08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050d07, 0x00060d08, 0x00060e08, 0x00060e09, 0x00050e09, 0x00050e09, 0x00040d09, 0x00060f09, 0x00060e09, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050f08, 0x00060e08, 0x00060d08, 0x00121812, 0x00222820, 0x00222118, 0x003e3834, 0x0076635e, 0x006e4e3c, 0x0081543b, 0x00815031, 0x006d4525, 0x00573a23, 0x0046382f, 0x00444041, 0x005f5b5f, 0x00686168, 0x006e646a, 0x0072646b, 0x00705e64, 0x00755e60, 0x00775c59, 0x007b5952, 0x007c5649, 0x007e543f, 0x007f5035, 0x0083502d, 0x00864f26, 0x008a5022, 0x008d5020, 0x008e521c, 0x00905218, 0x00965518, 0x00985618, 0x009d5817, 0x00a05b18, 0x00a25d17, 0x00a05c14, 0x009f5a14, 0x00a05c16, 0x00a05b18, 0x009e5915, 0x009e5915, 0x009f5917, 0x009c5818, 0x00975415, 0x00925215, 0x0090511b, 0x008e5121, 0x008c5430, 0x008d583c, 0x008f5d44, 0x008c5d4a, 0x008b5f50, 0x008b6150, 0x008d5f4b, 0x00905c41, 0x00975d32, 0x00a46228, 0x00b06924, 0x00b16c20, 0x00b1681e, 0x00b0661e, 0x00a55e16, 0x00985611, 0x00915313, 0x008c4e12, 0x00854a10, 0x0084480f, 0x0082480e, 0x00844910, 0x00854b13, 0x00854c15, 0x00854c14, 0x00884c11, 0x008d4d10, 0x00965014, 0x009c5215, 0x009d5415, 0x009d5514, 0x009f5714, 0x00a15917, 0x00a35b19, 0x00a25a18, 0x00a25b19, 0x00a35b19, 0x00a25c18, 0x009f5916, 0x009e5815, 0x009c5714, 0x00985411, 0x00945312, 0x00915010, 0x008a4c10, 0x0088480e, 0x0084460d, 0x0080430b, 0x007c3f0d, 0x00793c10, 0x00753e14, 0x006e3c15, 0x00693b16, 0x00653b17, 0x00643816, 0x00603514, 0x005d3411, 0x005c3311, 0x005c3311, 0x005c3210, 0x005a3111, 0x004e280f, 0x003d1a04, 0x00401a05, 0x005a301a, 0x00663512, 0x006c360b, 0x006d3608, 0x006c360d, 0x0070360d, 0x007e4012, 0x0081481b, 0x00663814, 0x002b1604, 0x00121510, 0x000b1412, 0x00081414, 0x00081412, 0x00081411, 0x000b1410, 0x00081410, 0x00071410, 0x00081210, 0x0008110f, 0x0008110f, 0x0007100e, 0x0008120f, 0x0007110f, 0x0005100c, 0x00040f0b, 0x0007110c, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x00050f0a, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040e0a, 0x00040e09, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f09, 0x00050f09, 0x00060f09, 0x00050e08, 0x00050e08, 0x00040f08, 0x00040f07, 0x00040f07, 0x00040f07, 0x00040f07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00040f07, 0x00040f07, 0x00040f07, 0x00040f07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f09, 0x00060e08, 0x00040d07, 0x00040d06, 0x00040d08, 0x00040d08, 0x00040d06, 0x00050c06, 0x00050d05, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00040d05, 0x00040e06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250b, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x00393b0c, 0x003c3e0c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004c4d0f, 0x006c6011, 0x00caa116, 0x00cba216, 0x00c69f16, 0x00c6a016, 0x00c6a017, 0x00c5a018, 0x00c5a018, 0x00c5a018, 0x00c5a018, 0x00c5a018, 0x00c5a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c49f18, 0x00c49f19, 0x00c49f19, 0x00c39f18, 0x00c39f18, 0x00c3a018, 0x00c3a018, 0x00c29f18, 0x00c29e18, 0x00c29e18, 0x00c29e18, 0x00bc9b18, 0x009e8716, 0x00696614, 0x00636414, 0x00626312, 0x00616112, 0x00606013, 0x00606013, 0x005e5f12, 0x005c5c11, 0x005c5b12, 0x00b49315, 0x00cca316, 0x00ae8d14, 0x004c4d10, 0x004c4d0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003c3e0c, 0x00393b0c, 0x0034350c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0024250b, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00070f0a, 0x00050d09, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x000b110b, 0x001b2219, 0x00212219, 0x00302c28, 0x006e625d, 0x00735a4b, 0x00835847, 0x00805032, 0x00744824, 0x00644023, 0x004a3428, 0x00443b3c, 0x005c585c, 0x00646068, 0x006b6369, 0x006e6169, 0x00706065, 0x00725d5f, 0x00745b59, 0x00785953, 0x007b584c, 0x007c5443, 0x007c513a, 0x00804f32, 0x00844e29, 0x00884f25, 0x008d5124, 0x008f5220, 0x0090531c, 0x0096571c, 0x00995819, 0x009c5919, 0x00a05c1a, 0x00a15d18, 0x00a05c15, 0x00a05c16, 0x00a15c18, 0x00a15c18, 0x009e5915, 0x009e5915, 0x009e5717, 0x00995415, 0x00945315, 0x00905014, 0x008d501a, 0x008b5023, 0x008d5634, 0x008d593f, 0x008b5c47, 0x00895c4c, 0x008b6051, 0x008d6354, 0x00916352, 0x00935f47, 0x00985e34, 0x00a66228, 0x00af6823, 0x00b26c1f, 0x00b46b1e, 0x00b0661a, 0x00a86114, 0x009c580f, 0x00955614, 0x008d4f11, 0x0086480e, 0x0082440d, 0x0080440c, 0x007f430c, 0x007c430c, 0x007a430c, 0x0079420c, 0x007e440c, 0x00854810, 0x008c4b14, 0x00914e15, 0x00955012, 0x00975310, 0x009b5514, 0x009d5618, 0x009e5718, 0x00a0581a, 0x00a35c1b, 0x00a45c1b, 0x00a35c1b, 0x00a05818, 0x009f5817, 0x009b5514, 0x00985412, 0x00945111, 0x008f4f0e, 0x00894a0f, 0x00884810, 0x0082430d, 0x007d400d, 0x00793f10, 0x00743c10, 0x00733f15, 0x006c3c18, 0x00683c17, 0x00653916, 0x00623714, 0x005e3414, 0x005c3211, 0x005c3311, 0x005c3110, 0x005a3010, 0x00583011, 0x004f280e, 0x00401b01, 0x00471e07, 0x005b2e17, 0x00653110, 0x00683208, 0x00683108, 0x006b3410, 0x00713711, 0x007a3c11, 0x007c451d, 0x005a3114, 0x00231206, 0x00101412, 0x00091514, 0x00081414, 0x00081414, 0x00081410, 0x000a120f, 0x0007130e, 0x0005130f, 0x0007120e, 0x0007110d, 0x0007110d, 0x0007110d, 0x0008110e, 0x0006100c, 0x0006100b, 0x00051009, 0x0007110b, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040d07, 0x00040d06, 0x00040c08, 0x00040c09, 0x00040d08, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0020230a, 0x00292b0b, 0x002c2d0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0048490f, 0x004c4d0f, 0x00535110, 0x009f8414, 0x00caa216, 0x00cba216, 0x00cba317, 0x00cba317, 0x00cba417, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cba419, 0x00a88d16, 0x00656414, 0x00626313, 0x00616112, 0x00616112, 0x00606012, 0x005e5f13, 0x005d5e11, 0x005c5c12, 0x00a78a14, 0x00cca316, 0x00b08f14, 0x004c4d10, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d06, 0x00040d06, 0x00040d06, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00070f0a, 0x00050d09, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00060e0a, 0x00060e09, 0x00070f08, 0x00111911, 0x001f211a, 0x00282823, 0x0068605b, 0x007d685e, 0x00846052, 0x007e5136, 0x007c4f28, 0x006e4624, 0x00503322, 0x00463835, 0x005c5559, 0x00645f68, 0x00696169, 0x006c6068, 0x006f6065, 0x00715e61, 0x00725c5b, 0x00745954, 0x0078584d, 0x007b5545, 0x007c523c, 0x007e4f34, 0x00814e2b, 0x00875027, 0x008c5226, 0x008e5322, 0x0090531f, 0x0096571f, 0x0098581c, 0x009b5718, 0x009e5a1b, 0x00a15e1b, 0x00a05c18, 0x00a05c16, 0x00a05c17, 0x00a15c18, 0x009d5814, 0x009d5816, 0x00985415, 0x00945214, 0x00904f14, 0x008b4c12, 0x00894e17, 0x00874d1f, 0x0085502c, 0x00845337, 0x00845641, 0x00855a4c, 0x00885f54, 0x008c6355, 0x00926657, 0x00926148, 0x00975e34, 0x00a56429, 0x00b06a25, 0x00b26c1f, 0x00b46a1c, 0x00b1661a, 0x00a85f14, 0x00a15b12, 0x00985613, 0x00904f11, 0x0088470d, 0x0081410b, 0x007e3f0a, 0x007b3c08, 0x00773c08, 0x00743c08, 0x00733c09, 0x00743c0a, 0x00773f0c, 0x007f4513, 0x00874a15, 0x008c4c12, 0x00904e10, 0x00945011, 0x00985216, 0x00995418, 0x00985315, 0x009c5819, 0x009f5818, 0x00a05818, 0x00a05819, 0x009e5718, 0x00995414, 0x00955212, 0x00905011, 0x008b4c0d, 0x0088490f, 0x00864610, 0x00804410, 0x007e4210, 0x00763d0e, 0x00703b0e, 0x00703e14, 0x006b3d17, 0x00663b15, 0x00633814, 0x00603513, 0x005c3311, 0x005c3211, 0x005d3412, 0x005b3010, 0x00582f0f, 0x00562f10, 0x004e290c, 0x00401c00, 0x0050280e, 0x005c3017, 0x0064300f, 0x00673109, 0x006a3309, 0x006b3410, 0x00733812, 0x00783c11, 0x0074411c, 0x004a290f, 0x00170d05, 0x000e1412, 0x00091413, 0x00071413, 0x00071413, 0x00081410, 0x0009120e, 0x0007130c, 0x0005130e, 0x0006110d, 0x0006100c, 0x0007100d, 0x0007100d, 0x00040e0b, 0x00040d0a, 0x0005100b, 0x0008110b, 0x00050f09, 0x0005100a, 0x0005100a, 0x00050f0a, 0x00050f0a, 0x00050f0a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e0a, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040d07, 0x00040d06, 0x00040d06, 0x00040d08, 0x00040d06, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c06, 0x00060c06, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0048490e, 0x004b4c0f, 0x004d4e0f, 0x00585410, 0x008b7612, 0x00957d13, 0x00967e13, 0x00978014, 0x00978014, 0x00988114, 0x00988214, 0x00998215, 0x009a8314, 0x009a8315, 0x009a8315, 0x009b8415, 0x009b8415, 0x009b8415, 0x009c8416, 0x009c8416, 0x009c8515, 0x009c8515, 0x009c8615, 0x009c8615, 0x009d8515, 0x009e8615, 0x009e8616, 0x009e8716, 0x009e8716, 0x009f8816, 0x009f8816, 0x009f8816, 0x009f8815, 0x00a08816, 0x00a08916, 0x00ba9918, 0x00cca519, 0x00c8a318, 0x00756c14, 0x00636414, 0x00626312, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5e11, 0x005c5c11, 0x00a08514, 0x00cca316, 0x00b09014, 0x004d4e10, 0x004f5010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x001d2009, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00060e08, 0x00060f06, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00070f0a, 0x00050d09, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e08, 0x000b130b, 0x00181d17, 0x00242720, 0x005a544f, 0x00816e6c, 0x007d5e59, 0x00785038, 0x007a4e28, 0x00784a25, 0x005f3c25, 0x0045332a, 0x00554c4e, 0x00645e68, 0x00676069, 0x006b6068, 0x006c5f65, 0x00705d60, 0x00705a58, 0x00725854, 0x0075584e, 0x00795747, 0x007a543f, 0x007c5036, 0x00804f2c, 0x00855128, 0x008a5329, 0x008d5425, 0x00905321, 0x0094561f, 0x0097561c, 0x009b591c, 0x009e5a1c, 0x009e5a1b, 0x009e5b18, 0x009c5814, 0x009d5814, 0x009e5915, 0x009b5612, 0x00985411, 0x00945214, 0x00904f14, 0x008a4c12, 0x0083460e, 0x00804711, 0x0080491a, 0x007c4924, 0x007e4e32, 0x007c4f3c, 0x007b5045, 0x0080584f, 0x00886055, 0x00906758, 0x0093644a, 0x00965f35, 0x00a6672c, 0x00b36e28, 0x00b26c20, 0x00b36a1c, 0x00b4671b, 0x00ac6117, 0x00a45c12, 0x009a5410, 0x00944f10, 0x0088450c, 0x00803f09, 0x007c3b08, 0x007c3c09, 0x007a3d0b, 0x00703607, 0x00693304, 0x00673204, 0x00673508, 0x006e3b0e, 0x00764010, 0x007e440f, 0x00884a10, 0x008f4d11, 0x00925014, 0x00945016, 0x00985418, 0x009a561b, 0x009c5818, 0x009c5818, 0x009b5518, 0x00985315, 0x00945011, 0x00904f10, 0x008c4d0f, 0x00894c0e, 0x00864810, 0x00834510, 0x007f4410, 0x007c4210, 0x00753f10, 0x00703c11, 0x006e3d14, 0x006a3d17, 0x00653a14, 0x00623713, 0x00603413, 0x005d3412, 0x005e3413, 0x005d3412, 0x005b3010, 0x00572e0d, 0x00552f0e, 0x004f2a0b, 0x00482102, 0x00572e10, 0x00613618, 0x00673411, 0x006c360e, 0x006f370e, 0x006e3813, 0x00713812, 0x00743c11, 0x00673a15, 0x00371d05, 0x00140e06, 0x000d1411, 0x00081412, 0x00051312, 0x00051312, 0x0008120f, 0x0009110d, 0x0007110c, 0x0006110d, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00040d0a, 0x0005100a, 0x0007110a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040d07, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d05, 0x00040e04, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c05, 0x00060c05, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c09, 0x00191c09, 0x001d2008, 0x0024250b, 0x0024250b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x0036370c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x00505010, 0x00525310, 0x00535411, 0x00555610, 0x00565711, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d13, 0x005d5e13, 0x005d5e13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606012, 0x00606012, 0x00606012, 0x00606013, 0x00606012, 0x00606012, 0x00616114, 0x00616114, 0x00616114, 0x00626314, 0x00626314, 0x00626314, 0x00636414, 0x00636414, 0x00736c14, 0x00c7a218, 0x00cca519, 0x00796f14, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x00606013, 0x005e5f12, 0x005c5c11, 0x00a08514, 0x00cca316, 0x00b09014, 0x004d4e10, 0x004f5010, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0036370c, 0x0034350c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e08, 0x00060f05, 0x00040e04, 0x00040e04, 0x00040e04, 0x00050d06, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d09, 0x00080e0a, 0x00060c08, 0x00080e0a, 0x00070c09, 0x00070c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060e0a, 0x00060e08, 0x00081008, 0x0010140e, 0x00242720, 0x004c4542, 0x00806e70, 0x007c5f5d, 0x00744f3c, 0x00774a28, 0x00794a26, 0x0069442c, 0x004e362d, 0x00514444, 0x00605860, 0x00666069, 0x006c6168, 0x006a5c62, 0x006e5c5e, 0x006c5859, 0x00705955, 0x0073584f, 0x0077584a, 0x00795644, 0x007a5139, 0x007e5030, 0x0083522c, 0x0088542b, 0x008c5427, 0x008e5523, 0x0090541f, 0x0093551c, 0x00965519, 0x00985418, 0x00985414, 0x00995413, 0x009c5715, 0x009c5615, 0x00995412, 0x00985411, 0x0092500e, 0x008c4c0f, 0x00884910, 0x0082450d, 0x007c400b, 0x00773e0b, 0x00723c0e, 0x006e3c16, 0x00784628, 0x00784934, 0x00784c3c, 0x007c5147, 0x00835a50, 0x008e6758, 0x0092674e, 0x00946038, 0x00a3662c, 0x00b06e27, 0x00b36d20, 0x00b3691c, 0x00b7691d, 0x00b06418, 0x00a45b12, 0x009c5410, 0x00954e11, 0x0089450c, 0x007d3b05, 0x007f3f08, 0x00925019, 0x0090501b, 0x008f501e, 0x00763b0d, 0x005f2800, 0x005f2e07, 0x0066360f, 0x006d3a11, 0x00733d0f, 0x007b400e, 0x0082450f, 0x00894a12, 0x008d4c14, 0x00904e14, 0x00945016, 0x00945214, 0x00945114, 0x00925013, 0x00914f11, 0x00915012, 0x008f4f11, 0x00884b0f, 0x00874b0f, 0x00834710, 0x0080440f, 0x007a400f, 0x00794110, 0x00743f12, 0x00703d12, 0x006c3d14, 0x006a3c16, 0x00653a14, 0x00623713, 0x00603513, 0x005d3412, 0x005e3413, 0x005f3414, 0x005b3110, 0x00552d0c, 0x00542e0d, 0x00502b0a, 0x004e2707, 0x005c3111, 0x00673a19, 0x006d3815, 0x00713914, 0x00733a11, 0x00743b14, 0x00753c14, 0x00703c12, 0x0056300f, 0x00231100, 0x0011100a, 0x000c1411, 0x00081410, 0x00051312, 0x00071210, 0x0008120f, 0x0008110d, 0x0007110c, 0x0006110d, 0x00050f0d, 0x00050f0c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00040e0b, 0x00040e09, 0x00051008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d09, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e09, 0x00060e09, 0x00060e08, 0x00050e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040e05, 0x00040e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060d06, 0x00060c05, 0x00060c05, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x002c2d0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x004f5010, 0x00515110, 0x00545510, 0x00565711, 0x00585810, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00686514, 0x00c6a219, 0x00cca519, 0x00796f14, 0x00636414, 0x00636414, 0x00626312, 0x00606013, 0x00606013, 0x005d5e12, 0x005c5c11, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d0f, 0x0048490f, 0x0044450e, 0x0040400d, 0x003b3c0c, 0x0038380c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0020230a, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x000c100b, 0x00161812, 0x003a3632, 0x00776868, 0x007b625f, 0x00714f3d, 0x00734829, 0x00764828, 0x00684130, 0x00593e36, 0x0052403f, 0x005d5359, 0x00645c64, 0x00685d64, 0x00695c62, 0x006c5a5c, 0x006c5858, 0x006e5855, 0x00705750, 0x0074584c, 0x00775849, 0x0079523d, 0x007d5137, 0x00805232, 0x0085542e, 0x00885429, 0x008a5424, 0x008c5420, 0x00905520, 0x0094561c, 0x0097561a, 0x00985517, 0x00995414, 0x00995414, 0x00985313, 0x00965214, 0x00905010, 0x008a4c0d, 0x0083480c, 0x007d440c, 0x0078400b, 0x00763e0f, 0x0070380a, 0x006d370c, 0x0075421c, 0x00895633, 0x008c5834, 0x008b5838, 0x0083543d, 0x00855a49, 0x008f6655, 0x00926852, 0x0094603e, 0x00a0632c, 0x00ad6b24, 0x00b46c20, 0x00b3681c, 0x00b4651a, 0x00b26519, 0x00a85d14, 0x009e5512, 0x00964e10, 0x008b440c, 0x0084410b, 0x008b4c12, 0x0098551c, 0x009c531a, 0x009d5418, 0x00904c15, 0x0071370b, 0x00572200, 0x00582507, 0x00613011, 0x00693612, 0x00703e14, 0x00794414, 0x00804812, 0x00844812, 0x00894b14, 0x008d4e14, 0x00904f15, 0x00904f15, 0x008e4f14, 0x008e4f13, 0x008f5014, 0x00884a0e, 0x0086480f, 0x0084460d, 0x007e430e, 0x0079400c, 0x00753d0b, 0x00723e0e, 0x00703f11, 0x006c3c10, 0x006c3c14, 0x006a3c16, 0x00663914, 0x00623713, 0x00603513, 0x005d3412, 0x00603514, 0x00603414, 0x005b3011, 0x00542c0c, 0x00542d0c, 0x00512a0c, 0x00502709, 0x005c3010, 0x006c3b19, 0x00703b15, 0x00733c14, 0x00743c11, 0x00753d10, 0x00744014, 0x00683c17, 0x003a2008, 0x00150d04, 0x000c100e, 0x00081410, 0x00081410, 0x0007130f, 0x0007130f, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100d, 0x00070e0f, 0x00070e0f, 0x00070e0d, 0x00070e0c, 0x00070e0d, 0x00070e0c, 0x00060e09, 0x00060e08, 0x00040e09, 0x00030f09, 0x0004100a, 0x00040f09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x00393b0d, 0x003c3e0c, 0x0041420e, 0x0044450d, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00515110, 0x00535410, 0x00555611, 0x00585810, 0x00585911, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca519, 0x00796f14, 0x00646414, 0x00626314, 0x00626312, 0x00616112, 0x00606012, 0x005d5e12, 0x005c5c11, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d0f, 0x00484910, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d09, 0x00080c08, 0x000a0e07, 0x002c2b26, 0x00736666, 0x007b625c, 0x00714f3c, 0x00734829, 0x00754828, 0x006d4632, 0x00604038, 0x00503936, 0x0056484c, 0x0060585e, 0x00655b62, 0x00685a60, 0x0068585a, 0x006a5656, 0x006a5654, 0x006c5650, 0x0071564d, 0x00745748, 0x00795441, 0x007c523b, 0x00805335, 0x00835430, 0x0085522b, 0x00865125, 0x00875020, 0x008c5420, 0x0090541c, 0x00915418, 0x00925214, 0x00925010, 0x00945011, 0x00935012, 0x00915014, 0x00894c10, 0x0082470e, 0x0078420b, 0x00733d09, 0x006c3607, 0x006c370b, 0x00683309, 0x007f4a20, 0x008e5830, 0x00945f36, 0x00945c30, 0x00945c33, 0x008f5c3a, 0x00906046, 0x00916752, 0x00966852, 0x0096603c, 0x00a0612b, 0x00aa6720, 0x00b0681c, 0x00b2661a, 0x00b4651a, 0x00b3661a, 0x00ac6016, 0x00a25815, 0x00964e11, 0x008b440c, 0x0089460f, 0x00925315, 0x009b581b, 0x009f5719, 0x00a05618, 0x00955018, 0x00854818, 0x005a2500, 0x00502001, 0x00572708, 0x0060300f, 0x00683812, 0x006e3c10, 0x00723d0b, 0x0078400d, 0x007f4410, 0x00834710, 0x00884810, 0x00884811, 0x008a4b13, 0x008a4c12, 0x00884a10, 0x0082440b, 0x0082440d, 0x007f410c, 0x00783f0b, 0x00733c09, 0x00733d0c, 0x00713f0f, 0x006f3e12, 0x006a3c10, 0x006a3c14, 0x00693c16, 0x00663914, 0x00633713, 0x00603513, 0x005c3311, 0x005e3413, 0x005e3113, 0x005a3010, 0x00542c0d, 0x00512b0c, 0x0050290a, 0x00502809, 0x005b3010, 0x006a3b19, 0x006f3d14, 0x00703d11, 0x006e3c0f, 0x006c3d0e, 0x006c3c13, 0x00532c0d, 0x00251000, 0x00100e06, 0x000b1310, 0x00081410, 0x0006120e, 0x0007130f, 0x0007130f, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x00070e0e, 0x00070e0d, 0x00070e0c, 0x00070f0a, 0x00070e0c, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00030c08, 0x0005100a, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0c, 0x0040400d, 0x0044450e, 0x0048490f, 0x004b4c0f, 0x004d4e10, 0x00505010, 0x00535410, 0x00545510, 0x00565710, 0x00585911, 0x00595a12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x00797014, 0x00636414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004f5010, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450d, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00141809, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e06, 0x00262521, 0x00736968, 0x00786058, 0x00704e39, 0x00744827, 0x00774925, 0x00724a33, 0x0067453b, 0x00503631, 0x00524244, 0x005f5659, 0x00645c61, 0x00685c61, 0x0069585b, 0x006b5858, 0x00695758, 0x006c5753, 0x006f584f, 0x0072584a, 0x00795444, 0x007d5440, 0x007f533a, 0x00825434, 0x0083522e, 0x00834f26, 0x00855024, 0x00885120, 0x008a511c, 0x008b5118, 0x008d5015, 0x008f4f12, 0x00905010, 0x008e4f10, 0x00884a0f, 0x0080450e, 0x0077400b, 0x00703c08, 0x00673305, 0x00623005, 0x005d2b04, 0x00713f18, 0x008b5730, 0x00935c33, 0x00986034, 0x009d602f, 0x009d6030, 0x009a613a, 0x00996444, 0x00996b53, 0x00976850, 0x00965e38, 0x00a26028, 0x00ac6820, 0x00ae671a, 0x00b06518, 0x00b06216, 0x00ae6115, 0x00a75c13, 0x00a25814, 0x00954d0f, 0x008c470c, 0x008c490d, 0x00945415, 0x009a5515, 0x009c5414, 0x009c5411, 0x00944f14, 0x00864817, 0x00643007, 0x00592c09, 0x00532508, 0x00562809, 0x005f3010, 0x00653710, 0x006c3c0d, 0x006f3c0c, 0x00743f0d, 0x007b4210, 0x00824510, 0x00844812, 0x00864913, 0x00854811, 0x0083450d, 0x0081430c, 0x0080410e, 0x007d3f0d, 0x00773f0e, 0x00713d0d, 0x006f3c0d, 0x006c3c10, 0x006b3c11, 0x006a3d12, 0x00683c14, 0x00673a14, 0x00643813, 0x00613613, 0x005f3411, 0x005c3311, 0x005a3010, 0x005a2d10, 0x00582e10, 0x00522b0c, 0x004d280b, 0x004c2809, 0x004c2808, 0x00562d0d, 0x00633714, 0x006b3b10, 0x006b3b10, 0x006a3e14, 0x00643c12, 0x00603615, 0x0044200a, 0x001d0c00, 0x000c0e08, 0x00081310, 0x0006110d, 0x0006110d, 0x0006110d, 0x0005100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00060d0c, 0x00060d0b, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00050c08, 0x00060c08, 0x00060c08, 0x00070d09, 0x00070d09, 0x00060c08, 0x00080f0b, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060d09, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004d4e0f, 0x00515110, 0x00525310, 0x00545511, 0x00565710, 0x00585910, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x00797014, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00031008, 0x00031008, 0x00031008, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f06, 0x0023241f, 0x00706665, 0x00745d55, 0x006e4c35, 0x00734825, 0x00764924, 0x00784c34, 0x00684638, 0x004c3129, 0x004d3d3c, 0x005b5154, 0x00625a5c, 0x00675b5f, 0x0068595b, 0x006b5859, 0x00685858, 0x006a5754, 0x006c554f, 0x006e544a, 0x00745345, 0x00795140, 0x007c503c, 0x007f5136, 0x00815130, 0x0081502a, 0x00814e23, 0x00864e20, 0x00874e1c, 0x00884e18, 0x00884e15, 0x00894d14, 0x008b4d11, 0x00874b0c, 0x0080470d, 0x00773f0c, 0x00703b0c, 0x0068380b, 0x00603006, 0x00542600, 0x00562703, 0x007b4b27, 0x00905f38, 0x00956035, 0x009c6338, 0x00a36132, 0x00a06234, 0x009e643e, 0x009d6748, 0x009c6c53, 0x0099684e, 0x00965c34, 0x00a05e24, 0x00aa651c, 0x00ac6418, 0x00ae6316, 0x00ac5e13, 0x00a6590d, 0x00a3580f, 0x009e5510, 0x00934c0c, 0x00904a0d, 0x008c4b0d, 0x00945414, 0x009a5613, 0x009c5412, 0x0098520d, 0x00904d0f, 0x007f430e, 0x006b370b, 0x005c2f0b, 0x00592e0d, 0x00572b0c, 0x00542809, 0x005c300c, 0x0065370d, 0x006b3b10, 0x006d3a0c, 0x00743f0f, 0x007c420e, 0x007e4410, 0x00804410, 0x0080440e, 0x0080430e, 0x007e420c, 0x007c3e0c, 0x00783c0b, 0x00753f10, 0x00703d0f, 0x006e3c0d, 0x006c3c10, 0x006a3d12, 0x00683e13, 0x00673c14, 0x00643913, 0x00613611, 0x00603512, 0x005e3412, 0x005c3212, 0x00572c0e, 0x00562b0e, 0x00562c0f, 0x00502b0b, 0x004c280a, 0x004c290b, 0x004c2808, 0x00522b0b, 0x00603412, 0x00623610, 0x00613612, 0x005c3514, 0x004f2c0c, 0x004f2a11, 0x00442613, 0x001c1002, 0x000b100a, 0x0007130f, 0x0007110d, 0x0007110d, 0x0007110d, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00060d0b, 0x00060e09, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e06, 0x00060f05, 0x00060e08, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00050c08, 0x00060c08, 0x00060c08, 0x00070d09, 0x00070d09, 0x00080c08, 0x000a0e0b, 0x00080c09, 0x00080c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004c4d0f, 0x00515110, 0x00525310, 0x00545511, 0x00565710, 0x00585910, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00626312, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x00797014, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00050e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x0008100b, 0x00060e0a, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100b, 0x0005110b, 0x0004100a, 0x0004100a, 0x00051009, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00050f06, 0x0010120c, 0x00564d4c, 0x006e5b53, 0x006c4c37, 0x00724828, 0x00784827, 0x00754a2d, 0x006c4833, 0x00573e31, 0x0050423e, 0x0058514f, 0x00605a5a, 0x00655c5d, 0x00695b5c, 0x00695858, 0x00685857, 0x00685553, 0x006a544f, 0x006c544c, 0x00715246, 0x00755143, 0x0078503e, 0x007a503b, 0x007e5134, 0x0080512e, 0x00835028, 0x00874e24, 0x00884c1d, 0x00884a18, 0x00894b18, 0x00884b18, 0x00844911, 0x007c450c, 0x0076400b, 0x006d3b09, 0x0066370b, 0x005e340e, 0x00542b05, 0x00542804, 0x005c300e, 0x00805230, 0x0094633e, 0x0095623b, 0x009a643b, 0x009d603b, 0x009c603e, 0x00996446, 0x00986850, 0x009b6c56, 0x00976447, 0x00955d30, 0x009b5b1f, 0x00a15b15, 0x00a55c13, 0x00a75c11, 0x00a4580e, 0x00a0560a, 0x009e540b, 0x0099520b, 0x00904a08, 0x008e4a0c, 0x008e4c10, 0x00915112, 0x00945412, 0x0091500d, 0x008e4c0b, 0x0088480e, 0x00783f0c, 0x00683409, 0x0063340f, 0x00623514, 0x005f3110, 0x00562908, 0x00582c0a, 0x005b300d, 0x00633610, 0x0068390d, 0x006b3b0c, 0x00703c0c, 0x00743d0c, 0x00763e0b, 0x00783e0c, 0x00773d0b, 0x00783d0c, 0x00773c0c, 0x00763c0c, 0x00733e10, 0x00703c10, 0x006c3b0e, 0x006a3c0e, 0x00693c15, 0x00673c16, 0x00663b14, 0x00633812, 0x00603613, 0x005e3412, 0x005c3313, 0x00562f10, 0x00532b0c, 0x00512a0c, 0x00532c0d, 0x00502b0d, 0x004d280b, 0x004d280e, 0x00472107, 0x004d270c, 0x00563014, 0x00583317, 0x00532f15, 0x0047260e, 0x003c1c06, 0x00442814, 0x003f2b17, 0x00251f0d, 0x000b1202, 0x00081409, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00090d0a, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00090d0a, 0x00090d0a, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00070c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004d4e0f, 0x00515110, 0x00525310, 0x00545511, 0x00565710, 0x00585910, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x00797014, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00616112, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00060e09, 0x0008100b, 0x0008100c, 0x0008100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005110b, 0x0005110b, 0x0004100a, 0x0004100a, 0x00041009, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00051008, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00041006, 0x00010800, 0x002e2927, 0x00645750, 0x006a523e, 0x00734f32, 0x00754c30, 0x0072492f, 0x00694530, 0x00533b2c, 0x00463832, 0x00544d4a, 0x005a5452, 0x00605756, 0x0068595b, 0x006b5b5b, 0x00665656, 0x00685453, 0x006a5450, 0x006c544c, 0x00705246, 0x00745042, 0x0076503c, 0x00784f39, 0x007a4e33, 0x007d4f2d, 0x00824e29, 0x00854e25, 0x00864c1f, 0x00854a1a, 0x00844918, 0x00804614, 0x007b440e, 0x00713d08, 0x006b3a07, 0x00673708, 0x005c3108, 0x00542b05, 0x00542a05, 0x005a2f0a, 0x00623614, 0x007f5034, 0x00906246, 0x00966548, 0x00946244, 0x00966044, 0x00956047, 0x0094624c, 0x00946452, 0x00936450, 0x008d5c3f, 0x008c5529, 0x0092541b, 0x00985412, 0x009c5410, 0x009e540f, 0x009e540e, 0x0098520c, 0x00945009, 0x008f4c09, 0x00894808, 0x0086480c, 0x00874b11, 0x008b4f14, 0x00884b10, 0x0084470c, 0x0080440d, 0x007b400e, 0x0070390c, 0x00643108, 0x0063320c, 0x006b3c18, 0x00643411, 0x00643410, 0x00552704, 0x00562a04, 0x005c3109, 0x00603409, 0x00643709, 0x0068390b, 0x006c3a0c, 0x00703b0b, 0x00703a0a, 0x00713c0c, 0x00713b0c, 0x00733d0e, 0x00743d0e, 0x00713d12, 0x006e3c10, 0x006c3c10, 0x00693c10, 0x00683c15, 0x00673c17, 0x00653a14, 0x00613712, 0x005f3511, 0x005d3512, 0x00593112, 0x00562f10, 0x00532c0f, 0x004e290b, 0x004c2709, 0x004c2609, 0x00482308, 0x004b230c, 0x00421c06, 0x0046220e, 0x00452611, 0x003e200e, 0x00381e0c, 0x002f1808, 0x00291405, 0x00352413, 0x00362919, 0x00282416, 0x0010150b, 0x00071008, 0x00060e09, 0x0009110d, 0x0008100c, 0x0008100b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00080e0a, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00070d09, 0x00070d09, 0x00080e0a, 0x00080e0a, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0041420d, 0x0044450e, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00505010, 0x00535410, 0x00555611, 0x00585810, 0x00585911, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f12, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x007a7014, 0x00646414, 0x00646414, 0x00636414, 0x00616112, 0x00616112, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00031008, 0x00031008, 0x00031008, 0x00031008, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x00050f0a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120d, 0x0008130d, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006110b, 0x0007110a, 0x0008110b, 0x0008120c, 0x0008120c, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x00061009, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00051008, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00031006, 0x0008130a, 0x000b0e08, 0x003f3a31, 0x00625441, 0x00654b32, 0x006b4834, 0x006e4831, 0x00633f29, 0x00503829, 0x00453831, 0x004f4846, 0x00565150, 0x005c5453, 0x00635456, 0x0069595a, 0x00675757, 0x00675452, 0x0067514c, 0x00685148, 0x00705144, 0x00735040, 0x00754e3c, 0x00784e38, 0x00784f33, 0x007a4f2f, 0x007f4e2b, 0x00804b26, 0x007e481c, 0x007c4517, 0x007b4414, 0x00784111, 0x00713f0c, 0x00693a08, 0x00643708, 0x005e330a, 0x00562d08, 0x00542d08, 0x005c340e, 0x00643915, 0x00643817, 0x0073472b, 0x00865940, 0x008e604b, 0x00875a44, 0x00845640, 0x00885a44, 0x00885b46, 0x00865b46, 0x00875c47, 0x00845739, 0x00875329, 0x008c501c, 0x008d4c11, 0x00904c0f, 0x00914c0e, 0x00934e10, 0x0090500e, 0x008d4f0f, 0x00884c0e, 0x0083480d, 0x007c440d, 0x00794510, 0x007a4614, 0x00754110, 0x00733d10, 0x00713b14, 0x0069340d, 0x005e2c06, 0x00602f08, 0x00693710, 0x006c3813, 0x006c3913, 0x006c3913, 0x00663510, 0x00592a03, 0x00562a02, 0x00582e05, 0x005c3108, 0x0062370c, 0x0065380e, 0x0069390c, 0x006c3b0d, 0x006d3b0c, 0x006f3c0e, 0x006d3c0d, 0x006e3c0d, 0x006d3c12, 0x006c3c12, 0x00693d12, 0x00683c11, 0x00643912, 0x00643914, 0x00633814, 0x00613514, 0x005d3411, 0x00583311, 0x00552f10, 0x00512c0f, 0x00502b0d, 0x004d280c, 0x004b250a, 0x004b270c, 0x00462108, 0x004c240f, 0x00371504, 0x00291001, 0x00241203, 0x00201104, 0x00201309, 0x00221810, 0x001c130b, 0x00241c12, 0x00262014, 0x00202018, 0x00101714, 0x00060f0c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00070f0a, 0x00050d08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0036370c, 0x00393b0d, 0x003c3e0c, 0x0041420e, 0x0044450d, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00525310, 0x00535410, 0x00555611, 0x00585810, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00636413, 0x00636414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00696614, 0x00c6a218, 0x00cca619, 0x007a7014, 0x00646414, 0x00646414, 0x00636414, 0x00616112, 0x00616112, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00021008, 0x00021008, 0x00021008, 0x00021008, 0x00021009, 0x00021009, 0x00021009, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120d, 0x0008130d, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006110b, 0x0007110a, 0x0008110b, 0x0008120c, 0x0008120c, 0x0007110c, 0x0006100b, 0x0007110c, 0x0007110c, 0x00061009, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00051008, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e08, 0x00041006, 0x00041007, 0x00060e08, 0x00101208, 0x00393120, 0x0056432d, 0x005e4433, 0x0064412e, 0x005f3d28, 0x00503b2c, 0x00443933, 0x004a4440, 0x00544e4c, 0x005c5252, 0x00605354, 0x00655555, 0x00675757, 0x00675452, 0x0067514c, 0x00685148, 0x006f5042, 0x00714f3e, 0x00724c38, 0x00744b34, 0x00744c31, 0x00764c2d, 0x007a4c28, 0x007b4924, 0x0079471b, 0x00784416, 0x00744113, 0x006f3c0e, 0x006a3a0c, 0x00643808, 0x005c3308, 0x00562d08, 0x00542c09, 0x005b340f, 0x00603912, 0x00673d17, 0x00673c18, 0x006a3c1f, 0x006f4328, 0x00754c34, 0x00734b36, 0x00714a34, 0x00744e35, 0x00785138, 0x00785138, 0x007c533c, 0x007e5136, 0x00804f28, 0x00844a19, 0x00844710, 0x0086470f, 0x0088480f, 0x008a480f, 0x0087480e, 0x0080460c, 0x007b430c, 0x0074400c, 0x006e3c0c, 0x006c3c0e, 0x006c3e13, 0x00693912, 0x00623010, 0x005a290c, 0x00542405, 0x005c2c0a, 0x00683611, 0x00703c13, 0x00703c12, 0x00713c14, 0x00703b13, 0x006c3810, 0x0064340b, 0x00582c04, 0x00542903, 0x00572f08, 0x005b320c, 0x00603710, 0x0064380f, 0x0068390e, 0x00693b0c, 0x006a3c0e, 0x006a3c0d, 0x006a3c0e, 0x00693b11, 0x00683c13, 0x00673c13, 0x00643b12, 0x00613810, 0x00623812, 0x00613614, 0x00603412, 0x005b3210, 0x0056300f, 0x00583113, 0x00532e10, 0x004c280c, 0x004d280c, 0x004b250c, 0x0048240a, 0x00422007, 0x00452310, 0x002c1404, 0x00120700, 0x00121002, 0x00151105, 0x001a150c, 0x001b1911, 0x00181710, 0x0019170f, 0x001c1b14, 0x00191c18, 0x000f1314, 0x00070f0d, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00050d09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040d07, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00050c08, 0x00050c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0024250b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x004f5010, 0x00525310, 0x00555611, 0x00565710, 0x00585911, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00696614, 0x00c6a218, 0x00cca619, 0x007a7014, 0x00646514, 0x00646414, 0x00636414, 0x00626312, 0x00606012, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x00494a10, 0x0045470e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006110c, 0x0005110b, 0x0006120c, 0x0007130d, 0x0006100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00040f08, 0x00040f08, 0x00060e08, 0x000b1008, 0x000c0d03, 0x001f1c0f, 0x00302c1c, 0x00413224, 0x00463426, 0x003d2f24, 0x00403630, 0x00423b38, 0x004e4845, 0x00584f4d, 0x00605452, 0x00645454, 0x00645454, 0x00675653, 0x0064504b, 0x00665048, 0x006c4f40, 0x00704f3e, 0x00704c37, 0x00704932, 0x00714a2f, 0x00714828, 0x00704320, 0x0070421c, 0x00734216, 0x00714012, 0x006f4013, 0x00683c10, 0x0062370c, 0x005b320a, 0x00562d07, 0x00562b07, 0x005d310f, 0x00653913, 0x00693d14, 0x006c3e10, 0x006d3c0f, 0x00683714, 0x00603414, 0x0060381f, 0x005c3822, 0x005b3724, 0x00603c29, 0x00684430, 0x00714d36, 0x00754f38, 0x00774c34, 0x00784829, 0x006e3c14, 0x00764012, 0x00773f0e, 0x00783f0e, 0x00793f0d, 0x00783f0d, 0x00753e0c, 0x006e3b0e, 0x00683b13, 0x00613814, 0x00572f10, 0x004c2507, 0x00471f03, 0x00411900, 0x004a2006, 0x00582a0e, 0x00683715, 0x006e3b14, 0x00733e12, 0x00744010, 0x00753f13, 0x00763f13, 0x00713c0d, 0x006b3808, 0x0065360b, 0x005b2e09, 0x00562c0b, 0x00592f10, 0x005d3412, 0x00603511, 0x00613710, 0x0061380d, 0x0061380c, 0x00643b0c, 0x00653c0d, 0x00663c12, 0x00663b14, 0x00653a14, 0x00633913, 0x00613811, 0x00613812, 0x00613814, 0x005c3210, 0x00582f0e, 0x00583112, 0x00583114, 0x00522b0f, 0x004e260d, 0x004c260c, 0x0048240a, 0x0047230a, 0x0044230c, 0x00402414, 0x00241405, 0x00100e00, 0x000e1406, 0x0015170a, 0x001c180e, 0x001c180e, 0x0018160e, 0x0013140f, 0x00131513, 0x00151914, 0x000d120c, 0x00081009, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d0a, 0x00080d09, 0x00080d09, 0x00080d08, 0x00080d0a, 0x00080c09, 0x00080c07, 0x00080c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c09, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x00292b0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a10, 0x004d4e0f, 0x00515110, 0x00525310, 0x00565610, 0x00595a11, 0x005b5b12, 0x005c5c12, 0x005e5f11, 0x00605f11, 0x00616012, 0x00626113, 0x00626113, 0x00636213, 0x00646313, 0x00646212, 0x00646313, 0x00646413, 0x00646413, 0x00656413, 0x00666412, 0x00666412, 0x00686513, 0x00686513, 0x00686613, 0x00696614, 0x00696614, 0x006b6814, 0x006b6814, 0x006c6814, 0x006c6914, 0x006c6914, 0x006d6a14, 0x006e6b14, 0x00938115, 0x00c9a419, 0x00cca619, 0x00797014, 0x00646414, 0x00646414, 0x00636414, 0x00626312, 0x00616112, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130c, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006110c, 0x0005110b, 0x0006120c, 0x0007130d, 0x0007100c, 0x0009110d, 0x0009110d, 0x0008100c, 0x0008100c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e06, 0x00080e05, 0x000c0f05, 0x00100f04, 0x00201a10, 0x002d251a, 0x002f261e, 0x002e2823, 0x00433e38, 0x0048413c, 0x00514744, 0x00615454, 0x00605251, 0x00615050, 0x00655451, 0x00624e49, 0x00644e45, 0x00684d40, 0x006d4d3f, 0x006f4c38, 0x006e4833, 0x006f472d, 0x006d4427, 0x006c401e, 0x006c4018, 0x006d3d13, 0x006b3b0f, 0x00683a10, 0x0061350e, 0x005b330c, 0x00573009, 0x00542b06, 0x00572c07, 0x00643710, 0x006b3c14, 0x006f3f13, 0x00724010, 0x00724010, 0x00703c15, 0x00683914, 0x0054290c, 0x0048240c, 0x0042200c, 0x003f1d08, 0x003f1f0c, 0x00543420, 0x00684631, 0x006f4832, 0x006c4229, 0x00653919, 0x0064340d, 0x0066350c, 0x0068340c, 0x0068350d, 0x0068350d, 0x0064340c, 0x005f310c, 0x00593010, 0x00482206, 0x00381600, 0x00351400, 0x003c1902, 0x00432009, 0x00512a0f, 0x00603414, 0x006c3a17, 0x00733e14, 0x00774111, 0x00784310, 0x007b4413, 0x007c4212, 0x0079420e, 0x00723f0a, 0x006e3b0d, 0x00663610, 0x005b2d0b, 0x00582e0c, 0x005b310f, 0x005c330f, 0x005d340f, 0x005e350d, 0x005e350c, 0x0060370c, 0x0060380c, 0x00623910, 0x00623812, 0x00623811, 0x00603710, 0x00603710, 0x00603711, 0x005e3411, 0x00592f0d, 0x0058300f, 0x00593112, 0x00593114, 0x0052280e, 0x004d240c, 0x004c240d, 0x0047220a, 0x0046230a, 0x0044240d, 0x003b2213, 0x001f1007, 0x00100d04, 0x000d1506, 0x00121306, 0x0021180f, 0x00241a10, 0x001c180d, 0x00151510, 0x00111310, 0x00101410, 0x000b1009, 0x0009100a, 0x0005100a, 0x00040f09, 0x0005100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070c0b, 0x00070d09, 0x00070d09, 0x00070d08, 0x00080e0a, 0x00070d09, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004d4e10, 0x00706411, 0x00b79414, 0x00bd9815, 0x00be9a16, 0x00be9a16, 0x00be9b16, 0x00be9b17, 0x00bf9b18, 0x00bf9b18, 0x00bf9b18, 0x00bf9b18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00c09d18, 0x00c09d18, 0x00c09d18, 0x00c09d18, 0x00c09d18, 0x00c09d18, 0x00c09e18, 0x00c09e18, 0x00c09e18, 0x00c09e18, 0x00c09f18, 0x00c8a418, 0x00cca619, 0x00c09e18, 0x00716c14, 0x00646514, 0x00646414, 0x00636414, 0x00626313, 0x00606013, 0x00606013, 0x005d5d12, 0x00a38814, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x00484910, 0x0044450e, 0x0040400d, 0x003b3c0c, 0x0038380c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040f09, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006110c, 0x0005110b, 0x0005110b, 0x0007130c, 0x000a140f, 0x000c140f, 0x000c140f, 0x0009110d, 0x0008100b, 0x0008120d, 0x0008120d, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00060e06, 0x00080d06, 0x00090c06, 0x000d0e09, 0x0022211c, 0x00282620, 0x00282620, 0x003c3833, 0x00443c38, 0x00544948, 0x005c504f, 0x005f5050, 0x00605050, 0x0062514e, 0x00624f49, 0x00604c43, 0x0062493d, 0x0066473a, 0x006c4a39, 0x006c4733, 0x006c452d, 0x006a4326, 0x00683f1d, 0x00683d18, 0x006a3c14, 0x0066380e, 0x0061340c, 0x005c320c, 0x0058300c, 0x00542c09, 0x00562c08, 0x00603510, 0x00683b11, 0x006c3d10, 0x00714010, 0x00733f10, 0x00743f10, 0x00764014, 0x006f3d15, 0x005f3211, 0x004f290a, 0x00442108, 0x003d1f07, 0x003c200b, 0x003a1d0b, 0x00432614, 0x00533421, 0x005b3924, 0x005c381e, 0x00593114, 0x005a2e10, 0x0054290a, 0x00582f10, 0x00593010, 0x00593013, 0x004c250a, 0x003e1a00, 0x00371700, 0x00361a09, 0x00391c0a, 0x003e1e09, 0x0048240c, 0x00542c0f, 0x00643715, 0x00703e17, 0x00744014, 0x00784210, 0x0079440f, 0x007c4410, 0x007e4410, 0x007c4410, 0x0077400e, 0x00703c0d, 0x006b3910, 0x0063340d, 0x00582e0a, 0x00582c09, 0x00582e0c, 0x005a300f, 0x005c3210, 0x005e3410, 0x005d340e, 0x005d340d, 0x00603610, 0x00623912, 0x00613811, 0x005e350e, 0x005c320c, 0x005d3410, 0x00603514, 0x005b3010, 0x00572d0f, 0x00593014, 0x00583014, 0x00582f15, 0x004f260f, 0x004f2611, 0x004f2a13, 0x0043200b, 0x003c1d08, 0x002e180b, 0x00180803, 0x00130e08, 0x00111409, 0x00161305, 0x0024180e, 0x00281c10, 0x00211a0d, 0x0018150e, 0x0012120f, 0x000e120e, 0x0009100c, 0x0008100c, 0x0005100a, 0x00040f09, 0x0005100a, 0x00050f0a, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070c0b, 0x00070d09, 0x00070d09, 0x00070d08, 0x00080e0a, 0x00070d09, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x00615910, 0x00bc9815, 0x00cca316, 0x00cca316, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00c2a018, 0x008b7c14, 0x00656614, 0x00646514, 0x00646514, 0x00636414, 0x00626313, 0x00616112, 0x00606012, 0x00605f12, 0x00ac8f15, 0x00cca417, 0x00b09014, 0x004f5010, 0x00505010, 0x004c4d0f, 0x00484910, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0036370c, 0x0034350c, 0x002d2f0b, 0x00292b0a, 0x0026280b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00040e09, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006110c, 0x0005110b, 0x0006120c, 0x0008140e, 0x0008120d, 0x0009110d, 0x0009110d, 0x0008100c, 0x0009110d, 0x0008120d, 0x0008110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00031006, 0x00031008, 0x00060e08, 0x00070c0a, 0x00070c0b, 0x00101512, 0x001c201a, 0x001e1e17, 0x00343129, 0x003e3832, 0x00504542, 0x00584c4b, 0x005a4c4b, 0x005c4d4c, 0x0062504e, 0x00604d48, 0x005d4c42, 0x0060493e, 0x0064483b, 0x00694b3b, 0x00694834, 0x0066442c, 0x00664024, 0x00663e1e, 0x00673d19, 0x00663b13, 0x0061350c, 0x005c330b, 0x0058300c, 0x00542d0c, 0x00542c0d, 0x005d3410, 0x00653a12, 0x006c3e12, 0x00703e0d, 0x0074400f, 0x00774010, 0x00784010, 0x00774011, 0x00713d12, 0x00653811, 0x00562f0c, 0x0048270a, 0x00402409, 0x003b1f0a, 0x00351b0a, 0x00341c0b, 0x00361e0c, 0x00412614, 0x0050311f, 0x00502f1a, 0x00502c17, 0x004c2511, 0x004e2915, 0x00492611, 0x0040200a, 0x00361702, 0x00341400, 0x00341801, 0x00381e0c, 0x003f220c, 0x004a260f, 0x00542c10, 0x005d3311, 0x00663813, 0x006f3d12, 0x00723e0f, 0x00744009, 0x0076400a, 0x0079410c, 0x007b420c, 0x007b420e, 0x0078400d, 0x00733d0c, 0x006c3a0c, 0x0067380c, 0x005e340e, 0x00582c09, 0x00542a09, 0x00552b0c, 0x00582e0f, 0x005b3010, 0x005c3210, 0x005d3410, 0x005e350e, 0x005d340d, 0x005d340d, 0x005c330c, 0x005b320b, 0x005e3410, 0x00582d0c, 0x005c3111, 0x00542a0d, 0x00542c10, 0x00532a0f, 0x00542c11, 0x0050260f, 0x004c250e, 0x004a240e, 0x00421f0a, 0x003c1c0a, 0x00281408, 0x00140703, 0x00130d09, 0x00131308, 0x00191404, 0x0025180c, 0x002f2014, 0x002a2011, 0x001e170e, 0x00181410, 0x00101410, 0x00081210, 0x0007120d, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x006e6011, 0x00cca215, 0x00c8a016, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48815, 0x00a48915, 0x00a48915, 0x00a48916, 0x00a48916, 0x00a48916, 0x00a48916, 0x00a38a15, 0x00a38a15, 0x00a38915, 0x00a38915, 0x00a28915, 0x00a28915, 0x00a28916, 0x00a28916, 0x00a18817, 0x00a18816, 0x00a18915, 0x00a18915, 0x00a18816, 0x00a18916, 0x00a08916, 0x00a08916, 0x00a08916, 0x00a08916, 0x00a08916, 0x00a08916, 0x00988416, 0x00787114, 0x00656614, 0x00656614, 0x00656614, 0x00646514, 0x00646414, 0x00626313, 0x00626312, 0x00606012, 0x00616012, 0x00bc9916, 0x00cca417, 0x00aa8b14, 0x004f5010, 0x00505010, 0x004c4d0f, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040f0a, 0x00040f09, 0x00040e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040f09, 0x0008110c, 0x0005100a, 0x00040d08, 0x00040d08, 0x0007110c, 0x0007110c, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0007110c, 0x0005100a, 0x0008120c, 0x0008120d, 0x0007120c, 0x0006120c, 0x0007130c, 0x0008140e, 0x0007130d, 0x0007110c, 0x0009120d, 0x0008120d, 0x0007110c, 0x0009130e, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x00061009, 0x00061009, 0x00040f08, 0x00051008, 0x0007100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040e05, 0x00040e05, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00031006, 0x00060e09, 0x00060e09, 0x0006100c, 0x000c120f, 0x00161a14, 0x0021211a, 0x002e2c22, 0x00352f28, 0x00493f3b, 0x00544845, 0x005a4d4c, 0x00544644, 0x00584945, 0x005c4a45, 0x005c4a43, 0x0060483d, 0x00604538, 0x0065483a, 0x00664838, 0x0067442f, 0x00644026, 0x00633d1f, 0x00633b18, 0x00633815, 0x005e3410, 0x0058320d, 0x0054300c, 0x00542f0e, 0x005c3014, 0x00633513, 0x006b3c12, 0x00724113, 0x0076400e, 0x0077410e, 0x007a4312, 0x00793f10, 0x00783e10, 0x00713c0f, 0x00693b11, 0x00603810, 0x00523111, 0x00482a0e, 0x0040240b, 0x003f250f, 0x003a2410, 0x0035210d, 0x00331e0a, 0x0038200c, 0x00422715, 0x00442818, 0x00452617, 0x00432414, 0x003d1f10, 0x00341605, 0x00351804, 0x003c1e0a, 0x00432510, 0x00482914, 0x004d2c14, 0x00522c11, 0x00582e11, 0x00643815, 0x00683b11, 0x006d3c10, 0x00703c0c, 0x00703c09, 0x00703c08, 0x00733c09, 0x0078400c, 0x00733d0c, 0x006c3808, 0x006c390b, 0x0068360a, 0x0066360e, 0x0061340e, 0x005b2f0d, 0x00562b0e, 0x00542b10, 0x00582f14, 0x00572c10, 0x005b3011, 0x005b3010, 0x005b320c, 0x005b310c, 0x005d3410, 0x005d3410, 0x005d3410, 0x005c3411, 0x00582f0e, 0x00582f10, 0x00542b0e, 0x00532c10, 0x0050280d, 0x00512a10, 0x00502910, 0x004b250c, 0x004c2610, 0x0044200b, 0x00381c0a, 0x00231206, 0x00120902, 0x00110f07, 0x00171408, 0x001f1708, 0x002c1c0f, 0x00342412, 0x0030220d, 0x00281c0f, 0x001f1810, 0x0012140f, 0x00091110, 0x00071310, 0x0006120c, 0x0004100a, 0x00030f09, 0x00040e08, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00060d09, 0x00080c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070e08, 0x00070e08, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c07, 0x00050d07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x00494a0f, 0x004d4e0f, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005b5811, 0x00595a12, 0x005b5b11, 0x005c5d12, 0x005d5e13, 0x005e5f13, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00616113, 0x00616113, 0x00616114, 0x00616114, 0x00616114, 0x00616114, 0x00626314, 0x00626314, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00646513, 0x00656614, 0x00656614, 0x00656613, 0x00666713, 0x00666713, 0x00666713, 0x00656614, 0x00646513, 0x00646414, 0x00636414, 0x00616112, 0x00606013, 0x00786c14, 0x00c8a116, 0x00cca417, 0x00927b13, 0x00515110, 0x00505010, 0x004c4d0f, 0x0047480e, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0038380c, 0x0030310c, 0x002d2f0a, 0x0026280a, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f09, 0x00040d08, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x0006100b, 0x00040f09, 0x00040d08, 0x00040d08, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0007110c, 0x0005100a, 0x0008120c, 0x0008120d, 0x0008120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0007110c, 0x0009130e, 0x0007110c, 0x0008120d, 0x0009130e, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x00061009, 0x00061009, 0x0008110b, 0x00040f08, 0x00040c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040e05, 0x00040e05, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00050f08, 0x00040e09, 0x00080f0b, 0x000e140f, 0x001b1c16, 0x0026251c, 0x00353028, 0x0048403a, 0x004e443e, 0x00524641, 0x00544743, 0x00584945, 0x00574640, 0x0056463d, 0x005e473c, 0x0062473b, 0x005e4334, 0x00604232, 0x0063412d, 0x00633f26, 0x00633c20, 0x00623b18, 0x005e3614, 0x005a3210, 0x0058300e, 0x0057310f, 0x00593110, 0x00613416, 0x00683914, 0x006c3d12, 0x00734011, 0x00794311, 0x00784311, 0x00784110, 0x00794110, 0x00763e10, 0x00703c10, 0x006b3c12, 0x00613810, 0x00573311, 0x00502d10, 0x00462508, 0x0047290f, 0x00402710, 0x003b240f, 0x0037200b, 0x00351e0a, 0x00341c08, 0x00341b0b, 0x00361b0c, 0x00391c0c, 0x003b1c0d, 0x00371908, 0x00391c09, 0x0040210c, 0x00482812, 0x004c2b12, 0x00502c13, 0x00542c11, 0x005b2e12, 0x00653514, 0x00683811, 0x006c380d, 0x006c3a0b, 0x006d3b0a, 0x006e3c0b, 0x006f390c, 0x00733c0e, 0x006e3a0b, 0x006c3b0c, 0x0068360b, 0x00613109, 0x005d2f08, 0x005d2e0b, 0x00582c0b, 0x00572a0f, 0x00552c12, 0x00562d13, 0x00592f13, 0x005a3012, 0x005b3010, 0x005a300c, 0x00582f0c, 0x005c3310, 0x005c3311, 0x005c3412, 0x005b3311, 0x0058300f, 0x00542c0d, 0x0050280b, 0x00532c10, 0x004f280c, 0x004e260c, 0x004d250b, 0x004a260b, 0x004d2810, 0x0044200c, 0x00361c0a, 0x001a0d00, 0x00100c04, 0x000d0d04, 0x00151306, 0x0023180b, 0x002f1d11, 0x003a2412, 0x0038240c, 0x002d1d0d, 0x0022180f, 0x0015140e, 0x000c1110, 0x00081310, 0x0006120c, 0x0004100a, 0x00030f09, 0x00020e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00060d09, 0x00080c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070e08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c07, 0x00050e08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x00202309, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606012, 0x00606012, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666713, 0x00666713, 0x00666714, 0x00666714, 0x00666714, 0x00666714, 0x00666713, 0x00666713, 0x00656614, 0x00646514, 0x00636414, 0x00626312, 0x00616113, 0x00a18815, 0x00cca417, 0x00c59f16, 0x006e6412, 0x00535410, 0x00505010, 0x004c4d0f, 0x0048490e, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130e, 0x000f130f, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f0a, 0x0005100a, 0x00040f09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x0008110c, 0x0008120d, 0x0008120d, 0x0007130c, 0x0007130d, 0x0007130d, 0x0005110b, 0x0008120c, 0x0008120d, 0x0008120c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120c, 0x0008120c, 0x0008120c, 0x0008120c, 0x0008120c, 0x0007110c, 0x00061009, 0x00061009, 0x00061009, 0x00040f08, 0x00060f09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00060e08, 0x00040e07, 0x00040f08, 0x00050e08, 0x00090e09, 0x0010120e, 0x001c1c17, 0x0034322b, 0x0048433b, 0x004b423c, 0x004c413a, 0x0050443c, 0x0050413a, 0x0053423a, 0x00534439, 0x005b463a, 0x0060483a, 0x005d4434, 0x005c412f, 0x005e3e2b, 0x00603c25, 0x005f391e, 0x005e3718, 0x005a3312, 0x0058300e, 0x00572f0d, 0x0059300f, 0x005c3010, 0x00633814, 0x00693a14, 0x006a3a0e, 0x006e3c0e, 0x00744012, 0x00733e10, 0x00733e10, 0x00794416, 0x00764113, 0x006d3c0f, 0x006a3a10, 0x00643611, 0x005c3010, 0x005c3417, 0x0050290f, 0x00522c13, 0x004b2b12, 0x00482b14, 0x003f230c, 0x003c1f09, 0x003b1e0a, 0x003b1e0b, 0x00381b08, 0x003a1c0c, 0x003f200e, 0x0040210d, 0x0040200a, 0x0045250c, 0x004d2c12, 0x004f2b11, 0x00542c11, 0x00562b0e, 0x005e3010, 0x00643413, 0x00693813, 0x006c3c12, 0x006f3c11, 0x006d3c0e, 0x006c3b0d, 0x006b370c, 0x006c380d, 0x00643306, 0x00633307, 0x00613308, 0x00643811, 0x005d300b, 0x00562908, 0x00582c0c, 0x0054290b, 0x00552c10, 0x00562c10, 0x00562b10, 0x005b3012, 0x005b3010, 0x00582f0c, 0x00572d0a, 0x005a300d, 0x00582f0d, 0x0059300f, 0x0058300f, 0x00552d0e, 0x00512a0c, 0x0050280c, 0x00502a10, 0x004d280d, 0x004f290f, 0x00502b10, 0x004a270b, 0x004a240c, 0x00411e0b, 0x00331909, 0x00140c01, 0x000e0e07, 0x000c0c06, 0x00141106, 0x0024170c, 0x00321c11, 0x003d2413, 0x003d260f, 0x00311e0e, 0x0026180e, 0x0019140e, 0x0010110e, 0x000a120e, 0x0005110c, 0x0004100a, 0x0004100a, 0x00040f09, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00060d09, 0x00080c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070e08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c07, 0x00050e08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005d5b12, 0x005c5d11, 0x005c5d11, 0x00606013, 0x00606012, 0x00606012, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00666714, 0x00656614, 0x00656614, 0x00646414, 0x00626313, 0x00756c14, 0x00c49f18, 0x00cca417, 0x00a68914, 0x00585811, 0x00535410, 0x00505010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f09, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x0005100a, 0x00040e08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x0007110c, 0x0008110c, 0x0007110c, 0x0005110b, 0x0006120c, 0x0008140e, 0x0008140e, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007110c, 0x00061009, 0x00061009, 0x0007110a, 0x00040f08, 0x00040e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00050e08, 0x00040e06, 0x00040f06, 0x00050f06, 0x00060e08, 0x00080c09, 0x000e100c, 0x00282721, 0x003c3932, 0x0048433a, 0x004b4338, 0x004e4439, 0x00504238, 0x0055443c, 0x00504136, 0x00584538, 0x005c4537, 0x00594030, 0x00583e2b, 0x00593c2a, 0x005c3c28, 0x005c3920, 0x005a3618, 0x00583212, 0x0055300e, 0x00572f0d, 0x005b300e, 0x005b310c, 0x0061360d, 0x00673810, 0x006b3b10, 0x006c3c10, 0x00703d11, 0x006c390d, 0x00703f13, 0x00734114, 0x00703f11, 0x006c3b0f, 0x006b3a11, 0x006b3b17, 0x006b3c1a, 0x00653818, 0x005b3012, 0x005c3416, 0x00543016, 0x004d2c14, 0x00492811, 0x0043220c, 0x0040210b, 0x003d200b, 0x003d1f0b, 0x003e1e0b, 0x003f1e0b, 0x0041200c, 0x0044220c, 0x0048260c, 0x004f2c10, 0x00532d10, 0x00552c0f, 0x005a2d0c, 0x0060300f, 0x00683717, 0x00683614, 0x00683810, 0x006c3c12, 0x0068380d, 0x0069380d, 0x0068370e, 0x0069370e, 0x005f3007, 0x005c2f06, 0x0060320c, 0x005f3310, 0x00542806, 0x00522407, 0x0053270a, 0x0054280b, 0x00542c0e, 0x00542b0f, 0x00552a0f, 0x00592f10, 0x005c3110, 0x005c320f, 0x00592f0d, 0x005a300e, 0x00592f0e, 0x00582f0d, 0x00542c0c, 0x00542c0c, 0x00502a0c, 0x0050280e, 0x004f2810, 0x004c260c, 0x004a240b, 0x00482208, 0x00482408, 0x00462009, 0x00401b0a, 0x002b1204, 0x000f0c02, 0x00090d07, 0x000c0e08, 0x00151009, 0x0025170c, 0x00341c12, 0x003e2212, 0x00402610, 0x00372311, 0x002a1c10, 0x001e160d, 0x0014140d, 0x000b120e, 0x0006120c, 0x0004100a, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00060d09, 0x00080c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070e08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c07, 0x00050e08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005d5b12, 0x005c5c11, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00626313, 0x00636413, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00666713, 0x00656614, 0x00646414, 0x00686413, 0x00b09317, 0x00cca418, 0x00c39e17, 0x00706612, 0x00565711, 0x00535410, 0x00505010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d08, 0x00070f0a, 0x00040d08, 0x00050e09, 0x00050e09, 0x00040f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050e08, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f0a, 0x00060f0a, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050f09, 0x00050e09, 0x00060d09, 0x00070e09, 0x00060d08, 0x00050c08, 0x00040c08, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100b, 0x0005100b, 0x0005100a, 0x0006100b, 0x0007120c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008110c, 0x0008110c, 0x0008110c, 0x0008110c, 0x0008120d, 0x0008110c, 0x0007110c, 0x0007100c, 0x0006100b, 0x0006110b, 0x00051009, 0x00051009, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00040e07, 0x00040f06, 0x00050e06, 0x00070e08, 0x00060c08, 0x00080d09, 0x001f1f1b, 0x0038352f, 0x00474339, 0x00484136, 0x004c4238, 0x0051433a, 0x0058483f, 0x00504034, 0x00564438, 0x00594334, 0x00543c2c, 0x004f3623, 0x00573d29, 0x005b3f2a, 0x00593b21, 0x0058361a, 0x00543313, 0x0054300e, 0x00542d0a, 0x005c330f, 0x005c320b, 0x0060360c, 0x0063360d, 0x0064350c, 0x00693a11, 0x00683910, 0x0066380e, 0x006c3b12, 0x006e3c14, 0x006b3b10, 0x006b3b10, 0x0067380f, 0x00683812, 0x006d3f1a, 0x00633611, 0x005f330f, 0x00603514, 0x005a3315, 0x00522c11, 0x00512a14, 0x0048240e, 0x0043200b, 0x0043230c, 0x0042230c, 0x0043210b, 0x00401e08, 0x00401e06, 0x0047250c, 0x004b270c, 0x004f2a0c, 0x00552f0d, 0x00572d0b, 0x00603410, 0x005e300f, 0x00683818, 0x00673715, 0x00643410, 0x00683911, 0x0064350d, 0x00643510, 0x00663611, 0x00643410, 0x005c2f0a, 0x005a2e08, 0x00592d0a, 0x00572c0c, 0x0054290b, 0x0055290d, 0x00502408, 0x0052280b, 0x0053280c, 0x0051280c, 0x00562c0f, 0x00592f0f, 0x005c3110, 0x005c3310, 0x005b3110, 0x005a3010, 0x0059300e, 0x00552e0c, 0x00542c0c, 0x00542c0d, 0x00542d10, 0x0050280f, 0x004f2910, 0x004d280f, 0x0049240b, 0x00462208, 0x00442308, 0x00421f0a, 0x00391c0b, 0x00200e00, 0x000d0d04, 0x00080e07, 0x000c0f09, 0x0016100a, 0x0024160c, 0x00311d10, 0x00392210, 0x003c2711, 0x00362313, 0x002c1d11, 0x00221a10, 0x0018150e, 0x0010140d, 0x000a130d, 0x0008100b, 0x00061009, 0x00050f09, 0x00040e0a, 0x00040e0a, 0x00040e0a, 0x00040e0a, 0x00050e09, 0x00050e09, 0x00070f09, 0x00060e09, 0x00060d09, 0x00060d09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00070e09, 0x00060d08, 0x00050c08, 0x00060c08, 0x00070c08, 0x00070c08, 0x00080c08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00080c09, 0x00080d09, 0x00060d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00060f09, 0x00070f09, 0x00060d08, 0x00060d08, 0x00070c08, 0x00080c08, 0x00080c08, 0x00070c08, 0x00050e08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00050d09, 0x00050d09, 0x00050d09, 0x00040c08, 0x00040c07, 0x00050d07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00050d08, 0x00050d09, 0x00050d0a, 0x00060e0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00050f08, 0x00050f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00050e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050f08, 0x00050f08, 0x00070e09, 0x00060e08, 0x00050e08, 0x00050e07, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00050c08, 0x00070c08, 0x00080c09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x001d200a, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005d5e11, 0x005e5f13, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00686614, 0x00a28916, 0x00cba418, 0x00caa418, 0x00907c14, 0x00595a11, 0x00585810, 0x00535410, 0x00505010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f07, 0x00040f07, 0x00040f07, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00050c08, 0x00050c08, 0x00050c08, 0x00040d08, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008120d, 0x0007110c, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x00050f0a, 0x0007100b, 0x00070f0a, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f07, 0x00050e07, 0x00070f09, 0x00040c08, 0x00090f0a, 0x0013140e, 0x002e2b24, 0x003b372d, 0x00463f34, 0x004d4339, 0x0051433a, 0x005a4941, 0x0058463c, 0x005a4539, 0x00573f30, 0x00543c2b, 0x004c321f, 0x00593f2b, 0x005e432d, 0x005a3c22, 0x0058361a, 0x00543213, 0x0054300d, 0x00532c09, 0x0058300c, 0x00502702, 0x005c320c, 0x005c310c, 0x005c300b, 0x00643814, 0x00623610, 0x00643712, 0x00683915, 0x006b3c18, 0x006a3c15, 0x006a3c14, 0x00693c15, 0x00693c15, 0x006c3e18, 0x00643811, 0x0060340d, 0x00603512, 0x005e3312, 0x005b3214, 0x00552c11, 0x00512811, 0x0049230b, 0x004c280f, 0x0047240b, 0x0048230a, 0x0049250c, 0x00452107, 0x00482408, 0x00502a0d, 0x00542d0c, 0x0059310c, 0x005b300c, 0x0060340f, 0x00603310, 0x00643413, 0x00643512, 0x0062340f, 0x0064350f, 0x0062340f, 0x00603210, 0x00603210, 0x005b2e0c, 0x00582c0b, 0x00562b0b, 0x0054290a, 0x0051280b, 0x00502609, 0x0051280c, 0x0053280c, 0x0054290f, 0x00542b10, 0x0053280c, 0x00582d10, 0x005b3010, 0x005b300f, 0x005a330f, 0x005a3210, 0x0056300d, 0x00542e0c, 0x00512c09, 0x00522c0b, 0x0050290a, 0x0050280c, 0x004b240b, 0x004c270e, 0x004b250d, 0x00441e07, 0x00462209, 0x003f2009, 0x003b1d0b, 0x00301a0c, 0x001a0e01, 0x000c0e04, 0x00090e06, 0x000c0f08, 0x0016100a, 0x00211608, 0x00281c0c, 0x002d1e0c, 0x0034210f, 0x00312113, 0x002a1c12, 0x00241a12, 0x001a170f, 0x0013140d, 0x000e130d, 0x000a100b, 0x00081009, 0x00060e09, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00050d09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060d0b, 0x00060d0b, 0x00060e08, 0x00060e08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050d09, 0x00050d09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e06, 0x00060e06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c08, 0x00070c08, 0x00080c09, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x00494a0f, 0x004f500f, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005c5c11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00616112, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646514, 0x00646513, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x006c6914, 0x00a48c17, 0x00caa419, 0x00cba418, 0x00a58b16, 0x00616012, 0x00595a11, 0x00585810, 0x00535410, 0x00505010, 0x004c4d0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00050d08, 0x00040c08, 0x0008100b, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00041004, 0x00041004, 0x00041004, 0x00041004, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d09, 0x00050f0a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x00040f09, 0x00040f09, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0008120c, 0x0008120c, 0x0008120c, 0x0008120c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x00040e09, 0x00050e09, 0x00070f0a, 0x00070f0a, 0x00060f09, 0x00050d08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060f08, 0x00040d07, 0x00080e08, 0x0010110b, 0x0027241e, 0x0038342a, 0x004b433a, 0x004c4238, 0x0051433c, 0x0057463f, 0x00544239, 0x00554035, 0x00553e30, 0x00543929, 0x004c321e, 0x005b412d, 0x005e432d, 0x005c3e24, 0x0058381b, 0x00543011, 0x00542e0e, 0x00542d0d, 0x00583010, 0x00522a0b, 0x005e3414, 0x005c3311, 0x00582d0e, 0x005d3212, 0x005c3010, 0x00643817, 0x00613514, 0x00653817, 0x00683b18, 0x006a3d19, 0x00683c17, 0x00693d18, 0x006a4019, 0x00643913, 0x00613610, 0x00613611, 0x005f340e, 0x005e3210, 0x005c2f10, 0x00582d10, 0x00542b0e, 0x00542c0f, 0x0050290c, 0x004e2708, 0x00522b0d, 0x0050280b, 0x00532c0c, 0x00572f0c, 0x00582f09, 0x0060360f, 0x0060330d, 0x005f310b, 0x00643710, 0x00633410, 0x0062340e, 0x005e300c, 0x00603210, 0x005f320f, 0x005d300f, 0x005a2f0e, 0x00572b0c, 0x00542a0b, 0x0051280b, 0x004f2709, 0x004c240a, 0x004a2108, 0x004b2309, 0x004d240b, 0x004f260c, 0x004f260c, 0x00542b10, 0x00592f11, 0x005a3010, 0x005c310f, 0x005b3410, 0x005b3310, 0x00552f0c, 0x00512b08, 0x00512c08, 0x00512b0a, 0x0050290a, 0x00522c10, 0x004b240c, 0x004b250d, 0x004b250f, 0x00462009, 0x0044220c, 0x003a1f0a, 0x00361b0c, 0x00291409, 0x00180d05, 0x000d0e04, 0x00090e05, 0x000d1007, 0x0016100a, 0x00201709, 0x0024190a, 0x00251708, 0x002a190c, 0x002c1e14, 0x00281c14, 0x00211b14, 0x00191710, 0x00141410, 0x000e140e, 0x000a110c, 0x00081009, 0x00060e0a, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00050d09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060d0b, 0x00060d0b, 0x00060e08, 0x00060e08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e06, 0x00060e06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c08, 0x00060c08, 0x00070d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x006e6011, 0x00cca215, 0x00c29c15, 0x005c5911, 0x00595a12, 0x005b5b12, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646514, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00686814, 0x00847815, 0x00b59718, 0x00cba519, 0x00cba419, 0x00ac9016, 0x00686413, 0x005d5e12, 0x005b5b12, 0x00585810, 0x00545511, 0x00505010, 0x004c4d0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00051008, 0x00051007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0006100b, 0x00050e09, 0x00070f0a, 0x0008100b, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00040e07, 0x00080e08, 0x000c0d07, 0x001c1812, 0x00332e26, 0x00463e36, 0x004d4239, 0x0053443d, 0x0056453e, 0x00534239, 0x0058443a, 0x005a4234, 0x004f3422, 0x004e3420, 0x005c422e, 0x005d412c, 0x005e4025, 0x005a381b, 0x00563010, 0x00542d0d, 0x00572f13, 0x00572e14, 0x00532c11, 0x00563013, 0x00552f13, 0x00563014, 0x00542d0f, 0x00583012, 0x00603818, 0x005a3112, 0x005e3414, 0x00623817, 0x00663c1b, 0x00623816, 0x00623815, 0x00653b16, 0x00643a14, 0x00663c15, 0x00653a14, 0x0060350d, 0x0060340c, 0x0060320d, 0x00603210, 0x005f3310, 0x005c320f, 0x00562e0a, 0x00572f0b, 0x0058300c, 0x005b320f, 0x005f3610, 0x00623810, 0x0063380e, 0x006b3d14, 0x006a3c13, 0x00673810, 0x00683910, 0x0064360d, 0x0062340e, 0x005f310d, 0x005e3110, 0x005a2e0e, 0x00582c0e, 0x00542b0d, 0x0051280c, 0x0050270b, 0x004d250c, 0x004b240a, 0x0048210a, 0x00441e08, 0x00441e06, 0x00482209, 0x00502812, 0x00532b13, 0x00582f13, 0x00542c0d, 0x00592f0e, 0x005c3310, 0x005d3511, 0x005d3511, 0x0057310c, 0x00512c06, 0x00502a07, 0x004f2809, 0x00512b10, 0x004f2a10, 0x0049240c, 0x004c2810, 0x004c2a14, 0x00482510, 0x00452510, 0x00381f0c, 0x00341b0e, 0x00241108, 0x00140c04, 0x000d0f07, 0x00080f05, 0x000c1008, 0x0016110a, 0x001f1809, 0x00261c0d, 0x00281c10, 0x0024150c, 0x0022140d, 0x001e1610, 0x001b1511, 0x00151511, 0x00121510, 0x000f140e, 0x000b120c, 0x0008110a, 0x00070f0a, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00070f0a, 0x0008100b, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060d0b, 0x00060d0b, 0x00060e08, 0x00060e08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e06, 0x00060e06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c08, 0x00050c08, 0x00060d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003c3e0d, 0x0041420d, 0x0044450e, 0x0048490f, 0x004c4d0f, 0x006d6011, 0x00cca215, 0x00c29c15, 0x005c5911, 0x005b5910, 0x005c5c11, 0x005e5d12, 0x00605e12, 0x00605e12, 0x00605f12, 0x00616012, 0x00616012, 0x00616012, 0x00626113, 0x00626113, 0x00626113, 0x00626113, 0x00626113, 0x00626113, 0x00626113, 0x00636213, 0x00636213, 0x00646413, 0x00646412, 0x00646412, 0x00656514, 0x00666614, 0x00666614, 0x00686714, 0x00686814, 0x00696814, 0x006a6914, 0x006b6a14, 0x006c6b14, 0x00706d14, 0x007b7315, 0x008f7f16, 0x00af9418, 0x00c6a319, 0x00cca61a, 0x00caa519, 0x00a88d17, 0x006a6713, 0x00606013, 0x005d5e12, 0x005b5b12, 0x00585810, 0x00545511, 0x00505010, 0x004c4d10, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040e07, 0x00040e06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0004100a, 0x0004100a, 0x0005100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100b, 0x0005100b, 0x0005100b, 0x0005100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00060f09, 0x00070f0a, 0x0008100b, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070e08, 0x000c0c07, 0x0012100a, 0x002e2921, 0x003a332a, 0x00453b32, 0x004c3e36, 0x0057453f, 0x00524238, 0x00544134, 0x00553e2f, 0x004c321f, 0x004f3520, 0x005d442f, 0x00644830, 0x005c3f25, 0x0059381a, 0x00583212, 0x00532c0f, 0x00522b10, 0x00502910, 0x004a250c, 0x004c280e, 0x004c280d, 0x004f2c11, 0x004f2c10, 0x004f2a0e, 0x00522e10, 0x00573012, 0x00603a1c, 0x005d3718, 0x00603a19, 0x00623919, 0x00613918, 0x00633916, 0x00633a15, 0x00683e18, 0x00683c14, 0x00673b11, 0x00683a10, 0x00673810, 0x00673811, 0x00653812, 0x00633811, 0x00603610, 0x005f350f, 0x005f350f, 0x00623811, 0x00653c14, 0x00673d13, 0x00693d12, 0x006c3f14, 0x006c3c13, 0x006c3c13, 0x0068380f, 0x0063340c, 0x0061330d, 0x0060330f, 0x005c2f0f, 0x00542a0c, 0x0051280c, 0x0050270b, 0x004e270c, 0x004e270c, 0x004b230a, 0x00492108, 0x004a220b, 0x00461e07, 0x00461d06, 0x00482109, 0x0049230c, 0x00512a13, 0x00532a0f, 0x00522809, 0x00592f0d, 0x005c330f, 0x005e370f, 0x005d360e, 0x0059320c, 0x00542d08, 0x00502908, 0x004c2406, 0x004c280c, 0x0048240a, 0x0049260c, 0x0044230c, 0x0043220c, 0x0040200c, 0x003c1c0a, 0x00361e0c, 0x00301b10, 0x001e1007, 0x00100c04, 0x000c1008, 0x00091007, 0x000c1006, 0x00141309, 0x001d1809, 0x00261c10, 0x002c2015, 0x002a1c14, 0x0020140f, 0x001c140f, 0x00181410, 0x00131510, 0x00111410, 0x000e140e, 0x000b120c, 0x0008110a, 0x00070f09, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080d09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050c0a, 0x00050d09, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c09, 0x00040c0a, 0x00060d0b, 0x00060e0a, 0x00060e08, 0x00060e08, 0x00040f08, 0x00031008, 0x00031008, 0x00031008, 0x00040f08, 0x00050e08, 0x00060e08, 0x00060e09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e07, 0x00060e06, 0x00040f06, 0x00031006, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a0f, 0x006c5f10, 0x00cca215, 0x00c9a016, 0x00ba9615, 0x00ba9615, 0x00ba9715, 0x00ba9716, 0x00ba9716, 0x00ba9716, 0x00ba9816, 0x00ba9815, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00bb9818, 0x00bb9818, 0x00bb9818, 0x00bb9818, 0x00bb9817, 0x00bb9917, 0x00bb9917, 0x00bb9a18, 0x00bb9a18, 0x00bb9b18, 0x00bb9b18, 0x00bb9b18, 0x00bc9b18, 0x00bc9c19, 0x00bc9c19, 0x00bd9d18, 0x00c4a119, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00c3a119, 0x00978415, 0x00686714, 0x00636414, 0x00616112, 0x005e5f12, 0x005b5b11, 0x00585910, 0x00545511, 0x00515110, 0x004c4d10, 0x0048490e, 0x0044450e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050c07, 0x00080c08, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x0008100b, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050f08, 0x00051008, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x0004100a, 0x00041009, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f0b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060f09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00070e08, 0x00090e08, 0x000e0e08, 0x0027241c, 0x00322c24, 0x003e342d, 0x004a3d36, 0x00504038, 0x0049392f, 0x004e3c2f, 0x004c3726, 0x004b301d, 0x00493019, 0x0058412a, 0x00614830, 0x005d4026, 0x005a381b, 0x00553111, 0x00542f10, 0x00552f13, 0x00502a11, 0x0046230a, 0x0044220b, 0x0044220b, 0x0045230a, 0x00462409, 0x0049280b, 0x00502d11, 0x00583416, 0x005c381b, 0x005b3617, 0x005c3618, 0x005d3618, 0x00603818, 0x00613818, 0x00633918, 0x00643915, 0x00653813, 0x00663910, 0x00673a10, 0x00673810, 0x00673811, 0x00673912, 0x00673a15, 0x00683c17, 0x00663b17, 0x00633813, 0x00603510, 0x0060340f, 0x00603410, 0x00603410, 0x00623510, 0x00633411, 0x0060310e, 0x005c2c0b, 0x00582806, 0x00582806, 0x00502301, 0x004c2000, 0x004b2003, 0x00461d01, 0x00451c00, 0x004b2102, 0x00512708, 0x00582d0f, 0x00592f13, 0x005c3115, 0x00562b0e, 0x0052280a, 0x004f250b, 0x0048220a, 0x004c240c, 0x00502708, 0x00542909, 0x0059300c, 0x005c340c, 0x0060370c, 0x005d340a, 0x00583008, 0x00562c08, 0x0050280b, 0x004c270a, 0x004a260b, 0x00462408, 0x0045230b, 0x0042220b, 0x0040210c, 0x003d200d, 0x00351c0b, 0x00321b0d, 0x0026150a, 0x00130a03, 0x00100e07, 0x000b1208, 0x000a1008, 0x000c1005, 0x00141409, 0x00191409, 0x00251910, 0x002d1c15, 0x002f2018, 0x00251910, 0x001c140b, 0x0018140c, 0x0012140c, 0x000f130e, 0x000e140e, 0x000c140e, 0x0009110b, 0x00070f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070e0c, 0x00070f0a, 0x00060e09, 0x00060e08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280c, 0x002c2d0b, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0044450d, 0x0048490f, 0x00565210, 0x00b08d14, 0x00cca215, 0x00cca216, 0x00cca316, 0x00cca316, 0x00cca316, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca518, 0x00cca518, 0x00cca519, 0x00cca519, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00caa61a, 0x00c3a119, 0x00a99017, 0x007c7315, 0x00656614, 0x00646514, 0x00636414, 0x00616112, 0x005e5f12, 0x005c5c11, 0x00585910, 0x00555610, 0x00515110, 0x004c4d10, 0x0048490f, 0x0044450e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050c07, 0x00060c08, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x0004100a, 0x00041009, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f0b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110c, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060f0a, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f08, 0x00080e08, 0x000c0f08, 0x001c1a14, 0x002a251e, 0x003c342d, 0x004b4038, 0x004e4038, 0x00473a30, 0x00534435, 0x00543d2c, 0x00543a27, 0x00503721, 0x005c432c, 0x00644b33, 0x00604328, 0x005c3c1d, 0x00563211, 0x00573211, 0x00583414, 0x00502a0f, 0x00482409, 0x0049250c, 0x004a240b, 0x00472108, 0x00441e03, 0x00482406, 0x00502b0c, 0x00522d0e, 0x00512c0e, 0x00532e10, 0x00542f10, 0x00542d0f, 0x00552d10, 0x00552c0f, 0x00572c0f, 0x00582e0d, 0x00582e09, 0x00582e07, 0x00582d07, 0x00582c07, 0x005a2c09, 0x005a2d0a, 0x005b2e0c, 0x005c2f0e, 0x005a2e0f, 0x00572b0c, 0x00512507, 0x00502406, 0x004f2304, 0x00502407, 0x00532408, 0x00542508, 0x00522204, 0x004e1d00, 0x004c1c00, 0x004c1d00, 0x004c1c00, 0x004f1f01, 0x00502104, 0x004f2304, 0x00542706, 0x00603210, 0x00683b15, 0x006c3f19, 0x0070421c, 0x0070411c, 0x00693b16, 0x00623410, 0x00582e0c, 0x004e2508, 0x004c240b, 0x00522a0b, 0x00572d0b, 0x005c340f, 0x00603610, 0x005d340c, 0x00582f07, 0x00562c08, 0x00532908, 0x0052280c, 0x00522c10, 0x00472208, 0x00412006, 0x0044240c, 0x0041220c, 0x003f210c, 0x003c200d, 0x00341c0b, 0x002d170a, 0x00211409, 0x00130c04, 0x000e0e07, 0x000c1108, 0x000c100a, 0x000e0f07, 0x00151409, 0x001d150b, 0x0023140a, 0x0029170d, 0x00312014, 0x00302416, 0x00281f14, 0x00211c13, 0x001c1b14, 0x00151711, 0x000d120c, 0x00091009, 0x00070f08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c0a, 0x00040c08, 0x00060e09, 0x00060e08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x0014180f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0045470e, 0x00494a10, 0x00605810, 0x00a08212, 0x00a48613, 0x00a58814, 0x00a58814, 0x00a58814, 0x00a58814, 0x00a58814, 0x00a48814, 0x00a58814, 0x00a48914, 0x00a58914, 0x00a48914, 0x00a48914, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48915, 0x00a48815, 0x00a48815, 0x00a48915, 0x00a48916, 0x00a48a15, 0x00a48b15, 0x00a48b16, 0x00a48b16, 0x00a48b16, 0x00a48c16, 0x00a48c18, 0x00a48c18, 0x00a48c18, 0x009e8917, 0x00908016, 0x00777114, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00646414, 0x00626312, 0x005e5f13, 0x005c5c11, 0x00585911, 0x00555610, 0x00515110, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d08, 0x00060c08, 0x00060d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00020e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x0004100a, 0x00041009, 0x00040d08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060f09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e0b, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00061009, 0x00061009, 0x00061009, 0x00061009, 0x00070f08, 0x00070f08, 0x00081009, 0x00060f08, 0x00040d05, 0x00071007, 0x00071007, 0x00071007, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00051009, 0x00051008, 0x00061009, 0x00070f0a, 0x00070f0a, 0x0007100b, 0x000a100a, 0x00191c16, 0x0025241e, 0x00342e28, 0x00433932, 0x00493e34, 0x0044382d, 0x004c3c2f, 0x00553f30, 0x00503724, 0x00503420, 0x00573d27, 0x00634932, 0x00604429, 0x005c3b1d, 0x005c3815, 0x0058330f, 0x00532d0c, 0x004f280a, 0x004b2607, 0x004b2406, 0x00522c0d, 0x00542e0f, 0x00532b0c, 0x00542c0c, 0x00572f0d, 0x00512908, 0x004d2605, 0x004c2507, 0x004c2506, 0x004d2406, 0x004e2508, 0x0051260b, 0x0050250a, 0x00502408, 0x004f2504, 0x004f2504, 0x004e2403, 0x004c2102, 0x004c2000, 0x004b1e00, 0x004c1f02, 0x004b1c00, 0x00481c00, 0x00481c01, 0x00471b00, 0x00451800, 0x00421600, 0x00431800, 0x00461900, 0x004b1c01, 0x004c1d01, 0x00542408, 0x005c2c10, 0x005d2c10, 0x005e2c0f, 0x00643114, 0x00643011, 0x00653311, 0x006b3814, 0x00744018, 0x00713e13, 0x00744214, 0x00764416, 0x00744013, 0x00703d10, 0x0065360a, 0x005d3008, 0x00582c0c, 0x00542b0f, 0x00542c0b, 0x005c3210, 0x005e3510, 0x005e350e, 0x005c330c, 0x00572d08, 0x00512806, 0x004f2407, 0x0051280d, 0x004e280f, 0x0048240c, 0x00401f06, 0x0040220b, 0x003e200a, 0x003c1f0c, 0x003e2210, 0x00321a0a, 0x002a160a, 0x001c1006, 0x00130f08, 0x000e100a, 0x000e100a, 0x000f100a, 0x00141009, 0x0019150c, 0x0021170d, 0x0028160d, 0x002a1408, 0x002e1b0a, 0x00312211, 0x002d2012, 0x00271e14, 0x001e1a13, 0x0013140f, 0x000c110c, 0x0009100a, 0x00081009, 0x00060e08, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060d0b, 0x00060e09, 0x00070f0a, 0x00070f09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00050e08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250b, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x003c3e0c, 0x0040400d, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4c0f, 0x004d4d10, 0x00505010, 0x00515110, 0x00535410, 0x00545411, 0x00555511, 0x00555511, 0x00565711, 0x00565710, 0x00585810, 0x00585810, 0x00585810, 0x00585810, 0x00585810, 0x00585811, 0x00585811, 0x00585811, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x005c5c12, 0x005d5d12, 0x005e5f13, 0x00606013, 0x00606013, 0x00626213, 0x00636314, 0x00646414, 0x00656514, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00686814, 0x00686814, 0x00646513, 0x00646414, 0x00616112, 0x005e5f13, 0x005c5c11, 0x00595a11, 0x00555610, 0x00515110, 0x004d4e0f, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0005100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x0004100a, 0x00041009, 0x00040d08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060f09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060d08, 0x00070d09, 0x00060e0b, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110c, 0x0009110d, 0x00070f0b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x00061009, 0x00061009, 0x00061009, 0x00061009, 0x00071007, 0x00071007, 0x0009120a, 0x00081008, 0x00040d05, 0x00071007, 0x00071007, 0x00071007, 0x0007110a, 0x0007110c, 0x0005100a, 0x0005100a, 0x00051009, 0x00051008, 0x00061009, 0x00070f0a, 0x00070f0a, 0x0006100b, 0x0009110b, 0x00161b15, 0x00282923, 0x002c2c25, 0x00353129, 0x00443c33, 0x00443c30, 0x00554538, 0x00554030, 0x00543928, 0x004c301c, 0x00573d29, 0x005e442e, 0x005e4227, 0x005a3b1c, 0x00573410, 0x0058340e, 0x00583210, 0x00542e0d, 0x00552d0d, 0x00532b09, 0x005b3210, 0x00633917, 0x00653c18, 0x00683e1c, 0x006c421f, 0x00683f1e, 0x00623818, 0x005e3618, 0x005e3618, 0x005e3519, 0x005d3519, 0x005e3418, 0x005c3015, 0x005c3010, 0x0054290a, 0x00532707, 0x00522507, 0x00502206, 0x00502004, 0x004d1d01, 0x004c1c00, 0x004c1d00, 0x004c1d00, 0x004d1e00, 0x00512103, 0x00542507, 0x00552809, 0x005c2f10, 0x005e3011, 0x00623414, 0x00663818, 0x00653617, 0x00673717, 0x00683616, 0x00693616, 0x006a3514, 0x006a3411, 0x006d3812, 0x00713a12, 0x00743f12, 0x00723c0c, 0x0076410c, 0x0078430e, 0x00753f0a, 0x00703d08, 0x006a3a08, 0x00633308, 0x005c2f0c, 0x005a2e10, 0x00572d0c, 0x005c3310, 0x005c340e, 0x005c340c, 0x005b320b, 0x00542a05, 0x00512806, 0x004e2508, 0x004e240a, 0x0048220a, 0x00431f08, 0x00412109, 0x0040210c, 0x003d1e09, 0x003b1d0b, 0x00361808, 0x00341c0c, 0x0028180c, 0x00170e04, 0x00121108, 0x000e110b, 0x000f100a, 0x00100f09, 0x0017130b, 0x001e170e, 0x00251810, 0x0028180d, 0x002a1609, 0x002e1c0b, 0x0030210f, 0x002b1e0e, 0x00261c10, 0x001d1810, 0x0013140f, 0x000c140d, 0x0009130c, 0x0007110a, 0x00061009, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e07, 0x00050e06, 0x00050e06, 0x00050e06, 0x00060e08, 0x00060e09, 0x00050d09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0a, 0x002c2d0a, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x004f5010, 0x00505010, 0x00515110, 0x00525310, 0x00535410, 0x00545510, 0x00545510, 0x00555611, 0x00545511, 0x00555611, 0x00565711, 0x00555610, 0x00555611, 0x00565710, 0x00565710, 0x00565710, 0x00585910, 0x00585911, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005d5e11, 0x005e5f12, 0x00606013, 0x00616112, 0x00626313, 0x00646414, 0x00646514, 0x00666714, 0x00686815, 0x006b6a14, 0x008a7c15, 0x008d7e15, 0x008d7e15, 0x008d7e15, 0x008c7d15, 0x008c7d16, 0x008c7c14, 0x008b7b14, 0x008b7a14, 0x00897814, 0x007c6f13, 0x005b5a11, 0x00555610, 0x00525310, 0x004d4e0f, 0x0048490f, 0x0045470e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00080d09, 0x00080c09, 0x00080d09, 0x00050e09, 0x00040e09, 0x00030d08, 0x00010d08, 0x00030f09, 0x00030f09, 0x0004100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x00090f0b, 0x00090f0b, 0x000a100c, 0x000a100c, 0x00081009, 0x00081009, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110a, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x0008110a, 0x0008110a, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x0008100b, 0x000c130f, 0x00131913, 0x002a2e29, 0x002e2f2a, 0x00323029, 0x00383329, 0x00403a2d, 0x00504434, 0x00534030, 0x0058402e, 0x00503422, 0x00533824, 0x00543924, 0x005c4025, 0x00563819, 0x0052310e, 0x005c3814, 0x005a3310, 0x0058300d, 0x005b3110, 0x005d330e, 0x00613610, 0x00673c14, 0x00683e14, 0x006c4219, 0x00744822, 0x00764a28, 0x00744728, 0x00714729, 0x006e4428, 0x006a4125, 0x00673d23, 0x006b401b, 0x0070431b, 0x00744218, 0x00764017, 0x00754018, 0x00743e19, 0x00743d1b, 0x00733d18, 0x00703d15, 0x006f3c14, 0x006c3910, 0x006c3910, 0x006c3a10, 0x006f3c13, 0x00703e15, 0x00703d16, 0x00703c15, 0x006d3b14, 0x006c3a13, 0x00693810, 0x00673610, 0x0067350f, 0x0068350f, 0x006a350f, 0x006a3510, 0x006c370f, 0x006c370c, 0x006e370a, 0x00703809, 0x00723a0a, 0x00743c0c, 0x00773f0d, 0x00753d0c, 0x00713b0c, 0x006d3c11, 0x0066360d, 0x005c2f09, 0x00592e0a, 0x005b320e, 0x005b330f, 0x005a330d, 0x005c320d, 0x005b320c, 0x00502804, 0x004e2805, 0x004f2809, 0x004c240b, 0x0048220a, 0x00411f07, 0x0040230c, 0x003e210c, 0x003c1f0a, 0x003c200e, 0x00351709, 0x0032180c, 0x001c1003, 0x00161004, 0x00111208, 0x0010140b, 0x0012110a, 0x00161008, 0x001e140b, 0x0024180d, 0x002a1a11, 0x002d1b11, 0x0028170a, 0x002a1908, 0x00302110, 0x002d2011, 0x00271d10, 0x00201710, 0x00151510, 0x000e150f, 0x000b130c, 0x0008120b, 0x0007110a, 0x0006100b, 0x0006100b, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0009120c, 0x0009120c, 0x0009130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a120c, 0x0009110c, 0x0009110c, 0x000a120e, 0x000a120e, 0x0009110d, 0x0008100c, 0x0008100c, 0x0008100c, 0x0009120b, 0x000a130c, 0x000a130c, 0x000a130c, 0x00081109, 0x00081109, 0x00081108, 0x00081008, 0x0009100b, 0x00080f0a, 0x00060e09, 0x00060f0a, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d09, 0x00040d09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00080f0a, 0x00081009, 0x00060e08, 0x00040d07, 0x00040e07, 0x00030e07, 0x00030e07, 0x00041008, 0x00041008, 0x0004100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060b07, 0x00050b05, 0x00070c06, 0x00070d06, 0x00060f08, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040e07, 0x00020e07, 0x00020e07, 0x00031008, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280a, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004b4c0f, 0x004c4d0f, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00525310, 0x00535410, 0x00535410, 0x00535410, 0x00545510, 0x00535410, 0x00545510, 0x00555611, 0x00545510, 0x00565711, 0x00565711, 0x00585810, 0x00585911, 0x00595a12, 0x005c5c11, 0x005d5e11, 0x005e5f13, 0x00606013, 0x00616112, 0x00636414, 0x00646514, 0x00666713, 0x00686714, 0x00a48c17, 0x00c8a519, 0x00caa51a, 0x00caa51a, 0x00caa51a, 0x00caa51a, 0x00caa41a, 0x00c9a419, 0x00c9a419, 0x00c9a418, 0x00c9a318, 0x00c7a017, 0x008e7a13, 0x00545511, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0040400d, 0x003c3e0d, 0x0036370c, 0x0032330c, 0x002d2f0a, 0x0026280a, 0x0026280c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00080d09, 0x00080c09, 0x00080c09, 0x00050e09, 0x00040e09, 0x00030d08, 0x00010d08, 0x00030f09, 0x00030f09, 0x0004100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x00081009, 0x00081009, 0x0008110b, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120b, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x0008110a, 0x0008110a, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0009100b, 0x00080f0a, 0x000b100c, 0x000e1310, 0x001a1e1b, 0x00303532, 0x0031322e, 0x002e2c26, 0x002d2920, 0x003d372a, 0x00473c2c, 0x00483928, 0x00503b28, 0x00533826, 0x0049301a, 0x0050351f, 0x00583c23, 0x0056381b, 0x00523211, 0x005b3716, 0x00593412, 0x005a310e, 0x005c320e, 0x00623711, 0x00693c14, 0x00683c12, 0x006e4218, 0x0070441a, 0x00784b24, 0x00764a28, 0x00754829, 0x0075482b, 0x0072462b, 0x006e4428, 0x006b4124, 0x006b411c, 0x006d4018, 0x00704015, 0x00743f14, 0x00763d13, 0x00783c13, 0x00783c13, 0x00783d13, 0x007c4217, 0x007c4317, 0x00774012, 0x00753d11, 0x00743c10, 0x00743c10, 0x00743c10, 0x00743c11, 0x00723a10, 0x006e350c, 0x006c360b, 0x0069340b, 0x0068350b, 0x0066360c, 0x0066370c, 0x0067370f, 0x0067370f, 0x0067360d, 0x0068360a, 0x006a3709, 0x006f3909, 0x00703a09, 0x00713b0a, 0x00743e0c, 0x00733d0c, 0x006f3a0b, 0x006d3c11, 0x0066360e, 0x005a2c06, 0x005c310c, 0x005e3511, 0x005c3511, 0x0058310c, 0x0058310c, 0x00552f09, 0x00512b06, 0x00492604, 0x00492708, 0x004a260c, 0x00432008, 0x003c1c05, 0x0040220c, 0x003d200c, 0x003c1f0b, 0x003c200e, 0x00371b0d, 0x002c170a, 0x00140c00, 0x00141006, 0x00141309, 0x0014140c, 0x0018140b, 0x001c1209, 0x0024170d, 0x00291b11, 0x002d1c12, 0x002d1d11, 0x002b1b0e, 0x0029190b, 0x002b1c0e, 0x002a1c10, 0x00271d12, 0x00211811, 0x00161610, 0x000f150e, 0x000c140e, 0x000b150e, 0x000a140d, 0x0009130e, 0x0009130e, 0x0008120c, 0x0008120c, 0x0008120d, 0x0008120d, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x0009110d, 0x0009110d, 0x000a120e, 0x000a120e, 0x000a120e, 0x000a120e, 0x000a120e, 0x000a120e, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x00081109, 0x00081108, 0x0009120a, 0x000a130b, 0x000b120d, 0x0009100c, 0x00070f0a, 0x00060f0a, 0x0006100b, 0x0006100b, 0x00050f0a, 0x0006100b, 0x0006100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00080f0a, 0x00091009, 0x00060e08, 0x00040d07, 0x00040e07, 0x00020e07, 0x00020e07, 0x00041008, 0x00041008, 0x0004100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00080c09, 0x00080c08, 0x00070d08, 0x00070e06, 0x00050f08, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040e07, 0x00020e07, 0x00020e07, 0x00031008, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0c, 0x00191c09, 0x001d2009, 0x00202308, 0x0020230a, 0x0026280b, 0x00292b0a, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003c3e0c, 0x0040400d, 0x0041420e, 0x0044450d, 0x0047480e, 0x0048490f, 0x00494a0f, 0x004b4c0f, 0x004c4d0f, 0x004f5010, 0x004f5010, 0x00505010, 0x004f5010, 0x00515110, 0x00505010, 0x00505010, 0x00515110, 0x00515110, 0x00525310, 0x00535410, 0x00535410, 0x00545510, 0x00545511, 0x00555611, 0x00565710, 0x00585911, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00626313, 0x00646414, 0x00656614, 0x006a6714, 0x00c5a219, 0x00cca71a, 0x00c4a019, 0x00c1a019, 0x00c1a019, 0x00c1a018, 0x00c19f18, 0x00c19f18, 0x00c19f18, 0x00c19f18, 0x00c6a018, 0x00cca418, 0x00b09014, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003b3c0c, 0x0036370b, 0x0034350c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00080d09, 0x00080c09, 0x00080c09, 0x00050e09, 0x00040e09, 0x00030d08, 0x00010d08, 0x00030f09, 0x0004100a, 0x0004100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x0008110a, 0x0008110a, 0x0009110d, 0x0009110d, 0x000a120e, 0x000a120e, 0x000a130c, 0x000a130c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009140b, 0x0009140b, 0x0009130b, 0x0009140b, 0x000b130c, 0x000b130c, 0x000b130c, 0x000b140b, 0x0009120c, 0x0009120c, 0x0009130c, 0x0009130c, 0x0009130c, 0x0009130c, 0x000b130e, 0x000b130f, 0x000b130e, 0x000b130e, 0x000b110e, 0x00101412, 0x00151918, 0x001c201e, 0x00222624, 0x00303230, 0x00343734, 0x00363733, 0x002d2b26, 0x0029251c, 0x00353024, 0x0041392a, 0x00403322, 0x00493523, 0x004c3521, 0x004b311a, 0x00523720, 0x00553b23, 0x0053351c, 0x00563519, 0x00573416, 0x005a3312, 0x005c320d, 0x005b310a, 0x005e340b, 0x00643a0f, 0x00693d10, 0x006c4013, 0x0070441b, 0x00754822, 0x00754925, 0x00714624, 0x00744728, 0x00744728, 0x00764c2c, 0x00734928, 0x006c4320, 0x006a3f19, 0x006c3e16, 0x00703d13, 0x00713b10, 0x0074390d, 0x0074390d, 0x0074390c, 0x00743a0d, 0x00743c0e, 0x00743c10, 0x00733b0f, 0x0070380c, 0x0070380c, 0x0070390c, 0x0070380e, 0x006d350c, 0x006a3208, 0x00693308, 0x00683309, 0x00663409, 0x0062360b, 0x0062370b, 0x0061370c, 0x0062370d, 0x0062360b, 0x0064380a, 0x006b3c0c, 0x006e3d0c, 0x006f3c0a, 0x00703d0b, 0x00713e0c, 0x006e3b09, 0x006b3808, 0x0068370d, 0x0062320a, 0x00582c05, 0x00582d08, 0x00562e08, 0x0058310c, 0x0059320c, 0x00562f09, 0x00522c09, 0x004c2907, 0x00462505, 0x00442608, 0x003c1d04, 0x003c1f07, 0x003c2008, 0x003a1e08, 0x003b1d09, 0x003e210f, 0x00371d0e, 0x00291405, 0x00201104, 0x00100c00, 0x000f0c02, 0x0015120c, 0x001a150e, 0x00241c12, 0x002a1d14, 0x002c1c11, 0x002d1c11, 0x002d1d11, 0x002e1e11, 0x002e1e10, 0x002f1f10, 0x002c1e11, 0x002a1d12, 0x00281e15, 0x00231914, 0x001a1812, 0x00131610, 0x000e140e, 0x000d140e, 0x000c140d, 0x000a120e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0008120c, 0x0008120d, 0x0009110c, 0x0009110d, 0x000a120e, 0x000a120e, 0x000c140d, 0x000c140d, 0x000c140e, 0x000c140d, 0x000c140d, 0x000c140e, 0x000d150f, 0x000d150f, 0x000c140f, 0x000c1410, 0x000c1410, 0x000d1510, 0x000d1510, 0x000d1510, 0x000d1510, 0x000c140f, 0x000a120e, 0x0009120c, 0x0009120c, 0x000c140d, 0x000c140d, 0x000a120b, 0x000c140c, 0x000a130b, 0x000a130b, 0x000b120d, 0x000b120e, 0x0009110d, 0x0008110c, 0x0008120c, 0x0009130e, 0x0009130e, 0x0008120c, 0x0008110c, 0x0009100c, 0x0009110c, 0x0008100c, 0x00070f0a, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f09, 0x00080e08, 0x00070f08, 0x00070f08, 0x00051008, 0x00031008, 0x00041008, 0x00041008, 0x00041008, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00090e0b, 0x00091009, 0x00080f08, 0x00061008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040e07, 0x00020e07, 0x00020e07, 0x00031008, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280a, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0040400d, 0x0043440e, 0x0044450d, 0x0045470e, 0x0047480f, 0x0048490f, 0x00494a0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004c4d0f, 0x004f5010, 0x004f5010, 0x004d4e10, 0x00505010, 0x00505010, 0x00505010, 0x00515110, 0x00515110, 0x00525310, 0x00535410, 0x00545511, 0x00555611, 0x00565710, 0x00585911, 0x005b5b12, 0x005c5d11, 0x005d5e12, 0x00606012, 0x00616112, 0x00626314, 0x00646414, 0x006a6714, 0x00c6a219, 0x00cca61a, 0x00847715, 0x00736e14, 0x00736e14, 0x00736e14, 0x00726d14, 0x00716c14, 0x00706a14, 0x006e6814, 0x009f8615, 0x00cca418, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x0030310c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00080d09, 0x00080c09, 0x00080c09, 0x00050e09, 0x00040e09, 0x00030d08, 0x00010d08, 0x00030f09, 0x0004100a, 0x0006120c, 0x0007120c, 0x00070f08, 0x00070f08, 0x0008110a, 0x0008110a, 0x0008120d, 0x0008120d, 0x0009130e, 0x0009130e, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x0009120c, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x0008140b, 0x0008140b, 0x0009150c, 0x000a150c, 0x000c150c, 0x000c150c, 0x000c150c, 0x000c150c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c1410, 0x000c1410, 0x000c1411, 0x000d1412, 0x000e1411, 0x00141816, 0x001b1f1c, 0x00282c29, 0x00353837, 0x00393b3b, 0x00363837, 0x00343434, 0x002d2c28, 0x0026241b, 0x002a281b, 0x00383324, 0x00423827, 0x00493826, 0x0049341f, 0x004d341c, 0x0050341c, 0x00563b24, 0x0052351f, 0x00573820, 0x005a381c, 0x005c3614, 0x005b330c, 0x005e340a, 0x0063380e, 0x0064390c, 0x006a3f10, 0x006d4213, 0x0074471d, 0x00794b24, 0x00754824, 0x00744624, 0x00704422, 0x00704423, 0x00734928, 0x00704724, 0x006b441f, 0x00693f1a, 0x006c3f19, 0x00693a11, 0x0068380b, 0x006c380b, 0x006c380c, 0x006c380c, 0x006b370c, 0x006a370c, 0x006a380d, 0x0069370d, 0x0066340b, 0x0067340b, 0x0067350c, 0x0068350c, 0x0064320a, 0x00633008, 0x00613108, 0x00613108, 0x005f3208, 0x005d3409, 0x005c3409, 0x0060370c, 0x0060380c, 0x0061380c, 0x00643b0c, 0x006a3e0d, 0x006c3e0d, 0x006d3c0b, 0x00703e0c, 0x00713f0c, 0x006c3c09, 0x00693808, 0x0065340a, 0x005e2e06, 0x00582c05, 0x00562c08, 0x00522c07, 0x00542f08, 0x004e2904, 0x00512c08, 0x004c2907, 0x00482506, 0x00442608, 0x0042260a, 0x003a1e05, 0x003b2007, 0x00391e08, 0x00381b07, 0x003c1d0c, 0x00371b0a, 0x00321b0c, 0x00241204, 0x00150c00, 0x000e0d00, 0x000e0c03, 0x0018140d, 0x00201811, 0x002a1f14, 0x002f2015, 0x00302014, 0x00312014, 0x00312014, 0x00322214, 0x00322214, 0x00322213, 0x00302114, 0x002d2016, 0x002a2018, 0x00241b16, 0x001b1813, 0x00141510, 0x0010140f, 0x000f140e, 0x000c120c, 0x000a140f, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x000b1410, 0x000b1510, 0x000c140f, 0x000c140f, 0x000b130e, 0x000a120e, 0x000c140d, 0x000c140e, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000c1410, 0x000c1410, 0x000d1510, 0x000d1510, 0x000d1510, 0x000d1510, 0x000d1510, 0x000c140f, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140c, 0x000d160e, 0x000b130c, 0x000a130c, 0x000b120d, 0x000b120e, 0x000a120e, 0x000b130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0009110d, 0x0009110d, 0x0009100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f09, 0x00080e08, 0x00070f08, 0x00070f08, 0x00051008, 0x00041008, 0x00051009, 0x00041008, 0x00041008, 0x00040f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00080f0b, 0x0008100a, 0x00070f08, 0x00061008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040e07, 0x00030e07, 0x00030e07, 0x00041008, 0x00041008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250c, 0x0026280b, 0x002c2d0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003b3c0c, 0x003e400c, 0x0040400d, 0x0043440e, 0x0044450d, 0x0045470d, 0x0047480e, 0x0048490f, 0x00494a10, 0x004b4c10, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e10, 0x004f5010, 0x00505010, 0x00515110, 0x00515110, 0x00525310, 0x00545510, 0x00555611, 0x00585810, 0x00585911, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00626313, 0x00646414, 0x00696614, 0x00c6a218, 0x00cca61a, 0x007c7315, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00646514, 0x00646414, 0x00616112, 0x009b8415, 0x00cca418, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e09, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e07, 0x00060e08, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e09, 0x00080c09, 0x00080c0a, 0x00070c0b, 0x00060e0b, 0x0005100a, 0x0004100a, 0x0007110d, 0x0008120d, 0x0008110b, 0x0008120a, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0008120c, 0x0008120c, 0x0009140c, 0x0009140c, 0x000c140d, 0x000c140d, 0x000b140d, 0x000b140d, 0x000b140d, 0x000b140d, 0x000c140d, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d160d, 0x000d160d, 0x000c150c, 0x000c150c, 0x000d140c, 0x000d140c, 0x000e140c, 0x000e140c, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c1510, 0x000b1410, 0x000f1614, 0x00151b18, 0x00171b17, 0x0020231e, 0x00292c27, 0x00343632, 0x00363636, 0x00323234, 0x002f2f2f, 0x0023231f, 0x001b1a11, 0x00242418, 0x002a2819, 0x00373020, 0x00403220, 0x0046341e, 0x00483018, 0x004f341c, 0x00593e28, 0x00543624, 0x00573723, 0x005b381f, 0x005c3718, 0x005b340e, 0x005c340c, 0x00603810, 0x00643a10, 0x006a3e14, 0x006e4016, 0x00774820, 0x00754720, 0x00754823, 0x00744823, 0x00704520, 0x00704520, 0x006d441f, 0x0069401b, 0x00673d18, 0x00633a13, 0x00613810, 0x0062360d, 0x0062360a, 0x00603508, 0x0060340a, 0x0060340c, 0x0060340c, 0x005f330a, 0x005b3108, 0x00582f06, 0x00593008, 0x005a3008, 0x00593008, 0x00593008, 0x005c320c, 0x005b310b, 0x00582d08, 0x005d2f08, 0x005f3108, 0x00603308, 0x00613409, 0x0064350b, 0x0063360b, 0x0064380c, 0x00683c0f, 0x006b3c0e, 0x006c3c0c, 0x00703d0b, 0x006e3c09, 0x006c3a08, 0x006b3a09, 0x00653808, 0x005a2f04, 0x00562c02, 0x0058310a, 0x0058310a, 0x00542e08, 0x00502c08, 0x004a2804, 0x004c2c08, 0x00402000, 0x00402104, 0x0043240b, 0x00371a02, 0x00381d06, 0x00391c07, 0x00381c08, 0x00381c08, 0x003b1d0b, 0x00351a09, 0x002c1708, 0x00201207, 0x00100c01, 0x000c0f06, 0x000e0d05, 0x00171208, 0x0022170c, 0x002e2013, 0x00342519, 0x002c1f14, 0x002a1e14, 0x00302118, 0x00332518, 0x00332517, 0x00302212, 0x002d2012, 0x002c2115, 0x002b221a, 0x00221c16, 0x001a1812, 0x00171511, 0x00121410, 0x0011140f, 0x000f140f, 0x000a140f, 0x000a140f, 0x000a140f, 0x000a140f, 0x000b150e, 0x000b150e, 0x000b150e, 0x000b150e, 0x000d150f, 0x000e1610, 0x000d150f, 0x000d150f, 0x000e1610, 0x000e1710, 0x000f1710, 0x000d150f, 0x000e1710, 0x000f1811, 0x000f1811, 0x000e1710, 0x000e1710, 0x000e1612, 0x000e1612, 0x000e1612, 0x000f1713, 0x000e1612, 0x000e1612, 0x000e1612, 0x000e1612, 0x000e1710, 0x000f1610, 0x000e150f, 0x000e150f, 0x000e1510, 0x000e1510, 0x000e1510, 0x000e1510, 0x000e140f, 0x000d130d, 0x000c120c, 0x000c130d, 0x000c140e, 0x000c140d, 0x000b130c, 0x0009120c, 0x0009120c, 0x0009130e, 0x0009130e, 0x0008120c, 0x0008110c, 0x0007110c, 0x0006100b, 0x0007110c, 0x0007110c, 0x0008120d, 0x0007130d, 0x0006120c, 0x0005100b, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x0005100a, 0x00040d08, 0x00040e09, 0x00040e09, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060f0a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100d, 0x0008100c, 0x0008100b, 0x00090f0b, 0x00080f0a, 0x00070f0a, 0x00060e0a, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040c06, 0x00040c08, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100a, 0x00051008, 0x00040f08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x0038380c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0047480e, 0x0047480f, 0x00484910, 0x00484910, 0x00494a10, 0x004b4c10, 0x004b4c0f, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00525310, 0x00525310, 0x00545510, 0x00555611, 0x00585810, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00626312, 0x00636414, 0x00686514, 0x00c6a219, 0x00cca619, 0x007c7215, 0x00686814, 0x00686814, 0x00666714, 0x00656613, 0x00656614, 0x00636414, 0x00626312, 0x009b8415, 0x00cca418, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x004b4c10, 0x0047480e, 0x0041420e, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e0a, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0006100b, 0x0006100b, 0x0005100b, 0x0005100a, 0x00050f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00060e06, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080f0b, 0x000a0f0b, 0x000a0f0c, 0x00090f0c, 0x00080f0b, 0x00070f08, 0x00051009, 0x0007110c, 0x0008120c, 0x0008130a, 0x0008130a, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c140e, 0x000c140e, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e170e, 0x000e170e, 0x000f1810, 0x000f1810, 0x0010160e, 0x0010160e, 0x0010160e, 0x0010160e, 0x000f1610, 0x000e1610, 0x000e1610, 0x000d1711, 0x000c1612, 0x00111815, 0x00151a17, 0x00181c16, 0x00272921, 0x00303028, 0x0034342e, 0x00323230, 0x002e2e2e, 0x00282828, 0x001b1c18, 0x0011130a, 0x001f2015, 0x0028281c, 0x00363024, 0x003b301f, 0x0042311c, 0x00432c15, 0x00472d16, 0x00523822, 0x00523625, 0x00563924, 0x0058391e, 0x00583616, 0x005b3713, 0x0059340e, 0x005c350f, 0x00613911, 0x006b3f17, 0x006e4218, 0x00754720, 0x00784a23, 0x00754823, 0x00744823, 0x00714620, 0x0070441e, 0x0069401c, 0x00673d18, 0x00643b14, 0x00603710, 0x005d340d, 0x005c340c, 0x005c3409, 0x005b3208, 0x00583107, 0x00562f08, 0x00562f0b, 0x00542e0a, 0x00502b09, 0x004e2807, 0x004f2908, 0x00502a08, 0x00502a08, 0x00502b08, 0x00522f0c, 0x0054300c, 0x00522c05, 0x005b300a, 0x0060340b, 0x0062340a, 0x0066360c, 0x0067380d, 0x0067380d, 0x0069390d, 0x006d3c10, 0x006f3c0e, 0x00703b0c, 0x00703c0c, 0x006f3c0a, 0x006b3909, 0x0068390a, 0x00603306, 0x005b3006, 0x005b320c, 0x0057310c, 0x0057310c, 0x00532f0a, 0x00502c09, 0x00492807, 0x004b2c0c, 0x00391c00, 0x003b1d01, 0x003d2008, 0x00381c06, 0x003b1d08, 0x00391c07, 0x00381c08, 0x00381c0b, 0x003a1d0c, 0x00341b0b, 0x00281708, 0x001c1106, 0x00110f07, 0x000b0f06, 0x000c0e06, 0x00171208, 0x0021170b, 0x002e2013, 0x00342619, 0x00281c12, 0x00241b13, 0x002a1f16, 0x002e2318, 0x00312518, 0x002e2213, 0x002e2416, 0x00292015, 0x00221c13, 0x001e1a14, 0x001a1813, 0x00161512, 0x00121410, 0x0011140f, 0x0010140f, 0x000c1410, 0x000c1410, 0x000d1510, 0x000d1510, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x00101711, 0x00101711, 0x000f150f, 0x000f150f, 0x000f1610, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1710, 0x000f1811, 0x000f1811, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x000f1811, 0x000f1811, 0x00101812, 0x00101812, 0x00121812, 0x00131712, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00101610, 0x000f150f, 0x000e150f, 0x000d150f, 0x000d150f, 0x000c140e, 0x000b130c, 0x000a130c, 0x000a140f, 0x000a140f, 0x000a140f, 0x000a140f, 0x0009130e, 0x0009130e, 0x0008120c, 0x0007110c, 0x0007130d, 0x0007130d, 0x0007130d, 0x0007130d, 0x0006110c, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040f09, 0x0005100a, 0x00040d08, 0x00040e09, 0x00040f09, 0x0008100b, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00060e09, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005100e, 0x0006100c, 0x0008100b, 0x00090f0b, 0x00080f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040c06, 0x00040c08, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100a, 0x00051008, 0x00040f08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x00191c08, 0x00202308, 0x0024250a, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0030310c, 0x0034350c, 0x0038380c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0040400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0047480d, 0x0047480e, 0x00484910, 0x00484910, 0x00494a10, 0x00494a10, 0x00494a10, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00515110, 0x00525310, 0x00535410, 0x00555611, 0x00585810, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00606013, 0x00636413, 0x00686414, 0x00c6a219, 0x00cca619, 0x007c7114, 0x00666714, 0x00666714, 0x00666713, 0x00656614, 0x00646414, 0x00646414, 0x00616112, 0x009b8415, 0x00cca417, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0047480f, 0x0041420e, 0x003e400d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250b, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f09, 0x0008110a, 0x00081009, 0x00070f08, 0x00070f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060f0b, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x0008100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0005100a, 0x00050f0a, 0x00060e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00060e06, 0x00081009, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f08, 0x00070f08, 0x00081009, 0x000a0f09, 0x000b0f0b, 0x000b0f0c, 0x000a100a, 0x000a100a, 0x0009120b, 0x0009120c, 0x000a130c, 0x000a130b, 0x000b140b, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000f150f, 0x00101610, 0x00101610, 0x00101710, 0x00101711, 0x00101711, 0x00111812, 0x00101711, 0x000f1510, 0x00111812, 0x00111812, 0x00121813, 0x00121813, 0x00121911, 0x00121911, 0x00131a12, 0x00131a12, 0x00141811, 0x00111610, 0x0010150e, 0x0010150e, 0x00101711, 0x00101711, 0x00101711, 0x00121913, 0x00101814, 0x00131a16, 0x00161914, 0x001c1d14, 0x0025251b, 0x002f2c24, 0x002f2d26, 0x00302d2a, 0x002e2c2b, 0x00252422, 0x00242420, 0x00181a14, 0x0013140c, 0x0024241a, 0x002e2b20, 0x0031281a, 0x003f301d, 0x0048351d, 0x003f2710, 0x00442c18, 0x004c3321, 0x00543924, 0x0055381c, 0x00543518, 0x00563416, 0x00573313, 0x005b3613, 0x00603b14, 0x00683f18, 0x00693f17, 0x006f421b, 0x00754923, 0x00744824, 0x00734823, 0x006e4520, 0x006b421d, 0x00683f1a, 0x00693e19, 0x00663c16, 0x00623912, 0x005f3710, 0x005d360e, 0x005d360c, 0x00583108, 0x00512a04, 0x00522c08, 0x00522c0c, 0x00502b0b, 0x00502a0c, 0x004e280b, 0x004e290c, 0x004d280b, 0x004d280b, 0x00542e10, 0x0053300f, 0x0054300c, 0x00552f09, 0x005e340d, 0x0064380e, 0x0065370c, 0x0067380d, 0x0067380d, 0x0068380e, 0x006b3a0f, 0x006f3d10, 0x00703c0e, 0x006f3b0b, 0x006e3a09, 0x006c3b0b, 0x0068390a, 0x00633508, 0x0062360b, 0x00603610, 0x005a300c, 0x005c3410, 0x0058300e, 0x00522c0b, 0x00502d0c, 0x00482709, 0x0047280b, 0x003a1d04, 0x003a1d04, 0x003c200b, 0x003a1e0a, 0x00381c0b, 0x00381c0b, 0x00381c0a, 0x00361a08, 0x00381c0b, 0x00311909, 0x00241507, 0x00181006, 0x00131209, 0x000c1107, 0x000d0f05, 0x00161107, 0x0020160b, 0x002b1e12, 0x00312418, 0x00271c11, 0x00231912, 0x00251d15, 0x002a2018, 0x002d2519, 0x0030271a, 0x002f261a, 0x00272116, 0x001f1c13, 0x001d1d15, 0x001a1b16, 0x00141813, 0x00141713, 0x00141612, 0x00131712, 0x00111814, 0x00101713, 0x00101512, 0x00101511, 0x00101711, 0x00111812, 0x00111812, 0x00111812, 0x00111611, 0x00111611, 0x00131712, 0x00131712, 0x00121812, 0x00111812, 0x00111812, 0x00101711, 0x00111812, 0x00111813, 0x00121813, 0x00121813, 0x00121813, 0x00111812, 0x00111812, 0x00101812, 0x00101812, 0x00101811, 0x00101811, 0x00111812, 0x00111812, 0x00131714, 0x00141614, 0x00131513, 0x00131513, 0x00131513, 0x00131513, 0x00131513, 0x00131513, 0x00121612, 0x00111711, 0x00101710, 0x00101610, 0x000e1610, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000b1510, 0x000b1510, 0x0008140f, 0x0007130d, 0x0008140d, 0x0008140e, 0x0008120c, 0x0006100b, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00050d09, 0x00040c08, 0x00040f09, 0x0005100a, 0x0004100a, 0x0003100d, 0x0004100c, 0x0006100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x00060e08, 0x00030d06, 0x00040d09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x0006100a, 0x00051008, 0x00040f08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180a, 0x00191c09, 0x00191c08, 0x001d2008, 0x00202308, 0x0026280c, 0x00292b0b, 0x00292b0a, 0x0030310b, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003b3c0d, 0x003e400c, 0x003e400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0045470e, 0x0047480d, 0x0047480e, 0x00484910, 0x00484910, 0x00494a10, 0x00494a10, 0x00494a10, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545511, 0x00565711, 0x00585911, 0x00595a12, 0x005c5c11, 0x005e5f13, 0x00606012, 0x00616112, 0x00686414, 0x00c6a219, 0x00cca619, 0x007b7014, 0x00666713, 0x00666713, 0x00656614, 0x00646514, 0x00646414, 0x00626313, 0x00606013, 0x009b8415, 0x00cca417, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0047480f, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e0a, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0007100b, 0x00060e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e06, 0x00081008, 0x00081008, 0x00070f08, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00081009, 0x00071009, 0x0008100a, 0x000a100a, 0x000b100a, 0x000c0f0a, 0x000b100a, 0x000d130c, 0x000d140c, 0x000c140c, 0x000d140c, 0x000d140b, 0x000d140b, 0x000f140d, 0x000f140e, 0x0010140f, 0x0010140f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x00101711, 0x00111812, 0x00111812, 0x00121813, 0x00121813, 0x00121813, 0x00121813, 0x00131914, 0x00141a14, 0x00141914, 0x00141914, 0x00151a14, 0x00151a14, 0x00151a13, 0x00151a13, 0x00141912, 0x00141912, 0x00161812, 0x00161812, 0x00171913, 0x00171913, 0x00141914, 0x00141914, 0x00141914, 0x00141a14, 0x00141a14, 0x00161a14, 0x00181a14, 0x001d1c13, 0x00211f14, 0x0028241a, 0x002a251e, 0x002d2923, 0x002f2b28, 0x00282724, 0x002c2b26, 0x00181914, 0x0011140d, 0x0023251e, 0x0026251c, 0x002e281c, 0x003c3122, 0x0046351f, 0x00402d15, 0x0048321c, 0x00493320, 0x004f361e, 0x0050351a, 0x00503318, 0x0053341a, 0x00513115, 0x00502e0c, 0x0058340f, 0x00633b15, 0x00684018, 0x00684017, 0x006c441c, 0x00744a25, 0x00704822, 0x006c4520, 0x006b411c, 0x00673d18, 0x00683c18, 0x00673e17, 0x00643b14, 0x00603710, 0x00613710, 0x0060380f, 0x005c330b, 0x00562c08, 0x00572c0c, 0x00572e0e, 0x00542c0c, 0x00542c0e, 0x00542b0d, 0x00542b0d, 0x0050280a, 0x00502809, 0x00522a0b, 0x00573010, 0x005a3310, 0x005c320e, 0x0060330c, 0x0064360d, 0x0066360c, 0x0067380d, 0x0067380d, 0x0067390e, 0x0067390b, 0x006b3c0c, 0x006b3c0a, 0x006c3a08, 0x006b3a08, 0x006a390b, 0x0068390d, 0x00623409, 0x0061340c, 0x00592e09, 0x00572d0a, 0x00583010, 0x00593111, 0x004f2809, 0x004d290c, 0x00452408, 0x003d2005, 0x003a1f06, 0x00381e08, 0x00381e09, 0x00361c0b, 0x00371c0a, 0x00381c0b, 0x00381c0c, 0x00341908, 0x00341b09, 0x002d1907, 0x00251809, 0x00161104, 0x00121408, 0x000c1107, 0x000d0f05, 0x00161008, 0x001f170b, 0x00281c0f, 0x002d2014, 0x00281d13, 0x00241a13, 0x00201813, 0x001f1912, 0x00241f15, 0x00282318, 0x00282418, 0x00242318, 0x00201f16, 0x001c1d14, 0x001b1c17, 0x00181a16, 0x00161814, 0x00161814, 0x00161814, 0x00141815, 0x00141815, 0x00141814, 0x00131714, 0x00141813, 0x00141914, 0x00141814, 0x00141813, 0x00141813, 0x00141813, 0x00141813, 0x00141612, 0x00141814, 0x00141914, 0x00141914, 0x00141813, 0x00141813, 0x00141914, 0x00141914, 0x00151a14, 0x00151a14, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00141913, 0x00141914, 0x00141914, 0x00141813, 0x00141813, 0x00141814, 0x00141814, 0x00141814, 0x00141814, 0x00141814, 0x00131813, 0x00121813, 0x00101812, 0x00101812, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000e1813, 0x000d1712, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000b1510, 0x000b1510, 0x000b1710, 0x0008140f, 0x0008140e, 0x0008140e, 0x0008130d, 0x0008110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00060e09, 0x00050d09, 0x00060e09, 0x00060e09, 0x0005100a, 0x0005100a, 0x0004100a, 0x0003100d, 0x0003100c, 0x00040f0a, 0x00040e09, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040e07, 0x00040d09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x0005100a, 0x00051009, 0x00051008, 0x00040f08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180a, 0x00191c09, 0x00191c08, 0x001d2008, 0x00202308, 0x0026280c, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0c, 0x003b3c0d, 0x003e400c, 0x003e400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0045470d, 0x0047480d, 0x0047480e, 0x00484910, 0x00484910, 0x00494a10, 0x00494a10, 0x00494a10, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00525310, 0x00535410, 0x00545511, 0x00565710, 0x00585911, 0x00595a12, 0x005c5c11, 0x005e5f13, 0x00606013, 0x00616112, 0x00666413, 0x00c6a219, 0x00cca619, 0x007b7014, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00636413, 0x00606013, 0x009a8215, 0x00cca417, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0047480f, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050d07, 0x00050e08, 0x00081008, 0x00071007, 0x00071007, 0x00060e08, 0x00040c07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x00050d07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060f08, 0x00060e0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050e09, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060e08, 0x00071007, 0x00071007, 0x00070f08, 0x00070f08, 0x00081009, 0x00061009, 0x0007110a, 0x0007110a, 0x0008120b, 0x0008120c, 0x000a110c, 0x000b110c, 0x000b110c, 0x000c120c, 0x000c130c, 0x000e120d, 0x000e120d, 0x000e130c, 0x000f140c, 0x00101610, 0x00101610, 0x00101610, 0x00101610, 0x00101510, 0x00111611, 0x00121712, 0x00131812, 0x00111812, 0x00121813, 0x00121813, 0x00131914, 0x00131913, 0x00131a12, 0x00131a13, 0x00121912, 0x00151c14, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161b14, 0x00181a14, 0x00181a15, 0x00181a15, 0x00181a15, 0x00171914, 0x00181a15, 0x00191c17, 0x00191c16, 0x00181c15, 0x00181a14, 0x00181a14, 0x00181b15, 0x00171914, 0x00181a14, 0x001e1c15, 0x00211e14, 0x00211c12, 0x00241d13, 0x00252016, 0x0027211a, 0x0028241e, 0x0026241f, 0x00292924, 0x0012140e, 0x00191d17, 0x0032342e, 0x0025241c, 0x00353127, 0x003b3226, 0x003d301e, 0x0040311c, 0x0045331c, 0x00432e17, 0x00473017, 0x004b3219, 0x004f361d, 0x004f341e, 0x004d3016, 0x004c2d0c, 0x00543210, 0x0054300c, 0x00623d17, 0x00643e18, 0x0069411c, 0x006b441e, 0x006b4420, 0x006b431f, 0x0069401d, 0x00673d1a, 0x00683c18, 0x00683d17, 0x00653b12, 0x00623810, 0x0060380f, 0x005e350c, 0x00593008, 0x00542b07, 0x00512707, 0x00582e0f, 0x00572d11, 0x00562f10, 0x00593111, 0x0058300d, 0x00512808, 0x00502708, 0x00532808, 0x005a2e10, 0x005e3210, 0x005e330d, 0x0060340c, 0x0064360c, 0x0066360e, 0x0066370c, 0x0068380c, 0x0068380c, 0x0069390c, 0x006a390a, 0x006a390b, 0x0069380c, 0x0069380c, 0x0067380d, 0x0064340c, 0x0061330a, 0x0060340c, 0x00562b07, 0x005d320f, 0x00582d0c, 0x00572d0e, 0x00542c0d, 0x00522e11, 0x00442408, 0x003c2005, 0x00391e08, 0x003b1f0b, 0x00371c08, 0x00371b09, 0x00371b09, 0x00381c0a, 0x00361c0b, 0x00321908, 0x00301807, 0x002c1a08, 0x00271a09, 0x00161002, 0x000c0d00, 0x00080c02, 0x00111309, 0x00171309, 0x001c1408, 0x0024180e, 0x002d2014, 0x00281d14, 0x00241b13, 0x001f1a13, 0x001f1c15, 0x001e1c14, 0x001f1c14, 0x00202014, 0x00212318, 0x00202219, 0x001d2019, 0x001c1e18, 0x00191c16, 0x00171a14, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00151a14, 0x00151a14, 0x00141914, 0x00151a14, 0x00141914, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00151a14, 0x00151b15, 0x00151c15, 0x00141a14, 0x00141914, 0x00171914, 0x00171914, 0x00181a15, 0x00161b15, 0x00151c14, 0x00151c14, 0x00141b13, 0x00121810, 0x00141912, 0x00141912, 0x00161b14, 0x00161b14, 0x00131815, 0x00131816, 0x00131917, 0x00131917, 0x00141a16, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141813, 0x00111812, 0x000f1912, 0x000f1912, 0x000d1710, 0x000c160f, 0x000c1712, 0x000e1814, 0x000c1713, 0x000c1713, 0x000c1610, 0x000d1510, 0x000c1410, 0x000c140f, 0x000a140f, 0x0008120d, 0x0007110c, 0x0007110c, 0x0007100c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x000a100c, 0x00070f0a, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100a, 0x0008110b, 0x0008120b, 0x00061009, 0x0006100b, 0x0007100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e08, 0x00040e09, 0x00040e09, 0x00040c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060f09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x00141810, 0x0014180b, 0x0014180a, 0x00191c09, 0x00191c08, 0x00202308, 0x0024250b, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0034350c, 0x0038380c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0040400d, 0x0043440f, 0x0043440e, 0x0045470e, 0x0045470e, 0x0047480d, 0x0047480e, 0x00484910, 0x00494a10, 0x00494a10, 0x00494a10, 0x00494a0f, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00525310, 0x00545510, 0x00555611, 0x00565711, 0x00585911, 0x00595a12, 0x005c5c11, 0x005e5f13, 0x00606013, 0x00606013, 0x00666413, 0x00c6a218, 0x00cca519, 0x007a7014, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00636414, 0x00616112, 0x00606013, 0x009a8215, 0x00cca417, 0x00b09015, 0x00515111, 0x00525310, 0x004f5010, 0x00494a0f, 0x0047480f, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00050e07, 0x00060e06, 0x00060e06, 0x00040c06, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x00040d07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00070f09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e07, 0x00060e09, 0x00040e09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060e08, 0x00071007, 0x00071007, 0x00060e08, 0x00060e08, 0x0008110b, 0x0008120b, 0x0008130c, 0x0008130c, 0x0009140c, 0x000a140d, 0x000c130d, 0x000c130d, 0x000c130d, 0x000d140e, 0x000d140e, 0x000f140e, 0x000f140e, 0x0010140f, 0x0010140f, 0x00101510, 0x00101510, 0x00111611, 0x00111611, 0x00111611, 0x00131712, 0x00141813, 0x00141813, 0x00121813, 0x00131914, 0x00131914, 0x00141a14, 0x00141a14, 0x00141b13, 0x00141b13, 0x00121911, 0x00151c14, 0x00161b15, 0x00161b14, 0x00181c14, 0x00181d14, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c17, 0x00181a16, 0x00181b17, 0x00191c16, 0x00191c16, 0x001b1c14, 0x001b1c14, 0x001c1d16, 0x001c1c15, 0x001a1b14, 0x001c1c15, 0x00201d17, 0x00231f15, 0x00241e14, 0x00272018, 0x0028201a, 0x0028211b, 0x00272219, 0x0025231b, 0x0022231c, 0x0010120c, 0x001c211a, 0x00383b34, 0x002c2c24, 0x002d2920, 0x00362e24, 0x002f2417, 0x00372917, 0x0041321a, 0x00412e15, 0x0048341a, 0x00503820, 0x00513822, 0x004b311a, 0x004a2f14, 0x00523414, 0x00593818, 0x0054320f, 0x00623e19, 0x00623c18, 0x0066401a, 0x0067411b, 0x0067411c, 0x0068401c, 0x0068401c, 0x00693d1b, 0x00683d19, 0x00683d17, 0x00663c13, 0x00623810, 0x0061380e, 0x0061380e, 0x005d340c, 0x00562d09, 0x00502706, 0x00552d0f, 0x00542c12, 0x00573013, 0x005b3314, 0x00582f0f, 0x00502608, 0x0054290c, 0x00562a0d, 0x005d3013, 0x005f330f, 0x005f320c, 0x0062350d, 0x0064370f, 0x0065370e, 0x0066380d, 0x0067390c, 0x00683a0d, 0x00693a0c, 0x006a390c, 0x0069380d, 0x0068380f, 0x0068370f, 0x0063340c, 0x00613209, 0x00603209, 0x005f330b, 0x005c2f09, 0x00592e0b, 0x00542b09, 0x005c3112, 0x00552c0e, 0x00502b0e, 0x00402004, 0x00391d03, 0x00371c05, 0x003a1e0a, 0x00371b08, 0x00371b09, 0x00371c0a, 0x00371c0a, 0x00331c09, 0x002e1707, 0x002d1708, 0x002c190a, 0x00271a09, 0x00161000, 0x000c0c00, 0x00090d03, 0x00101008, 0x0018140b, 0x001b1408, 0x0022160c, 0x002b1e14, 0x00291e14, 0x00241c14, 0x00201c14, 0x001d1c14, 0x001b1b12, 0x00181911, 0x00181a11, 0x001b1d14, 0x001b1d17, 0x001c1e18, 0x001c1e18, 0x00191c16, 0x00181c15, 0x00171c17, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161b15, 0x00161b15, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a13, 0x00151a13, 0x00161b14, 0x00161b14, 0x00161c16, 0x00171d18, 0x00171d18, 0x00161c17, 0x00171b16, 0x00181b17, 0x00181b16, 0x00181a15, 0x00181a15, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00171c15, 0x00171c15, 0x00161b14, 0x00161b14, 0x00141b17, 0x00141b17, 0x00151b17, 0x00151b17, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00131914, 0x00121b12, 0x00111b12, 0x00101810, 0x000e1710, 0x00101814, 0x00101814, 0x000f1713, 0x000f1713, 0x000f1713, 0x000d1510, 0x000e1611, 0x000c1410, 0x000b1410, 0x0009130e, 0x0007110c, 0x0007110c, 0x0007100c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00080f0b, 0x0008100c, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040f08, 0x00061009, 0x0007110a, 0x00061009, 0x0006100c, 0x0007110d, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x0020230a, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x003c3e0c, 0x0040400c, 0x0041420e, 0x0043440e, 0x0045470e, 0x0047480e, 0x0047480e, 0x00484910, 0x00484910, 0x00494a0f, 0x00494a0f, 0x004b4c0f, 0x004c4d0f, 0x004b4c0f, 0x004c4d0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00515110, 0x00525310, 0x00545510, 0x00565711, 0x00585810, 0x00585911, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00616112, 0x00666413, 0x00c6a218, 0x00cca519, 0x007a7014, 0x00646514, 0x00646514, 0x00646514, 0x00646414, 0x00626313, 0x00616112, 0x00606013, 0x009a8214, 0x00cca417, 0x00b09015, 0x00515110, 0x00525310, 0x004f5010, 0x004b4c10, 0x0047480f, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e07, 0x00050d07, 0x00040d06, 0x00040d05, 0x00071007, 0x00070f08, 0x00081009, 0x00081009, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050d07, 0x00070f08, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e07, 0x00060e09, 0x00040e09, 0x00080c09, 0x00080c09, 0x00070c08, 0x00050d08, 0x00040d08, 0x00070f0a, 0x00070f0a, 0x00050e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e06, 0x00070f08, 0x00070f08, 0x00081008, 0x00071007, 0x00060e07, 0x00050d07, 0x0009120c, 0x0009120c, 0x000a130c, 0x000b120c, 0x000c130c, 0x000c140c, 0x000c140d, 0x000d140e, 0x000e140e, 0x000f150f, 0x000f150f, 0x0010140f, 0x0010140f, 0x00101510, 0x00101510, 0x00131611, 0x00131611, 0x00141813, 0x00141712, 0x00141813, 0x00141813, 0x00141813, 0x00151814, 0x00151814, 0x00161914, 0x00161914, 0x00171914, 0x00171a14, 0x00171a14, 0x00181b14, 0x00181b14, 0x00181c15, 0x00181c16, 0x001a1d15, 0x001a1e14, 0x001a1d15, 0x001c1d18, 0x001c1d18, 0x001c1d18, 0x001c1d18, 0x001b1c18, 0x001b1c16, 0x001c1d17, 0x001c1d16, 0x001d1c15, 0x001c1c15, 0x001c1c15, 0x001e1d16, 0x001c1d17, 0x001d1d17, 0x00201d16, 0x00231e14, 0x00241d14, 0x00272017, 0x002a221c, 0x0028201a, 0x00241f15, 0x001c1a11, 0x00151610, 0x0010140e, 0x00242621, 0x003c3d38, 0x0036352e, 0x0027231b, 0x00282218, 0x0030261a, 0x003b3020, 0x00423420, 0x0044341b, 0x00432f16, 0x0047331a, 0x004f3820, 0x0048321a, 0x00452d13, 0x004f3014, 0x00543314, 0x00583616, 0x005c3815, 0x005f3915, 0x00633d18, 0x0065401b, 0x0066401c, 0x0067401c, 0x0068401c, 0x00693d1c, 0x00683c18, 0x00663b15, 0x00663c13, 0x00643a11, 0x00643a10, 0x0062380e, 0x005c340c, 0x0058300c, 0x00562e0a, 0x00572f0f, 0x00582e10, 0x005c3213, 0x005c3110, 0x005c300d, 0x005c2f0e, 0x005d3010, 0x005a2c0c, 0x00603210, 0x0060340c, 0x0061340d, 0x0063360f, 0x00643710, 0x0064380f, 0x0065380d, 0x00653a0c, 0x00663a0d, 0x00673b0c, 0x0067380c, 0x0066380e, 0x00673810, 0x0064370e, 0x0060340a, 0x005f3309, 0x005f340a, 0x005f340c, 0x005e320c, 0x005a2f0c, 0x00572b0b, 0x005d3213, 0x00562d0f, 0x004f290c, 0x00432207, 0x003d2107, 0x00351904, 0x00371b07, 0x003a1e0a, 0x00371c0a, 0x00351c09, 0x00341c0a, 0x002c1807, 0x002a1707, 0x002c1809, 0x002c190b, 0x0025180b, 0x00170e02, 0x000e0b00, 0x000c0f04, 0x000f0f04, 0x0018150c, 0x001b140a, 0x001f140b, 0x00251a10, 0x00271d14, 0x00272018, 0x00221d14, 0x001f1b14, 0x001d1b13, 0x001d1c15, 0x001b1c13, 0x00191c14, 0x00191c16, 0x00191c16, 0x00191d16, 0x00181d16, 0x00171c16, 0x00171c17, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00171c17, 0x00171c17, 0x00171c14, 0x00171c15, 0x00171c15, 0x00171c15, 0x00161c16, 0x00161c16, 0x00171d16, 0x00181f18, 0x001b1f18, 0x00191c17, 0x00181c15, 0x00181c16, 0x00181c16, 0x00181c14, 0x00171b13, 0x00171b13, 0x00171b13, 0x00161c13, 0x00161c13, 0x00171c14, 0x00171c14, 0x00161c16, 0x00151b15, 0x00151c16, 0x00151c16, 0x00151c15, 0x00141b15, 0x00141a14, 0x00141b15, 0x00161c17, 0x00151c16, 0x00151c16, 0x00151c16, 0x00151c16, 0x00161b15, 0x00161b15, 0x00151a14, 0x00141914, 0x00141b13, 0x00141b13, 0x00131b13, 0x00111912, 0x00121815, 0x00121814, 0x00121814, 0x00101814, 0x00101814, 0x00101813, 0x000e1611, 0x000e1611, 0x000c1510, 0x000a140f, 0x0008120d, 0x0008120c, 0x0007100b, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00070d09, 0x0008100c, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040e08, 0x00040f08, 0x00051008, 0x00061009, 0x0006100c, 0x0007110d, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x0038380c, 0x00393b0d, 0x003c3e0c, 0x003e400c, 0x0041420e, 0x0044450e, 0x0045470e, 0x0047480e, 0x0048490f, 0x00494a10, 0x004b4c10, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004d4e0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004d4e10, 0x004f5010, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00545511, 0x00555611, 0x00565711, 0x00585910, 0x00595a12, 0x005c5c12, 0x005c5d11, 0x005d5e12, 0x00606013, 0x00606013, 0x00666413, 0x00c6a218, 0x00cca519, 0x00796f14, 0x00646514, 0x00646514, 0x00646414, 0x00636414, 0x00626313, 0x00606013, 0x005e5f13, 0x009a8214, 0x00cca417, 0x00b09015, 0x00515110, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e06, 0x00050e06, 0x00060e08, 0x00060e08, 0x00050e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00070f08, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e07, 0x00060e09, 0x00040e09, 0x00080c09, 0x00080c09, 0x00070c08, 0x00040c08, 0x00050d08, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e06, 0x00070f08, 0x00081009, 0x00081108, 0x00081008, 0x00081008, 0x00081009, 0x000b130c, 0x000c140d, 0x000d140c, 0x000e140c, 0x000f140d, 0x000f140d, 0x000f140e, 0x000e140f, 0x000f150f, 0x00101610, 0x00101610, 0x00101510, 0x00101510, 0x00111611, 0x00111611, 0x00151814, 0x00151814, 0x00171914, 0x00171914, 0x00171814, 0x00171814, 0x00171814, 0x00171814, 0x00181915, 0x00181915, 0x00181914, 0x00181814, 0x00181914, 0x00181a14, 0x00181a14, 0x00191b15, 0x00191b15, 0x001a1c15, 0x001c1e15, 0x001b1d14, 0x001c1d14, 0x001d1d17, 0x001d1d17, 0x001d1d17, 0x001d1d17, 0x001c1c18, 0x001c1c17, 0x001d1d17, 0x001d1d16, 0x001f1e16, 0x001e1c14, 0x001e1c14, 0x001e1c15, 0x001e1d17, 0x001f1c16, 0x00201c15, 0x00201c12, 0x00211b13, 0x00231c14, 0x00241c16, 0x00231c15, 0x001f1910, 0x0019170e, 0x0014130c, 0x0012140e, 0x0020241e, 0x00373831, 0x00383730, 0x002b271f, 0x001f1a10, 0x002c261c, 0x00393023, 0x003c311f, 0x0041341d, 0x0045341c, 0x00453218, 0x0047331a, 0x0049351c, 0x00452c14, 0x00482910, 0x00543118, 0x005c381c, 0x005c3716, 0x00603917, 0x00603b18, 0x00613c18, 0x00643d1b, 0x00643e1a, 0x00653d1b, 0x00673d1a, 0x006a3c19, 0x00663b15, 0x00663c13, 0x00653b12, 0x00653b10, 0x00633a10, 0x0060370c, 0x005c340d, 0x005e3412, 0x005d3410, 0x005e340e, 0x0063370f, 0x0067390f, 0x00673a0f, 0x006a3b12, 0x006a3b12, 0x0064350c, 0x0067380f, 0x0064350b, 0x0065380e, 0x0063350e, 0x00643711, 0x0063360f, 0x0062380c, 0x0062380b, 0x0062380b, 0x0062370a, 0x0061370c, 0x0062370e, 0x0061360d, 0x0060350c, 0x005d3409, 0x005c3208, 0x005f340a, 0x005e340b, 0x005b310b, 0x005b300d, 0x005c3110, 0x00582e0f, 0x00552c0d, 0x004c280c, 0x00442408, 0x003e2208, 0x00351904, 0x00361a06, 0x003a1e0b, 0x00381c0a, 0x00331b09, 0x00301b08, 0x00281704, 0x00281808, 0x002a1809, 0x0028170b, 0x00221509, 0x00160d04, 0x000e0a00, 0x000c0e02, 0x00121207, 0x0019150c, 0x001b150b, 0x0021170c, 0x00251c12, 0x00241d13, 0x00241d15, 0x00231c14, 0x001f1a13, 0x001d1b13, 0x001c1c14, 0x001a1b14, 0x00181c14, 0x00191c15, 0x00191c16, 0x00191c16, 0x00181d16, 0x00181c16, 0x00181c18, 0x00181c18, 0x00181c18, 0x00181c18, 0x00171c16, 0x00171c16, 0x00161b14, 0x00161b14, 0x00171c17, 0x00171c17, 0x00171c15, 0x00171c14, 0x00171c14, 0x00171c14, 0x00161c14, 0x00161d14, 0x00171d14, 0x00171e15, 0x00181c15, 0x00191c15, 0x00191c15, 0x00191c15, 0x00191c15, 0x00191d14, 0x00191c13, 0x00191c13, 0x00191c13, 0x00181d13, 0x00181d13, 0x00181d13, 0x00181d14, 0x00181f16, 0x00161d14, 0x00151c13, 0x00151c13, 0x00151c15, 0x00151c15, 0x00141b14, 0x00151c16, 0x00161c17, 0x00161c17, 0x00171d18, 0x00181e18, 0x00181d18, 0x00181c18, 0x00181c18, 0x00171c16, 0x00161b15, 0x00141c14, 0x00141c14, 0x00141b13, 0x00141b13, 0x00151c15, 0x00151c16, 0x00151b16, 0x00131914, 0x00101814, 0x00101814, 0x00101814, 0x000e1611, 0x000c1610, 0x000c1610, 0x000b1510, 0x000a140f, 0x0008110c, 0x0009110c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00050d09, 0x00080f0b, 0x0008100b, 0x0008100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00061009, 0x0006100c, 0x0007110d, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0005100a, 0x0005100a, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00050d09, 0x00060d09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x00191c08, 0x00202308, 0x0020230a, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0045470e, 0x0048490f, 0x00494a10, 0x004b4c10, 0x004b4c0f, 0x004d4e0f, 0x004d4e10, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x004f5010, 0x00505010, 0x00515110, 0x00515110, 0x00505010, 0x00525310, 0x00515110, 0x00525310, 0x00535410, 0x00545510, 0x00555611, 0x00565711, 0x00585810, 0x00595a11, 0x005b5b12, 0x005c5c11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00616112, 0x00666413, 0x00c6a218, 0x00cca519, 0x00796f14, 0x00646414, 0x00646414, 0x00646414, 0x00636414, 0x00616112, 0x00616112, 0x005e5f13, 0x009a8214, 0x00cca417, 0x00b09015, 0x00515110, 0x00515110, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00050e07, 0x00060e07, 0x00050e08, 0x00050e08, 0x00040d07, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x0008100b, 0x00070f09, 0x00070f09, 0x00040d08, 0x00050d08, 0x00050e08, 0x0008100b, 0x00060e09, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e07, 0x00060e09, 0x00050e09, 0x00080d09, 0x00080d09, 0x00070d09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070e0b, 0x00070f09, 0x00070f09, 0x00070f08, 0x0008100a, 0x0008100a, 0x0009120b, 0x000a130c, 0x000b130b, 0x000c140c, 0x000c140d, 0x000c140d, 0x000f140e, 0x0010140e, 0x0011140f, 0x0013140f, 0x00111510, 0x00111510, 0x00111510, 0x00121510, 0x00121510, 0x00141510, 0x00141610, 0x00141611, 0x00141611, 0x00181914, 0x00181914, 0x00191b15, 0x00181a14, 0x00181814, 0x00181814, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181914, 0x00181914, 0x00181a14, 0x00181a14, 0x00181a14, 0x00191a14, 0x00191b14, 0x001b1c16, 0x001c1e18, 0x001c1c14, 0x001c1c14, 0x001c1c15, 0x001d1e16, 0x001e1d15, 0x001f1e15, 0x00201d17, 0x00201d17, 0x00201e16, 0x00201e15, 0x00201e14, 0x00201e14, 0x00201e14, 0x00201e14, 0x001f1e16, 0x00201d15, 0x00201c14, 0x00201b13, 0x00201b13, 0x00211b14, 0x00221c14, 0x00221c15, 0x001b180f, 0x0018150d, 0x0014140c, 0x0012140c, 0x001c1d17, 0x0034342c, 0x0036342c, 0x002c2920, 0x00201c12, 0x00241e16, 0x002e271c, 0x00352c1b, 0x003c301a, 0x00483820, 0x0048361c, 0x00443015, 0x00473018, 0x0049301b, 0x004a2c17, 0x004c2c16, 0x004c2a13, 0x00502c10, 0x00603a1b, 0x005f3918, 0x005f3815, 0x00603a16, 0x00623b17, 0x00633b17, 0x00643b17, 0x00673c18, 0x00643c14, 0x00653b12, 0x00663b11, 0x00663a10, 0x00663a10, 0x00643a10, 0x0063380f, 0x00643910, 0x00673910, 0x00693b10, 0x006f4013, 0x00734012, 0x00724010, 0x00734111, 0x00754313, 0x00723f10, 0x00713d0e, 0x006d390b, 0x006b380c, 0x0068350c, 0x0068370f, 0x0064370c, 0x0063360a, 0x00623508, 0x00613608, 0x005f3408, 0x0060340b, 0x00623710, 0x0060360e, 0x005e340c, 0x005d330a, 0x005d330a, 0x0061360d, 0x005c3109, 0x00572e07, 0x00582f09, 0x005c3311, 0x00542b0b, 0x00522c0c, 0x00492608, 0x00412106, 0x003c2007, 0x00381904, 0x00351804, 0x00381c0a, 0x00341c0b, 0x002f1b08, 0x00281704, 0x00241504, 0x00241504, 0x00271709, 0x0026170b, 0x0020140a, 0x00150c03, 0x000e0901, 0x000d0c04, 0x0014130c, 0x0018140f, 0x0019140e, 0x00211a0f, 0x00241d13, 0x00241d13, 0x00211c13, 0x00201c14, 0x00201b14, 0x001e1b14, 0x001c1b15, 0x001b1c15, 0x00191c15, 0x00191c16, 0x00191c16, 0x00191c17, 0x00181c17, 0x00191d18, 0x00181c18, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161c16, 0x00161c16, 0x00151c14, 0x00151b14, 0x00181e16, 0x00181e16, 0x00181e15, 0x00181e15, 0x00171d14, 0x00161d14, 0x00161d14, 0x00161d14, 0x00171e14, 0x00161d14, 0x00171c13, 0x00181c14, 0x00191c14, 0x00181c14, 0x00191c14, 0x00191c14, 0x00191c14, 0x00191c14, 0x00191c14, 0x00181c14, 0x00181c14, 0x00191c14, 0x00181d14, 0x00181f15, 0x00182016, 0x00171d14, 0x00171d14, 0x00181d16, 0x00181c16, 0x00181c15, 0x00181c16, 0x00181d17, 0x00181d16, 0x00181d17, 0x00181e18, 0x00181d18, 0x00191d18, 0x00191e18, 0x00191d18, 0x00171c15, 0x00181c16, 0x00181d17, 0x00181c17, 0x00171c16, 0x00161c17, 0x00151d17, 0x00141c16, 0x00131a14, 0x00101813, 0x00101813, 0x00101813, 0x00101813, 0x000e1711, 0x000d1610, 0x000d1710, 0x000d1610, 0x000a130d, 0x000a130d, 0x000a120d, 0x0009110c, 0x0009110c, 0x0009110c, 0x0008100b, 0x0008100b, 0x00060f0a, 0x00090f0b, 0x00080f0b, 0x00070f0a, 0x0005100a, 0x00060f0a, 0x00060f0a, 0x00060f0a, 0x00060f0a, 0x00050e08, 0x00050e08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f0b, 0x00040e0a, 0x00040e0a, 0x00040f0a, 0x0005100a, 0x00060f0a, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x0006100a, 0x00050e09, 0x00030c08, 0x00040e09, 0x0008100b, 0x0008100b, 0x0008100b, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x00141810, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x00393b0c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x0048490f, 0x004b4c10, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00515110, 0x00515110, 0x00525310, 0x00525310, 0x00525310, 0x00525310, 0x00535410, 0x00535410, 0x00535410, 0x00545510, 0x00555611, 0x00555611, 0x00565710, 0x00585910, 0x00585911, 0x00595a12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x00606013, 0x00606013, 0x00616112, 0x00666413, 0x00c6a218, 0x00cca519, 0x00796f14, 0x00646414, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x009a8114, 0x00cca417, 0x00b09015, 0x004f5010, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0c, 0x00393b0c, 0x0034350c, 0x0030310c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00070f0a, 0x0008100c, 0x00050d09, 0x00040c08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00070f0a, 0x0008100b, 0x00081009, 0x0008110b, 0x0009120c, 0x000a130c, 0x000c140d, 0x000c140c, 0x000c150c, 0x000e150d, 0x000e150d, 0x0011140f, 0x0013130f, 0x00131410, 0x00141410, 0x00141511, 0x00141712, 0x00141712, 0x00141712, 0x00141712, 0x00171812, 0x00171812, 0x00171812, 0x00171812, 0x00181813, 0x00181a14, 0x001a1b15, 0x00181914, 0x00181813, 0x00181813, 0x00181a14, 0x00181a14, 0x00191a14, 0x00191a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00191c18, 0x001c1d18, 0x001c1c17, 0x001c1c14, 0x001c1c15, 0x00201e17, 0x00201e15, 0x00221e15, 0x00231e18, 0x00231e17, 0x00231e16, 0x00231e14, 0x00201e14, 0x00201e14, 0x00201e14, 0x00201e14, 0x00201d14, 0x00201d14, 0x00201d14, 0x00211c14, 0x00221c14, 0x00211c14, 0x00211c14, 0x00201c14, 0x0018160e, 0x0016140c, 0x0014140b, 0x0012130a, 0x00181810, 0x002a2a22, 0x00302e25, 0x0029281f, 0x0026231a, 0x00201b13, 0x00221b10, 0x00342c1d, 0x003a2f1d, 0x00453722, 0x004a3821, 0x00453117, 0x0047301a, 0x0049301c, 0x004c301d, 0x004d311c, 0x0053341d, 0x0056351a, 0x005e3b1c, 0x005e3818, 0x005f3715, 0x00623815, 0x00633b16, 0x00643c18, 0x00653c18, 0x00643c17, 0x00633b14, 0x00643911, 0x00673a10, 0x00673a10, 0x00683b10, 0x006b3e14, 0x006c3e11, 0x00704010, 0x00724312, 0x00774416, 0x007c4a19, 0x00814c18, 0x0078440e, 0x007d4813, 0x00804914, 0x007e4712, 0x007f4712, 0x007b4310, 0x0078400f, 0x00733c0e, 0x006f3a0d, 0x006c380a, 0x00683808, 0x00663608, 0x00643508, 0x0060340a, 0x0060330c, 0x0061340e, 0x0060350f, 0x0061360f, 0x0062370f, 0x0062370f, 0x00643810, 0x005a3007, 0x00542c05, 0x00562e08, 0x0059300e, 0x00522a0a, 0x004d280a, 0x00442005, 0x003d1d04, 0x003e2008, 0x003b1c08, 0x00361806, 0x00361c0c, 0x002d1809, 0x00271607, 0x00221404, 0x00231404, 0x00231404, 0x00241508, 0x00241508, 0x001e1409, 0x00150c04, 0x00130c06, 0x0015100c, 0x00181310, 0x00181310, 0x0018140f, 0x001d180f, 0x001f1b10, 0x001f1c11, 0x001e1b12, 0x001e1a13, 0x001d1b14, 0x001c1b14, 0x001c1b16, 0x001b1c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c17, 0x00181c18, 0x00191d18, 0x00181d18, 0x00161b15, 0x00161c17, 0x00161c17, 0x00161c15, 0x00161c15, 0x00161c15, 0x00171d16, 0x00171e14, 0x00171e14, 0x00181f15, 0x00171e14, 0x00171e14, 0x00161d14, 0x00161d14, 0x00161d14, 0x00161d14, 0x00161d14, 0x00161c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00171e15, 0x00171e15, 0x00181e15, 0x00181e15, 0x001c1e18, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d15, 0x00181d14, 0x001a1f16, 0x001a1f15, 0x00191e16, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00161d18, 0x00151e18, 0x00141d17, 0x00131b14, 0x00121a14, 0x00111913, 0x00111913, 0x00111913, 0x00101811, 0x000e170e, 0x000e1710, 0x000e1710, 0x000c140d, 0x000c140d, 0x000c140e, 0x000c140f, 0x000c140f, 0x000a120e, 0x0008100b, 0x0008100b, 0x0008100b, 0x00090f0b, 0x00080f0b, 0x00070f0a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x0005100a, 0x00070f0a, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060f0a, 0x00050f0a, 0x0005100a, 0x00040e09, 0x00040d08, 0x0007100b, 0x00070f0a, 0x00070f0a, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00515110, 0x00515110, 0x00525310, 0x00535410, 0x00535410, 0x00545510, 0x00545511, 0x00545510, 0x00545510, 0x00545510, 0x00545510, 0x00555611, 0x00555611, 0x00555611, 0x00565711, 0x00585810, 0x00585810, 0x00585911, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00616112, 0x00626312, 0x00666414, 0x00c6a219, 0x00cca519, 0x00796f14, 0x00646414, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005d5e12, 0x009a8114, 0x00cca417, 0x00b09014, 0x00505010, 0x00515110, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040c06, 0x00050e08, 0x00050d07, 0x00050e08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00050d08, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e0a, 0x00070f0a, 0x00050d09, 0x00050d09, 0x00040c08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00070e0c, 0x0008100b, 0x0008100c, 0x0008100a, 0x0009120c, 0x000a130c, 0x000c130d, 0x000c140d, 0x000d140c, 0x000e150d, 0x0010150d, 0x0010150e, 0x00121510, 0x00131410, 0x00141511, 0x00151512, 0x00151713, 0x00161814, 0x00161814, 0x00161814, 0x00171814, 0x00171812, 0x00171812, 0x00181a14, 0x00181a14, 0x00181813, 0x00181a14, 0x00191b14, 0x00181a14, 0x00181813, 0x00181813, 0x00181914, 0x00181914, 0x00181a14, 0x00181a14, 0x00181914, 0x00181914, 0x00191a14, 0x001a1b15, 0x00191a14, 0x00181914, 0x00181a14, 0x00191c17, 0x001b1c16, 0x001c1b16, 0x001c1b14, 0x00201c17, 0x00241e18, 0x00241d16, 0x00241e14, 0x00241d16, 0x00241d16, 0x00241e14, 0x00241e13, 0x00221e14, 0x00201f14, 0x00201e14, 0x00201e14, 0x00211e14, 0x00211e14, 0x00201e14, 0x00221d14, 0x00231c14, 0x00221c14, 0x00211c14, 0x001e1a13, 0x0017150c, 0x0017140c, 0x0014140a, 0x00141209, 0x0015150b, 0x001f1e15, 0x0029271f, 0x0026241c, 0x00201e15, 0x00201d14, 0x001a180e, 0x00231c11, 0x0032281c, 0x003a2d1d, 0x0041321c, 0x00402e16, 0x0046301b, 0x004b3321, 0x004d3423, 0x004f3420, 0x0051341d, 0x0055351c, 0x005c3a1c, 0x005d3818, 0x005e3614, 0x00603614, 0x00643c16, 0x00663f19, 0x00643d18, 0x00643c17, 0x00623b14, 0x00643911, 0x00663910, 0x00683a10, 0x006b3c11, 0x00714114, 0x00754415, 0x00794715, 0x007b4814, 0x007d4914, 0x00814d17, 0x00824b11, 0x007c450b, 0x007e450c, 0x007f460c, 0x0081470e, 0x00854a11, 0x00834811, 0x007f4610, 0x007c4410, 0x00753f0d, 0x00703c0a, 0x006d3b08, 0x006c380a, 0x0069370b, 0x0064340c, 0x0063340c, 0x0064370f, 0x0062350d, 0x005f330b, 0x0060340c, 0x0060340c, 0x0062350e, 0x005b300a, 0x00562e09, 0x00522a07, 0x00542c0c, 0x0051280b, 0x004e280c, 0x00452209, 0x0041200b, 0x003e200b, 0x003c1e0c, 0x00381c0c, 0x00341d0d, 0x00281608, 0x00221408, 0x00201306, 0x00211407, 0x00211407, 0x00221407, 0x00201407, 0x001d1208, 0x001a1008, 0x0018110a, 0x0017130c, 0x0018130e, 0x0018130f, 0x0019140f, 0x001b170f, 0x001d1a11, 0x001c1912, 0x001c1911, 0x001a1811, 0x001b1812, 0x001b1a15, 0x001b1b16, 0x001b1c16, 0x001a1c16, 0x00191c16, 0x00181c15, 0x00181c16, 0x00181c18, 0x00181c18, 0x00181c18, 0x00161c16, 0x00161c17, 0x00161c17, 0x00161c16, 0x00171e17, 0x00171d17, 0x00181e17, 0x00151c14, 0x00151c14, 0x00161c16, 0x00161c16, 0x00151c14, 0x00151c14, 0x00151c15, 0x00151c15, 0x00151c16, 0x00151c15, 0x00161c15, 0x00171c15, 0x00171c15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00171c15, 0x00171c15, 0x00161c16, 0x00171d17, 0x00171d17, 0x00171d16, 0x001b1d17, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d15, 0x00181d14, 0x001a1f16, 0x001a1f16, 0x001a1f17, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00171e18, 0x00161e18, 0x00151d17, 0x00141c15, 0x00141c15, 0x00131b14, 0x00141c15, 0x00121a14, 0x00111a12, 0x00101810, 0x000f1810, 0x000f1811, 0x000c140e, 0x000c140e, 0x000c140f, 0x000c1410, 0x000c1410, 0x000b130f, 0x0008100c, 0x0008100c, 0x0008100c, 0x0009100c, 0x0008100b, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00050d07, 0x00040d07, 0x00050d08, 0x00050d08, 0x00050d09, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x00070f0a, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070f0a, 0x0005100a, 0x00040f09, 0x0006100b, 0x0006100b, 0x00050f0a, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a0f, 0x004c4d0f, 0x004f5010, 0x00505010, 0x00525310, 0x00535410, 0x00545510, 0x00555611, 0x00555611, 0x00565711, 0x00565710, 0x00565710, 0x00585810, 0x00585810, 0x00585810, 0x00585810, 0x00565710, 0x00585810, 0x00585911, 0x00585910, 0x00595a11, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00616112, 0x00626312, 0x00626313, 0x00666414, 0x00c6a219, 0x00cca519, 0x00796f14, 0x00646414, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606012, 0x005d5e12, 0x009a8114, 0x00cca417, 0x00b09014, 0x00505010, 0x00515110, 0x004d4e0f, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040c06, 0x00040d07, 0x00040d07, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00050e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00070f0a, 0x00070f0b, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100c, 0x0009110d, 0x000b130e, 0x000b130c, 0x000a130c, 0x000c140e, 0x000f150f, 0x000f150f, 0x0010160f, 0x00111710, 0x00131610, 0x00141710, 0x00151813, 0x00151813, 0x00171814, 0x00171814, 0x00171814, 0x00181a15, 0x00181a15, 0x00181a15, 0x00181a15, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181813, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181913, 0x00181914, 0x00181913, 0x00181813, 0x00181914, 0x00181b16, 0x001a1b15, 0x001b1a15, 0x001b1a14, 0x00201c16, 0x00231e18, 0x00241c16, 0x00241d14, 0x00241d16, 0x00241d14, 0x00241d13, 0x00241d12, 0x00241f13, 0x00242013, 0x00231f13, 0x00231f12, 0x00231f12, 0x00231f12, 0x00221e12, 0x00221d14, 0x00231c14, 0x00231c14, 0x00231c14, 0x001d1912, 0x001a1810, 0x0018150d, 0x0015130a, 0x00141208, 0x00131308, 0x0017150d, 0x001f1c14, 0x00211f17, 0x001d1c13, 0x001c1c13, 0x001c1b13, 0x0017130c, 0x00241c14, 0x0032281b, 0x003b2f19, 0x003c2e16, 0x0044311c, 0x00452f1e, 0x0048321d, 0x004a321c, 0x0051371f, 0x0055371d, 0x005d3a1e, 0x005e3818, 0x005e3614, 0x005e3411, 0x00633914, 0x00643d18, 0x00663e18, 0x00643c17, 0x00653c18, 0x00663c16, 0x00693d14, 0x006d4014, 0x00714014, 0x00784518, 0x007d4918, 0x007c4714, 0x007b4511, 0x0078420d, 0x007c4510, 0x00854d14, 0x00844910, 0x007c420a, 0x007c4109, 0x007e420a, 0x0081450c, 0x00854a10, 0x0081470e, 0x007c440c, 0x007c440e, 0x0078420c, 0x00733f09, 0x00703c0c, 0x006e3b0c, 0x006a380e, 0x0066360e, 0x0064360d, 0x0063340c, 0x0060340b, 0x0060340c, 0x0060340b, 0x005d3009, 0x005c310d, 0x005c3311, 0x00582f0f, 0x0052290d, 0x004c2409, 0x00462008, 0x0044200a, 0x0041200d, 0x003a1c0a, 0x003a1c0d, 0x00351c0e, 0x002a170a, 0x00241408, 0x001e1307, 0x001c1106, 0x001d1308, 0x001f1408, 0x00201408, 0x001f1408, 0x001e1409, 0x001c1209, 0x0019140b, 0x0017140b, 0x0016120a, 0x0016120a, 0x0018140d, 0x0019180f, 0x001c1a13, 0x001c1a14, 0x001c1a14, 0x001a1913, 0x00191913, 0x001a1a14, 0x001a1b15, 0x001b1c16, 0x001a1c16, 0x00181c15, 0x00181a14, 0x00181b15, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161c16, 0x00151c15, 0x00161c17, 0x00161c17, 0x00161c16, 0x00161c17, 0x00151c16, 0x00141b15, 0x00141b15, 0x00151c17, 0x00151c16, 0x00141b15, 0x00141a15, 0x00141c15, 0x00141c15, 0x00141c15, 0x00131b14, 0x00131a14, 0x00141a14, 0x00151a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00151b15, 0x00151b15, 0x00161c16, 0x00161c17, 0x00161c16, 0x00151b15, 0x00181b14, 0x00181b14, 0x00181b14, 0x00181b14, 0x00181c15, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d15, 0x00181d14, 0x001a1f16, 0x001b2017, 0x001a1f18, 0x00191d18, 0x00191d18, 0x001a1f19, 0x00191e18, 0x00181e18, 0x00171f18, 0x00171f18, 0x00171f18, 0x00161e18, 0x00161e18, 0x00161e18, 0x00131b14, 0x00121a12, 0x00121b12, 0x00111a12, 0x000f1811, 0x000e1710, 0x000e1710, 0x000e1610, 0x000d1510, 0x000d1510, 0x000c1410, 0x000b130f, 0x000a120e, 0x000a120e, 0x0009120e, 0x0008120d, 0x0005110b, 0x0005110b, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f09, 0x00070f08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060e09, 0x00070f0a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x00070f0a, 0x00080e0a, 0x00070d09, 0x00070d09, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0007110c, 0x00040c08, 0x00050d08, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a0f, 0x004c4d0f, 0x004b4c10, 0x004d4e10, 0x00505010, 0x00525311, 0x00535411, 0x00545510, 0x00555610, 0x00565711, 0x00585812, 0x00585811, 0x00585912, 0x00585912, 0x00585911, 0x00585911, 0x00585912, 0x00595a11, 0x00595a11, 0x00595a12, 0x00595a12, 0x005c5c12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005d5d11, 0x00606012, 0x00606013, 0x00616113, 0x00626213, 0x00636312, 0x00646412, 0x00646414, 0x00847714, 0x00c8a318, 0x00cca519, 0x00797014, 0x00646414, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606012, 0x005d5e12, 0x009a8114, 0x00cca417, 0x00b09014, 0x00505010, 0x00515110, 0x004c4d10, 0x00494a10, 0x0045470e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0020230a, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00070f08, 0x00040d07, 0x00040c07, 0x00040d08, 0x00040d08, 0x00070f0a, 0x00060e0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x0008100b, 0x0008100c, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060f08, 0x00060f08, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050e08, 0x00060d08, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0009110c, 0x000c140e, 0x000c140f, 0x000c140e, 0x000c140e, 0x000d150f, 0x00101711, 0x00101711, 0x00131811, 0x00141811, 0x00141811, 0x00151812, 0x00181814, 0x00181814, 0x00181914, 0x00181915, 0x00181a15, 0x00181a15, 0x00181a15, 0x00181a15, 0x00181a14, 0x00181a13, 0x00181a13, 0x00181a13, 0x00181a13, 0x00181913, 0x00181a14, 0x00181a14, 0x00181a13, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00171813, 0x00171812, 0x00171813, 0x00181813, 0x00181813, 0x00181a14, 0x001a1b15, 0x001b1a15, 0x001a1a15, 0x001c1c15, 0x001f1d16, 0x00201c14, 0x00211c13, 0x00241e14, 0x00241e13, 0x00241e13, 0x00241e11, 0x00241f12, 0x00261f12, 0x00251e11, 0x00251d11, 0x00241e11, 0x00241e11, 0x00241e11, 0x00241e11, 0x00241d13, 0x00231c15, 0x00231c14, 0x001f1a13, 0x001c1810, 0x0018160d, 0x0015140a, 0x00131308, 0x00141408, 0x0014130a, 0x0017150d, 0x001a1910, 0x001b1b12, 0x001b1b12, 0x001b1a13, 0x0015140d, 0x0016120c, 0x0020190f, 0x00352c1c, 0x00372b18, 0x0040311e, 0x0040301c, 0x0043301c, 0x0046321b, 0x0050381f, 0x0051361b, 0x00583418, 0x005b3616, 0x005d3612, 0x00603611, 0x00633914, 0x00653d18, 0x00673d18, 0x00673c18, 0x00683d19, 0x00683d17, 0x006f4319, 0x00714419, 0x00774418, 0x007c4718, 0x00804919, 0x007c4614, 0x007a4411, 0x00753d0b, 0x00743c09, 0x007d440f, 0x007c410c, 0x007e420d, 0x007e420d, 0x007c400c, 0x007d430c, 0x00834b10, 0x007f480f, 0x007c450e, 0x007a440d, 0x0078440d, 0x00743f08, 0x00703c08, 0x006e3a0a, 0x006c380e, 0x0069370f, 0x0066360e, 0x0067370f, 0x0063340b, 0x0061340b, 0x0060340b, 0x005c300a, 0x005c2f0c, 0x00582f0d, 0x00542c0e, 0x0050270b, 0x00482006, 0x00411c04, 0x00411f09, 0x003b1c0a, 0x00341908, 0x00361c10, 0x002c150c, 0x00201005, 0x001e1107, 0x001c1108, 0x001a1007, 0x001b1208, 0x001c1308, 0x001e1309, 0x001f1409, 0x001e1409, 0x001b1309, 0x0019140b, 0x0018140b, 0x0017140a, 0x0017130b, 0x0018160e, 0x0019170f, 0x001c1913, 0x001b1a15, 0x001a1b15, 0x001a1914, 0x00181a14, 0x00181a14, 0x00181c14, 0x00181c16, 0x00191c16, 0x001a1c16, 0x00191a14, 0x00181b15, 0x00171c17, 0x00161c17, 0x00151c16, 0x00141c15, 0x00131b14, 0x00141a14, 0x00151c15, 0x00151a14, 0x00151b16, 0x00141a16, 0x00141a15, 0x00141915, 0x00131915, 0x00131915, 0x00141a16, 0x00141a16, 0x00141c15, 0x00141c15, 0x00141c15, 0x00121a14, 0x00121913, 0x00131813, 0x00131813, 0x00121813, 0x00131813, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00141814, 0x00141814, 0x00141814, 0x00141914, 0x00141a14, 0x00141a14, 0x00141a14, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a14, 0x00161b14, 0x00171c15, 0x00181d16, 0x00181c16, 0x00181d16, 0x001a1e18, 0x00191d17, 0x00181d16, 0x00181d18, 0x00191d18, 0x001b201a, 0x001b201a, 0x00181e18, 0x00181e18, 0x00181e18, 0x00181e18, 0x00171f18, 0x00171f18, 0x00161e18, 0x00141c16, 0x00131b14, 0x00141c15, 0x00141b15, 0x00101812, 0x00101812, 0x00111812, 0x00101610, 0x000f1410, 0x000f1410, 0x000e1510, 0x000d1410, 0x000b120e, 0x000a120e, 0x0009130e, 0x0009130e, 0x0006100b, 0x0005110b, 0x0006100a, 0x00070f0b, 0x00070f0b, 0x00070f0b, 0x0008100b, 0x00081009, 0x00081009, 0x00070f09, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x00060f0a, 0x00070e0a, 0x00070d09, 0x00070e09, 0x0007100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040c08, 0x00060e09, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x003e400d, 0x0043440e, 0x0045470e, 0x00494a0f, 0x004c4d0f, 0x00685e10, 0x00aa8b14, 0x00af8e14, 0x00af8f14, 0x00b09014, 0x00b09014, 0x00b09014, 0x00b09115, 0x00b09115, 0x00b09115, 0x00b09115, 0x00b19315, 0x00b19215, 0x00b19215, 0x00b19215, 0x00b19216, 0x00b29316, 0x00b29316, 0x00b29316, 0x00b29316, 0x00b39316, 0x00b39317, 0x00b39317, 0x00b39417, 0x00b49417, 0x00b49417, 0x00b49417, 0x00b49417, 0x00b49517, 0x00b49518, 0x00b49518, 0x00b59518, 0x00c4a119, 0x00cca519, 0x00c4a019, 0x00746c14, 0x00646514, 0x00646414, 0x00636414, 0x00636413, 0x00616112, 0x00606012, 0x005d5e12, 0x009b8314, 0x00cca417, 0x00b09014, 0x00505010, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450d, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x0008110a, 0x0008110a, 0x000a130c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000e1610, 0x000e1610, 0x000f1811, 0x00101812, 0x00141813, 0x00141811, 0x00141912, 0x00141910, 0x00181813, 0x00181813, 0x00181914, 0x00181a14, 0x00191b14, 0x001a1b14, 0x00191b14, 0x00181a12, 0x00181a12, 0x00181910, 0x0017180f, 0x00181910, 0x00181910, 0x00181b12, 0x00181b12, 0x00181a12, 0x00161811, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00181814, 0x00181814, 0x00181813, 0x00181a14, 0x00181a14, 0x001a1815, 0x00181a14, 0x001b1c15, 0x001f1e14, 0x00211c13, 0x00221c11, 0x00251d11, 0x00261d11, 0x00261d11, 0x00261d11, 0x00271e10, 0x00271e10, 0x00271f0f, 0x00271e10, 0x00271e10, 0x00271e10, 0x00261d10, 0x00241c10, 0x00241c12, 0x00241c12, 0x00241e14, 0x00231c14, 0x001f1910, 0x001b180e, 0x0018170c, 0x0015150a, 0x00141408, 0x00141408, 0x00141408, 0x00191810, 0x00181810, 0x00181810, 0x00181710, 0x00161510, 0x00161410, 0x0016120a, 0x00282217, 0x00372d1f, 0x003f3320, 0x00453823, 0x0043321d, 0x0043301a, 0x004e3820, 0x004d341b, 0x0055341a, 0x005d3b1c, 0x005e3815, 0x005e3812, 0x00623a13, 0x00663c16, 0x00673c16, 0x00693c18, 0x00683c18, 0x00683c16, 0x0070441c, 0x006f4117, 0x0079481b, 0x00804a1e, 0x007c4619, 0x00763e11, 0x00733c0c, 0x00743c0d, 0x00703808, 0x00743b0b, 0x00773d0d, 0x00733909, 0x00753c0a, 0x00773e0c, 0x00743e0a, 0x00744009, 0x0074410c, 0x00764310, 0x0074410d, 0x00703d09, 0x006d3905, 0x006c3907, 0x006c3908, 0x006c390d, 0x0068360d, 0x0068370e, 0x00683810, 0x00603108, 0x00603208, 0x005c2f08, 0x005a2d08, 0x00592d0b, 0x00562c0c, 0x00542c0d, 0x004c2409, 0x00421d03, 0x00432007, 0x003c1e08, 0x00351c0a, 0x0030190c, 0x0025130c, 0x001e0d06, 0x001c1007, 0x001b1108, 0x00191108, 0x00191208, 0x00191208, 0x001c1309, 0x001c1309, 0x001c1208, 0x001c1307, 0x001a130b, 0x0019140b, 0x0018140b, 0x00171409, 0x0018140c, 0x001b170f, 0x001c1810, 0x001c1914, 0x001b1a17, 0x00181915, 0x00181915, 0x00181915, 0x00181a15, 0x00141a14, 0x00141c14, 0x00161b14, 0x00171a14, 0x00181712, 0x00161811, 0x00141812, 0x00111812, 0x00131915, 0x00131b16, 0x00121a15, 0x00131914, 0x00141914, 0x00151a14, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00131914, 0x00131914, 0x00131914, 0x00131914, 0x00121a14, 0x00121a14, 0x00111913, 0x00101812, 0x00121812, 0x00131712, 0x00121712, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00121511, 0x00131511, 0x00131511, 0x00131511, 0x00131511, 0x00141612, 0x00141813, 0x00131914, 0x00131b14, 0x00131b14, 0x00131b14, 0x00131b14, 0x00131a14, 0x00141a14, 0x00141b14, 0x00151c15, 0x00161c15, 0x00181b17, 0x00191c18, 0x00191c18, 0x00181b17, 0x00171c17, 0x00191e19, 0x001a1f18, 0x001a1f16, 0x001a1f16, 0x001a1f18, 0x001a201a, 0x001a1f19, 0x00181f17, 0x00181f17, 0x00181f17, 0x00161c15, 0x00151c14, 0x00151b17, 0x00151b17, 0x00141a16, 0x00141914, 0x00141914, 0x00131712, 0x00101510, 0x0010140f, 0x0010140f, 0x000e140e, 0x000c130d, 0x000c140d, 0x000b140d, 0x000a130c, 0x0008110a, 0x00081009, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x0005100a, 0x00040d08, 0x00040d08, 0x00040d08, 0x0006100b, 0x00040d08, 0x0005100a, 0x00040d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003c3e0d, 0x0041420e, 0x0044450d, 0x0048490f, 0x004c4d0f, 0x005c5710, 0x00b69314, 0x00cca316, 0x00cca316, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca619, 0x00cca619, 0x00c8a418, 0x00978315, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00626313, 0x00626312, 0x00606012, 0x005e5f12, 0x00a48914, 0x00cca417, 0x00b09014, 0x004f5010, 0x00505010, 0x004c4d10, 0x00484910, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0036370b, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x00081009, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f0a, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00060e08, 0x00070f08, 0x00081009, 0x00081009, 0x00081009, 0x0009120b, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c140d, 0x000e1610, 0x000e1610, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00141813, 0x00141811, 0x00141912, 0x00141910, 0x00181813, 0x00181813, 0x00181914, 0x00181a14, 0x001a1b14, 0x001c1c15, 0x001b1c14, 0x00181a12, 0x00181a12, 0x00181910, 0x0017180f, 0x00181910, 0x00181910, 0x00181a14, 0x00181a14, 0x00171914, 0x00161812, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00141813, 0x00131712, 0x00141612, 0x00151612, 0x00161713, 0x00161712, 0x00171812, 0x00191813, 0x001a1b12, 0x001c1c12, 0x001f1e12, 0x00221c10, 0x00241c10, 0x00281c11, 0x00291c12, 0x00291c12, 0x00291c10, 0x00291d10, 0x002a1e10, 0x002a1e11, 0x002a1e11, 0x002a1d13, 0x00291c11, 0x00281c13, 0x00281c13, 0x00281c13, 0x00251c10, 0x00261d11, 0x00241d11, 0x00221b0f, 0x001d190c, 0x001b190b, 0x0018180b, 0x00141508, 0x00121205, 0x00121206, 0x0018170c, 0x0017160d, 0x0016160d, 0x0014140c, 0x0014140b, 0x0014140c, 0x0016140b, 0x00151107, 0x00282315, 0x00352d1d, 0x003c3220, 0x00423421, 0x0044331f, 0x004c3823, 0x004c341d, 0x0055361e, 0x005c3c20, 0x005a3817, 0x005c3814, 0x005f3a15, 0x00633c18, 0x00653b18, 0x00683c1a, 0x00673c18, 0x00683c16, 0x006e411a, 0x006d3f16, 0x0078461c, 0x00764218, 0x006f3c11, 0x006e380f, 0x006f3a0e, 0x006e380c, 0x006b360a, 0x006e390b, 0x00703a0c, 0x006a3508, 0x006c3708, 0x00713c0c, 0x006c3808, 0x006c3b0a, 0x006d3c0c, 0x006d3c0d, 0x006d3c0d, 0x00693809, 0x00683808, 0x00683609, 0x0068370c, 0x0069380c, 0x0068380c, 0x0069390f, 0x0068380f, 0x005f3006, 0x00603209, 0x00582c06, 0x005a2d09, 0x00572c09, 0x0053280a, 0x0050290c, 0x00462107, 0x00401d04, 0x00402208, 0x00391f0b, 0x00311d0c, 0x00241408, 0x001d1108, 0x001c1009, 0x001a0f08, 0x00191008, 0x00181006, 0x00191107, 0x00191208, 0x001a1208, 0x001a1108, 0x00191006, 0x00181205, 0x00181408, 0x00181408, 0x00181408, 0x00181408, 0x001a160b, 0x001c180c, 0x001f190f, 0x001e1913, 0x001b1814, 0x00191816, 0x00181917, 0x00181917, 0x00191816, 0x00171814, 0x00161814, 0x00141811, 0x0013150f, 0x0010120c, 0x0010120a, 0x0010140b, 0x000d120b, 0x00101610, 0x00121914, 0x00111913, 0x00121813, 0x00131712, 0x00121812, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00131914, 0x00131914, 0x00131914, 0x00131914, 0x00131914, 0x00131914, 0x00111813, 0x00101711, 0x00121712, 0x00131712, 0x00121712, 0x00111611, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00121611, 0x00131712, 0x00111812, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00111813, 0x00131914, 0x00141b14, 0x00151c15, 0x00151c15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00141a14, 0x00171d18, 0x00181f17, 0x00181f15, 0x00181f15, 0x00181f17, 0x00181e18, 0x00181f19, 0x00181f17, 0x00181f17, 0x00181f17, 0x00171e16, 0x00161c16, 0x00161c17, 0x00161c17, 0x00141b15, 0x00141a14, 0x00141914, 0x00131712, 0x00111611, 0x0010140f, 0x0010140f, 0x000e140e, 0x000c130d, 0x000c140d, 0x000c140d, 0x000b140d, 0x0008110a, 0x0008100a, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x0006100b, 0x00040e09, 0x0005100a, 0x00040e09, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x00202309, 0x00202309, 0x0026280c, 0x00292b0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00706211, 0x00cca316, 0x00caa216, 0x00b59414, 0x00b39315, 0x00b39316, 0x00b39416, 0x00b39417, 0x00b39417, 0x00b39417, 0x00b39417, 0x00b39417, 0x00b29317, 0x00b29317, 0x00b19217, 0x00b19317, 0x00b19316, 0x00b19316, 0x00b09216, 0x00b09216, 0x00b09216, 0x00b09117, 0x00b09117, 0x00b09116, 0x00b09116, 0x00b09216, 0x00b09217, 0x00b09217, 0x00b09218, 0x00b09218, 0x00b09218, 0x00b09217, 0x00af9318, 0x00a88e17, 0x00857814, 0x00666713, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00636414, 0x00616112, 0x00606013, 0x00605e12, 0x00b49416, 0x00cca417, 0x00ac8c15, 0x004f5010, 0x00505010, 0x004c4d10, 0x00484910, 0x0045470e, 0x0040400d, 0x003c3e0d, 0x0036370c, 0x0034350c, 0x002d2f0a, 0x00292b0b, 0x0026280b, 0x00202309, 0x001d2008, 0x001d2009, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00050d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00050d05, 0x00060e06, 0x00060e06, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x0008100a, 0x000a130c, 0x000c140e, 0x000d140e, 0x00101610, 0x00101610, 0x00101610, 0x00101610, 0x00101610, 0x00121812, 0x00131914, 0x00141a14, 0x00161b15, 0x00161b14, 0x00171c15, 0x00171c14, 0x00181a14, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x001a1b14, 0x001a1b14, 0x00191b13, 0x00181a12, 0x00181a12, 0x00181a10, 0x00181a10, 0x0017180f, 0x00161810, 0x00141913, 0x00141914, 0x00141813, 0x00111611, 0x00131712, 0x00111611, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101610, 0x00101610, 0x00111510, 0x00141712, 0x00161814, 0x00161815, 0x00181613, 0x00191710, 0x001c1b0f, 0x001e1c0f, 0x00221d10, 0x00251c0e, 0x00281d0d, 0x002b1d0c, 0x002d1d0d, 0x002c1c0c, 0x002d1e0e, 0x002f200d, 0x0030210f, 0x00322310, 0x00332411, 0x00322312, 0x00302010, 0x002e1e0f, 0x002c1f10, 0x002c1f10, 0x002a1e0f, 0x00281c0d, 0x00281e0f, 0x00231a0c, 0x001f180a, 0x001d1a0a, 0x001b190a, 0x00171708, 0x00171408, 0x00141208, 0x0016140a, 0x001a180e, 0x001a180e, 0x0016150b, 0x00141408, 0x00141408, 0x00131308, 0x00141207, 0x00141105, 0x00241e13, 0x00342b1d, 0x00413424, 0x00403020, 0x0043301e, 0x004f3824, 0x00523520, 0x0054351c, 0x00573718, 0x00553412, 0x00573413, 0x005d3a18, 0x00623c18, 0x00643c1a, 0x00663b18, 0x00693c18, 0x006b3c17, 0x006c3d14, 0x00704118, 0x006f3f15, 0x006c3b11, 0x006d3b12, 0x006d3c12, 0x0066360d, 0x00623208, 0x00643409, 0x00613107, 0x00633308, 0x0064340a, 0x006a3b0e, 0x0066370a, 0x00643508, 0x0067380b, 0x006a3a10, 0x00633308, 0x0067380d, 0x0067380c, 0x0065350c, 0x0065350d, 0x0066360c, 0x0067390c, 0x0067390d, 0x00623709, 0x005c3005, 0x00582c04, 0x00542904, 0x00542908, 0x00532909, 0x004c2306, 0x004b2509, 0x00462309, 0x003f1f06, 0x003a210a, 0x00311e0a, 0x00221404, 0x00180f04, 0x00150f07, 0x00150f06, 0x00180e07, 0x00180e07, 0x00180f05, 0x00191108, 0x001a1208, 0x00191208, 0x00191208, 0x00181207, 0x00161307, 0x00161408, 0x00161408, 0x00171507, 0x001a1709, 0x001c170a, 0x001d170b, 0x00221b0e, 0x00221b12, 0x001e1913, 0x001c1812, 0x001a1913, 0x001b1812, 0x001b1711, 0x001d1810, 0x001d1912, 0x001c180f, 0x001c1b10, 0x0018190f, 0x00121408, 0x00101408, 0x000d1008, 0x000c100b, 0x000c130d, 0x00101610, 0x00101610, 0x00101610, 0x000e1611, 0x000c1710, 0x000c1710, 0x000c1710, 0x000c1710, 0x00101812, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000e1710, 0x000e1610, 0x000f1610, 0x00101610, 0x00101610, 0x000f150f, 0x000f150f, 0x0010140f, 0x0010140f, 0x0010140f, 0x0010140f, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101711, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x00101913, 0x00121a14, 0x00131b14, 0x00141c15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00151a14, 0x00141a14, 0x00161c16, 0x00171d16, 0x00171e14, 0x00171e14, 0x00171d16, 0x00171d18, 0x00171d18, 0x00181f17, 0x00181f17, 0x00182018, 0x00182018, 0x00171e18, 0x00171d18, 0x00171d18, 0x00161c17, 0x00151c15, 0x00151a14, 0x00141914, 0x00141813, 0x00111611, 0x00111611, 0x00101610, 0x000f150f, 0x000d150f, 0x000e1610, 0x000c140e, 0x000a130c, 0x000a130c, 0x000a1210, 0x0009110f, 0x0008100d, 0x0008100d, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0006100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x0005100a, 0x0006100b, 0x00040e09, 0x0006100b, 0x00060c07, 0x000f130f, 0x000f130f, 0x0014180f, 0x0014180b, 0x00191c0a, 0x001d200a, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004f5010, 0x00515110, 0x00706411, 0x00cca316, 0x00c7a016, 0x006d6612, 0x00605f12, 0x00626013, 0x00636212, 0x00646413, 0x00646413, 0x00656414, 0x00656414, 0x00656414, 0x00656414, 0x00656414, 0x00646413, 0x00646413, 0x00646413, 0x00646313, 0x00646312, 0x00646313, 0x00646313, 0x00646313, 0x00646313, 0x00646313, 0x00646413, 0x00646413, 0x00646414, 0x00656414, 0x00656414, 0x00656414, 0x00666514, 0x00666513, 0x00686714, 0x00686813, 0x00666713, 0x00666713, 0x00656614, 0x00656614, 0x00656614, 0x00646514, 0x00636414, 0x00626313, 0x00616112, 0x006c6613, 0x00c4a017, 0x00cca417, 0x00988014, 0x00515110, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x0008100b, 0x0008100b, 0x00050d08, 0x00050d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00060e06, 0x00060e06, 0x00050d05, 0x00060e08, 0x00060e08, 0x00081009, 0x00070f08, 0x00070f08, 0x0009110b, 0x0008100a, 0x0008100a, 0x0008110a, 0x0008110b, 0x000a130c, 0x000c140e, 0x000d140e, 0x00101510, 0x00101510, 0x00131712, 0x00131712, 0x00131712, 0x00141914, 0x00151a14, 0x00151a14, 0x00161b15, 0x00181a14, 0x00181c15, 0x00181c14, 0x00181813, 0x001a1c15, 0x001c1d18, 0x001b1c16, 0x001a1b14, 0x001a1b14, 0x00191a13, 0x00181911, 0x00181911, 0x00171810, 0x00171810, 0x00161710, 0x00141810, 0x00131812, 0x00121813, 0x00111812, 0x00101610, 0x00101711, 0x00101610, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x00101510, 0x00131713, 0x00161815, 0x00161815, 0x00181712, 0x001a1810, 0x001e1b10, 0x00201c0f, 0x00241d10, 0x00281c0c, 0x002b1c0a, 0x002f1c05, 0x00311f05, 0x00322004, 0x00312005, 0x0038260a, 0x0038270b, 0x00362509, 0x00352408, 0x00352408, 0x00352408, 0x00342408, 0x00342409, 0x0033230b, 0x0030220a, 0x002d200a, 0x002b1e09, 0x00261b08, 0x00241b0a, 0x00211c0a, 0x00201c0b, 0x001c1908, 0x0018170c, 0x0017140a, 0x0017140b, 0x0017140a, 0x0019180c, 0x0017170a, 0x00141408, 0x00131408, 0x00111408, 0x00111308, 0x00131208, 0x00141008, 0x00221c10, 0x00393021, 0x00423525, 0x003f2f1f, 0x0044311e, 0x004a321f, 0x004c311a, 0x0055371d, 0x00543415, 0x00553515, 0x00563414, 0x00603a1a, 0x00633c1c, 0x00643a18, 0x00673c18, 0x00683b15, 0x00673b12, 0x00693c13, 0x006c3d14, 0x006b3c14, 0x00683a11, 0x0064360f, 0x005e300a, 0x00582c05, 0x00572b04, 0x00542803, 0x00572b06, 0x005f320c, 0x0062340c, 0x0062350c, 0x005f3109, 0x005f310a, 0x0061340d, 0x005d300a, 0x005c2f08, 0x005d3009, 0x005f320c, 0x005f320c, 0x0061340c, 0x0064380e, 0x0064380e, 0x005d3308, 0x00592e05, 0x00572c06, 0x00542a08, 0x00542c0c, 0x00542c0d, 0x00492308, 0x00431f05, 0x003e1c06, 0x00381b06, 0x00341f0b, 0x00201200, 0x00181002, 0x00141004, 0x00141008, 0x00151007, 0x00160e06, 0x00170e04, 0x00171005, 0x00181208, 0x00191308, 0x00181308, 0x00181308, 0x00161307, 0x00141407, 0x00141506, 0x00161408, 0x00191709, 0x001c1809, 0x001d1707, 0x001e1607, 0x00251c0d, 0x00281d10, 0x00231a0f, 0x001e180c, 0x001c190c, 0x001d190b, 0x001d1609, 0x00261c0c, 0x002c200f, 0x002e2411, 0x00322a18, 0x002a2514, 0x00181606, 0x00131307, 0x00101308, 0x000f1009, 0x000e1109, 0x0010150e, 0x00101510, 0x00101610, 0x000e1611, 0x000c1810, 0x000c1810, 0x000c1810, 0x000c1810, 0x000e1811, 0x000c160f, 0x000c160f, 0x000c160f, 0x000c160f, 0x000c1710, 0x000c1710, 0x000d1810, 0x000d1610, 0x000c140e, 0x000c140e, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000e150f, 0x000d150f, 0x000c160f, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000e1811, 0x000e1811, 0x000f1912, 0x000f1912, 0x00101912, 0x00111812, 0x00111812, 0x00111812, 0x00101812, 0x00131b14, 0x00141c15, 0x00131c13, 0x00131c13, 0x00131c13, 0x00131c13, 0x00151e18, 0x00151e18, 0x00181f17, 0x00181f17, 0x00182018, 0x00182018, 0x00181e17, 0x00171d16, 0x00181e17, 0x00182018, 0x00181f18, 0x00161b15, 0x00151a14, 0x00141914, 0x00131712, 0x00131712, 0x00111711, 0x00101610, 0x000e1610, 0x000f1710, 0x000c140e, 0x000c140e, 0x000c140e, 0x000a120f, 0x0009110f, 0x0008100d, 0x0008100d, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0007100b, 0x0006100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x00040e09, 0x0008110c, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003e400c, 0x0043440e, 0x0047480e, 0x004c4d10, 0x004f5010, 0x00535410, 0x00716512, 0x00cca417, 0x00c7a116, 0x006c6713, 0x00606013, 0x00626313, 0x00646414, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666713, 0x00656614, 0x00646514, 0x00656614, 0x00646414, 0x00646514, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646514, 0x00646514, 0x00646513, 0x00656614, 0x00666714, 0x00666713, 0x00666714, 0x00666714, 0x00666714, 0x00666714, 0x00666713, 0x00656614, 0x00646513, 0x00646414, 0x00626313, 0x00606013, 0x00947f14, 0x00caa317, 0x00c8a117, 0x00746811, 0x00535410, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x0026280a, 0x0026280c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00081009, 0x00060e08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d07, 0x00070f08, 0x00070f08, 0x00081009, 0x0008100b, 0x0008100c, 0x000b130e, 0x000c1410, 0x000c140f, 0x000e140e, 0x000f150f, 0x000f150f, 0x00101510, 0x00121611, 0x00121711, 0x00141814, 0x00151a14, 0x00151a13, 0x00161b14, 0x00171c15, 0x00171c15, 0x001a1b15, 0x001a1b15, 0x001b1c16, 0x001b1c16, 0x001c1c18, 0x001b1c16, 0x00191b14, 0x001a1b14, 0x00171811, 0x00171812, 0x00161711, 0x00151610, 0x00151610, 0x00131611, 0x00131611, 0x00131510, 0x00131510, 0x00101510, 0x00101510, 0x00111611, 0x00101610, 0x000d1510, 0x000d1510, 0x000c1410, 0x000c1410, 0x000f150f, 0x000f150f, 0x000f150f, 0x000e140e, 0x000c140d, 0x000e150f, 0x00101610, 0x00101510, 0x00131714, 0x00161814, 0x00191711, 0x001c180f, 0x001e190e, 0x00241b10, 0x002c1c10, 0x00321b0d, 0x003c200d, 0x004f3414, 0x00583d1a, 0x004f340e, 0x00482f08, 0x00503812, 0x00503814, 0x004a330f, 0x00442c08, 0x00442b09, 0x00482d0c, 0x00462f0c, 0x0045300c, 0x00422f0c, 0x00382805, 0x00342404, 0x002f2104, 0x002a1e03, 0x00261b08, 0x00251c09, 0x00251d0b, 0x00231c0a, 0x001b190b, 0x00181609, 0x00181709, 0x00161407, 0x0019180a, 0x0019180c, 0x00141408, 0x00111406, 0x00101407, 0x000f1307, 0x00101207, 0x00101107, 0x00131107, 0x00211b10, 0x0033291c, 0x003a2d1f, 0x00483828, 0x0046311f, 0x00442e18, 0x00563d24, 0x00553920, 0x0058391c, 0x00553517, 0x005d391a, 0x005f3818, 0x00603718, 0x00653a18, 0x00623712, 0x00643911, 0x0064380f, 0x0064380f, 0x00653910, 0x005e320a, 0x00592c07, 0x00592c0b, 0x00582c0d, 0x00542b0c, 0x004d2408, 0x0051280c, 0x00552a0c, 0x00582d0e, 0x005c310c, 0x005d320c, 0x005b300b, 0x00582d09, 0x005c300c, 0x00542804, 0x005a2f0b, 0x005d320e, 0x005a2f09, 0x005f340e, 0x00623810, 0x0061370e, 0x005c3008, 0x00542a03, 0x00562b07, 0x00542c0a, 0x00542c0d, 0x004b2608, 0x004b260c, 0x0041210a, 0x00361c09, 0x002e1808, 0x00200e01, 0x00190e04, 0x00141005, 0x00121008, 0x00131008, 0x00151008, 0x00161007, 0x00171106, 0x00171207, 0x00181308, 0x00171408, 0x00151408, 0x00151408, 0x00141408, 0x00161408, 0x00181408, 0x0019140b, 0x001d160c, 0x001f170a, 0x00201806, 0x00261b09, 0x002d200e, 0x00342511, 0x00311f08, 0x002a1901, 0x002b1c05, 0x002e2007, 0x00302003, 0x003d2a08, 0x00463413, 0x00433415, 0x0040321a, 0x002f2410, 0x00181104, 0x00110f05, 0x00121006, 0x00110f05, 0x000f0d04, 0x000f100b, 0x0010140f, 0x000f1410, 0x000d1510, 0x000c1710, 0x000b1710, 0x000b1710, 0x000b1710, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000b1510, 0x000b1510, 0x000a140f, 0x0009130e, 0x000a140f, 0x000a140d, 0x000a140d, 0x000a140d, 0x000a140d, 0x0009140b, 0x0008130a, 0x0009140b, 0x0009140b, 0x000c140c, 0x000c140c, 0x000c140c, 0x000c140c, 0x000a140d, 0x000b150e, 0x000b150e, 0x000b150e, 0x000c1410, 0x000c1410, 0x000d1510, 0x000d1510, 0x000c1610, 0x000b170f, 0x000c1810, 0x000c1810, 0x000c1811, 0x000d1712, 0x000d1711, 0x000e1813, 0x000f1812, 0x00111913, 0x00131b14, 0x00131b14, 0x00131b14, 0x00131b15, 0x00131b14, 0x00141c15, 0x00141c14, 0x00161c16, 0x00181c18, 0x00191d18, 0x00191e18, 0x00191d18, 0x00181c18, 0x00181c17, 0x00181d15, 0x00181c15, 0x00171c17, 0x00171c17, 0x00161b15, 0x00141914, 0x00141612, 0x00131712, 0x00101812, 0x000e1710, 0x00101610, 0x00101610, 0x000c140e, 0x000b140d, 0x000a140d, 0x0009140d, 0x0008120c, 0x0008120c, 0x0009110c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0007100b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0004100a, 0x0004100a, 0x00030f09, 0x00030f09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0044450d, 0x00494a0f, 0x004d4e0f, 0x00515110, 0x00555610, 0x00726612, 0x00cca417, 0x00c7a118, 0x006f6913, 0x00636413, 0x00646514, 0x00656614, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00686814, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00656614, 0x00646514, 0x00636414, 0x006b6613, 0x00bc9917, 0x00cca418, 0x00ad8e15, 0x005b5911, 0x00545510, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0038380c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00081009, 0x00060e08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d07, 0x00070f08, 0x0009110b, 0x0009120b, 0x0008100c, 0x0008100c, 0x000b130e, 0x000c1410, 0x000e1510, 0x000f150f, 0x00101610, 0x00101710, 0x00111711, 0x00141814, 0x00141814, 0x00151a14, 0x00161a14, 0x00181a14, 0x00181a14, 0x00181c15, 0x00181c15, 0x001a1b15, 0x001a1b15, 0x001b1c16, 0x001b1c16, 0x001a1b17, 0x00181914, 0x00181913, 0x001a1b14, 0x00191b14, 0x00181813, 0x00161711, 0x00151610, 0x00141610, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x000f150f, 0x000f150f, 0x000e140e, 0x000e140e, 0x000c140d, 0x000c140d, 0x000b130c, 0x000b130c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140e, 0x000f1610, 0x00101510, 0x00121814, 0x00141711, 0x001a1811, 0x001e1910, 0x0020190c, 0x00281b0e, 0x00301c0a, 0x00402508, 0x005c3c16, 0x00755324, 0x0074501d, 0x0066440e, 0x00603f07, 0x00684811, 0x00684814, 0x0064430f, 0x005f3c08, 0x005c3a08, 0x005e3b0b, 0x005c3a0c, 0x005a3a0f, 0x00573a10, 0x00483008, 0x003b2704, 0x00332204, 0x002d1f05, 0x002b1d09, 0x00291d0a, 0x00281e09, 0x00241c08, 0x001e1c0b, 0x001b1909, 0x001b1a0a, 0x001c1c0c, 0x001b1a0a, 0x00191809, 0x00181809, 0x00101404, 0x000d1204, 0x000e1205, 0x000e1207, 0x000e1107, 0x00121308, 0x00151206, 0x001a1408, 0x002d2416, 0x003e3121, 0x00443220, 0x0045301d, 0x00523a25, 0x00583c27, 0x00563a1f, 0x00543518, 0x005a3818, 0x005a3415, 0x005d3415, 0x00613816, 0x005f3511, 0x00663c15, 0x0060370e, 0x0060340c, 0x005c320b, 0x005c320b, 0x00572b06, 0x0057290b, 0x0056290c, 0x00542a10, 0x004c250b, 0x004e250c, 0x004e250a, 0x00532a0c, 0x005a3110, 0x005c3310, 0x005a300d, 0x00562c09, 0x00552b08, 0x00562c09, 0x005c3310, 0x00603613, 0x005a310d, 0x005b310c, 0x00603611, 0x005f350f, 0x005c330c, 0x00552c07, 0x00542c09, 0x00532c0b, 0x00492607, 0x00411f04, 0x0042230c, 0x0039200b, 0x00291505, 0x001c0d01, 0x00160b00, 0x00160e06, 0x00140f09, 0x00120f0a, 0x00141009, 0x00161109, 0x00161208, 0x00171407, 0x00171408, 0x00171408, 0x00161408, 0x00161408, 0x00161407, 0x00151406, 0x00171406, 0x001a1408, 0x001b1308, 0x001e150c, 0x0021170a, 0x00281b08, 0x002b1d08, 0x00362410, 0x003f2a0f, 0x00432b08, 0x00462d03, 0x004e3407, 0x005a4010, 0x00563e0b, 0x0058400f, 0x00543d13, 0x0044300d, 0x0032230a, 0x00241707, 0x00170f04, 0x00110f05, 0x00121006, 0x00111005, 0x000f0d04, 0x00101009, 0x0011140e, 0x000f1410, 0x000d1410, 0x00091410, 0x00091410, 0x00091410, 0x00091410, 0x000a1410, 0x000a1410, 0x000a1410, 0x000a1410, 0x000a1410, 0x00091310, 0x00091310, 0x0008120f, 0x0009130f, 0x0009130e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0008120c, 0x0008120c, 0x0009140c, 0x0009140c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000a140d, 0x000b150e, 0x000a140d, 0x000a140d, 0x000c140f, 0x000c140f, 0x000c1410, 0x000c1410, 0x000b150f, 0x000a160e, 0x000b170f, 0x000c1810, 0x000c1811, 0x000c1713, 0x000c1711, 0x000c1711, 0x000d1710, 0x00101812, 0x00111913, 0x00131b14, 0x00131b14, 0x00141a16, 0x00141a14, 0x00151c15, 0x00151c14, 0x00161b15, 0x00161b15, 0x00171c17, 0x00181c17, 0x00181c18, 0x00181d17, 0x00181d15, 0x00181d14, 0x00181c14, 0x00171c17, 0x00171c17, 0x00161b15, 0x00141914, 0x00141813, 0x00121712, 0x00101812, 0x000e1710, 0x00101610, 0x00101610, 0x000e1710, 0x000c140e, 0x000a140d, 0x0009140c, 0x0008120c, 0x0008120c, 0x0009110c, 0x0009110d, 0x0008100b, 0x0008100b, 0x0007100b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0004100a, 0x0004100a, 0x00030f09, 0x00030f09, 0x00040e09, 0x0005100a, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0026280c, 0x00292b0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x004b4c0f, 0x00505010, 0x00535410, 0x00565711, 0x00746812, 0x00cca418, 0x00c7a118, 0x00706b14, 0x00646414, 0x00656614, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00666713, 0x00656614, 0x00646513, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00646514, 0x00646414, 0x00a28915, 0x00cba418, 0x00c6a118, 0x00786c13, 0x00565711, 0x00545511, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00081009, 0x00060e08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060e06, 0x00071007, 0x00060e06, 0x00060e06, 0x00081009, 0x00081009, 0x0009120c, 0x0009120c, 0x000a120e, 0x000b130e, 0x000c1410, 0x000d1510, 0x000e1510, 0x00101610, 0x00101711, 0x00111812, 0x00131812, 0x00161812, 0x00161812, 0x00181c15, 0x00191c15, 0x001a1b14, 0x001a1b14, 0x001a1b14, 0x001a1b14, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x001a1b17, 0x00181914, 0x00181813, 0x00181912, 0x00161810, 0x00141710, 0x00131610, 0x0012150f, 0x0011150f, 0x0010150f, 0x000f150f, 0x000e140f, 0x000c130d, 0x000c140d, 0x000c140e, 0x000a130c, 0x000a130c, 0x000a130c, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008130c, 0x0008130c, 0x0008120c, 0x0008120c, 0x0009130c, 0x000b140d, 0x000e150f, 0x00101510, 0x00111613, 0x00141510, 0x001b1811, 0x00201810, 0x0023190d, 0x002e1e0f, 0x003c2408, 0x00634414, 0x007f581b, 0x0091651c, 0x008e6212, 0x008c600f, 0x00895f0b, 0x00916814, 0x00916815, 0x008c6410, 0x008a600d, 0x008a600c, 0x00895e0c, 0x00855a11, 0x007e5514, 0x00684209, 0x00513302, 0x00432b02, 0x00372405, 0x002e1e06, 0x002e1e09, 0x002d1e0a, 0x002b1f09, 0x0029200b, 0x00221e0b, 0x001f1c0a, 0x00201c0b, 0x00201d0b, 0x001e1c09, 0x001a1908, 0x001a1b09, 0x00161a09, 0x000c1002, 0x000c1004, 0x000c1005, 0x000c1006, 0x000e1006, 0x00121108, 0x00151208, 0x00181307, 0x00292012, 0x003f3020, 0x00402e1e, 0x004b3623, 0x00503824, 0x0050351d, 0x00503419, 0x00563719, 0x00563417, 0x005d3417, 0x005f3414, 0x00623816, 0x00643c16, 0x005d350e, 0x005b330c, 0x00572f0a, 0x005b330d, 0x005b300e, 0x00582b0e, 0x0054280e, 0x0050270c, 0x004c240c, 0x004c240d, 0x004b250a, 0x00532c0e, 0x00532c0c, 0x00502808, 0x00512908, 0x00572c0c, 0x00562c0c, 0x00512807, 0x00572d0c, 0x005d3313, 0x005c3210, 0x00572d0a, 0x00582e0a, 0x0059300c, 0x00582f0a, 0x00512806, 0x004e2809, 0x00502c10, 0x0049270d, 0x003c1f08, 0x00331c0b, 0x00281608, 0x00190c02, 0x00140c04, 0x00120d05, 0x00110d08, 0x00120e0c, 0x00100f0c, 0x00120f0b, 0x00131009, 0x00141208, 0x00151406, 0x00161407, 0x00161408, 0x00161408, 0x00161407, 0x00181508, 0x00191507, 0x001b1406, 0x001d1408, 0x0020160b, 0x0024180c, 0x00281a0c, 0x002e1f0a, 0x00312008, 0x003f280d, 0x00503510, 0x006e4e1b, 0x008d682a, 0x009d7128, 0x00a0762a, 0x008e6b24, 0x006e4e16, 0x004d340a, 0x00352103, 0x00211400, 0x00180f02, 0x00131006, 0x00111005, 0x00100f04, 0x00111005, 0x00100e05, 0x000e0f08, 0x000e110b, 0x000e130e, 0x000c1410, 0x00081311, 0x00081312, 0x00081312, 0x00081312, 0x00091312, 0x00091312, 0x00091312, 0x00091312, 0x00091211, 0x00091111, 0x00091211, 0x00091211, 0x00091310, 0x00091310, 0x00091310, 0x0008120f, 0x0008120f, 0x0009130e, 0x0008120c, 0x0008110c, 0x0008110c, 0x0009110e, 0x0009110e, 0x0009110e, 0x0009110e, 0x0008130c, 0x0009140c, 0x0009140c, 0x0009140c, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009140e, 0x0009160e, 0x000a160e, 0x000b160e, 0x000b1610, 0x000c1511, 0x000c1610, 0x000c1610, 0x000c160f, 0x000d150f, 0x000f1710, 0x000f1811, 0x00111913, 0x00141815, 0x00151a14, 0x00141914, 0x00151a13, 0x00161a14, 0x00161a15, 0x00171c17, 0x00181c17, 0x00171c16, 0x00171c14, 0x00171c14, 0x00171c13, 0x00171c14, 0x00171c17, 0x00171c17, 0x00171c17, 0x00151a14, 0x00161b15, 0x00141a14, 0x00131914, 0x00101812, 0x00101610, 0x00101710, 0x000e1610, 0x000e1610, 0x000c1610, 0x000b150e, 0x000a140d, 0x0008120c, 0x0009110c, 0x0009110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110b, 0x0005110b, 0x0006120c, 0x0004100a, 0x0004100a, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00141809, 0x00191c09, 0x00202309, 0x00202309, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003e400d, 0x0043440e, 0x0048490e, 0x004c4d0f, 0x00505010, 0x00545510, 0x00585911, 0x00756a13, 0x00cca418, 0x00c7a218, 0x00716c14, 0x00656614, 0x00686814, 0x00696914, 0x006a6a14, 0x006b6b14, 0x006b6b14, 0x006b6b14, 0x006b6b14, 0x006b6b14, 0x006a6a14, 0x006a6a14, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00686814, 0x00686814, 0x00686814, 0x00656614, 0x00907e15, 0x00c8a418, 0x00cba418, 0x009c8415, 0x005c5c12, 0x00585810, 0x00545511, 0x00515110, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00081009, 0x00060e08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060e06, 0x00071007, 0x00081108, 0x00081108, 0x00081009, 0x00081009, 0x0009120c, 0x000a130c, 0x000c1410, 0x000d1510, 0x000d1510, 0x000e1610, 0x000f1610, 0x00101610, 0x00111812, 0x00141914, 0x00151a14, 0x00191a13, 0x00191a13, 0x001a1b14, 0x001a1b14, 0x001b1a14, 0x001b1a14, 0x001b1a14, 0x001b1a14, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x00181915, 0x00171813, 0x00161712, 0x00161710, 0x00141610, 0x00111610, 0x0011160f, 0x0010150e, 0x0010150e, 0x000d150f, 0x000d150f, 0x000c140e, 0x000c140d, 0x0009140c, 0x0009140c, 0x0009140c, 0x0009140c, 0x0009120a, 0x00081108, 0x00081108, 0x00081108, 0x0007110a, 0x0006120a, 0x0007120b, 0x0008130c, 0x0008130c, 0x000a150d, 0x000d1510, 0x000f1510, 0x00111613, 0x00141510, 0x001c1711, 0x00201810, 0x00261c0e, 0x0031200c, 0x00462a08, 0x007c571b, 0x00a97e2c, 0x00be8c28, 0x00c08e24, 0x00c09023, 0x00bd8e1d, 0x00c29422, 0x00c39523, 0x00c29423, 0x00c19421, 0x00c0931b, 0x00bd9018, 0x00bc8e22, 0x00b08223, 0x007c5003, 0x00583400, 0x004a2e00, 0x003c2707, 0x00322109, 0x00311f0a, 0x0030200a, 0x002d1f08, 0x002b1f08, 0x0024210c, 0x00222009, 0x00201d08, 0x00201d08, 0x00221e09, 0x001e1c09, 0x001a1b06, 0x00141803, 0x00151909, 0x000f1208, 0x000c0f04, 0x000c1007, 0x000c0f08, 0x000e0e07, 0x00100e06, 0x00141108, 0x00171004, 0x002c2314, 0x00382c1c, 0x0040301e, 0x003f2c17, 0x004f3720, 0x004d321b, 0x0055371d, 0x00553418, 0x005c3416, 0x005b3213, 0x00613916, 0x00603914, 0x005f3810, 0x00573009, 0x005c3410, 0x00572f0b, 0x005c3312, 0x00582b10, 0x0054280f, 0x0050270c, 0x004c240d, 0x0049240d, 0x004a250c, 0x00522b11, 0x00522b0e, 0x004f280a, 0x00572f10, 0x0053280c, 0x00572c0f, 0x00582e10, 0x00592e11, 0x00572e0e, 0x0059300f, 0x00572c0c, 0x00582e0c, 0x00562c0c, 0x00512808, 0x00492104, 0x00472008, 0x0048250f, 0x003d1e0a, 0x00311705, 0x00201004, 0x00170c04, 0x00130c07, 0x0013110b, 0x000f0e08, 0x000f0e08, 0x000f0e0b, 0x00110d0d, 0x0010100c, 0x00121109, 0x00141408, 0x00141407, 0x00161408, 0x00161408, 0x00151407, 0x0019170a, 0x001c190a, 0x001d1807, 0x001e1707, 0x00201608, 0x0024180a, 0x00281b0c, 0x002b1c0a, 0x00312109, 0x00352308, 0x00442c0c, 0x0055370a, 0x008c6528, 0x00b98c40, 0x00be862c, 0x00af7a1d, 0x008d6016, 0x005d3504, 0x00351a00, 0x00221200, 0x001a1103, 0x00131206, 0x00101108, 0x00110f05, 0x000e0c02, 0x000e0c02, 0x00101007, 0x0011130b, 0x000e110b, 0x000e120d, 0x000c1310, 0x00081110, 0x00071210, 0x00071210, 0x00071210, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0007100f, 0x00081110, 0x00081110, 0x00081210, 0x0008120f, 0x0008120e, 0x0007110d, 0x0007110d, 0x0008120d, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110b, 0x0008120c, 0x0009140d, 0x0009140d, 0x0008140e, 0x0008140e, 0x0007130d, 0x0007130d, 0x0008140d, 0x0008140d, 0x0008140d, 0x0008150e, 0x0008140f, 0x000a1410, 0x000b1410, 0x000c1610, 0x000c160f, 0x000d150f, 0x000d150f, 0x000d140e, 0x000e1610, 0x00121613, 0x00141813, 0x00121712, 0x00141811, 0x00141914, 0x00141914, 0x00151a14, 0x00161b16, 0x00171c15, 0x00171c14, 0x00171c13, 0x00161c12, 0x00161c13, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161b15, 0x00161c16, 0x00161c15, 0x00151b15, 0x00141914, 0x00131712, 0x00111813, 0x000f1610, 0x000f1610, 0x000d1710, 0x000c1710, 0x000c160f, 0x000a140d, 0x0009120c, 0x0008100c, 0x0008100b, 0x0008100c, 0x0007100c, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110b, 0x0005110b, 0x0006120c, 0x0004100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0020230a, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003e400c, 0x0043440e, 0x0048490f, 0x004c4d10, 0x00515110, 0x00555610, 0x00595a11, 0x00756a13, 0x00cca418, 0x00c7a218, 0x00726d14, 0x00686814, 0x00696914, 0x006b6b14, 0x006c6c14, 0x006c6c15, 0x006c6c15, 0x006c6c15, 0x006c6c15, 0x006c6c15, 0x006b6b14, 0x006a6a14, 0x006a6a14, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x006a6a14, 0x00696914, 0x00696914, 0x00686814, 0x00686814, 0x00938115, 0x00c6a219, 0x00cca518, 0x00b09217, 0x00646212, 0x005b5b11, 0x00585910, 0x00545510, 0x00515110, 0x004c4d10, 0x00484910, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00080f0a, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00081009, 0x0008110a, 0x00081009, 0x00060e08, 0x00040f08, 0x00081009, 0x000c120c, 0x000c130d, 0x000c130d, 0x000f150f, 0x00101610, 0x0010170f, 0x00121911, 0x00141912, 0x00151812, 0x00171910, 0x00181b12, 0x001a1b14, 0x001a1b14, 0x001b1c14, 0x001b1c14, 0x001a1b14, 0x001a1b14, 0x001b1c14, 0x001b1c14, 0x00181c15, 0x00181c15, 0x00171a14, 0x00161913, 0x00141813, 0x00141714, 0x00141714, 0x00121510, 0x00101510, 0x00101510, 0x0010140f, 0x0010140f, 0x000f140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000c130d, 0x0008120b, 0x0008120b, 0x0007110a, 0x0007110a, 0x00061009, 0x0007110a, 0x0007110a, 0x0007110a, 0x00061008, 0x00070f08, 0x00081009, 0x0009120b, 0x000b140e, 0x000c140f, 0x000c1210, 0x000d1211, 0x00101412, 0x00141510, 0x001b1610, 0x00201810, 0x00271c0c, 0x00351f0a, 0x004c2d0f, 0x00856021, 0x00c49936, 0x00c9a124, 0x00cca622, 0x00cca81d, 0x00cca819, 0x00cba817, 0x00cba817, 0x00cba918, 0x00c9a818, 0x00c8a914, 0x00c9a90e, 0x00cba615, 0x00c3981d, 0x00906208, 0x00633b01, 0x00523108, 0x00442c0c, 0x0038260f, 0x0034230b, 0x0034230b, 0x0033230b, 0x00302108, 0x002a2108, 0x00272008, 0x00241d08, 0x00241d09, 0x00241f0b, 0x00221e09, 0x001a1a08, 0x00151a08, 0x00141809, 0x000e1106, 0x000b0e04, 0x000c0f07, 0x000c0f08, 0x000d0f07, 0x00100f08, 0x00100f08, 0x00131007, 0x00151004, 0x00211a0c, 0x00322817, 0x003b2c18, 0x003f2c18, 0x0049311c, 0x0051341d, 0x00543419, 0x00563214, 0x00583312, 0x00583410, 0x0056310b, 0x0059340c, 0x0059340e, 0x0058320f, 0x0055300d, 0x00532c0c, 0x0052280c, 0x004d2408, 0x004f260c, 0x00502a10, 0x0048240b, 0x00442006, 0x00512c12, 0x00512c0f, 0x004c2508, 0x0050290a, 0x00542e0f, 0x00522a0c, 0x00532b0f, 0x00572f10, 0x00512c0b, 0x00532d0a, 0x00542d09, 0x00502907, 0x004e2708, 0x004b240c, 0x0046220b, 0x003e1e08, 0x00341c08, 0x00271703, 0x001a1000, 0x00171009, 0x00140e09, 0x00100d07, 0x00100e08, 0x00100e08, 0x00100d07, 0x000f0e06, 0x00101008, 0x00131009, 0x00131008, 0x00161309, 0x0018140b, 0x0018140a, 0x00181409, 0x001b170b, 0x00201c0c, 0x00201c0a, 0x00201807, 0x00221708, 0x00251809, 0x00281b09, 0x002d1f05, 0x002f2008, 0x0033240b, 0x003b2a0d, 0x00432b0a, 0x0055390c, 0x00805c20, 0x00a77b33, 0x00a77420, 0x0084540c, 0x00623604, 0x003d1800, 0x00291103, 0x00201004, 0x00181107, 0x00121208, 0x00111108, 0x000f0e05, 0x000b0b01, 0x00121108, 0x00101008, 0x00101109, 0x000e110b, 0x000d110c, 0x000c120d, 0x0009110e, 0x0009120f, 0x00081010, 0x00061110, 0x00091211, 0x00081110, 0x0007100f, 0x0007100f, 0x00091310, 0x0007110d, 0x0006100c, 0x0006100c, 0x0007100d, 0x0008120e, 0x0008110e, 0x0006110d, 0x0007110d, 0x0007110c, 0x00040e09, 0x00040f09, 0x0005100a, 0x0008120c, 0x0006100b, 0x0008110c, 0x0009130e, 0x0008120e, 0x0008120f, 0x0007110d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0008120e, 0x0008120e, 0x0008120f, 0x0007130f, 0x0007130f, 0x0007130f, 0x0007130f, 0x0008120f, 0x000b1411, 0x000a1410, 0x000a1410, 0x000b1510, 0x000c1610, 0x000c1610, 0x000c1610, 0x000e1410, 0x00101512, 0x00111611, 0x00111610, 0x00121911, 0x00131a12, 0x00131a12, 0x00131a12, 0x00141a13, 0x00151a13, 0x00161b14, 0x00161b14, 0x00161c15, 0x00181e18, 0x00181e18, 0x00171d16, 0x00181d15, 0x00191c16, 0x00181c15, 0x00181b14, 0x00161913, 0x00141914, 0x00141813, 0x00111611, 0x0010140f, 0x000f1410, 0x000e1610, 0x000c160f, 0x000a140c, 0x000a130d, 0x000b120e, 0x0009110d, 0x0009110d, 0x0008120c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x0005100a, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250c, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x003b3c0d, 0x0040400d, 0x0044450e, 0x00494a0f, 0x004d4e0f, 0x00525310, 0x00565711, 0x005c5c12, 0x00776c14, 0x00cca518, 0x00c7a218, 0x00736e14, 0x00696914, 0x006b6b14, 0x006c6c15, 0x006d6d15, 0x006d6d15, 0x006e6e15, 0x006d6d15, 0x006d6d15, 0x006c6c15, 0x006c6c15, 0x006b6b14, 0x006b6b14, 0x00696914, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x006a6a14, 0x006a6a14, 0x006a6a14, 0x00686814, 0x00757014, 0x00a58d17, 0x00c8a419, 0x00cca619, 0x00b79817, 0x006f6813, 0x005e5f12, 0x005c5c12, 0x00585910, 0x00555610, 0x00515110, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040c08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00050d09, 0x00040c08, 0x0008100a, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00070f08, 0x00081009, 0x00070f08, 0x00081009, 0x00051008, 0x0008110b, 0x000d140e, 0x000d140e, 0x000d140e, 0x00101610, 0x00101710, 0x00111810, 0x00131810, 0x00151812, 0x00171812, 0x00191b12, 0x001b1c13, 0x001a1b14, 0x001a1b14, 0x001b1c14, 0x001b1c14, 0x001a1b15, 0x001a1b15, 0x001b1c16, 0x001b1c16, 0x00181c15, 0x00171c15, 0x00151a13, 0x00141811, 0x00111613, 0x00111613, 0x00121714, 0x00101512, 0x00101510, 0x000f150f, 0x000f150f, 0x000d140e, 0x000d140e, 0x000c120c, 0x000c120c, 0x000c120c, 0x000a110c, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00040f08, 0x00051008, 0x00051008, 0x00051008, 0x00070f08, 0x00070f08, 0x00081009, 0x0009120b, 0x000a130c, 0x000a120e, 0x000b1110, 0x000d1211, 0x00101412, 0x00141510, 0x001b1610, 0x00201810, 0x00271c0c, 0x0035200b, 0x004c2c0e, 0x00876123, 0x00c39c33, 0x00cbab24, 0x00ccb020, 0x00ccb219, 0x00ccb414, 0x00ccb412, 0x00ccb412, 0x00ccb411, 0x00cbb410, 0x00cbb40e, 0x00cbb30b, 0x00ccb011, 0x00c09b18, 0x008a6102, 0x00684006, 0x0058360c, 0x0048300e, 0x003c2b10, 0x0037250a, 0x0037250a, 0x0038260b, 0x00342408, 0x00302407, 0x002d2207, 0x002b1f08, 0x002a1f09, 0x00281f09, 0x00241d09, 0x0020200d, 0x00191c0b, 0x00151a09, 0x00111508, 0x000c1004, 0x000b0e05, 0x000c0f07, 0x000d0f07, 0x000f1008, 0x000f1008, 0x00111109, 0x00141006, 0x00151105, 0x001b1404, 0x00261d0c, 0x00362915, 0x00422f1c, 0x004f3520, 0x0051341c, 0x00533417, 0x00543414, 0x00543110, 0x00502d08, 0x0058350f, 0x0056330d, 0x00502c0a, 0x004c2808, 0x004c280a, 0x004d270a, 0x004a2306, 0x00482406, 0x004d280c, 0x00482408, 0x004a260a, 0x004f2c10, 0x00502c0e, 0x004b2508, 0x004d2809, 0x004f2b0b, 0x004c2808, 0x004c2808, 0x00502c0c, 0x004c2a06, 0x004e2d08, 0x004d2a04, 0x00492602, 0x00472505, 0x00432409, 0x0040220c, 0x00301804, 0x00231000, 0x001b1000, 0x00160f02, 0x00131009, 0x00121009, 0x00110f08, 0x00100d07, 0x000f0f05, 0x000f0f05, 0x000e0e04, 0x00111008, 0x00131107, 0x00131107, 0x0018140b, 0x001a160c, 0x001b150d, 0x001c160d, 0x001e180c, 0x00221c0c, 0x00241c0c, 0x00251b09, 0x00271b08, 0x002b1c08, 0x002e1f0a, 0x00302209, 0x0032240a, 0x0038290f, 0x0038290d, 0x00392409, 0x00412704, 0x00543308, 0x00633d0b, 0x005d3504, 0x00482200, 0x00381800, 0x002c1104, 0x0025120d, 0x001d100d, 0x0018100b, 0x00141108, 0x00121107, 0x00111007, 0x00101007, 0x00131209, 0x000f0f05, 0x000d0f07, 0x000c1009, 0x000c100c, 0x000c120c, 0x0008100a, 0x000b1310, 0x00091310, 0x00081311, 0x00091310, 0x0008120f, 0x0007110d, 0x0007110d, 0x00091310, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110d, 0x0006110d, 0x0006100b, 0x0005100a, 0x0006100b, 0x0006100b, 0x0007110c, 0x0006100b, 0x0005100a, 0x0008110c, 0x0007100d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0007110e, 0x0007130f, 0x0007130f, 0x0007130f, 0x0007130f, 0x0008110d, 0x000a1410, 0x00091310, 0x00091310, 0x0009130e, 0x000a140f, 0x000b1510, 0x000b1410, 0x000c130f, 0x000f1410, 0x00101610, 0x0010160e, 0x00121911, 0x00121911, 0x00111810, 0x00111810, 0x00131812, 0x00141813, 0x00141913, 0x00141913, 0x00151b15, 0x00161c17, 0x00161c16, 0x00171d16, 0x00181d14, 0x00191c16, 0x00181c15, 0x001a1d17, 0x00181b14, 0x00161b16, 0x00151a14, 0x00141813, 0x00111611, 0x00101411, 0x0010150f, 0x000e150f, 0x000c150d, 0x000c130e, 0x000b120e, 0x0009110d, 0x0009110d, 0x0008120c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008110c, 0x0008110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0b, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x0040400e, 0x0045470e, 0x004b4c0f, 0x004f5010, 0x00535410, 0x00585811, 0x005c5d12, 0x00786c14, 0x00cca518, 0x00c7a318, 0x00746f14, 0x006a6a14, 0x006c6c14, 0x006d6d15, 0x006e6e15, 0x006f6f14, 0x006f6f14, 0x006f6f14, 0x006e6e15, 0x006d6d15, 0x006c6c15, 0x006c6c14, 0x006b6b14, 0x006a6a14, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x006a6a14, 0x006c6b14, 0x00716e14, 0x007d7414, 0x009f8a16, 0x00c09e19, 0x00cca71a, 0x00cba51a, 0x00b49618, 0x00716c14, 0x00626313, 0x005e5f13, 0x005c5c11, 0x00585911, 0x00555610, 0x00515110, 0x004d4e0f, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x000f130b, 0x000f130f, 0x000f130f, 0x0008100b, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040f09, 0x0005100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00070f08, 0x00081009, 0x00060e08, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d05, 0x00040c08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00060e08, 0x0008110b, 0x0008110a, 0x0008110b, 0x00061009, 0x000a130c, 0x000f150f, 0x000f150f, 0x00101510, 0x00121712, 0x00141812, 0x00141810, 0x00161912, 0x00181913, 0x00181913, 0x001a1a12, 0x001c1c14, 0x001b1c14, 0x001b1c14, 0x001a1b14, 0x001a1b14, 0x001b1c16, 0x001b1c16, 0x001a1b15, 0x001a1b15, 0x00171913, 0x00151a13, 0x00141811, 0x00111610, 0x00101411, 0x00101411, 0x00121613, 0x00101512, 0x000e140f, 0x000d140e, 0x000d140e, 0x000c120c, 0x000b110c, 0x0009120c, 0x00081009, 0x0008110a, 0x00070f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x0008110a, 0x0009120c, 0x000a110d, 0x000d1210, 0x00101410, 0x0015140e, 0x001c1510, 0x0020170f, 0x00271b0a, 0x00311f08, 0x0044280c, 0x006f4c14, 0x00aa8628, 0x00c5a524, 0x00cbae20, 0x00ccb017, 0x00cbb310, 0x00ccb410, 0x00ccb410, 0x00cbb50c, 0x00cab408, 0x00cbb508, 0x00cbb508, 0x00ccb112, 0x00b99513, 0x00845b00, 0x00683e04, 0x005a380c, 0x004a310c, 0x00402e0c, 0x003b2a09, 0x003b2a09, 0x003c2b0a, 0x00392808, 0x00372808, 0x00342508, 0x00332307, 0x0033220a, 0x002f220b, 0x00261e08, 0x00201e08, 0x001e1f0b, 0x001b1f0c, 0x00141807, 0x000c1002, 0x000b0d04, 0x000a0d04, 0x000c0e06, 0x000d0f07, 0x000d0f07, 0x00101009, 0x00101008, 0x00141208, 0x00161105, 0x00181203, 0x00221908, 0x00372817, 0x00483421, 0x004c331c, 0x00503218, 0x00543417, 0x00583718, 0x00533310, 0x0050300c, 0x004c2c09, 0x004b2809, 0x004a270b, 0x00482509, 0x004a260a, 0x00492608, 0x004a2709, 0x004c280a, 0x004e290b, 0x004e290c, 0x004d280a, 0x004c2808, 0x00482606, 0x00482505, 0x004b2908, 0x004e2d0b, 0x00502f0c, 0x004c2c08, 0x004b2b08, 0x004d2f0a, 0x0051310f, 0x00492a0b, 0x00402408, 0x003d230c, 0x002d1704, 0x00211000, 0x001c0f04, 0x00191005, 0x00151108, 0x0013120b, 0x00101009, 0x00101008, 0x000e0e06, 0x000e0d04, 0x000e0d04, 0x00100e06, 0x00121207, 0x00161409, 0x00171408, 0x001a160b, 0x001b150b, 0x001c150b, 0x001f170b, 0x00251c0d, 0x0028200d, 0x00281e0a, 0x002c200a, 0x0030220b, 0x00312109, 0x00312109, 0x00302108, 0x00302308, 0x00302206, 0x002d1e04, 0x002d1a03, 0x00321902, 0x00381a01, 0x00381600, 0x00331804, 0x002c1605, 0x00241106, 0x001d0e08, 0x001a0e0c, 0x001a100d, 0x0018100b, 0x00161008, 0x00141108, 0x00131108, 0x00121008, 0x00111108, 0x000e0e05, 0x000d0f07, 0x000c1008, 0x000a0f08, 0x000c120b, 0x000c140d, 0x0008110b, 0x0009130f, 0x00081410, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x00091310, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0004100c, 0x0005100c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100c, 0x0006100c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0007100d, 0x00050f0c, 0x0005100c, 0x0006110d, 0x0006110d, 0x0006110d, 0x0006110d, 0x0007110d, 0x0007110d, 0x00091310, 0x00091310, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x000b130e, 0x000c1410, 0x000d150f, 0x000d160d, 0x00101710, 0x00111810, 0x00111810, 0x00101710, 0x00121711, 0x00131712, 0x00141813, 0x00141914, 0x00141a14, 0x00151c15, 0x00151c15, 0x00161c15, 0x00171c14, 0x00181c15, 0x00181c15, 0x001a1d17, 0x00181c15, 0x00171c17, 0x00161b15, 0x00151a14, 0x00141813, 0x00141614, 0x00111611, 0x00101610, 0x000e160e, 0x000d1410, 0x000c1410, 0x000c140f, 0x000a120e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120c, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120d, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f1612, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x0014180a, 0x001d2009, 0x001d2008, 0x0024250b, 0x00292b0b, 0x002d2f0b, 0x0030310c, 0x0036370c, 0x003b3c0d, 0x0040400d, 0x0045470e, 0x004b4c0f, 0x00505010, 0x00545510, 0x00585911, 0x005c5d12, 0x00786c14, 0x00cca518, 0x00caa419, 0x00b19518, 0x00af9418, 0x00b09418, 0x00b09418, 0x00b09518, 0x00b09518, 0x00b09518, 0x00b09518, 0x00b09518, 0x00b09518, 0x00b09418, 0x00b09418, 0x00af9418, 0x00af9318, 0x00af9318, 0x00af9318, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00ae9117, 0x00ae9117, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00af9218, 0x00af9318, 0x00af9318, 0x00af9418, 0x00b39618, 0x00bc9c18, 0x00c8a519, 0x00cca71a, 0x00cca71a, 0x00c8a419, 0x00a48c17, 0x006d6a14, 0x00646514, 0x00626314, 0x00606013, 0x005c5d11, 0x00595a11, 0x00555610, 0x00525310, 0x004d4e0f, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x0006100b, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00081009, 0x00081009, 0x00060e08, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d06, 0x00040c08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00060e08, 0x0009120b, 0x0008110a, 0x0008110b, 0x0009130c, 0x000c140d, 0x00101711, 0x00101711, 0x00101510, 0x00141612, 0x00141812, 0x00151811, 0x00181a12, 0x00181a14, 0x00191a13, 0x001a1a12, 0x001d1c14, 0x001c1c14, 0x001b1c14, 0x001a1b14, 0x001a1b14, 0x001b1c16, 0x001b1c16, 0x001a1b15, 0x001a1b15, 0x00161913, 0x00151a13, 0x00141811, 0x00111610, 0x00101411, 0x00101411, 0x00101411, 0x000f1310, 0x000d120e, 0x000a130c, 0x000a130c, 0x0008110a, 0x0008110a, 0x00061009, 0x00040f08, 0x00051008, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x00081109, 0x0009120a, 0x000a120c, 0x000d130f, 0x0012140f, 0x0015140e, 0x001c160f, 0x0020160c, 0x00261b08, 0x002d1c04, 0x003c2109, 0x00542f06, 0x00734d04, 0x0099710d, 0x00b68f1d, 0x00be981a, 0x00c5a318, 0x00caaa14, 0x00ccb013, 0x00ccb10e, 0x00ccb208, 0x00ccb208, 0x00ccb00b, 0x00caaa12, 0x00ac8208, 0x00805100, 0x00683e04, 0x0058380b, 0x004a3308, 0x00403008, 0x003f2f09, 0x003f2f0a, 0x00402f0a, 0x003e2c08, 0x003c2b07, 0x003b2807, 0x00382508, 0x00382409, 0x0034250c, 0x002b2109, 0x00241e08, 0x00201f09, 0x001c1f0b, 0x00161b08, 0x00111405, 0x000c0f03, 0x000c0e04, 0x000c0e06, 0x000d0f07, 0x000d0f07, 0x000e1109, 0x000f1009, 0x0012120a, 0x00141208, 0x00151306, 0x00171402, 0x00181100, 0x002d210e, 0x0044301c, 0x004f341c, 0x00523418, 0x00503415, 0x004f3210, 0x004f310e, 0x004b2c0b, 0x0048280a, 0x004c2a0d, 0x004b290c, 0x00472507, 0x00482707, 0x004c2a0a, 0x004b2a09, 0x004b2808, 0x004a2808, 0x00492706, 0x00492805, 0x00472605, 0x00462605, 0x00492b09, 0x004d2f0b, 0x0050320c, 0x004d3009, 0x004b2e0b, 0x004d300e, 0x004b2f10, 0x0041280e, 0x00371e0c, 0x00281102, 0x001e0d00, 0x001a1004, 0x00181106, 0x00181108, 0x0016140b, 0x0012140c, 0x0010120a, 0x00101009, 0x000d0f07, 0x000c0e04, 0x000e0d04, 0x00100e06, 0x00121207, 0x00161406, 0x00161406, 0x00181609, 0x00181808, 0x00201705, 0x00251a05, 0x002c2008, 0x002e2408, 0x002f2207, 0x00332308, 0x0036240b, 0x00352108, 0x00332107, 0x00302005, 0x002f2105, 0x002f2105, 0x002d1e04, 0x002c1b03, 0x002f1905, 0x00301808, 0x002e1408, 0x00271809, 0x00231707, 0x00201609, 0x001c1408, 0x00181105, 0x00171106, 0x00171008, 0x00171009, 0x00141008, 0x00131008, 0x00121008, 0x000f0f05, 0x000e0e04, 0x000c0d05, 0x000b0e05, 0x000a0f08, 0x000c120b, 0x000b130b, 0x0009120b, 0x0009130c, 0x0007120c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008120f, 0x0007100d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100c, 0x0005100c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100c, 0x0006100c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x00040f0c, 0x00050f0c, 0x0006100d, 0x0006110d, 0x0006110d, 0x0005100c, 0x0005100c, 0x0007110d, 0x0007110d, 0x00091310, 0x00091310, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009110c, 0x000a120e, 0x000c140e, 0x000d160d, 0x000f150d, 0x0010160e, 0x0010170f, 0x00101710, 0x00121711, 0x00141813, 0x00141813, 0x00141813, 0x00141a14, 0x00151c15, 0x00151c15, 0x00161c15, 0x00171c14, 0x00181c15, 0x00181c15, 0x001a1d17, 0x00181c15, 0x00171c17, 0x00161b15, 0x00151a14, 0x00151a14, 0x00161815, 0x00141813, 0x00131712, 0x00101710, 0x00101510, 0x000e1510, 0x000d1510, 0x000b130f, 0x0009130e, 0x0008120d, 0x0008120d, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0041420d, 0x0045470e, 0x004b4c0f, 0x00505010, 0x00545511, 0x00585911, 0x005d5e12, 0x006d6813, 0x00bd9c18, 0x00cca61a, 0x00cca71a, 0x00cca71a, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca71a, 0x00cca71a, 0x00cca61a, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca61a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cba61a, 0x00c9a41a, 0x00b59818, 0x00887a16, 0x00686814, 0x00686814, 0x00646514, 0x00626313, 0x00606013, 0x005c5d11, 0x00595a11, 0x00555611, 0x00525310, 0x004d4e0f, 0x00494a10, 0x0045470e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070e0c, 0x00070f0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x00081009, 0x00081009, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00050e08, 0x00091009, 0x0009120c, 0x000b130c, 0x000b150e, 0x000c140e, 0x000c140e, 0x00101610, 0x00131813, 0x00161814, 0x00181814, 0x00181814, 0x00191a14, 0x001b1b14, 0x001d1b14, 0x001c1b14, 0x001b1a14, 0x001e1d16, 0x001e1e18, 0x001c1b16, 0x001a1b15, 0x001a1b15, 0x00181c15, 0x00181c15, 0x00171812, 0x00171812, 0x00111711, 0x00111711, 0x00101610, 0x000e140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000d110d, 0x000b110c, 0x0009120a, 0x00081108, 0x00081008, 0x00081009, 0x0006100a, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00071008, 0x00071007, 0x00071007, 0x00081008, 0x0008110a, 0x000a110b, 0x000d130d, 0x0012140f, 0x0015140e, 0x001b150e, 0x001e140b, 0x00241809, 0x002a1a08, 0x00371d09, 0x00442203, 0x00552e00, 0x00683d00, 0x00764a01, 0x00845801, 0x00946806, 0x00aa800b, 0x00b8910f, 0x00c39e12, 0x00c9a510, 0x00cba814, 0x00cca81a, 0x00bd9410, 0x00946800, 0x00784c02, 0x0064400c, 0x00573a0b, 0x004a3408, 0x00433309, 0x00413209, 0x00413209, 0x00413209, 0x00413208, 0x00423007, 0x003d2d06, 0x003b2b06, 0x00392b08, 0x00352808, 0x002d2406, 0x00261f05, 0x00211e07, 0x00201e0a, 0x001e1d0c, 0x00181709, 0x000c1002, 0x000c0f04, 0x000d0f05, 0x000d0f05, 0x000c0e05, 0x000f1008, 0x000d1008, 0x00101008, 0x0016140b, 0x0017140c, 0x0018140b, 0x00191509, 0x00181002, 0x00241807, 0x00382610, 0x00432f14, 0x00442f13, 0x00472f11, 0x00482d0e, 0x004c2c0e, 0x00482809, 0x004c280b, 0x004d2b0c, 0x004b2b0c, 0x004a2a0b, 0x00462707, 0x00472808, 0x00472808, 0x00482809, 0x00482809, 0x00482809, 0x00482c0c, 0x00472c0c, 0x00482c0c, 0x004b2f0e, 0x004b300c, 0x00503414, 0x00493012, 0x0044290f, 0x003b230c, 0x002e1807, 0x00241204, 0x00201004, 0x001c1106, 0x00181105, 0x00171107, 0x00171008, 0x0014130a, 0x00131209, 0x00101007, 0x00101008, 0x000e0f08, 0x000d0f07, 0x000f0f05, 0x00131107, 0x00161409, 0x00181408, 0x00181407, 0x001a1507, 0x001d1707, 0x00261908, 0x002a1b08, 0x0030200a, 0x00403014, 0x003d2c0c, 0x003d2b09, 0x003e2b05, 0x00402a07, 0x00402a0c, 0x00392307, 0x00352006, 0x00321f06, 0x00301e04, 0x002e1c04, 0x002c1a06, 0x002b1908, 0x00271606, 0x00241705, 0x00221604, 0x00201605, 0x001b1302, 0x00181304, 0x00181106, 0x00181109, 0x0017100a, 0x0016100a, 0x00141109, 0x00121008, 0x00100e05, 0x00100f06, 0x000e0f05, 0x000c0f06, 0x000c1007, 0x000c1108, 0x000a1008, 0x000a1008, 0x0009120c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x00060e0b, 0x0008100c, 0x0008120d, 0x0007110c, 0x0005100b, 0x0007100c, 0x0008100c, 0x0005100b, 0x0006100b, 0x0005110b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f0a, 0x0008110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006110c, 0x0008100c, 0x00050d09, 0x00060f0a, 0x000a120e, 0x0009110d, 0x0008100c, 0x0009130e, 0x0005100b, 0x0008120c, 0x0007110a, 0x0009140c, 0x000a140b, 0x000c150c, 0x000d160d, 0x000f150d, 0x0010160e, 0x00101710, 0x00111812, 0x00131812, 0x00141914, 0x00141914, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161c12, 0x00171c14, 0x00171c14, 0x00171c14, 0x00171c14, 0x00171c17, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161b15, 0x00151a14, 0x00141813, 0x00131712, 0x00101510, 0x000f150f, 0x000e140f, 0x000c140e, 0x000a130c, 0x0009120c, 0x0009120c, 0x0008110a, 0x00070f08, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x0007100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0038380c, 0x003b3c0c, 0x0041420d, 0x0047480f, 0x004c4d0f, 0x00505010, 0x00545511, 0x00595a12, 0x005d5e12, 0x00606013, 0x007d7314, 0x00b09418, 0x00b29618, 0x00b39718, 0x00b39818, 0x00b49819, 0x00b49819, 0x00b49819, 0x00b49819, 0x00b49819, 0x00b49819, 0x00b39819, 0x00b39718, 0x00b39618, 0x00b29618, 0x00b29618, 0x00b19518, 0x00b19518, 0x00b19418, 0x00b19317, 0x00b19317, 0x00b19317, 0x00b09317, 0x00b09317, 0x00b19317, 0x00b19317, 0x00b19317, 0x00b19417, 0x00b19518, 0x00b19518, 0x00b19518, 0x00b29618, 0x00b29618, 0x00b19518, 0x00ad9218, 0x009f8a17, 0x00837815, 0x006c6b14, 0x00696914, 0x00686814, 0x00666714, 0x00656614, 0x00626313, 0x00606013, 0x005c5d11, 0x00595a11, 0x00565711, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070e0c, 0x00070f0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f08, 0x00081009, 0x00081009, 0x00081009, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x0008110a, 0x000a1009, 0x0009130c, 0x000b130c, 0x000b150e, 0x000d150f, 0x000d150f, 0x00101610, 0x00141813, 0x00181814, 0x00181814, 0x00181814, 0x00191b14, 0x001b1b14, 0x001c1c14, 0x001c1b14, 0x001c1b14, 0x001e1d16, 0x001d1e18, 0x001b1c16, 0x001a1b15, 0x001a1b15, 0x00181c15, 0x00181c15, 0x00161812, 0x00161812, 0x00111611, 0x00101711, 0x00101610, 0x000d140e, 0x000d130d, 0x000c130d, 0x000c120c, 0x000b100b, 0x0009110a, 0x00081108, 0x00081108, 0x00081008, 0x00081009, 0x0006100b, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100a, 0x00081009, 0x00081008, 0x00081007, 0x0008110a, 0x0009120c, 0x000a120c, 0x000c120c, 0x0011140f, 0x0015140e, 0x001b150c, 0x001c1409, 0x00221708, 0x0028180a, 0x00311a08, 0x00391c01, 0x00442201, 0x00502c05, 0x00583204, 0x005e3700, 0x00684000, 0x00714800, 0x007b5200, 0x00886001, 0x00966d07, 0x00a2780c, 0x00ab8013, 0x00996e09, 0x007d5200, 0x006c4406, 0x005d3d0d, 0x0054390a, 0x004c3609, 0x0048350a, 0x0048360b, 0x0048360b, 0x0048350a, 0x00483509, 0x00463408, 0x00413106, 0x003c2f06, 0x003b2f08, 0x00372c08, 0x00302705, 0x00272003, 0x00241e05, 0x00221d0a, 0x00201c0c, 0x0018180a, 0x000f1104, 0x000d1004, 0x000f1007, 0x000d0f05, 0x000c0e04, 0x000d0f05, 0x000c1005, 0x00101008, 0x00141109, 0x0017130b, 0x0016140c, 0x0018140b, 0x001c140a, 0x001d1407, 0x00241906, 0x00271803, 0x0033210a, 0x00402a13, 0x00432c10, 0x00472c12, 0x00492c10, 0x0049280b, 0x0048280a, 0x0047280c, 0x0046280c, 0x0045270b, 0x0045280c, 0x0047280c, 0x0048290d, 0x0047280c, 0x0047280c, 0x00442a0d, 0x00442a0e, 0x00432a0d, 0x00442b0e, 0x003c2308, 0x003d240c, 0x00381e09, 0x00311705, 0x002b1404, 0x00241003, 0x00201004, 0x00201408, 0x001d1408, 0x001a1508, 0x00181308, 0x00171008, 0x00151109, 0x00131008, 0x00100e05, 0x00110f07, 0x00100f08, 0x000f0e07, 0x00100e05, 0x00131107, 0x00181408, 0x00191408, 0x001b1407, 0x001e1508, 0x00221809, 0x002a1c0c, 0x002d1d0c, 0x00382411, 0x004b3519, 0x0049300e, 0x004e3209, 0x00533706, 0x00563808, 0x0058390a, 0x004f3305, 0x00452b04, 0x003c2406, 0x00362006, 0x00301d06, 0x002c1c07, 0x00291b08, 0x00261808, 0x00241506, 0x00241508, 0x00221608, 0x001c1404, 0x00191204, 0x00181107, 0x00181109, 0x0017100b, 0x0016100b, 0x0014100a, 0x00121008, 0x00110f07, 0x00110f07, 0x000f0f05, 0x000d0f05, 0x000c1007, 0x000b1007, 0x000b1007, 0x000b1008, 0x000a110b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0009110e, 0x0008100c, 0x0008100b, 0x00071009, 0x00061009, 0x00051109, 0x0008100b, 0x0008100c, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x0006100b, 0x00040f09, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0007100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x0007110c, 0x0006120c, 0x0008120c, 0x0007110a, 0x0008130a, 0x00081308, 0x000a130b, 0x000c150c, 0x000f150d, 0x000d140c, 0x000e150e, 0x00111812, 0x00121812, 0x00141813, 0x00141914, 0x00141914, 0x00161b15, 0x00161b14, 0x00161c12, 0x00161c12, 0x00161c12, 0x00171c14, 0x00171c14, 0x00171c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00161b15, 0x00151a14, 0x00141813, 0x00131712, 0x00101510, 0x000f150f, 0x000d140e, 0x000e150f, 0x000b140d, 0x000a130c, 0x0009120c, 0x0009120c, 0x00081009, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x003b3c0c, 0x0041420d, 0x0047480f, 0x004c4d0f, 0x00505010, 0x00555610, 0x00595a12, 0x005d5e12, 0x00606013, 0x00646314, 0x00686614, 0x006c6914, 0x006d6b14, 0x00706d15, 0x00706e15, 0x00716f16, 0x00716f16, 0x00716f16, 0x00716f15, 0x00706e15, 0x006f6c15, 0x006f6d15, 0x006e6c15, 0x006c6b14, 0x006c6a14, 0x006a6814, 0x00686714, 0x00686614, 0x00656414, 0x00656413, 0x00646312, 0x00646313, 0x00646313, 0x00646312, 0x00646313, 0x00656414, 0x00666514, 0x00686714, 0x00696813, 0x006a6814, 0x006c6a14, 0x006c6a14, 0x00706d14, 0x00706d14, 0x006f6d14, 0x006f6d14, 0x006f6d14, 0x006e6c14, 0x006d6c14, 0x006c6914, 0x006a6814, 0x00686713, 0x00656413, 0x00626011, 0x005e5d11, 0x00565711, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0040400d, 0x003b3c0c, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00031008, 0x00041008, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f0a, 0x00070f0a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x00081009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x0009120c, 0x000a120c, 0x000b140d, 0x000c140e, 0x000c1710, 0x000e1610, 0x000f160f, 0x00111610, 0x00151812, 0x00181914, 0x00181a14, 0x00191a14, 0x001a1b14, 0x001c1c15, 0x001c1d16, 0x001c1d15, 0x001c1d15, 0x001c1c15, 0x001b1c16, 0x001a1b15, 0x00181a14, 0x00181a14, 0x00171913, 0x00161913, 0x00141811, 0x00141811, 0x00101510, 0x000f1510, 0x000e150f, 0x000c140d, 0x000b130c, 0x000a130c, 0x000a120c, 0x00081009, 0x00071008, 0x00081008, 0x00081008, 0x00071007, 0x00071009, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100a, 0x00081008, 0x0008110a, 0x0009120c, 0x000a120c, 0x000c110c, 0x0011130e, 0x0015140d, 0x001a140c, 0x001c1308, 0x001f1408, 0x00241608, 0x002a1809, 0x00311a05, 0x00371c04, 0x003b2108, 0x00402408, 0x00482907, 0x004f2e04, 0x00583405, 0x005a3602, 0x005f3900, 0x00633f00, 0x00694400, 0x00704700, 0x00694200, 0x005c3700, 0x00543201, 0x004e3406, 0x004b3204, 0x004b3104, 0x004c3509, 0x004c3508, 0x004a3407, 0x00483306, 0x00493407, 0x00463408, 0x0047370c, 0x0041340c, 0x0040340c, 0x003c310a, 0x00382b08, 0x002c2204, 0x00281f04, 0x0026200c, 0x00221f0c, 0x001b1b0a, 0x00141508, 0x00101104, 0x000d0f04, 0x000c0d04, 0x000c1005, 0x000c1007, 0x000d1008, 0x00101008, 0x00131008, 0x00141008, 0x0014130a, 0x0018140b, 0x001d160b, 0x0021180b, 0x0023180a, 0x00241505, 0x00241302, 0x00281403, 0x00291701, 0x0034210a, 0x003f2811, 0x0040280d, 0x0041270c, 0x0043280e, 0x0045280f, 0x00462810, 0x00462810, 0x0045280f, 0x0044260d, 0x0041240c, 0x003f2309, 0x003c250c, 0x003a2209, 0x00351d04, 0x00351d04, 0x00301802, 0x002c1401, 0x002c1303, 0x002c1408, 0x002a150a, 0x0027160c, 0x00211408, 0x001f1406, 0x001c1708, 0x001b1608, 0x00191408, 0x00171108, 0x0016120a, 0x00141008, 0x00100e05, 0x00110f07, 0x00100f08, 0x00100f08, 0x00110f06, 0x00151108, 0x00191408, 0x001b1408, 0x001c1307, 0x00201507, 0x00251808, 0x002b1d0b, 0x0032220e, 0x003d2910, 0x004c3410, 0x00593b0b, 0x006c480c, 0x007c5810, 0x00896616, 0x00947020, 0x007e5b0f, 0x00583600, 0x004c2e04, 0x0041280c, 0x00342008, 0x002f1d09, 0x002a1c09, 0x0029190b, 0x00241608, 0x00241409, 0x00211408, 0x001c1305, 0x00191105, 0x00181108, 0x0018110b, 0x0017100b, 0x0016100b, 0x0014100a, 0x00141008, 0x00121008, 0x00110f07, 0x000e0e04, 0x000d0f05, 0x000c1007, 0x000c1108, 0x000c1007, 0x000c0f08, 0x000a0f09, 0x0009100a, 0x0008100c, 0x0008100c, 0x0009110c, 0x000a120e, 0x0008110a, 0x0007100a, 0x00061009, 0x00051109, 0x0008100c, 0x0008100c, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x0006100b, 0x00040e09, 0x0005100a, 0x0007110c, 0x0006110c, 0x0005110b, 0x0006120c, 0x0006120c, 0x0006100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100b, 0x00070f0a, 0x0007110c, 0x0003100a, 0x00061009, 0x00051008, 0x00071208, 0x00081308, 0x0009120a, 0x000a120a, 0x000c130b, 0x000c140c, 0x000c130c, 0x00101610, 0x00111711, 0x00111611, 0x00121712, 0x00131812, 0x00141813, 0x00141912, 0x00151a11, 0x00161c12, 0x00161c12, 0x00171c13, 0x00171c14, 0x00181d16, 0x00181d16, 0x00171c15, 0x00171c15, 0x00171c16, 0x00151a14, 0x00141914, 0x00131712, 0x00111611, 0x00101510, 0x000f150f, 0x000e150f, 0x000c140e, 0x000b140d, 0x000a130c, 0x0009120c, 0x00081009, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x003b3c0c, 0x0041420d, 0x0047480f, 0x004c4d0f, 0x00505010, 0x00545511, 0x00595a12, 0x005d5e12, 0x00756c14, 0x00c29f18, 0x00c2a019, 0x00c2a119, 0x00c2a11a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x009e8918, 0x006a6a14, 0x00686814, 0x00686814, 0x00656614, 0x00646514, 0x00636413, 0x00616112, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00626312, 0x00636413, 0x00646414, 0x00646514, 0x00656614, 0x00686814, 0x006b6914, 0x00bc9c18, 0x00c4a119, 0x00c4a119, 0x00c4a119, 0x00c4a119, 0x00c4a119, 0x00c4a019, 0x00c4a019, 0x00c4a019, 0x00c39f18, 0x00c39e18, 0x00c39e18, 0x00aa8c14, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003b3c0c, 0x0036370c, 0x0032330c, 0x002d2f0a, 0x0026280a, 0x0026280c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00031008, 0x00041008, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x0006100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00050f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x00081009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00081009, 0x0009120c, 0x000b130c, 0x000c140d, 0x000c160f, 0x000c1710, 0x000e1610, 0x00111810, 0x00141911, 0x00181b14, 0x001b1c16, 0x001b1c16, 0x001c1c17, 0x001c1d17, 0x001c1e16, 0x001c1e16, 0x001c1e16, 0x001c1c15, 0x001a1b14, 0x001b1a15, 0x001b1a15, 0x00181913, 0x00171812, 0x00151812, 0x00141710, 0x00141710, 0x00131610, 0x0010140f, 0x000f150f, 0x000c140e, 0x000b130c, 0x0009120c, 0x0008120c, 0x0008120c, 0x00071009, 0x00060f08, 0x00081008, 0x00081008, 0x00071007, 0x00070f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100d, 0x0008100c, 0x0008100c, 0x0008100a, 0x0008110a, 0x0009120c, 0x000a120c, 0x000c110c, 0x0011130e, 0x0014140c, 0x0019140b, 0x001c1208, 0x001e1407, 0x0021140a, 0x0026170c, 0x00291808, 0x002e1b08, 0x00331d0a, 0x00371e0a, 0x003c2008, 0x00412406, 0x00492a07, 0x004a2b05, 0x004c2d04, 0x00513105, 0x00543103, 0x00543004, 0x00543005, 0x00503008, 0x004a2f06, 0x00483306, 0x004f3809, 0x005b3d10, 0x005e4012, 0x005b3e10, 0x00573c0d, 0x004e3304, 0x004c3103, 0x00443104, 0x003f3004, 0x003d3004, 0x0040340b, 0x0041340d, 0x003c2f0b, 0x00332708, 0x002c2004, 0x00282008, 0x0024200c, 0x00201f0c, 0x00181909, 0x00101104, 0x000c0e03, 0x000b0c03, 0x000c1005, 0x000c1007, 0x000d1008, 0x00101007, 0x00131008, 0x00151109, 0x00141109, 0x0018140b, 0x001c150b, 0x0020180c, 0x0023190d, 0x0024190e, 0x0028180e, 0x0029190c, 0x00251708, 0x00231704, 0x00281905, 0x002a1801, 0x002c1700, 0x00361c05, 0x003c230c, 0x003e240e, 0x003f250e, 0x003c230c, 0x003b200a, 0x00381f08, 0x00351c05, 0x00301b04, 0x00311b04, 0x002f1902, 0x002d1800, 0x002c1600, 0x002d1804, 0x002c1807, 0x00291406, 0x002b180f, 0x0027180f, 0x00211608, 0x001f1506, 0x001d1707, 0x001a1508, 0x00181308, 0x00181108, 0x0016120a, 0x00141008, 0x00100e05, 0x00110f07, 0x00100f08, 0x00111009, 0x00140f07, 0x00181207, 0x00191408, 0x001b1406, 0x001f1406, 0x00221706, 0x00261808, 0x002d2008, 0x0037280a, 0x0046300c, 0x00583c0c, 0x008a6825, 0x00aa872d, 0x00b9982b, 0x00c6a62c, 0x00c8a62d, 0x00b48b21, 0x00785001, 0x00553400, 0x00462908, 0x0038240c, 0x00311f09, 0x002c1c09, 0x002a1b0a, 0x00261808, 0x00241507, 0x00201404, 0x001b1302, 0x00181204, 0x00181106, 0x0018110b, 0x0017100c, 0x0016100b, 0x00151009, 0x00141008, 0x00121008, 0x00111008, 0x00101007, 0x000f1007, 0x000d1008, 0x000c1108, 0x000c1007, 0x000c0f08, 0x000b0e09, 0x000a0f09, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100c, 0x0008110b, 0x0007110a, 0x00061009, 0x00051109, 0x0008110c, 0x0008100c, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x0006100b, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0005110b, 0x0006120c, 0x0007130c, 0x0006100a, 0x00060e09, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00060e09, 0x0006100b, 0x00030f09, 0x00051008, 0x00051008, 0x00061108, 0x00061106, 0x00081008, 0x00081108, 0x000b110a, 0x000c120b, 0x000c120c, 0x00101610, 0x00101610, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00121710, 0x00141810, 0x00161c12, 0x00161c12, 0x00161c12, 0x00171c13, 0x00181d15, 0x00181d15, 0x00181d15, 0x00171c14, 0x00171c17, 0x00161b15, 0x00151a14, 0x00141813, 0x00131712, 0x00101711, 0x00101610, 0x000f1610, 0x000e1610, 0x000c140d, 0x000a130c, 0x0009120c, 0x00081009, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x003b3c0c, 0x0041420d, 0x0047480f, 0x004c4d0f, 0x00505010, 0x00545511, 0x00585911, 0x005d5e12, 0x00786d14, 0x00cca519, 0x00cca619, 0x00cca71a, 0x00cca71a, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00a48c18, 0x00696914, 0x00686814, 0x00666714, 0x00646514, 0x00636413, 0x00616112, 0x00606013, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00616112, 0x00636413, 0x00646414, 0x00646514, 0x00656614, 0x006b6814, 0x00c4a119, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca61a, 0x00cca619, 0x00cca619, 0x00cca519, 0x00cca418, 0x00cca418, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003b3c0c, 0x0036370b, 0x0034350c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00041008, 0x00041008, 0x00051009, 0x00051009, 0x00051009, 0x00051009, 0x0006100a, 0x0006100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00070f09, 0x00070f09, 0x0008100a, 0x0008100a, 0x00081009, 0x00071008, 0x00071008, 0x00071008, 0x00070f08, 0x00070f08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00070f08, 0x0008110b, 0x0009130c, 0x000c140d, 0x000c150e, 0x000c1710, 0x000c180f, 0x00101912, 0x00131a12, 0x00161b14, 0x00181c15, 0x001c1c17, 0x001d1c17, 0x001d1d17, 0x001d1d16, 0x001d1d16, 0x001d1d16, 0x001d1d16, 0x001c1c15, 0x001a1a13, 0x001b1a15, 0x001b1a15, 0x00181813, 0x00151811, 0x00141711, 0x00131611, 0x00111510, 0x0010140f, 0x000f150f, 0x000d140e, 0x000b130c, 0x000a120c, 0x0008110b, 0x0008110b, 0x0008110a, 0x00071009, 0x00060f08, 0x0006100a, 0x0007100a, 0x0006100a, 0x0006100a, 0x0005100a, 0x00051009, 0x00040f08, 0x00040f08, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0007100b, 0x0007100c, 0x0007100b, 0x0007100b, 0x0007100a, 0x0008110b, 0x000a120c, 0x000c110b, 0x0010130c, 0x0013140b, 0x0017140a, 0x00191408, 0x001b1408, 0x0020150c, 0x0023160c, 0x0026180c, 0x002a190b, 0x002d1a0a, 0x00301b09, 0x00341c07, 0x00371e04, 0x003d2207, 0x00402308, 0x0044270b, 0x00472b0c, 0x00482c0b, 0x00482c0b, 0x00482e0c, 0x004b320e, 0x004d3410, 0x0052370f, 0x00644612, 0x006e4c0c, 0x006b4805, 0x006c480c, 0x00644308, 0x005f3f08, 0x00543404, 0x00443000, 0x003c2c00, 0x00392b00, 0x003c2e07, 0x00433611, 0x003f300d, 0x00382a09, 0x002f2303, 0x00292005, 0x0025210a, 0x0024220e, 0x001c1c0a, 0x00121404, 0x000c0f02, 0x000b0d04, 0x000c0f05, 0x000b0f06, 0x000c1008, 0x00101008, 0x0013100a, 0x0016110b, 0x0014110a, 0x0018140c, 0x001c140b, 0x0020180c, 0x00231a0f, 0x00241a0e, 0x00281c0f, 0x002b1d0f, 0x002b1c0c, 0x002d1f0c, 0x002c1e0a, 0x002c1d07, 0x002f1a04, 0x00301701, 0x00321903, 0x00321a04, 0x00341c05, 0x00341b05, 0x00301803, 0x00331c06, 0x00341d07, 0x00301905, 0x00321b07, 0x00341c08, 0x00331b06, 0x00301b04, 0x00301b07, 0x002c1807, 0x002c1808, 0x002c190e, 0x0028180e, 0x00241709, 0x00201607, 0x001e1607, 0x001b1407, 0x00191308, 0x00181008, 0x00141008, 0x00141008, 0x00121008, 0x00121008, 0x00111008, 0x00121008, 0x00141007, 0x00181207, 0x001a1407, 0x001b1204, 0x00201704, 0x00241a07, 0x00281c08, 0x00322309, 0x003d2b09, 0x0050360a, 0x00715114, 0x00b7983a, 0x00c9ae30, 0x00ccb321, 0x00ccb41b, 0x00ccb11b, 0x00c3a01f, 0x00876002, 0x005c3500, 0x004e2f0b, 0x003e280b, 0x0035220b, 0x002c1c06, 0x002a1b09, 0x00251705, 0x00241604, 0x00201404, 0x001b1202, 0x00191104, 0x00181106, 0x00181109, 0x0017100a, 0x00151009, 0x00141008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00101008, 0x000f1008, 0x000d1008, 0x000c0d07, 0x000c0e08, 0x000c0f08, 0x000a100a, 0x0008100b, 0x0007100b, 0x0006100b, 0x0007100c, 0x0008100a, 0x00081009, 0x00071009, 0x00061009, 0x0007100b, 0x0007100b, 0x0006100b, 0x0007100c, 0x0007100b, 0x00060f0a, 0x0007100b, 0x0007100b, 0x0007100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0007110c, 0x0006100c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100b, 0x0007110c, 0x0007120c, 0x0005100a, 0x00060f0a, 0x0006100b, 0x0006100b, 0x0006100b, 0x00050f0a, 0x00040d08, 0x0005100a, 0x0005100a, 0x0006100a, 0x0006100a, 0x0007110a, 0x00071109, 0x00071008, 0x00071008, 0x0008120b, 0x000a120b, 0x000a120c, 0x000e150f, 0x000f1610, 0x00101610, 0x00101610, 0x00111410, 0x00111410, 0x00121510, 0x00121510, 0x00141812, 0x00151a14, 0x00151a14, 0x00151b14, 0x00181c14, 0x00191d15, 0x00191c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00171b15, 0x00161913, 0x00141812, 0x00131711, 0x00121610, 0x00101610, 0x000f160f, 0x000d140e, 0x000c140d, 0x000b130c, 0x0008110b, 0x0009110c, 0x0009110c, 0x0008110b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008110c, 0x0008110c, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0007100b, 0x0007100b, 0x0007100c, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x004b4c0f, 0x00505010, 0x00545511, 0x00585910, 0x005c5d12, 0x00786c14, 0x00cca518, 0x00c8a418, 0x008b7c16, 0x00897c16, 0x00897c17, 0x00887c16, 0x00887c16, 0x00887c16, 0x00887c17, 0x00867b16, 0x00b19618, 0x00cca71a, 0x00a48c17, 0x00686814, 0x00666714, 0x00646514, 0x00636413, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005c5d11, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00616112, 0x00636413, 0x00646414, 0x00656614, 0x006a6814, 0x00c4a019, 0x00cca71a, 0x00958316, 0x00887c15, 0x00887a16, 0x00867915, 0x00857816, 0x00847714, 0x00827514, 0x00807414, 0x00998315, 0x00c9a218, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x00292b0b, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x00071007, 0x00071007, 0x00071007, 0x00071008, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x0009120c, 0x000a140c, 0x000c140e, 0x000c1710, 0x000c1710, 0x000d180f, 0x00131b12, 0x00131a13, 0x00171c15, 0x00191c16, 0x001c1b16, 0x001c1c17, 0x001e1c16, 0x001e1d16, 0x001e1d16, 0x001d1d16, 0x001d1d16, 0x001c1c14, 0x001b1912, 0x001b1a15, 0x001b1a15, 0x00171813, 0x00141810, 0x00101610, 0x00101610, 0x000f1610, 0x000c140e, 0x000c140e, 0x000b130c, 0x0009120b, 0x0008100a, 0x00080f09, 0x00080f09, 0x00071008, 0x00070f08, 0x00060f09, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00061009, 0x00040f08, 0x00040f07, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x00061009, 0x0009120b, 0x000b130c, 0x000b1109, 0x000e1109, 0x00101208, 0x00131208, 0x00151308, 0x00181408, 0x001e150c, 0x001f1409, 0x0024180b, 0x0027180b, 0x002a180a, 0x002c1909, 0x00301c09, 0x00301c06, 0x00371f08, 0x003b200a, 0x003d2309, 0x003e260b, 0x003f280c, 0x0040290d, 0x00432c0c, 0x0048340e, 0x00503612, 0x00624115, 0x008d6d2c, 0x00a4842c, 0x00a07e1d, 0x008f6a13, 0x00815d08, 0x00745004, 0x00654204, 0x00573d03, 0x00483404, 0x003d2c01, 0x00342603, 0x003c300d, 0x003f3010, 0x00392b09, 0x00342604, 0x002b2105, 0x00282108, 0x0027230c, 0x00201e0a, 0x00151605, 0x000c1002, 0x000b0e04, 0x000c0f06, 0x000a0f06, 0x000c1007, 0x000f0f08, 0x0014100b, 0x0018120c, 0x0014110b, 0x0018140c, 0x001a130a, 0x001e170c, 0x0022190e, 0x00241a0d, 0x00281c0c, 0x002c1e0d, 0x002c1c0a, 0x002e1d0c, 0x00301f0c, 0x0032200a, 0x00331f08, 0x00372008, 0x0038210a, 0x0039230c, 0x003c260e, 0x003c260f, 0x0038240c, 0x003a230d, 0x0038220c, 0x0038200b, 0x0038200c, 0x0039200c, 0x00341a07, 0x00341c08, 0x00311b07, 0x002c1706, 0x00291808, 0x002a180c, 0x0028170b, 0x00251709, 0x00221508, 0x001f1407, 0x001c1407, 0x001a1308, 0x00181008, 0x00140e08, 0x00131008, 0x00131008, 0x00121008, 0x00131008, 0x00121008, 0x00151108, 0x00181308, 0x001b1407, 0x001d1606, 0x00221c08, 0x00241c06, 0x00281e06, 0x0035260c, 0x00442f0c, 0x00583c0c, 0x007c5a15, 0x00bfa034, 0x00cbb424, 0x00ccb713, 0x00cab810, 0x00cab714, 0x00c4ab1b, 0x00906a01, 0x00643c00, 0x00503208, 0x00422d08, 0x0039260a, 0x00301f04, 0x002b1c08, 0x00271805, 0x00241605, 0x00201406, 0x001c1104, 0x001a1105, 0x00181108, 0x00181009, 0x00171009, 0x00141109, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00111108, 0x000e1008, 0x000e0f08, 0x000f100a, 0x000f100a, 0x000c1009, 0x000a100a, 0x0007100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0009100a, 0x00081009, 0x00081009, 0x00071009, 0x0006100a, 0x0006100b, 0x0007100b, 0x0008100c, 0x0007100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100b, 0x0007110c, 0x0007110c, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x00061009, 0x00061009, 0x00061108, 0x00081109, 0x000c140d, 0x000c140e, 0x000c140e, 0x000f140f, 0x0010140f, 0x0010140f, 0x00121511, 0x00121611, 0x00131712, 0x00151a14, 0x00151a14, 0x00151a14, 0x00181a14, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181c15, 0x00181c15, 0x00181c15, 0x00171913, 0x00171812, 0x00161812, 0x00141811, 0x0012160f, 0x0010140e, 0x000d140e, 0x000d140e, 0x000c140d, 0x0008120c, 0x0009120c, 0x0009120c, 0x0008110a, 0x0008100b, 0x0008100d, 0x0008100d, 0x0007110d, 0x0006110d, 0x0008120d, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x0041420d, 0x0045470e, 0x004b4c0f, 0x004f5010, 0x00545510, 0x00585811, 0x005c5c12, 0x00776c14, 0x00cca518, 0x00c6a219, 0x006b6814, 0x006a6a14, 0x006b6b14, 0x006c6c15, 0x006c6c15, 0x006d6d15, 0x006c6c15, 0x006a6a14, 0x00a99018, 0x00cca71a, 0x00a38b18, 0x00666714, 0x00656614, 0x00636414, 0x00616112, 0x00606013, 0x005d5e12, 0x005c5d11, 0x005c5c11, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x00606013, 0x00616112, 0x00636413, 0x00646414, 0x00686614, 0x00c4a019, 0x00cca61a, 0x007c7315, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00646414, 0x00626313, 0x00887814, 0x00c8a218, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00050f08, 0x00050f08, 0x00050f08, 0x00051008, 0x00051008, 0x00051008, 0x00050f09, 0x00050f0a, 0x00040f0a, 0x0004100a, 0x0004100a, 0x0004100a, 0x00050f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081008, 0x00071007, 0x00071007, 0x00071008, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00071009, 0x0008110a, 0x000a130c, 0x000c140e, 0x000e150f, 0x000f1610, 0x000f1610, 0x00111911, 0x00141b13, 0x00141b12, 0x00181c14, 0x001b1d16, 0x001c1c16, 0x001d1c16, 0x001e1c16, 0x001e1d16, 0x001d1d16, 0x001c1e16, 0x001c1d16, 0x001a1b14, 0x00181912, 0x00191914, 0x00191a14, 0x00151812, 0x00111610, 0x000f1610, 0x000f150f, 0x000d150f, 0x000c140d, 0x0008120c, 0x0008120b, 0x00071009, 0x00071008, 0x00060f08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060f09, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00061009, 0x00040f08, 0x00040f07, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100a, 0x000a130c, 0x000c140d, 0x000c110a, 0x000d1008, 0x000f1007, 0x00111006, 0x00131107, 0x00161307, 0x001b1208, 0x001c1307, 0x00211609, 0x00231608, 0x00251708, 0x0028180a, 0x002c1c0a, 0x002e1e08, 0x00311c06, 0x00341d07, 0x00361f08, 0x00382209, 0x003b250c, 0x003d270c, 0x00432c0d, 0x0048330b, 0x00543b0e, 0x00705118, 0x00b0923d, 0x00caae3d, 0x00c8ac2b, 0x00c4a528, 0x00b8981f, 0x00ac881a, 0x0094700f, 0x006d4e00, 0x00543901, 0x00443004, 0x00382806, 0x00342504, 0x003c2e0d, 0x003b2c0b, 0x00362807, 0x002d2203, 0x002a2006, 0x002a230b, 0x00242009, 0x00181806, 0x000d1002, 0x000c0f04, 0x000b0f06, 0x000a0f07, 0x000c1008, 0x000e0e07, 0x00141009, 0x0018110c, 0x0014110b, 0x0018130c, 0x00191209, 0x001c150b, 0x0021180c, 0x0024180c, 0x00281c0c, 0x002b1e0d, 0x002d1c0b, 0x002e1d0c, 0x002e1d0a, 0x002e1d06, 0x00321c06, 0x00382008, 0x0039210b, 0x00382008, 0x003a230b, 0x003d250c, 0x00392108, 0x003c240c, 0x003c240c, 0x003a220b, 0x0039200a, 0x003a210a, 0x00381e09, 0x00341c08, 0x00321b07, 0x002e1908, 0x002a1707, 0x00281508, 0x00271509, 0x00251609, 0x00221407, 0x00201406, 0x001c1406, 0x001a1208, 0x00171008, 0x00140f08, 0x00131008, 0x00131008, 0x00121008, 0x00131008, 0x00131008, 0x00171108, 0x001a1408, 0x001c1408, 0x00221a0a, 0x0028200d, 0x00271e08, 0x00281e06, 0x0038280d, 0x0048320d, 0x005c3e0d, 0x00836018, 0x00c3a236, 0x00ccb421, 0x00cbb710, 0x00cab80c, 0x00cab80f, 0x00c7ae18, 0x00987303, 0x00684000, 0x00543707, 0x00443006, 0x003b2608, 0x00342304, 0x002d1c05, 0x002b1c08, 0x00241806, 0x00201406, 0x001c1104, 0x001a1105, 0x00181108, 0x00181009, 0x00181009, 0x00141008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00141008, 0x0014130a, 0x000e0f08, 0x000f1008, 0x0010100b, 0x0010100b, 0x000c0f08, 0x000b1009, 0x0007100a, 0x0006100a, 0x0006100a, 0x0008110c, 0x0009100a, 0x00081009, 0x00080f09, 0x00061009, 0x0006100a, 0x0006100b, 0x0007100b, 0x0008100b, 0x0006100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0006100b, 0x0006100b, 0x00050f0a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x00061009, 0x00061009, 0x00061008, 0x00071008, 0x000a120c, 0x000b140d, 0x000c140e, 0x000c140e, 0x000f140f, 0x0010150f, 0x00101610, 0x00101610, 0x00121712, 0x00141914, 0x00151a14, 0x00151a14, 0x00181a14, 0x00181c15, 0x00191c16, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181a14, 0x00171813, 0x00171813, 0x00151811, 0x0012160f, 0x0010140e, 0x000e140f, 0x000e140f, 0x000c140e, 0x0009130c, 0x0009120c, 0x0009120c, 0x0008110a, 0x0008100b, 0x0008100d, 0x0008100d, 0x0007100d, 0x0006110d, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002d2f0b, 0x0030310c, 0x0036370c, 0x003b3c0d, 0x0040400d, 0x0045470e, 0x00494a0f, 0x004f5010, 0x00535410, 0x00585811, 0x005c5c12, 0x00776c14, 0x00cca518, 0x00c6a118, 0x006a6714, 0x00696914, 0x006a6a14, 0x006b6b14, 0x006c6c15, 0x006c6c15, 0x006c6c14, 0x00686814, 0x00a99017, 0x00cca71a, 0x00a38b17, 0x00646514, 0x00646414, 0x00616113, 0x00606013, 0x005d5e12, 0x005c5c11, 0x005b5b12, 0x00595a12, 0x00585911, 0x00585911, 0x00585911, 0x00585911, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00616112, 0x00636413, 0x00686514, 0x00c3a018, 0x00cca619, 0x007c7114, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00646514, 0x00646414, 0x00616112, 0x00887814, 0x00c8a217, 0x00b09015, 0x00525311, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e06, 0x00060e06, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00070f0a, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081008, 0x00081008, 0x00081008, 0x00081008, 0x00081009, 0x00081009, 0x00081009, 0x0008110a, 0x0009120b, 0x000a130c, 0x000c140d, 0x000d140e, 0x00101510, 0x00111610, 0x00121812, 0x00141a13, 0x00151a13, 0x00171a11, 0x00191c14, 0x001d1f17, 0x001e1c15, 0x001d1c15, 0x001e1d16, 0x001d1d17, 0x001c1d17, 0x001b1e16, 0x001b1e15, 0x00181c14, 0x00171810, 0x00161812, 0x00151812, 0x00111610, 0x0010160e, 0x000c150f, 0x000c140d, 0x000b140d, 0x0008110b, 0x0007110a, 0x0007110a, 0x00061009, 0x00061009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060f09, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00061009, 0x00040f08, 0x00040f07, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110c, 0x0009110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007100a, 0x0009110b, 0x000a120c, 0x000b1109, 0x000c1006, 0x000e0f05, 0x00121107, 0x00131107, 0x00151307, 0x00191208, 0x001b1307, 0x001f1508, 0x001e1404, 0x00201408, 0x0024180b, 0x00271908, 0x002b1c08, 0x002f1c07, 0x00311e08, 0x00321f08, 0x0034210b, 0x003a250e, 0x003c260c, 0x00432d0c, 0x004a350b, 0x00583e0a, 0x00795c13, 0x00bba038, 0x00ccb42a, 0x00ccb818, 0x00ccb612, 0x00c8b111, 0x00cbb01b, 0x00c4a41e, 0x0099750e, 0x00674700, 0x004c3400, 0x003d2c05, 0x00342504, 0x00302100, 0x003c2d0c, 0x003a2c0a, 0x00302403, 0x002e2406, 0x002c2309, 0x00272008, 0x001e1b07, 0x00101406, 0x000d1007, 0x000a0f06, 0x000a0f08, 0x000c1008, 0x000d0f07, 0x00100f08, 0x0016100b, 0x0014100b, 0x00161109, 0x001a120a, 0x001c140a, 0x0020170c, 0x0021170a, 0x00261b0b, 0x00291c0b, 0x002e1d0c, 0x002f1e0c, 0x002e1d0b, 0x00301f08, 0x00342009, 0x003a230c, 0x003b230c, 0x003a230a, 0x003c240c, 0x003e250c, 0x003c230a, 0x003d2409, 0x003f250b, 0x003a2109, 0x00381f07, 0x00381f06, 0x00371d05, 0x00341c05, 0x00301a06, 0x002f1a08, 0x002c1909, 0x00281608, 0x00261508, 0x00241608, 0x00211406, 0x001f1306, 0x001b1305, 0x00181108, 0x00170f07, 0x00151008, 0x00131008, 0x00131008, 0x00121008, 0x00121008, 0x00141109, 0x00181309, 0x001c1408, 0x001c1608, 0x00241c0a, 0x002f2711, 0x00291f08, 0x002a1d05, 0x0039290c, 0x0048330a, 0x005d400b, 0x00836017, 0x00c0a030, 0x00ccb420, 0x00cbb80e, 0x00cab80b, 0x00cab80c, 0x00cab215, 0x00a17d05, 0x006e4700, 0x00563804, 0x00483104, 0x003c2704, 0x00372402, 0x002f1d04, 0x002c1c08, 0x00261808, 0x00211406, 0x001d1204, 0x001a1105, 0x00181108, 0x00181009, 0x00161008, 0x00141008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00141008, 0x00141109, 0x00100f08, 0x000f1008, 0x000f100a, 0x000f100a, 0x000d1009, 0x00090f08, 0x00060f08, 0x00070f08, 0x00061009, 0x0008120c, 0x000a100a, 0x00080f08, 0x00070f08, 0x00061008, 0x00051009, 0x0005100a, 0x0006100a, 0x0007100b, 0x0006100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040f09, 0x00040f09, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00040e09, 0x00040f08, 0x00051008, 0x00051008, 0x00071008, 0x0008110b, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c130d, 0x000d140e, 0x00101610, 0x00101610, 0x00111611, 0x00131712, 0x00141814, 0x00141814, 0x00171913, 0x00171913, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181b14, 0x00181a14, 0x00181913, 0x00151811, 0x00121610, 0x0010150e, 0x00101610, 0x00101610, 0x000d150f, 0x000a140d, 0x000a130c, 0x000a130c, 0x0008110b, 0x0008100a, 0x0008100d, 0x0008100d, 0x0006100c, 0x0005100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0006100b, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x0024250b, 0x00292b0b, 0x002d2f0b, 0x0030310c, 0x0036370c, 0x003b3c0d, 0x0040400e, 0x0045470e, 0x00494a10, 0x004d4e0f, 0x00525310, 0x00565711, 0x005b5b12, 0x00766a13, 0x00cca418, 0x00c6a118, 0x00696614, 0x00686814, 0x00696914, 0x006a6a14, 0x006a6a14, 0x006a6a14, 0x006a6a14, 0x00686814, 0x00a99017, 0x00cca61a, 0x00a28a16, 0x00636414, 0x00626313, 0x00606013, 0x005d5e12, 0x005c5c11, 0x00595a12, 0x00585911, 0x00585810, 0x00565710, 0x00565710, 0x00565710, 0x00565710, 0x00585810, 0x00585911, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00616112, 0x00656314, 0x00c3a018, 0x00cca619, 0x007a7014, 0x00656613, 0x00656613, 0x00656614, 0x00656614, 0x00646514, 0x00626313, 0x00606012, 0x00887814, 0x00c8a217, 0x00b09015, 0x00515110, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e06, 0x00060e06, 0x00060e08, 0x00040f08, 0x00040f08, 0x00030f08, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00080f0a, 0x0008100b, 0x0008100b, 0x00060e0a, 0x00040d08, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x0008100a, 0x000c140e, 0x000d140e, 0x000f140f, 0x0010150f, 0x00111610, 0x00131812, 0x00151813, 0x00171913, 0x00161b14, 0x00181b13, 0x001c1c15, 0x001f1e16, 0x001e1c15, 0x001e1c15, 0x001e1d16, 0x001c1d17, 0x001c1d17, 0x00191e16, 0x00181d15, 0x00161c13, 0x00141811, 0x00111610, 0x00101610, 0x000e170e, 0x000c170e, 0x000a140d, 0x0009140c, 0x0008110b, 0x00061009, 0x00061009, 0x0007110a, 0x00061009, 0x00061009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060f09, 0x0006100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00061009, 0x00050f08, 0x00050f08, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0007100a, 0x0008100a, 0x0009110a, 0x000b1008, 0x000b0f06, 0x000d1006, 0x00111108, 0x00121107, 0x00141207, 0x00181207, 0x00191306, 0x001b1306, 0x001b1104, 0x001d1308, 0x00201508, 0x00231808, 0x00261907, 0x00281806, 0x002c1b06, 0x002f1d06, 0x00332009, 0x0038250c, 0x003b270b, 0x0044300c, 0x004d380b, 0x005d440c, 0x00836618, 0x00baa12e, 0x00ccb720, 0x00cbba09, 0x00cbbb05, 0x00cbbb07, 0x00ccb80c, 0x00ccb518, 0x00b79618, 0x00755400, 0x00543a00, 0x00443203, 0x00382a04, 0x002c1c00, 0x00392b0a, 0x003d300c, 0x00372b08, 0x00312807, 0x002f2608, 0x00282006, 0x0024200b, 0x00171608, 0x00101106, 0x000c0f06, 0x000a0f08, 0x000c1007, 0x000d1007, 0x00100f08, 0x00141009, 0x0014110b, 0x00161109, 0x00191209, 0x001c140a, 0x001f150a, 0x00201608, 0x00251909, 0x00281a0b, 0x002c1c0c, 0x002f1d0c, 0x002e1d0b, 0x0032200a, 0x0038240c, 0x003a220c, 0x003a220c, 0x003b230b, 0x003d240c, 0x003e250c, 0x003e250b, 0x003d2309, 0x003d2309, 0x00392008, 0x00371e06, 0x00381f08, 0x00371e08, 0x00341b06, 0x00301805, 0x002d1806, 0x002e1b09, 0x002b180a, 0x00261607, 0x00251608, 0x00211406, 0x00201406, 0x001c1306, 0x00191108, 0x00170f08, 0x00151008, 0x00141008, 0x00131008, 0x00121008, 0x00121008, 0x00141008, 0x0019140a, 0x001e170a, 0x001f1807, 0x0028200c, 0x00352c14, 0x00291e05, 0x002b1d03, 0x0039290a, 0x00483309, 0x005c3f0b, 0x00805d13, 0x00bc9c2c, 0x00cab41d, 0x00cbb80c, 0x00cab908, 0x00cab80a, 0x00cab314, 0x00a88408, 0x00754e00, 0x00573a00, 0x00483303, 0x003e2804, 0x00372401, 0x00301e03, 0x002c1c08, 0x00261808, 0x00221608, 0x001e1407, 0x001a1105, 0x00171208, 0x00161008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00140f08, 0x00110f06, 0x00100f08, 0x000f1008, 0x000f100a, 0x000f1009, 0x000f120b, 0x00080d06, 0x00080f08, 0x00070f08, 0x00071009, 0x0008120b, 0x0008110a, 0x00080f08, 0x00060f08, 0x00061008, 0x00051009, 0x0006100a, 0x0006100a, 0x0008100c, 0x0009120d, 0x0009110c, 0x0009110c, 0x0009110c, 0x0009110c, 0x0009110c, 0x0009110c, 0x0008100b, 0x0008100b, 0x0005100c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0007100c, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040d08, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00040f08, 0x00051008, 0x00051007, 0x00061008, 0x0008100a, 0x0009120c, 0x0009120c, 0x000a130c, 0x000c130d, 0x000c130d, 0x000e150f, 0x00101610, 0x00101510, 0x00121712, 0x00141812, 0x00141812, 0x00161913, 0x00171913, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181b14, 0x00171a14, 0x00141812, 0x00131710, 0x00111610, 0x00101610, 0x00101610, 0x000e150f, 0x000c140e, 0x000b140d, 0x000a130c, 0x0009120b, 0x00081009, 0x0008100c, 0x0008100c, 0x0006100c, 0x0005100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x0040400d, 0x0044450e, 0x00494a10, 0x004d4e0f, 0x00515110, 0x00555610, 0x00595a11, 0x00756a13, 0x00cca418, 0x00c6a118, 0x00686514, 0x00666714, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00656614, 0x00a88f17, 0x00cca619, 0x00a28917, 0x00616113, 0x00606013, 0x005e5f13, 0x005c5c11, 0x00595a12, 0x00585810, 0x00585810, 0x00555610, 0x00545511, 0x00545511, 0x00545511, 0x00545511, 0x00555611, 0x00565710, 0x00585911, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00646113, 0x00c3a018, 0x00cca519, 0x007a7014, 0x00646514, 0x00656614, 0x00646514, 0x00646514, 0x00636414, 0x00626312, 0x00606013, 0x00887714, 0x00c8a117, 0x00b09015, 0x00515110, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040e07, 0x00020e07, 0x00020e07, 0x00020e08, 0x00020e08, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081009, 0x00081009, 0x0008110a, 0x0008110a, 0x000c130d, 0x000f150f, 0x0010140f, 0x00111510, 0x00141810, 0x00151912, 0x00181813, 0x00181913, 0x00181c13, 0x001a1d14, 0x001d1c15, 0x00201c14, 0x001f1c14, 0x001f1c14, 0x001e1c17, 0x001c1c17, 0x001a1d17, 0x00171b14, 0x00151812, 0x00141912, 0x00121911, 0x00101811, 0x000e1610, 0x000c160f, 0x0008150d, 0x0009140c, 0x0008120b, 0x00051008, 0x00051008, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00081009, 0x00081009, 0x00081009, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0006100b, 0x0007100c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0009100b, 0x000a100a, 0x000a1009, 0x00091007, 0x00091006, 0x000b1007, 0x000e1108, 0x00101108, 0x00121006, 0x00151005, 0x00161006, 0x00181105, 0x001a1307, 0x001c1408, 0x001c1408, 0x00201608, 0x00241809, 0x00261809, 0x00291b08, 0x002c1d07, 0x00312006, 0x00382508, 0x003c2809, 0x0046300b, 0x00503a0a, 0x005f460c, 0x00846819, 0x00bda432, 0x00ccb81e, 0x00ccbc09, 0x00cbbc09, 0x00cbbc0a, 0x00caba0c, 0x00cbb910, 0x00b79c0f, 0x00795800, 0x00573c00, 0x00453400, 0x00392c02, 0x002e2000, 0x00382908, 0x003f330d, 0x003b3009, 0x00352c08, 0x00302808, 0x002c2409, 0x00271e08, 0x001f1705, 0x00141104, 0x000d0f07, 0x000b1008, 0x000c1007, 0x000d1007, 0x00101008, 0x00101008, 0x0014110b, 0x00161109, 0x00181108, 0x001b1308, 0x001e1409, 0x00201608, 0x00231809, 0x0028180a, 0x002b1a0a, 0x002e1c0c, 0x00311e0c, 0x00321f09, 0x00341d07, 0x00372008, 0x0039210a, 0x003a220c, 0x003c250e, 0x003e240c, 0x003f250d, 0x003c240a, 0x003c2309, 0x00382008, 0x0038200a, 0x00371f0c, 0x00361e0e, 0x00371c0c, 0x00331a08, 0x00301a08, 0x002e1b08, 0x002c1a08, 0x00281706, 0x00261808, 0x00231507, 0x00201407, 0x001d1407, 0x001b1108, 0x00181008, 0x00171009, 0x00141109, 0x00141109, 0x00131008, 0x00121009, 0x00141008, 0x001a150b, 0x001e1809, 0x00201806, 0x002b210c, 0x00382d14, 0x00281c02, 0x002f2004, 0x003a2808, 0x0048330a, 0x005a3c09, 0x007e5b13, 0x00bc9c2c, 0x00c9b21c, 0x00cbb80c, 0x00cab908, 0x00cab808, 0x00cbb314, 0x00ae880b, 0x00775100, 0x00583b00, 0x004a3401, 0x003f2a04, 0x00382401, 0x00301f04, 0x002d1c08, 0x00271807, 0x00241506, 0x00201307, 0x00181105, 0x00171208, 0x00171109, 0x00141008, 0x00141009, 0x00151109, 0x00151109, 0x00151109, 0x00151109, 0x00141008, 0x00131008, 0x00101009, 0x00101009, 0x00100f08, 0x00100f08, 0x000f1009, 0x000a0f06, 0x000a0f08, 0x00091008, 0x00081008, 0x00071208, 0x0008110a, 0x00061008, 0x00061009, 0x00051109, 0x0008100b, 0x0008100c, 0x0006100a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0009100c, 0x0007110c, 0x0005100a, 0x0007110c, 0x0007110c, 0x0006100b, 0x0008120d, 0x0005100a, 0x0005100a, 0x0005100b, 0x0006100b, 0x0005100b, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00040f09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051008, 0x00051008, 0x00040e06, 0x00050e07, 0x00070f08, 0x0008110a, 0x0008110a, 0x0008110b, 0x000a120c, 0x000c140e, 0x000c140e, 0x000d150f, 0x000f140f, 0x00101610, 0x00121710, 0x00131810, 0x00131712, 0x00151a14, 0x00161b15, 0x00161b15, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181c17, 0x00151a14, 0x00151a14, 0x00141814, 0x00131712, 0x00131712, 0x00101510, 0x00101510, 0x00101510, 0x000d150f, 0x000a120c, 0x0008110b, 0x0008110a, 0x00081009, 0x0008100a, 0x0007110a, 0x00051109, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008110c, 0x0008110c, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003e400c, 0x0044450e, 0x0048490f, 0x004c4d10, 0x00515110, 0x00555611, 0x00585911, 0x00746913, 0x00cca418, 0x00c6a118, 0x00666414, 0x00646514, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00646514, 0x00a88e16, 0x00cca519, 0x00a18816, 0x00606012, 0x005e5f13, 0x005c5d11, 0x005b5b12, 0x00585910, 0x00565710, 0x00555611, 0x00535410, 0x00525310, 0x00525310, 0x00525310, 0x00535410, 0x00545510, 0x00555611, 0x00565710, 0x00585911, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00636013, 0x00c39f18, 0x00cca518, 0x00786e14, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00626313, 0x00616112, 0x00606013, 0x00887614, 0x00c8a117, 0x00b09015, 0x00505010, 0x00515110, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040e07, 0x00020e07, 0x00020e07, 0x00020e08, 0x00020e08, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081009, 0x00081009, 0x0008110a, 0x0009110a, 0x000c130d, 0x00101610, 0x00111610, 0x00121712, 0x00141812, 0x00161913, 0x00181913, 0x00181a14, 0x001a1c14, 0x001c1e16, 0x001e1d16, 0x00201c14, 0x00201c14, 0x001f1c14, 0x001d1c16, 0x001a1c16, 0x00191c16, 0x00181b14, 0x00151812, 0x00131811, 0x00111810, 0x00101711, 0x000e1610, 0x0009140c, 0x0008140d, 0x0009140c, 0x0007110a, 0x00040f08, 0x00040e07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00081009, 0x00081009, 0x00081008, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0006100b, 0x0006100b, 0x00040e09, 0x0007110c, 0x000a140f, 0x0008120d, 0x0007110c, 0x0007110c, 0x0009100b, 0x000a100a, 0x000a1009, 0x00091008, 0x00091006, 0x000a0f06, 0x000d1007, 0x00101108, 0x00121006, 0x00141007, 0x00151008, 0x00151006, 0x00181207, 0x00191409, 0x001a140a, 0x001f1509, 0x0022170a, 0x0025180b, 0x00281c0a, 0x002c1d08, 0x00302008, 0x00352508, 0x003b2908, 0x0044310a, 0x00503a09, 0x0062470c, 0x00886b1a, 0x00c0a835, 0x00ccb820, 0x00ccbb0c, 0x00cbbc09, 0x00cabb0b, 0x00caba0d, 0x00cbb910, 0x00b6980b, 0x007c5900, 0x005c3e00, 0x004a3802, 0x003d3004, 0x00322400, 0x003a2c0a, 0x00413410, 0x003f340a, 0x003b3008, 0x00352b0a, 0x0031250a, 0x002c230b, 0x00211a07, 0x00181404, 0x000f0f05, 0x000c1007, 0x000c1005, 0x000e1208, 0x00101108, 0x00101008, 0x0014110b, 0x00161009, 0x00181108, 0x001b1308, 0x001e1409, 0x001f1406, 0x00221608, 0x00281809, 0x002b190a, 0x002e1c0c, 0x00301d0c, 0x00321f09, 0x00341d08, 0x00371f08, 0x0039210a, 0x003a220c, 0x003c240d, 0x003e240c, 0x003e240d, 0x003c230b, 0x003c230a, 0x003a230a, 0x00382108, 0x00371f0b, 0x00371f0c, 0x00371c0c, 0x00331a08, 0x00301a08, 0x002f1a08, 0x002c1a08, 0x00281706, 0x00261807, 0x00231607, 0x00201407, 0x001d1407, 0x001b1108, 0x00181008, 0x00171009, 0x00141109, 0x00141109, 0x00131008, 0x00131009, 0x00141109, 0x001c170d, 0x001f1809, 0x00201805, 0x00302610, 0x00382c14, 0x002b1d01, 0x00332205, 0x003c2a08, 0x0048340b, 0x005a3d0d, 0x007b5812, 0x00b7972b, 0x00c9b21e, 0x00ccb80c, 0x00cab908, 0x00cbb808, 0x00cbb516, 0x00b08b0c, 0x00785000, 0x005a3b00, 0x004c3501, 0x00412c04, 0x00382401, 0x00301f04, 0x002d1c07, 0x00281806, 0x00241506, 0x00201305, 0x00181105, 0x00171208, 0x00171109, 0x00151008, 0x00141009, 0x00151109, 0x00151109, 0x00151109, 0x00151109, 0x00141008, 0x00131008, 0x00111009, 0x00101009, 0x00100f08, 0x00100f08, 0x000f1009, 0x000c0f05, 0x000a0f06, 0x00091008, 0x000a1008, 0x00081108, 0x0008110a, 0x00061008, 0x00061009, 0x00051109, 0x0008100b, 0x0008100b, 0x0006100a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0007110c, 0x0005100a, 0x0007110c, 0x0007110c, 0x0006100b, 0x0008120d, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040f09, 0x0006100b, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00040f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051008, 0x00051008, 0x00040e06, 0x00050e07, 0x00070f08, 0x0008110a, 0x0008110a, 0x0008110a, 0x0009120c, 0x000c140e, 0x000c140d, 0x000c140e, 0x000d140e, 0x00101610, 0x0010170f, 0x00111810, 0x00131712, 0x00131712, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161b14, 0x00181c15, 0x00181d16, 0x00181c17, 0x00151a14, 0x00151a14, 0x00141814, 0x00131712, 0x00131712, 0x00101510, 0x00101510, 0x00101510, 0x000c140e, 0x0009120b, 0x0008110a, 0x0008110a, 0x0009120c, 0x0009120c, 0x0008130c, 0x00051109, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008110c, 0x0008110c, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250c, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003e400c, 0x0043440e, 0x0048490e, 0x004c4d0f, 0x00505010, 0x00545511, 0x00585810, 0x00746813, 0x00cca418, 0x00c6a018, 0x00656313, 0x00646414, 0x00646514, 0x00666713, 0x00656613, 0x00666713, 0x00666714, 0x00636414, 0x00a88e16, 0x00cca519, 0x00a18815, 0x005e5f13, 0x005c5d11, 0x005b5b12, 0x00585911, 0x00585810, 0x00555611, 0x00535410, 0x00525310, 0x00515110, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00545510, 0x00555611, 0x00565710, 0x00585911, 0x005b5b12, 0x005c5d11, 0x00626013, 0x00c39e18, 0x00cca518, 0x00786e14, 0x00636414, 0x00636414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x00887614, 0x00c8a117, 0x00b09015, 0x00505010, 0x00515110, 0x004d4e0f, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e06, 0x00060e06, 0x00070d08, 0x00050e08, 0x00040f08, 0x00031008, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008110a, 0x0008110a, 0x0009120c, 0x0009120c, 0x000d140e, 0x00101610, 0x00111611, 0x00121712, 0x00171912, 0x00171913, 0x00181a14, 0x001b1c16, 0x001c1e16, 0x001c1e16, 0x001f1c16, 0x00201c14, 0x00201c14, 0x00201c14, 0x001c1b14, 0x00191b16, 0x00181a15, 0x00151811, 0x0012160f, 0x0010150e, 0x0010160e, 0x000f150f, 0x000b140d, 0x0009140c, 0x0008140c, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x0008100a, 0x00070f0a, 0x00060f0a, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008110a, 0x00081009, 0x00070f08, 0x0008100b, 0x0008100b, 0x00060e09, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008120d, 0x0008120d, 0x0007110c, 0x0007100a, 0x00081009, 0x00091008, 0x000a0f08, 0x000a0f08, 0x000b1008, 0x00090e05, 0x000a0f06, 0x000c0f04, 0x000f1007, 0x00101005, 0x00141008, 0x00141008, 0x00141006, 0x00171008, 0x0019140b, 0x0019140b, 0x001c1308, 0x00201508, 0x00231809, 0x00271b0b, 0x002b1c08, 0x00302008, 0x00342408, 0x003c2a08, 0x00443109, 0x0051390b, 0x0063470c, 0x00896c18, 0x00c0a835, 0x00ccb721, 0x00cbba0d, 0x00cbba08, 0x00cab90a, 0x00cbb90d, 0x00ccb811, 0x00b6950b, 0x007d5700, 0x00603e00, 0x004b3702, 0x00403006, 0x00342502, 0x003c2e0b, 0x00443610, 0x0040340a, 0x003e3208, 0x00382c08, 0x00342709, 0x0030240a, 0x00271e08, 0x001a1505, 0x00100e04, 0x000c0e06, 0x000c1005, 0x000e1208, 0x00101208, 0x00121108, 0x00131008, 0x00141008, 0x00170f07, 0x00181108, 0x001e1409, 0x001f1406, 0x00211507, 0x00271809, 0x002b1a0b, 0x002e1b0a, 0x00301c0b, 0x00331e09, 0x0037200a, 0x00382009, 0x0039210a, 0x0039220a, 0x003b240b, 0x003c230b, 0x003f260d, 0x003c220a, 0x00392006, 0x00392207, 0x00372005, 0x00372008, 0x00361e09, 0x00361c0a, 0x00331a08, 0x00301a08, 0x002f1a08, 0x002d1a08, 0x00281808, 0x00261807, 0x00241607, 0x00231709, 0x001f1408, 0x001a1108, 0x00181008, 0x00170f08, 0x00151109, 0x00151109, 0x00141008, 0x0015100b, 0x0016130b, 0x001c170d, 0x001e180a, 0x00221a06, 0x00342811, 0x003c2e14, 0x002e1f03, 0x00342206, 0x003c2b08, 0x0048340b, 0x005a3e0d, 0x00785712, 0x00b49529, 0x00ccb220, 0x00ccb80f, 0x00cab809, 0x00cab808, 0x00cbb416, 0x00b18a0c, 0x007b5000, 0x005d3b00, 0x004e3403, 0x00432c04, 0x00382401, 0x00311f04, 0x002d1d05, 0x00291a06, 0x00261808, 0x00201406, 0x00181204, 0x00171208, 0x00171109, 0x00161109, 0x00141209, 0x0014130a, 0x0014120a, 0x00141109, 0x00141109, 0x00141008, 0x00141008, 0x00121009, 0x00101009, 0x00110f08, 0x00111009, 0x00101009, 0x000d0f05, 0x000c1006, 0x000a0f06, 0x000a1008, 0x00081108, 0x00081009, 0x00061009, 0x0007110a, 0x00061009, 0x0007100a, 0x0007100b, 0x0006100a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0008120d, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007110c, 0x0006100b, 0x0006100b, 0x00051008, 0x00051008, 0x00061008, 0x00071008, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x0008100a, 0x000a130c, 0x000a130c, 0x000c140e, 0x000d140e, 0x00101610, 0x00101610, 0x00111810, 0x00131712, 0x00131712, 0x00141914, 0x00141914, 0x00151a13, 0x00151a13, 0x00171c15, 0x00171c15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00141914, 0x00141814, 0x00121711, 0x00101510, 0x00101510, 0x000d150f, 0x000d150f, 0x000b130c, 0x0009120c, 0x00081009, 0x00081009, 0x0008120b, 0x00051109, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250c, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x00535410, 0x00565710, 0x00736812, 0x00cca418, 0x00c6a018, 0x00646212, 0x00626313, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00616114, 0x00a88d16, 0x00cca518, 0x00a08716, 0x005d5e12, 0x005c5c11, 0x00595a11, 0x00585810, 0x00555611, 0x00535410, 0x00525310, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00545510, 0x00555610, 0x00585810, 0x00595a12, 0x005c5c11, 0x00615f12, 0x00c39e17, 0x00cca418, 0x00786c14, 0x00616112, 0x00616112, 0x00626312, 0x00616112, 0x00606013, 0x00606013, 0x005e5f12, 0x00877514, 0x00c8a117, 0x00b09014, 0x00505010, 0x00515110, 0x004d4e0f, 0x00494a10, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e06, 0x00060e07, 0x00070d08, 0x00060e08, 0x00040f08, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008110b, 0x0009120c, 0x0009120c, 0x0009120c, 0x000d140e, 0x00101610, 0x00131712, 0x00141813, 0x00171913, 0x00171913, 0x001a1b15, 0x001c1c17, 0x001c1e16, 0x001c1e16, 0x001f1c16, 0x001f1c14, 0x00201c14, 0x001f1c14, 0x001c1b14, 0x001a1b14, 0x00181a14, 0x00151811, 0x0012160f, 0x0010150e, 0x000f150f, 0x000b130e, 0x000a120e, 0x0009130e, 0x0008140d, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060f09, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008110a, 0x00081009, 0x00070f08, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110d, 0x0006100b, 0x0006100b, 0x0009130d, 0x0006100b, 0x0006100b, 0x0008110c, 0x0008100b, 0x00081009, 0x000a0f08, 0x000a0f08, 0x000a0f08, 0x000b1008, 0x00090e05, 0x000b0e05, 0x000c0f06, 0x000f1007, 0x00101007, 0x00131008, 0x00131008, 0x00141006, 0x00151108, 0x00171309, 0x00171309, 0x00191308, 0x001d1509, 0x00201808, 0x00241b0a, 0x00291c08, 0x002e2008, 0x00342508, 0x003c2a09, 0x0045320a, 0x0051390b, 0x0064480b, 0x00896c16, 0x00c0a834, 0x00ccb721, 0x00cbb90e, 0x00cbba0a, 0x00cab909, 0x00cbb90d, 0x00ccb810, 0x00b5950b, 0x007e5800, 0x00603f00, 0x004d3703, 0x00403005, 0x00342601, 0x003e300c, 0x00473913, 0x0043360c, 0x00403309, 0x003c2e09, 0x00362808, 0x00312709, 0x00292008, 0x001c1705, 0x00111002, 0x000d0f05, 0x000c1005, 0x000f1308, 0x00101208, 0x00121108, 0x00131008, 0x00161109, 0x00181008, 0x00181108, 0x001c1408, 0x001e1407, 0x00201507, 0x00251709, 0x002b1a0c, 0x002d1a0a, 0x002f1c09, 0x00321d08, 0x0037200b, 0x003a220c, 0x003b240c, 0x003b240c, 0x003b230a, 0x003c230b, 0x00392008, 0x003c220a, 0x00392007, 0x00392104, 0x00382004, 0x00381f08, 0x00381e09, 0x00371c08, 0x00331a08, 0x00301a08, 0x002f1a08, 0x002d1a08, 0x00281808, 0x00271708, 0x00241608, 0x00221708, 0x001f1408, 0x001a1108, 0x00181008, 0x00161008, 0x00151109, 0x00151109, 0x00141008, 0x0016110c, 0x0016130b, 0x001d180e, 0x001d1709, 0x00221a06, 0x00342910, 0x003c2f14, 0x002f2004, 0x00342206, 0x003c2c0a, 0x0049350c, 0x005c3f0f, 0x00785712, 0x00b4942a, 0x00ccb320, 0x00ccb70e, 0x00ccb80a, 0x00ccb809, 0x00cbb415, 0x00b18a0c, 0x007b5000, 0x005e3c00, 0x004f3404, 0x00442c05, 0x00382501, 0x00312004, 0x002d1d05, 0x00291a06, 0x00261808, 0x00201504, 0x00191104, 0x00171307, 0x00161209, 0x00151109, 0x00141109, 0x0014130a, 0x0014120a, 0x00141109, 0x00141109, 0x00141008, 0x00141008, 0x00121009, 0x00101009, 0x00110f08, 0x00121009, 0x00101009, 0x000f0f06, 0x000c0f05, 0x000c1007, 0x000b1008, 0x00081108, 0x00081009, 0x00061009, 0x0007110a, 0x0006100a, 0x0007100a, 0x0007100b, 0x0007100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0007110c, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008110c, 0x0007110c, 0x0006100b, 0x00061009, 0x00061009, 0x00061009, 0x00061008, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00081009, 0x0009120c, 0x0008110a, 0x000a130c, 0x000c140d, 0x000d150f, 0x000e1710, 0x00101810, 0x00111711, 0x00121711, 0x00141914, 0x00141914, 0x00151a14, 0x00151a13, 0x00171c15, 0x00171c15, 0x00161b14, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00151a14, 0x00131712, 0x00101510, 0x00101510, 0x000d150f, 0x000d150f, 0x000b130c, 0x0009120c, 0x0008100a, 0x0008100b, 0x0008120c, 0x0005110b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f1612, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003e400d, 0x0041420e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x00525310, 0x00565711, 0x00736812, 0x00cca417, 0x00c6a018, 0x00646113, 0x00616112, 0x00626313, 0x00646414, 0x00646414, 0x00646414, 0x00636414, 0x00606013, 0x00a78c16, 0x00cca418, 0x00a08715, 0x005c5d11, 0x005b5b12, 0x00585910, 0x00565711, 0x00545510, 0x00525310, 0x00515110, 0x004f5010, 0x004f5010, 0x004d4e0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545511, 0x00565711, 0x00585810, 0x00595a12, 0x00605d11, 0x00c39e17, 0x00cca418, 0x00776c14, 0x00616112, 0x00606012, 0x00616112, 0x00606013, 0x00606013, 0x005e5f13, 0x005c5d11, 0x00877514, 0x00c8a117, 0x00b09014, 0x004f5010, 0x00505010, 0x004d4e10, 0x0048490f, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e0b, 0x00050e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00041007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x0009120c, 0x000a130c, 0x000c120c, 0x000d140d, 0x000f150d, 0x00101710, 0x00141811, 0x00151a13, 0x00181c15, 0x00181c15, 0x001b1c14, 0x001e1d14, 0x00201e15, 0x00201e15, 0x001f1c14, 0x001e1d14, 0x001e1d14, 0x001c1c14, 0x00191812, 0x00181810, 0x00171812, 0x00141611, 0x0011140f, 0x0010140f, 0x000b130e, 0x000a1410, 0x000a1410, 0x0008120f, 0x0007100c, 0x00051009, 0x00040f08, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051008, 0x00061009, 0x00061009, 0x00061009, 0x00061009, 0x0008110b, 0x00081009, 0x00081009, 0x0006100b, 0x0007110c, 0x0007110c, 0x0008100a, 0x00081008, 0x000a0f08, 0x000a0f08, 0x000a0f07, 0x000a0f06, 0x000c0f06, 0x000c0d08, 0x000c0d08, 0x000c0f08, 0x000c0f08, 0x000f1008, 0x000f1007, 0x00111008, 0x00141208, 0x00161409, 0x00161409, 0x00171308, 0x001a1508, 0x001f180a, 0x00241b0a, 0x00271c07, 0x002e1f08, 0x0034240a, 0x003b2b0a, 0x0045330b, 0x00513b0c, 0x0064480b, 0x00886b14, 0x00c0a730, 0x00cbb620, 0x00cbba0c, 0x00cbba0a, 0x00cbba0a, 0x00cbb90c, 0x00ccb810, 0x00b2930a, 0x00805a00, 0x00604000, 0x004c3803, 0x00403006, 0x00342701, 0x003e300b, 0x00483913, 0x0046370e, 0x0043340c, 0x003f300c, 0x00322503, 0x00342a0a, 0x002d250b, 0x00201c06, 0x00111000, 0x000d1004, 0x000c1005, 0x000f1308, 0x00101208, 0x00111008, 0x00131008, 0x00161108, 0x00181009, 0x00191209, 0x001c1208, 0x001e1407, 0x00211509, 0x00241609, 0x00241607, 0x002b190a, 0x002f1b0a, 0x00321d0a, 0x00371f0b, 0x003a200b, 0x003d240c, 0x003c230b, 0x003c230b, 0x0040240e, 0x003d220b, 0x003c210a, 0x003c2208, 0x003b2007, 0x003c2009, 0x003b1f09, 0x003a1e0a, 0x00381f08, 0x00341c08, 0x00311a06, 0x002f1a08, 0x002d190a, 0x002a180b, 0x00261509, 0x00231409, 0x00201408, 0x001d1508, 0x001a1308, 0x00181108, 0x0018120b, 0x0018110a, 0x00140e07, 0x00161009, 0x0016120a, 0x0018140b, 0x001c170c, 0x001c1408, 0x00241b07, 0x00362c10, 0x003f3214, 0x002f2004, 0x00342208, 0x003c2b0a, 0x0049350d, 0x005c400f, 0x00785614, 0x00b4942a, 0x00ccb321, 0x00ccb60d, 0x00ccb80a, 0x00ccb809, 0x00cbb414, 0x00ab8305, 0x007b5000, 0x005f3c00, 0x004f3404, 0x00452c08, 0x00382600, 0x00312004, 0x002d1d05, 0x00291a06, 0x00251908, 0x001e1506, 0x00191306, 0x00181207, 0x00171208, 0x00141209, 0x00141109, 0x00141109, 0x00141109, 0x00131008, 0x00131008, 0x00140f09, 0x00121009, 0x00121009, 0x00120f0b, 0x00120f0b, 0x00120f0b, 0x00110f08, 0x00121108, 0x00141008, 0x000f1007, 0x000c1108, 0x00091008, 0x00081009, 0x00081009, 0x0009110c, 0x0008110c, 0x0007100b, 0x0008100b, 0x0008100c, 0x0008100d, 0x00070e0c, 0x0008100c, 0x0008100d, 0x0008100d, 0x0008100d, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00060f0b, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0007110d, 0x0006100c, 0x00050f0c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110b, 0x0005110b, 0x00030f09, 0x00030f09, 0x0004100a, 0x0005100b, 0x00040f09, 0x0004100a, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008100b, 0x000a120e, 0x0009110d, 0x000c140f, 0x000f150f, 0x00101610, 0x00101811, 0x00101811, 0x00101812, 0x00121a14, 0x00141814, 0x00151a14, 0x00171c17, 0x00171c15, 0x00181e15, 0x00181f16, 0x00171e15, 0x00161d14, 0x00171c14, 0x00171913, 0x00141813, 0x00141614, 0x00131714, 0x000e1811, 0x000e1811, 0x000a140d, 0x0009140d, 0x00091310, 0x0008120e, 0x0008120f, 0x0008120f, 0x0008100b, 0x0008100b, 0x0008100b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280b, 0x00292b0a, 0x002d2f0c, 0x0032330c, 0x00393b0c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x00525310, 0x00555611, 0x00726612, 0x00cca417, 0x00c6a017, 0x00636013, 0x00606013, 0x00616112, 0x00626313, 0x00636413, 0x00636413, 0x00626313, 0x00606012, 0x00a78c15, 0x00cca418, 0x00a08615, 0x005b5b12, 0x00595a12, 0x00585810, 0x00555611, 0x00535410, 0x00515110, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004c4d0e, 0x004d4e0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00525310, 0x00545510, 0x00565711, 0x00585910, 0x00595a12, 0x00605c12, 0x00c39e17, 0x00cca418, 0x00766c14, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005e5f12, 0x005c5d11, 0x00867414, 0x00c8a116, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d0f, 0x00484910, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00060d0b, 0x00060d0b, 0x00060e0a, 0x00050f08, 0x00040f08, 0x00040f08, 0x00041007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x0009120c, 0x000c130d, 0x000e140e, 0x000f150f, 0x0010170f, 0x00121911, 0x00141912, 0x00161b14, 0x00181c15, 0x00181c15, 0x001c1d15, 0x001e1d14, 0x00201e15, 0x00201e15, 0x001e1d14, 0x001d1e14, 0x001c1c14, 0x001a1b14, 0x00181913, 0x00171812, 0x00161812, 0x00131610, 0x0010140e, 0x000e150f, 0x000a120e, 0x0008120f, 0x0008120f, 0x0007100d, 0x0006100c, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051009, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100c, 0x0008100b, 0x0008100b, 0x0006100b, 0x0007110d, 0x0007110c, 0x0008100a, 0x00091008, 0x000a0f08, 0x000a0f08, 0x000a0f07, 0x000a0f06, 0x000c0f06, 0x000c0e06, 0x000c0e06, 0x000c1007, 0x000c1007, 0x000f1008, 0x000f1007, 0x00111108, 0x00141208, 0x00141308, 0x00141308, 0x00151208, 0x00191408, 0x001d1809, 0x00221a09, 0x00271c07, 0x002e1e08, 0x0035250b, 0x003b2c0b, 0x0045340c, 0x00523b0c, 0x0064480b, 0x00886a15, 0x00c0a730, 0x00cbb61f, 0x00cbba0b, 0x00cbba0a, 0x00cbba0a, 0x00cbba0c, 0x00ccb910, 0x00af9008, 0x007c5800, 0x00604100, 0x004c3903, 0x003e2f04, 0x00342701, 0x003e300b, 0x00483912, 0x0047380f, 0x0044350e, 0x0040300c, 0x00322602, 0x00352b0b, 0x0031280d, 0x00231e08, 0x00121101, 0x00101005, 0x000c1005, 0x000e1208, 0x00101208, 0x00111008, 0x00131008, 0x00171208, 0x0018100a, 0x00191209, 0x001b1108, 0x001d1205, 0x00211408, 0x00241508, 0x00251608, 0x002a1909, 0x002e1909, 0x00301c08, 0x00351c09, 0x00381d08, 0x00392009, 0x003c220a, 0x003e250c, 0x0040240e, 0x003d220b, 0x003c210a, 0x003c2208, 0x003c210a, 0x003b2008, 0x003b1f09, 0x003a1e0a, 0x00381f08, 0x00341c08, 0x00301a06, 0x002f1a08, 0x002c1909, 0x00281609, 0x00261509, 0x00241409, 0x00201408, 0x001c1407, 0x00191208, 0x00181108, 0x00171009, 0x00161009, 0x00161009, 0x00161009, 0x0018130c, 0x0019160c, 0x001c160d, 0x001f180b, 0x00271f0a, 0x00382e10, 0x00423414, 0x00312204, 0x00342206, 0x003c2b0a, 0x0049350c, 0x005c4010, 0x00785614, 0x00b4942b, 0x00ccb322, 0x00cbb50d, 0x00ccb90c, 0x00ccb80a, 0x00cbb414, 0x00aa8305, 0x007b5000, 0x00603c00, 0x004e3404, 0x00462d08, 0x00392701, 0x00332104, 0x002d1d04, 0x00291a06, 0x00251908, 0x001e1506, 0x001b1407, 0x00181207, 0x00171208, 0x00141309, 0x00141009, 0x00131008, 0x00131008, 0x00121008, 0x00121008, 0x00140f09, 0x00121009, 0x00121009, 0x00120f0b, 0x00120f0b, 0x00120f0b, 0x00121008, 0x00141209, 0x00141108, 0x00101008, 0x000a0d05, 0x000a1109, 0x0008110a, 0x00081009, 0x000a130c, 0x0009130c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x00060e09, 0x0008100b, 0x0009110d, 0x0008100c, 0x0008100c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0007100d, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x0007100b, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0004100a, 0x00040f09, 0x0004100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0008100b, 0x0009110d, 0x0008100c, 0x0009110d, 0x000c130d, 0x000d140e, 0x000d150f, 0x000e1710, 0x000f1811, 0x00101812, 0x00141815, 0x00141914, 0x00161b15, 0x00161b14, 0x00171d14, 0x00171e14, 0x00171e14, 0x00161d14, 0x00171c13, 0x00171912, 0x00141812, 0x00141612, 0x00131714, 0x000e1811, 0x000e1811, 0x000a140d, 0x0009130d, 0x00091310, 0x0008120e, 0x0008120f, 0x0008120f, 0x0008100b, 0x0008100b, 0x0008100b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x00494a10, 0x004d4e0f, 0x00515110, 0x00545510, 0x00726612, 0x00cca417, 0x00c6a016, 0x00615f12, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x005e5f13, 0x00a78b15, 0x00cca418, 0x00a08614, 0x00595a12, 0x00585910, 0x00565711, 0x00545510, 0x00525310, 0x00515110, 0x004f5010, 0x004d4e0f, 0x004c4d0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545511, 0x00565710, 0x00585911, 0x005e5c12, 0x00c39e17, 0x00cca418, 0x00766b14, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005c5c11, 0x00867414, 0x00c8a116, 0x00b09014, 0x004f5010, 0x00505010, 0x004c4d0f, 0x0048490f, 0x0044450e, 0x0040400d, 0x003b3c0c, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0020230a, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00041007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00060e09, 0x0008100b, 0x00060e09, 0x00050d09, 0x00070f0a, 0x0008100c, 0x000a120e, 0x000a120d, 0x000c140d, 0x000d140f, 0x00101610, 0x0010160f, 0x00101710, 0x00111810, 0x00151a13, 0x00171c15, 0x00191c16, 0x001b1d18, 0x001c1e16, 0x001e1d14, 0x001f1c14, 0x001e1d14, 0x001d1e16, 0x001b1c15, 0x00181c13, 0x00181b12, 0x00141810, 0x00131610, 0x00131612, 0x00101411, 0x000c140f, 0x000c140f, 0x0008110c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110e, 0x0009110e, 0x0008100c, 0x0007100d, 0x0006100d, 0x0007110c, 0x0008100a, 0x000a0f07, 0x000b0f06, 0x000c0f06, 0x000c0f06, 0x000c0f06, 0x000c0f06, 0x000c0e06, 0x000c0e06, 0x000c1007, 0x000c1007, 0x000f1008, 0x000f1007, 0x00101008, 0x00131107, 0x00141208, 0x0014130a, 0x00151108, 0x00191408, 0x001e1809, 0x00221a09, 0x00271c07, 0x002d1f08, 0x0034240a, 0x003b2d0b, 0x0044340c, 0x00523b0c, 0x0066480c, 0x00876814, 0x00c2a732, 0x00ccb61f, 0x00ccb90c, 0x00ccb90a, 0x00ccb90c, 0x00ccb90c, 0x00ccb810, 0x00af9009, 0x007c5800, 0x00604200, 0x004c3903, 0x003f3005, 0x00352801, 0x0042340d, 0x00483811, 0x0044350c, 0x0043340c, 0x0040310d, 0x00342805, 0x00322809, 0x00342a10, 0x0027210c, 0x00191707, 0x00101105, 0x000d0f05, 0x000d1107, 0x00101208, 0x00131209, 0x00121006, 0x00161108, 0x0018100a, 0x0019110b, 0x001b1108, 0x001d1205, 0x00221609, 0x00241609, 0x00251608, 0x00281808, 0x002e1a0a, 0x00311b08, 0x00341b07, 0x00381d09, 0x0039200a, 0x003a2108, 0x003b2209, 0x003e230d, 0x003c2109, 0x00391e07, 0x003c2007, 0x00391e06, 0x00391e06, 0x00381c07, 0x00381c08, 0x00371d07, 0x00341c06, 0x00311b07, 0x002f1907, 0x002c1808, 0x00281408, 0x00241408, 0x00221207, 0x001f1307, 0x001c1306, 0x00181108, 0x00181108, 0x0018110a, 0x00181009, 0x00170f08, 0x00170f08, 0x0018120b, 0x001a150c, 0x001c140c, 0x0021180c, 0x0029200b, 0x00382f0e, 0x00443815, 0x00322402, 0x00352304, 0x003c2c09, 0x00483409, 0x005b3f0f, 0x00785514, 0x00b4922b, 0x00ccb122, 0x00cbb40e, 0x00ccb80b, 0x00ccb80a, 0x00cbb214, 0x00ab8205, 0x007a4e00, 0x00603b00, 0x004e3104, 0x00472d0b, 0x00392602, 0x00322104, 0x002d1d04, 0x00291a06, 0x00251908, 0x001e1506, 0x001b1407, 0x00181207, 0x00171208, 0x00141309, 0x00131109, 0x00121108, 0x00111108, 0x00101008, 0x00111008, 0x00121009, 0x00121009, 0x00121009, 0x00120f0b, 0x00120d0a, 0x00120d0a, 0x00130f08, 0x00141109, 0x00151208, 0x00101008, 0x000c0e06, 0x000c1009, 0x000b130c, 0x0008110b, 0x0008110b, 0x000c140e, 0x0008110b, 0x0008110a, 0x0008110b, 0x0009120b, 0x0009120c, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110b, 0x0007110c, 0x0006100b, 0x0006100b, 0x0008120c, 0x0009120c, 0x00081009, 0x00081009, 0x00081009, 0x00061009, 0x00061009, 0x00061009, 0x00061009, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00060f0a, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x0006100c, 0x0007130d, 0x0007130d, 0x0006120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0005110b, 0x0005110b, 0x0006100b, 0x0006100b, 0x00050d09, 0x0008100c, 0x0009110c, 0x000a120e, 0x000c120e, 0x000d1410, 0x000c140e, 0x000c140e, 0x000d150f, 0x000f1811, 0x00141815, 0x00141914, 0x00151a14, 0x00161b14, 0x00171d14, 0x00171e14, 0x00171e14, 0x00161c13, 0x00171c11, 0x00181b11, 0x00161811, 0x00141711, 0x00131712, 0x000e1811, 0x000e1811, 0x000b150e, 0x000a140e, 0x000a1410, 0x00091310, 0x0008120f, 0x0008120f, 0x0008100c, 0x0008100c, 0x0008100c, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0c, 0x0040400d, 0x0044450d, 0x0048490f, 0x004c4d10, 0x00505010, 0x00545510, 0x00716512, 0x00cca417, 0x00c6a016, 0x00605d11, 0x005e5f13, 0x00606013, 0x00606013, 0x00606012, 0x00606012, 0x00606013, 0x005d5e13, 0x00a78b15, 0x00cca418, 0x00a08614, 0x00595a12, 0x00585810, 0x00555610, 0x00535410, 0x00525310, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004c4d0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00525310, 0x00545510, 0x00565710, 0x00595a11, 0x005e5c13, 0x00c39e17, 0x00cca418, 0x00756a13, 0x005e5f13, 0x00606013, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005c5d11, 0x005b5b11, 0x00867414, 0x00c8a116, 0x00b09014, 0x004d4e10, 0x004f5010, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0036370c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00050e08, 0x00040f08, 0x00040f08, 0x00041007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00060e09, 0x0008100b, 0x00060e09, 0x00070f0a, 0x0009110c, 0x0009110c, 0x0009110e, 0x000c140e, 0x000c140e, 0x000f1610, 0x00101710, 0x00101711, 0x00111810, 0x00131a12, 0x00161b14, 0x00171c15, 0x001a1c17, 0x001c1e18, 0x001c1e16, 0x001e1d14, 0x001e1d14, 0x001d1e14, 0x001b1c14, 0x00181c13, 0x00181a13, 0x00171913, 0x00141611, 0x00131410, 0x00101410, 0x000e1410, 0x000b130f, 0x000a130e, 0x0006100b, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x00040f09, 0x00040e08, 0x00051009, 0x00051009, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x000b1310, 0x000b1310, 0x000b1310, 0x00091310, 0x0008120f, 0x0007110c, 0x0009100a, 0x000a0f08, 0x000b0f07, 0x000c0f06, 0x000c0f06, 0x000c0f05, 0x000c0f04, 0x000c0e04, 0x000c0f04, 0x000c1005, 0x000c1005, 0x000f1008, 0x000f1007, 0x00101008, 0x00131107, 0x00131308, 0x0014130a, 0x00141208, 0x00181408, 0x001e1809, 0x00221a09, 0x00271c07, 0x002d1f08, 0x00342509, 0x003c2d0c, 0x0044340c, 0x00523b0c, 0x0068480c, 0x00876813, 0x00c2a732, 0x00ccb61e, 0x00ccb90c, 0x00ccb90a, 0x00ccb90c, 0x00cbbb0c, 0x00ccb910, 0x00af9009, 0x007d5800, 0x00604400, 0x004c3a04, 0x00413208, 0x00382b04, 0x0044370f, 0x0047380f, 0x0044340b, 0x0042340c, 0x00413410, 0x00342806, 0x002e2304, 0x00342a11, 0x002b2510, 0x00191605, 0x00111104, 0x000e1006, 0x000d1007, 0x00101208, 0x00111208, 0x00121006, 0x00161108, 0x0018100a, 0x0019110a, 0x001b1108, 0x001d1205, 0x00221609, 0x00241608, 0x00251608, 0x00281808, 0x002d1a09, 0x00301a08, 0x00331a06, 0x00351c08, 0x00381f09, 0x00381f08, 0x00392008, 0x003c210b, 0x003b2008, 0x003c2008, 0x003a1f06, 0x00371c04, 0x00381c05, 0x00371c06, 0x00371b08, 0x00371c08, 0x00341c06, 0x00321b07, 0x002f1907, 0x002c1809, 0x00281408, 0x00241408, 0x00221207, 0x001f1306, 0x001b1305, 0x00181107, 0x00181108, 0x0018110a, 0x00181009, 0x00170f08, 0x00170f08, 0x0018120b, 0x001a150c, 0x001c140c, 0x0021180c, 0x0029200a, 0x00382f0c, 0x00443813, 0x00342502, 0x00352401, 0x003e2d09, 0x0048340a, 0x005c3f0e, 0x00785514, 0x00b3932b, 0x00ccb222, 0x00cab40e, 0x00ccb80c, 0x00ccb80a, 0x00cbb214, 0x00ab8205, 0x007a4f00, 0x00603b00, 0x004d3003, 0x00472d0b, 0x003a2802, 0x00322104, 0x002d1d04, 0x00291a06, 0x00251908, 0x001e1506, 0x001b1407, 0x00181207, 0x00171208, 0x00141309, 0x00131109, 0x00121108, 0x00111108, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00121009, 0x00120f0b, 0x00140f0b, 0x00130e0a, 0x00140f08, 0x0015110a, 0x00151208, 0x00111008, 0x000d0f07, 0x00080e06, 0x000a120c, 0x000c140e, 0x000d140f, 0x00101711, 0x000d150e, 0x000e150e, 0x000c140c, 0x000a110a, 0x00091109, 0x00091008, 0x00091008, 0x00091008, 0x00081109, 0x0007110a, 0x00061009, 0x00061009, 0x0008130c, 0x0009120c, 0x00081009, 0x00081009, 0x00081008, 0x00061008, 0x00061108, 0x00061009, 0x0006100a, 0x0008110a, 0x0008110a, 0x0008100b, 0x0008100c, 0x0008100c, 0x0006100d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x0006100c, 0x0008120d, 0x0007130d, 0x0006120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0007120c, 0x0007120c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100c, 0x0009110d, 0x0009110d, 0x000a120e, 0x000a120e, 0x000c1410, 0x000c140f, 0x000c140f, 0x000d1510, 0x000f1812, 0x00141815, 0x00141914, 0x00151a14, 0x00161b14, 0x00171c14, 0x00171e14, 0x00171e14, 0x00161c13, 0x00161c12, 0x00181b11, 0x00161810, 0x00141710, 0x00131810, 0x000f1811, 0x000e1811, 0x000c150e, 0x000a140e, 0x000a1410, 0x00091310, 0x0008120f, 0x0008120f, 0x0008100c, 0x0008100c, 0x0008100c, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00141809, 0x00191c09, 0x00202309, 0x00202309, 0x0026280c, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0040400e, 0x0044450e, 0x0048490f, 0x004c4d0f, 0x00505010, 0x00535410, 0x00716412, 0x00cca316, 0x00c5a016, 0x00605d11, 0x005d5e12, 0x00606013, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x005c5d13, 0x00a68b15, 0x00cca418, 0x00a08514, 0x00585912, 0x00585910, 0x00555610, 0x00535410, 0x00525310, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004d4e0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545510, 0x00565710, 0x00585910, 0x005e5c12, 0x00c39e17, 0x00cca418, 0x00756a13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005b5b12, 0x00867414, 0x00c8a016, 0x00b09014, 0x004c4d10, 0x004f5010, 0x004c4d0f, 0x0048490e, 0x0044450e, 0x0040400e, 0x003c3e0d, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x00060e08, 0x00060e08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00080f0b, 0x00080f0a, 0x00060e08, 0x00050e07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f07, 0x00040f07, 0x00051008, 0x00051008, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00081009, 0x00081009, 0x00060e08, 0x00060e08, 0x00081009, 0x00081009, 0x00081009, 0x0008110a, 0x000b130c, 0x000e140e, 0x00101610, 0x00111812, 0x00121813, 0x00151a13, 0x00151a13, 0x00161b14, 0x00191c16, 0x001d1c18, 0x001e1c18, 0x001e1d16, 0x001e1d14, 0x001e1d16, 0x001c1e16, 0x001b1c14, 0x00181b12, 0x00151a13, 0x00141811, 0x00121710, 0x0010150f, 0x000e1410, 0x000c1410, 0x000c140f, 0x000a140f, 0x0008130e, 0x0006110d, 0x0006110d, 0x0005100c, 0x0005100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00040e0b, 0x0006100b, 0x00061009, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0006110b, 0x0006120c, 0x0005120c, 0x0005110b, 0x0005110b, 0x0005120c, 0x0006120c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0006110c, 0x0006120c, 0x0008130d, 0x0008120d, 0x0007100c, 0x0009120e, 0x000a120e, 0x000a120e, 0x000a1210, 0x0008100c, 0x00091009, 0x000a0f08, 0x000a0f08, 0x000a0f07, 0x000b0f05, 0x000c0f04, 0x000c0f04, 0x000b0f04, 0x000a1004, 0x000b1005, 0x000b1005, 0x000c1007, 0x000c1005, 0x000d0f05, 0x00101108, 0x00131209, 0x00131209, 0x00141208, 0x00181408, 0x001c1709, 0x00211808, 0x00271c08, 0x002c1f08, 0x00322408, 0x003a2e0b, 0x0044340c, 0x00523b0c, 0x0066480c, 0x00856611, 0x00c0a630, 0x00cbb61f, 0x00cbba0b, 0x00cbba0c, 0x00ccbb0c, 0x00ccba0e, 0x00cbb80e, 0x00ac8d09, 0x007c5700, 0x00614400, 0x004d3c04, 0x00413209, 0x00382b04, 0x0044370e, 0x0045380e, 0x0045380c, 0x00413409, 0x003f320c, 0x003a2f0d, 0x00281d01, 0x0033280f, 0x002a240f, 0x001c1a08, 0x00121204, 0x000f1007, 0x000e1006, 0x000e1208, 0x00101108, 0x00131107, 0x00151007, 0x00181009, 0x00181009, 0x001c1208, 0x001d1205, 0x00211509, 0x00241609, 0x00241608, 0x0028180a, 0x002c1a0a, 0x002f1a08, 0x00311807, 0x00351806, 0x00371b08, 0x00371b08, 0x00351c08, 0x00381f08, 0x00381f08, 0x00371e08, 0x00371e07, 0x00381e06, 0x00361c07, 0x00351c07, 0x00341907, 0x00351807, 0x00341907, 0x00311908, 0x002e1708, 0x002b1709, 0x0028140a, 0x0024130a, 0x00221209, 0x001d1107, 0x001c1106, 0x00191007, 0x00181108, 0x0018100a, 0x00171009, 0x00151008, 0x00151008, 0x0018120b, 0x00191409, 0x001b130a, 0x0020180a, 0x00281f08, 0x003c330f, 0x00453914, 0x00342603, 0x00362404, 0x003e2d09, 0x00483409, 0x005c400d, 0x00785514, 0x00b3932b, 0x00ccb222, 0x00cbb40e, 0x00ccb80c, 0x00ccb80a, 0x00cbb213, 0x00ab8204, 0x007b4f00, 0x00603c00, 0x00513408, 0x00462c0a, 0x003b2804, 0x002e1d01, 0x002d1d05, 0x00291a06, 0x00251908, 0x001e1504, 0x001a1305, 0x00181308, 0x0018130a, 0x00141209, 0x00121008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00121009, 0x00121009, 0x00140f09, 0x00140f09, 0x00140f09, 0x00151009, 0x00140f08, 0x00121008, 0x000d0e06, 0x000c0d08, 0x000e120b, 0x0010140e, 0x00151712, 0x00171712, 0x00181711, 0x00171710, 0x00171710, 0x0016160f, 0x0015150e, 0x0014140c, 0x0012140c, 0x0010140b, 0x000c1209, 0x000a140a, 0x000b140d, 0x000a140c, 0x0008120c, 0x0008120c, 0x0007110c, 0x0007110c, 0x0007110d, 0x0006110e, 0x0006110e, 0x0007110d, 0x0007100d, 0x0006100a, 0x00061009, 0x00061009, 0x00071008, 0x0008100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0008120c, 0x000c140f, 0x000c140f, 0x000c1511, 0x000c1512, 0x000c1713, 0x000e1814, 0x00121816, 0x00141815, 0x00151916, 0x00151a14, 0x00181c17, 0x00191d17, 0x00181d15, 0x00171c14, 0x00171c14, 0x00171c15, 0x00171c15, 0x00141912, 0x00141811, 0x00121812, 0x00111812, 0x000f150f, 0x000c140f, 0x000c1411, 0x000c1310, 0x00091310, 0x00081410, 0x0009110d, 0x0009110d, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002d2f0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x00525310, 0x00716412, 0x00cca316, 0x00c5a017, 0x00605c12, 0x005d5e11, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005c5c13, 0x00a68b15, 0x00cca417, 0x00a08514, 0x00585912, 0x00585810, 0x00565711, 0x00535410, 0x00525310, 0x00515110, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00525310, 0x00535410, 0x00555611, 0x00585810, 0x00585911, 0x005e5c13, 0x00c39d17, 0x00cca417, 0x00756a12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5c11, 0x005b5b12, 0x00867414, 0x00c8a016, 0x00b09014, 0x004c4d10, 0x004f5010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00070f08, 0x00070f08, 0x00080e08, 0x00070f08, 0x00070f08, 0x00051008, 0x00051008, 0x00051008, 0x00070d08, 0x00080f0b, 0x0008100a, 0x00050f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00051007, 0x00051008, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x0008100a, 0x000a130c, 0x000c140e, 0x000f150f, 0x00101711, 0x00111812, 0x00131813, 0x00151a13, 0x00151a13, 0x00171c14, 0x00191c16, 0x001d1c18, 0x001e1c18, 0x001e1d16, 0x001e1d14, 0x001e1d16, 0x001c1c14, 0x001b1c14, 0x00181b12, 0x00151a13, 0x00141811, 0x00131810, 0x0012160f, 0x000e150f, 0x000b1510, 0x000b1410, 0x0008120d, 0x0006100b, 0x0004100c, 0x0004100c, 0x0005100c, 0x0005100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00040e0b, 0x0006100b, 0x00061009, 0x0008110b, 0x0008110b, 0x0008110c, 0x0008110c, 0x0007110c, 0x0006100b, 0x0006100a, 0x00051109, 0x00061109, 0x0006120a, 0x0007110a, 0x000b110c, 0x000b110c, 0x000a100a, 0x0009100a, 0x000b130c, 0x000b130c, 0x000c140d, 0x000c140d, 0x000d140e, 0x00101610, 0x000e140e, 0x000e140e, 0x000c130f, 0x0009100b, 0x00090f08, 0x000a0f08, 0x000a0f06, 0x000a0f06, 0x000b0f05, 0x000c0f04, 0x000c0f04, 0x000a1004, 0x000a1004, 0x000b1005, 0x000b1005, 0x000b1007, 0x000c1005, 0x000d0f05, 0x00101108, 0x00111309, 0x00111309, 0x00131308, 0x00171509, 0x001c170a, 0x00231809, 0x00271c08, 0x002c2009, 0x00322408, 0x003a2e0b, 0x0044350c, 0x00523c0c, 0x0066480e, 0x00856611, 0x00c0a630, 0x00cbb61f, 0x00cab90a, 0x00cbba0c, 0x00cbba0c, 0x00cbbb0e, 0x00c9b810, 0x00ac8c08, 0x007c5700, 0x00624500, 0x004f3c05, 0x0044340c, 0x003b2d07, 0x0044380f, 0x0045380d, 0x0045390b, 0x00403408, 0x003e330c, 0x00392f0e, 0x00261c00, 0x002e240b, 0x002a240f, 0x00201e0b, 0x00111302, 0x000c0e04, 0x000c0e04, 0x000d1107, 0x00101208, 0x00121107, 0x00141007, 0x00181009, 0x00181009, 0x001c1208, 0x001d1205, 0x00211509, 0x00231709, 0x00231708, 0x0026180a, 0x002a1a0b, 0x002c1a08, 0x00301806, 0x00331906, 0x00351c08, 0x00351c09, 0x00351c09, 0x00361f08, 0x00361f08, 0x00361f08, 0x00361f08, 0x00381e08, 0x00361c08, 0x00351c08, 0x00341907, 0x00331806, 0x00321808, 0x00301808, 0x002e1808, 0x002c1709, 0x0027150a, 0x0024140a, 0x0021140a, 0x001e1208, 0x001c1307, 0x00181107, 0x00181108, 0x0017110a, 0x00151109, 0x00141008, 0x00151009, 0x0017130b, 0x00191409, 0x001b1308, 0x00201808, 0x00282008, 0x003d3210, 0x00453914, 0x00352804, 0x00362404, 0x003f2e08, 0x00493609, 0x005c400c, 0x00775512, 0x00b2932b, 0x00cab322, 0x00c9b50e, 0x00cab80c, 0x00ccb80a, 0x00cbb313, 0x00ac8406, 0x007c5000, 0x00603c00, 0x00513408, 0x00462c09, 0x003c2805, 0x002f1d02, 0x002d1d05, 0x00291a06, 0x00251908, 0x001e1504, 0x001a1304, 0x00181309, 0x0018130a, 0x00141209, 0x00121008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00121009, 0x00121009, 0x0013100a, 0x00121009, 0x00121009, 0x00141209, 0x00140f09, 0x00121008, 0x000e0d06, 0x000c0f06, 0x000e110a, 0x0012140e, 0x00151410, 0x0016140f, 0x0018140d, 0x0018130d, 0x0018130c, 0x0017120b, 0x0017120b, 0x0014130a, 0x0014130a, 0x0016180e, 0x0014180f, 0x0013180f, 0x0012170e, 0x0010150e, 0x000e140c, 0x000b110c, 0x000a110c, 0x0009100b, 0x0009100c, 0x0007110c, 0x0006110c, 0x0007110c, 0x0007110c, 0x0008120c, 0x0008120c, 0x0008100b, 0x00070f08, 0x00081009, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0006100b, 0x0007110c, 0x000a140f, 0x000a140f, 0x000b1411, 0x000b1411, 0x000c1713, 0x000c1713, 0x00101614, 0x00141814, 0x00141815, 0x00151914, 0x00161b17, 0x00171b18, 0x00171c16, 0x00171c14, 0x00171c14, 0x00171c15, 0x00171c15, 0x00161b14, 0x00141811, 0x00131712, 0x00111812, 0x000f150f, 0x000c140f, 0x000c1411, 0x000c1411, 0x00091310, 0x00081410, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x0040400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x00525310, 0x00706411, 0x00cca316, 0x00c5a017, 0x00605c12, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x005e5f13, 0x005e5f13, 0x005c5c13, 0x00a68a14, 0x00cca417, 0x00a08514, 0x00585912, 0x00585910, 0x00565711, 0x00545511, 0x00535410, 0x00515110, 0x00505010, 0x004f5010, 0x004f5010, 0x004d4e10, 0x004f5010, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545510, 0x00555611, 0x00565710, 0x00595a11, 0x005e5c13, 0x00c39e17, 0x00cca417, 0x00756a12, 0x005d5e12, 0x005e5f13, 0x005e5f12, 0x005d5e11, 0x005d5e11, 0x005c5c11, 0x00595a12, 0x00867413, 0x00c8a016, 0x00b09014, 0x004c4d10, 0x004d4e0f, 0x004b4c10, 0x0047480e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00080e08, 0x00080e08, 0x00080e08, 0x00070f08, 0x00070f08, 0x00051008, 0x00051008, 0x00051008, 0x0009100b, 0x0009100c, 0x0008110b, 0x00071008, 0x00051007, 0x00051007, 0x00051007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00061108, 0x00041008, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00081009, 0x00081009, 0x0009120c, 0x0008120c, 0x0008110b, 0x0008110a, 0x0008110a, 0x000a130c, 0x000c140e, 0x00101610, 0x00101711, 0x00131712, 0x00141813, 0x00181a14, 0x00181c15, 0x00191c16, 0x001a1d17, 0x001c1d18, 0x001c1d18, 0x001c1e16, 0x001c1e14, 0x001c1d15, 0x001a1b14, 0x001a1b14, 0x00171913, 0x00141813, 0x00131811, 0x00101610, 0x0010150e, 0x000c140e, 0x00091310, 0x0008120e, 0x0006100c, 0x0006100c, 0x00030f0b, 0x00030f0b, 0x0005100c, 0x0005100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100b, 0x00061009, 0x0007110a, 0x0007110a, 0x0007110c, 0x0007110c, 0x0007110b, 0x00061009, 0x00050f08, 0x00081009, 0x0009120b, 0x000a130b, 0x000b130b, 0x000c130c, 0x000c130c, 0x000f130c, 0x000e130c, 0x0010150e, 0x00111610, 0x0010150e, 0x0010150e, 0x00141811, 0x00161912, 0x0011160f, 0x0010140d, 0x000d120b, 0x00090e07, 0x00090e06, 0x00090f05, 0x000a1004, 0x000a1004, 0x000b1005, 0x000c0f06, 0x000c0f06, 0x000a1004, 0x000a1004, 0x000b1005, 0x000b1005, 0x000b1007, 0x000c1005, 0x000d0f05, 0x00101108, 0x00111309, 0x0013120b, 0x00141109, 0x0018140b, 0x001d160a, 0x00231809, 0x00271c08, 0x002c2009, 0x00322408, 0x003a2d0b, 0x0044350c, 0x00503c0d, 0x0065480d, 0x00846311, 0x00c0a430, 0x00ccb520, 0x00ccb80b, 0x00cab90a, 0x00cbb90c, 0x00cbb90d, 0x00cbb810, 0x00aa8a08, 0x007c5700, 0x00624500, 0x004f3c04, 0x0044350b, 0x003c2e07, 0x00483a11, 0x0045380d, 0x0044380a, 0x00403408, 0x00392e08, 0x003b3010, 0x002b2104, 0x00291f06, 0x0028220c, 0x00201e0b, 0x00141404, 0x000d0d02, 0x000c0e04, 0x000c1005, 0x00101109, 0x00131208, 0x00161108, 0x00181009, 0x00181009, 0x001c1208, 0x001d1205, 0x00211408, 0x00231708, 0x00241809, 0x00241809, 0x00281a0a, 0x002c1a08, 0x002e1906, 0x00311906, 0x00341b08, 0x00341b08, 0x00341b08, 0x00341c08, 0x00341c08, 0x00341c08, 0x00341c08, 0x00341b06, 0x00341b08, 0x00341a0a, 0x00341a0a, 0x00331806, 0x00311908, 0x00311a09, 0x002e1908, 0x002a1709, 0x00261509, 0x00231409, 0x00211409, 0x001c1308, 0x001a1308, 0x00181207, 0x00151108, 0x00141109, 0x00141109, 0x00131008, 0x00141109, 0x0017140c, 0x00181409, 0x001b1308, 0x00211709, 0x002a2008, 0x003c3110, 0x00443812, 0x00352804, 0x00382505, 0x00402f09, 0x0049370a, 0x005c400c, 0x00755410, 0x00af8f27, 0x00ccb323, 0x00cab40e, 0x00ccb80c, 0x00ccb80a, 0x00cbb412, 0x00ac8606, 0x007c5100, 0x00603c00, 0x004f3308, 0x00432b09, 0x003b2804, 0x002e1c01, 0x002d1d05, 0x00291a06, 0x00251908, 0x001e1504, 0x001a1304, 0x00181309, 0x0018130a, 0x00141209, 0x00121008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00121009, 0x00110f08, 0x00101009, 0x000f0e08, 0x00100f08, 0x00110f08, 0x00121009, 0x00100e08, 0x000e0d06, 0x000e1109, 0x000d1209, 0x0010140b, 0x0014140c, 0x0014130a, 0x0016110a, 0x00181309, 0x00181309, 0x00181309, 0x00181108, 0x00171309, 0x00161409, 0x00151409, 0x0014140a, 0x0015170d, 0x0016170f, 0x00171810, 0x0015170f, 0x0014160f, 0x00141610, 0x0014150f, 0x0010130e, 0x000c140d, 0x000c140d, 0x000c140d, 0x0009120b, 0x0008110a, 0x0008110a, 0x0009120b, 0x00081009, 0x00081009, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x00070f0a, 0x0008100c, 0x0006100b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0007100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0007110c, 0x0007110c, 0x0009130e, 0x0009130e, 0x00091310, 0x00091310, 0x000b1411, 0x000c1713, 0x00101614, 0x00111613, 0x00111613, 0x00141813, 0x00151916, 0x00151917, 0x00171b17, 0x00171c16, 0x00171c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00151a14, 0x00131712, 0x00111812, 0x00101710, 0x000d150f, 0x000d1510, 0x000d1510, 0x000a140f, 0x000a140f, 0x0009130e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0009110d, 0x0009110d, 0x0008100c, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x00515110, 0x00706412, 0x00cca316, 0x00c5a016, 0x005e5c12, 0x005c5c11, 0x005d5e11, 0x005e5f12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005b5b12, 0x00a68a14, 0x00cca417, 0x00a08514, 0x00585912, 0x00585810, 0x00565711, 0x00555611, 0x00535410, 0x00525310, 0x00515110, 0x00505010, 0x00505010, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00535410, 0x00545511, 0x00565711, 0x00585910, 0x00595a12, 0x005e5c12, 0x00c39e17, 0x00cca418, 0x00756a13, 0x005d5e12, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x005b5b12, 0x00867413, 0x00c8a016, 0x00b08f14, 0x004c4d10, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x0040400c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x0026280a, 0x0026280c, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x000a100a, 0x000a100a, 0x000a100a, 0x0008110a, 0x0008110a, 0x0007110a, 0x0007110a, 0x0007110a, 0x0009100b, 0x0009100c, 0x0008110b, 0x00081109, 0x00061108, 0x00071208, 0x00071208, 0x00061108, 0x00061108, 0x00061108, 0x00061108, 0x00071208, 0x00051008, 0x0008100b, 0x0008100b, 0x0009110c, 0x0008100c, 0x0008110a, 0x0008110a, 0x0009120c, 0x0009140c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000c140e, 0x000e1510, 0x00101711, 0x00131813, 0x00141914, 0x00151a14, 0x00181c15, 0x001a1d17, 0x001b1e18, 0x001c1f18, 0x001c1d18, 0x001c1d18, 0x001c1e16, 0x001c1d14, 0x001a1b14, 0x001a1b14, 0x00181813, 0x00141811, 0x00131712, 0x00101610, 0x000f150f, 0x000d140e, 0x000a120d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0004100c, 0x00030f0b, 0x0005100c, 0x0005100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100a, 0x00061009, 0x0007110a, 0x0007110a, 0x0009130d, 0x0009130e, 0x0009120c, 0x000a130c, 0x000d140d, 0x000f150e, 0x0010160f, 0x0011170e, 0x0012170e, 0x0014170f, 0x0013160e, 0x0013140c, 0x0012150c, 0x0012150c, 0x0013160d, 0x0012150c, 0x0012150c, 0x0014160d, 0x0016180e, 0x0013160c, 0x0011140c, 0x000e1209, 0x00090f05, 0x00080e04, 0x00070e03, 0x00090e02, 0x000b0e03, 0x000c0f05, 0x000c0f07, 0x000c0f06, 0x000a1004, 0x000a1004, 0x000b1005, 0x000b1005, 0x000b1007, 0x000c1005, 0x000d0f05, 0x00101108, 0x00111309, 0x0013120b, 0x00141109, 0x0018140b, 0x001d160a, 0x00231809, 0x00271c08, 0x002c2008, 0x00332408, 0x003a2d0b, 0x0044350c, 0x00523c0d, 0x0064460e, 0x00846210, 0x00c0a330, 0x00ccb420, 0x00ccb80c, 0x00cab90a, 0x00cab80c, 0x00cab80c, 0x00ccb811, 0x00a68606, 0x00795400, 0x00604300, 0x004c3a02, 0x00413208, 0x00382b04, 0x00463810, 0x0045380d, 0x00423509, 0x003f3307, 0x003b3008, 0x003a3010, 0x002e2407, 0x00281f07, 0x0028220c, 0x00201e0b, 0x00141404, 0x000e0e03, 0x000c0e04, 0x000c0f04, 0x0010120a, 0x00131208, 0x00161108, 0x00181009, 0x00181009, 0x001c1208, 0x001d1206, 0x00201408, 0x00221608, 0x00231809, 0x00231808, 0x00261909, 0x002b1b08, 0x002c1a06, 0x002e1a05, 0x00301c07, 0x00311c08, 0x00321c08, 0x00331a07, 0x00331a07, 0x00331a07, 0x00331a07, 0x00341b08, 0x00341b08, 0x00341a0a, 0x00341a0b, 0x00311906, 0x00311908, 0x00301808, 0x002c1707, 0x00281608, 0x00241409, 0x00211308, 0x001f1308, 0x001b1307, 0x00181208, 0x00161106, 0x00131107, 0x00121108, 0x00131008, 0x00111008, 0x00131209, 0x0017140c, 0x00181409, 0x001b1308, 0x00211709, 0x002b2008, 0x003c300f, 0x00433710, 0x00332400, 0x00342303, 0x003c2c07, 0x00473407, 0x005b3f0c, 0x0074520c, 0x00af8f26, 0x00ccb224, 0x00cbb510, 0x00ccb80b, 0x00ccb80a, 0x00ccb411, 0x00b08909, 0x007d5200, 0x00603c00, 0x004f3207, 0x00422a08, 0x003a2704, 0x00301d02, 0x002d1c05, 0x00291a06, 0x00251907, 0x001e1504, 0x001a1304, 0x00181308, 0x0018130a, 0x00141209, 0x00121008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00101009, 0x00100f08, 0x000f100a, 0x000d0f08, 0x000f100a, 0x000f1008, 0x00121009, 0x00100d07, 0x000e0d04, 0x00101108, 0x0010140a, 0x00101409, 0x00121308, 0x00141309, 0x0016140a, 0x00161409, 0x00161409, 0x00151408, 0x00161307, 0x00161408, 0x00161408, 0x00141408, 0x00141409, 0x00151409, 0x0017140a, 0x0017140c, 0x0018160d, 0x0018170e, 0x0018170e, 0x001b1b12, 0x00181810, 0x00171810, 0x00171810, 0x00171810, 0x0014150e, 0x0010140c, 0x000c140c, 0x000a130b, 0x0009120a, 0x0008100a, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x000a120e, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0009110c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0009110d, 0x0007110c, 0x0007110c, 0x0008120d, 0x0008120d, 0x00091310, 0x00091310, 0x000b1410, 0x000c1512, 0x00101614, 0x00111613, 0x00111613, 0x00141813, 0x00151917, 0x00161a18, 0x00171b18, 0x00171c18, 0x00171c16, 0x00171c15, 0x00171c15, 0x00181d16, 0x00171c15, 0x00141813, 0x00121813, 0x00111812, 0x000f1810, 0x000e1611, 0x000e1611, 0x000b1510, 0x000b1510, 0x0008140e, 0x0008140e, 0x0007130d, 0x0007130d, 0x0009110d, 0x0009110d, 0x0008100c, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x00393b0c, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x00515110, 0x00706311, 0x00cca316, 0x00c59f16, 0x005e5c12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005c5c12, 0x00a68a15, 0x00cca417, 0x00a48814, 0x005b5b12, 0x00585910, 0x00565710, 0x00555611, 0x00545511, 0x00535410, 0x00525310, 0x00515110, 0x00515110, 0x00515110, 0x00515110, 0x00515110, 0x00525310, 0x00535410, 0x00545510, 0x00555611, 0x00585810, 0x00585911, 0x00595a12, 0x00615e12, 0x00c5a017, 0x00cca418, 0x00756b13, 0x005e5f12, 0x005e5f13, 0x005d5e11, 0x005d5e11, 0x005c5d11, 0x005b5b12, 0x00595a12, 0x008c7813, 0x00caa116, 0x00af8f14, 0x004b4c10, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x0008110a, 0x0008110a, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x0009130c, 0x0009120a, 0x0009120a, 0x000a130b, 0x000a130b, 0x0009140b, 0x0009140b, 0x0008130a, 0x0008130a, 0x0009120c, 0x0009120c, 0x000a130c, 0x000c120c, 0x000a100a, 0x000a100a, 0x000a130c, 0x0009140c, 0x000b140d, 0x000d140e, 0x000f150f, 0x00101510, 0x00121611, 0x00141813, 0x00151a14, 0x00171914, 0x00181a15, 0x001a1d17, 0x001a1d17, 0x001d1e18, 0x001d1e18, 0x001c1e16, 0x001c1e16, 0x001c1e16, 0x001b1c14, 0x001a1b14, 0x00181a14, 0x00141811, 0x00111611, 0x00101511, 0x00101511, 0x000e1411, 0x000b120e, 0x0008120e, 0x0006120d, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005100a, 0x0006100b, 0x0008100c, 0x0008100c, 0x0009100c, 0x0009100c, 0x0008100c, 0x0009110c, 0x00081009, 0x0009120c, 0x000a140d, 0x000a140d, 0x000f140e, 0x00121410, 0x00131610, 0x00131710, 0x0012170e, 0x0011170e, 0x0012170e, 0x0013160c, 0x0013160c, 0x0015150c, 0x0014140c, 0x0014130a, 0x0014130a, 0x0013140b, 0x0012140b, 0x0013140c, 0x0013140c, 0x0012140a, 0x0013140b, 0x000f1308, 0x0011140a, 0x000c1208, 0x00090e04, 0x00070e03, 0x00070e03, 0x000a0e02, 0x000b0e03, 0x000c0e04, 0x000c0e06, 0x000c0e06, 0x000c1007, 0x000c1007, 0x000c0f08, 0x000c0f08, 0x000f100a, 0x000f1008, 0x000e0f08, 0x00101108, 0x00131209, 0x00131209, 0x0014130a, 0x0019150b, 0x001e1809, 0x00231909, 0x00271c08, 0x002c2008, 0x00342407, 0x003b2d0a, 0x0044350c, 0x00523c0f, 0x0064460d, 0x00846311, 0x00c0a430, 0x00ccb420, 0x00ccb80c, 0x00ccb80a, 0x00ccb80c, 0x00cab80c, 0x00c8b40d, 0x00a48404, 0x00785300, 0x005f4200, 0x004b3802, 0x003f3005, 0x003c2e05, 0x00473910, 0x0045370c, 0x00423408, 0x003e3108, 0x00392e09, 0x00342a0a, 0x002e2408, 0x00231b02, 0x002c2510, 0x00231e0c, 0x00171505, 0x000c0d02, 0x000b0e04, 0x000b0f05, 0x000d1209, 0x0014120c, 0x0016110c, 0x0018100b, 0x00181009, 0x001a1008, 0x001b1007, 0x001c1005, 0x001f1406, 0x00221708, 0x00231708, 0x00251708, 0x00271706, 0x00281805, 0x002c1906, 0x002e1b08, 0x002f1a08, 0x00301a06, 0x00311b08, 0x00331a08, 0x00341908, 0x00341908, 0x00331a07, 0x00331a07, 0x00341b08, 0x00341b08, 0x00341c08, 0x00301807, 0x002d1809, 0x002c180b, 0x00261509, 0x0024140b, 0x00201409, 0x001d1409, 0x001a1208, 0x00181107, 0x00161106, 0x00141007, 0x00121007, 0x00121008, 0x00121008, 0x0014120a, 0x0017140c, 0x0018140b, 0x001b120a, 0x0021180b, 0x002b210b, 0x003b3010, 0x00413510, 0x00342702, 0x00332000, 0x003a2905, 0x00463309, 0x00593d0c, 0x0074520d, 0x00ad8c24, 0x00ccb224, 0x00ccb610, 0x00ccb80a, 0x00ccb808, 0x00cbb411, 0x00b08b0a, 0x007c5300, 0x005f3b00, 0x004e3307, 0x00412b09, 0x00382603, 0x00311e03, 0x002f1d06, 0x002a1c05, 0x00241704, 0x00201604, 0x001b1405, 0x00171106, 0x00161309, 0x00131308, 0x00111007, 0x00101006, 0x00121107, 0x00101006, 0x000e0e05, 0x000f0d06, 0x000f0d07, 0x0010100b, 0x0010100c, 0x000f0f0c, 0x000f0f0c, 0x000d100c, 0x000d100c, 0x00100f08, 0x00101007, 0x000f0f06, 0x00131209, 0x00111309, 0x00101208, 0x00121108, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014140a, 0x00141408, 0x00141407, 0x00141308, 0x00141308, 0x00141408, 0x00141408, 0x0014130a, 0x0014130a, 0x00141308, 0x00141308, 0x00161408, 0x00161408, 0x00171509, 0x0019150c, 0x0019150c, 0x0019160c, 0x0018170c, 0x0018170e, 0x0018180f, 0x00181811, 0x00181810, 0x0016150f, 0x0011130d, 0x000d130e, 0x000c140d, 0x00081009, 0x0008100a, 0x0009120c, 0x00081009, 0x00061009, 0x0008120c, 0x0008120d, 0x0008120d, 0x0008110c, 0x0008120d, 0x0008120f, 0x0008120f, 0x0007110d, 0x0007110d, 0x0008110d, 0x0009110d, 0x0009110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x000a110f, 0x000b100f, 0x000c1110, 0x000d1411, 0x00101513, 0x00101513, 0x00111514, 0x00141716, 0x00141815, 0x00141a16, 0x00151c15, 0x00151c15, 0x00161b15, 0x00181a15, 0x00181b15, 0x00171c17, 0x00151a14, 0x00151a14, 0x00141914, 0x00111812, 0x00111812, 0x000f1713, 0x000f1713, 0x000c1410, 0x000b1510, 0x000c1410, 0x000c1310, 0x000a1410, 0x00091310, 0x000a1210, 0x000a1210, 0x000a1210, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003e400d, 0x0041420e, 0x0045470e, 0x0048490f, 0x004c4d10, 0x00515110, 0x006e6210, 0x00cba216, 0x00c69f15, 0x00646012, 0x005b5b12, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005c5c11, 0x00a08615, 0x00cca417, 0x00b09115, 0x005d5c12, 0x00585911, 0x00585810, 0x00565710, 0x00555611, 0x00545511, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00545511, 0x00555611, 0x00565710, 0x00585910, 0x00595a12, 0x005b5b12, 0x007b6e12, 0x00c8a116, 0x00c49f18, 0x006f6612, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x005c5c12, 0x00595a11, 0x009c8314, 0x00cca316, 0x00ab8c14, 0x004c4d10, 0x004c4d10, 0x00494a0f, 0x0045470e, 0x0041420e, 0x003c3e0c, 0x00393b0c, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130e, 0x000f130f, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000b140d, 0x000c140d, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x0009120a, 0x0009120a, 0x000a130b, 0x000a130b, 0x000a140c, 0x000a140c, 0x0009140b, 0x0009140b, 0x000a130c, 0x000a130c, 0x000a130c, 0x000c120c, 0x000c120c, 0x000b110c, 0x000c140d, 0x000a140d, 0x000c130d, 0x000d140e, 0x00101510, 0x00111611, 0x00121712, 0x00141914, 0x00151a14, 0x00171914, 0x00191c18, 0x001a1d17, 0x001b1e18, 0x001d1e18, 0x001c1d18, 0x001c1e16, 0x001c1e16, 0x001c1e16, 0x001b1c14, 0x001a1b14, 0x00181a14, 0x00141811, 0x00111611, 0x00101511, 0x00101512, 0x000e1411, 0x000a110e, 0x0008120d, 0x0008110c, 0x00051009, 0x00081009, 0x00081009, 0x00081009, 0x0008110a, 0x000a100a, 0x000b110c, 0x000d110c, 0x000e120d, 0x000e120d, 0x000e140e, 0x000d140d, 0x00101710, 0x00101710, 0x00101710, 0x00141610, 0x0016160f, 0x0016160f, 0x0015150e, 0x0014150c, 0x0013140b, 0x0012140a, 0x0014130a, 0x0014130a, 0x00141408, 0x00141408, 0x00141308, 0x00141308, 0x0014130a, 0x0013130a, 0x00121209, 0x00121108, 0x00111108, 0x00131209, 0x00101208, 0x0012140a, 0x00101409, 0x000c1005, 0x000b0e04, 0x00090d03, 0x000a0e03, 0x000b0e04, 0x000c0e04, 0x000c0e04, 0x000c0e05, 0x000c1007, 0x000c1007, 0x000c0f08, 0x000d0e0a, 0x00100f0a, 0x000f1008, 0x000e0f08, 0x00101108, 0x0014130a, 0x0014130a, 0x00161409, 0x001a160b, 0x001f180a, 0x00241b0a, 0x00271c07, 0x002c2008, 0x00342508, 0x003c2e0a, 0x0044340c, 0x00523c0f, 0x0064460d, 0x00846311, 0x00c0a430, 0x00ccb420, 0x00ccb80c, 0x00ccb80a, 0x00ccb80c, 0x00cab80c, 0x00c8b40d, 0x00a48404, 0x00785300, 0x00604300, 0x004c3903, 0x003f3005, 0x003c2e05, 0x00463810, 0x0044370c, 0x00413408, 0x003d3108, 0x00382d0a, 0x0033290a, 0x002c2509, 0x001f1a00, 0x0025200b, 0x00211e0c, 0x00191809, 0x000d1004, 0x00090e03, 0x00090f06, 0x000b1008, 0x0012120b, 0x0014130c, 0x0016100b, 0x00171009, 0x00181108, 0x00181107, 0x001a1105, 0x001d1408, 0x00211808, 0x00231708, 0x00251708, 0x00261807, 0x00271706, 0x00281808, 0x002c1808, 0x002d1806, 0x002d1806, 0x00301808, 0x00301808, 0x00311809, 0x00341909, 0x00321a07, 0x00311b07, 0x00311b07, 0x00311b07, 0x00311b08, 0x00301808, 0x002c1609, 0x002a160b, 0x00241408, 0x00201409, 0x001f1308, 0x001c1308, 0x00191208, 0x00181107, 0x00171106, 0x00141007, 0x00121006, 0x00120e07, 0x00120e07, 0x0015120a, 0x0017140c, 0x0018140b, 0x001b130a, 0x0020180b, 0x002b210b, 0x003a2f10, 0x0040340f, 0x00342702, 0x00332001, 0x00392808, 0x0048330d, 0x005a3d0f, 0x0073510e, 0x00ac8c23, 0x00ccb224, 0x00ccb610, 0x00ccb808, 0x00ccb806, 0x00cbb40f, 0x00b18c09, 0x007c5300, 0x005e3b00, 0x004c3306, 0x00412c09, 0x00372502, 0x00332004, 0x002f1d06, 0x002a1c05, 0x00241704, 0x00211504, 0x001c1505, 0x00181106, 0x00161308, 0x00141308, 0x00131207, 0x00111006, 0x000f0f04, 0x00101005, 0x00101008, 0x00121009, 0x00111009, 0x0010100b, 0x0010100c, 0x00100f0a, 0x00100f0a, 0x000f100a, 0x0010100b, 0x00100f08, 0x00101007, 0x00141109, 0x0014130a, 0x00131008, 0x00141109, 0x00141109, 0x00141109, 0x0014120a, 0x0016120b, 0x00161209, 0x00161208, 0x00161307, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x0016120a, 0x0016120a, 0x00161208, 0x00161208, 0x00171309, 0x00171309, 0x00181408, 0x00181408, 0x00181309, 0x00181309, 0x00161409, 0x0016150b, 0x0017160c, 0x0019170f, 0x00191710, 0x00181710, 0x00191811, 0x00181a14, 0x00171914, 0x00131811, 0x00121710, 0x000f140d, 0x000c110a, 0x000b1009, 0x000a1009, 0x000a100b, 0x000b110c, 0x000a100a, 0x000a100b, 0x000a100c, 0x000a100c, 0x0008100c, 0x0008100c, 0x0009110c, 0x0009110d, 0x0009110c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0009110f, 0x0009110f, 0x000a1210, 0x000c1411, 0x000e1613, 0x000e1613, 0x00101513, 0x00131615, 0x00131815, 0x00131914, 0x00141b14, 0x00151c15, 0x00151c15, 0x00161b15, 0x00161b15, 0x00171c17, 0x00161b15, 0x00151c15, 0x00141a14, 0x00121813, 0x00111812, 0x00101814, 0x00101814, 0x000d1510, 0x000c1711, 0x000f1412, 0x000c1210, 0x000c1411, 0x000a1310, 0x000a120f, 0x000a120e, 0x000a120e, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0044450e, 0x0048490f, 0x004c4d0f, 0x004f5010, 0x006b6010, 0x00c8a015, 0x00c8a015, 0x00736812, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f12, 0x005e5f13, 0x005c5d11, 0x008c7914, 0x00cba417, 0x00c49f17, 0x00696312, 0x00595a12, 0x00585910, 0x00585810, 0x00565710, 0x00555611, 0x00545511, 0x00545511, 0x00535410, 0x00535410, 0x00545510, 0x00545511, 0x00545511, 0x00555610, 0x00565710, 0x00585910, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x00a28814, 0x00cca418, 0x00b79617, 0x00646213, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005b5b12, 0x005b5911, 0x00b09015, 0x00cca316, 0x00a38613, 0x004b4c10, 0x004c4d0f, 0x0048490f, 0x0045470e, 0x0041420d, 0x003e400d, 0x0038380c, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x00292b0b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c130d, 0x000c130d, 0x000c140d, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140d, 0x000b140c, 0x000c140c, 0x000c140c, 0x000c140c, 0x000c140c, 0x000c140c, 0x000b140c, 0x000a130b, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c130d, 0x000c120c, 0x000c130d, 0x000c140d, 0x000b170f, 0x000d160f, 0x00101610, 0x00121812, 0x00141813, 0x00141813, 0x00141914, 0x00161b15, 0x00191a17, 0x001c1c18, 0x001c1c17, 0x001d1e18, 0x001d1e18, 0x001d1e18, 0x001c1e16, 0x001c1e16, 0x001c1e16, 0x001a1c15, 0x00181b12, 0x00171913, 0x00131712, 0x00101511, 0x00111611, 0x00101510, 0x000d1310, 0x000a100b, 0x000a100b, 0x000a1009, 0x00091008, 0x000b1008, 0x000b1009, 0x000f140c, 0x000f140c, 0x0010130c, 0x0010130d, 0x0012140e, 0x0012140e, 0x0013140f, 0x00141510, 0x00141610, 0x00161810, 0x0015160f, 0x0014150f, 0x0014120c, 0x0016140c, 0x0017140d, 0x0018140d, 0x0016140c, 0x0014120c, 0x0014120b, 0x0014120b, 0x0014120b, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x00151208, 0x00161208, 0x00171309, 0x00171309, 0x00141008, 0x00121007, 0x00131108, 0x00131308, 0x0014140a, 0x00101309, 0x000f1007, 0x000c0f04, 0x000c0e04, 0x000c0e04, 0x000c0e04, 0x000d0f05, 0x000d0f06, 0x000e1108, 0x000e1109, 0x000e100b, 0x000f100c, 0x0011100c, 0x0010110a, 0x000f1008, 0x00101208, 0x0014130a, 0x0014130a, 0x00171409, 0x001b150b, 0x001f180a, 0x00241b0a, 0x00271c07, 0x002c2008, 0x00342508, 0x003c2e09, 0x0045340c, 0x00503c10, 0x0064470e, 0x00866413, 0x00c0a432, 0x00ccb420, 0x00ccb80c, 0x00ccb80a, 0x00ccb80c, 0x00ccb80c, 0x00c8b40d, 0x00a48404, 0x00785200, 0x005f4100, 0x004c3803, 0x003d2f04, 0x003a2d05, 0x0044380f, 0x0041340a, 0x0042350c, 0x003c300a, 0x00342b0b, 0x0030280c, 0x002b240b, 0x001d1802, 0x001d1b08, 0x00211f0f, 0x001a190c, 0x00101208, 0x000a0e03, 0x00090e05, 0x000a0e07, 0x000f1009, 0x0013100c, 0x0014100c, 0x00150f0a, 0x0018100a, 0x00181108, 0x00181107, 0x001c1407, 0x00201708, 0x00211707, 0x00221606, 0x00261808, 0x00251605, 0x00281708, 0x00291808, 0x002b1807, 0x002b1807, 0x002d1809, 0x002e1709, 0x00301709, 0x00301809, 0x00301906, 0x00301905, 0x00301905, 0x00301905, 0x00301908, 0x002c1808, 0x002b1709, 0x0028150b, 0x0024140a, 0x00211409, 0x001f1308, 0x001c1308, 0x001a1108, 0x00191008, 0x00181008, 0x00141007, 0x00121008, 0x00120e07, 0x00120e07, 0x0016120a, 0x0017140c, 0x0018140b, 0x001b130a, 0x001f170a, 0x002b210c, 0x00382d11, 0x003f3210, 0x00342602, 0x00321f04, 0x00392809, 0x00453210, 0x00573c11, 0x00725110, 0x00ad8c25, 0x00ccb024, 0x00ccb510, 0x00ccb809, 0x00ccb806, 0x00cbb40f, 0x00b08e0a, 0x007c5400, 0x005e3b00, 0x004c3104, 0x00402c09, 0x00372502, 0x00342005, 0x002f1c05, 0x002b1c06, 0x00261805, 0x00221604, 0x001e1506, 0x00181104, 0x00171308, 0x00151207, 0x00141106, 0x00131107, 0x00121106, 0x00121106, 0x00131107, 0x00131008, 0x0013100a, 0x0012100a, 0x0012100a, 0x00110f09, 0x000f0c06, 0x00100d07, 0x00121008, 0x00121008, 0x00151309, 0x00161409, 0x00141308, 0x00141208, 0x00141208, 0x00141108, 0x00141008, 0x00151108, 0x00161208, 0x00171307, 0x00181206, 0x00181306, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00171408, 0x00171408, 0x00171408, 0x00171408, 0x00181208, 0x00161208, 0x00161309, 0x00151409, 0x0015140a, 0x0015140b, 0x0015140b, 0x0015140b, 0x0015140c, 0x0014140c, 0x0014140c, 0x0016160f, 0x00181710, 0x00181810, 0x00181811, 0x00151710, 0x0014150e, 0x0010110b, 0x0010110c, 0x0010110c, 0x000d100b, 0x000c0f09, 0x000c100c, 0x000c100c, 0x000a110c, 0x000b110c, 0x000a110c, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006120c, 0x0006120c, 0x0005110b, 0x0005110b, 0x0006120c, 0x0007110c, 0x0008110d, 0x0008110d, 0x0009120f, 0x000b1410, 0x000c1411, 0x000c1411, 0x000e1513, 0x00101614, 0x00111814, 0x00111913, 0x00131a14, 0x00141c15, 0x00151c15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151c15, 0x00151c15, 0x00141a14, 0x00111812, 0x00101812, 0x00101813, 0x000f1811, 0x000e1610, 0x00111414, 0x000f1311, 0x000f1412, 0x000c1411, 0x000c1410, 0x000c1410, 0x000c1410, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0048490e, 0x004b4c0f, 0x004f5010, 0x00635b10, 0x00c09b14, 0x00c9a116, 0x008a7613, 0x00595a12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e12, 0x005d5e11, 0x006d6612, 0x00c49f17, 0x00cba417, 0x00988114, 0x005b5b12, 0x00595a12, 0x00585910, 0x00585810, 0x00565710, 0x00565711, 0x00555611, 0x00565711, 0x00555611, 0x00555611, 0x00555611, 0x00565710, 0x00585810, 0x00585910, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x00756b13, 0x00c4a018, 0x00cca418, 0x009e8415, 0x005c5d13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x00605c11, 0x00c39c16, 0x00cca216, 0x00917912, 0x004d4e10, 0x004b4c0f, 0x0048490f, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x000f130b, 0x000f130f, 0x000f130f, 0x000b140d, 0x000b140d, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000e140e, 0x000e140e, 0x000d140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140d, 0x000c140c, 0x000c140c, 0x000c150c, 0x000c150c, 0x000c140c, 0x000c140c, 0x000c150c, 0x000c140c, 0x000c140e, 0x000c140e, 0x000c140d, 0x000c130d, 0x000c130d, 0x000e140f, 0x000c140e, 0x000c1710, 0x000e1610, 0x00101710, 0x00131813, 0x00141914, 0x00141914, 0x00151a14, 0x00181a16, 0x001b1c18, 0x001c1c18, 0x001e1c18, 0x001d1e18, 0x001e1e18, 0x001d1e18, 0x001c1e16, 0x001b1d15, 0x00191c14, 0x00181c14, 0x00181b12, 0x00171913, 0x00141711, 0x00121410, 0x00101410, 0x00111610, 0x00111610, 0x0010140e, 0x0010140d, 0x0010140c, 0x0010140c, 0x0012140c, 0x0014140e, 0x0014150e, 0x0014160f, 0x00141610, 0x00151610, 0x00181710, 0x00181710, 0x0014140c, 0x0016140f, 0x0017150e, 0x0018150e, 0x0018140d, 0x0018140d, 0x0016130b, 0x00181209, 0x0017130c, 0x0018140c, 0x0017140c, 0x0017130c, 0x0017130c, 0x0017140d, 0x0017140d, 0x0016140b, 0x0016140b, 0x00161309, 0x00161309, 0x00151308, 0x00141208, 0x00141007, 0x00151108, 0x00151108, 0x00151208, 0x00141308, 0x00141308, 0x0014140a, 0x00131209, 0x00101208, 0x000f1007, 0x000c0e04, 0x000c0e04, 0x000c0e04, 0x000d0f05, 0x000d1006, 0x000e1109, 0x000e1109, 0x000e110b, 0x0010100c, 0x0012100c, 0x0010120a, 0x00101109, 0x0012140a, 0x0014130a, 0x0015140b, 0x0018140b, 0x001c160c, 0x0021180b, 0x00241c0b, 0x00291f09, 0x002e2209, 0x00352708, 0x003d2f0a, 0x0044360c, 0x00503c0f, 0x0064480e, 0x00866414, 0x00c1a433, 0x00ccb421, 0x00ccb80c, 0x00ccb80a, 0x00ccb80c, 0x00cbb80c, 0x00c8b40d, 0x00a48404, 0x00765300, 0x005f4000, 0x004b3704, 0x003d2e04, 0x00392c04, 0x0044380e, 0x003d3007, 0x003c3008, 0x00342c08, 0x00302809, 0x002c250c, 0x0028220b, 0x001c1904, 0x001b1a08, 0x001e1d0f, 0x0017180c, 0x000f1108, 0x000a0f04, 0x00080e05, 0x00090e07, 0x000d0d08, 0x0011100a, 0x0014100b, 0x0014100a, 0x0018110a, 0x00181108, 0x00181107, 0x001a1304, 0x001e1506, 0x001e1505, 0x00201504, 0x00241807, 0x00221404, 0x00271608, 0x00281708, 0x00291807, 0x002a1706, 0x002b1808, 0x002c1708, 0x002d1708, 0x002f1708, 0x002e1805, 0x002d1804, 0x002d1804, 0x002d1804, 0x002e1808, 0x002c1608, 0x0029150a, 0x0027140b, 0x0023140a, 0x00201309, 0x001f1308, 0x001c1207, 0x001a1008, 0x00191008, 0x00170f07, 0x00141007, 0x00110f07, 0x00120e07, 0x00120e07, 0x0016120a, 0x0018140c, 0x0018140b, 0x001a1409, 0x001c1407, 0x00271e08, 0x00362c10, 0x003d3010, 0x00332404, 0x00311e03, 0x0038260a, 0x0044310f, 0x00553910, 0x00704f0f, 0x00ac8b28, 0x00ccaf2a, 0x00ccb416, 0x00ccb70e, 0x00ccb80a, 0x00cbb40d, 0x00b08e0a, 0x007b5400, 0x005e3b00, 0x004b3004, 0x00402b09, 0x00372502, 0x00342005, 0x002e1c05, 0x002b1c06, 0x00281b07, 0x00241806, 0x00201705, 0x001c1204, 0x00191408, 0x00181307, 0x00151308, 0x00141308, 0x00141308, 0x00141308, 0x00141308, 0x00141108, 0x00131008, 0x00131009, 0x00141109, 0x00141108, 0x00110e04, 0x00110e04, 0x00141007, 0x00141307, 0x00141207, 0x00161408, 0x00161408, 0x00141308, 0x00141307, 0x00151408, 0x00161408, 0x00181308, 0x001a1307, 0x001a1305, 0x00191305, 0x00191305, 0x00191306, 0x00191307, 0x00191307, 0x00191208, 0x00191208, 0x00191208, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x00171408, 0x00171408, 0x00181108, 0x00161208, 0x00141208, 0x00141308, 0x00141309, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x00141309, 0x00141309, 0x00141409, 0x00141409, 0x00161309, 0x00161309, 0x001a170d, 0x0018150c, 0x0018150e, 0x0018150e, 0x0018160e, 0x0014140c, 0x0014130c, 0x0012140c, 0x0012140e, 0x000f120c, 0x000a100a, 0x00080f08, 0x0007100a, 0x0006100b, 0x0007110c, 0x0006120c, 0x0006120c, 0x0005130c, 0x0005130c, 0x0004110b, 0x0004110b, 0x0005130c, 0x0005120c, 0x0006110d, 0x0006110d, 0x0006110d, 0x0008130f, 0x000a1511, 0x000a1511, 0x000c1512, 0x000f1714, 0x000f1714, 0x00101912, 0x00101a13, 0x00111b14, 0x00141c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00131914, 0x00111913, 0x00121a14, 0x000f1811, 0x00101812, 0x00111514, 0x00101211, 0x00101412, 0x000f1412, 0x000d1410, 0x000d150f, 0x000c140f, 0x00060c07, 0x000f130f, 0x000f130f, 0x0014180f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x002c2d0b, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c10, 0x004d4e0f, 0x00585510, 0x00b69314, 0x00cca316, 0x00a48814, 0x005b5a12, 0x005b5b12, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5d11, 0x009f8615, 0x00cca417, 0x00c49f17, 0x00736813, 0x00595a12, 0x00595a12, 0x00585910, 0x00585910, 0x00585810, 0x00585810, 0x00565711, 0x00565711, 0x00565710, 0x00585810, 0x00585810, 0x00585911, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x00646112, 0x00b19316, 0x00cca418, 0x00c7a118, 0x00766c14, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x007f7012, 0x00c8a016, 0x00cba216, 0x00786811, 0x004d4e10, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x0030310c, 0x00292b0a, 0x0026280b, 0x0024250b, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x000c140e, 0x000c140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000f150f, 0x000f150f, 0x000d150f, 0x000d150f, 0x000c140e, 0x000c140e, 0x000c140d, 0x000c140c, 0x000c140c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000d140d, 0x000d140d, 0x000e140e, 0x000f150f, 0x000f150f, 0x0010140f, 0x000f1410, 0x00101510, 0x00131713, 0x00141714, 0x00151814, 0x00171814, 0x00171814, 0x00181914, 0x00191a17, 0x001c1c18, 0x001d1c18, 0x001f1e18, 0x001d1e18, 0x001d1f18, 0x001b1d16, 0x001b1d15, 0x001a1d15, 0x00181c13, 0x00171a11, 0x00161910, 0x00161811, 0x00151711, 0x00141610, 0x0012140d, 0x0012160e, 0x00141810, 0x00141710, 0x0014160d, 0x0015150d, 0x0015150d, 0x0017150d, 0x0017150d, 0x0017150e, 0x0017150d, 0x0014130b, 0x0015140b, 0x0016130c, 0x0017140c, 0x0014130b, 0x0015130b, 0x0016140a, 0x0016140b, 0x0016140b, 0x0017140b, 0x0017140a, 0x00151308, 0x0017140b, 0x0018140c, 0x0018140b, 0x0018140b, 0x0018140b, 0x0018140c, 0x0018140c, 0x0017140b, 0x0017140a, 0x00161409, 0x00161409, 0x00151409, 0x00151409, 0x0017130a, 0x0017130a, 0x0017140b, 0x0017130a, 0x00151209, 0x0016130a, 0x0017130a, 0x0016130a, 0x00141208, 0x00111108, 0x000f1006, 0x000f0d04, 0x000f0d05, 0x00111008, 0x00101008, 0x00101209, 0x00101209, 0x0010120a, 0x0010110a, 0x00121109, 0x00121109, 0x00141209, 0x00151309, 0x00161309, 0x0018140a, 0x001a150a, 0x001e1809, 0x00231808, 0x00271a09, 0x002c1e08, 0x00302208, 0x00372708, 0x003e2f09, 0x0044370b, 0x004f3d0c, 0x0064480c, 0x00866414, 0x00bea130, 0x00ccb421, 0x00ccb80c, 0x00cbb80a, 0x00cbb80c, 0x00cbb90d, 0x00c9b60f, 0x00a48604, 0x00765200, 0x005f4000, 0x004a3604, 0x003c2f05, 0x00382c04, 0x0044370f, 0x003b2f06, 0x00352b04, 0x00342c08, 0x0030290c, 0x0029230b, 0x0024210c, 0x001c1a08, 0x00191808, 0x001a1b0c, 0x00131509, 0x000d1107, 0x00090f04, 0x00070e04, 0x00080e05, 0x000c0e07, 0x00100f08, 0x0013100b, 0x0014100a, 0x0016100a, 0x00181108, 0x00181207, 0x00181305, 0x001c1407, 0x001c1405, 0x001e1406, 0x00201508, 0x00211407, 0x00251709, 0x0028180a, 0x00281708, 0x00281708, 0x00281708, 0x00281708, 0x00291708, 0x002b1608, 0x002b1706, 0x002b1706, 0x002c1806, 0x002c1806, 0x002b1708, 0x00291509, 0x00261409, 0x0024130a, 0x0021140a, 0x001e1309, 0x001d1208, 0x001c110a, 0x001b1008, 0x00191008, 0x00170f07, 0x00141008, 0x00120e07, 0x00110f08, 0x00110f08, 0x00141109, 0x0016140a, 0x0018140b, 0x00191408, 0x001c1407, 0x00231b08, 0x00322711, 0x003b2e14, 0x00312408, 0x002f1e03, 0x00382809, 0x0044310c, 0x0052370c, 0x006d4b0c, 0x00ac8a28, 0x00ccb12b, 0x00ccb417, 0x00cbb50f, 0x00cbb60a, 0x00cbb60e, 0x00af8e0a, 0x007a5300, 0x005e3a00, 0x004c2f04, 0x00402b09, 0x00362602, 0x00342005, 0x002f1c07, 0x002c1c08, 0x00291b08, 0x00261808, 0x00221706, 0x00201408, 0x001c1508, 0x001a1407, 0x00181306, 0x00181208, 0x00181208, 0x00171107, 0x00151208, 0x00151208, 0x00141208, 0x00121108, 0x00141308, 0x00151408, 0x00181409, 0x00151206, 0x00151106, 0x00181208, 0x00161005, 0x00171207, 0x00181208, 0x00171208, 0x00181409, 0x00171408, 0x00181508, 0x001b1408, 0x001c1408, 0x001c1405, 0x001c1405, 0x001c1405, 0x001d1405, 0x001d1407, 0x001e1408, 0x001d1408, 0x001c1408, 0x001c1409, 0x001c1408, 0x001d1508, 0x001c1508, 0x001c1608, 0x00181307, 0x00171408, 0x00181108, 0x00171109, 0x00161109, 0x00141108, 0x00141209, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x00141309, 0x00141309, 0x00151008, 0x00171109, 0x00171109, 0x0018120a, 0x0019130b, 0x0019130b, 0x0017140c, 0x0017140c, 0x0019170f, 0x0018160e, 0x0017150f, 0x0017150f, 0x00181710, 0x00181710, 0x00141510, 0x00101510, 0x00101410, 0x000c120d, 0x000b110c, 0x0008100b, 0x0008110b, 0x0006130c, 0x0006130c, 0x0006110a, 0x0006110a, 0x0007110b, 0x0007110b, 0x0006110a, 0x0008120c, 0x0006120b, 0x0006130c, 0x0008140f, 0x000b1510, 0x000b1510, 0x000d1712, 0x000e1812, 0x000f1812, 0x00101a13, 0x00111c14, 0x00131c15, 0x00141c14, 0x00141c14, 0x00161c15, 0x00161c15, 0x00161c15, 0x00161c15, 0x00161c14, 0x00151a14, 0x00131a14, 0x00131914, 0x00101812, 0x00101812, 0x00131714, 0x00111412, 0x00101512, 0x00101411, 0x000d140f, 0x000d150f, 0x000c140e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004c4d0f, 0x004d4e10, 0x00a48714, 0x00cca316, 0x00be9915, 0x00615d12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x00696412, 0x00b99816, 0x00cca417, 0x00b49415, 0x00696312, 0x005b5b12, 0x00595a12, 0x00585911, 0x00585910, 0x00585910, 0x00585910, 0x00585910, 0x00585910, 0x00585911, 0x00595a12, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x00605e12, 0x00a38815, 0x00cca418, 0x00cca418, 0x00a48815, 0x00605f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5c11, 0x005b5b12, 0x00595a11, 0x00a08514, 0x00cca316, 0x00bf9915, 0x00615a10, 0x004d4e0f, 0x00494a0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0036370b, 0x0034350c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x000d150f, 0x000c150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x00101610, 0x00101610, 0x000e150f, 0x000d150f, 0x000d150f, 0x000e1610, 0x000d150f, 0x000d150f, 0x000d150f, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x0010160d, 0x0010160d, 0x00101710, 0x00101710, 0x00101610, 0x00101510, 0x00141613, 0x00151613, 0x00161714, 0x00171814, 0x00171814, 0x00181814, 0x00181814, 0x001a1a15, 0x001c1b17, 0x001e1c17, 0x001f1e18, 0x001f1e18, 0x001f1e18, 0x001e2018, 0x001c1e16, 0x00191c13, 0x00171a10, 0x0017190f, 0x0014170c, 0x0013150d, 0x0014150d, 0x0015150f, 0x0014140d, 0x0013140b, 0x0013140b, 0x0012140b, 0x0014140b, 0x0014140b, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0015130a, 0x0015130a, 0x0014130a, 0x0014130a, 0x00151108, 0x00151108, 0x00141108, 0x00151208, 0x00141308, 0x00161409, 0x00151409, 0x00151409, 0x00151408, 0x00171408, 0x00171409, 0x00181409, 0x00181409, 0x00181408, 0x001a1408, 0x001b1408, 0x00191408, 0x00181408, 0x00181408, 0x00181408, 0x00181409, 0x00181308, 0x00181309, 0x0018130a, 0x0018130a, 0x0018130a, 0x0018130a, 0x00181309, 0x00181109, 0x00181008, 0x00181007, 0x00161208, 0x00141207, 0x00141108, 0x00141108, 0x00141008, 0x00131007, 0x00131108, 0x00131409, 0x00121308, 0x00121308, 0x00131308, 0x00141208, 0x00151108, 0x00181308, 0x00191408, 0x001a1408, 0x001b1409, 0x001e1708, 0x00221808, 0x00261808, 0x002b1a08, 0x002f1e08, 0x00342208, 0x00382709, 0x003e2f09, 0x0044360b, 0x00503c0c, 0x0064480c, 0x00876414, 0x00bca02e, 0x00ccb421, 0x00ccb80c, 0x00cab90a, 0x00cbb90c, 0x00cbba0e, 0x00cab810, 0x00a48805, 0x00745100, 0x00604100, 0x004a3505, 0x003c2f07, 0x00382c04, 0x0042370f, 0x003b2f07, 0x00342803, 0x002e2605, 0x002b2509, 0x00262009, 0x00221f0c, 0x001b1809, 0x00161507, 0x0017180b, 0x00131509, 0x000e1208, 0x000a1006, 0x00070e04, 0x00070e04, 0x000c0e08, 0x00100f08, 0x00100e0a, 0x00101009, 0x00140f09, 0x00141008, 0x00171207, 0x00181205, 0x001a1407, 0x001b1407, 0x001d1408, 0x0020140a, 0x00201409, 0x00241809, 0x0026170a, 0x0027170a, 0x0027170a, 0x00241708, 0x00241708, 0x00261608, 0x00261508, 0x00261607, 0x00261607, 0x00281708, 0x00281809, 0x0028160a, 0x00251409, 0x0023140a, 0x0021140a, 0x0020140a, 0x001d140a, 0x001c120a, 0x001b1008, 0x001a1008, 0x00181008, 0x00161007, 0x00140e08, 0x00110f07, 0x00100f08, 0x00100f08, 0x00131109, 0x00141409, 0x0017140b, 0x00181408, 0x001c1507, 0x00221a0a, 0x002b2010, 0x00342713, 0x0030210a, 0x002f1d04, 0x00382708, 0x00422e0a, 0x0053350b, 0x006e4c0b, 0x00a98823, 0x00caac24, 0x00cbb10f, 0x00cab408, 0x00cbb406, 0x00ccb411, 0x00ae8c0b, 0x00785000, 0x005c3800, 0x004c3004, 0x00412c09, 0x00372703, 0x00342006, 0x00301c07, 0x002f1c08, 0x002c1c08, 0x002b1b08, 0x00251806, 0x00231708, 0x00201609, 0x001c1408, 0x001c1306, 0x001c1306, 0x001b1307, 0x00191108, 0x00181108, 0x00181308, 0x00171408, 0x00141308, 0x00161408, 0x001a170b, 0x001e1a0e, 0x001d180c, 0x001b1509, 0x001d1409, 0x001c1208, 0x001d1409, 0x001d1409, 0x001d1409, 0x001d150a, 0x001d160a, 0x001d1709, 0x00201708, 0x00201706, 0x00201707, 0x00221708, 0x00221708, 0x00241708, 0x00241708, 0x00241808, 0x00241808, 0x00231809, 0x0023180a, 0x00221708, 0x00211707, 0x00211807, 0x00201808, 0x001c1407, 0x001a1409, 0x001a140a, 0x0019120b, 0x00181209, 0x00171109, 0x0017120a, 0x0015130a, 0x0015130a, 0x0014130a, 0x0014130a, 0x0015120a, 0x0016120a, 0x00161109, 0x00161109, 0x0018110a, 0x0018110a, 0x0018110a, 0x0018110a, 0x0016120a, 0x0015140a, 0x0015140b, 0x0016140c, 0x0017140d, 0x0018140d, 0x0018140e, 0x0018150f, 0x00171610, 0x00161812, 0x00161813, 0x00141611, 0x0011140e, 0x0010140d, 0x000f150c, 0x000b140b, 0x00091409, 0x00091208, 0x000a1208, 0x00091108, 0x00091008, 0x00081007, 0x000a1309, 0x00081309, 0x00081409, 0x0008120c, 0x0009140d, 0x000b150f, 0x000c1710, 0x000e1811, 0x000f1812, 0x000f1912, 0x00101b14, 0x00121c14, 0x00141c14, 0x00151c14, 0x00171c15, 0x00181c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00171c14, 0x00151c16, 0x00141b14, 0x00121813, 0x00121813, 0x00141914, 0x00141814, 0x00131713, 0x00111511, 0x00101610, 0x00101710, 0x000f1610, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0041420d, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x004d4e10, 0x00847011, 0x00cba216, 0x00c9a116, 0x00827113, 0x00595a12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x00786e13, 0x00c19c17, 0x00cca417, 0x00b09115, 0x006c6412, 0x00595a12, 0x005b5b12, 0x00595a12, 0x00595a12, 0x00595a12, 0x00595a12, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x005c5c12, 0x005b5b11, 0x00646112, 0x00a38815, 0x00caa418, 0x00cca418, 0x00b89717, 0x006b6513, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x005b5b12, 0x00615d11, 0x00be9916, 0x00cca316, 0x00a88914, 0x00505010, 0x004c4d0f, 0x00494a0f, 0x0045470e, 0x0041420e, 0x003c3e0c, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x001d200a, 0x00191c0b, 0x0014180b, 0x000f130d, 0x000f130f, 0x000f130f, 0x000e150f, 0x000e150f, 0x00101610, 0x00101610, 0x00101610, 0x00101610, 0x00101611, 0x00101711, 0x00101610, 0x000f1610, 0x000f1710, 0x00101811, 0x00101711, 0x000f1610, 0x000f1710, 0x00101811, 0x00101811, 0x00101811, 0x00101811, 0x000f1610, 0x000f1610, 0x00101710, 0x00101710, 0x00101710, 0x00101710, 0x00101710, 0x00111610, 0x00161813, 0x00181814, 0x00181814, 0x00181713, 0x001a1813, 0x001c1a14, 0x001c1b14, 0x001c1c16, 0x001d1c14, 0x001d1d15, 0x001e1d15, 0x001d1c14, 0x001c1c14, 0x00181911, 0x00161810, 0x0016180e, 0x0016180e, 0x0015170d, 0x0014150c, 0x0014140c, 0x0014120c, 0x0014120c, 0x0014120c, 0x0014130a, 0x0013130a, 0x0014140a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x00141109, 0x00141107, 0x00141107, 0x00141108, 0x00151208, 0x00151308, 0x00161409, 0x0017140a, 0x00181309, 0x00181408, 0x00181408, 0x001a1408, 0x001b1408, 0x001b1408, 0x001c1407, 0x001c1408, 0x001d1508, 0x001c1406, 0x001c1405, 0x001c1405, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1308, 0x001c1309, 0x001c130a, 0x001c130a, 0x001c130a, 0x001c140b, 0x001c140b, 0x001e150a, 0x001d150a, 0x001b1409, 0x00191509, 0x001b160b, 0x001b160c, 0x001b160c, 0x00181409, 0x00141006, 0x00151408, 0x00151408, 0x00141408, 0x00151408, 0x00171408, 0x00181308, 0x001a1308, 0x001b1408, 0x001d1508, 0x001d1508, 0x00201708, 0x00241a08, 0x00281908, 0x002d1c08, 0x00311f08, 0x00362308, 0x003b2808, 0x00402e09, 0x0047340b, 0x00513a0a, 0x0064460b, 0x00846312, 0x00bca02e, 0x00ccb421, 0x00ccb80c, 0x00cab90a, 0x00cab80c, 0x00caba0d, 0x00c9b810, 0x00a68908, 0x00745200, 0x005e4000, 0x004a3406, 0x003c2c06, 0x00362a04, 0x0040350e, 0x003c3109, 0x00332904, 0x002a2103, 0x00251f06, 0x00241f0a, 0x00201d0e, 0x0018180c, 0x00131407, 0x00111408, 0x0012160c, 0x000e1409, 0x000a1007, 0x00060f04, 0x00070f04, 0x000b0e08, 0x000f1009, 0x0010100b, 0x00101109, 0x00121009, 0x00141008, 0x00151206, 0x00171305, 0x00191306, 0x001b1407, 0x001c1408, 0x001c1308, 0x001d1308, 0x00201508, 0x00231608, 0x00241508, 0x00241508, 0x00211508, 0x00231408, 0x00241408, 0x00241408, 0x00241407, 0x00241406, 0x00251608, 0x00261708, 0x00241408, 0x00211308, 0x00201409, 0x001f1409, 0x001c1309, 0x001b1309, 0x001a1108, 0x00191008, 0x00181008, 0x00161008, 0x00140f07, 0x00120f07, 0x00100f08, 0x000f0f07, 0x000f0f07, 0x00121309, 0x00131408, 0x0015140a, 0x00171407, 0x001a1507, 0x00201909, 0x00261c0c, 0x002a1c0b, 0x002e2009, 0x002e1c05, 0x0037260a, 0x00402b09, 0x0052340b, 0x00684506, 0x00ab8726, 0x00ccac28, 0x00cbb012, 0x00ccb10c, 0x00cbb00b, 0x00cbac1c, 0x00a9810e, 0x00764c01, 0x00593600, 0x004c3004, 0x00412c0a, 0x003a2804, 0x00382107, 0x00341e06, 0x00301c05, 0x002f1c06, 0x002d1c07, 0x00291906, 0x00271808, 0x00241809, 0x00211608, 0x00201407, 0x00201408, 0x00201407, 0x001c1306, 0x001a1207, 0x00191308, 0x00181407, 0x00171306, 0x00191408, 0x001d180c, 0x00231c0f, 0x00231b0f, 0x0021190c, 0x0024180c, 0x0024180b, 0x0025180c, 0x0027190c, 0x0026190c, 0x00271a0c, 0x00281b0c, 0x00281b0a, 0x00281a08, 0x00281a0a, 0x00281b0b, 0x002a1b0c, 0x00291a09, 0x002a1a09, 0x002a1a09, 0x002b1b09, 0x002b1b09, 0x002a1b0b, 0x002a1b0b, 0x00281a0a, 0x00271808, 0x00241906, 0x00231807, 0x00201708, 0x001e1708, 0x001d150a, 0x001c130a, 0x001a1309, 0x00181208, 0x00181109, 0x0018110a, 0x0017120a, 0x0017120a, 0x0016120a, 0x0016120a, 0x0016120a, 0x0016120a, 0x00141008, 0x00151008, 0x00151008, 0x00151109, 0x00141109, 0x00141008, 0x00131008, 0x00141109, 0x00141109, 0x0014120b, 0x0014120c, 0x0014120b, 0x0014130c, 0x0016140f, 0x00161510, 0x0014140f, 0x0014140e, 0x0014140e, 0x0016160f, 0x0015180f, 0x0014180e, 0x0010160c, 0x0010140b, 0x0010140b, 0x000e1309, 0x000c1108, 0x000c1007, 0x000d1208, 0x000c1308, 0x000a1308, 0x000a130b, 0x000a130c, 0x0009130c, 0x000b140d, 0x000c170f, 0x000d1810, 0x000e1810, 0x000f1911, 0x00111b13, 0x00141b13, 0x00161c14, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00161c17, 0x00161c17, 0x00141a14, 0x00141a14, 0x00161b15, 0x00141914, 0x00141914, 0x00141813, 0x00121712, 0x00121812, 0x00111711, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004d4e10, 0x00605911, 0x00c09a14, 0x00cca316, 0x00ae8e14, 0x005c5b12, 0x005c5c12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x007c7013, 0x00bf9b17, 0x00cca417, 0x00bc9916, 0x00847413, 0x00605d12, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005c5c12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x00786d13, 0x00b39317, 0x00cca418, 0x00cca418, 0x00bb9917, 0x00736a14, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5c12, 0x00595a12, 0x00887512, 0x00caa116, 0x00caa016, 0x007c6c11, 0x004d4e10, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0036370c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x000f130f, 0x00101610, 0x00101610, 0x00101710, 0x00101710, 0x00101710, 0x00101710, 0x00111611, 0x00121611, 0x00111711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00111711, 0x00111711, 0x00121812, 0x00121812, 0x00121810, 0x00121810, 0x00121810, 0x00121810, 0x00131910, 0x00151910, 0x00171810, 0x00191810, 0x00191810, 0x00191710, 0x001b1811, 0x001c1912, 0x001b1811, 0x00191810, 0x0018180f, 0x0018170e, 0x0018170e, 0x0018150c, 0x00141309, 0x00111309, 0x00111309, 0x00131309, 0x00141209, 0x00141209, 0x00141209, 0x0014100a, 0x00131009, 0x0013100a, 0x0013100a, 0x00111008, 0x00121108, 0x00121108, 0x00131109, 0x00141209, 0x0014130a, 0x0014130a, 0x0013120a, 0x0013120a, 0x0013120a, 0x0013120a, 0x00131209, 0x00131209, 0x00141208, 0x00141208, 0x00141207, 0x00151308, 0x00181309, 0x00181309, 0x001a140b, 0x001a140a, 0x001c140a, 0x001d1609, 0x001e160a, 0x0020160a, 0x00201609, 0x00201708, 0x00201708, 0x00201809, 0x00201808, 0x00221807, 0x00221807, 0x00241808, 0x00241809, 0x00241809, 0x00241809, 0x0024180c, 0x0024180c, 0x0024180c, 0x0024180c, 0x0024180d, 0x0024190e, 0x0025190e, 0x0023180c, 0x0021180c, 0x00211a0d, 0x00201a0f, 0x0020190e, 0x001f190e, 0x001b1409, 0x00181206, 0x00171508, 0x00171508, 0x00161407, 0x00171407, 0x001a150a, 0x001c140a, 0x001d1509, 0x001e1708, 0x0020180a, 0x00201809, 0x00241a09, 0x00281c08, 0x002c1c09, 0x00311e0a, 0x00352109, 0x003b2508, 0x0040290b, 0x00452f0c, 0x004a340c, 0x0054390a, 0x00644409, 0x00805e0d, 0x00ba9c2c, 0x00ccb421, 0x00ccb80c, 0x00cab90a, 0x00cab80c, 0x00c8b90c, 0x00c9b810, 0x00a88b09, 0x00755200, 0x005c3d00, 0x004b3407, 0x003a2a04, 0x00302400, 0x003d310a, 0x003d330a, 0x00342b08, 0x002c2207, 0x00241e08, 0x00201a08, 0x001b190b, 0x0014150b, 0x00101207, 0x000e1308, 0x0010150c, 0x000c1209, 0x00091006, 0x00071005, 0x00080f05, 0x00090d06, 0x000c0f07, 0x0010100b, 0x00101109, 0x0012110a, 0x00131008, 0x00151307, 0x00151305, 0x00181406, 0x001a1407, 0x001b1407, 0x001c1307, 0x001c1306, 0x001c1407, 0x00201408, 0x00201308, 0x00201308, 0x001e1307, 0x001f1207, 0x00211308, 0x00221208, 0x00201307, 0x00201406, 0x00221408, 0x00211407, 0x00211408, 0x001f1308, 0x001d1309, 0x001c1408, 0x00191308, 0x00191208, 0x00181208, 0x00181008, 0x00171008, 0x00151008, 0x00130f08, 0x00100f07, 0x00100f08, 0x000d0f05, 0x000d0f05, 0x00101308, 0x00111308, 0x00141208, 0x00161306, 0x00181306, 0x001c1408, 0x0022170b, 0x0027190b, 0x002c1d0a, 0x002e1c06, 0x00352405, 0x00402c06, 0x004e300a, 0x00644008, 0x00a27b28, 0x00c49e2c, 0x00c2a019, 0x00bf9f14, 0x00be9b13, 0x00c2941d, 0x009c6d0c, 0x006e4201, 0x00563400, 0x00493106, 0x00432e0b, 0x003d2907, 0x003b2208, 0x00382008, 0x00341e06, 0x00301c05, 0x00301c05, 0x002e1b06, 0x002b1908, 0x00281909, 0x00251808, 0x00251707, 0x00251607, 0x00241707, 0x00221508, 0x00201408, 0x001f150a, 0x001d160a, 0x001a1407, 0x00181206, 0x001b1305, 0x001d1407, 0x001e1508, 0x001e1406, 0x00231608, 0x00251808, 0x00251807, 0x00291a0b, 0x002c1c0c, 0x002e1c0c, 0x002f1d0b, 0x002f1d0a, 0x00301e0a, 0x00311e0b, 0x00321e0d, 0x00311e0c, 0x00301c08, 0x00301c08, 0x00311c09, 0x00321d0a, 0x00311d0a, 0x00301d0b, 0x00301d0c, 0x002e1c09, 0x002c1b08, 0x00291a07, 0x00281b08, 0x00271b08, 0x00241908, 0x00201608, 0x001d1408, 0x001e150b, 0x001c140a, 0x001a1208, 0x001a1208, 0x00191208, 0x0018120a, 0x0018130a, 0x0017130b, 0x0017130b, 0x0016130b, 0x00141008, 0x00111008, 0x00121008, 0x00121008, 0x00131009, 0x00131009, 0x00131009, 0x00131009, 0x00131009, 0x0013120b, 0x0013120b, 0x0012110a, 0x0013120b, 0x0013120a, 0x0012110a, 0x0013120b, 0x0013120a, 0x0014110a, 0x00141209, 0x0015140b, 0x0013140a, 0x0013140a, 0x0013140a, 0x0013140a, 0x0014140b, 0x0013140a, 0x0013140a, 0x0013140a, 0x0012150a, 0x00101409, 0x000d150b, 0x000c150c, 0x000c140c, 0x000c150c, 0x000c170d, 0x000e1810, 0x000f1910, 0x000e1810, 0x00121a11, 0x00151a11, 0x00171c12, 0x00191c14, 0x00191c14, 0x001b1c16, 0x00181c16, 0x00191c16, 0x00181d16, 0x00161c17, 0x00161c17, 0x00151c15, 0x00151c15, 0x00161b14, 0x00151a14, 0x00151a14, 0x00141813, 0x00131712, 0x00131712, 0x00131712, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280c, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x00494a0f, 0x004c4d0f, 0x00505010, 0x009e8213, 0x00cca316, 0x00c8a015, 0x007b6d12, 0x00595a12, 0x005c5c12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x00736a13, 0x00b49415, 0x00cba417, 0x00c9a318, 0x00b19216, 0x00897714, 0x00686212, 0x00605d11, 0x00605d12, 0x00605e12, 0x00636012, 0x007c7013, 0x00a68916, 0x00c6a118, 0x00cca418, 0x00cba418, 0x00b39317, 0x00706813, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5d12, 0x005b5b12, 0x00605c11, 0x00b49314, 0x00cca316, 0x00b69314, 0x00595510, 0x004d4e0f, 0x00494a10, 0x0045470e, 0x0043440e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0b, 0x00292b0a, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x00101711, 0x00101711, 0x00121812, 0x00121812, 0x00121812, 0x00111812, 0x00131712, 0x00121712, 0x00111611, 0x00111611, 0x00111611, 0x00121712, 0x00121712, 0x00111712, 0x00121712, 0x00121712, 0x00131712, 0x00141712, 0x00121611, 0x00141812, 0x00141812, 0x00141811, 0x00141811, 0x00141810, 0x00141810, 0x00161810, 0x00161810, 0x0016180e, 0x0017170e, 0x0018160e, 0x0018160e, 0x0017150c, 0x0016140c, 0x0016140b, 0x0016140b, 0x0015140b, 0x0018170e, 0x0018170e, 0x0016140b, 0x00131308, 0x00101208, 0x00101208, 0x00101006, 0x00121006, 0x00121008, 0x00131008, 0x00141009, 0x00130f08, 0x00130f09, 0x00111009, 0x00111008, 0x00111008, 0x00111108, 0x00131109, 0x0014120a, 0x0014120a, 0x0014120c, 0x0013120c, 0x0014120c, 0x0014120b, 0x0014130c, 0x0014130c, 0x0014130b, 0x00171108, 0x00181208, 0x00171005, 0x00181207, 0x00191208, 0x001a1209, 0x001b130a, 0x001c1308, 0x00201509, 0x00241609, 0x0024170b, 0x0024180b, 0x0024180a, 0x0025180b, 0x0026190c, 0x00271a0c, 0x00271b0a, 0x00281c08, 0x00281c08, 0x002a1c0a, 0x002a1c0a, 0x002a1c0a, 0x00281b09, 0x00271a0a, 0x00271a0a, 0x00271b0a, 0x00261a09, 0x00261a09, 0x00251a09, 0x0024190c, 0x0020180c, 0x001c1509, 0x001a1508, 0x00191508, 0x00181406, 0x00191407, 0x00191406, 0x001b1407, 0x001a1408, 0x001a1407, 0x00191407, 0x001a1407, 0x001d170a, 0x001f1709, 0x00201708, 0x00231808, 0x00241c09, 0x00241c08, 0x00271d09, 0x002c200a, 0x002f2008, 0x00342008, 0x00382408, 0x003e2706, 0x00442b0a, 0x0048300c, 0x004f350c, 0x00573a0b, 0x0064430a, 0x007c590d, 0x00b8992d, 0x00ccb423, 0x00ccb810, 0x00c9b80c, 0x00cab80c, 0x00c8ba0a, 0x00cbba11, 0x00ab8e0b, 0x00745400, 0x005b3e00, 0x00493204, 0x003b2a05, 0x002e2100, 0x00382c0a, 0x00392e0c, 0x0033280b, 0x002c240b, 0x00241c08, 0x001b1706, 0x00181609, 0x00111409, 0x000e1207, 0x000d1208, 0x000d140a, 0x000c1208, 0x00080f05, 0x00080e04, 0x00080e04, 0x00090d04, 0x00080c03, 0x000c0e06, 0x000c0f06, 0x00100f08, 0x00120f07, 0x00151108, 0x00171207, 0x00181407, 0x00191307, 0x00191307, 0x001b1307, 0x001b1207, 0x001b1207, 0x001c1308, 0x001c1107, 0x001c1107, 0x001c1207, 0x001c1107, 0x001e1108, 0x001e1108, 0x001e1108, 0x001e1108, 0x001e1107, 0x001d1107, 0x001e1408, 0x001c1308, 0x001b1409, 0x00191408, 0x00181308, 0x00181209, 0x00181108, 0x00171008, 0x00161008, 0x00130f08, 0x00110f07, 0x000f0e05, 0x000f0e06, 0x000c0f04, 0x000c1005, 0x000e1007, 0x00101207, 0x00131208, 0x00161208, 0x00181308, 0x00191308, 0x0020170b, 0x0025180a, 0x002a1b08, 0x002c1b05, 0x00352204, 0x00402a04, 0x004b2d09, 0x005b370a, 0x00724b08, 0x0088600b, 0x008a6102, 0x008b6303, 0x008b5f00, 0x00845300, 0x00754700, 0x005f3400, 0x00573406, 0x004a3008, 0x00442e0a, 0x00402a08, 0x003c2408, 0x00392207, 0x00361f06, 0x00341e06, 0x00321d04, 0x00311c05, 0x002e1c07, 0x002b1b07, 0x00281906, 0x00271804, 0x00271804, 0x00261804, 0x00261707, 0x00241809, 0x0024180b, 0x0023190b, 0x0020160a, 0x001c1406, 0x001b1204, 0x001c1104, 0x001c1305, 0x001c1304, 0x001d1101, 0x00201301, 0x00241404, 0x00271706, 0x002c1b08, 0x002f1c08, 0x00301d09, 0x0034200b, 0x0038220c, 0x0039230d, 0x003a230d, 0x003a230c, 0x0039210b, 0x003a210a, 0x0039210a, 0x00382009, 0x00382009, 0x00372009, 0x00352009, 0x00332009, 0x002f1f08, 0x002c1d07, 0x002b1c08, 0x002c1c08, 0x00291b08, 0x00261908, 0x00231608, 0x0022170a, 0x0022170b, 0x001f1408, 0x001d1206, 0x001c1108, 0x001a1208, 0x0019130a, 0x0017130b, 0x0016140b, 0x0014130a, 0x00111008, 0x00131209, 0x0014110a, 0x0012110a, 0x0012110a, 0x0013100a, 0x0013100a, 0x0012110a, 0x0012110a, 0x0013110b, 0x0013110b, 0x0012110a, 0x00101009, 0x00101008, 0x00121109, 0x0014120a, 0x00141109, 0x00141109, 0x00141008, 0x00131108, 0x00131108, 0x00121108, 0x00121108, 0x00121108, 0x00131208, 0x00141409, 0x0017140a, 0x0016140a, 0x0016150b, 0x0014150a, 0x0012160c, 0x0012170e, 0x0012180e, 0x0013180f, 0x00121810, 0x00121911, 0x00101810, 0x00101810, 0x00141911, 0x00181b12, 0x00191a12, 0x001a1b14, 0x001b1c14, 0x001b1c16, 0x00181b14, 0x001a1d17, 0x00191e17, 0x00161c17, 0x00161c17, 0x00151c15, 0x00151c15, 0x00161b14, 0x00151b14, 0x00141a13, 0x00141912, 0x00131812, 0x00131813, 0x00141813, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x001d200a, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x00393b0d, 0x003c3e0c, 0x0041420d, 0x0044450d, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00685f10, 0x00c39c15, 0x00cca316, 0x00b09014, 0x005e5c11, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x00636012, 0x00958014, 0x00c09d16, 0x00cba417, 0x00caa317, 0x00c6a117, 0x00bb9816, 0x00b49415, 0x00b69515, 0x00c19d17, 0x00c8a218, 0x00cca418, 0x00cba418, 0x00c19c18, 0x00978014, 0x00646213, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5c12, 0x00585912, 0x00887413, 0x00caa116, 0x00caa116, 0x00847012, 0x004f5010, 0x004c4d0f, 0x0048490f, 0x0045470e, 0x0041420e, 0x003e400c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x00292b0a, 0x0026280c, 0x0020230a, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00111812, 0x00111812, 0x00131812, 0x00131812, 0x00131812, 0x00131712, 0x00131812, 0x00131812, 0x00141813, 0x00141813, 0x00141814, 0x00141914, 0x00141a14, 0x00131914, 0x00141914, 0x00161814, 0x00171814, 0x00171711, 0x00151610, 0x0014150f, 0x0014150f, 0x0014140f, 0x0015140f, 0x0015140d, 0x0015140e, 0x0015150c, 0x0015150c, 0x0014140b, 0x0014140b, 0x0017150c, 0x0017150d, 0x0015140b, 0x0014130a, 0x0014120a, 0x00141109, 0x00141109, 0x0014130a, 0x0014130a, 0x00131209, 0x00101208, 0x00101108, 0x00101108, 0x00101008, 0x00101008, 0x00111008, 0x00121008, 0x00141109, 0x00110e07, 0x00101009, 0x00101009, 0x000f1008, 0x00101008, 0x00101008, 0x00101109, 0x0014100a, 0x0015100b, 0x0015100b, 0x0016100c, 0x0014120c, 0x0014120c, 0x0015120c, 0x0015120d, 0x0016120c, 0x001c1009, 0x001c1107, 0x001d1206, 0x001f1408, 0x00201408, 0x0020160b, 0x0023160b, 0x0024180b, 0x0026180a, 0x0027180a, 0x0029190b, 0x002b1b0c, 0x002c1c0c, 0x002c1c0f, 0x002d1d0e, 0x002e1d0d, 0x002d1e0b, 0x002d1c08, 0x002d1c08, 0x002d1e09, 0x002c1d08, 0x002b1c08, 0x00291a08, 0x00271805, 0x00251804, 0x00241704, 0x00201400, 0x001e1300, 0x001e1300, 0x001c1406, 0x001b1508, 0x00181507, 0x00161506, 0x00141505, 0x00151404, 0x00171304, 0x001c1404, 0x00201607, 0x00211708, 0x00211708, 0x00201605, 0x00201706, 0x00241908, 0x00281b0b, 0x00281a09, 0x002a1c08, 0x00281c06, 0x00281d05, 0x002c1f05, 0x00302008, 0x00332307, 0x00382506, 0x003b2704, 0x00402a04, 0x00442d06, 0x00482f08, 0x0050350c, 0x00583b0b, 0x0062420c, 0x00795510, 0x00b4902c, 0x00ccb228, 0x00ccb717, 0x00ccb610, 0x00ccb70c, 0x00c9b908, 0x00cab810, 0x00ae910d, 0x00725100, 0x00563a00, 0x00452d00, 0x00382802, 0x002d1e00, 0x00342509, 0x00362a10, 0x0030250c, 0x0029210a, 0x00211c09, 0x001e1909, 0x00181709, 0x00101207, 0x000e1105, 0x000e1208, 0x000f1308, 0x000e1007, 0x000b0e04, 0x000a0d03, 0x000a0d03, 0x000b0c02, 0x000b0c02, 0x000c0d04, 0x000e0f05, 0x00140f08, 0x00140e08, 0x00140e08, 0x00161009, 0x00181109, 0x00181006, 0x00171006, 0x00181006, 0x00181107, 0x001a1108, 0x001a1108, 0x00191007, 0x001a1007, 0x001b1007, 0x001b1007, 0x001c1108, 0x001b1108, 0x001b1108, 0x001b1108, 0x001a1108, 0x00191007, 0x00181107, 0x00181105, 0x00191306, 0x00191306, 0x00181108, 0x00181009, 0x00161008, 0x00151008, 0x00141008, 0x00120e07, 0x00110e06, 0x00100d05, 0x000f0d05, 0x000f0d05, 0x00100f05, 0x00101005, 0x00121108, 0x00131108, 0x00161108, 0x0019120c, 0x001a130b, 0x001f1508, 0x00241808, 0x00281a06, 0x00301c05, 0x00362004, 0x00402707, 0x004b2f09, 0x00523309, 0x005b3806, 0x00633c04, 0x00684005, 0x006b3f04, 0x006c4002, 0x00683c00, 0x00613b01, 0x00583502, 0x00543204, 0x004e3108, 0x00482d07, 0x00452c09, 0x0041290a, 0x003c2509, 0x00392209, 0x00382309, 0x00372108, 0x00341f07, 0x00321e05, 0x00301c05, 0x00301c05, 0x002d1c04, 0x002d1b05, 0x002c1b05, 0x002d1c08, 0x002e1d0c, 0x002e1d0d, 0x002e1d0d, 0x002b1d0d, 0x00271b0a, 0x00241807, 0x00231706, 0x00211407, 0x00211504, 0x00201401, 0x00221403, 0x00241504, 0x00281808, 0x002a1807, 0x002e1c08, 0x002e1c06, 0x00311d07, 0x00372008, 0x003c230c, 0x003e250a, 0x0040270b, 0x0042280d, 0x0042280d, 0x0042280f, 0x0042280e, 0x0040280d, 0x0040270b, 0x003d280c, 0x003c270e, 0x0038260f, 0x0033230a, 0x00302006, 0x00301e04, 0x00311c05, 0x002d1c08, 0x00281a08, 0x00271809, 0x0026180a, 0x00241608, 0x00211406, 0x001e1205, 0x001d1206, 0x001b1208, 0x00181309, 0x00161409, 0x0013140a, 0x00121108, 0x0013120a, 0x0013120b, 0x0012110a, 0x0012110a, 0x0012110a, 0x0012110a, 0x0012110a, 0x0012110a, 0x0013100a, 0x0013100a, 0x0013100a, 0x00121009, 0x00111009, 0x00101009, 0x00101009, 0x00111009, 0x00121009, 0x00131008, 0x00121008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00141109, 0x00161008, 0x00151108, 0x00151208, 0x00141308, 0x0016130b, 0x0016140b, 0x0016150c, 0x0016160d, 0x0017160f, 0x00181710, 0x0017160f, 0x0016160f, 0x00181710, 0x001c1910, 0x001c1910, 0x001a1811, 0x001a1710, 0x00191811, 0x001a1913, 0x001c1d18, 0x001b1e18, 0x00181d16, 0x00171d16, 0x00161c15, 0x00161c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00141b14, 0x00131a14, 0x00121a14, 0x00131b14, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x00515110, 0x00947c13, 0x00caa216, 0x00caa216, 0x00917c13, 0x00585912, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5d11, 0x006b6412, 0x00957f14, 0x00b59516, 0x00c7a117, 0x00cba418, 0x00cca418, 0x00cba418, 0x00cba418, 0x00c39e18, 0x00b19316, 0x00947f15, 0x006b6513, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5c12, 0x005b5b12, 0x00666011, 0x00bc9815, 0x00cca316, 0x00b08f14, 0x00565410, 0x004d4e10, 0x00494a0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0024250b, 0x00202309, 0x001d2008, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x00060c07, 0x00131914, 0x00131914, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00141a14, 0x00141a14, 0x00131914, 0x00141914, 0x00171813, 0x00171812, 0x00161510, 0x0014130d, 0x0014130c, 0x0014110b, 0x0014110b, 0x0014110b, 0x0014110b, 0x0014110b, 0x00141109, 0x00141109, 0x00121108, 0x00121108, 0x0014140b, 0x0015140c, 0x0013120a, 0x00101008, 0x00111008, 0x00121009, 0x00121009, 0x00121009, 0x00101009, 0x00101008, 0x00101108, 0x000f1007, 0x000f1007, 0x00101009, 0x00101009, 0x00100f08, 0x000f0e07, 0x0012110a, 0x000f1008, 0x000d1008, 0x000d1008, 0x000f1008, 0x00101008, 0x00121008, 0x00131008, 0x00141109, 0x0017100b, 0x00171009, 0x00181009, 0x0018110a, 0x0018110a, 0x0018130a, 0x0019140a, 0x001a130a, 0x001f1308, 0x001f1307, 0x00241808, 0x0028190a, 0x0028190a, 0x0029190b, 0x002a1a0c, 0x002c1b0b, 0x002c1b0b, 0x002d1c0c, 0x002e1d0b, 0x00301e0c, 0x00301f0d, 0x00301f0d, 0x0031200e, 0x0032200e, 0x00311f0a, 0x00301d06, 0x002f1c05, 0x002f1e08, 0x002d1d07, 0x002c1c06, 0x002b1a06, 0x00281805, 0x00281806, 0x00281808, 0x00241705, 0x00241506, 0x00221405, 0x00201404, 0x001f1506, 0x001d1606, 0x001d1807, 0x001c1805, 0x001f1906, 0x00231b08, 0x00271b08, 0x002b1c09, 0x002c1d0a, 0x002c1d0a, 0x002c1c08, 0x002c1c08, 0x002c1c08, 0x002c1c08, 0x002d1b06, 0x00301d04, 0x00302006, 0x00302104, 0x00342205, 0x00362508, 0x003b2a0d, 0x003e2d0d, 0x0041300c, 0x0046330c, 0x0048340d, 0x004a3610, 0x00503910, 0x00563c0c, 0x0061410e, 0x00784e10, 0x00a3791f, 0x00c8a126, 0x00c9a714, 0x00ccaa11, 0x00cbac0d, 0x00cbaf10, 0x00ccb018, 0x00ad8c14, 0x00704e00, 0x00553701, 0x00422800, 0x00362402, 0x002a1b00, 0x00312307, 0x0033270d, 0x002f240c, 0x0028200a, 0x00201b08, 0x001d1909, 0x00171608, 0x00121207, 0x00101106, 0x00101106, 0x00101106, 0x00101108, 0x000d0f05, 0x000e0f05, 0x000f0f06, 0x000f0d04, 0x000f0d04, 0x000e0d04, 0x00100f05, 0x00121008, 0x00140f08, 0x00120e06, 0x00140f08, 0x00141008, 0x00141007, 0x00141008, 0x00151108, 0x00151108, 0x00151108, 0x00151108, 0x00141007, 0x00141007, 0x00151007, 0x00151007, 0x00171008, 0x00171008, 0x00161008, 0x00151109, 0x00151009, 0x00141008, 0x00171108, 0x00181108, 0x00181209, 0x00181309, 0x00171109, 0x00171009, 0x00151008, 0x00141008, 0x00140f08, 0x00140f08, 0x00140f08, 0x00121008, 0x00121008, 0x00140f08, 0x00131008, 0x00131006, 0x00131107, 0x00151208, 0x00181108, 0x001c140c, 0x001c130c, 0x001e1508, 0x00241804, 0x002c1b05, 0x00352008, 0x0040280b, 0x004c310e, 0x004e3008, 0x00543407, 0x00593605, 0x005c3804, 0x005e3905, 0x005f3804, 0x00603804, 0x00603804, 0x005e3804, 0x00583504, 0x00543204, 0x00523206, 0x004d2e04, 0x00482c05, 0x00462d08, 0x00422a0c, 0x003f280b, 0x003f280c, 0x003d260c, 0x003c240b, 0x003a2309, 0x00392108, 0x00382108, 0x00372007, 0x00372007, 0x00342005, 0x00341f05, 0x00341e08, 0x00341d0a, 0x00341f0b, 0x00341f0a, 0x0032200a, 0x0030200b, 0x002f200c, 0x002d1c08, 0x002d1c07, 0x002c1b05, 0x002c1c06, 0x002c1904, 0x002f1c06, 0x002d1b04, 0x00301c04, 0x00331f05, 0x00372106, 0x00382306, 0x003b2408, 0x003d2707, 0x00402808, 0x00412b0a, 0x00412b0a, 0x00422c0c, 0x00432c0d, 0x00452c0c, 0x00462a0b, 0x0045290c, 0x0044290e, 0x0040290f, 0x00402b10, 0x003e290d, 0x003b250a, 0x00382409, 0x0033210a, 0x002e1d09, 0x002c1b0a, 0x002c190b, 0x00291809, 0x00261607, 0x00211404, 0x001f1304, 0x001d1306, 0x001a1208, 0x00191408, 0x0018140a, 0x00141308, 0x00141109, 0x00141109, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x00121009, 0x00121009, 0x00111009, 0x00101009, 0x00101009, 0x00101009, 0x00111009, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00140f08, 0x00140f08, 0x00131008, 0x00121108, 0x00141109, 0x00141109, 0x00141109, 0x0014120a, 0x0016110b, 0x0017120c, 0x0018130d, 0x001a140f, 0x001b140f, 0x001c140e, 0x001d150f, 0x001b1410, 0x0017100b, 0x0014130c, 0x00191812, 0x001b1c17, 0x001b1d17, 0x00181d16, 0x00181e17, 0x00171d16, 0x00171d16, 0x00151c16, 0x00151c15, 0x00151c15, 0x00151c15, 0x00131b14, 0x00121a14, 0x00131b14, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x0048490f, 0x004b4c0f, 0x004d4e10, 0x00595510, 0x00b79414, 0x00cca316, 0x00c39c15, 0x00786b12, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005c5d11, 0x00636011, 0x00706713, 0x00847413, 0x008d7a14, 0x00887714, 0x00786e13, 0x006c6514, 0x00626013, 0x005d5e13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5c11, 0x005b5b12, 0x005b5a11, 0x00a48714, 0x00cca316, 0x00c49d15, 0x00706410, 0x004f5010, 0x004b4c0f, 0x0048490f, 0x0045470e, 0x0041420e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0020230a, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00151a14, 0x00191c16, 0x00181712, 0x0013110b, 0x00110f08, 0x00141209, 0x00131008, 0x00151109, 0x00151109, 0x00151009, 0x00140f08, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00111008, 0x00101007, 0x00101008, 0x00110f08, 0x00110f08, 0x00121009, 0x00101009, 0x00101008, 0x00101108, 0x00101108, 0x00101108, 0x00101008, 0x00101008, 0x00100f08, 0x0012110a, 0x00121009, 0x00101009, 0x0010120a, 0x000f120a, 0x00131109, 0x00151109, 0x0018110a, 0x0018110a, 0x0018120a, 0x0018130a, 0x001b130a, 0x001c1309, 0x001e140b, 0x001e140b, 0x001f150b, 0x0023180d, 0x00241a0e, 0x00291c10, 0x002a1c0d, 0x002b1c0b, 0x002c1c08, 0x002d1c08, 0x002d1c08, 0x00301c0a, 0x00301c0a, 0x002f1c08, 0x00301c0a, 0x00301d09, 0x00301e09, 0x00301e09, 0x00301e09, 0x00301e07, 0x00301f07, 0x00321e06, 0x00321e04, 0x00321e04, 0x00322005, 0x00301f04, 0x00301e03, 0x002f1d02, 0x002f1e05, 0x002e1e06, 0x002e1e07, 0x002d1e08, 0x002c1d08, 0x002b1c08, 0x002a1b08, 0x00291c08, 0x00271c08, 0x00281e09, 0x002a210b, 0x002c210c, 0x002d2009, 0x002f1f09, 0x00301e08, 0x00342009, 0x0035210b, 0x0036230a, 0x0036220c, 0x0038240d, 0x0038230c, 0x0039230b, 0x003c2509, 0x003c2809, 0x003c2808, 0x003c2808, 0x00402a0c, 0x00422c0f, 0x00452f11, 0x00493110, 0x004a330f, 0x004d3610, 0x0050390f, 0x00543c0e, 0x0059400c, 0x0065440d, 0x00754809, 0x00885706, 0x00a06d07, 0x00a87803, 0x00af7c02, 0x00b18304, 0x00b28809, 0x00b38914, 0x00946e0e, 0x00664000, 0x00543404, 0x00422800, 0x003a2806, 0x002d1e01, 0x00302206, 0x002d2008, 0x002b2007, 0x00241c07, 0x001e1907, 0x001c1809, 0x00181509, 0x0015150b, 0x00141408, 0x00141409, 0x00141409, 0x0014130a, 0x0014130a, 0x00131209, 0x00131209, 0x00141109, 0x00141109, 0x0014130a, 0x00141109, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00111008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00101007, 0x00101007, 0x000f0f05, 0x000f0f05, 0x00100e05, 0x00110f07, 0x00121008, 0x00111008, 0x00101009, 0x00101009, 0x00101009, 0x00101009, 0x00140f08, 0x00140e08, 0x00151008, 0x00151008, 0x00151008, 0x00151008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00141109, 0x00151109, 0x00181108, 0x00181309, 0x00171408, 0x001a160b, 0x001a160a, 0x001e150a, 0x0020170c, 0x00241910, 0x00281d0c, 0x002a1d07, 0x002e1c04, 0x00412b10, 0x005b3d19, 0x00654519, 0x006a4816, 0x006c4711, 0x006f450e, 0x00724510, 0x00714610, 0x006c4410, 0x0068420d, 0x0064400b, 0x00603c08, 0x005c3704, 0x005b3704, 0x00583504, 0x00543204, 0x004f3004, 0x004c3007, 0x004b3008, 0x00472e07, 0x00462d08, 0x00462d08, 0x00462c09, 0x00432b0b, 0x00432b0b, 0x00452b0c, 0x00452b0c, 0x00462a0c, 0x00442809, 0x00422609, 0x0041250b, 0x0041240d, 0x0041250c, 0x003e240a, 0x003a2208, 0x00392409, 0x00382409, 0x00392308, 0x003a2308, 0x003a2308, 0x003b2409, 0x003c240a, 0x003d240c, 0x003c250b, 0x003c2609, 0x003f2708, 0x003f2707, 0x00412805, 0x00452c07, 0x004b3008, 0x0050340b, 0x0053360c, 0x0054360d, 0x0054360d, 0x0053350c, 0x00513109, 0x00513008, 0x004d2d06, 0x004c2d09, 0x00492d0c, 0x0045290d, 0x0043280d, 0x0041290d, 0x003d280b, 0x003a270c, 0x0038240e, 0x0034200d, 0x00301c0d, 0x002f1c0b, 0x002e1b09, 0x002a1908, 0x00251808, 0x0024180a, 0x0021160b, 0x001b1206, 0x00191208, 0x00181308, 0x00171209, 0x00161208, 0x0016120a, 0x0016120a, 0x00161209, 0x00151009, 0x00141008, 0x00141008, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0012110a, 0x0012110a, 0x0011110a, 0x00101009, 0x00111009, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00140f09, 0x00121009, 0x00101009, 0x00101009, 0x00101008, 0x00121008, 0x00141008, 0x00151109, 0x00161009, 0x0018110a, 0x0018110a, 0x001a120c, 0x001c140d, 0x001c130d, 0x001c120c, 0x0018100b, 0x00130c07, 0x0014120c, 0x001b1b14, 0x00191b14, 0x001b1e18, 0x001a2018, 0x00181f17, 0x00171d16, 0x00171d16, 0x00181e18, 0x00171d18, 0x00161c17, 0x00161c17, 0x00141c15, 0x00141c15, 0x00141c15, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x00141810, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a0f, 0x004c4d0f, 0x004f5010, 0x00726511, 0x00c39c15, 0x00cca316, 0x00b99615, 0x006a6312, 0x00595a12, 0x005b5b12, 0x005b5b11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x005c5c12, 0x005b5b12, 0x00585811, 0x008f7913, 0x00c9a116, 0x00c9a116, 0x00907812, 0x00505010, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0034350c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x000f130b, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00151a13, 0x00151a13, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00161a13, 0x00191b14, 0x0013120b, 0x000f0e07, 0x00100e05, 0x00100e05, 0x00131008, 0x00151109, 0x00151109, 0x00151009, 0x00140f08, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00110f07, 0x00100e05, 0x00100f05, 0x000f0f05, 0x00100f07, 0x00110f08, 0x00121009, 0x00121009, 0x00101009, 0x00101008, 0x00101108, 0x00101108, 0x00101008, 0x00101006, 0x00111006, 0x00131008, 0x00110f07, 0x00140d07, 0x00140f08, 0x0015120a, 0x0015130c, 0x0018120b, 0x001a120c, 0x001c130d, 0x001c130c, 0x001d140c, 0x001e140b, 0x0020160b, 0x0024180e, 0x0024190e, 0x00241a0d, 0x00251b0e, 0x00281a0c, 0x00291b0d, 0x00291b0d, 0x002a1b0c, 0x002b1909, 0x002c1906, 0x002c1a05, 0x002e1c06, 0x00301c06, 0x00321c06, 0x00301c05, 0x00311c06, 0x00331d08, 0x00352008, 0x00372108, 0x00382308, 0x00392408, 0x003a2608, 0x003b2608, 0x003b2608, 0x003c2708, 0x003c2809, 0x003c2807, 0x003b2706, 0x003a2605, 0x00382604, 0x00392605, 0x00382807, 0x00382709, 0x0036270a, 0x0035250b, 0x0035240a, 0x0036240c, 0x0032220a, 0x0032240c, 0x0033240c, 0x00322309, 0x00342209, 0x00352208, 0x00372108, 0x00392208, 0x003a2308, 0x003c2509, 0x003d280c, 0x003f280e, 0x00412910, 0x00432a0f, 0x00442c0d, 0x00452f0c, 0x00452f0b, 0x00462f0a, 0x004a300c, 0x004c330d, 0x0051350c, 0x0054380c, 0x0058390b, 0x005a3c0c, 0x005c3f0c, 0x0062430c, 0x0068480c, 0x00744f0f, 0x0082530c, 0x008a5504, 0x00975f04, 0x009a6401, 0x009d6201, 0x00945c00, 0x008d5800, 0x00865400, 0x00724800, 0x00603c08, 0x00503104, 0x00442c04, 0x003d2b0b, 0x00312005, 0x002f2006, 0x002b1d06, 0x002a1e08, 0x00241c08, 0x001f1808, 0x001d1809, 0x001a1609, 0x0018140b, 0x00171309, 0x0019160c, 0x0019150c, 0x0016120a, 0x0016120a, 0x00151109, 0x00151109, 0x00141008, 0x00141008, 0x00151109, 0x00141008, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00111008, 0x00101008, 0x00101008, 0x00101008, 0x00101108, 0x000f1008, 0x000f1008, 0x000c1007, 0x000d0f05, 0x000d0f05, 0x000f1007, 0x00101008, 0x00101108, 0x00101009, 0x00101009, 0x00101009, 0x00101009, 0x00110f08, 0x00120e08, 0x00140f09, 0x00140f09, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00131008, 0x00131008, 0x00141008, 0x00151109, 0x00161108, 0x00181309, 0x0019140b, 0x00191408, 0x001c150a, 0x001e1708, 0x00211608, 0x00241809, 0x00271b0d, 0x00291d0b, 0x002e1e07, 0x00342006, 0x00543b1c, 0x006d491e, 0x00724813, 0x00805418, 0x00845613, 0x0088550f, 0x008e5712, 0x008e5816, 0x008b5818, 0x00835518, 0x007a5314, 0x00765012, 0x00754c10, 0x006e450b, 0x00684008, 0x00623d08, 0x005a3805, 0x00583908, 0x00593908, 0x00573807, 0x00543504, 0x00543606, 0x0051350b, 0x004f340c, 0x004c310b, 0x004c300a, 0x004c300a, 0x004c300a, 0x004a2d08, 0x00482b0a, 0x0047290a, 0x0044270a, 0x0045280c, 0x0044280c, 0x0042280b, 0x0042280c, 0x0041280b, 0x00402609, 0x00412709, 0x00412709, 0x0043280c, 0x00452a0d, 0x00482c10, 0x004a2e0e, 0x004c2f0e, 0x0050310e, 0x00553511, 0x005e3c13, 0x00664312, 0x006c4715, 0x00744c18, 0x00784e1a, 0x00784e18, 0x00784e1a, 0x00784c18, 0x00744914, 0x006f4610, 0x006a430f, 0x00613d0d, 0x00553407, 0x004b2907, 0x00452705, 0x00402606, 0x003c2507, 0x00382306, 0x00372209, 0x0038230f, 0x0034200d, 0x00331f0a, 0x0033200b, 0x002e1d0b, 0x002a1b0a, 0x00291b0c, 0x0027190d, 0x00211509, 0x00201609, 0x0020170b, 0x001c140c, 0x001b130b, 0x001b130b, 0x001b130b, 0x0019130a, 0x00181209, 0x00151008, 0x00151008, 0x00141008, 0x00141008, 0x0014100a, 0x0013100a, 0x0013100a, 0x00101009, 0x00111109, 0x00101009, 0x00121009, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00131008, 0x00121009, 0x00101009, 0x00100f08, 0x00100f08, 0x00101008, 0x00101008, 0x00141008, 0x00151009, 0x00151108, 0x00161208, 0x0016130a, 0x0017120a, 0x0018130b, 0x0018120b, 0x0017120b, 0x00120d07, 0x000e0904, 0x00100f08, 0x00161810, 0x00191c15, 0x001b1f18, 0x00192018, 0x00181f17, 0x00181f17, 0x00181f17, 0x00181f18, 0x00171d18, 0x00161c17, 0x00161c17, 0x00151c16, 0x00151c15, 0x00151c15, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180c, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0041420d, 0x0044450e, 0x0048490f, 0x004b4c10, 0x004d4e0f, 0x004f4f10, 0x008b7512, 0x00c8a015, 0x00cca316, 0x00b39115, 0x00656011, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005d5e12, 0x005e5f13, 0x005d5e12, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5c12, 0x005b5b12, 0x00585811, 0x00867413, 0x00c59f15, 0x00cba216, 0x00a48614, 0x00535210, 0x004d4e0f, 0x004b4c10, 0x0048490f, 0x0044450e, 0x0041420e, 0x003e400c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a13, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00181a14, 0x00191a14, 0x0011120c, 0x000e0f07, 0x000c1007, 0x000c0f06, 0x000e1006, 0x00141109, 0x00151109, 0x00141008, 0x00141008, 0x00121006, 0x00121006, 0x00121006, 0x00121006, 0x00111007, 0x00110f06, 0x00110f07, 0x00130f08, 0x00121008, 0x00131008, 0x00131008, 0x00141209, 0x00121008, 0x00131107, 0x00131107, 0x00131208, 0x00131207, 0x00151307, 0x00141005, 0x00161006, 0x00191007, 0x00191007, 0x001a1108, 0x001e150c, 0x0020160f, 0x001e140d, 0x0021150e, 0x00231710, 0x00241610, 0x0024180e, 0x0025190d, 0x00261a0d, 0x0023160a, 0x0021180a, 0x00201708, 0x001f1607, 0x00211507, 0x00221608, 0x00211405, 0x00241405, 0x00271604, 0x002b1907, 0x00291a06, 0x002c1d08, 0x00301d08, 0x00342006, 0x00372206, 0x003b2609, 0x003e260c, 0x0043280e, 0x00462b0c, 0x00462c0a, 0x0048310a, 0x004a3308, 0x004b3308, 0x004b3308, 0x004c340a, 0x004c340c, 0x004c340b, 0x004d340b, 0x004d340c, 0x004e340c, 0x004b310b, 0x0049320d, 0x0044300c, 0x0041300c, 0x0040300c, 0x00402d0c, 0x0040290c, 0x003e270c, 0x003e260d, 0x003d240c, 0x003d250b, 0x003f250c, 0x0040250a, 0x00402609, 0x003f2708, 0x003f2708, 0x00422a09, 0x00442c0b, 0x00442c0c, 0x00482e11, 0x00452b0c, 0x004a300c, 0x004f340d, 0x004f350c, 0x0051370b, 0x00573b0c, 0x005c3c0c, 0x005e3b07, 0x00654009, 0x006c440a, 0x006e450a, 0x0074490c, 0x00794f0c, 0x007e540c, 0x008b5f11, 0x009b6912, 0x00a57416, 0x00af8017, 0x00bc8c1f, 0x00c08823, 0x00996109, 0x00824e04, 0x00784e04, 0x00633e00, 0x00553709, 0x00483205, 0x00403008, 0x003b2808, 0x00342207, 0x002e1e08, 0x00281b09, 0x0026190a, 0x00221809, 0x001f170a, 0x001d170a, 0x001a1509, 0x00191408, 0x00181309, 0x0018110a, 0x0018110a, 0x0018110a, 0x0018110a, 0x0017100b, 0x0017100b, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x0014100a, 0x0013100a, 0x00121009, 0x00121009, 0x00110f08, 0x00110e0a, 0x00110e0a, 0x00110e0a, 0x00110e0a, 0x00110d0a, 0x00100e0a, 0x000d0d08, 0x000c0d08, 0x000e0d06, 0x000f0e07, 0x00110f08, 0x00110f08, 0x00110f08, 0x00100f08, 0x00140f09, 0x00140f09, 0x00120f0b, 0x00120f0b, 0x0013100c, 0x0013100a, 0x00121109, 0x00121108, 0x00121108, 0x0013120a, 0x0014120b, 0x0014110b, 0x0014110a, 0x00141208, 0x00161208, 0x00181308, 0x00181308, 0x00191207, 0x001c1608, 0x00201608, 0x00221606, 0x00251706, 0x00291a08, 0x002c1d0c, 0x00311f0a, 0x003d2407, 0x00604016, 0x00744c17, 0x00845617, 0x00a77829, 0x00b38224, 0x00af7d1b, 0x00ac7716, 0x00a87314, 0x00a16c10, 0x009f6810, 0x0099630f, 0x00945d0d, 0x00905a11, 0x0088530c, 0x0085540c, 0x007c4e08, 0x00754908, 0x00714608, 0x006f440a, 0x006c410a, 0x0067400a, 0x0065400c, 0x00613f0d, 0x005b390a, 0x0058360a, 0x0058360c, 0x0057350a, 0x00543307, 0x00513306, 0x00503208, 0x00503208, 0x004b3108, 0x004a310b, 0x00462f0b, 0x00442c0a, 0x00472c0b, 0x00482c0c, 0x00492c0c, 0x00492d0f, 0x00492e10, 0x00492f0e, 0x004d300e, 0x00523410, 0x0054370c, 0x005b3d0c, 0x00694814, 0x006e4a14, 0x00785013, 0x00835412, 0x008a5915, 0x00935f19, 0x0099651b, 0x00986616, 0x00946413, 0x00936212, 0x00905f0f, 0x008e5a0c, 0x0088560e, 0x00815211, 0x00794c12, 0x006e400f, 0x005d3608, 0x004c2c05, 0x00402804, 0x003c2404, 0x00382208, 0x00341e08, 0x00301c05, 0x00301c04, 0x002e1c04, 0x002c1c07, 0x002b1c08, 0x002b1c0c, 0x00291c0e, 0x0025180c, 0x0024180e, 0x0024180e, 0x0022180e, 0x0021150c, 0x0021150c, 0x0020140c, 0x001e140b, 0x001c1409, 0x001b1309, 0x001a1208, 0x00181108, 0x00181108, 0x00181209, 0x00171009, 0x00141008, 0x00141008, 0x00140f08, 0x0014100a, 0x0014100a, 0x00140f09, 0x00140f09, 0x0014100a, 0x00141008, 0x00140f08, 0x00141006, 0x00141007, 0x00141007, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00130f09, 0x00140f09, 0x0014100b, 0x0015110a, 0x0017130a, 0x00171309, 0x0017140a, 0x0018140c, 0x0018140c, 0x00140f08, 0x000f0c04, 0x000c0c04, 0x000b0c04, 0x000c0e06, 0x0013150d, 0x00171c15, 0x00182017, 0x00192018, 0x00182018, 0x00192018, 0x00181f17, 0x00181f15, 0x00181f15, 0x00181f15, 0x00181f15, 0x00181e15, 0x00191e15, 0x00191e15, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x004d4e10, 0x00515110, 0x00967d12, 0x00c9a116, 0x00cca316, 0x00b29115, 0x006a6211, 0x00585912, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5c11, 0x005c5c12, 0x00595a12, 0x00585911, 0x00887513, 0x00c49e16, 0x00cca316, 0x00ac8b14, 0x00595510, 0x004d4e10, 0x004c4d0f, 0x0048490f, 0x0045470e, 0x0043440e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002d2f0b, 0x00292b0b, 0x0026280c, 0x0020230a, 0x00202308, 0x00191c08, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00151a11, 0x00151a11, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a13, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00181a14, 0x00191a14, 0x0011120c, 0x000d0f07, 0x000c1007, 0x000c0f06, 0x000c0f06, 0x0011110a, 0x0014110b, 0x00131008, 0x00121008, 0x00121008, 0x00121008, 0x00141006, 0x00141006, 0x00120f05, 0x00120f05, 0x00141006, 0x00161008, 0x00161007, 0x00151007, 0x00151007, 0x00151007, 0x00140f04, 0x00151005, 0x00151005, 0x00181206, 0x00181306, 0x00191408, 0x001e170b, 0x0021160a, 0x0022170b, 0x0020180b, 0x0020190c, 0x00221b0f, 0x0020190d, 0x0020190d, 0x0020180c, 0x001d150b, 0x001d140a, 0x001e1509, 0x001d1408, 0x001c1204, 0x001b1104, 0x001a1104, 0x00181202, 0x001a1203, 0x001c1203, 0x001e1204, 0x00231404, 0x00271804, 0x002b1906, 0x002f1c07, 0x00302008, 0x00332408, 0x003b280c, 0x003f2b0c, 0x00442f0c, 0x004a320e, 0x004e330f, 0x00533510, 0x00593810, 0x005c3c11, 0x00603f13, 0x00604010, 0x0061420d, 0x0061430b, 0x0062430b, 0x0060420a, 0x0060420b, 0x0061400c, 0x00613f0d, 0x005f3c0d, 0x005a390c, 0x0056370d, 0x0050340d, 0x004c340e, 0x004c340f, 0x004a330e, 0x0048300c, 0x00462c0c, 0x00452c0f, 0x00442a0e, 0x00442a0c, 0x00442a0c, 0x00442a0c, 0x00452c0b, 0x00452c09, 0x00452c08, 0x00482e0a, 0x004b300c, 0x004a300b, 0x004f330d, 0x0054340e, 0x00573810, 0x00593b13, 0x005a3c11, 0x00603f13, 0x00654212, 0x00704711, 0x0072470b, 0x007b4f0d, 0x0081540e, 0x0087590d, 0x00926414, 0x009c6f19, 0x00a6791f, 0x00b58c26, 0x00c39b25, 0x00c8a227, 0x00caa421, 0x00ccaa23, 0x00caa120, 0x009e7007, 0x007c4d00, 0x006c4600, 0x005f3f02, 0x00503407, 0x00443004, 0x003e2c07, 0x00372406, 0x00332108, 0x002e1c08, 0x00291b09, 0x00241809, 0x00211609, 0x001d1508, 0x001b1508, 0x001a1508, 0x00191409, 0x00181309, 0x0018110a, 0x0018110a, 0x0018110a, 0x0018110a, 0x0017100b, 0x0017100b, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x0014100a, 0x0013100a, 0x00121009, 0x00121009, 0x00110e0b, 0x00110e0c, 0x00110e0c, 0x00110e0c, 0x00110e0b, 0x00120d0a, 0x00110e0a, 0x000e0d08, 0x000c0d08, 0x000e0d06, 0x000f0e07, 0x00110f08, 0x00110f08, 0x00110f08, 0x00110f08, 0x00140f09, 0x00140f09, 0x00120f0b, 0x00120f0b, 0x0013100a, 0x00131009, 0x00121108, 0x00121108, 0x00121108, 0x0013120a, 0x0013110b, 0x0013100a, 0x00141109, 0x00141208, 0x00161307, 0x00181308, 0x00181308, 0x00191206, 0x001d1608, 0x00211609, 0x00241708, 0x00281808, 0x002c1c09, 0x002d1c0c, 0x0034200b, 0x00412709, 0x00644418, 0x00774f13, 0x008c6214, 0x00b8902d, 0x00cba32c, 0x00caa422, 0x00c99f1c, 0x00c89b1c, 0x00c5971b, 0x00c3921b, 0x00bd8c19, 0x00b88418, 0x00b07b16, 0x00a87312, 0x009d6a0b, 0x00976408, 0x00925f0a, 0x008e5c0c, 0x008b5a10, 0x00885710, 0x00855411, 0x00835414, 0x00805416, 0x007b5014, 0x00744b12, 0x00744912, 0x00714711, 0x006b430c, 0x00664008, 0x00603a04, 0x005b3803, 0x00543401, 0x00543604, 0x00523507, 0x00503308, 0x0050300b, 0x0051300c, 0x0052300d, 0x00502f0c, 0x0051320d, 0x0052330c, 0x005a3810, 0x005f3c10, 0x0068430c, 0x00734c0c, 0x00805911, 0x008c6416, 0x009c7118, 0x00aa7e1b, 0x00b48721, 0x00bb8d25, 0x00c29528, 0x00c19927, 0x00bd9724, 0x00bd9724, 0x00bc9423, 0x00b8841b, 0x00ad7a16, 0x009e6a10, 0x00915f0d, 0x0086560d, 0x00784d0d, 0x00674109, 0x00583707, 0x004b2c07, 0x00422509, 0x003a200a, 0x00301c05, 0x002c1a01, 0x002a1901, 0x00281804, 0x00261804, 0x00241706, 0x00231708, 0x0021180b, 0x0020180c, 0x0020180e, 0x0020180e, 0x00221a10, 0x00221a10, 0x0021180e, 0x0020160c, 0x0020150c, 0x0021180f, 0x0020170d, 0x001f150c, 0x001f150c, 0x001f160c, 0x001d140b, 0x001a1308, 0x001a1208, 0x00181208, 0x00181209, 0x00181209, 0x00181008, 0x00150f07, 0x00151008, 0x00161008, 0x00171008, 0x00171008, 0x00161007, 0x00151007, 0x00131008, 0x00121008, 0x00121008, 0x00121008, 0x00140f08, 0x00140f08, 0x0016120a, 0x0017130a, 0x00161208, 0x00181408, 0x001a160c, 0x00161209, 0x00120e06, 0x000f0d04, 0x000c0c03, 0x000b0c04, 0x00090c04, 0x000b0e05, 0x000e1109, 0x00171d16, 0x00182018, 0x00181e17, 0x001a2018, 0x001a2119, 0x00181f17, 0x00181f15, 0x00181f15, 0x00181f15, 0x00181f15, 0x00181e15, 0x00191e15, 0x00191e15, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0b, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003c3e0d, 0x0040400d, 0x0043440e, 0x0045470e, 0x00494a10, 0x004c4d0f, 0x004d4e10, 0x00525110, 0x00987e12, 0x00c8a016, 0x00cca316, 0x00b99615, 0x00786b12, 0x00585810, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5c11, 0x005c5d12, 0x005c5c12, 0x005b5b12, 0x00585912, 0x005e5c11, 0x00988013, 0x00c7a015, 0x00cba216, 0x00ac8b14, 0x005c5810, 0x004d4e10, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0043440e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x0024250c, 0x00202308, 0x001d2008, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00181b12, 0x00181b12, 0x00181a14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161b14, 0x00171c14, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00161711, 0x0011130b, 0x000f1008, 0x000d1008, 0x000b0e05, 0x000a0e05, 0x000d0e06, 0x00101009, 0x00141109, 0x00131107, 0x00131008, 0x00131008, 0x00131107, 0x00151308, 0x00181308, 0x00181208, 0x00191208, 0x001a1208, 0x001a1208, 0x001a1208, 0x001b1208, 0x001d140a, 0x001d140a, 0x001e1409, 0x001f1509, 0x001f170b, 0x0020190d, 0x00201a0c, 0x00201a0d, 0x0022180c, 0x00201509, 0x001c1508, 0x001c1608, 0x00191507, 0x00181406, 0x00171305, 0x00161104, 0x00141104, 0x00141104, 0x00151003, 0x00171002, 0x00181003, 0x001c1507, 0x00191404, 0x001b1605, 0x00201708, 0x0023180a, 0x00241808, 0x002a1c09, 0x00301e0a, 0x0034200a, 0x00382309, 0x003d280b, 0x00452f0e, 0x004a320d, 0x0050340f, 0x0057390c, 0x005d3c0c, 0x0064400c, 0x006b440c, 0x0072480d, 0x007a4e11, 0x00805415, 0x00835814, 0x00855a13, 0x00865c0f, 0x00865c0f, 0x00865c0f, 0x0083590c, 0x007f5708, 0x007b5308, 0x0079500a, 0x00714806, 0x006b430c, 0x00623c09, 0x005e3a0c, 0x0058370c, 0x0053360b, 0x004f340a, 0x004c320b, 0x004c320c, 0x004a300d, 0x00482f0d, 0x00482f0c, 0x004b300c, 0x004d330d, 0x004d330c, 0x004e330a, 0x0050340b, 0x0052360a, 0x00563709, 0x005c390c, 0x005f3b0c, 0x00643c0e, 0x00653f10, 0x00694310, 0x0070480e, 0x0078500f, 0x00845613, 0x008c5d13, 0x00986815, 0x00a4761a, 0x00b1851f, 0x00bb9121, 0x00c39b25, 0x00c9a429, 0x00ccaa24, 0x00ccad1b, 0x00ccb018, 0x00ccb215, 0x00ccb313, 0x00caac16, 0x00a17c04, 0x007d5300, 0x006e4803, 0x00593c00, 0x004c3305, 0x00442f04, 0x003d2804, 0x00362204, 0x00311f08, 0x002d1c08, 0x002a1908, 0x0027180b, 0x00211608, 0x001c1408, 0x001b1408, 0x00191407, 0x00181308, 0x00181108, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x0017100b, 0x0017100b, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x0015100b, 0x0015100b, 0x0014100a, 0x0014100a, 0x0014100c, 0x00120f0c, 0x00120f0c, 0x00120f0c, 0x00130f0c, 0x00140f0b, 0x00120f0b, 0x000f0e09, 0x000b0c06, 0x00100f08, 0x00100f08, 0x00121009, 0x00121009, 0x00140f0b, 0x00140f0b, 0x00140f0b, 0x00140f0b, 0x00110e0a, 0x00110f08, 0x00110f08, 0x00131108, 0x00131108, 0x00121108, 0x00111008, 0x00101008, 0x00111009, 0x00131008, 0x00131008, 0x00131107, 0x00171408, 0x00181107, 0x00181107, 0x001a1306, 0x001c1408, 0x00201408, 0x00241708, 0x00281808, 0x002c1c09, 0x002d1e0c, 0x00342009, 0x00422708, 0x00644418, 0x00795010, 0x00926710, 0x00bf9a26, 0x00ccad1f, 0x00ccb316, 0x00ccb011, 0x00ccae13, 0x00ccac14, 0x00ccaa16, 0x00cca819, 0x00cca61b, 0x00cba31e, 0x00c59c1c, 0x00c3991c, 0x00be9319, 0x00bb8c1a, 0x00b38216, 0x00ab7a14, 0x00a47311, 0x009f6c0e, 0x00a06a10, 0x009b6610, 0x0094600e, 0x00915d0f, 0x00905b10, 0x008d5810, 0x0088540e, 0x0083500a, 0x00804f0a, 0x007a4c0a, 0x0072490a, 0x006e470a, 0x00674107, 0x00623d06, 0x0060380c, 0x0060370c, 0x005e350b, 0x005c350a, 0x005c3708, 0x0064400e, 0x006d4512, 0x00744913, 0x0080530d, 0x00916410, 0x00a77d19, 0x00ba9322, 0x00c59f22, 0x00caa620, 0x00cca920, 0x00ccaa1e, 0x00ccac1d, 0x00ccaf1c, 0x00ccb01d, 0x00ccb01c, 0x00ccaf1c, 0x00cca81a, 0x00c9a019, 0x00c69a1d, 0x00b88a15, 0x00a67611, 0x00926309, 0x00885a0e, 0x00784c09, 0x00643c0a, 0x00532e09, 0x0046290a, 0x003b2407, 0x00332004, 0x002c1a02, 0x00281802, 0x00241602, 0x001f1201, 0x001b1102, 0x001a1104, 0x00161004, 0x00141005, 0x00141105, 0x00141206, 0x00171408, 0x0018160a, 0x001b140a, 0x001c140a, 0x001f160c, 0x0020180e, 0x0021180d, 0x0022180c, 0x0021180c, 0x0023180d, 0x0022180c, 0x0021160a, 0x00201509, 0x001e150a, 0x001c1308, 0x001c1308, 0x00191106, 0x00181206, 0x00181206, 0x00181008, 0x00181008, 0x00181107, 0x00171006, 0x00141007, 0x00141007, 0x00141007, 0x00141007, 0x00141008, 0x00141008, 0x0016120a, 0x00171309, 0x00181409, 0x00181408, 0x00171308, 0x00130f05, 0x000f0c04, 0x000d0c05, 0x000c0d05, 0x000b0e05, 0x000b0d07, 0x000b0d07, 0x000c0e08, 0x00161b14, 0x00161d15, 0x00181f17, 0x001a2018, 0x001a2119, 0x00181f17, 0x00171e14, 0x00182016, 0x00182016, 0x00182016, 0x00191f15, 0x00191e15, 0x00191e15, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0040400d, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x004d4e10, 0x00505010, 0x008f7812, 0x00c49e15, 0x00cca316, 0x00c49e16, 0x00947c14, 0x00605c10, 0x00585911, 0x00595a12, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5c11, 0x005c5c11, 0x005b5b12, 0x005b5b12, 0x00595a12, 0x00595911, 0x00756911, 0x00b09015, 0x00cba216, 0x00c9a116, 0x00a48614, 0x00585510, 0x004d4e10, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450e, 0x0041420d, 0x003e400c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0020230a, 0x001d2008, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181b12, 0x00181b12, 0x00181a14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161b14, 0x00161c14, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181b14, 0x00141510, 0x00101009, 0x000f1008, 0x000d1008, 0x000c0e08, 0x000a0d07, 0x000b0c04, 0x00100f08, 0x0017140c, 0x00151309, 0x00151308, 0x00151308, 0x00151308, 0x00181609, 0x001c1509, 0x001d1408, 0x0020150b, 0x0022170c, 0x0022170c, 0x0022170c, 0x0022170c, 0x0024180d, 0x0024180d, 0x0024180f, 0x0024180e, 0x0020140c, 0x001f150c, 0x001a170b, 0x001a170b, 0x00181309, 0x00181108, 0x00140e04, 0x00130f04, 0x00110f03, 0x00121004, 0x00141405, 0x00131304, 0x00141404, 0x00141504, 0x00151504, 0x00191404, 0x00191505, 0x001f1a09, 0x00201a09, 0x00211c09, 0x00241c0a, 0x002b200f, 0x002c200f, 0x0033230e, 0x0034220c, 0x003c280f, 0x00412910, 0x00492d0c, 0x0052340e, 0x005c3a11, 0x00643c11, 0x006b410a, 0x00754a0a, 0x00845811, 0x00906417, 0x009c6f16, 0x00aa7c19, 0x00b78924, 0x00bc9127, 0x00c09428, 0x00c09525, 0x00c09625, 0x00c09725, 0x00bc9421, 0x00b89020, 0x00b68c23, 0x00a67c1b, 0x0094690e, 0x00895f10, 0x007a500a, 0x0070470b, 0x00673f09, 0x005c3c0a, 0x0056390a, 0x0053370a, 0x0052370c, 0x0050350c, 0x004e340c, 0x004e340c, 0x0050340c, 0x0054370c, 0x0054380b, 0x0055380a, 0x005a3c0c, 0x005d3d0c, 0x00623f08, 0x00684009, 0x0070460c, 0x0073490e, 0x00784f0e, 0x00845912, 0x008c610e, 0x00996f13, 0x00a77c18, 0x00b48a1f, 0x00be951f, 0x00c8a220, 0x00ccaa20, 0x00ccac1e, 0x00ccb01c, 0x00ccb318, 0x00ccb314, 0x00ccb410, 0x00ccb50f, 0x00cbb60c, 0x00cbb70d, 0x00cab316, 0x00a38104, 0x007c5400, 0x006d4804, 0x00563900, 0x00493004, 0x00422c04, 0x003c2403, 0x00352005, 0x00301d06, 0x002b1908, 0x00281807, 0x00241608, 0x00201407, 0x001b1306, 0x001a1407, 0x00191407, 0x00181308, 0x00181108, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x0017100b, 0x0017100b, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x0017100b, 0x0017100b, 0x00150f0a, 0x00150f0a, 0x0014100a, 0x00130f0a, 0x00120e09, 0x00130f0a, 0x00130f0a, 0x00140f0b, 0x0012100b, 0x0011100b, 0x000c0d08, 0x0013120b, 0x0012110a, 0x00121009, 0x00121009, 0x00140f0b, 0x00140f0b, 0x00140f0b, 0x00140f0b, 0x00120f08, 0x00110e08, 0x00131007, 0x00131006, 0x00121008, 0x00121008, 0x00121008, 0x00111008, 0x00121008, 0x00131008, 0x00131008, 0x00131107, 0x00161307, 0x00181107, 0x00181107, 0x001a1306, 0x001c1408, 0x00201408, 0x00241608, 0x00291909, 0x002d1c0a, 0x002e1c0a, 0x00362009, 0x00432808, 0x00654518, 0x00805013, 0x00996810, 0x00c29a22, 0x00cbae16, 0x00ccb40c, 0x00cab30a, 0x00c9b20c, 0x00c9b20e, 0x00cab20f, 0x00cab110, 0x00cab114, 0x00cbb018, 0x00c9b01a, 0x00cab019, 0x00cbae1b, 0x00cca91d, 0x00c8a51d, 0x00c9a420, 0x00c79d1d, 0x00c4981b, 0x00c09018, 0x00be8a19, 0x00b98419, 0x00b37c15, 0x00af7714, 0x00aa7115, 0x00a36b15, 0x009c6510, 0x0098600e, 0x00935e0e, 0x00895c10, 0x00865810, 0x00825510, 0x007c5211, 0x00784b17, 0x00774a18, 0x00734615, 0x00704613, 0x006d440e, 0x006f450d, 0x00754a0f, 0x00885a1b, 0x00a07420, 0x00bd922b, 0x00c9a42c, 0x00ccad21, 0x00ccb116, 0x00ccb50f, 0x00cbb60d, 0x00cbb80d, 0x00c9b80d, 0x00cab710, 0x00cbb510, 0x00cbb511, 0x00cab510, 0x00cab40c, 0x00ccb411, 0x00ccb018, 0x00ccac1c, 0x00c89c1f, 0x00b98c1b, 0x00a07110, 0x008b5c09, 0x00805210, 0x0068400b, 0x0054340a, 0x00442c06, 0x003a2505, 0x00332208, 0x002e1f07, 0x00271a04, 0x00241705, 0x001e1404, 0x001c1405, 0x00181104, 0x00141105, 0x00101003, 0x000c0d00, 0x000d0f01, 0x000d0f02, 0x00101003, 0x00101003, 0x00101103, 0x00141407, 0x001c1408, 0x001f1309, 0x00201409, 0x0021170a, 0x0024180b, 0x0026180b, 0x0025190b, 0x0024190b, 0x00211709, 0x00211609, 0x001f1408, 0x001f1409, 0x001f150a, 0x001c1308, 0x001a1106, 0x00191006, 0x00191007, 0x00181106, 0x00181206, 0x00181106, 0x00171107, 0x00161208, 0x00161208, 0x00181309, 0x0018140a, 0x00191409, 0x00181408, 0x00161308, 0x00130f06, 0x000e0d04, 0x000c0d05, 0x000b0e05, 0x000b0e05, 0x000a0d07, 0x000c0e08, 0x000c0f08, 0x00161b14, 0x00151d15, 0x00181f17, 0x00182018, 0x00192018, 0x00181f17, 0x00171e14, 0x00182016, 0x00182016, 0x00182016, 0x00191e15, 0x00191e15, 0x00191e15, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180b, 0x0014180b, 0x00191c09, 0x001d2009, 0x001d2008, 0x0024250b, 0x0026280b, 0x00292b0a, 0x002d2f0b, 0x0030310c, 0x0034350c, 0x0036370c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x004d4e0f, 0x004d4e10, 0x00786911, 0x00bb9614, 0x00cba216, 0x00cba216, 0x00b49215, 0x007d6e12, 0x005c5a10, 0x00585810, 0x00585911, 0x00595a12, 0x00595a12, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x005c5c12, 0x005c5c12, 0x005c5c12, 0x005c5c12, 0x005b5b12, 0x00595a12, 0x00595a12, 0x00585912, 0x005c5b11, 0x00726811, 0x00a48713, 0x00c6a015, 0x00cca316, 0x00c49c15, 0x008f7812, 0x00535210, 0x004d4e10, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450e, 0x0041420e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002d2f0b, 0x002c2d0b, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x0014180e, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c16, 0x00181b17, 0x00191b17, 0x00191916, 0x00141510, 0x0010100b, 0x000f100a, 0x000d100a, 0x000a0f08, 0x000a0e07, 0x000c0c07, 0x000c0d05, 0x00141408, 0x0019170b, 0x0021180f, 0x0023180e, 0x0020180d, 0x001f180b, 0x0024170c, 0x0028160c, 0x0028180c, 0x0029180d, 0x0029180e, 0x0024170d, 0x0020160b, 0x001c170a, 0x00181408, 0x00181209, 0x0018130a, 0x00161108, 0x00120f04, 0x00100f04, 0x00100e04, 0x000f0e03, 0x00111006, 0x00151106, 0x00151005, 0x00141205, 0x00161408, 0x00181708, 0x00191709, 0x00191808, 0x001a1908, 0x001e1908, 0x00231807, 0x00241807, 0x00281c0a, 0x002b1f0c, 0x002b200b, 0x002b1f0a, 0x002d200a, 0x0034240b, 0x003f240c, 0x0042270d, 0x00442b0b, 0x00482f0b, 0x0050370b, 0x005f410f, 0x006c460c, 0x00805210, 0x00946314, 0x00a8781c, 0x00b48922, 0x00c19a28, 0x00c6a425, 0x00cbaa23, 0x00ccad22, 0x00ccaf20, 0x00ccb01e, 0x00ccb01c, 0x00ccb11a, 0x00ccb41a, 0x00ccb419, 0x00ccb419, 0x00ccb221, 0x00cbab26, 0x00c5a326, 0x00bc961f, 0x00a67f14, 0x00946810, 0x007d4d06, 0x006e4309, 0x00623c0b, 0x005a3a0c, 0x00583a0e, 0x0058390b, 0x00583809, 0x005b3a0b, 0x005f3f0c, 0x0060410b, 0x00614209, 0x0068450a, 0x00704a0e, 0x00754c0e, 0x007c4c09, 0x0084540d, 0x008c5c10, 0x00996a18, 0x00a5781b, 0x00b48823, 0x00be9424, 0x00c89f27, 0x00c6a423, 0x00c9ac24, 0x00ccb020, 0x00ccb11a, 0x00ccb315, 0x00ccb413, 0x00ccb413, 0x00ccb612, 0x00ccb70f, 0x00cab808, 0x00cab808, 0x00c9b808, 0x00ccb80c, 0x00ccb315, 0x00ab880b, 0x007d5600, 0x00694401, 0x00553804, 0x00462d05, 0x00402b08, 0x003a2404, 0x00342004, 0x002f1d07, 0x00291907, 0x00261706, 0x00221508, 0x001f1307, 0x001b1308, 0x00191207, 0x00181307, 0x00171309, 0x00171309, 0x00151108, 0x00151108, 0x0017100b, 0x0017100b, 0x00150f0a, 0x00150f0a, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x00160f08, 0x00170f08, 0x00151008, 0x00151008, 0x00141009, 0x0014100a, 0x0013100a, 0x0014140c, 0x000e1008, 0x00101109, 0x0012110a, 0x0013100a, 0x0014100a, 0x0014100a, 0x0014100a, 0x00150f0a, 0x00150f0a, 0x00151009, 0x00151008, 0x00151008, 0x00171009, 0x00151008, 0x00161108, 0x00161108, 0x00161108, 0x00161109, 0x00151109, 0x00151108, 0x00151108, 0x00161208, 0x00181207, 0x00191208, 0x001c1208, 0x001d1409, 0x00201408, 0x00241508, 0x00281808, 0x002d1c09, 0x002f1b09, 0x0037200a, 0x0044280a, 0x00674418, 0x007f5014, 0x009b6915, 0x00c59c26, 0x00cbac15, 0x00cbb10a, 0x00c8b209, 0x00c8b209, 0x00c9b30b, 0x00c9b30c, 0x00cab40f, 0x00cbb410, 0x00ccb410, 0x00ccb411, 0x00ccb40f, 0x00ccb40f, 0x00ccb310, 0x00ccb311, 0x00ccb211, 0x00ccb113, 0x00ccb012, 0x00ccaf13, 0x00ccac16, 0x00ccaa1a, 0x00caa61d, 0x00caa321, 0x00c9a023, 0x00c39820, 0x00be921c, 0x00b98c19, 0x00b48417, 0x00af7c18, 0x00a77211, 0x00a06c0f, 0x009a660b, 0x009a6412, 0x00925c14, 0x00895414, 0x00885414, 0x00845310, 0x00815010, 0x008b5a15, 0x00a87925, 0x00c4a02b, 0x00caad24, 0x00ccb11d, 0x00cab314, 0x00cab40f, 0x00c9b70c, 0x00c9b80b, 0x00c8b80c, 0x00c8b80c, 0x00c8b80c, 0x00c8b70c, 0x00c8b60c, 0x00c8b50c, 0x00cbb50c, 0x00cbb40d, 0x00c9b510, 0x00c9b412, 0x00ccb018, 0x00c9ac18, 0x00bf9d18, 0x00a87e0c, 0x00905f02, 0x00804f08, 0x00683c08, 0x004c3003, 0x00402a04, 0x003c2808, 0x00342307, 0x002e2008, 0x002b1d09, 0x00281a08, 0x00241606, 0x00201407, 0x001b1207, 0x00161207, 0x00121004, 0x00100f04, 0x000c0e02, 0x00090d01, 0x00080d01, 0x00060e01, 0x00081003, 0x000e1004, 0x00101005, 0x00101004, 0x00131405, 0x001b1408, 0x0021180b, 0x0023190c, 0x0024190d, 0x0024190c, 0x00261a0c, 0x00291c10, 0x0026180e, 0x0023160c, 0x0021180a, 0x0020180b, 0x001e140a, 0x001c1108, 0x001c1206, 0x001a1306, 0x00181406, 0x00181407, 0x00181508, 0x00181408, 0x001b1408, 0x001d1408, 0x001c1409, 0x00181308, 0x00140f07, 0x00100c04, 0x000d0c04, 0x000b0c03, 0x000a0d05, 0x000c0e08, 0x000c0e08, 0x000c1009, 0x000c0f08, 0x00121710, 0x001c2019, 0x00191e17, 0x001a1f18, 0x001b2018, 0x001a1f18, 0x00182018, 0x00182018, 0x001b2018, 0x001b2018, 0x001d211a, 0x001c1f18, 0x001c1e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250c, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004b4c10, 0x004c4d0f, 0x004f5010, 0x005d5810, 0x00a08413, 0x00c79f15, 0x00cca316, 0x00c9a116, 0x00b19015, 0x00887512, 0x00635e10, 0x005b5910, 0x00585810, 0x00595a11, 0x00585911, 0x00595a11, 0x00585911, 0x00585911, 0x00585911, 0x00595a11, 0x00595a11, 0x005c5a11, 0x00656010, 0x008a7613, 0x00ae8e14, 0x00c8a015, 0x00cca316, 0x00c9a116, 0x00b08f14, 0x00706410, 0x004f4f10, 0x004d4e10, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450e, 0x0041420e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c16, 0x00181b17, 0x00191b18, 0x00191a16, 0x0014150e, 0x00101009, 0x000f100a, 0x000d100a, 0x000a0f08, 0x00090e07, 0x000b0d07, 0x000b0c04, 0x000e0d02, 0x001c190d, 0x00281b12, 0x00271810, 0x0023160c, 0x0021160c, 0x0020140a, 0x00201409, 0x00201409, 0x00201409, 0x001e1408, 0x001a1305, 0x00151203, 0x00121201, 0x000d0f00, 0x000c0d02, 0x000e0d03, 0x000e0e01, 0x000f0f02, 0x00141105, 0x00131104, 0x00141205, 0x00181608, 0x001e180b, 0x001f180a, 0x00201809, 0x00221a0b, 0x00241c0d, 0x00241c0d, 0x00241d0c, 0x00271e0b, 0x002b1d0a, 0x00301c08, 0x00301c08, 0x00311e0a, 0x00331f0b, 0x0033200b, 0x00342209, 0x0037250a, 0x003c290c, 0x00492a10, 0x004e2f10, 0x0053320e, 0x005c3c11, 0x00664410, 0x007a5413, 0x00936917, 0x00b08422, 0x00c09728, 0x00c7a328, 0x00ccac24, 0x00ccaf1c, 0x00ccb216, 0x00ccb412, 0x00ccb512, 0x00ccb611, 0x00ccb811, 0x00ccb810, 0x00ccb80e, 0x00cbba0c, 0x00cbba0b, 0x00cbb90c, 0x00ccb911, 0x00ccb816, 0x00ccb619, 0x00ccb31c, 0x00cbae22, 0x00be9a21, 0x00a47a10, 0x00805703, 0x00704808, 0x00653f0a, 0x00613e0b, 0x00603d08, 0x00673f09, 0x006d440c, 0x0071480c, 0x00754c0a, 0x007e540d, 0x0084560e, 0x008d5f13, 0x00976717, 0x00a07115, 0x00ac801c, 0x00bc9026, 0x00c39929, 0x00cba427, 0x00cca824, 0x00ccac1e, 0x00ccad18, 0x00c9ae14, 0x00cbb314, 0x00ccb511, 0x00cbb50c, 0x00ccb60b, 0x00ccb60a, 0x00ccb70b, 0x00ccb80b, 0x00ccb80a, 0x00cab808, 0x00cab908, 0x00cab908, 0x00ccb80d, 0x00ccb718, 0x00af8c0d, 0x00825800, 0x00674000, 0x00563705, 0x00462d06, 0x003c2806, 0x00382201, 0x00332005, 0x002d1d07, 0x00291907, 0x00251707, 0x00221408, 0x001f1307, 0x001b1307, 0x00191207, 0x00181308, 0x00171309, 0x00171309, 0x00161208, 0x00151108, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x00161008, 0x00160f08, 0x00151008, 0x00151008, 0x00151009, 0x0014100a, 0x0012100a, 0x0014140c, 0x000e1008, 0x00101109, 0x0012110a, 0x0013100a, 0x0014100a, 0x0014100a, 0x0014100a, 0x0017100b, 0x0017100b, 0x00151008, 0x00151008, 0x00171009, 0x00171009, 0x00171008, 0x00171008, 0x00181209, 0x00181309, 0x00171209, 0x0016120a, 0x00151109, 0x00151108, 0x00151108, 0x00181207, 0x00191208, 0x001c1208, 0x001d1409, 0x00201408, 0x00231406, 0x00281808, 0x002e1b09, 0x00301a09, 0x0038200a, 0x0045290a, 0x00684619, 0x007f5014, 0x009a6916, 0x00c69d27, 0x00ccad18, 0x00c9b109, 0x00c8b308, 0x00c8b308, 0x00c9b408, 0x00c9b408, 0x00cab408, 0x00cbb509, 0x00cbb608, 0x00cbb708, 0x00cab707, 0x00c9b706, 0x00cab606, 0x00cab607, 0x00cab407, 0x00cab408, 0x00cbb408, 0x00cbb408, 0x00ccb40b, 0x00ccb20e, 0x00ccb011, 0x00ccaf13, 0x00cbad14, 0x00caac14, 0x00caab18, 0x00caab1b, 0x00cba81d, 0x00cca01c, 0x00c99d1c, 0x00c4981b, 0x00bf9217, 0x00b58716, 0x00b07f19, 0x00a36e15, 0x0096600d, 0x008d5b0c, 0x00905e13, 0x00aa7c27, 0x00c79f34, 0x00ccb025, 0x00ccb418, 0x00ccb512, 0x00ccb60c, 0x00ccb708, 0x00cbb708, 0x00cab509, 0x00cbb30b, 0x00cbb30a, 0x00cbb30a, 0x00ccb50c, 0x00ccb50c, 0x00ccb50b, 0x00ccb409, 0x00cbb509, 0x00c9b708, 0x00c9b707, 0x00ccb50e, 0x00cbb410, 0x00ccb318, 0x00c4a219, 0x00ae7f0d, 0x00935e02, 0x007c4c07, 0x00613a04, 0x004d3004, 0x00432906, 0x00392506, 0x00342408, 0x00312008, 0x00301e08, 0x002d1c09, 0x00291909, 0x0024170a, 0x0020170c, 0x001d150b, 0x001a1409, 0x00151006, 0x00101007, 0x000e0f06, 0x000c1006, 0x000a0f05, 0x000a0f04, 0x000b0f04, 0x000a0e04, 0x000a0e03, 0x000e0d03, 0x00140d03, 0x00161006, 0x00180f05, 0x00181004, 0x001b1207, 0x001e1409, 0x0020150a, 0x0022180c, 0x0024180e, 0x0024180d, 0x0024170c, 0x0022150b, 0x0022140b, 0x0021150b, 0x00201609, 0x001f1709, 0x001d1508, 0x001d1508, 0x001f1508, 0x00201508, 0x001c1408, 0x00141005, 0x00100c04, 0x000e0c04, 0x000c0c04, 0x00090d03, 0x00090c04, 0x000b0d07, 0x000c0f08, 0x000c1009, 0x000d100a, 0x000d120c, 0x001a1f18, 0x00191e17, 0x00191e17, 0x001a1f18, 0x001a1f18, 0x00182018, 0x00182018, 0x001b2018, 0x001b2018, 0x001d201a, 0x001c1f18, 0x001c1e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0045470e, 0x0048490f, 0x004b4c10, 0x004c4d0f, 0x004d4e0f, 0x00515010, 0x00726511, 0x00aa8a14, 0x00c8a015, 0x00cca216, 0x00c9a116, 0x00c49d15, 0x00af8f14, 0x009c8214, 0x008c7713, 0x007e6e12, 0x00786a12, 0x00726811, 0x00796c12, 0x00837212, 0x00907a13, 0x00a08514, 0x00b39114, 0x00c59e15, 0x00caa116, 0x00cca316, 0x00caa116, 0x00b89514, 0x00877312, 0x00565410, 0x004f5010, 0x004c4d0f, 0x004b4c10, 0x0048490f, 0x0047480e, 0x0044450e, 0x0041420e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0020230a, 0x001d2008, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x00141810, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x00181c15, 0x00181c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00191c16, 0x00191c16, 0x00181c15, 0x00181c16, 0x00191b17, 0x001b1c18, 0x00171813, 0x0013140c, 0x000f1008, 0x000f1008, 0x000d1008, 0x000b0f06, 0x000a0f06, 0x000c0e08, 0x000c1006, 0x000c0c01, 0x00181509, 0x0021150e, 0x001e0f09, 0x00190e07, 0x00180f07, 0x00161007, 0x00120f05, 0x00110f03, 0x00110e03, 0x00100e02, 0x000f0f01, 0x000d0f00, 0x000f1001, 0x000e1000, 0x00101204, 0x00141407, 0x00141405, 0x00141405, 0x001a1306, 0x001d1608, 0x00201708, 0x00241c0c, 0x00261c0c, 0x00271c09, 0x00261907, 0x00281b08, 0x002c1d09, 0x002d1e0a, 0x002e1e0a, 0x0030200a, 0x00332008, 0x00362008, 0x00372109, 0x00382209, 0x003c240c, 0x003c270d, 0x003c270b, 0x00402a0c, 0x00442d0c, 0x0050310f, 0x0055340c, 0x00603b08, 0x00724a11, 0x00875d14, 0x00a87f21, 0x00bf9924, 0x00c9a820, 0x00cbaf1c, 0x00cbb118, 0x00ccb413, 0x00ccb50f, 0x00ccb410, 0x00ccb10d, 0x00ccae0d, 0x00cbac0c, 0x00cbad0f, 0x00caae0f, 0x00c9af0d, 0x00cab10c, 0x00ccb50d, 0x00ccb50c, 0x00cbb70a, 0x00ccb809, 0x00ccbc09, 0x00ccba0e, 0x00ccb814, 0x00ccb41d, 0x00c4a718, 0x00a17d0b, 0x00785000, 0x00724704, 0x0072460a, 0x00764b0b, 0x0081540f, 0x008b5e12, 0x00926614, 0x009b6f13, 0x00a47814, 0x00af821d, 0x00bc9028, 0x00c49c2d, 0x00c6a023, 0x00cba824, 0x00cba81f, 0x00ccac1c, 0x00ccb014, 0x00ccb210, 0x00ccb40d, 0x00ccb409, 0x00cab608, 0x00c9b608, 0x00c9b707, 0x00c9b706, 0x00cab806, 0x00cab808, 0x00cbb808, 0x00ccb808, 0x00ccb808, 0x00ccb808, 0x00cab908, 0x00cbba0a, 0x00ccb80d, 0x00ccb518, 0x00b18e10, 0x00835a00, 0x00673f00, 0x00543403, 0x00452d06, 0x003c2805, 0x00362100, 0x00331f04, 0x002c1c08, 0x00281808, 0x00251607, 0x00221408, 0x001e1307, 0x001a1207, 0x00191207, 0x00181308, 0x00171309, 0x00171309, 0x00161208, 0x00161208, 0x0018110a, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00151109, 0x00171109, 0x0018110a, 0x0017110b, 0x0016110c, 0x0014120c, 0x0014140c, 0x000c0e06, 0x0012110a, 0x0013120b, 0x0014110b, 0x0015100b, 0x0017100b, 0x0017100b, 0x0017100b, 0x0017100b, 0x0018110a, 0x0018110a, 0x00171009, 0x00171009, 0x00181108, 0x00181108, 0x00181208, 0x00181208, 0x00171108, 0x00161208, 0x00151108, 0x00151108, 0x00161208, 0x00181207, 0x00191208, 0x001c1309, 0x001f140a, 0x00201408, 0x00231406, 0x00281707, 0x002c1a08, 0x00301b08, 0x00371f08, 0x00442707, 0x006a4819, 0x00805014, 0x009c6b18, 0x00c59c26, 0x00ccaf1a, 0x00cab30a, 0x00c9b407, 0x00c9b405, 0x00c9b405, 0x00c9b405, 0x00cab506, 0x00cab504, 0x00cbb605, 0x00c9b705, 0x00c9b707, 0x00c8b807, 0x00c9b707, 0x00c9b707, 0x00cbb607, 0x00cbb608, 0x00ccb508, 0x00ccb508, 0x00ccb507, 0x00ccb508, 0x00cbb408, 0x00cbb409, 0x00cab509, 0x00cbb50b, 0x00cbb40c, 0x00ccb410, 0x00ccb311, 0x00ccb212, 0x00ccb013, 0x00ccad14, 0x00ccac16, 0x00cba718, 0x00cba01d, 0x00c1901c, 0x00a06c06, 0x0099620a, 0x00a07017, 0x00c2982d, 0x00ccac27, 0x00cbb315, 0x00ccb60e, 0x00ccb70a, 0x00ccb805, 0x00cab504, 0x00ccb20c, 0x00cbaa0d, 0x00caa411, 0x00c8a010, 0x00c49d0c, 0x00c29c0a, 0x00c49f0c, 0x00c5a20d, 0x00c8a80e, 0x00ccb011, 0x00ccb410, 0x00ccb60c, 0x00ccb60d, 0x00ccb908, 0x00cbb707, 0x00ccb214, 0x00c8a218, 0x00ac7e08, 0x008e5c00, 0x00774903, 0x005e3805, 0x004e2f07, 0x00432804, 0x003c2608, 0x00382408, 0x00362006, 0x00331e07, 0x00301d08, 0x002c1c0a, 0x002a190e, 0x0028180d, 0x0026180e, 0x0024190e, 0x001e160b, 0x00181207, 0x00171409, 0x00131207, 0x00101105, 0x000c1003, 0x000c0f03, 0x000c0f03, 0x000d0c03, 0x00100c04, 0x00100c03, 0x00100c03, 0x000f0c02, 0x00100b01, 0x00120d02, 0x00151005, 0x001a1308, 0x001e1409, 0x001f1509, 0x0025180c, 0x0025190d, 0x0024180b, 0x0026190d, 0x0025170a, 0x00251609, 0x00241608, 0x00231608, 0x00231708, 0x001f1407, 0x00161002, 0x00100d02, 0x000e0c03, 0x000d0c04, 0x000a0d03, 0x00080e03, 0x00080d04, 0x00090e07, 0x000a0f09, 0x000d100a, 0x0010120c, 0x000e110b, 0x00151812, 0x00181d16, 0x00181d16, 0x00191e17, 0x00191e17, 0x00192018, 0x00192018, 0x001b2018, 0x001b2018, 0x001c2019, 0x001c1f18, 0x001c1e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0040400d, 0x0043440e, 0x0045470e, 0x0047480f, 0x00494a10, 0x004b4c0f, 0x004c4d0f, 0x004d4e10, 0x00525010, 0x00706311, 0x00a08413, 0x00be9815, 0x00cba116, 0x00cca216, 0x00cca216, 0x00caa116, 0x00c8a015, 0x00c7a015, 0x00c7a015, 0x00c8a015, 0x00c8a016, 0x00caa216, 0x00cca316, 0x00cca316, 0x00cca216, 0x00c8a015, 0x00af8e14, 0x00867111, 0x00595510, 0x004f5010, 0x004d4e0f, 0x004b4c0f, 0x00494a10, 0x0048490f, 0x0045470e, 0x0043440e, 0x0041420d, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c09, 0x00141809, 0x0014180b, 0x0014180e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c15, 0x00181c15, 0x001a1b15, 0x00181c15, 0x00181c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00191c16, 0x00191c16, 0x00181c15, 0x00181c16, 0x00191b17, 0x001c1c18, 0x00171812, 0x0013140c, 0x000f1007, 0x000f1007, 0x000d1007, 0x000c0f04, 0x00091006, 0x000a0f06, 0x000d1007, 0x00101005, 0x00151309, 0x001a120c, 0x00140d07, 0x00100b04, 0x000e0c04, 0x000c0d04, 0x000c0d04, 0x000e0f04, 0x00101005, 0x00101005, 0x00121205, 0x00131204, 0x00151405, 0x00161405, 0x001c180b, 0x00201a0c, 0x00201a0d, 0x00211a0c, 0x00241c09, 0x00281d0b, 0x00281f0c, 0x002b1f0c, 0x002c1e0b, 0x002d1e0a, 0x002f1e0a, 0x0030200a, 0x0033220a, 0x00342209, 0x00342209, 0x0037230a, 0x00382509, 0x003a270a, 0x003c280b, 0x003f290e, 0x00402a0f, 0x00412b0e, 0x00442c0c, 0x00482e0c, 0x004c320c, 0x0058380b, 0x00634009, 0x0078500d, 0x009c7224, 0x00b9902a, 0x00cba62e, 0x00caac1f, 0x00ccb313, 0x00cbb50c, 0x00cbb40a, 0x00ccb10c, 0x00cbac0a, 0x00caa30d, 0x00c49810, 0x00bd8f0a, 0x00b58906, 0x00b08405, 0x00b08406, 0x00af8604, 0x00b48c08, 0x00bc960d, 0x00c5a311, 0x00cbae14, 0x00cab50c, 0x00c9b806, 0x00cabb09, 0x00cbbb0e, 0x00c9b710, 0x00ccb616, 0x00c0a015, 0x008c6600, 0x00805104, 0x0081530c, 0x00966919, 0x00ad8328, 0x00b38b27, 0x00bb9527, 0x00c7a129, 0x00cba826, 0x00ccac28, 0x00ccae25, 0x00ccb122, 0x00cab01c, 0x00cbb418, 0x00ccb614, 0x00ccb710, 0x00cab70c, 0x00c9b608, 0x00cab607, 0x00c9b705, 0x00c8b807, 0x00c8b708, 0x00c9b608, 0x00c9b609, 0x00c9b709, 0x00c9b809, 0x00cbb80a, 0x00ccb80a, 0x00cab908, 0x00cab908, 0x00c8ba08, 0x00cabb0a, 0x00cbb90c, 0x00ccb618, 0x00b18e10, 0x00845b00, 0x00664000, 0x00543403, 0x00442d06, 0x00382603, 0x00331f00, 0x00311e04, 0x002c1c08, 0x00281708, 0x00241508, 0x00201307, 0x001c1206, 0x00191307, 0x00181307, 0x00171408, 0x00171309, 0x00171309, 0x00161208, 0x00161208, 0x00171008, 0x00171008, 0x00171008, 0x00171008, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00141109, 0x00141109, 0x0015110a, 0x0017120a, 0x0017110b, 0x0016110c, 0x0014120c, 0x0014140c, 0x000c0e06, 0x0012110b, 0x0013120b, 0x0014110b, 0x0015100b, 0x0017100b, 0x0017100b, 0x0018110c, 0x0018110c, 0x0018110a, 0x0018110a, 0x00171009, 0x00171009, 0x00181108, 0x00181108, 0x00171008, 0x00171008, 0x00161008, 0x00151108, 0x00151108, 0x00151108, 0x00161208, 0x00181207, 0x00191208, 0x001c1409, 0x001f140b, 0x00201408, 0x00231407, 0x00261706, 0x002c1908, 0x00301b08, 0x00381e08, 0x00442606, 0x006b491c, 0x00825417, 0x00a06e1b, 0x00c69c27, 0x00ccb01a, 0x00cab30a, 0x00c9b404, 0x00c9b404, 0x00c9b405, 0x00c9b405, 0x00cab506, 0x00cab506, 0x00ccb508, 0x00cbb508, 0x00cbb509, 0x00cbb50a, 0x00cbb50c, 0x00ccb40d, 0x00ccb40d, 0x00ccb40d, 0x00ccb40f, 0x00cbb40f, 0x00cbb40d, 0x00cab60c, 0x00c8b50a, 0x00c8b508, 0x00c9b508, 0x00cbb607, 0x00cbb609, 0x00cbb50c, 0x00cbb50c, 0x00cbb50c, 0x00cab40b, 0x00c9b30d, 0x00cbb210, 0x00ccad0d, 0x00cca710, 0x00c2910f, 0x00a46b00, 0x009c6504, 0x00b48720, 0x00cba82c, 0x00cbb217, 0x00cbb60c, 0x00ccb80c, 0x00ccb708, 0x00ccb805, 0x00cab109, 0x00c6a30e, 0x00b88c07, 0x00ae7902, 0x00a87002, 0x00a06d00, 0x00a06c00, 0x00a37000, 0x00a67402, 0x00b38308, 0x00bd900d, 0x00c79f14, 0x00ccaa18, 0x00cbb412, 0x00c8bb03, 0x00c9b900, 0x00ccb40b, 0x00ccb115, 0x00c4a014, 0x00a47804, 0x00815300, 0x00683f06, 0x00543306, 0x00482c04, 0x00422a07, 0x003f2707, 0x003b2305, 0x00372004, 0x00341f07, 0x00331e09, 0x00311c0c, 0x00301b0b, 0x002f1a0b, 0x002d1b0c, 0x00291a0d, 0x0026180c, 0x0024190c, 0x001f170b, 0x001b1709, 0x00181406, 0x00171306, 0x00141004, 0x00111004, 0x00101005, 0x000f0f04, 0x000c0c01, 0x000c0c01, 0x000e0c02, 0x000f0d03, 0x000d0c01, 0x00100d02, 0x00130f03, 0x00141002, 0x00191507, 0x001d1808, 0x001e1708, 0x00231809, 0x00281a0c, 0x0029190b, 0x0029180a, 0x0028180a, 0x00231707, 0x001c1101, 0x00130e00, 0x000e0c01, 0x000d0d03, 0x000c0d04, 0x000a0e04, 0x00070e03, 0x00080e04, 0x00090e07, 0x00090e07, 0x000c100a, 0x000f140c, 0x000e110b, 0x00151812, 0x00171c15, 0x00181d16, 0x00181d16, 0x00191e17, 0x00192018, 0x00192018, 0x001b2018, 0x001b2018, 0x001c2019, 0x001c1f18, 0x001c1e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0038380c, 0x00393b0d, 0x003c3e0d, 0x0040400d, 0x0041420e, 0x0044450e, 0x0045470e, 0x0048490f, 0x00494a10, 0x004b4c0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x005e5810, 0x007a6a11, 0x009c8013, 0x00b18f14, 0x00bc9815, 0x00c49c15, 0x00c8a015, 0x00c9a116, 0x00c8a015, 0x00c49d16, 0x00c09915, 0x00b69314, 0x00a98914, 0x008c7512, 0x006b6011, 0x00535110, 0x004d4e10, 0x004d4e0f, 0x004c4d0f, 0x004b4c10, 0x0048490f, 0x0047480e, 0x0044450e, 0x0043440e, 0x0040400d, 0x003c3e0c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1b15, 0x00151710, 0x00101208, 0x000f1006, 0x000f1007, 0x000d0f05, 0x000c0f04, 0x000c0f06, 0x000c1007, 0x000e0f08, 0x0015130c, 0x0014120c, 0x00141109, 0x000f0e07, 0x000e0d06, 0x000c0e06, 0x000c0e05, 0x000e1008, 0x00111108, 0x00151308, 0x00181408, 0x001d1809, 0x0021190b, 0x00241a0d, 0x0026190c, 0x002b1d0d, 0x002c1e0d, 0x002c1d0d, 0x002e1e0e, 0x002d1d0d, 0x002d1e0c, 0x00301f0c, 0x0033220d, 0x0034220c, 0x0035210c, 0x00352209, 0x0038240a, 0x0038270c, 0x003b290e, 0x003e2c11, 0x003f2d12, 0x00402e10, 0x00402f0f, 0x0040300c, 0x0044310d, 0x00473410, 0x00483310, 0x004b3410, 0x004f3610, 0x00543810, 0x0068400f, 0x00784f0f, 0x00a37823, 0x00c19530, 0x00c8ab26, 0x00ccb31d, 0x00ccb414, 0x00cab40f, 0x00ccb20f, 0x00c8a811, 0x00c29c13, 0x00b38708, 0x00a47300, 0x00976300, 0x00905a00, 0x00895400, 0x00885300, 0x00875100, 0x00855300, 0x00895700, 0x00906001, 0x009a6f07, 0x00af860e, 0x00c5a416, 0x00cbb416, 0x00cab60f, 0x00c8b80e, 0x00c8b80e, 0x00ccb80e, 0x00cbb017, 0x00a37c08, 0x00885902, 0x00916210, 0x00bb9030, 0x00cba732, 0x00c8ac26, 0x00cbb120, 0x00ccb319, 0x00ccb518, 0x00ccb618, 0x00cab715, 0x00cab813, 0x00c8b710, 0x00c8b80e, 0x00c9b80c, 0x00c9b80b, 0x00c9b809, 0x00c9b809, 0x00c9b809, 0x00c9b809, 0x00c9b80b, 0x00c9b80c, 0x00c9b80c, 0x00c9b70e, 0x00c9b70e, 0x00c9b80c, 0x00c9b80a, 0x00c8ba08, 0x00c8b908, 0x00c8b808, 0x00c8b809, 0x00cab90a, 0x00ccb90a, 0x00ccb713, 0x00b3900c, 0x00835c00, 0x00694500, 0x00543602, 0x00422c04, 0x00382504, 0x00321f00, 0x00301e08, 0x002c1a0b, 0x00251608, 0x00221406, 0x001f1406, 0x001c1205, 0x00181307, 0x00181307, 0x00171408, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x0018110a, 0x00171009, 0x00171009, 0x00171009, 0x00141208, 0x00141208, 0x00141108, 0x00161108, 0x00171109, 0x0016120a, 0x0016120a, 0x0016140b, 0x00131008, 0x00121108, 0x00141209, 0x00141109, 0x00141109, 0x00171009, 0x00171009, 0x0018100a, 0x0018100a, 0x00181108, 0x00161208, 0x00161208, 0x00161208, 0x00151108, 0x00151108, 0x00151108, 0x00151108, 0x00161108, 0x00171008, 0x00171008, 0x00171008, 0x00171309, 0x00171309, 0x00181309, 0x001c130c, 0x001d140b, 0x00201408, 0x00231407, 0x00261706, 0x002c1908, 0x00301b08, 0x00381f08, 0x00442608, 0x0069481e, 0x0085551a, 0x00a36f1c, 0x00c99e2c, 0x00ccaf1d, 0x00c8b20e, 0x00c8b408, 0x00c8b408, 0x00c8b40a, 0x00c8b40a, 0x00c8b509, 0x00cab409, 0x00cbb50b, 0x00cbb50c, 0x00cbb50c, 0x00cbb50c, 0x00cbb50c, 0x00cbb50c, 0x00ccb40d, 0x00ccb40d, 0x00ccb40c, 0x00ccb40c, 0x00cbb50a, 0x00cbb50a, 0x00cbb50a, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00cbb408, 0x00cbb408, 0x00cbb408, 0x00cbb409, 0x00ccb309, 0x00ccb008, 0x00cca80e, 0x00b78504, 0x00a16500, 0x00a1690e, 0x00c49a2c, 0x00ccb020, 0x00ccb90c, 0x00ccb90b, 0x00ccb80f, 0x00ccb810, 0x00cbb410, 0x00bc9c09, 0x00a97d03, 0x00976501, 0x00945e02, 0x008d5700, 0x008c5404, 0x008a5203, 0x008c5505, 0x008d5503, 0x00925d01, 0x009c6904, 0x00ab780a, 0x00c19018, 0x00cca619, 0x00ccb30d, 0x00cab804, 0x00ccb70a, 0x00ccb411, 0x00ccb014, 0x00c09a15, 0x00906001, 0x00744804, 0x005d3d04, 0x00503204, 0x00482e06, 0x00442b07, 0x00412909, 0x003d2507, 0x00382307, 0x00362008, 0x00341e08, 0x00321c08, 0x00321d09, 0x00301e0b, 0x002f1c0a, 0x002e1d0a, 0x002c1d09, 0x002a1d0a, 0x00251b0c, 0x0020180a, 0x00201709, 0x001d1409, 0x00191004, 0x00151004, 0x00141004, 0x00100f03, 0x00100e04, 0x00100f05, 0x000d0c04, 0x000d0c04, 0x000c0c02, 0x000c0c01, 0x000c0e00, 0x000d1002, 0x00101405, 0x00131405, 0x00171304, 0x001f1508, 0x0027190d, 0x00281c10, 0x0024190f, 0x001d1408, 0x00150f04, 0x000f0c01, 0x000e0e03, 0x000d0d04, 0x000c0c04, 0x000a0e04, 0x00080f05, 0x00080f05, 0x00080d04, 0x00080d06, 0x00090d05, 0x000a0d05, 0x000e1109, 0x0013160e, 0x00171c15, 0x00171c15, 0x00181d16, 0x00181d16, 0x00192018, 0x00192018, 0x00192018, 0x00192018, 0x001b2019, 0x001b201a, 0x001b201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0043440e, 0x0045470e, 0x0047480e, 0x0048490f, 0x00494a0f, 0x004b4c10, 0x004c4d0f, 0x004d4e0f, 0x004c4d0f, 0x004b4c10, 0x00515010, 0x00605810, 0x00685d11, 0x006d6011, 0x006f6110, 0x006c6010, 0x006a5f10, 0x00635b10, 0x00585410, 0x004c4d10, 0x004c4d10, 0x004d4e0f, 0x004c4d0f, 0x004b4c0f, 0x00494a0f, 0x0048490f, 0x0047480e, 0x0045470e, 0x0044450e, 0x0041420e, 0x0040400d, 0x003c3e0d, 0x00393b0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1c16, 0x00181812, 0x0012140c, 0x000f1007, 0x000f1005, 0x000d0f05, 0x000c0e04, 0x000c0f04, 0x000c0e04, 0x000d0f07, 0x00101009, 0x0016130c, 0x0017120c, 0x00121209, 0x000d1007, 0x000d1007, 0x000e1108, 0x00111208, 0x0015150c, 0x0019160b, 0x001d180a, 0x0021190a, 0x00281b0b, 0x002c1c0d, 0x002f1d10, 0x00301d0e, 0x00311f0c, 0x0032200b, 0x0033200b, 0x0034210c, 0x0035220e, 0x0035230f, 0x0035240c, 0x0039270e, 0x003b280e, 0x003b280c, 0x003d2a0d, 0x00402c0d, 0x00412f0d, 0x00453010, 0x00473311, 0x00463211, 0x00473311, 0x00473310, 0x00483510, 0x004c3910, 0x004e3c10, 0x00503b0d, 0x00523b0c, 0x00583c0d, 0x0060420f, 0x00744e0b, 0x009c7621, 0x00be9a2b, 0x00ccac28, 0x00ccb41a, 0x00ccb710, 0x00ccb611, 0x00c9ac0e, 0x00c29e10, 0x00ad8208, 0x00996902, 0x008a5800, 0x00815000, 0x007a4900, 0x00764500, 0x00724100, 0x00724201, 0x00744403, 0x00744401, 0x00774802, 0x007f5007, 0x00825504, 0x008f6001, 0x00ac840f, 0x00cbac1f, 0x00cbb511, 0x00c8b80b, 0x00c8bb08, 0x00cbb908, 0x00cbb514, 0x00a88204, 0x00906001, 0x00996a0d, 0x00c19926, 0x00ccb024, 0x00cab414, 0x00cbb60f, 0x00ccb70a, 0x00cab80c, 0x00cab80c, 0x00ccb80d, 0x00ccb80d, 0x00cab70c, 0x00cab70c, 0x00cbb70c, 0x00cbb70c, 0x00cab70c, 0x00cab70b, 0x00cab70b, 0x00cab809, 0x00cab809, 0x00cab70b, 0x00c9b80b, 0x00c9b80b, 0x00c9b80a, 0x00c9b809, 0x00c9b808, 0x00cab907, 0x00caba06, 0x00ccba08, 0x00ccb90a, 0x00ccb80a, 0x00ccb80d, 0x00ccb616, 0x00b38f0e, 0x00845d00, 0x006e4c03, 0x00513400, 0x003f2903, 0x00362606, 0x00321e04, 0x002f1c08, 0x00281809, 0x00241506, 0x00201305, 0x001d1204, 0x001a1305, 0x00181307, 0x00171407, 0x00161408, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x0016120a, 0x0016120a, 0x0016120a, 0x0016120a, 0x00141208, 0x00141106, 0x00161106, 0x00171006, 0x00181008, 0x00181108, 0x00181108, 0x00181309, 0x00141008, 0x00121107, 0x00141208, 0x00151108, 0x00151108, 0x00161208, 0x00171108, 0x00181108, 0x00181108, 0x00161307, 0x00161307, 0x00161307, 0x00161307, 0x00151208, 0x00151108, 0x00151108, 0x00151108, 0x00161108, 0x00181108, 0x00171008, 0x00181309, 0x00171309, 0x00171309, 0x00181309, 0x001c140c, 0x001d140b, 0x00201408, 0x00231406, 0x00261706, 0x002b1908, 0x00301c08, 0x00361f09, 0x00402408, 0x0065451d, 0x007c5013, 0x009a6712, 0x00c79927, 0x00cca91b, 0x00caaf0c, 0x00cab309, 0x00cab309, 0x00cab308, 0x00cab308, 0x00cbb408, 0x00cab408, 0x00cbb608, 0x00c9b608, 0x00c9b708, 0x00c9b708, 0x00c9b708, 0x00c9b707, 0x00cab608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00cbb408, 0x00cab307, 0x00cbb408, 0x00ccb408, 0x00ccb409, 0x00ccb20f, 0x00caa510, 0x00b07d02, 0x00a06301, 0x00ac7415, 0x00c7a02a, 0x00ccb31c, 0x00ccbb0a, 0x00ccbb0c, 0x00ccb810, 0x00ccb712, 0x00c4a60d, 0x00a88000, 0x00946500, 0x00885802, 0x00855405, 0x00815103, 0x0081500a, 0x00805008, 0x00804f08, 0x007f5007, 0x00835404, 0x00885802, 0x00916002, 0x00a06d08, 0x00b88c14, 0x00caa819, 0x00cbb212, 0x00ccb511, 0x00ccb510, 0x00ccb410, 0x00cbaa19, 0x00aa7c0f, 0x007d5300, 0x00664402, 0x00573804, 0x004d3306, 0x00482e07, 0x00462c09, 0x00442c0a, 0x003e2808, 0x00392306, 0x00392208, 0x00382108, 0x00362008, 0x00331f08, 0x00321e08, 0x00301e08, 0x002f1f08, 0x002f1f08, 0x002e1f0c, 0x002d1c0e, 0x002c1b0c, 0x002b190b, 0x0026180a, 0x0025180b, 0x00221809, 0x001e1707, 0x001b1408, 0x00161008, 0x00141007, 0x00121107, 0x00101006, 0x000f0f04, 0x000b0c01, 0x00090e00, 0x00081000, 0x00081000, 0x000b0f00, 0x00101001, 0x00171104, 0x001c140a, 0x001e170c, 0x0018140b, 0x00121006, 0x000f0d03, 0x000f0d03, 0x000e0d04, 0x000e0d04, 0x000c0e04, 0x00080f05, 0x00080f05, 0x00080d04, 0x00080d04, 0x00090c04, 0x00090c04, 0x000d1008, 0x0013160d, 0x00171c15, 0x00171c15, 0x00181d16, 0x00181d16, 0x00192018, 0x00192018, 0x00192018, 0x00192018, 0x001a2019, 0x001b201a, 0x001b201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x00393b0c, 0x003b3c0d, 0x003c3e0c, 0x0040400d, 0x0041420d, 0x0043440e, 0x0044450d, 0x0045470e, 0x0047480e, 0x0048490f, 0x00494a10, 0x00494a0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d10, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004c4d10, 0x004c4d0f, 0x004c4d0f, 0x004b4c10, 0x0048490f, 0x0048490f, 0x0047480e, 0x0045470e, 0x0044450e, 0x0041420e, 0x0040400d, 0x003e400c, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0026280b, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180b, 0x0014180e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00191b15, 0x001a1b15, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181c15, 0x00141710, 0x000d1008, 0x000d1008, 0x000d1007, 0x000c1005, 0x000c0e04, 0x000d1004, 0x000d0f05, 0x00101007, 0x0014120a, 0x0019130c, 0x0018110a, 0x00120e04, 0x00121007, 0x00141308, 0x0017140b, 0x001c180c, 0x00201c0e, 0x00261c0c, 0x00281d0c, 0x002c1f0c, 0x0030200c, 0x0032200c, 0x0036200d, 0x0038200c, 0x0039220c, 0x003c240c, 0x003c250b, 0x003d260b, 0x003c260b, 0x003c260b, 0x003c280b, 0x00402c0c, 0x00442e0e, 0x00442f0c, 0x0048310c, 0x0048330b, 0x004b340a, 0x0050380d, 0x0050380e, 0x00543810, 0x00543a0f, 0x00553b0e, 0x0059400f, 0x005b410f, 0x005d430b, 0x00604308, 0x005d4002, 0x00654404, 0x00704e0a, 0x008d6816, 0x00be9b32, 0x00caad27, 0x00cbb416, 0x00cab80c, 0x00ccb80c, 0x00cbb113, 0x00bc980c, 0x00a67603, 0x008f5b00, 0x00815003, 0x00784904, 0x00704402, 0x006a4202, 0x00684002, 0x00673e04, 0x00683f07, 0x00684008, 0x00684107, 0x006f4709, 0x00744c0b, 0x00794f08, 0x00855708, 0x009e710c, 0x00c3a01f, 0x00cbb414, 0x00c8b908, 0x00c8bc04, 0x00ccb907, 0x00cbb414, 0x00ab8304, 0x00926000, 0x00a06e0a, 0x00c49c1f, 0x00ccb219, 0x00cab40c, 0x00cab707, 0x00cbb704, 0x00c9b808, 0x00c9b808, 0x00ccb80a, 0x00ccb80a, 0x00ccb80c, 0x00ccb80c, 0x00ccb80c, 0x00ccb80c, 0x00ccb80c, 0x00ccb80c, 0x00ccb80a, 0x00ccb80a, 0x00ccb80a, 0x00ccb80a, 0x00ccb80a, 0x00cbb80a, 0x00ccb809, 0x00ccb808, 0x00ccb90b, 0x00ccb809, 0x00cbb408, 0x00cbb40b, 0x00ccb611, 0x00ccb312, 0x00ccb016, 0x00caac20, 0x00a98312, 0x00875f08, 0x00785512, 0x00513404, 0x003c2704, 0x00342307, 0x00301c05, 0x002c1906, 0x00271708, 0x00231407, 0x00201407, 0x001d1104, 0x001a1305, 0x00181307, 0x00161406, 0x00151308, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00181309, 0x00181309, 0x00161409, 0x00161409, 0x00161409, 0x00161409, 0x00161308, 0x00171205, 0x00181105, 0x00191105, 0x00191107, 0x00191208, 0x00191208, 0x001a1308, 0x00151106, 0x00141106, 0x00161307, 0x00161307, 0x00161307, 0x00161307, 0x00161307, 0x00171308, 0x00171308, 0x00171408, 0x00171408, 0x00171408, 0x00171408, 0x00161208, 0x00161208, 0x00161208, 0x00171309, 0x00171208, 0x00181108, 0x00181309, 0x00181309, 0x00171309, 0x00171309, 0x00181309, 0x001b130b, 0x001c140a, 0x00201408, 0x00211406, 0x00261607, 0x002a1a09, 0x002e1c0c, 0x00321d0a, 0x003a2008, 0x0060421c, 0x00724c11, 0x008d5f0e, 0x00ba8a21, 0x00c49a18, 0x00c8a313, 0x00caa711, 0x00ccaa10, 0x00cbab0c, 0x00cbac0c, 0x00ccb00e, 0x00ccb00e, 0x00ccb10d, 0x00cbb10c, 0x00c8b208, 0x00cab40b, 0x00cbb60a, 0x00cbb509, 0x00cbb509, 0x00ccb40a, 0x00ccb40a, 0x00cbb409, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00ccb508, 0x00cbb408, 0x00cbb408, 0x00ccb307, 0x00ccb308, 0x00ccb210, 0x00c9a410, 0x00ad7a02, 0x00a06402, 0x00b47c18, 0x00cba727, 0x00ccb418, 0x00cbb90d, 0x00cbbc0c, 0x00ccb80c, 0x00ccb310, 0x00ba9507, 0x009d6e00, 0x008c5b01, 0x00835107, 0x007f5008, 0x007a5006, 0x007a500c, 0x00794f0b, 0x00794f0b, 0x007b500d, 0x007c510c, 0x0080540a, 0x00875809, 0x008f600b, 0x009f6e0e, 0x00b98f19, 0x00caa81c, 0x00ccb61c, 0x00cab70e, 0x00ccb60b, 0x00ccb015, 0x00bc9612, 0x008b6200, 0x00704900, 0x00603c00, 0x00563506, 0x004f3005, 0x004c3007, 0x00482e08, 0x00452c08, 0x00402705, 0x00402506, 0x003e2508, 0x003c2509, 0x003a2409, 0x00362007, 0x00352007, 0x00342008, 0x00331f07, 0x00331e0a, 0x00341d0a, 0x00341c0b, 0x00341c0c, 0x00311a0a, 0x002f1b0a, 0x002c1c0c, 0x002b1c0c, 0x00281c0c, 0x00211809, 0x001d1508, 0x001b1408, 0x00161305, 0x00131004, 0x00100e02, 0x000c0e00, 0x00080e00, 0x00090f02, 0x000a1002, 0x000b0e02, 0x000d0e02, 0x00121004, 0x00181508, 0x0017150b, 0x00121006, 0x00100d02, 0x00100d01, 0x000f0e04, 0x000f0f05, 0x000c0f05, 0x00090f06, 0x00090f06, 0x00090e05, 0x00090e05, 0x000b0e05, 0x000b0e05, 0x000c1007, 0x0010130a, 0x00141810, 0x00191e17, 0x00171c15, 0x00171c17, 0x00182018, 0x00182018, 0x00192018, 0x00192018, 0x001b201a, 0x001c201b, 0x001c201b, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x0014180b, 0x00191c09, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x002d2f0a, 0x0030310c, 0x0032330c, 0x0036370c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x003e400c, 0x0040400d, 0x0041420d, 0x0043440e, 0x0044450e, 0x0045470e, 0x0045470e, 0x0047480e, 0x0048490f, 0x0048490f, 0x00494a0f, 0x00494a0f, 0x004b4c10, 0x00494a0f, 0x00494a0f, 0x004b4c10, 0x00494a0f, 0x00494a0f, 0x0048490f, 0x0047480e, 0x0047480e, 0x0045470e, 0x0044450e, 0x0043440e, 0x0041420e, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x00393b0d, 0x0038380c, 0x0036370c, 0x0032330c, 0x0030310c, 0x0030310b, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x001a1b15, 0x001a1b15, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x0013160f, 0x000c1008, 0x000d1008, 0x000d1007, 0x000c1005, 0x000d0f05, 0x000d1004, 0x000e0f04, 0x00141308, 0x0018130a, 0x001b1309, 0x00191007, 0x00180f04, 0x001c1207, 0x001f150a, 0x0022180d, 0x00241a0c, 0x00271d0c, 0x002c200d, 0x002e200b, 0x0030220a, 0x0033240a, 0x0034230a, 0x0038240c, 0x0039240b, 0x003c2509, 0x0040290c, 0x00422c0c, 0x00442d0d, 0x00442f0d, 0x00442f0c, 0x0046300a, 0x0049330c, 0x004d360f, 0x004e360e, 0x0051380d, 0x0052390a, 0x00543a0a, 0x0059400c, 0x005c400d, 0x005f420f, 0x00654610, 0x006b4b10, 0x006e4d0f, 0x0070500f, 0x0076540f, 0x007c5811, 0x00765006, 0x00714900, 0x007e5505, 0x00ac8629, 0x00cbaa34, 0x00ccb51e, 0x00caba09, 0x00c8bb04, 0x00ccb70b, 0x00c7a512, 0x00a67802, 0x008f5900, 0x00804c00, 0x00754804, 0x006a4602, 0x00664204, 0x00644008, 0x00643f08, 0x00643e07, 0x00653e08, 0x00653e08, 0x00664009, 0x006c460c, 0x00714b0d, 0x00784e0c, 0x00845510, 0x009d6f13, 0x00c39c22, 0x00cbb419, 0x00c8b909, 0x00c8bb05, 0x00ccb80c, 0x00cbb017, 0x00aa7d04, 0x00945e00, 0x00a87410, 0x00caa022, 0x00ccb118, 0x00cab40d, 0x00cab50c, 0x00cbb608, 0x00c9b80a, 0x00c9b80a, 0x00cbb80b, 0x00cbb909, 0x00cbb909, 0x00cbb909, 0x00cbb80a, 0x00cbb80b, 0x00cbb80b, 0x00cbb90a, 0x00ccb80a, 0x00ccb80b, 0x00ccb80c, 0x00ccb70d, 0x00ccb70d, 0x00ccb60c, 0x00cbb60a, 0x00cab50c, 0x00ccb50d, 0x00ccb20f, 0x00cbae10, 0x00c9aa12, 0x00c5a413, 0x00c09c12, 0x00b4900f, 0x009e7a09, 0x008c6004, 0x00825810, 0x006d4910, 0x004c2f04, 0x003b2604, 0x00332106, 0x002e1c04, 0x00281704, 0x00241406, 0x00231407, 0x001f1205, 0x001d1104, 0x001a1305, 0x00181306, 0x00151306, 0x00151308, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00181309, 0x00181309, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x00181407, 0x001a1405, 0x001a1305, 0x001a1204, 0x001b1206, 0x001a1206, 0x00191307, 0x001b1407, 0x00181105, 0x00161104, 0x00181306, 0x00181205, 0x00181205, 0x00171406, 0x00171406, 0x00171406, 0x00171406, 0x00171408, 0x00171408, 0x00171408, 0x00171408, 0x00161308, 0x00161208, 0x00171309, 0x00171309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00171309, 0x00171309, 0x00181309, 0x001b130b, 0x001c140a, 0x001f1308, 0x00211406, 0x00251507, 0x00291909, 0x002d1c0d, 0x00301c0c, 0x00351e08, 0x00513613, 0x006a4715, 0x007a4e0e, 0x00905e09, 0x00a06c04, 0x00a87403, 0x00ac7c08, 0x00b5860c, 0x00bb8d0d, 0x00c0940e, 0x00c49a10, 0x00c89f14, 0x00c9a115, 0x00cca717, 0x00caac12, 0x00ccb013, 0x00cbb012, 0x00cbb010, 0x00cbb010, 0x00ccb110, 0x00cab110, 0x00cbb30e, 0x00cbb50b, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00ccb508, 0x00cbb408, 0x00cbb408, 0x00ccb307, 0x00ccb307, 0x00ccb10c, 0x00c9a50c, 0x00ad7c00, 0x00a16600, 0x00b47e13, 0x00cca821, 0x00ccb614, 0x00cab80e, 0x00cbbb0e, 0x00ccb80c, 0x00ccad0c, 0x00ad8000, 0x00976300, 0x00885503, 0x007f5009, 0x007b5008, 0x00784f05, 0x007a4e0c, 0x007a4d0c, 0x007a4d0c, 0x007c5010, 0x007c5010, 0x007f5111, 0x00825210, 0x0085540f, 0x008d5b09, 0x009e6d09, 0x00c29a1b, 0x00ccb119, 0x00c9b709, 0x00cab806, 0x00ccb40f, 0x00c8a812, 0x009e7803, 0x007e5200, 0x006b4202, 0x00623d0a, 0x005a3809, 0x00533408, 0x00503208, 0x004c3008, 0x004a2e09, 0x00492c09, 0x00482d0b, 0x00452b0a, 0x0042280a, 0x0040270c, 0x003f270d, 0x003c250b, 0x00382108, 0x00382008, 0x00382008, 0x00381f09, 0x00371d09, 0x00361d09, 0x00311c08, 0x002e1c08, 0x002d1c0a, 0x002c1d0b, 0x002a1c0b, 0x00271c0a, 0x00251a0a, 0x00211808, 0x0021150b, 0x001d1409, 0x00160f03, 0x00100d01, 0x000e1003, 0x000c0f03, 0x000c0e04, 0x000c0f03, 0x000a0d00, 0x00131408, 0x0018150c, 0x00151208, 0x00130f04, 0x00131004, 0x00100f06, 0x000f0f05, 0x000c0f05, 0x000a0f06, 0x000a0f06, 0x00090e05, 0x00090e05, 0x000b0e05, 0x000b0e05, 0x000c1007, 0x000e1109, 0x0010160c, 0x00171b14, 0x00161b14, 0x00161b15, 0x00181f17, 0x00181f17, 0x00192018, 0x00192018, 0x001b201a, 0x001c201b, 0x001c201b, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0b, 0x00191c09, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0b, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x00393b0c, 0x00393b0d, 0x003b3c0d, 0x003c3e0c, 0x003e400c, 0x0041420d, 0x0041420e, 0x0043440e, 0x0044450e, 0x0044450e, 0x0044450d, 0x0045470e, 0x0047480e, 0x0047480e, 0x0045470e, 0x0045470e, 0x0047480e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0044450e, 0x0043440e, 0x0043440e, 0x0041420d, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0b, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c16, 0x00181c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181b14, 0x0012150f, 0x000d1009, 0x000d1008, 0x000c1007, 0x000c1005, 0x000e1005, 0x000f1004, 0x00101105, 0x0017140a, 0x0018140b, 0x001b1308, 0x001b1106, 0x00231508, 0x00251508, 0x00281809, 0x002b1c0b, 0x002c1e0c, 0x002f200c, 0x0033220c, 0x0034230a, 0x0035250a, 0x0037280b, 0x00382909, 0x003d2c0c, 0x003e2c0c, 0x00402c0c, 0x00442e0b, 0x0048300c, 0x004a300a, 0x004c320b, 0x004f340c, 0x004f3409, 0x0053370b, 0x00583c0f, 0x00583b0c, 0x005c400c, 0x005d440b, 0x0063450b, 0x006b490d, 0x00745011, 0x007a5412, 0x00815910, 0x008c6411, 0x00957016, 0x00a17e20, 0x00ac8a26, 0x00b5922b, 0x00966d0c, 0x007c4f00, 0x008b5f09, 0x00bc952e, 0x00cbaf28, 0x00ccb715, 0x00cab909, 0x00cbbb04, 0x00ccb60c, 0x00b79406, 0x00946600, 0x00834f00, 0x00764800, 0x006c4502, 0x00674502, 0x00644307, 0x0064400b, 0x00643f07, 0x00623d03, 0x00633e03, 0x00654006, 0x00684209, 0x006c440c, 0x00744b10, 0x0079500c, 0x0087590e, 0x00a77a1a, 0x00c9a428, 0x00ccb41a, 0x00c9b80d, 0x00c8b909, 0x00ccb70e, 0x00cba717, 0x00a47203, 0x00945f00, 0x00b4821b, 0x00cca523, 0x00ccb115, 0x00c9b40c, 0x00c8b608, 0x00c8b705, 0x00c8b70b, 0x00c9b80c, 0x00cbb80b, 0x00ccb90c, 0x00cbb809, 0x00cbb809, 0x00ccb809, 0x00ccb808, 0x00ccb806, 0x00ccb806, 0x00cbb809, 0x00cbb70c, 0x00ccb60d, 0x00ccb40d, 0x00ccb310, 0x00ccb010, 0x00ccae10, 0x00ccab11, 0x00cca817, 0x00c69f15, 0x00b9900f, 0x00ab8007, 0x00a07403, 0x00936801, 0x00855b00, 0x00775000, 0x006c4501, 0x0067430c, 0x00523305, 0x003f2500, 0x00362201, 0x00312004, 0x002c1c02, 0x00251804, 0x00241707, 0x00201406, 0x001d1307, 0x001b1205, 0x00191107, 0x00181207, 0x00171307, 0x00171308, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x0018140a, 0x0018140a, 0x00181309, 0x00181308, 0x001a1308, 0x001a1407, 0x001a1407, 0x001b1307, 0x001a1407, 0x001b1407, 0x001b1406, 0x001a1305, 0x001a1306, 0x001b1307, 0x001a1407, 0x001a1306, 0x00181004, 0x00161105, 0x00171307, 0x00171307, 0x00181307, 0x00181307, 0x00191207, 0x00191207, 0x00181307, 0x00181306, 0x00181307, 0x00181307, 0x00181307, 0x00181306, 0x00181208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191307, 0x001c1308, 0x001c1408, 0x001f1408, 0x00211407, 0x00241406, 0x00281809, 0x002c1c0d, 0x002e1c0c, 0x00321d08, 0x00392106, 0x0052320c, 0x0068400e, 0x0078490c, 0x00814f07, 0x00895406, 0x008c5607, 0x008f5904, 0x00925d00, 0x00986401, 0x009f6b01, 0x00a67004, 0x00ae7809, 0x00b47f0c, 0x00b8880b, 0x00ba8c0c, 0x00c39814, 0x00c89d17, 0x00cba016, 0x00cca415, 0x00cba612, 0x00ccab14, 0x00ccae0f, 0x00ccb00d, 0x00ccb10b, 0x00cab20a, 0x00c9b70b, 0x00c8b609, 0x00c8b409, 0x00cbb40b, 0x00c8b307, 0x00c8b406, 0x00cab406, 0x00ccb307, 0x00ccb208, 0x00ccb20c, 0x00c8a50c, 0x00af7f00, 0x00a16700, 0x00b78015, 0x00cca820, 0x00ccb513, 0x00cab80a, 0x00cabb0c, 0x00ccb80c, 0x00c9a80d, 0x00ad7c01, 0x00955d01, 0x00865405, 0x007a5008, 0x00765007, 0x00744e04, 0x00774c0b, 0x00794c0c, 0x007a4d0c, 0x007c500f, 0x007c500d, 0x007d5110, 0x00805110, 0x0080510f, 0x0084560c, 0x0093600c, 0x00ac7f11, 0x00c9a91b, 0x00c8b60b, 0x00c8b906, 0x00cbb60c, 0x00ccb114, 0x00b38c0c, 0x00885b00, 0x00784a06, 0x0073470e, 0x00684006, 0x00633e05, 0x005e3b09, 0x0057360a, 0x0055340c, 0x00513008, 0x004f2e08, 0x004d2e0b, 0x004a2c0c, 0x00492a0e, 0x00462a0e, 0x0042290c, 0x003f280b, 0x003d2608, 0x003d2407, 0x003c240a, 0x003a220a, 0x00382108, 0x00362108, 0x00332008, 0x002f1d07, 0x002e1c08, 0x002d1d08, 0x002d1c09, 0x002c1c0a, 0x002b1b09, 0x002b1a0c, 0x002a190c, 0x0024150a, 0x001c1005, 0x00151004, 0x00111005, 0x000f1106, 0x00091003, 0x00080e01, 0x00111407, 0x0018160c, 0x001a140a, 0x00181108, 0x00151006, 0x00121004, 0x00100f06, 0x000e1007, 0x000c1007, 0x000c1006, 0x000b0f06, 0x000a0f06, 0x000a0f04, 0x000c0f04, 0x000c1006, 0x000d1008, 0x0010150c, 0x00151a12, 0x00161b14, 0x00161b15, 0x00181d18, 0x00181e18, 0x00181f18, 0x00192019, 0x001b201a, 0x001b211a, 0x001b2019, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0b, 0x00191c09, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0024250b, 0x0026280b, 0x00292b0a, 0x002c2d0a, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x003c3e0d, 0x003c3e0c, 0x0040400d, 0x0040400d, 0x0040400d, 0x0041420e, 0x0041420e, 0x0043440e, 0x0043440e, 0x0044450e, 0x0044450e, 0x0043440e, 0x0043440e, 0x0041420e, 0x0041420d, 0x0040400d, 0x0040400d, 0x003e400c, 0x003c3e0c, 0x003c3e0d, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x002c2d0b, 0x0026280b, 0x0026280c, 0x0024250b, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x00191c16, 0x00171a14, 0x0011140d, 0x000d100a, 0x000c1008, 0x000c1007, 0x000d1008, 0x000f1005, 0x00101005, 0x00151408, 0x0018150a, 0x00181409, 0x001a1307, 0x00211609, 0x0029190b, 0x002c190a, 0x002d1c09, 0x00301f09, 0x0032220b, 0x0035240e, 0x003a270f, 0x003c280d, 0x003d2c0c, 0x003f2d0c, 0x0040300a, 0x0048330c, 0x0048340f, 0x00483410, 0x004c3410, 0x0050380f, 0x0050380b, 0x00533a0b, 0x00583d0c, 0x005c3d0b, 0x0061400d, 0x0065400a, 0x006a4409, 0x00704b0a, 0x0077530c, 0x00805910, 0x008c6416, 0x00987019, 0x00a77c20, 0x00b48b22, 0x00bf9824, 0x00c8a729, 0x00caad26, 0x00ccb529, 0x00cbb128, 0x00ae8810, 0x008b5f00, 0x0091670c, 0x00c29c29, 0x00caaf1c, 0x00ccb70f, 0x00ccb80d, 0x00ccb90a, 0x00ccb510, 0x00ba980d, 0x00946a00, 0x00815300, 0x00784b04, 0x00704708, 0x006c4609, 0x0068450d, 0x00674410, 0x0065420c, 0x00634008, 0x00624007, 0x0066450c, 0x0069470f, 0x006d4810, 0x00784f15, 0x007f540f, 0x00906712, 0x00b99224, 0x00ccad24, 0x00ccb711, 0x00cab909, 0x00ccb90c, 0x00ccb20d, 0x00bf920f, 0x00986400, 0x009c6806, 0x00c29424, 0x00cca920, 0x00ccb012, 0x00ccb10c, 0x00cbb404, 0x00c9b604, 0x00cab60b, 0x00cbb60c, 0x00ccb50c, 0x00ccb60c, 0x00cbb40c, 0x00cbb40c, 0x00cab40c, 0x00cbb40a, 0x00ccb509, 0x00ccb509, 0x00ccb30e, 0x00caae0e, 0x00ccac12, 0x00c8a40f, 0x00c49f10, 0x00c0980e, 0x00ba900b, 0x00b18407, 0x00a87804, 0x00986801, 0x008d5c00, 0x00825300, 0x007d5000, 0x00744901, 0x00704404, 0x00603900, 0x00533100, 0x004c2f03, 0x003f2700, 0x00382200, 0x00342103, 0x002e1f03, 0x002a1c02, 0x00241804, 0x00221807, 0x001e1508, 0x001c1407, 0x001a1107, 0x00191107, 0x00181107, 0x00171207, 0x00171308, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x0019140b, 0x0019140b, 0x00181309, 0x00181308, 0x001b1308, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001a1407, 0x001a1407, 0x001b1407, 0x001b1407, 0x00191306, 0x00181004, 0x00151106, 0x00161307, 0x00171408, 0x00181308, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00181306, 0x00181404, 0x00181404, 0x00181404, 0x00191305, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001b1206, 0x001b1206, 0x001c1305, 0x001c1407, 0x001f1408, 0x00221507, 0x00241406, 0x00281808, 0x002c1c0c, 0x002d1c0a, 0x00301b08, 0x00321c07, 0x00371c00, 0x00442402, 0x00532e06, 0x005d3405, 0x00683906, 0x006e3f06, 0x00724305, 0x00774804, 0x007d4d05, 0x00855206, 0x008c5506, 0x00925803, 0x00975d02, 0x009a6000, 0x009e6401, 0x00a46b04, 0x00a86f04, 0x00ad7405, 0x00b27904, 0x00b88508, 0x00be8e0c, 0x00c4940d, 0x00c89d11, 0x00cca515, 0x00cca814, 0x00cbab10, 0x00c8ad0c, 0x00caaf0e, 0x00ccb10f, 0x00ccb30c, 0x00ccb40c, 0x00ccb40a, 0x00cbb308, 0x00cbb309, 0x00ccb20f, 0x00c8a50e, 0x00b28204, 0x009f6500, 0x00b27c12, 0x00cba623, 0x00ccb414, 0x00c9b808, 0x00c9ba0a, 0x00ccb70f, 0x00caaa0f, 0x00ae8000, 0x00945f00, 0x00875406, 0x007c5108, 0x00755109, 0x00744f07, 0x00784e0b, 0x00784e0b, 0x00784f0c, 0x0079500c, 0x007b500a, 0x007c500b, 0x007c500b, 0x007d510c, 0x007d5409, 0x0089590c, 0x009f700e, 0x00c4a01c, 0x00c8b410, 0x00c8b809, 0x00cab60d, 0x00ccb312, 0x00c09b13, 0x00936400, 0x00804f04, 0x0080500e, 0x007c4d08, 0x00764804, 0x00724608, 0x006e430d, 0x00684010, 0x00633c0c, 0x005d3709, 0x0058330a, 0x0054300c, 0x0051300c, 0x004c2f0a, 0x00482e08, 0x00462e09, 0x00462e0a, 0x00452b09, 0x0043280a, 0x00402709, 0x003f2508, 0x003d260a, 0x003c250b, 0x0039230b, 0x00362008, 0x00352008, 0x00342009, 0x00321d0a, 0x00311b08, 0x00301c08, 0x00301c0a, 0x002c1909, 0x0028180a, 0x00201609, 0x00181306, 0x00141407, 0x000c1104, 0x000c1104, 0x00111206, 0x0019150b, 0x001e150c, 0x001c1409, 0x00161006, 0x00131005, 0x00100f08, 0x000f0f08, 0x000c1007, 0x000c1007, 0x000c0f06, 0x000a0f06, 0x000a1004, 0x000c0f04, 0x000c1005, 0x000c1006, 0x0010140c, 0x00141910, 0x00161b15, 0x00161b15, 0x00181e18, 0x00181e18, 0x00181e18, 0x0019201a, 0x001a2019, 0x001b2119, 0x001a2018, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x00202309, 0x0024250c, 0x0026280b, 0x00292b0b, 0x002c2d0b, 0x002c2d0a, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x0038380c, 0x0038380c, 0x003b3c0d, 0x003b3c0d, 0x003b3c0d, 0x003c3e0d, 0x003c3e0c, 0x003e400c, 0x003e400c, 0x0040400c, 0x003e400c, 0x003e400c, 0x0040400c, 0x003e400c, 0x003e400c, 0x003c3e0c, 0x003c3e0d, 0x003b3c0d, 0x003b3c0d, 0x00393b0c, 0x0038380c, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002d2f0b, 0x002c2d0a, 0x00292b0b, 0x0026280b, 0x0024250c, 0x0020230a, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180c, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x00161913, 0x0010140d, 0x000d110a, 0x000c1008, 0x000d1009, 0x000d1008, 0x000f1006, 0x00141307, 0x00181708, 0x00191509, 0x001a1509, 0x001e1507, 0x00261b0b, 0x002c1d0a, 0x002f1e0b, 0x00302009, 0x0033230b, 0x0037270c, 0x003c290d, 0x00412c10, 0x00452e0f, 0x0046310c, 0x0048340b, 0x004c340a, 0x0050380c, 0x0052390e, 0x0051380f, 0x00553b10, 0x005c3f10, 0x005d410e, 0x005e440d, 0x0064460c, 0x006c480b, 0x00744c0c, 0x007b500b, 0x0086590f, 0x00946512, 0x00a37319, 0x00ac821f, 0x00b89325, 0x00c29e27, 0x00c8a628, 0x00ccad25, 0x00ccb11e, 0x00ccb518, 0x00ccb812, 0x00ccbc12, 0x00cbb91c, 0x00b4950c, 0x008f6500, 0x008c6201, 0x00c09c24, 0x00caae18, 0x00ccb60c, 0x00ccb80d, 0x00ccb80d, 0x00ccb511, 0x00c8a918, 0x00a78209, 0x008e6200, 0x00845606, 0x00794f08, 0x00744b09, 0x00714a0d, 0x006f4812, 0x006c440e, 0x0069430c, 0x0068440c, 0x006b480f, 0x006d490e, 0x00744c10, 0x007c5312, 0x008d6313, 0x00ab8523, 0x00c7a828, 0x00ccb518, 0x00ccb90b, 0x00cab806, 0x00cbb30c, 0x00c8a30d, 0x00ab7b07, 0x00905d00, 0x00ac7c13, 0x00c89e24, 0x00cba81b, 0x00ccac12, 0x00ccb00f, 0x00ccb20a, 0x00cab309, 0x00cbb40c, 0x00ccb40c, 0x00cbb40c, 0x00cbb40c, 0x00cbb20e, 0x00ccb010, 0x00ccad11, 0x00c9a90f, 0x00c7a510, 0x00c4a00e, 0x00c09c10, 0x00b8900b, 0x00af8409, 0x00a67a05, 0x009c6d01, 0x00936400, 0x008d5c00, 0x00885901, 0x00845501, 0x007a4c00, 0x00704400, 0x00694004, 0x00643d05, 0x005b3704, 0x00543204, 0x004e3001, 0x00472a01, 0x00402703, 0x00382202, 0x00342004, 0x002f1e05, 0x002c1e08, 0x00281c06, 0x00231905, 0x00201705, 0x001d1407, 0x001b1406, 0x001a1107, 0x00191107, 0x00181208, 0x00171207, 0x00171308, 0x00181209, 0x00181209, 0x00181309, 0x00181309, 0x00181209, 0x00181209, 0x00181309, 0x00181309, 0x0019140b, 0x0019140b, 0x00181309, 0x00181308, 0x001b1308, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001a1306, 0x00181105, 0x00161207, 0x00181408, 0x00171408, 0x00181408, 0x001a1208, 0x001a1208, 0x001a1208, 0x001a1208, 0x00181306, 0x00181404, 0x00181404, 0x00181404, 0x00191305, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001b1206, 0x001b1206, 0x001c1305, 0x001c1406, 0x001f1408, 0x00231608, 0x00251508, 0x00271708, 0x002c1c0b, 0x002d1c0a, 0x00301b09, 0x00311c08, 0x00321d08, 0x00331d05, 0x00391d04, 0x00432206, 0x00492603, 0x004d2900, 0x00502d00, 0x00553101, 0x005c3704, 0x00653b05, 0x006b3d04, 0x00744406, 0x007c4905, 0x00834f04, 0x00875207, 0x008a5607, 0x008c5606, 0x008f5704, 0x00925a04, 0x00955d02, 0x009b6301, 0x009f6700, 0x00a66e02, 0x00ab7306, 0x00b27b0b, 0x00b9840c, 0x00be8d0a, 0x00c1940d, 0x00c59910, 0x00c9a111, 0x00caa50e, 0x00ccaa0f, 0x00ccad0e, 0x00ccb111, 0x00ccab14, 0x00caa316, 0x00b6850c, 0x009c6400, 0x00a97210, 0x00c8a124, 0x00cbb318, 0x00c9b70c, 0x00c9b80c, 0x00ccb70f, 0x00cbaf10, 0x00af8802, 0x00946300, 0x00885401, 0x007e5005, 0x00795009, 0x00755009, 0x00784e0a, 0x00784e0a, 0x00784f0b, 0x0079500b, 0x007b4f09, 0x007b500a, 0x007b500a, 0x007c510b, 0x007c5208, 0x0087560a, 0x00976709, 0x00bc9619, 0x00c9b114, 0x00c8b70c, 0x00cab70c, 0x00ccb411, 0x00c6a316, 0x009e7001, 0x008b5804, 0x009a6719, 0x00a16f1b, 0x0096650f, 0x00895806, 0x00865308, 0x0081510c, 0x007b4b0b, 0x00744609, 0x006e410a, 0x00683c08, 0x005f3807, 0x00593606, 0x00543407, 0x00503408, 0x00503409, 0x004c3107, 0x004c2f08, 0x004a2c08, 0x00452907, 0x00442807, 0x0044270a, 0x00412609, 0x003e2408, 0x003c2408, 0x003b240a, 0x003b230b, 0x00382008, 0x00362008, 0x00341f07, 0x00311d08, 0x002f1b09, 0x002c1a0c, 0x00261a0c, 0x001d1608, 0x00141205, 0x00141105, 0x00141004, 0x00191208, 0x0020160b, 0x001e150b, 0x00181206, 0x00151006, 0x00120f08, 0x000f0f08, 0x000e0e07, 0x000c0f07, 0x000c1006, 0x000a1006, 0x000a1004, 0x000c0f04, 0x000c1005, 0x000c0f04, 0x000d1309, 0x0012170f, 0x00151a14, 0x00161a16, 0x00171d18, 0x00181e18, 0x00181e18, 0x00181f19, 0x001a2019, 0x001b2119, 0x001a2018, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x0024250b, 0x0024250b, 0x0026280b, 0x00292b0b, 0x002c2d0a, 0x002d2f0a, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0032330c, 0x0036370c, 0x0036370c, 0x0036370b, 0x0038380c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x00393b0d, 0x00393b0d, 0x00393b0d, 0x00393b0d, 0x00393b0d, 0x003b3c0d, 0x00393b0d, 0x00393b0c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0034350c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0030310c, 0x002d2f0a, 0x002c2d0a, 0x002c2d0b, 0x0026280b, 0x0026280c, 0x0024250b, 0x00202309, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x001b1d17, 0x001a1c16, 0x00131610, 0x000d120b, 0x000d120b, 0x000c100a, 0x000d120b, 0x000e1108, 0x00121207, 0x00151407, 0x001a1809, 0x001b1608, 0x001d1507, 0x00241909, 0x002b1e0c, 0x0030200c, 0x0034240d, 0x0035250c, 0x0038280c, 0x003f2c0e, 0x00432f0f, 0x0048310f, 0x004c340f, 0x0050370e, 0x00533b0c, 0x00573d0c, 0x005c400c, 0x0061430f, 0x00654310, 0x006b4710, 0x00704b11, 0x00754f0f, 0x0078520c, 0x0080580c, 0x008f6611, 0x009a7015, 0x00a77c20, 0x00b68b28, 0x00c09826, 0x00c8a126, 0x00caa920, 0x00caae1b, 0x00cab219, 0x00cbb618, 0x00cbb817, 0x00ccb812, 0x00cbbb10, 0x00c9bd0d, 0x00cabd0e, 0x00cab814, 0x00b99a0c, 0x00956800, 0x00906001, 0x00b08816, 0x00cbae1a, 0x00cbb40c, 0x00cbb80d, 0x00cab80c, 0x00ccb80d, 0x00ccb417, 0x00c6a81b, 0x00ac880f, 0x009a7008, 0x00885f04, 0x00825704, 0x007e5208, 0x00794d09, 0x00764c09, 0x00764b0b, 0x00744b0a, 0x00754d08, 0x00785006, 0x00825708, 0x00916611, 0x00ae8724, 0x00c6a430, 0x00ccb424, 0x00c9b910, 0x00ccba0c, 0x00cbb50f, 0x00cbae1a, 0x00b6870c, 0x00945d00, 0x009b6408, 0x00bd8c24, 0x00c79921, 0x00c49914, 0x00c59b10, 0x00c8a011, 0x00cba513, 0x00cca913, 0x00ccaa14, 0x00cca912, 0x00cba811, 0x00cba711, 0x00c8a211, 0x00c49b10, 0x00bd930f, 0x00b08406, 0x00a47704, 0x009e6f04, 0x00946400, 0x008c5c00, 0x00895800, 0x00815200, 0x007c4c00, 0x007a4801, 0x00754403, 0x006f4104, 0x00694004, 0x00603c02, 0x00583801, 0x00533506, 0x00503307, 0x00492e07, 0x00432b04, 0x00402807, 0x003e2708, 0x003a2309, 0x00372008, 0x00301e08, 0x002c1e08, 0x00291c09, 0x00231908, 0x00221805, 0x00201604, 0x001c1407, 0x001a1306, 0x001a1107, 0x00191108, 0x001a1308, 0x00171207, 0x00161207, 0x00171008, 0x00181108, 0x00181309, 0x00181309, 0x00181108, 0x00181108, 0x00181309, 0x00181309, 0x0019140b, 0x0019140b, 0x00191209, 0x00191208, 0x001b1308, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1408, 0x00181206, 0x00171408, 0x0018150a, 0x00181408, 0x00181408, 0x001b1308, 0x001b1308, 0x001b1308, 0x001b1308, 0x00181306, 0x00181404, 0x00181404, 0x00181404, 0x00191305, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001c1307, 0x001c1307, 0x001c1305, 0x001c1305, 0x001f1408, 0x0023170a, 0x00251709, 0x0027170a, 0x0029190b, 0x002b1908, 0x002e1a09, 0x00301c0a, 0x002e1d09, 0x00301e0a, 0x00351e09, 0x003d210b, 0x00432408, 0x00462806, 0x00482908, 0x00482908, 0x00492c08, 0x004a2b07, 0x004d2b03, 0x00543003, 0x00593101, 0x005e3401, 0x00633804, 0x00663c04, 0x00683f04, 0x0074480d, 0x00794c0d, 0x007e4e0c, 0x0084510a, 0x008b5409, 0x008f5609, 0x00905607, 0x00955908, 0x00975c05, 0x00996002, 0x009d6604, 0x00a36c04, 0x00a87204, 0x00b07c08, 0x00b8840a, 0x00c08d0f, 0x00c59412, 0x00c79a17, 0x00c89c1d, 0x00c08c1d, 0x00a06708, 0x009a6404, 0x00b8911a, 0x00cab01c, 0x00c9b613, 0x00cbb80f, 0x00ccb80f, 0x00ccb411, 0x00bc9a0c, 0x009a6e00, 0x008e5a00, 0x00845004, 0x007e520b, 0x0079540d, 0x007a500c, 0x00784f0b, 0x0078500b, 0x0079500c, 0x007b500c, 0x007c510c, 0x007d520d, 0x0080540e, 0x007c5308, 0x0087560c, 0x0095650b, 0x00bc941e, 0x00cab11a, 0x00c9b70f, 0x00cab70c, 0x00ccb50f, 0x00c9a814, 0x00a77801, 0x00976202, 0x00b67f24, 0x00c7962f, 0x00c09222, 0x00b7881b, 0x00ab7910, 0x00a06c0a, 0x00935e07, 0x008b5705, 0x00875407, 0x00815006, 0x007a4b08, 0x00754809, 0x006f440c, 0x00623c05, 0x005c3c09, 0x00583908, 0x0055380a, 0x00523409, 0x004e3108, 0x004c3008, 0x004b2f0b, 0x00482d0c, 0x00462c0a, 0x00442b0a, 0x00432a0b, 0x0041250a, 0x00402408, 0x003e2408, 0x003b2306, 0x00382108, 0x00351f09, 0x00361c0e, 0x00311c0e, 0x0027170a, 0x00201608, 0x001e150b, 0x001e140b, 0x001c1208, 0x001f160b, 0x0020180c, 0x001c1408, 0x00181108, 0x0015110a, 0x0013100a, 0x00101008, 0x000f0e06, 0x000d0f06, 0x000b1006, 0x000a1004, 0x000c0f04, 0x000c0f04, 0x000c0f04, 0x000c1106, 0x0010140c, 0x00141914, 0x00151916, 0x00151b15, 0x00171d18, 0x00181e18, 0x00181f19, 0x001a2019, 0x001b2119, 0x00192018, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x00202309, 0x0024250b, 0x0024250b, 0x00292b0b, 0x00292b0b, 0x00292b0a, 0x002c2d0a, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0030310c, 0x0034350c, 0x0032330c, 0x0036370c, 0x0034350c, 0x0036370c, 0x0036370c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0036370c, 0x0036370c, 0x0034350c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x00292b0a, 0x00292b0a, 0x0026280b, 0x0026280c, 0x0024250c, 0x0020230a, 0x00202308, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x001b1e18, 0x00181c15, 0x0010140c, 0x000d120b, 0x000d120b, 0x000c110a, 0x000e1109, 0x00101208, 0x00141307, 0x00181407, 0x001c1809, 0x001a1405, 0x001f1606, 0x00281c09, 0x002f200b, 0x0035250c, 0x003a2a0f, 0x003e2c0e, 0x0042300e, 0x00483410, 0x004c3610, 0x00533811, 0x00583a10, 0x005f3f12, 0x00654611, 0x00694a0f, 0x006f4f0f, 0x0074500f, 0x007f520f, 0x0084570f, 0x00906214, 0x00986b15, 0x00a67a16, 0x00b08518, 0x00ba901c, 0x00c59d21, 0x00c8a527, 0x00c9aa24, 0x00ccb223, 0x00ccb418, 0x00ccb510, 0x00cbb80c, 0x00c9b90d, 0x00c8ba10, 0x00c9bb0f, 0x00cbbb0f, 0x00cabb10, 0x00c8bb10, 0x00c7ba10, 0x00c9b712, 0x00c1a010, 0x00a37402, 0x008c5800, 0x00966c06, 0x00bf9c19, 0x00ccb316, 0x00cbb80f, 0x00c8ba08, 0x00caba09, 0x00cbb90f, 0x00ccb514, 0x00cbae1c, 0x00c4a31f, 0x00b6911b, 0x00a67f11, 0x0099710c, 0x0092690c, 0x008c6208, 0x008a5f08, 0x008a6008, 0x0090650b, 0x00996e10, 0x00aa7e19, 0x00be9428, 0x00c6a42b, 0x00c9af24, 0x00cab818, 0x00c8bc0d, 0x00ccb90f, 0x00ccb218, 0x00b79014, 0x00996203, 0x008a4d00, 0x00955809, 0x00ab711b, 0x00a46c0d, 0x00a06704, 0x00a16803, 0x00a46d04, 0x00ab7608, 0x00b17d0c, 0x00b37e0c, 0x00b27d0b, 0x00ad7805, 0x00ad7807, 0x00a36e02, 0x00986400, 0x00905c00, 0x00895700, 0x00825100, 0x007c4c00, 0x00784901, 0x00734701, 0x006e4300, 0x00673d00, 0x00643b00, 0x00613802, 0x00603605, 0x005a3505, 0x00553404, 0x00513406, 0x004c3407, 0x00493307, 0x00473108, 0x00422e04, 0x003d2a04, 0x003b270c, 0x003b250d, 0x0036200a, 0x00331d0a, 0x002e1c0a, 0x00291a08, 0x00261a09, 0x00201807, 0x00201607, 0x001f1406, 0x001c1306, 0x001a1306, 0x00191107, 0x001a1208, 0x00191308, 0x00171307, 0x00161207, 0x00161008, 0x00171008, 0x00181208, 0x00181209, 0x00181208, 0x00181108, 0x00181209, 0x00181209, 0x0019140a, 0x0019140a, 0x00191208, 0x00191208, 0x001b1308, 0x001b1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001b1407, 0x001b1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001a1306, 0x00181207, 0x001a1409, 0x001a1408, 0x001a1408, 0x001c1308, 0x001c1208, 0x001c1208, 0x001c1308, 0x001a1304, 0x001a1304, 0x001a1304, 0x001a1304, 0x001a1305, 0x001a1207, 0x001a1307, 0x001a1307, 0x001a1307, 0x001a1306, 0x001a1306, 0x001a1306, 0x001b1206, 0x001c1308, 0x001c1308, 0x001c1306, 0x001d1306, 0x00201408, 0x0023160a, 0x00241608, 0x00251608, 0x00281608, 0x00281608, 0x002c1708, 0x002e1b08, 0x00301c06, 0x00301d06, 0x00341d05, 0x00381f04, 0x003d2106, 0x003f2408, 0x0043270b, 0x0044280c, 0x0044280c, 0x00452b0c, 0x00472c09, 0x004a2c07, 0x00492b03, 0x004b2b03, 0x004e2e06, 0x004f2f05, 0x004f3105, 0x004f3004, 0x00513003, 0x00583404, 0x005d3803, 0x00663c03, 0x006b3d04, 0x00744308, 0x0079470b, 0x007c4c0e, 0x007f500f, 0x00835310, 0x0085550c, 0x0089560a, 0x00905505, 0x00985b08, 0x009c5c03, 0x00a06302, 0x00a26c02, 0x00a8730a, 0x00a06a0c, 0x008e5600, 0x00915c04, 0x00a97d11, 0x00c8a71f, 0x00ccb418, 0x00ccb70f, 0x00ccb80b, 0x00ccb80c, 0x00c5aa11, 0x00a98207, 0x00966100, 0x00895402, 0x0084540b, 0x00805510, 0x007d5410, 0x007a510e, 0x0078500e, 0x0078500f, 0x007d5411, 0x007f530f, 0x0080540f, 0x0081560f, 0x007e5309, 0x0088570d, 0x0096640d, 0x00bf9421, 0x00cbb11c, 0x00c9b711, 0x00cab70c, 0x00ccb60c, 0x00ccac14, 0x00ae7d03, 0x009e6703, 0x00ba8320, 0x00ca9d26, 0x00cba61e, 0x00cca51c, 0x00caa01c, 0x00c59818, 0x00bd8c18, 0x00b07f10, 0x00a4730b, 0x00996805, 0x00925e05, 0x008c5805, 0x008a570d, 0x0081500c, 0x00754b0d, 0x006f480d, 0x0068440c, 0x00623f0c, 0x005c3a0b, 0x0058380b, 0x0054360c, 0x0050340c, 0x004d320b, 0x004c300b, 0x004c300c, 0x00482c0b, 0x00452908, 0x0044280a, 0x00422709, 0x003f2509, 0x003c2309, 0x003c210c, 0x0039200e, 0x00301a0a, 0x002a190a, 0x00281a0c, 0x0026190d, 0x0022170b, 0x001f1308, 0x0023180c, 0x0020160a, 0x001b1308, 0x0018130a, 0x0014120a, 0x00121008, 0x00101007, 0x000e1006, 0x000c1005, 0x000b1005, 0x000c0f04, 0x000c0f04, 0x000c0f03, 0x000a1004, 0x000e130a, 0x00141914, 0x00141815, 0x00141a15, 0x00161c17, 0x00181d18, 0x00181e19, 0x001a201b, 0x001a2019, 0x00192019, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x0024250b, 0x0024250c, 0x0024250b, 0x0026280b, 0x00292b0b, 0x00292b0a, 0x00292b0a, 0x002d2f0a, 0x002c2d0a, 0x0030310c, 0x0030310c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0030310c, 0x0030310c, 0x0030310c, 0x0030310c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x0026280a, 0x0026280b, 0x0026280c, 0x0024250c, 0x0020230a, 0x00202308, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c09, 0x00141809, 0x0014180b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x00191c16, 0x00191c16, 0x00191c16, 0x00171a14, 0x0010130c, 0x000f120a, 0x000f120a, 0x000e1109, 0x00101009, 0x00121107, 0x00171408, 0x001d170a, 0x00201809, 0x001c1304, 0x00281c0c, 0x002f210b, 0x0035260d, 0x003b2a0c, 0x00402e0c, 0x00443108, 0x004c350b, 0x00523a0c, 0x005c400f, 0x00644310, 0x006e4812, 0x00764d12, 0x007f5612, 0x00855d12, 0x008d6713, 0x009a7318, 0x00a8781b, 0x00b18420, 0x00ba9023, 0x00c09822, 0x00c7a21b, 0x00cba81a, 0x00ccac17, 0x00ccb018, 0x00ccb418, 0x00ccb817, 0x00ccb811, 0x00ccb80c, 0x00cab90a, 0x00cab90a, 0x00cbb90c, 0x00ccba0d, 0x00ccbb0e, 0x00cbbc0c, 0x00cbbc0c, 0x00cbbb0d, 0x00c9bc0d, 0x00c8ba0c, 0x00cbb317, 0x00b48d10, 0x00926100, 0x008a5a00, 0x009c7507, 0x00c1a11b, 0x00c9b116, 0x00cab80d, 0x00c8ba09, 0x00cabb08, 0x00cbbb07, 0x00ccb712, 0x00ccb51b, 0x00ccb31e, 0x00c9af21, 0x00c3a621, 0x00bc9f21, 0x00b8981c, 0x00b8961f, 0x00b89420, 0x00bb9621, 0x00c49e25, 0x00c9a425, 0x00ccaa24, 0x00ccb21b, 0x00ccb813, 0x00cab90b, 0x00c8ba0a, 0x00ccb410, 0x00bb9910, 0x00996a06, 0x00834b00, 0x00723e00, 0x00714000, 0x00754500, 0x00744200, 0x00713f00, 0x00743f02, 0x00754100, 0x007c4800, 0x00804b00, 0x00824c00, 0x00834c00, 0x00834c00, 0x00824b00, 0x00784400, 0x00724000, 0x00724202, 0x006c4003, 0x00663c00, 0x00633d03, 0x00603c04, 0x005a3a02, 0x00533600, 0x00513601, 0x00503404, 0x00503407, 0x00503407, 0x004c3006, 0x004b3008, 0x00472f09, 0x00422e0a, 0x00402c08, 0x003d2a06, 0x003c2905, 0x00382503, 0x00362106, 0x00342007, 0x00331d08, 0x002f1908, 0x002c1909, 0x00281908, 0x00221707, 0x00201806, 0x00201508, 0x001e1308, 0x001c1206, 0x001a1306, 0x00191207, 0x00181308, 0x00181308, 0x00151307, 0x00161207, 0x00171008, 0x00151007, 0x00151007, 0x00181108, 0x00181309, 0x00171008, 0x00181108, 0x00181108, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x001b1308, 0x001b1308, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1307, 0x00181105, 0x001c1509, 0x001c1408, 0x001c1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001c1104, 0x001c1104, 0x001c1107, 0x001b1108, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x00201408, 0x00211408, 0x00221407, 0x00241508, 0x00241409, 0x00271308, 0x00291607, 0x002d1807, 0x002f1b07, 0x002f1b05, 0x00311b03, 0x00331c01, 0x00341d04, 0x00372006, 0x003a2108, 0x003c230a, 0x0040240c, 0x00402508, 0x00402505, 0x00402504, 0x00412703, 0x00412804, 0x00422a07, 0x00442907, 0x00442908, 0x00472908, 0x004a2d0a, 0x004c2e09, 0x004e2e05, 0x00503003, 0x00533104, 0x00553004, 0x00573105, 0x00583205, 0x005d3508, 0x00613a09, 0x00643c0b, 0x006b3f0b, 0x00734005, 0x00784405, 0x00804a07, 0x00844f06, 0x00885306, 0x00885305, 0x00855004, 0x00814d02, 0x00885706, 0x009b680c, 0x00c29620, 0x00ccad1c, 0x00ccb510, 0x00ccb907, 0x00ccb907, 0x00cbb411, 0x00c09d14, 0x00a47503, 0x008f5e00, 0x00885704, 0x0084540c, 0x0080540e, 0x007c5210, 0x0079500f, 0x007a5112, 0x007d5211, 0x007f530f, 0x0080540d, 0x0083580e, 0x00835609, 0x008c5a0e, 0x009c6c11, 0x00c29a23, 0x00ccb21b, 0x00c9b611, 0x00cbb60c, 0x00ccb60b, 0x00ccac13, 0x00ae7c03, 0x009f6502, 0x00b98319, 0x00cca422, 0x00ccad14, 0x00cab010, 0x00ccb014, 0x00ccac14, 0x00cca814, 0x00c8a215, 0x00c69d19, 0x00c09418, 0x00bc8b19, 0x00b07b13, 0x00a97113, 0x009c650f, 0x00935c0d, 0x008b580d, 0x00865510, 0x00805110, 0x007c4c0f, 0x0076480f, 0x006f4410, 0x00674110, 0x00613d0e, 0x005b390a, 0x00553508, 0x00513208, 0x004c3008, 0x004c2e09, 0x004a2c0a, 0x00472a0c, 0x0044280b, 0x00422608, 0x0040240a, 0x00371e08, 0x00311c09, 0x002e1e0a, 0x002c1d0b, 0x00271a09, 0x00201404, 0x00211507, 0x0023180a, 0x001d1408, 0x001a1308, 0x00171209, 0x00131008, 0x00110f07, 0x00101006, 0x000c1005, 0x000c1007, 0x000c0f04, 0x000b0e02, 0x000b0e02, 0x000a1004, 0x000e130b, 0x00141813, 0x00141814, 0x00141815, 0x00161a17, 0x00181c19, 0x00191d1a, 0x00191f1a, 0x0019201a, 0x0019201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180b, 0x00141809, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x00202309, 0x0024250b, 0x0024250b, 0x0026280c, 0x0026280b, 0x00292b0b, 0x00292b0b, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x00292b0a, 0x00292b0b, 0x00292b0b, 0x0026280b, 0x0024250b, 0x0024250c, 0x0020230a, 0x00202308, 0x001d2008, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x00191c16, 0x00191c16, 0x00181c15, 0x00141710, 0x000f110b, 0x0010120a, 0x0010120a, 0x00101009, 0x00101008, 0x00141208, 0x001a140a, 0x0020180b, 0x00221808, 0x00241809, 0x002d200e, 0x0035260e, 0x003a2a0c, 0x00402e0c, 0x0048350c, 0x00543c0c, 0x005c3f0b, 0x00644408, 0x00714e0b, 0x007c560d, 0x00886011, 0x00986d14, 0x00a77c1b, 0x00b38821, 0x00bc9324, 0x00c49d28, 0x00c8a426, 0x00cba926, 0x00caab21, 0x00caad1c, 0x00cab011, 0x00ccb611, 0x00ccb810, 0x00ccb90f, 0x00ccba10, 0x00ccba0f, 0x00cbba0c, 0x00cab908, 0x00cab909, 0x00cab90a, 0x00cbba0b, 0x00cbba0b, 0x00cbba0b, 0x00cbbb0a, 0x00ccbb08, 0x00cbba08, 0x00cbbb06, 0x00cbbc08, 0x00ccb614, 0x00bf9e19, 0x00966a03, 0x007f4f00, 0x00835400, 0x009d7407, 0x00bc9a18, 0x00caad18, 0x00ccb416, 0x00ccb70e, 0x00cbba0a, 0x00ccbc0c, 0x00ccbc10, 0x00ccbc14, 0x00ccbc18, 0x00ccbb1b, 0x00ccb91c, 0x00cab61c, 0x00ccb41f, 0x00c9b21e, 0x00cab11d, 0x00ccb41d, 0x00ccb318, 0x00ccb414, 0x00ccb80a, 0x00ccb809, 0x00ccb60e, 0x00cab114, 0x00bc980f, 0x009c7002, 0x00805200, 0x00724100, 0x00603700, 0x005c3700, 0x005b3700, 0x005a3504, 0x005c340a, 0x005d3408, 0x005c3402, 0x005e3502, 0x00603802, 0x00633901, 0x00643a00, 0x00663b01, 0x00663c01, 0x00603800, 0x005b3500, 0x00593503, 0x00543403, 0x00533303, 0x00523404, 0x00513509, 0x004d3408, 0x00493407, 0x00483306, 0x00483207, 0x00483009, 0x0048300b, 0x00442d0a, 0x00412c0c, 0x003e2c0c, 0x003b290d, 0x003a280d, 0x0038250b, 0x0037240a, 0x00332005, 0x00321f06, 0x00321f08, 0x00301c08, 0x002c1808, 0x0029180b, 0x00251508, 0x00241508, 0x00201608, 0x00201508, 0x001e1308, 0x001c1206, 0x001a1306, 0x00191207, 0x00181308, 0x00181308, 0x00151307, 0x00161207, 0x00171008, 0x00171008, 0x00161008, 0x00181108, 0x00181209, 0x00171008, 0x00181108, 0x00181108, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x001b1308, 0x001b1308, 0x001b1407, 0x001b1407, 0x001c1307, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001b1407, 0x001e170b, 0x001d160a, 0x001e150a, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001c1104, 0x001c1104, 0x001c1108, 0x001b1108, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x00201408, 0x00211408, 0x00211507, 0x00221608, 0x00241409, 0x00261408, 0x00261504, 0x00291807, 0x002b1909, 0x002b190a, 0x002c1a08, 0x002d1b06, 0x002e1c06, 0x002f1c09, 0x00321d0b, 0x00341e0a, 0x0038200b, 0x00382108, 0x00392107, 0x003a2305, 0x003b2404, 0x003a2404, 0x003d2506, 0x00402607, 0x00422809, 0x00432809, 0x00442909, 0x00472a08, 0x00482b07, 0x00482c04, 0x00482c05, 0x00482c04, 0x004b2b05, 0x004c2c04, 0x004d2c03, 0x004d2c00, 0x004e2d00, 0x00502f00, 0x00542f01, 0x00583303, 0x005e3603, 0x00643803, 0x00653801, 0x006f4207, 0x0072460a, 0x00754a0b, 0x0080530c, 0x008d5e0f, 0x00ac7f1a, 0x00c5a422, 0x00cab218, 0x00ccb80d, 0x00ccb808, 0x00cbb40f, 0x00cbb11b, 0x00ba960f, 0x00a27703, 0x00946400, 0x008b5904, 0x00845408, 0x00805208, 0x007c5109, 0x007d510d, 0x0080520e, 0x0081530d, 0x0083540b, 0x0086580c, 0x00885908, 0x00915f0c, 0x00ab7d1a, 0x00c9a425, 0x00ccb417, 0x00cab70d, 0x00ccb60b, 0x00cbb70c, 0x00ccac13, 0x00b07b03, 0x009f6502, 0x00b9841b, 0x00cca520, 0x00cab30d, 0x00c8b708, 0x00c9b70e, 0x00ccb30e, 0x00ccb210, 0x00ccb114, 0x00ccae17, 0x00cbab18, 0x00cba117, 0x00c99e19, 0x00c8991c, 0x00c08f18, 0x00b78418, 0x00ac7814, 0x00a26e10, 0x009a640c, 0x00975f0c, 0x0091590d, 0x008c550e, 0x0084510e, 0x007d500c, 0x00774c0b, 0x006c4407, 0x00684009, 0x00613b07, 0x005c3705, 0x00583405, 0x00543108, 0x00502e0a, 0x004b2c07, 0x00472908, 0x003d2306, 0x00382108, 0x00362209, 0x0034210b, 0x002f1e09, 0x00281604, 0x00231403, 0x00241708, 0x00211708, 0x001c1408, 0x00181308, 0x00141007, 0x00110f05, 0x00101005, 0x000d0f05, 0x000c1005, 0x000c0f04, 0x000b0e02, 0x000c1001, 0x000a1004, 0x000e130b, 0x00131712, 0x00141814, 0x00141815, 0x00161a17, 0x00181c18, 0x00181d1a, 0x00191f1a, 0x0019201a, 0x0019201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x00202309, 0x0024250a, 0x0024250b, 0x0024250c, 0x0026280c, 0x0026280b, 0x0026280b, 0x00292b0b, 0x0026280a, 0x00292b0b, 0x0026280a, 0x0026280a, 0x00292b0b, 0x00292b0b, 0x0026280a, 0x0026280a, 0x00292b0b, 0x00292b0b, 0x00292b0b, 0x0026280b, 0x0026280b, 0x0024250b, 0x0024250b, 0x0024250b, 0x00202309, 0x00202309, 0x001d2008, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180e, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x00191e17, 0x00191d18, 0x00191d18, 0x001a1d18, 0x001a1d17, 0x001a1c16, 0x0013140e, 0x0010110b, 0x0012110a, 0x0012110a, 0x00121108, 0x00131008, 0x00181309, 0x001d160c, 0x0022180c, 0x00231808, 0x002c1e0e, 0x0034240f, 0x003b280f, 0x00402d0e, 0x0048340e, 0x00543d10, 0x00644510, 0x00745012, 0x00855d11, 0x00936b14, 0x00a17c18, 0x00b79124, 0x00c39e24, 0x00c9a823, 0x00ccac24, 0x00ccae20, 0x00ccb11e, 0x00ccb318, 0x00ccb516, 0x00ccb514, 0x00ccb610, 0x00ccb70c, 0x00ccb80b, 0x00ccb90c, 0x00cbba0c, 0x00ccb90c, 0x00ccb90c, 0x00ccb90c, 0x00ccb90c, 0x00cbba0c, 0x00cbba0c, 0x00cbba0c, 0x00cbba0c, 0x00cbba0b, 0x00cab908, 0x00cab908, 0x00c9b808, 0x00cab709, 0x00ccb30d, 0x00c6a814, 0x00b58d14, 0x008e6204, 0x00784a04, 0x007b4c07, 0x007f5200, 0x00946904, 0x00b48c13, 0x00c6a31c, 0x00cbaf18, 0x00ccb510, 0x00cbb90d, 0x00ccba0c, 0x00cbba0c, 0x00ccba0c, 0x00cbba0c, 0x00cbbb0c, 0x00cbba0f, 0x00ccba11, 0x00ccb911, 0x00ccb911, 0x00ccb810, 0x00ccb70d, 0x00ccb70b, 0x00ccb508, 0x00ccb10d, 0x00c8a614, 0x00b58e10, 0x009e6d05, 0x00805300, 0x00694101, 0x00583700, 0x00543305, 0x00533205, 0x00523104, 0x00503007, 0x00502f0a, 0x00522f07, 0x00523001, 0x00523004, 0x00523008, 0x00533003, 0x00533002, 0x00533003, 0x00543003, 0x00543104, 0x00533204, 0x00503205, 0x004c3004, 0x004a2e05, 0x00492e08, 0x00482e0b, 0x00462f0c, 0x00442e09, 0x00422b07, 0x00422a09, 0x00422a0a, 0x00422a0a, 0x003e2808, 0x003a2509, 0x0038250c, 0x0036260c, 0x0034240c, 0x00322009, 0x00312008, 0x00301d06, 0x002e1e07, 0x002d1c08, 0x002a1908, 0x00271508, 0x0028150b, 0x0026150b, 0x0024150c, 0x0020160b, 0x001f1409, 0x001d1207, 0x001c1206, 0x001a1306, 0x00191207, 0x00181308, 0x00181308, 0x00151307, 0x00171208, 0x00181108, 0x00181108, 0x00181309, 0x00171008, 0x00151007, 0x00181108, 0x00181309, 0x00181309, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x00191208, 0x00191208, 0x00191306, 0x00191306, 0x001b1307, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1307, 0x001c1307, 0x001e1409, 0x001c1408, 0x001b1408, 0x001e170b, 0x001d160a, 0x001d1409, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001c1104, 0x001c1104, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x00201408, 0x00201408, 0x00221407, 0x00221407, 0x00241409, 0x00241608, 0x00251607, 0x00271706, 0x00271706, 0x00281808, 0x00291807, 0x002c1906, 0x002c1a07, 0x002d1a07, 0x002e1b08, 0x00301b08, 0x00311c0a, 0x00331c09, 0x00331d08, 0x00351e06, 0x00351e05, 0x00351e05, 0x00351e05, 0x00382007, 0x003c230a, 0x003e230b, 0x0040240a, 0x00402409, 0x00402607, 0x003f2707, 0x003c2404, 0x003d2505, 0x00412909, 0x00442909, 0x00422806, 0x00442804, 0x00442802, 0x00422a00, 0x00442c03, 0x00482d07, 0x004b2c05, 0x00502f08, 0x00543008, 0x00553005, 0x00543302, 0x00593802, 0x00694305, 0x007f5214, 0x00946412, 0x00b48e1a, 0x00c7ac1d, 0x00c9b412, 0x00ccb80b, 0x00ccb70d, 0x00cab611, 0x00cab315, 0x00bf9b11, 0x00ab7a06, 0x00986401, 0x00905b08, 0x00885606, 0x00835305, 0x00815207, 0x0085540d, 0x0085540c, 0x0087570c, 0x008c5b0d, 0x00925f05, 0x00a37014, 0x00bd9426, 0x00ccac21, 0x00ccb510, 0x00cab808, 0x00ccb708, 0x00cab60b, 0x00c8a70f, 0x00ac7800, 0x00a46907, 0x00bc881e, 0x00cca61d, 0x00c8b40a, 0x00c6b804, 0x00c6b609, 0x00c9b60a, 0x00ccb60b, 0x00cbb60c, 0x00ccb40e, 0x00ccb30f, 0x00ccb00d, 0x00ccb00e, 0x00ccaf11, 0x00ccac13, 0x00cba819, 0x00c79e18, 0x00c29518, 0x00bd8c14, 0x00b88414, 0x00b17a12, 0x00a8700f, 0x00a0680c, 0x00976008, 0x00905c06, 0x00895808, 0x0085540c, 0x007d4e0a, 0x00764a08, 0x006f4408, 0x00683e0b, 0x00603709, 0x00553105, 0x004e2d04, 0x00472804, 0x00422706, 0x003f2508, 0x003b2108, 0x00392109, 0x00331d07, 0x00281502, 0x00241603, 0x00241807, 0x00201608, 0x001b1408, 0x00161008, 0x00141006, 0x00121006, 0x00101007, 0x000d1007, 0x000c1005, 0x000c0f03, 0x000c1001, 0x000b1004, 0x000c1109, 0x00101510, 0x00141814, 0x00141814, 0x00151916, 0x00161a17, 0x00171c18, 0x00181d18, 0x00181e18, 0x00181f19, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x001d200a, 0x001d2009, 0x001d2008, 0x001d2008, 0x00202308, 0x00202309, 0x00202309, 0x0024250b, 0x0024250b, 0x0024250b, 0x0024250c, 0x0024250c, 0x0026280c, 0x0026280c, 0x0026280c, 0x0026280c, 0x0026280c, 0x0026280c, 0x0024250c, 0x0024250c, 0x0024250b, 0x0024250b, 0x0020230a, 0x00202309, 0x00202309, 0x00202308, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x00191e17, 0x00191d18, 0x00191d18, 0x001a1d18, 0x001a1d17, 0x00191c16, 0x0011140d, 0x0012120c, 0x0014110b, 0x0013120a, 0x00121108, 0x00131008, 0x001b140b, 0x0020170c, 0x0024180a, 0x00251808, 0x00312310, 0x0038280e, 0x00402c0e, 0x0044300c, 0x00503910, 0x005f4211, 0x0079571a, 0x0090691f, 0x00a98220, 0x00bb9826, 0x00c6a82a, 0x00caae27, 0x00cbb41f, 0x00cab414, 0x00cbb613, 0x00ccb712, 0x00ccb910, 0x00cbb90d, 0x00ccbb0d, 0x00cbb90d, 0x00cbb90d, 0x00ccb80e, 0x00ccb80f, 0x00ccb810, 0x00ccb810, 0x00ccb80d, 0x00ccb80d, 0x00cbb90d, 0x00cbb90d, 0x00cbb90d, 0x00cbb90d, 0x00ccb80d, 0x00ccb80d, 0x00ccb80c, 0x00ccb80c, 0x00ccb70d, 0x00ccb510, 0x00cbb014, 0x00bf9810, 0x00a17802, 0x00895b00, 0x00764700, 0x00694005, 0x006c410a, 0x00704608, 0x007c5204, 0x008f6103, 0x00a07408, 0x00b79212, 0x00c6a717, 0x00cbaf13, 0x00cbb010, 0x00cbb10d, 0x00ccb40c, 0x00ccb60a, 0x00ccb509, 0x00ccb60b, 0x00ccb60c, 0x00ccb60d, 0x00ccb50d, 0x00ccb40e, 0x00ccb30e, 0x00ccb012, 0x00c7a412, 0x00be9812, 0x00aa7e0c, 0x008c5c00, 0x00804f01, 0x00704604, 0x00553802, 0x004b3607, 0x0048310e, 0x004a300f, 0x004a2f0a, 0x00492e0a, 0x00492d0c, 0x00492e08, 0x004a2e04, 0x004a2d09, 0x004a2c0d, 0x00492e0b, 0x00492e0b, 0x00492e0b, 0x00482d0a, 0x00472c08, 0x00472d08, 0x00462c07, 0x00452c06, 0x00442c06, 0x00442a08, 0x0043290a, 0x0042290c, 0x003f270a, 0x003e2509, 0x003e250b, 0x003e250b, 0x003e250a, 0x003c2307, 0x00382007, 0x00352008, 0x00342108, 0x00302007, 0x002d1d05, 0x002e1e06, 0x002d1d07, 0x002c1d08, 0x002b1c0a, 0x0028180a, 0x00251509, 0x0027140b, 0x0026150c, 0x0024150d, 0x0020150c, 0x001e1208, 0x001e1107, 0x001c1106, 0x001b1206, 0x00191207, 0x00181308, 0x00181308, 0x00161408, 0x00151308, 0x00181108, 0x00181209, 0x00181309, 0x00171008, 0x00151007, 0x00181108, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181308, 0x00191208, 0x00191208, 0x00191306, 0x00191306, 0x001b1307, 0x001c1307, 0x001c1408, 0x001c1407, 0x001c1407, 0x001c1307, 0x001c1307, 0x001e1409, 0x001e1409, 0x001b1407, 0x001c1509, 0x001b1407, 0x001d1409, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001c1104, 0x001c1104, 0x001c1206, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x00201408, 0x00201408, 0x00211507, 0x00211507, 0x00241409, 0x00241608, 0x00241607, 0x00271706, 0x00271706, 0x00281707, 0x002a1807, 0x002c1906, 0x002c1a05, 0x002e1a05, 0x002f1b06, 0x002f1b06, 0x002f1a08, 0x00301b08, 0x00301b08, 0x00311c08, 0x00311c06, 0x00311c06, 0x00311c06, 0x00341d08, 0x00351d08, 0x00371e09, 0x00381f08, 0x00392008, 0x00392207, 0x00382206, 0x00352105, 0x00362107, 0x00382309, 0x003a2408, 0x003b2408, 0x003b2407, 0x003c2404, 0x003c2404, 0x003e2606, 0x0042280b, 0x0044280b, 0x00492a0e, 0x004b2d0c, 0x004b2e08, 0x004f3408, 0x004e3202, 0x005a3704, 0x00704713, 0x00845610, 0x00946c09, 0x00b49415, 0x00c7ac18, 0x00ccb610, 0x00ccb80c, 0x00c8ba0b, 0x00c8b90c, 0x00ccb218, 0x00c9a01a, 0x00ba8813, 0x00a5700e, 0x00945f02, 0x00945f06, 0x00905c07, 0x00905c10, 0x00915c0f, 0x00935f0e, 0x0098630f, 0x00a6720f, 0x00b98a20, 0x00caa529, 0x00cbb11d, 0x00cab60c, 0x00cab805, 0x00ccb808, 0x00c8b107, 0x00c39e0a, 0x00a97200, 0x00a46c0a, 0x00bf8c20, 0x00cca91f, 0x00c9b408, 0x00c8b606, 0x00c8b40b, 0x00cbb50a, 0x00cbb50a, 0x00cbb50a, 0x00ccb40c, 0x00cbb50a, 0x00c9b608, 0x00c9b608, 0x00c8b508, 0x00cab50b, 0x00ccb50f, 0x00ccb413, 0x00ccae15, 0x00cba915, 0x00cba418, 0x00ca9e1c, 0x00c6981c, 0x00bf8d18, 0x00b98715, 0x00b27e14, 0x00a87410, 0x00a16c13, 0x00996611, 0x00925e0c, 0x008a560e, 0x00885619, 0x007c4c17, 0x00643c08, 0x00583706, 0x004d2f04, 0x00492c05, 0x00452808, 0x00432608, 0x003e2006, 0x00381f05, 0x002e1b04, 0x00231500, 0x00241806, 0x00221808, 0x001d1609, 0x00181208, 0x00141007, 0x00131008, 0x00101009, 0x000f1007, 0x000c1005, 0x000c0f04, 0x000c1004, 0x000c1004, 0x000d1008, 0x0011150f, 0x00141814, 0x00141814, 0x00151916, 0x00161a17, 0x00171c18, 0x00181d18, 0x00181e18, 0x00181f19, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x001d2008, 0x00202308, 0x00202308, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202308, 0x001d2008, 0x001d2008, 0x00202309, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180c, 0x0014180e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x001a1d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x001a1d18, 0x001a1d17, 0x00171a14, 0x0011140d, 0x0011130d, 0x0011120c, 0x00121309, 0x00131209, 0x0016120a, 0x001d140d, 0x0023170c, 0x00281a0a, 0x002c1d0c, 0x0035240e, 0x003a280c, 0x0044300d, 0x004c360c, 0x005c4010, 0x0076521f, 0x00956e28, 0x00b69530, 0x00c8ac26, 0x00ccb41e, 0x00cbb51c, 0x00cbb819, 0x00cbb914, 0x00cbbb0d, 0x00ccbb0d, 0x00ccbb0d, 0x00ccbc0a, 0x00cbbb07, 0x00cbba0a, 0x00cbba0c, 0x00cbb90d, 0x00cbb90f, 0x00cbb90f, 0x00cbb90d, 0x00ccb80d, 0x00ccb80c, 0x00ccb80c, 0x00cbba0c, 0x00cbba0c, 0x00ccb90b, 0x00ccb80c, 0x00ccb70e, 0x00ccb60f, 0x00cbb40c, 0x00cab00c, 0x00ccac13, 0x00c39d0f, 0x00b08609, 0x00956805, 0x007c5000, 0x006c4300, 0x00603902, 0x0059350a, 0x00583607, 0x005c3b06, 0x00614005, 0x00754b08, 0x007c5002, 0x00895c00, 0x009c7003, 0x00ad840b, 0x00b6900e, 0x00bf9911, 0x00c39e10, 0x00c6a10c, 0x00c7a20c, 0x00c7a20c, 0x00c7a10d, 0x00c7a00d, 0x00c49c0c, 0x00c1990e, 0x00b78e07, 0x00ad8104, 0x009d6c04, 0x008d5b00, 0x007a4c00, 0x006c4100, 0x00613b07, 0x00543204, 0x004c3007, 0x00452e09, 0x00442b0a, 0x0044290a, 0x0044280a, 0x0045270c, 0x0044260c, 0x0044260c, 0x0045270c, 0x0047270b, 0x0046280c, 0x0044290c, 0x0044290c, 0x00422a0c, 0x00412b0c, 0x00402a0b, 0x00402a0b, 0x0040290a, 0x003e2708, 0x003c2708, 0x003c2808, 0x003c280a, 0x003a2409, 0x0038220a, 0x0038220a, 0x0038200b, 0x00341e08, 0x0038200b, 0x00341e08, 0x00331c08, 0x00331d09, 0x00321d09, 0x00301d08, 0x002c1b07, 0x002c1b0a, 0x002c1c0c, 0x00281c0c, 0x00271a0a, 0x00241707, 0x00241607, 0x0026150a, 0x00241409, 0x00211308, 0x00201408, 0x00211308, 0x00201207, 0x001d1004, 0x001c1104, 0x001a1207, 0x00181308, 0x00181308, 0x00161408, 0x00151408, 0x0018140c, 0x0019130c, 0x0019110b, 0x0019110b, 0x00181108, 0x00181108, 0x00181108, 0x00181109, 0x0018110b, 0x0018110a, 0x0019130c, 0x0019140b, 0x00191208, 0x00191208, 0x00191306, 0x00191304, 0x001a1308, 0x001b1309, 0x001c1408, 0x001c1408, 0x001d1408, 0x001e1308, 0x001e1308, 0x001f1408, 0x001c1407, 0x00191407, 0x001c1509, 0x001e1409, 0x001e1409, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001e1407, 0x001c1407, 0x001c1406, 0x001c1407, 0x001d1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1408, 0x001f1409, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001e1308, 0x001e1308, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001f1206, 0x00201307, 0x00221509, 0x00231509, 0x00211407, 0x00241407, 0x00251709, 0x00261709, 0x00271809, 0x00291808, 0x00291808, 0x002c1909, 0x002c1a0a, 0x002c1a08, 0x002c1a08, 0x002c1a08, 0x002c1a08, 0x002c1b07, 0x002c1a07, 0x002f1a08, 0x00321c09, 0x00331c0a, 0x00311b06, 0x00331c09, 0x00331c09, 0x00321e08, 0x00321e06, 0x00341e07, 0x00341e07, 0x00341e07, 0x00351e07, 0x00361e07, 0x00381f08, 0x00381f06, 0x003c2105, 0x003e2408, 0x00402409, 0x0041270a, 0x00422808, 0x00422805, 0x00482e08, 0x00482e06, 0x00513007, 0x005e3807, 0x0074490e, 0x00835610, 0x009a6d0b, 0x00bf981c, 0x00cbad1c, 0x00ccb70f, 0x00c7ba06, 0x00c8b906, 0x00ccb80e, 0x00ccb414, 0x00cbad18, 0x00c69d18, 0x00bb8c0f, 0x00b9810e, 0x00b07509, 0x00ad7210, 0x00ac7310, 0x00b07710, 0x00b88117, 0x00c4981c, 0x00caa721, 0x00ccaf1c, 0x00c9b414, 0x00c9b80a, 0x00ccb806, 0x00ccb307, 0x00ccaf0c, 0x00bc8f06, 0x00a36a00, 0x00a87010, 0x00c39924, 0x00c8ad15, 0x00cbb407, 0x00cab40b, 0x00cbb50a, 0x00cbb608, 0x00ccb508, 0x00ccb508, 0x00ccb409, 0x00ccb40a, 0x00cbb50a, 0x00cbb50a, 0x00cbb50a, 0x00cbb50a, 0x00cab60a, 0x00c9b60b, 0x00c9b60b, 0x00c9b50b, 0x00cbb10a, 0x00ccad0f, 0x00ccac14, 0x00cca917, 0x00caa618, 0x00c9a319, 0x00c59c18, 0x00c0951a, 0x00be901b, 0x00ba8113, 0x00af7112, 0x00ac6f20, 0x00a06721, 0x0081500e, 0x00653f02, 0x00523600, 0x004c3306, 0x004a2e09, 0x00482908, 0x00432507, 0x003c2307, 0x00342008, 0x002a1a05, 0x00261704, 0x00251808, 0x0022180b, 0x001c140a, 0x00171008, 0x00141008, 0x00131009, 0x00101007, 0x00100f08, 0x000c0e08, 0x000e1008, 0x00101008, 0x00101006, 0x00111309, 0x00131610, 0x00141914, 0x00141914, 0x00151a14, 0x00161b15, 0x00161c17, 0x00181e18, 0x0019201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180a, 0x0014180a, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x00202309, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x00202309, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x00191c09, 0x001d200a, 0x00191c09, 0x00191c0a, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180c, 0x0014180e, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x001a1d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x001a1d18, 0x001a1d17, 0x00181914, 0x0011120c, 0x0012130d, 0x0013120c, 0x00131209, 0x0014130a, 0x00161208, 0x00211810, 0x00261a0e, 0x00281a09, 0x002e1e09, 0x0038250e, 0x003e2b0d, 0x0048320c, 0x00533c0e, 0x006a4b12, 0x00886420, 0x00ad892e, 0x00caad34, 0x00cbb81f, 0x00ccb914, 0x00cbb810, 0x00cbba0e, 0x00cbbb0b, 0x00ccbc09, 0x00cbbb07, 0x00ccbc08, 0x00ccbc06, 0x00cbbb06, 0x00cbba0a, 0x00cbba0c, 0x00cbba0b, 0x00cbba09, 0x00cbba08, 0x00cbba0b, 0x00cbba0a, 0x00ccb90a, 0x00ccb90a, 0x00ccb90c, 0x00cbb80b, 0x00ccb609, 0x00ccb30c, 0x00ccb011, 0x00c8aa12, 0x00c6a313, 0x00c09611, 0x00b2840f, 0x009f6e08, 0x00885700, 0x00744600, 0x00684001, 0x005c3703, 0x00553408, 0x0051340a, 0x00503408, 0x00503403, 0x00523401, 0x005a3807, 0x00643e09, 0x006e4606, 0x00754b03, 0x00784d00, 0x00815602, 0x00875b03, 0x008c5f04, 0x00906502, 0x00926701, 0x00936701, 0x00946601, 0x00946501, 0x00905f01, 0x008c5b00, 0x00855300, 0x007b4a00, 0x00744500, 0x00683c00, 0x00603700, 0x00573202, 0x00503005, 0x004b2c04, 0x00462c07, 0x00442c09, 0x00422808, 0x00412708, 0x00402608, 0x0041260a, 0x0040250b, 0x0040240b, 0x0040240a, 0x00402309, 0x00402308, 0x003f2308, 0x003d2408, 0x003c2409, 0x003a2509, 0x00392408, 0x00392409, 0x0039240a, 0x00382306, 0x00352206, 0x00352206, 0x00342006, 0x00332008, 0x00331f08, 0x00331e09, 0x00321d09, 0x002f1b06, 0x00321d09, 0x002f1b08, 0x00301b08, 0x00311e0b, 0x00301d0a, 0x002c1b07, 0x002a1907, 0x002b190b, 0x002a190c, 0x0027190c, 0x0024180a, 0x00241809, 0x00241809, 0x00241409, 0x00221408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x001d1104, 0x001c1204, 0x001a1207, 0x00181308, 0x00181308, 0x00161408, 0x00141308, 0x00151308, 0x00171208, 0x00181309, 0x00191209, 0x0018100a, 0x0018100a, 0x0018100a, 0x0018100a, 0x0018110a, 0x0018110a, 0x0019140b, 0x00191409, 0x00191208, 0x00191208, 0x00191306, 0x00191304, 0x001a1308, 0x001b1309, 0x001c1408, 0x001c1408, 0x001d1408, 0x001e1308, 0x001e1308, 0x001f1408, 0x001c1407, 0x00191407, 0x001c1509, 0x001e1409, 0x001f1409, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001e1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001d1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1408, 0x001f1409, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001e1308, 0x001e1308, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001e1205, 0x001e1205, 0x00201408, 0x00201408, 0x00201408, 0x00221509, 0x0023160a, 0x0023160a, 0x00241608, 0x00241506, 0x00251506, 0x00261708, 0x0028180a, 0x00281908, 0x00281908, 0x00281908, 0x00281908, 0x00291908, 0x002a1807, 0x002c1808, 0x002e1908, 0x00311c0b, 0x002f1a08, 0x002f1a08, 0x002f1a08, 0x00301b06, 0x00301a04, 0x00311b05, 0x00331b05, 0x00331b05, 0x00331b05, 0x00341b06, 0x00341b07, 0x00341c05, 0x00381c04, 0x00391e06, 0x003b2007, 0x003d2209, 0x003e230a, 0x003e2408, 0x00442b0c, 0x00452a09, 0x00492c08, 0x00523005, 0x00603704, 0x0075480e, 0x00815404, 0x009c700b, 0x00ba9318, 0x00cbac1a, 0x00cbb412, 0x00cab50c, 0x00ccb80e, 0x00ccb60d, 0x00cbb210, 0x00cbb018, 0x00cbaa17, 0x00cca618, 0x00caa31c, 0x00c89c18, 0x00c89c17, 0x00c9a017, 0x00cba519, 0x00ccac19, 0x00ccb116, 0x00cbb410, 0x00c9b70c, 0x00c8b908, 0x00cbb809, 0x00ccb30d, 0x00c4a40e, 0x00ae7f01, 0x00a06601, 0x00af7813, 0x00c89f23, 0x00c8b013, 0x00cab507, 0x00cab40b, 0x00cbb50a, 0x00cbb605, 0x00cbb503, 0x00cbb405, 0x00ccb507, 0x00ccb508, 0x00cbb608, 0x00cbb608, 0x00cbb50a, 0x00cbb50a, 0x00c9b60a, 0x00c9b60a, 0x00cbb50a, 0x00cbb609, 0x00cbb408, 0x00cbb208, 0x00ccb20c, 0x00ccb412, 0x00ccb313, 0x00ccb213, 0x00ccb116, 0x00c9ad16, 0x00c8a815, 0x00caa016, 0x00c38e13, 0x00c3871c, 0x00b47818, 0x009e6210, 0x00804d04, 0x00643c01, 0x00583704, 0x00503108, 0x004c2e0a, 0x00472b0b, 0x0040270a, 0x0039240c, 0x00301d08, 0x00281803, 0x00261806, 0x00251b0b, 0x001c1609, 0x00181308, 0x00161209, 0x00141109, 0x00101007, 0x00100f08, 0x000f100a, 0x000e1008, 0x000f0f05, 0x000f0f04, 0x00111309, 0x00131610, 0x00131712, 0x00131712, 0x00141813, 0x00141914, 0x00141a14, 0x00161c17, 0x00181e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180b, 0x00191c0b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x001d2009, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c18, 0x00191c18, 0x001a1d18, 0x00191d18, 0x00191d18, 0x00181e18, 0x00191d18, 0x00191d18, 0x00181c18, 0x00191d18, 0x00121510, 0x0010130c, 0x0013110c, 0x0014100b, 0x00141008, 0x00171208, 0x001d180c, 0x00241a0e, 0x00261a0c, 0x002c1c09, 0x0034240c, 0x003c280e, 0x00442d0e, 0x004d350d, 0x005c4313, 0x00775714, 0x009a771f, 0x00c2a42e, 0x00cbb721, 0x00ccc018, 0x00cbc010, 0x00cabc0b, 0x00cbbc07, 0x00cabc06, 0x00cbba07, 0x00cbba07, 0x00cbba07, 0x00cbbb05, 0x00cbbb06, 0x00cbba0a, 0x00cbba0c, 0x00cab908, 0x00caba06, 0x00cab907, 0x00ccb90c, 0x00cab70c, 0x00cbb50e, 0x00cbb20f, 0x00cab014, 0x00c9aa12, 0x00c6a50c, 0x00c09a07, 0x00b89008, 0x00ad8406, 0x00a07405, 0x00926403, 0x00875604, 0x00784703, 0x006c3c02, 0x00603a02, 0x00563400, 0x00513404, 0x004c3305, 0x00483008, 0x00473007, 0x00483106, 0x00483005, 0x004a3004, 0x004c2f03, 0x00543504, 0x005a3803, 0x005f3a04, 0x00613b03, 0x00643c03, 0x00643c01, 0x00653d00, 0x00673f00, 0x00684000, 0x00684000, 0x00684101, 0x00674002, 0x00623c01, 0x005d3701, 0x00593400, 0x00553200, 0x00502e00, 0x004e2b01, 0x00492a04, 0x00452908, 0x00432908, 0x00412808, 0x003f2708, 0x003e2407, 0x003c2306, 0x003c2107, 0x003d2209, 0x003c220a, 0x003c220a, 0x003b2109, 0x003a2009, 0x003a2009, 0x003b2009, 0x00392008, 0x00371f08, 0x00362008, 0x00341f09, 0x00341f09, 0x00341f08, 0x00341f08, 0x00331f07, 0x00331f07, 0x00321e09, 0x00311c09, 0x00301c08, 0x00301b08, 0x002e1b08, 0x002d1b08, 0x002d1b08, 0x002c1908, 0x002c1908, 0x002b1908, 0x002b1908, 0x00281806, 0x00261607, 0x00261608, 0x00251609, 0x0024170a, 0x00221509, 0x00221509, 0x00221509, 0x00241409, 0x00211408, 0x001f1407, 0x001d1407, 0x001d1205, 0x001e1205, 0x001d1205, 0x001c1305, 0x001b1308, 0x001a1408, 0x00181408, 0x00151307, 0x00141207, 0x00141308, 0x00151308, 0x00181309, 0x00181309, 0x00191209, 0x00181108, 0x00181108, 0x00191209, 0x0018120a, 0x00181309, 0x00191409, 0x00181307, 0x00191208, 0x00191208, 0x00191306, 0x00191304, 0x00191207, 0x00191208, 0x001a1307, 0x001b1407, 0x001c1207, 0x001c1106, 0x001c1106, 0x001e1407, 0x001f1508, 0x00181306, 0x001c1408, 0x001c1408, 0x001d1308, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1407, 0x001c1407, 0x001d1305, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201409, 0x00201409, 0x00201309, 0x00201308, 0x00201308, 0x00221407, 0x00221407, 0x00241508, 0x00241608, 0x00241707, 0x00241707, 0x00241707, 0x00241707, 0x00251706, 0x00261605, 0x00281707, 0x002b1808, 0x002c1a09, 0x002a1807, 0x002a1808, 0x002d1c09, 0x002c1a07, 0x002e1a05, 0x002e1a05, 0x002f1a05, 0x002f1a05, 0x002f1a05, 0x002f1a06, 0x00301b06, 0x00311a04, 0x00321b04, 0x00321b04, 0x00341c06, 0x00351e09, 0x00371f0a, 0x00372008, 0x003d260d, 0x003d260b, 0x00422809, 0x00492c08, 0x00502e04, 0x005d3507, 0x00704509, 0x007f5406, 0x00946807, 0x00b48915, 0x00c9a51d, 0x00ccb018, 0x00ccb214, 0x00ccb60d, 0x00ccb80c, 0x00cab710, 0x00cab610, 0x00cab410, 0x00cbb411, 0x00cbb311, 0x00cbb310, 0x00ccb40e, 0x00ccb40d, 0x00ccb60d, 0x00ccb70b, 0x00cab707, 0x00c9b804, 0x00c9b807, 0x00ccb80e, 0x00caac14, 0x00b48c08, 0x009f6c00, 0x00a06503, 0x00bd881c, 0x00cca823, 0x00cab210, 0x00cab507, 0x00cbb50c, 0x00cbb50a, 0x00cbb605, 0x00ccb604, 0x00ccb506, 0x00ccb508, 0x00ccb508, 0x00cbb608, 0x00cbb608, 0x00cbb50a, 0x00cbb50a, 0x00c9b60a, 0x00c9b60a, 0x00cbb50a, 0x00cbb609, 0x00cbb508, 0x00cbb406, 0x00cbb408, 0x00ccb509, 0x00ccb509, 0x00cbb50b, 0x00cbb50b, 0x00cab50c, 0x00ccb40f, 0x00ccaa0f, 0x00cc9d0e, 0x00cb9412, 0x00c48b12, 0x00bc8213, 0x00a66e0e, 0x00875408, 0x006d4306, 0x005d3b0a, 0x004f3308, 0x0048300c, 0x0043290c, 0x0040260e, 0x0038220b, 0x002e1b06, 0x00281704, 0x00261a09, 0x001c1708, 0x00161104, 0x00171208, 0x00141308, 0x00121208, 0x00101008, 0x000d0f08, 0x000c0f07, 0x00101007, 0x00101005, 0x00101108, 0x0011140e, 0x00101510, 0x00101510, 0x00131712, 0x00141813, 0x00141a14, 0x00151c16, 0x00151c16, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x00191c0b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x0014180f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c18, 0x00181c18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00181e18, 0x00191d18, 0x001a1f19, 0x00191e17, 0x00191e17, 0x0011150f, 0x0010120c, 0x0013100c, 0x0016100b, 0x00171009, 0x00181308, 0x001d170b, 0x00241a0c, 0x00271909, 0x002f200c, 0x0038260e, 0x00402c0e, 0x0048300c, 0x00563b10, 0x00654916, 0x00846214, 0x00b09027, 0x00cab025, 0x00cabc14, 0x00cbc210, 0x00cbc210, 0x00cabe0c, 0x00cbbc08, 0x00cbba07, 0x00cab909, 0x00cab90b, 0x00cbba0c, 0x00cbba08, 0x00cbbb06, 0x00cbbb09, 0x00ccb90c, 0x00cbb80b, 0x00cbb908, 0x00cbb70b, 0x00cab511, 0x00c8b014, 0x00c8a815, 0x00c39c11, 0x00b98f0e, 0x00ab7d04, 0x009e6f00, 0x00946400, 0x008e5d00, 0x00895700, 0x007d4e00, 0x00704700, 0x00674000, 0x005e3800, 0x005a3706, 0x0055350b, 0x004e3208, 0x00483207, 0x00453106, 0x00432f06, 0x00422e08, 0x00422d08, 0x00422d09, 0x00422d09, 0x00442e08, 0x00432a03, 0x00482e06, 0x004a2e04, 0x004c2e02, 0x004c2f03, 0x004c3003, 0x004c3002, 0x004d3203, 0x004d3403, 0x004d3403, 0x004f3403, 0x004e3401, 0x004c3101, 0x004c3105, 0x00492f04, 0x00482c04, 0x00472c05, 0x00462b0b, 0x0044290d, 0x0040260c, 0x003d260a, 0x003c2308, 0x003a2207, 0x00392106, 0x00381f05, 0x00361d05, 0x00361d07, 0x00351e08, 0x00341e08, 0x00341d08, 0x00331c08, 0x00341c07, 0x00341c07, 0x00341c08, 0x00341d09, 0x00321d09, 0x00311c0a, 0x00321d0b, 0x00301d0a, 0x00311d08, 0x00301d08, 0x00301d08, 0x00301c0a, 0x00301c0c, 0x002c1a08, 0x002c1a08, 0x002c1908, 0x002a1807, 0x002a1808, 0x00291809, 0x00281808, 0x00271708, 0x00261808, 0x00241606, 0x00241607, 0x00241608, 0x0024160a, 0x0023160c, 0x0021140a, 0x0021140a, 0x0021140a, 0x0022150b, 0x0020140a, 0x001d1408, 0x001c1408, 0x001c1305, 0x001d1205, 0x001c1205, 0x001c1305, 0x001b1407, 0x001a1308, 0x00181408, 0x00151207, 0x00141206, 0x00131306, 0x00141206, 0x00161307, 0x00181308, 0x00191307, 0x00191207, 0x00191307, 0x00191307, 0x00181308, 0x00181308, 0x00181307, 0x00181306, 0x00191307, 0x00191208, 0x00191306, 0x00191304, 0x00191207, 0x00191208, 0x001a1308, 0x001b1407, 0x001c1207, 0x001c1106, 0x001c1106, 0x001e1407, 0x001f1508, 0x00181306, 0x001c1408, 0x001c1408, 0x001d1408, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1407, 0x001c1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201208, 0x00201208, 0x00201208, 0x001e1208, 0x001d1208, 0x001d1207, 0x001c1106, 0x001f1207, 0x00201207, 0x00211308, 0x00221408, 0x00231509, 0x00221608, 0x00221708, 0x00221708, 0x00221708, 0x00241508, 0x00251508, 0x00261508, 0x00281408, 0x00281808, 0x00261606, 0x00261707, 0x00281908, 0x00281805, 0x00291806, 0x00291805, 0x00291805, 0x00291805, 0x00291805, 0x002a1806, 0x002a1806, 0x002b1905, 0x00301c08, 0x002f1c08, 0x002f1c08, 0x00301c08, 0x00301c0c, 0x00311e0b, 0x00341f0a, 0x00352008, 0x003c270c, 0x00442a0b, 0x00492b09, 0x004f2d08, 0x00583505, 0x00654104, 0x00795002, 0x008f6203, 0x00a87d0c, 0x00bf9918, 0x00cbab1b, 0x00ccb111, 0x00ccb50c, 0x00cab60c, 0x00cab70c, 0x00cab80c, 0x00cbb90d, 0x00cab90d, 0x00c8ba0b, 0x00c8b908, 0x00c8ba08, 0x00c9b908, 0x00c9b808, 0x00c9b806, 0x00cbb804, 0x00cab205, 0x00ccaf0f, 0x00bc9205, 0x00a57300, 0x009c6200, 0x00a16504, 0x00bf8b1b, 0x00caa41b, 0x00c9af0e, 0x00cbb40a, 0x00ccb40e, 0x00ccb50c, 0x00ccb508, 0x00ccb40a, 0x00ccb50a, 0x00ccb40a, 0x00ccb40a, 0x00cbb50a, 0x00c9b60a, 0x00c9b60a, 0x00c9b60a, 0x00c8b70a, 0x00c8b709, 0x00c9b609, 0x00c9b60a, 0x00cab509, 0x00cab408, 0x00cab509, 0x00cbb509, 0x00cbb50a, 0x00cbb50c, 0x00cbb50c, 0x00cbb50b, 0x00ccb40c, 0x00ccab0d, 0x00cba00c, 0x00c8980e, 0x00c99a14, 0x00cba315, 0x00bd8d12, 0x00a36f0e, 0x00855408, 0x00684108, 0x0057390a, 0x004a320a, 0x00472c0e, 0x0042280d, 0x003c260c, 0x00322007, 0x00291802, 0x00261b08, 0x00201908, 0x00191404, 0x00181206, 0x00141307, 0x00121108, 0x00100f08, 0x000d0f08, 0x000d0f07, 0x00101007, 0x00101005, 0x000f1108, 0x0012140e, 0x0010140f, 0x0010140f, 0x00111611, 0x00121712, 0x00131914, 0x00141a14, 0x00141a14, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180f, 0x000f130b, 0x0014180d, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130b, 0x000f130b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191d18, 0x00191d18, 0x00191d1a, 0x00181e18, 0x00181e18, 0x00181f17, 0x00171d18, 0x0019201a, 0x001b211a, 0x00141a13, 0x000f120c, 0x0010110c, 0x0011110b, 0x0014110a, 0x00161208, 0x001c170c, 0x0020190c, 0x00231809, 0x00281b0a, 0x0032230f, 0x0038260f, 0x00422e0c, 0x004c350c, 0x005b3f0c, 0x00724f14, 0x00906c17, 0x00c0a129, 0x00cbb41a, 0x00c9bc0e, 0x00cac110, 0x00cbc113, 0x00cbbf11, 0x00cbbc09, 0x00cbbb06, 0x00cabc09, 0x00c9bb09, 0x00c9bb07, 0x00cabb04, 0x00cbba04, 0x00ccb907, 0x00ccb80c, 0x00ccb40d, 0x00ccb110, 0x00caa910, 0x00c49f12, 0x00b8900c, 0x00a97a03, 0x009c6a00, 0x00925f00, 0x00855200, 0x007c4a00, 0x00774800, 0x00704400, 0x006b4000, 0x00643e02, 0x00593803, 0x00533502, 0x00503706, 0x004d3609, 0x0048330e, 0x0044300c, 0x00412f0a, 0x0040300a, 0x003e2c08, 0x003c2a05, 0x003d2808, 0x003d2808, 0x003d2808, 0x003e2909, 0x0040280a, 0x0041290b, 0x00402b0a, 0x00412b09, 0x00422b08, 0x00432a08, 0x00422a08, 0x00422a08, 0x00442b08, 0x00442b08, 0x00472c0a, 0x00482b0a, 0x00482b0c, 0x00482a0c, 0x00482a0c, 0x00472a09, 0x00452808, 0x00432509, 0x0040250c, 0x003c230b, 0x003a230a, 0x00382008, 0x00351e05, 0x00341d05, 0x00341d07, 0x00331c08, 0x00311c08, 0x00311c08, 0x00301c08, 0x00301c08, 0x00301c09, 0x00311c08, 0x00301b07, 0x00301a06, 0x00311b07, 0x00321d09, 0x00301c09, 0x002e1c08, 0x002c1c07, 0x002b1a06, 0x002c1b07, 0x002d1a07, 0x002d1a07, 0x002c1b07, 0x002a1906, 0x002a1907, 0x00281808, 0x00281809, 0x0028180b, 0x0027180a, 0x00241709, 0x00241608, 0x00231708, 0x00231708, 0x00231708, 0x00221608, 0x00221508, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1409, 0x001f1409, 0x001f1409, 0x001f1409, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001a1508, 0x001a1508, 0x00191408, 0x00181205, 0x00151204, 0x00151405, 0x00171305, 0x00181306, 0x00181306, 0x001b1407, 0x001b1407, 0x00191306, 0x00191306, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x001b1206, 0x001b1205, 0x001b1204, 0x001b1204, 0x001a1207, 0x00191208, 0x00191307, 0x00191306, 0x001c1206, 0x001d1207, 0x001d1207, 0x001d1205, 0x00201508, 0x001a1105, 0x001c1307, 0x001c1408, 0x001c1408, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1207, 0x001d1207, 0x001e1308, 0x001e1308, 0x001f140a, 0x001e130a, 0x001d1208, 0x001d1208, 0x001d130a, 0x001c140a, 0x001c1309, 0x001c1309, 0x001d1309, 0x001f1208, 0x001f1208, 0x00201409, 0x0020140a, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00221408, 0x00221408, 0x00231409, 0x0022160a, 0x0024150b, 0x00241509, 0x00251709, 0x00251708, 0x00261707, 0x00261607, 0x00271708, 0x00281708, 0x00281708, 0x00281708, 0x00281808, 0x00281809, 0x00281808, 0x002a1908, 0x002c1b09, 0x002f1c0a, 0x002f1c0a, 0x002d1c0a, 0x002f1c0b, 0x00321d09, 0x00341e08, 0x00372007, 0x003f250c, 0x0042270b, 0x00472a0b, 0x004a310a, 0x00503403, 0x005e3b00, 0x00754b06, 0x00845805, 0x00966a08, 0x00b08514, 0x00c49a14, 0x00cba814, 0x00cbb212, 0x00ccb411, 0x00ccb60e, 0x00ccb70c, 0x00ccb80b, 0x00cbb80b, 0x00cab80b, 0x00cab80b, 0x00cbb80a, 0x00cab409, 0x00cbb40b, 0x00ccb30c, 0x00cca810, 0x00bd8d08, 0x00aa7401, 0x009d6000, 0x00a16104, 0x00a16202, 0x00b47810, 0x00bc8910, 0x00c49511, 0x00c89f11, 0x00cca615, 0x00cca912, 0x00ccae13, 0x00ccb014, 0x00caaf0e, 0x00cab30c, 0x00cbb50a, 0x00cbb608, 0x00cbb608, 0x00cab608, 0x00c8b708, 0x00c8b708, 0x00c8b806, 0x00c9b707, 0x00c9b608, 0x00cbb509, 0x00cbb50a, 0x00cbb50c, 0x00cbb50c, 0x00cab50c, 0x00c9b50d, 0x00c9b60c, 0x00c9b60a, 0x00cbb508, 0x00ccac08, 0x00c8a108, 0x00c49c07, 0x00c8a80d, 0x00ccb416, 0x00caab18, 0x00be9318, 0x00a36e0c, 0x00875107, 0x006d4207, 0x00583809, 0x004c3007, 0x00432b08, 0x003f2a0b, 0x0038250b, 0x002f1d06, 0x00281805, 0x0027190a, 0x00201708, 0x00181305, 0x00161306, 0x00141008, 0x0014130c, 0x0010100b, 0x000e0e07, 0x00111008, 0x00101006, 0x0013120a, 0x0012140e, 0x000f140e, 0x00101610, 0x00101711, 0x000f1812, 0x00111914, 0x00121a15, 0x00131b16, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e1a, 0x00181e18, 0x00181e18, 0x00181f17, 0x00181f17, 0x001a2018, 0x001b2119, 0x00141a13, 0x0010110c, 0x0010100b, 0x0011110b, 0x0015130a, 0x00181209, 0x001e180c, 0x0021180a, 0x00241907, 0x002d200c, 0x00352710, 0x003c2911, 0x0046320d, 0x0053390d, 0x006a4812, 0x007f5a17, 0x00a58423, 0x00c9ad2c, 0x00ccb718, 0x00cbbd0e, 0x00cbc110, 0x00cbc111, 0x00ccc011, 0x00cbbd0b, 0x00cabc06, 0x00c9bc06, 0x00c8bb06, 0x00c8b805, 0x00c9b705, 0x00cab607, 0x00cbb40c, 0x00c8ab0c, 0x00c4a00a, 0x00bb8b07, 0x00ae7d04, 0x009c6d01, 0x008c5d00, 0x00835400, 0x00784c00, 0x006e4400, 0x00643d01, 0x00613c01, 0x005d3a01, 0x00583800, 0x00543400, 0x004f3303, 0x004f3309, 0x004c320a, 0x0049310c, 0x0046300e, 0x00412c0c, 0x003c2a09, 0x003b2807, 0x003a2807, 0x003a2707, 0x00382606, 0x00372405, 0x00362305, 0x00382307, 0x00382408, 0x00392409, 0x00392508, 0x00392709, 0x00392708, 0x00382606, 0x00372404, 0x00382406, 0x00382408, 0x003b2409, 0x003b240a, 0x00402509, 0x00412609, 0x0043270b, 0x0043260c, 0x0042250a, 0x00402406, 0x003f2306, 0x003c2108, 0x003a2108, 0x00371f08, 0x00351f08, 0x00331d06, 0x00321c05, 0x00301c05, 0x00301c06, 0x002f1a08, 0x002f1a09, 0x002e1a0a, 0x002e1b0a, 0x002e1b0a, 0x002e1b0a, 0x002e1b09, 0x002f1a08, 0x002e1908, 0x002e1907, 0x002f1b08, 0x002e1b0a, 0x002c1c0a, 0x00281a08, 0x00271908, 0x00281808, 0x00291808, 0x00291808, 0x00281807, 0x00281807, 0x00271808, 0x00251808, 0x00251709, 0x0024180a, 0x0024180b, 0x0024170b, 0x0023160a, 0x0023160a, 0x00231708, 0x00231708, 0x00221608, 0x00221608, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1409, 0x001f1409, 0x001f1409, 0x001f1409, 0x001e1407, 0x001e1407, 0x001d1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001b1407, 0x00181306, 0x00171305, 0x00181205, 0x00191306, 0x001a1306, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x001b1205, 0x001b1204, 0x001b1204, 0x001b1204, 0x001a1207, 0x00191208, 0x00191307, 0x00191306, 0x001c1206, 0x001d1207, 0x001d1207, 0x001d1205, 0x00201508, 0x001a1105, 0x001c1307, 0x001c1408, 0x001c1408, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1409, 0x001e1308, 0x001d1207, 0x001d1207, 0x001c1408, 0x001c1408, 0x001e1409, 0x001e1409, 0x001e1409, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201508, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201508, 0x00201408, 0x00211408, 0x00221608, 0x00221608, 0x00241508, 0x00241409, 0x0024150a, 0x0024160a, 0x0024160a, 0x0024160a, 0x0024160a, 0x0025170a, 0x00261608, 0x00281806, 0x00281807, 0x002b1908, 0x002c1b09, 0x002c1b09, 0x002d1c08, 0x00301c08, 0x00331d08, 0x00351d05, 0x00381f06, 0x003d2208, 0x0043290c, 0x00442e0c, 0x0048320a, 0x00503404, 0x005c3801, 0x006d4404, 0x007b4f01, 0x00895c00, 0x009d6d03, 0x00b0840c, 0x00bc9411, 0x00c7a015, 0x00cba814, 0x00ccad13, 0x00ccb00c, 0x00ccb00b, 0x00ccb00c, 0x00ccb10c, 0x00ccb00f, 0x00ccad0f, 0x00caa811, 0x00c49c0c, 0x00b78405, 0x00a87001, 0x009e6200, 0x00a96a0a, 0x00b57514, 0x00b0700c, 0x00ac6f05, 0x00a96d00, 0x00ac7200, 0x00b27a03, 0x00b98208, 0x00be890a, 0x00c59410, 0x00c39c10, 0x00c9a514, 0x00ccac14, 0x00ccb013, 0x00ccb40c, 0x00ccb40a, 0x00cbb508, 0x00cab608, 0x00cab707, 0x00cbb606, 0x00cbb607, 0x00cbb608, 0x00ccb409, 0x00ccb40b, 0x00ccb40c, 0x00cbb40d, 0x00cbb40d, 0x00cbb40d, 0x00cbb50c, 0x00c9b60a, 0x00cab508, 0x00ccae08, 0x00c8a309, 0x00c7a009, 0x00caac0f, 0x00cbb812, 0x00ccb514, 0x00cbad1d, 0x00bc8f14, 0x009c6a0c, 0x007f5208, 0x00644006, 0x00513303, 0x004a3008, 0x00402b0b, 0x003c280c, 0x00332108, 0x002a1a05, 0x00281908, 0x00241b09, 0x00191404, 0x00161304, 0x00151208, 0x00121109, 0x0011130b, 0x00101009, 0x00110f07, 0x00101006, 0x00101008, 0x0010120c, 0x000f140e, 0x00101610, 0x000f1811, 0x000f1912, 0x00101914, 0x00121a15, 0x00131b16, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e1a, 0x00181e1a, 0x00181e1a, 0x00181e18, 0x00181e18, 0x00182018, 0x00181f17, 0x001a2018, 0x001a1f18, 0x00141811, 0x0012140e, 0x0011110c, 0x0013100c, 0x00151209, 0x0019140a, 0x001e170b, 0x00221909, 0x00261a08, 0x0031220d, 0x00382710, 0x003e2b11, 0x004a330e, 0x00583c0d, 0x006f4c0e, 0x008a6417, 0x00b69628, 0x00c9b024, 0x00ccb814, 0x00cabc0d, 0x00c8be0d, 0x00c8c00c, 0x00cbc00e, 0x00ccc010, 0x00c8b60a, 0x00c8b309, 0x00c8af09, 0x00ccad0e, 0x00ccac11, 0x00caa815, 0x00c09c12, 0x00b08809, 0x00a17400, 0x00946000, 0x00885500, 0x00794c00, 0x00714800, 0x006a4403, 0x00603c02, 0x00583804, 0x00543708, 0x00513509, 0x004e3307, 0x004c3309, 0x004a330b, 0x0046320c, 0x0046300e, 0x00442c0d, 0x0042290e, 0x00402a0e, 0x003e290c, 0x003a2809, 0x00392608, 0x00372407, 0x00372407, 0x00362407, 0x00342107, 0x00342108, 0x00342007, 0x00342007, 0x00342107, 0x00342208, 0x00342208, 0x00322306, 0x00332206, 0x00342304, 0x00342204, 0x00342204, 0x00352204, 0x00372205, 0x00392307, 0x003c2308, 0x003c2408, 0x003c220b, 0x003c230a, 0x003b2307, 0x00382005, 0x00382008, 0x00372009, 0x00331d08, 0x00311d08, 0x00301c08, 0x002f1b06, 0x002d1c06, 0x002d1b08, 0x002c1a08, 0x002c180a, 0x002c180b, 0x002c180b, 0x002c180b, 0x002c180b, 0x002c180a, 0x002c1909, 0x002c1909, 0x002a1808, 0x002b1809, 0x00271708, 0x00261808, 0x00261a0a, 0x00271a0b, 0x0027180a, 0x0028180a, 0x00281809, 0x00271809, 0x00251808, 0x00251808, 0x00231709, 0x0023160a, 0x0023160c, 0x0023160c, 0x0023160c, 0x0023160b, 0x0023160a, 0x00221509, 0x00221608, 0x00211507, 0x00211507, 0x00221509, 0x00201408, 0x00201307, 0x00201307, 0x001f1409, 0x001f1409, 0x001f1409, 0x001f1409, 0x00201307, 0x00201307, 0x001e1407, 0x001d1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x00191306, 0x00181306, 0x00191306, 0x001c1307, 0x001c1307, 0x001d1207, 0x001d1207, 0x001e1308, 0x001c1206, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001b1204, 0x001b1204, 0x001b1204, 0x001b1204, 0x001b1308, 0x001b1309, 0x001a1308, 0x00191306, 0x001c1206, 0x001d1207, 0x001d1207, 0x001d1205, 0x00201508, 0x001b1206, 0x001c1307, 0x001e1409, 0x001e1409, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1409, 0x001e1308, 0x001d1207, 0x001d1207, 0x001c140a, 0x001c140a, 0x001c1309, 0x001c1208, 0x001c1209, 0x001e130a, 0x001e130a, 0x001e130a, 0x001e130a, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x00201409, 0x001f1409, 0x001e1409, 0x001d1409, 0x001e1407, 0x001e1407, 0x00201508, 0x00201508, 0x00211507, 0x00211506, 0x00211506, 0x00211506, 0x00211507, 0x00221607, 0x00221607, 0x00221607, 0x00241607, 0x00241607, 0x00251608, 0x00281709, 0x0028180a, 0x0028180a, 0x00291809, 0x002f1b0b, 0x00321d0b, 0x00341e0a, 0x00351d08, 0x00392009, 0x003e250c, 0x00402a0d, 0x00442c0d, 0x004a300a, 0x00503306, 0x005b3705, 0x00693f06, 0x007c4e08, 0x00885404, 0x00956004, 0x00a46e04, 0x00ad7807, 0x00b48008, 0x00bb8b08, 0x00c09206, 0x00c59a0c, 0x00c69a0c, 0x00c59b0c, 0x00c1980c, 0x00bb8f08, 0x00b58506, 0x00a77200, 0x00a16800, 0x00a66a06, 0x00b07510, 0x00c0891b, 0x00cb9b21, 0x00ca981b, 0x00c59114, 0x00bd880c, 0x00b57e05, 0x00af7501, 0x00ac7001, 0x00a96b00, 0x00a46800, 0x00a46f02, 0x00ae7c07, 0x00b6880d, 0x00c59b18, 0x00caa714, 0x00ccab14, 0x00cbac10, 0x00cbb00f, 0x00cbb10c, 0x00ccb30b, 0x00ccb30a, 0x00ccb40b, 0x00ccb40c, 0x00ccb40d, 0x00ccb40d, 0x00cbb40d, 0x00cbb40d, 0x00cbb40d, 0x00cab40b, 0x00c8b509, 0x00cab408, 0x00ccac08, 0x00c8a308, 0x00c9a30c, 0x00ccaf11, 0x00cab911, 0x00cbb90f, 0x00ccb814, 0x00c8aa13, 0x00a88007, 0x00895e00, 0x00734a04, 0x005c3a02, 0x004f3107, 0x00452c09, 0x0040290a, 0x003a250c, 0x002e1c05, 0x00261704, 0x00261b08, 0x001f1808, 0x00181404, 0x00161208, 0x00100e07, 0x0010120a, 0x00121108, 0x00101008, 0x00101006, 0x00101008, 0x0010110c, 0x000f140e, 0x00101510, 0x000f1611, 0x000e1813, 0x00101815, 0x00111816, 0x00121917, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e1a, 0x00181e1a, 0x00181e1a, 0x00181e18, 0x00181e18, 0x00182018, 0x00182018, 0x001a2018, 0x00191e17, 0x0010140d, 0x0010110c, 0x0012110c, 0x0013100b, 0x00161109, 0x0019140a, 0x0020180c, 0x00221808, 0x00271a07, 0x0031220a, 0x0039270f, 0x00402c10, 0x004d340e, 0x005c3d0d, 0x00704c08, 0x00986f1c, 0x00c4a72e, 0x00cab41e, 0x00ccba10, 0x00cabd0c, 0x00c8bd0d, 0x00c8bf09, 0x00cbbf0a, 0x00ccbc10, 0x00c5ac0d, 0x00bf9d08, 0x00bb9305, 0x00bc8c08, 0x00b88408, 0x00b37e0d, 0x00a07008, 0x008a5c00, 0x007c5000, 0x006f4500, 0x00684200, 0x005f3c00, 0x00593a00, 0x00573801, 0x00543605, 0x00513407, 0x004f3108, 0x004e3109, 0x004b300a, 0x00482f0c, 0x00442e0c, 0x00402c09, 0x003e2a09, 0x003e2708, 0x003d2409, 0x003c240a, 0x00392409, 0x00362407, 0x00342107, 0x00321e04, 0x00321e04, 0x00311d04, 0x002f1d05, 0x002f1c05, 0x00301d06, 0x00301d06, 0x00301d06, 0x00301d06, 0x00301d06, 0x00311d04, 0x00311d04, 0x00321c04, 0x00311d04, 0x00301e05, 0x00301e06, 0x00321e06, 0x00331e06, 0x00321e04, 0x00321d06, 0x00341d08, 0x00341e08, 0x00352006, 0x00341f05, 0x00341e08, 0x00331d09, 0x002f1b08, 0x002d1b08, 0x002c1c08, 0x002c1c08, 0x002c1b08, 0x002a1b0a, 0x00291809, 0x0028170a, 0x0028170b, 0x0028170b, 0x0028170b, 0x0028170b, 0x0028170a, 0x00281709, 0x00281709, 0x00281809, 0x0029190b, 0x00251709, 0x00241809, 0x00231809, 0x00231809, 0x00231708, 0x00241608, 0x00251709, 0x00241608, 0x00231708, 0x0023160a, 0x0020150a, 0x0020150a, 0x0020140b, 0x0021140c, 0x0021140c, 0x0021140c, 0x0021140a, 0x00221608, 0x00221608, 0x00211507, 0x00211507, 0x00221509, 0x00201408, 0x00201307, 0x00201307, 0x001f1409, 0x001f1409, 0x001f1409, 0x001f1409, 0x00201307, 0x00201307, 0x001e1407, 0x001d1407, 0x001d1308, 0x001e1308, 0x001e1308, 0x001d1308, 0x001a1206, 0x00181306, 0x001a1306, 0x001c1307, 0x001c1307, 0x001d1207, 0x001d1207, 0x001e1308, 0x001c1106, 0x001a1204, 0x00191304, 0x00191304, 0x00191304, 0x001b1204, 0x001b1204, 0x001b1204, 0x001b1204, 0x001b1308, 0x001b1309, 0x001a1307, 0x00191306, 0x001c1206, 0x001d1207, 0x001d1207, 0x001d1205, 0x00201508, 0x001b1206, 0x001c1307, 0x001e1409, 0x001e1409, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1304, 0x001d1304, 0x001e1405, 0x001e1406, 0x001f1408, 0x001d1205, 0x001d1205, 0x001d1205, 0x001c1409, 0x001c140a, 0x001c1309, 0x001c1208, 0x001c1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1508, 0x001d1508, 0x001c1508, 0x001c1405, 0x001c1405, 0x001f1608, 0x001f150a, 0x00201508, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00221608, 0x00221608, 0x00241608, 0x00241608, 0x00251709, 0x00251709, 0x00261808, 0x002b1809, 0x00301c0a, 0x00321c09, 0x00331c08, 0x00381f09, 0x003d240c, 0x0040280c, 0x00442a0d, 0x004c300d, 0x0052340c, 0x0059380c, 0x00613a08, 0x0073460c, 0x0084500d, 0x00a36a1b, 0x00b47817, 0x00ae730c, 0x00a86e04, 0x00a86e00, 0x00a66c00, 0x00a86d00, 0x00aa7000, 0x00a97000, 0x00a56e00, 0x00a46c00, 0x00a66c00, 0x00aa6c00, 0x00ac730c, 0x00bc871f, 0x00c69722, 0x00cca51d, 0x00ccae16, 0x00ccb013, 0x00ccb015, 0x00ccac15, 0x00cca515, 0x00c99c14, 0x00c38f16, 0x00ad730b, 0x009a5b00, 0x00975704, 0x00945600, 0x00975d00, 0x00a06c05, 0x00ad7e09, 0x00bb8e13, 0x00c09816, 0x00c7a318, 0x00caac13, 0x00ccb014, 0x00ccb113, 0x00ccb212, 0x00ccb211, 0x00ccb310, 0x00ccb40e, 0x00cbb40d, 0x00cbb40d, 0x00cbb40d, 0x00cab40b, 0x00c8b408, 0x00c9b407, 0x00cbac07, 0x00c8a208, 0x00c9a30c, 0x00cbb012, 0x00cab913, 0x00c9bb0e, 0x00cbb90d, 0x00c9b50f, 0x00b9980c, 0x00986e00, 0x00805403, 0x00684103, 0x00543407, 0x004a2f09, 0x00432a0a, 0x003d270c, 0x00321f07, 0x00281804, 0x00251906, 0x00231b0a, 0x001a1506, 0x00181408, 0x00111009, 0x00101208, 0x00121108, 0x0011110a, 0x00101007, 0x00101008, 0x0010110c, 0x0010130e, 0x00101510, 0x00101511, 0x000e1813, 0x00101816, 0x00121918, 0x00121918, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e18, 0x00182019, 0x00182019, 0x0019201a, 0x001b2018, 0x001c1f18, 0x00181a14, 0x0011130c, 0x0012110b, 0x0013120b, 0x0014110a, 0x00161108, 0x001b1309, 0x0020170b, 0x00231808, 0x002c1e0a, 0x0034240a, 0x003a280c, 0x00412c0c, 0x004e360e, 0x005c3e0e, 0x00744d0f, 0x00a27b21, 0x00c9ad2c, 0x00cbb818, 0x00ccbc0c, 0x00cabd0b, 0x00cabd0d, 0x00c9bc0a, 0x00cbbc0c, 0x00cab411, 0x00b8940c, 0x00a47503, 0x009f6b01, 0x00945d00, 0x008f5800, 0x00855600, 0x00795000, 0x006c4700, 0x00603f01, 0x005b3a05, 0x00583907, 0x00543806, 0x004e3405, 0x004d3507, 0x004b3407, 0x004c340b, 0x0048300b, 0x00442b08, 0x00442a0a, 0x0040270b, 0x003c2508, 0x003a2407, 0x00382408, 0x00382308, 0x00372008, 0x00351e08, 0x00331f08, 0x00331f08, 0x00331f08, 0x00311c06, 0x00311c08, 0x00301d08, 0x002d1c07, 0x002b1b06, 0x002c1b07, 0x002c1c08, 0x002c1c08, 0x002c1c08, 0x002e1b08, 0x002e1b08, 0x002d1b06, 0x002c1a05, 0x002c1a05, 0x002c1906, 0x002b1804, 0x002e1c06, 0x002f1c07, 0x00301d08, 0x00301d08, 0x00301c07, 0x00301c05, 0x002f1c04, 0x002e1904, 0x00301c08, 0x002f1c08, 0x002d1a09, 0x002c190a, 0x002c190a, 0x002b180a, 0x0028180c, 0x0028180c, 0x00261609, 0x0025150a, 0x0027150a, 0x0028150b, 0x0028150b, 0x0027160b, 0x0025170a, 0x00241608, 0x00241608, 0x00241608, 0x00241608, 0x0026180c, 0x0026180c, 0x0024170a, 0x00231409, 0x00221509, 0x00221509, 0x00221509, 0x0023160a, 0x0023160a, 0x0023160a, 0x00211408, 0x00201409, 0x00201409, 0x0020150a, 0x0020150a, 0x0020150a, 0x00201508, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00211408, 0x00201408, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201307, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001f1408, 0x001c1205, 0x001c1305, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1409, 0x001c1106, 0x001b1005, 0x001c1106, 0x001d1208, 0x001e1308, 0x001e1308, 0x001c1408, 0x001d1408, 0x001f1307, 0x001e1407, 0x001e1407, 0x001e1508, 0x001b1206, 0x001c1307, 0x0020150a, 0x001e1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001d1205, 0x001c1204, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1306, 0x001c1307, 0x001c1408, 0x001e1308, 0x001e1308, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001c1305, 0x001c1305, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1306, 0x001e1407, 0x001f1407, 0x00221509, 0x0024170b, 0x0024160a, 0x0024160a, 0x0024160a, 0x00241608, 0x00281809, 0x002b1b08, 0x002e1b08, 0x00311c08, 0x00341c08, 0x003a2108, 0x003f2608, 0x0040280b, 0x00462b0b, 0x004c3008, 0x00543505, 0x00643f0b, 0x00754a10, 0x008a5910, 0x00b88729, 0x00cb9e2a, 0x00cb9e20, 0x00c89918, 0x00c29117, 0x00b58211, 0x00b37f0a, 0x00b17c08, 0x00b17b0b, 0x00b17c0c, 0x00b27c0b, 0x00b7820d, 0x00c6921b, 0x00c89f1e, 0x00c9a81f, 0x00ccac1b, 0x00ccb014, 0x00ccb30e, 0x00ccb409, 0x00ccb409, 0x00cab40b, 0x00cbb410, 0x00ccb214, 0x00cca91a, 0x00b88913, 0x00945b00, 0x008b5107, 0x007f4800, 0x007d4902, 0x00804f01, 0x00875703, 0x00905f02, 0x009c6c05, 0x00a8780b, 0x00b4870c, 0x00c19515, 0x00c89e18, 0x00caa418, 0x00cba714, 0x00ccac13, 0x00ccaf10, 0x00ccb30f, 0x00ccb60f, 0x00cbb40c, 0x00cab40b, 0x00cab409, 0x00cab308, 0x00caab0c, 0x00c9a00b, 0x00c8a30f, 0x00cbb114, 0x00c9ba12, 0x00c8bb0b, 0x00c8bb07, 0x00c8ba0a, 0x00c9ad15, 0x00a67c04, 0x008a5c04, 0x00754c08, 0x005c3b03, 0x00503305, 0x00462c08, 0x003e270a, 0x00362309, 0x002b1c04, 0x00251804, 0x00221a09, 0x001a1506, 0x00181407, 0x00141407, 0x00121108, 0x00101108, 0x00101009, 0x000f1008, 0x0010120a, 0x0011120c, 0x0010130e, 0x00101411, 0x000f1411, 0x000d1712, 0x000f1816, 0x00101818, 0x00121918, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e18, 0x00182019, 0x00182019, 0x0019201a, 0x001c1f18, 0x001d1e18, 0x00181a14, 0x0010120c, 0x0012120c, 0x0014120c, 0x0014110b, 0x00181108, 0x001d160c, 0x0020160b, 0x00231707, 0x002e200a, 0x0037260a, 0x003c290d, 0x00442e0a, 0x0051390e, 0x00604010, 0x007e5817, 0x00af8828, 0x00cbb028, 0x00ccb918, 0x00ccbc0c, 0x00cbbe0b, 0x00cbbc0c, 0x00ccbb0c, 0x00ccb710, 0x00ba9b06, 0x009c7400, 0x00885802, 0x00835200, 0x007f4c04, 0x00784802, 0x006c4400, 0x00603e00, 0x005b3c02, 0x00543804, 0x00533607, 0x00503408, 0x004c3408, 0x00483006, 0x00452f06, 0x00412c04, 0x00432e08, 0x00402906, 0x003c2706, 0x003c2608, 0x003b2408, 0x00382108, 0x00342006, 0x00341f06, 0x00331f08, 0x00331d08, 0x00321d09, 0x00301d08, 0x00301d08, 0x002e1c06, 0x002c1904, 0x002c1906, 0x002c1a06, 0x002a1a06, 0x00281905, 0x00291808, 0x002b1909, 0x002b1909, 0x002b1909, 0x002c1808, 0x002c1808, 0x002a1807, 0x00291807, 0x00291806, 0x00281804, 0x00281603, 0x002a1806, 0x002c1a08, 0x002c1a08, 0x002c1a08, 0x002e1b08, 0x002f1c07, 0x002e1c04, 0x002c1904, 0x002c1a07, 0x002c1a08, 0x002c1808, 0x002c1809, 0x002c190c, 0x002b170c, 0x0028150b, 0x0027160b, 0x0025150a, 0x0025150a, 0x0027150b, 0x0028150b, 0x0027160b, 0x0025170b, 0x0024180a, 0x00231708, 0x00231708, 0x00231708, 0x00231708, 0x0024160a, 0x0024160a, 0x0025170b, 0x00231409, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00211408, 0x00211408, 0x00201508, 0x001f1608, 0x001f1608, 0x001f1608, 0x00201508, 0x00201408, 0x00211408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001e1407, 0x001d1407, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1308, 0x001d1207, 0x001d1207, 0x001d1207, 0x001f1208, 0x001f1308, 0x001e1308, 0x001d1308, 0x001f1308, 0x00201307, 0x001e1407, 0x001e1407, 0x001e1508, 0x001b1206, 0x001c1307, 0x001f1409, 0x0020150a, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1406, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1306, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x00201408, 0x00221509, 0x0024160a, 0x0024160a, 0x0024160a, 0x00241608, 0x00261708, 0x002a1a09, 0x002c1906, 0x00311c08, 0x00341c07, 0x00381f08, 0x003b2307, 0x003f2609, 0x00452a0c, 0x004b3008, 0x00533303, 0x00603c08, 0x0072480e, 0x00906314, 0x00c49b2e, 0x00ccaf22, 0x00ccb015, 0x00ccb011, 0x00ccac18, 0x00cba91e, 0x00caa718, 0x00caa517, 0x00caa419, 0x00cba51c, 0x00cba619, 0x00cba818, 0x00ccaa1a, 0x00ccad17, 0x00cbb016, 0x00cbb211, 0x00cbb30d, 0x00cbb40c, 0x00cbb50a, 0x00c8b706, 0x00c7b607, 0x00c8b70b, 0x00cbb40e, 0x00cbab14, 0x00b3840a, 0x00915b00, 0x007c4b02, 0x00704000, 0x006c3e01, 0x006f4302, 0x00714501, 0x007a4d03, 0x00845504, 0x00895800, 0x00905c00, 0x00986402, 0x009d6901, 0x00ac780a, 0x00b7840e, 0x00c08f12, 0x00c69614, 0x00cba017, 0x00cba615, 0x00cba910, 0x00ccab10, 0x00ccac0e, 0x00ccac0c, 0x00c9a60a, 0x00c89c07, 0x00c9a30a, 0x00cab310, 0x00cab911, 0x00cabb09, 0x00c8bb05, 0x00c8bb09, 0x00cbb314, 0x00b48e0c, 0x00906201, 0x0081560b, 0x00644004, 0x00533402, 0x00482d05, 0x0040290a, 0x0038240b, 0x002c1d05, 0x00241602, 0x00221808, 0x00211a0c, 0x00171404, 0x00151405, 0x00121106, 0x00101108, 0x00101009, 0x000f1008, 0x00101009, 0x0010100a, 0x000f120d, 0x00101410, 0x000f1410, 0x000e1613, 0x000f1816, 0x00101818, 0x00121918, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e18, 0x00181f19, 0x0019201a, 0x001b211b, 0x001c2019, 0x001c1d17, 0x00161711, 0x0014140e, 0x0014120c, 0x0014120c, 0x0015120b, 0x001b140c, 0x0020160c, 0x0021160b, 0x00271b0b, 0x0031230b, 0x00372708, 0x003f2b0c, 0x0048330c, 0x00543c10, 0x0062440f, 0x00866118, 0x00b9942a, 0x00ccb222, 0x00cbb916, 0x00ccbc0f, 0x00ccbc0c, 0x00ccbb0c, 0x00cbb70e, 0x00c7a911, 0x00a27d00, 0x00885f00, 0x00784e00, 0x00724b01, 0x00694402, 0x00603d00, 0x00573b00, 0x00513801, 0x004f3707, 0x004c3408, 0x004c3208, 0x004c320a, 0x0048310b, 0x00432e08, 0x003f2c07, 0x003c2805, 0x003c2808, 0x003a2507, 0x00382305, 0x00382206, 0x00372108, 0x00342008, 0x00321d07, 0x00301d06, 0x00301d08, 0x002f1c08, 0x002d1b08, 0x002e1b08, 0x002e1b08, 0x002c1a07, 0x002b1805, 0x00291807, 0x00281807, 0x00281907, 0x00281a07, 0x00281808, 0x00281809, 0x0028180a, 0x0028180a, 0x00291808, 0x00291808, 0x00281707, 0x00271706, 0x00271706, 0x00241504, 0x00241403, 0x00251605, 0x00281809, 0x0029190b, 0x002b1909, 0x002b1908, 0x002c1a07, 0x002d1c06, 0x002b1a06, 0x002c1a08, 0x002a1808, 0x00291808, 0x00291808, 0x002b180b, 0x0028170b, 0x0025150a, 0x0024160a, 0x00241509, 0x00241409, 0x0025150a, 0x0025150a, 0x0024160a, 0x0023160a, 0x0023160a, 0x00231708, 0x00231708, 0x00231708, 0x00231708, 0x00241409, 0x00241409, 0x00231408, 0x00221408, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00201408, 0x00201408, 0x001f1608, 0x001f1608, 0x001f1608, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001d1306, 0x001e1407, 0x00201508, 0x00201508, 0x00201508, 0x001e1407, 0x001d1306, 0x001f1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001d1207, 0x001d1207, 0x001d1207, 0x001f1208, 0x001f1308, 0x001e1308, 0x001d1308, 0x001f1308, 0x00201307, 0x001e1407, 0x001e1407, 0x001e1508, 0x001b1206, 0x001c1307, 0x0020140a, 0x0020160b, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1306, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1306, 0x001b1407, 0x001c1308, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x00201307, 0x00221509, 0x00241409, 0x00241409, 0x0024160a, 0x00241608, 0x00271709, 0x00281808, 0x002c1808, 0x00301b08, 0x00341c08, 0x00381f08, 0x003b2208, 0x003e240a, 0x0044290d, 0x00492e0a, 0x00533307, 0x005f3809, 0x006d4409, 0x00916414, 0x00c7a02c, 0x00c9b418, 0x00cab70c, 0x00cab808, 0x00cab60f, 0x00cbb412, 0x00cbb40e, 0x00ccb50f, 0x00ccb412, 0x00ccb514, 0x00ccb512, 0x00ccb50e, 0x00cbb40c, 0x00cbb40e, 0x00cab40e, 0x00cab40d, 0x00c9b50c, 0x00c8b60c, 0x00c8b708, 0x00c7b704, 0x00c8b708, 0x00cbb50c, 0x00ccb413, 0x00caa614, 0x00a87804, 0x00885200, 0x00734600, 0x00643700, 0x00603601, 0x005c3500, 0x005c3801, 0x00613c04, 0x00694204, 0x00714707, 0x00784b08, 0x0082510c, 0x0088540a, 0x008d5708, 0x00935a06, 0x00986008, 0x00a2690c, 0x00a9720d, 0x00af7c0c, 0x00b98b0c, 0x00c29510, 0x00c89c12, 0x00cba010, 0x00c5980d, 0x00c7940c, 0x00c8a00c, 0x00ccb512, 0x00cbb910, 0x00cbba09, 0x00cabc06, 0x00c8bb0a, 0x00ccb412, 0x00c19e12, 0x009c7003, 0x00875908, 0x006e4808, 0x00563501, 0x00482d02, 0x00402908, 0x00392508, 0x00301f08, 0x00271703, 0x00211507, 0x00241b0d, 0x00181505, 0x00141405, 0x00131107, 0x00121108, 0x00101008, 0x00101108, 0x00101108, 0x00101009, 0x0010110c, 0x00111310, 0x000f1412, 0x000e1514, 0x000e1716, 0x00101817, 0x00101818, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e18, 0x00181f19, 0x0019201a, 0x001b211a, 0x001f241c, 0x00181a14, 0x0014130c, 0x0014120c, 0x0014120c, 0x0014130a, 0x0018140c, 0x001d170d, 0x001f160b, 0x0020160b, 0x002b1d0d, 0x00322409, 0x00392808, 0x00422f0d, 0x004c380f, 0x00563d0e, 0x00684b11, 0x008d6919, 0x00c19e2b, 0x00cbb31c, 0x00cbba14, 0x00cabc0f, 0x00cbbc0b, 0x00cab90c, 0x00ccb410, 0x00b8970c, 0x00926600, 0x007f5304, 0x006e4a04, 0x00624201, 0x00583e03, 0x00503800, 0x004c3804, 0x00483504, 0x00483408, 0x00473008, 0x00482f0a, 0x00452c09, 0x00402b0a, 0x003c2808, 0x00382605, 0x00342304, 0x00342307, 0x00322006, 0x00301f05, 0x00301f04, 0x00311d08, 0x00301c08, 0x002e1c08, 0x002e1c08, 0x002c1c09, 0x002a1b0a, 0x002a1808, 0x002c1908, 0x002c1908, 0x00281805, 0x00281604, 0x00261605, 0x00251605, 0x00251705, 0x00241705, 0x00241604, 0x00241605, 0x00251706, 0x00261807, 0x00281809, 0x00281809, 0x00271708, 0x00251709, 0x00261709, 0x00231407, 0x00221406, 0x00221308, 0x00231408, 0x0025160a, 0x0028180b, 0x002b180b, 0x002b1909, 0x002a1b08, 0x00281806, 0x00281808, 0x00271708, 0x00281808, 0x00281809, 0x00261608, 0x0027160a, 0x0024160a, 0x0023160a, 0x00231509, 0x00221509, 0x0024150a, 0x0024160a, 0x0023160a, 0x0023160a, 0x0022170a, 0x00231708, 0x00231708, 0x00231708, 0x00231708, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00201408, 0x001f1407, 0x001c1407, 0x001e1508, 0x001c1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1408, 0x001e1407, 0x001f1408, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001d1207, 0x001c1106, 0x001d1207, 0x001f1208, 0x001f1308, 0x001e1308, 0x001d1308, 0x001f1308, 0x00201307, 0x001e1407, 0x001e1407, 0x001e1508, 0x001b1206, 0x001c1307, 0x0020150a, 0x0020150a, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001c1306, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1306, 0x001b1407, 0x001c1307, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x00211409, 0x00221509, 0x00241409, 0x00241409, 0x0024160a, 0x00241608, 0x0028180b, 0x00291808, 0x002c1a08, 0x00301b08, 0x00321c08, 0x00361e08, 0x003b220a, 0x003f250e, 0x00442810, 0x00482c0b, 0x00523209, 0x005e380c, 0x0070460c, 0x00986c19, 0x00cba530, 0x00c9b417, 0x00cab70b, 0x00cab808, 0x00cab70d, 0x00c8b60c, 0x00c8b709, 0x00c9b80a, 0x00c9b80c, 0x00cab80d, 0x00cab80c, 0x00c9b809, 0x00c8b807, 0x00c8b708, 0x00c9b608, 0x00c9b608, 0x00c8b708, 0x00c8b806, 0x00c8b704, 0x00c9b404, 0x00cbb10b, 0x00cbad0f, 0x00cba80f, 0x00c0950e, 0x009d6902, 0x00854f04, 0x006c4401, 0x005b3400, 0x00583306, 0x00523004, 0x004c3006, 0x004e3307, 0x00503205, 0x00543304, 0x00593705, 0x005d3a04, 0x00673d04, 0x0074460a, 0x007b4a09, 0x00814e0b, 0x0088530c, 0x008d5608, 0x008f5806, 0x00925c03, 0x00986300, 0x009c6900, 0x00a87402, 0x00b07708, 0x00b57b07, 0x00c49812, 0x00ccb319, 0x00cbb811, 0x00cbba09, 0x00cabc06, 0x00c9bc0b, 0x00ccb810, 0x00caaa14, 0x00a87d05, 0x00885800, 0x00714a08, 0x00593a02, 0x004b3003, 0x00432c09, 0x003c280b, 0x0036230b, 0x002c1b06, 0x00221405, 0x0021180b, 0x001c1908, 0x00141405, 0x00141207, 0x00121107, 0x00101008, 0x00101108, 0x00101108, 0x00101009, 0x0010110c, 0x0011140f, 0x00101412, 0x000e1514, 0x000e1716, 0x000f1817, 0x00101818, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181d18, 0x00182018, 0x00182018, 0x001a2018, 0x001d2119, 0x00161710, 0x0012120b, 0x0013120a, 0x0014120a, 0x0014130a, 0x0018150c, 0x001c170b, 0x001c1407, 0x00211907, 0x002c210b, 0x00322508, 0x003a2a06, 0x0043310d, 0x004c3a0e, 0x00583d0c, 0x00714f11, 0x0099731c, 0x00c8a62a, 0x00ccb518, 0x00caba11, 0x00c9bc0e, 0x00cbbc0b, 0x00ccb80b, 0x00c7ac0f, 0x00a78204, 0x00875b02, 0x00734b05, 0x00614204, 0x00573c03, 0x004f3907, 0x00483606, 0x00443408, 0x00423207, 0x00443008, 0x00432d08, 0x00422b08, 0x003f2808, 0x003a2507, 0x00362306, 0x00322104, 0x00312004, 0x002f1f03, 0x002e1e03, 0x002f1d06, 0x00301c09, 0x002e1c0a, 0x002c1b0a, 0x002b1a09, 0x00291908, 0x00281808, 0x00271808, 0x00271708, 0x00261605, 0x00261605, 0x00251504, 0x00241604, 0x00241507, 0x00241508, 0x00241508, 0x00241608, 0x00241608, 0x00241608, 0x00241608, 0x00251708, 0x00251608, 0x00261608, 0x0027160b, 0x0026160a, 0x00241609, 0x0023140a, 0x00201308, 0x001c1008, 0x0020140c, 0x0023140c, 0x0026150c, 0x0028180c, 0x0029180b, 0x00281708, 0x00281608, 0x00281709, 0x00251407, 0x00261608, 0x00261608, 0x00241408, 0x00251509, 0x00241509, 0x00241509, 0x00231409, 0x00231409, 0x00241409, 0x00231509, 0x00221609, 0x00211609, 0x00211609, 0x00201608, 0x00201608, 0x00211609, 0x00211609, 0x00211408, 0x00221408, 0x00211408, 0x00231509, 0x00211408, 0x00201408, 0x00211408, 0x00211408, 0x00201508, 0x00201508, 0x00201508, 0x00201408, 0x001e1306, 0x001d1306, 0x001d1306, 0x001d1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001d1205, 0x00201408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1307, 0x001e1306, 0x001e1306, 0x001d1205, 0x001e1306, 0x001e1306, 0x001e1306, 0x001e1306, 0x001d1306, 0x001d1306, 0x001f1406, 0x001f1407, 0x001d1304, 0x001d1304, 0x001d1208, 0x001e1308, 0x001d1208, 0x001d1208, 0x001f1208, 0x001f1308, 0x001e1308, 0x001e1409, 0x001e1408, 0x001e1406, 0x001e1406, 0x001d1407, 0x001c1407, 0x001c1306, 0x001c1307, 0x001f1409, 0x001f1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201407, 0x00201407, 0x001f1406, 0x001d1406, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1406, 0x001c1407, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1408, 0x001d1306, 0x001e1306, 0x001f1408, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001f1306, 0x001f1306, 0x00201307, 0x00201307, 0x001f1406, 0x001f1406, 0x001f1406, 0x001f1406, 0x001f1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00231409, 0x00231409, 0x00241409, 0x00241409, 0x0025150b, 0x0026160a, 0x0028180a, 0x00281809, 0x002b1908, 0x002f1b08, 0x00311b08, 0x00341c07, 0x0039210a, 0x003d250e, 0x00432810, 0x00482c0c, 0x0051320b, 0x005e390f, 0x006f470d, 0x009a6f1b, 0x00cba42f, 0x00cbb11b, 0x00ccb50e, 0x00ccb609, 0x00ccb50e, 0x00cbb50d, 0x00cbb608, 0x00cbb807, 0x00cbb709, 0x00cbb60c, 0x00cbb70b, 0x00cbb709, 0x00cab608, 0x00cab608, 0x00cbb708, 0x00cbb60a, 0x00cbb409, 0x00cbb208, 0x00ccaf08, 0x00cba80b, 0x00c6a00d, 0x00c0950f, 0x00b6860a, 0x00a57003, 0x008c5500, 0x007b4604, 0x00694004, 0x00593400, 0x00563206, 0x00503007, 0x004a3008, 0x004b3009, 0x004c3009, 0x004c2f0a, 0x004b2f06, 0x004b3003, 0x004f3000, 0x00523200, 0x00573500, 0x00603c03, 0x00664104, 0x006c4606, 0x0074480b, 0x00804c0f, 0x0083500c, 0x00845308, 0x00875604, 0x00915a02, 0x00a16607, 0x00bd8f18, 0x00cbb01c, 0x00ccb811, 0x00ccbb0a, 0x00cbbc08, 0x00cabc0b, 0x00ccb911, 0x00ccb016, 0x00b2880b, 0x008c5c00, 0x00744c04, 0x005c3c00, 0x004d3204, 0x00442f0b, 0x003d290c, 0x0038240b, 0x002e1e07, 0x00251806, 0x00201507, 0x001f1808, 0x00181306, 0x00141307, 0x00121207, 0x00111108, 0x00111108, 0x00101108, 0x000f1108, 0x000f110a, 0x000f110d, 0x000e120f, 0x000e1513, 0x000c1413, 0x000e1614, 0x00101815, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00191d18, 0x00192018, 0x00192018, 0x001a2018, 0x001d2119, 0x0016170e, 0x00121209, 0x00131209, 0x00141309, 0x00151309, 0x0018160b, 0x001c160b, 0x001c1404, 0x00261e09, 0x00291f05, 0x00342608, 0x003c2c08, 0x0044320d, 0x004e3a0c, 0x005c400c, 0x00775111, 0x00a88026, 0x00ccae2c, 0x00ccb714, 0x00c8bb0e, 0x00c9bc0c, 0x00ccbc09, 0x00ccb70c, 0x00c0a10c, 0x009a7301, 0x00805503, 0x00694604, 0x00583c01, 0x004f3602, 0x00493406, 0x0046340a, 0x0041310a, 0x003f2e08, 0x003f2a07, 0x003d2605, 0x003c2404, 0x00392304, 0x00352004, 0x00332005, 0x00301f05, 0x00301e06, 0x002f1d05, 0x002d1c04, 0x002c1b07, 0x002c1b08, 0x002c1a09, 0x00291908, 0x00281808, 0x00261706, 0x00261706, 0x00241406, 0x00251607, 0x00241706, 0x00231605, 0x00211404, 0x00211404, 0x00211407, 0x00211408, 0x00231508, 0x00231508, 0x00231509, 0x00231509, 0x00231509, 0x0024160a, 0x00241609, 0x00241609, 0x0025150b, 0x0024140a, 0x0023140a, 0x0023150b, 0x0020140a, 0x001a1007, 0x001d140b, 0x0020140b, 0x0024140b, 0x0025150a, 0x00261508, 0x00271609, 0x00261508, 0x00261508, 0x00261508, 0x00251508, 0x00241608, 0x00241608, 0x00241608, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00231409, 0x00211509, 0x00201609, 0x00201709, 0x00201508, 0x00201508, 0x00201609, 0x00201609, 0x00201508, 0x00201508, 0x00201508, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1306, 0x001d1306, 0x001e1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1104, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1306, 0x001e1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001f1406, 0x001f1406, 0x001d1304, 0x001d1304, 0x001d1207, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1208, 0x001f1308, 0x001f1409, 0x001f1409, 0x001e1408, 0x001e1405, 0x001e1405, 0x001c1407, 0x001c1407, 0x001c1305, 0x001c1407, 0x001f1409, 0x001f1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201406, 0x00201406, 0x001f1406, 0x001e1506, 0x001d1507, 0x001c1508, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001d1205, 0x001d1306, 0x00201508, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x001f1406, 0x001f1406, 0x001f1406, 0x001f1406, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x00201508, 0x00221509, 0x00211408, 0x00201408, 0x00201408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x0025140c, 0x0027160b, 0x00271609, 0x0028180a, 0x002a1908, 0x002e1b08, 0x00311c0c, 0x00331c0b, 0x00361f08, 0x003c240c, 0x0042280f, 0x00482d0c, 0x0050330b, 0x005d3b0f, 0x0070490f, 0x009d741d, 0x00cba72f, 0x00cbb019, 0x00ccb60c, 0x00ccb707, 0x00ccb60b, 0x00cbb60c, 0x00ccb707, 0x00ccb804, 0x00ccb707, 0x00ccb508, 0x00ccb506, 0x00cbb406, 0x00cbb306, 0x00ccb10c, 0x00ccac0c, 0x00ccab10, 0x00caa40f, 0x00c4990c, 0x00bc8c08, 0x00b28004, 0x00a67300, 0x009c6500, 0x009c6000, 0x00945800, 0x00885204, 0x00784908, 0x00603801, 0x00583401, 0x00533104, 0x004d2e04, 0x00482c04, 0x00462c05, 0x00462a07, 0x00472c0a, 0x00482b09, 0x00482b05, 0x00482b03, 0x00482b01, 0x00482c00, 0x004c3003, 0x004f3302, 0x00523603, 0x00583806, 0x00613909, 0x00643c07, 0x00694108, 0x00704806, 0x007d4f03, 0x00925d08, 0x00be9220, 0x00ccb320, 0x00ccb811, 0x00ccbb0a, 0x00cbbc08, 0x00ccbc0c, 0x00ccbc11, 0x00ccb414, 0x00bc960f, 0x00936200, 0x007a4f05, 0x005f3e02, 0x00503404, 0x00442f09, 0x003e2b0b, 0x00392508, 0x002f1f06, 0x00251804, 0x001f1504, 0x00201808, 0x001b1408, 0x00151407, 0x00121207, 0x00121109, 0x00121109, 0x00101008, 0x000e1108, 0x000e1109, 0x000e110b, 0x000d110e, 0x000e1612, 0x000a1410, 0x000d1512, 0x000f1714, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181f19, 0x001a1e19, 0x001a2018, 0x001a2018, 0x001b2118, 0x001b1f14, 0x0013150c, 0x00111109, 0x00121109, 0x00131208, 0x00151308, 0x001a170c, 0x001c150a, 0x00201606, 0x00281f08, 0x002d2208, 0x0035270a, 0x003d2d09, 0x0046330c, 0x00503b0c, 0x0064450c, 0x007e5812, 0x00b48f2d, 0x00ccaf25, 0x00ccb813, 0x00c8bb0d, 0x00c9bc0c, 0x00ccbc09, 0x00ccb411, 0x00b9960d, 0x00916801, 0x00774e01, 0x00614301, 0x004f3800, 0x00483300, 0x00443104, 0x00433008, 0x003f2d08, 0x003c2a06, 0x003c2605, 0x003b2304, 0x00392004, 0x00351f04, 0x00341e08, 0x00311d08, 0x00301d08, 0x002e1c08, 0x002d1c08, 0x002c1a08, 0x002a1906, 0x00281806, 0x00281806, 0x00281808, 0x00281807, 0x00251708, 0x00251608, 0x00241507, 0x00241608, 0x00221708, 0x00211607, 0x00201506, 0x00201406, 0x00211509, 0x00201509, 0x00201509, 0x0021160a, 0x00201409, 0x00201409, 0x00201409, 0x00211509, 0x0023150a, 0x0024160b, 0x0024150b, 0x00211309, 0x00201309, 0x0021140c, 0x0020150b, 0x00191208, 0x00191208, 0x001c1308, 0x001e1408, 0x00201408, 0x00221306, 0x00241408, 0x00231408, 0x00241408, 0x00251509, 0x00241509, 0x00241509, 0x00241509, 0x00241509, 0x00241409, 0x00241409, 0x00231409, 0x00231409, 0x00231409, 0x00221409, 0x00211508, 0x00201508, 0x001f1608, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x00201408, 0x00201408, 0x00201408, 0x00201308, 0x00201408, 0x001f1408, 0x001f1408, 0x001e1408, 0x001e1407, 0x001e1407, 0x001e1306, 0x001e1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001d1306, 0x001e1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001f1306, 0x001e1306, 0x001d1306, 0x001d1305, 0x001d1305, 0x001d1306, 0x001d1306, 0x001e1306, 0x001d1306, 0x001f1406, 0x001f1406, 0x001d1304, 0x001d1304, 0x001d1207, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1208, 0x001f1308, 0x001f1409, 0x001f1409, 0x001e1408, 0x001e1405, 0x001e1405, 0x001c1407, 0x001c1407, 0x001c1305, 0x001c1407, 0x001f1409, 0x001f1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201406, 0x00201406, 0x001f1406, 0x001d1405, 0x001c1406, 0x001c1406, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1306, 0x001e1306, 0x001f1408, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201308, 0x00211408, 0x00211408, 0x00201507, 0x00201506, 0x00201506, 0x00201506, 0x00201508, 0x00201508, 0x00211609, 0x0022170a, 0x0023170a, 0x0023160a, 0x00221509, 0x00211408, 0x00211408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x0025140c, 0x0027160b, 0x0027160a, 0x0028180a, 0x002a1908, 0x002e1b09, 0x00311c0c, 0x00331c0b, 0x00341e08, 0x0039210b, 0x0042280e, 0x00482d0a, 0x0050340b, 0x005e3c0e, 0x00714b0d, 0x00a37a20, 0x00caa82b, 0x00cbb114, 0x00c9b608, 0x00c9b804, 0x00c9b80b, 0x00c9b80c, 0x00cab607, 0x00ccb508, 0x00ccb20a, 0x00ccb008, 0x00ccaf07, 0x00cbab08, 0x00c8a707, 0x00c49e0a, 0x00bf9208, 0x00b98404, 0x00b37800, 0x00a86b00, 0x00a16600, 0x009c6400, 0x009c6603, 0x00a56c0b, 0x00ae710d, 0x009e6405, 0x00845202, 0x00774d0c, 0x005c3802, 0x00523001, 0x004f2f05, 0x004a2c05, 0x00452a04, 0x00442906, 0x00422707, 0x00432709, 0x00432708, 0x00432607, 0x00432607, 0x00432607, 0x00432608, 0x00452907, 0x00482c07, 0x004b3009, 0x004e310b, 0x0050320a, 0x00533508, 0x00573a08, 0x005f4006, 0x006e4804, 0x00855509, 0x00bc9327, 0x00ccb525, 0x00ccb813, 0x00ccba0a, 0x00ccbc08, 0x00ccbc0c, 0x00ccbc0e, 0x00ccb80e, 0x00c2a20f, 0x00976b00, 0x007c5003, 0x00623f00, 0x00513402, 0x00453008, 0x003e2c09, 0x003a2506, 0x00302004, 0x00271902, 0x00201402, 0x00201607, 0x001c1609, 0x00171408, 0x00131108, 0x00111009, 0x00101009, 0x000f1008, 0x000d1008, 0x000d1008, 0x000e100b, 0x000e110e, 0x000e1512, 0x000a1410, 0x000d1512, 0x000f1714, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181f19, 0x001a1f19, 0x001b2018, 0x001b2018, 0x001c2118, 0x00181c11, 0x0010140a, 0x00101109, 0x00101009, 0x00121009, 0x00151308, 0x001b140c, 0x001b1107, 0x00241809, 0x002c1f09, 0x00302208, 0x003a280c, 0x00422e0b, 0x0049340e, 0x00543c0c, 0x006a480c, 0x00876014, 0x00bf9c34, 0x00cbb121, 0x00cbb812, 0x00c9bb0d, 0x00cabc0b, 0x00ccbb0a, 0x00ccb014, 0x00ac8408, 0x00895d03, 0x006e4800, 0x00583f00, 0x00473800, 0x00423200, 0x00402e02, 0x003c2b04, 0x00382804, 0x00352503, 0x00362202, 0x00372004, 0x00351d04, 0x00321c06, 0x00301c08, 0x002c1908, 0x002b1908, 0x002b1a0a, 0x002a1908, 0x00281806, 0x00281806, 0x00261805, 0x00261804, 0x00261804, 0x00241605, 0x00231508, 0x00231508, 0x00231508, 0x00221608, 0x00201608, 0x001f1407, 0x00201508, 0x00201508, 0x001f1409, 0x0020150a, 0x001f1409, 0x0020160b, 0x001f1409, 0x0020140a, 0x0020150a, 0x0020150a, 0x00201409, 0x0021140a, 0x0022150b, 0x00201409, 0x001f1108, 0x001f1208, 0x001c1409, 0x00191307, 0x00151205, 0x00181307, 0x001b1407, 0x001e1407, 0x00201305, 0x00221408, 0x00221408, 0x00211408, 0x00211408, 0x00221509, 0x00211509, 0x00211509, 0x00211509, 0x00241409, 0x00241409, 0x00231408, 0x00221408, 0x00221408, 0x00221408, 0x00201408, 0x00201508, 0x001f1508, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201408, 0x00201307, 0x00201307, 0x001f1307, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1306, 0x001e1306, 0x001e1306, 0x001e1407, 0x001e1407, 0x001f1406, 0x001f1406, 0x001d1304, 0x001d1304, 0x001d1207, 0x001d1207, 0x001e1308, 0x001e1308, 0x001f1208, 0x001f1308, 0x001f1409, 0x001f1409, 0x001e1408, 0x001e1405, 0x001e1405, 0x001c1407, 0x001c1407, 0x001c1305, 0x001c1407, 0x001f1409, 0x001f1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201406, 0x00201406, 0x001e1405, 0x001c1405, 0x001c1405, 0x001b1405, 0x001c1406, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00201508, 0x00201508, 0x00201609, 0x0021170a, 0x0022160a, 0x00221509, 0x00211408, 0x00211408, 0x00211408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x0025140c, 0x0027160b, 0x0027160b, 0x0028180b, 0x002a180a, 0x002e1b09, 0x00311c0c, 0x00331c0b, 0x00341d08, 0x0039210b, 0x0041270e, 0x00482c0a, 0x00523409, 0x005e3c0c, 0x00734c0c, 0x00a88022, 0x00cba828, 0x00cbb113, 0x00cbb509, 0x00ccb70b, 0x00ccb712, 0x00cab410, 0x00cab10a, 0x00cbac0c, 0x00c9a40c, 0x00c89c0a, 0x00c49407, 0x00bb8b04, 0x00ae7d00, 0x00a87200, 0x00a56b00, 0x00a66800, 0x00a86802, 0x00ac6d0a, 0x00b17614, 0x00b38017, 0x00be8f20, 0x00c69824, 0x00ca9a26, 0x00b4801a, 0x00855402, 0x00744a0b, 0x00583603, 0x004d2e00, 0x004a2c04, 0x00442905, 0x00412805, 0x00402707, 0x003f2408, 0x003f2408, 0x003d2306, 0x003f2507, 0x00402609, 0x0040260c, 0x0040250c, 0x003f2508, 0x00412808, 0x00452c09, 0x00482f0c, 0x004a300c, 0x004a3108, 0x00503709, 0x00573c08, 0x0064440b, 0x007c520d, 0x00aa841f, 0x00c9b024, 0x00ccb611, 0x00ccb909, 0x00ccbc08, 0x00cbbc09, 0x00cabc0a, 0x00ccbb04, 0x00caae0e, 0x00a47c06, 0x007f5303, 0x00684201, 0x00553803, 0x00483308, 0x00412d08, 0x003c2604, 0x00332002, 0x002d1d04, 0x00231602, 0x001e1506, 0x001e170a, 0x00181409, 0x00141108, 0x0013100a, 0x0011100a, 0x000f1008, 0x000c1007, 0x000d1008, 0x000d100a, 0x000e120f, 0x000d1411, 0x000a1410, 0x000c1512, 0x000e1613, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181f19, 0x00191f19, 0x001b2019, 0x001b2019, 0x001c2118, 0x00171b11, 0x0010140a, 0x00101009, 0x00101009, 0x00121009, 0x00161309, 0x0019140a, 0x001d1108, 0x00271a0b, 0x002c1f0a, 0x00312108, 0x003c280c, 0x0043300c, 0x0049330c, 0x00573c0c, 0x006c480c, 0x008f6816, 0x00c2a332, 0x00cab420, 0x00cab912, 0x00c9bc0c, 0x00ccbd0a, 0x00ccba0c, 0x00c6a611, 0x00a07403, 0x00825602, 0x00684400, 0x00523c00, 0x00443600, 0x003f3000, 0x003c2c00, 0x00382804, 0x00362505, 0x00332303, 0x00332002, 0x00321e03, 0x00321c08, 0x00301c08, 0x002c1a08, 0x00281808, 0x00271809, 0x00271809, 0x00271808, 0x00261707, 0x00261807, 0x00241706, 0x00241605, 0x00241706, 0x00231606, 0x00221508, 0x00211407, 0x00211508, 0x00211508, 0x00201407, 0x00201407, 0x00201508, 0x00201508, 0x001c1206, 0x001f1408, 0x001e1308, 0x00201509, 0x001e1308, 0x00201509, 0x00201509, 0x001f1408, 0x001f1308, 0x00201408, 0x00201408, 0x00201408, 0x001f1208, 0x001e1207, 0x001c1408, 0x00181407, 0x00141104, 0x00161306, 0x00191407, 0x001c1407, 0x001e1307, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201609, 0x00201609, 0x00201609, 0x00201609, 0x00241409, 0x00241409, 0x00231409, 0x00221408, 0x00221408, 0x00221408, 0x00221409, 0x0022160a, 0x00221609, 0x00221409, 0x00211509, 0x00221609, 0x00211609, 0x00201508, 0x00201508, 0x00201609, 0x00201608, 0x00201408, 0x00201408, 0x001f1306, 0x001f1307, 0x001f1408, 0x001f1408, 0x001e1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001f1408, 0x001e1306, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201408, 0x00201307, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1406, 0x001f1406, 0x001d1304, 0x001d1305, 0x001d1205, 0x001d1206, 0x001e1308, 0x001f1308, 0x00201208, 0x00201308, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1406, 0x001f1406, 0x001d1407, 0x001d1407, 0x001c1305, 0x001c1306, 0x00201409, 0x001e1408, 0x001f1408, 0x00201508, 0x00211408, 0x00201408, 0x001f1305, 0x001f1305, 0x001e1406, 0x001d1405, 0x001c1306, 0x001c1306, 0x001c1307, 0x001d1408, 0x001d1408, 0x001d1408, 0x001f1308, 0x001f1308, 0x00201208, 0x00201208, 0x00201208, 0x00201208, 0x001f1208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1306, 0x001e1306, 0x001e1306, 0x001e1306, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001e1306, 0x001f1407, 0x001f1407, 0x001f1407, 0x001f1407, 0x001f1306, 0x001f1306, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00221508, 0x00221508, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221409, 0x00231509, 0x00221408, 0x00231408, 0x00241408, 0x00241408, 0x00241509, 0x0024150b, 0x0026160a, 0x0027160b, 0x0027180c, 0x0029180a, 0x002d1a0b, 0x00301c0c, 0x00321c0c, 0x00331d08, 0x0038210a, 0x0040270d, 0x00482c0a, 0x0051320a, 0x005e3c0c, 0x00734c0a, 0x00ac8423, 0x00cca92b, 0x00ccac14, 0x00ccac0d, 0x00ccaa0c, 0x00c8a40f, 0x00c69f0f, 0x00c3980b, 0x00bb8804, 0x00b37c01, 0x00b07301, 0x00a96a00, 0x00a46600, 0x00a56800, 0x00a86a02, 0x00ac7008, 0x00b37a10, 0x00be8919, 0x00c4941e, 0x00c99d20, 0x00cba61f, 0x00cbab1b, 0x00cbac1c, 0x00cca71f, 0x00b18213, 0x00885503, 0x00744408, 0x00533200, 0x004d2f02, 0x00452b04, 0x00412805, 0x00402508, 0x003f2409, 0x003c240b, 0x003c220c, 0x003c2309, 0x003b2108, 0x003b2309, 0x003d240c, 0x003e250c, 0x003e250b, 0x003f2608, 0x00402708, 0x00442a0a, 0x00452c0a, 0x00452d06, 0x004b3208, 0x00513809, 0x005e400c, 0x00744f0d, 0x00977414, 0x00c3a725, 0x00cbb415, 0x00ccb90c, 0x00ccbb08, 0x00cbbc08, 0x00cbbc08, 0x00ccbb05, 0x00cab00c, 0x00ae8909, 0x00845a01, 0x006c4404, 0x00583a04, 0x004c3607, 0x00423006, 0x003c2805, 0x00342203, 0x002f2006, 0x00261904, 0x001d1405, 0x001e170a, 0x00181409, 0x00141208, 0x0014110a, 0x0014130b, 0x00101008, 0x000c1007, 0x000d1008, 0x000d100a, 0x000e120c, 0x000c1410, 0x000a1410, 0x000c1512, 0x000d1512, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181f19, 0x00181f19, 0x00192018, 0x00192018, 0x001a2118, 0x00141910, 0x000e130c, 0x000f100a, 0x0011110a, 0x0014110a, 0x0017130a, 0x001a1409, 0x001e1308, 0x00281c0b, 0x002c1f0a, 0x00322208, 0x003d280d, 0x0042300b, 0x0049340c, 0x005b3f0e, 0x00714c0f, 0x009a741c, 0x00c8a930, 0x00cab51d, 0x00c8ba11, 0x00c8bc0a, 0x00cbbd09, 0x00cbb80d, 0x00be9c0d, 0x00946700, 0x007b5000, 0x00624100, 0x004c3701, 0x00413101, 0x003b2b00, 0x00382902, 0x00352604, 0x00342404, 0x00312204, 0x00311e04, 0x002d1b02, 0x002c1c07, 0x002b1a08, 0x00281807, 0x00261808, 0x00261909, 0x00241808, 0x00241607, 0x00241607, 0x00241507, 0x00231506, 0x00241607, 0x00241507, 0x00211407, 0x00221509, 0x001f1206, 0x00201408, 0x00211408, 0x00201407, 0x00201406, 0x00201406, 0x00211507, 0x001f1408, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x001f1208, 0x001c1408, 0x00191508, 0x00131003, 0x00141206, 0x00181306, 0x001b1408, 0x001c1208, 0x00201409, 0x00201409, 0x00211408, 0x00221608, 0x00201609, 0x00201609, 0x00201609, 0x00201609, 0x00241409, 0x00241409, 0x00241409, 0x00211308, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00201508, 0x00201408, 0x00201307, 0x00201508, 0x00201709, 0x00201508, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001e1205, 0x00201408, 0x00211408, 0x00201307, 0x00201307, 0x00201307, 0x001d1205, 0x001f1408, 0x00201508, 0x001f1408, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201307, 0x001e1407, 0x001c1205, 0x001c1205, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001e1306, 0x001d1306, 0x001e1407, 0x001e1306, 0x001d1206, 0x001d1207, 0x001e1308, 0x001e1308, 0x001f1308, 0x00201208, 0x00201208, 0x00201208, 0x00201208, 0x00211308, 0x00201105, 0x00201105, 0x001f1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001c1104, 0x001e1205, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001d1306, 0x001e1306, 0x001f1408, 0x00201508, 0x00201508, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241509, 0x00241409, 0x00221407, 0x00241508, 0x00241508, 0x00241608, 0x0023160a, 0x00231708, 0x0024180c, 0x0025180c, 0x0028170c, 0x002b180c, 0x002f1c0c, 0x00301b0a, 0x00321d08, 0x0037210b, 0x0040270c, 0x00482c09, 0x0052320c, 0x00633c10, 0x00744c0a, 0x00a2781c, 0x00c49824, 0x00c09410, 0x00b88908, 0x00b38000, 0x00af7700, 0x00ac7000, 0x00a76900, 0x00a66700, 0x00a46400, 0x00a66801, 0x00ad7106, 0x00b47c0d, 0x00ba8412, 0x00c38f19, 0x00c7981e, 0x00c9a220, 0x00ccaa20, 0x00ccaf1c, 0x00cbb214, 0x00cab40c, 0x00c8b608, 0x00c8b40c, 0x00cbab17, 0x00a97d08, 0x00885400, 0x00714002, 0x00523000, 0x004a2d02, 0x00422802, 0x003d2504, 0x003c2208, 0x003a1f08, 0x00361f0a, 0x00351f0d, 0x00351e0c, 0x00341c0c, 0x00341c08, 0x00351f08, 0x00392109, 0x003c240c, 0x003e250b, 0x003e260a, 0x0041290c, 0x00432c0b, 0x00432c08, 0x0048310c, 0x004e370c, 0x005e4010, 0x00705010, 0x008a670f, 0x00b5921f, 0x00ccb21d, 0x00ccb812, 0x00cbba0a, 0x00cabb08, 0x00cbba08, 0x00ccb80a, 0x00ccb412, 0x00b9980f, 0x008c6400, 0x006e4803, 0x00593b04, 0x004c3704, 0x00423004, 0x003c2805, 0x00372404, 0x00301f06, 0x00261803, 0x001c1404, 0x001d1609, 0x00181409, 0x00141208, 0x00141109, 0x00131209, 0x00101208, 0x000d1007, 0x000d1007, 0x000e1109, 0x000d110c, 0x000c140f, 0x000b1410, 0x000b1411, 0x000c1512, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181f19, 0x0019201a, 0x0019201a, 0x001b2119, 0x00192018, 0x00192017, 0x00131810, 0x000e130c, 0x000f1009, 0x0011100a, 0x0015120b, 0x0017130a, 0x00191309, 0x0020140a, 0x00281c0c, 0x002d200b, 0x00342409, 0x003e290e, 0x0044320d, 0x004b380e, 0x005d4110, 0x0074500f, 0x00a37f21, 0x00caac2d, 0x00cbb818, 0x00c8ba10, 0x00c8bc0a, 0x00cbba08, 0x00cab310, 0x00b18e0b, 0x008a5e00, 0x00764c03, 0x005d3f02, 0x00493402, 0x003f2f01, 0x00392800, 0x00352502, 0x00322402, 0x00312206, 0x00302005, 0x002c1c02, 0x00291900, 0x002b1a07, 0x00281807, 0x00241606, 0x00231707, 0x00241808, 0x00221606, 0x00211505, 0x00211505, 0x001f1305, 0x00211407, 0x00221608, 0x00211507, 0x00201408, 0x00221509, 0x001e1206, 0x00211408, 0x00221509, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x001f1308, 0x001c1408, 0x00191508, 0x00131003, 0x00131105, 0x00181308, 0x001b1308, 0x001c1208, 0x00201409, 0x00201409, 0x00221509, 0x00221608, 0x00201609, 0x00201609, 0x00201609, 0x00201609, 0x00241409, 0x00241409, 0x00241409, 0x00211308, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00201508, 0x00201408, 0x00201307, 0x00201508, 0x00201709, 0x00201508, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001e1205, 0x00201408, 0x00211408, 0x00201307, 0x00201307, 0x00201307, 0x001d1205, 0x001f1408, 0x00201508, 0x00201508, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001d1305, 0x001e1407, 0x001e1407, 0x00201307, 0x001e1205, 0x00201307, 0x00201307, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201307, 0x001e1407, 0x001c1205, 0x001c1204, 0x001e1306, 0x00201609, 0x001f1408, 0x001d1205, 0x001d1205, 0x001f1408, 0x00201508, 0x00201508, 0x00201609, 0x00201508, 0x001d1307, 0x001d1207, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x00201408, 0x001e1205, 0x001e1205, 0x001e1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1306, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201508, 0x00201508, 0x00201508, 0x00201508, 0x00201508, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241509, 0x0024160a, 0x00241409, 0x00221407, 0x00241508, 0x00241508, 0x00241608, 0x0023160a, 0x00231708, 0x0023170a, 0x0025180c, 0x0028170c, 0x002b180c, 0x002f1c0c, 0x00301b0a, 0x00321c07, 0x0037210b, 0x003f250b, 0x00472a07, 0x0055340a, 0x00673f0e, 0x0073460b, 0x00855408, 0x009c680b, 0x009a6200, 0x009a6100, 0x009c6300, 0x009c6300, 0x00a46902, 0x00aa7007, 0x00b2780a, 0x00ba8410, 0x00c39517, 0x00c79e1a, 0x00c8a31a, 0x00cca91c, 0x00ccac18, 0x00ccae14, 0x00ccb113, 0x00cab210, 0x00c8b30e, 0x00c6b40b, 0x00c6b706, 0x00c7b805, 0x00c9b60c, 0x00caa813, 0x00a47701, 0x00845300, 0x006d3e00, 0x00502d00, 0x00472a01, 0x003f2502, 0x003a2304, 0x00392007, 0x00371c07, 0x00341c09, 0x00321c0c, 0x00321c0c, 0x00331c0c, 0x00321c08, 0x00321c06, 0x00321d05, 0x00361f08, 0x00392209, 0x003a2308, 0x003c2609, 0x003f2809, 0x003f2907, 0x00422d0a, 0x0048340b, 0x00563e0f, 0x006b4c13, 0x00815d0e, 0x00a58018, 0x00caaf24, 0x00ccb718, 0x00ccb90d, 0x00cabb0a, 0x00cbba0a, 0x00ccb90a, 0x00ccb711, 0x00c0a212, 0x00936d01, 0x00734c03, 0x005c3d04, 0x004d3805, 0x00433005, 0x003d2a07, 0x00382404, 0x00312005, 0x00281904, 0x001c1404, 0x001b1406, 0x001a150a, 0x00141308, 0x00141109, 0x00131209, 0x00111309, 0x000e1107, 0x000d1007, 0x000e1109, 0x000d110c, 0x000c130e, 0x000b1410, 0x000b1411, 0x000b1411, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181f19, 0x0019201a, 0x0019201a, 0x001b2119, 0x00192018, 0x00171e14, 0x000f140b, 0x000e130b, 0x000d1009, 0x0011100b, 0x0015140c, 0x00171308, 0x00181208, 0x0020150b, 0x00281c0c, 0x002f200a, 0x0037250b, 0x003f2a0d, 0x00483611, 0x004e390f, 0x005f4310, 0x007c5810, 0x00ae8925, 0x00cbae2a, 0x00cbb814, 0x00c8bb0e, 0x00c8ba08, 0x00cab80c, 0x00c8af10, 0x00a07c03, 0x00825702, 0x00704807, 0x00573903, 0x00483404, 0x003e2d03, 0x003a2902, 0x00322201, 0x002e1f01, 0x002c1c03, 0x002a1c04, 0x00281a04, 0x00261802, 0x00261704, 0x00241505, 0x00211506, 0x00211508, 0x00201608, 0x001f1406, 0x001f1406, 0x001f1406, 0x00201408, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x0021140a, 0x00201208, 0x0021140a, 0x0021140a, 0x00201409, 0x00201409, 0x00201208, 0x00201208, 0x001d1205, 0x001d1205, 0x001c1104, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001f1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00211309, 0x001f1409, 0x00181407, 0x00141305, 0x00141005, 0x00181308, 0x001b1308, 0x001c1208, 0x00201309, 0x00201409, 0x00211408, 0x00221608, 0x00201609, 0x00201609, 0x00201508, 0x00201508, 0x00231409, 0x00241409, 0x00231408, 0x00221408, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00201508, 0x00211408, 0x00201307, 0x00201508, 0x001f1608, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001e1205, 0x00201408, 0x00201408, 0x001f1206, 0x001e1205, 0x001e1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x001e1205, 0x00201307, 0x00201307, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201307, 0x001e1407, 0x001c1205, 0x001c1204, 0x001f1408, 0x00201508, 0x001d1205, 0x001d1205, 0x001d1306, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201508, 0x001e1407, 0x001d1206, 0x001d1207, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201408, 0x001e1205, 0x001e1205, 0x001e1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x00201508, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1306, 0x001e1205, 0x001f1205, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x00201508, 0x00211408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00211406, 0x00221407, 0x00221407, 0x00241508, 0x0023160a, 0x00231708, 0x0023160a, 0x0024180c, 0x0027160c, 0x0028170b, 0x002c190a, 0x00301b0a, 0x00331c09, 0x0038210c, 0x0040270d, 0x004a2c08, 0x00593608, 0x006c410c, 0x00774609, 0x00804c01, 0x008e5500, 0x00985e01, 0x00a06803, 0x00ab760c, 0x00b68416, 0x00c19220, 0x00c89a22, 0x00caa01c, 0x00cca51a, 0x00ccab14, 0x00ccb013, 0x00cbb213, 0x00cab310, 0x00c9b30b, 0x00ccb509, 0x00cbb608, 0x00cab408, 0x00c8b60a, 0x00c8b708, 0x00c8b705, 0x00c8b605, 0x00cbb30e, 0x00c9a214, 0x009f7001, 0x00815000, 0x00693d03, 0x004f2c01, 0x00452803, 0x003d2404, 0x00392206, 0x00392008, 0x00361c08, 0x00341c0b, 0x00321c0e, 0x00301c0d, 0x00301c0c, 0x00301c0a, 0x00301b08, 0x00301c08, 0x00311d07, 0x00341f08, 0x00372108, 0x00382308, 0x003b2608, 0x003d2908, 0x003e2b07, 0x00422f08, 0x004d380c, 0x00614511, 0x0079540f, 0x009a6f14, 0x00c0a020, 0x00ccb41f, 0x00ccb912, 0x00cbbc0c, 0x00c9bc0c, 0x00cbbc0a, 0x00ccb80e, 0x00c3aa11, 0x009a7603, 0x00774f02, 0x00604006, 0x00503906, 0x00443006, 0x003e2a07, 0x00382405, 0x00342006, 0x002c1d07, 0x001d1405, 0x00191304, 0x001c170b, 0x0016140a, 0x00131008, 0x00121108, 0x00101208, 0x000e1208, 0x000d1007, 0x000d1008, 0x000d120b, 0x000a120e, 0x000a1410, 0x000b1310, 0x000b1411, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001b211b, 0x001b211b, 0x001b211b, 0x001c221b, 0x001b2119, 0x00141a10, 0x000c1108, 0x000b1008, 0x000d0f08, 0x0012110b, 0x0016140c, 0x00161408, 0x00191308, 0x0020180c, 0x00281c0c, 0x00302109, 0x0038270a, 0x003f2c0c, 0x00473710, 0x00513c11, 0x00634811, 0x00856114, 0x00b8952a, 0x00cab024, 0x00cbb910, 0x00cabb0c, 0x00c8ba07, 0x00c8b408, 0x00c4a811, 0x00967100, 0x00795003, 0x00664104, 0x00513603, 0x00423004, 0x003d2c05, 0x00372703, 0x00302001, 0x002c1c03, 0x002a1c05, 0x002a1c05, 0x00271a05, 0x00241704, 0x00241605, 0x00211506, 0x001f1305, 0x001e1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001e1407, 0x001e1308, 0x001d1308, 0x001f1409, 0x0020150a, 0x0021140c, 0x0020120a, 0x0021140c, 0x0021140c, 0x00201409, 0x00201409, 0x00201208, 0x00201208, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001f1408, 0x00201408, 0x00201409, 0x001f1409, 0x00191407, 0x00161305, 0x00141005, 0x00181308, 0x001b1308, 0x001c1208, 0x001f1208, 0x00201409, 0x00201408, 0x00221608, 0x00221509, 0x00221509, 0x00201408, 0x00201408, 0x00211308, 0x00211308, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00201508, 0x00211408, 0x00201307, 0x00201508, 0x001f1608, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001e1205, 0x00201408, 0x00201408, 0x001f1206, 0x001e1205, 0x001e1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x001e1205, 0x00201307, 0x00201307, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201307, 0x001e1407, 0x001c1205, 0x001c1105, 0x00201508, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1206, 0x001d1207, 0x001d1308, 0x001e1308, 0x001c1408, 0x001c1405, 0x001c1405, 0x001c1405, 0x001c1405, 0x001f1408, 0x001d1305, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x00201609, 0x00201508, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001e1205, 0x001f1206, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x00211408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00231409, 0x00211406, 0x00221407, 0x00221407, 0x00221407, 0x0023160a, 0x00231609, 0x0023160a, 0x0024170a, 0x0028180d, 0x00281608, 0x002b1808, 0x00301b0a, 0x00331d08, 0x0038220c, 0x00432810, 0x004c2e0e, 0x005c370a, 0x0070440c, 0x00845410, 0x00a26f1a, 0x00b17e18, 0x00bf8f1a, 0x00c89e23, 0x00caa11e, 0x00cba81f, 0x00ccac1f, 0x00ccaf1b, 0x00ccb015, 0x00cbb011, 0x00cab20d, 0x00cab50c, 0x00cab80a, 0x00cbba0a, 0x00ccb808, 0x00ccb709, 0x00ccb508, 0x00cbb409, 0x00cbb40a, 0x00cbb40a, 0x00ccb109, 0x00ccae0b, 0x00cca913, 0x00c09312, 0x00956100, 0x007e4d03, 0x00643804, 0x004c2b03, 0x00442502, 0x003b2204, 0x00382006, 0x00371d07, 0x00341a06, 0x00311908, 0x002f1a0b, 0x002c190a, 0x002c1a0a, 0x002c1908, 0x002c1808, 0x002d1a07, 0x002f1c08, 0x00301d06, 0x00331f08, 0x00352209, 0x00372407, 0x00382807, 0x003b2b06, 0x003c2c04, 0x0046360b, 0x00553b0b, 0x00714c0d, 0x008b600e, 0x00b28e19, 0x00ccb024, 0x00ccb715, 0x00cbbc0c, 0x00c8bc0b, 0x00cabc07, 0x00ccb908, 0x00c6b010, 0x009f7d04, 0x007b5200, 0x00644205, 0x00533b06, 0x00463206, 0x00402c09, 0x00392506, 0x00352206, 0x002d1d05, 0x001e1504, 0x00191304, 0x001a1709, 0x0018140a, 0x00131008, 0x00131008, 0x00111108, 0x000f1108, 0x000e1208, 0x000d1007, 0x000d120b, 0x000b130c, 0x000b140e, 0x000c1310, 0x000b1411, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001b211b, 0x001c221c, 0x001c211c, 0x001c211b, 0x001d221b, 0x0013170f, 0x000d1008, 0x000e1008, 0x00101109, 0x0013130c, 0x0016140c, 0x00151307, 0x00181408, 0x0020180c, 0x00291e0c, 0x00302209, 0x00392809, 0x003f2c09, 0x0046370d, 0x00523c11, 0x00684a10, 0x008a6610, 0x00c2a22c, 0x00ccb41d, 0x00ccba0d, 0x00c8bb0b, 0x00cbbc02, 0x00ccb80b, 0x00b8980c, 0x008c6500, 0x00754f04, 0x005f3f01, 0x004b3301, 0x00412f07, 0x003c2c09, 0x00352507, 0x002e1e04, 0x002a1c05, 0x00281a07, 0x00271a08, 0x00261808, 0x00231507, 0x00201408, 0x001e1407, 0x001c1406, 0x001c1305, 0x001d1207, 0x001c1307, 0x001c1408, 0x001c1408, 0x001c1409, 0x001c140a, 0x001c140a, 0x001c140a, 0x001d1409, 0x001e1409, 0x00201409, 0x00201409, 0x00201409, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1205, 0x001e1407, 0x00201508, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x001f1307, 0x001d1408, 0x001c1408, 0x001b1408, 0x00161003, 0x00141003, 0x00191208, 0x00191208, 0x001c1307, 0x001d1409, 0x001e1508, 0x00201607, 0x00231509, 0x00241409, 0x00201207, 0x00201207, 0x00211308, 0x00241409, 0x00241509, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00221509, 0x00201609, 0x00211408, 0x00211408, 0x001f1408, 0x001e1508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001f1408, 0x001f1408, 0x001d1205, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201406, 0x001f1204, 0x001e1204, 0x001e1204, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1205, 0x001e1205, 0x00201407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1608, 0x001d1408, 0x001c1407, 0x001c1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201207, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x00201709, 0x001d1207, 0x001b1005, 0x0020150a, 0x001f1409, 0x001d1207, 0x001d1207, 0x001e1308, 0x001e1308, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1306, 0x001b1204, 0x001b1205, 0x001c1407, 0x001c1407, 0x001c1405, 0x001c1405, 0x001c1405, 0x001c1405, 0x001e1407, 0x001e1407, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x00201609, 0x00201609, 0x001f1408, 0x00201408, 0x00241409, 0x00241409, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00211409, 0x00221509, 0x00221509, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x0021140a, 0x0024160a, 0x00271608, 0x00291808, 0x002c1a08, 0x00311b08, 0x00351e07, 0x0039210b, 0x00442811, 0x004a2c10, 0x005c360f, 0x0075480e, 0x00a17024, 0x00c89b32, 0x00cba624, 0x00cbad18, 0x00cbaf14, 0x00ccb110, 0x00ccb30e, 0x00cab40c, 0x00cab70d, 0x00c8b80b, 0x00c8b80a, 0x00c8b60a, 0x00c9b60a, 0x00c8b809, 0x00c8ba07, 0x00ccb808, 0x00ccb408, 0x00ccb108, 0x00ccb20a, 0x00cbaf09, 0x00caa90c, 0x00c8a311, 0x00c0940e, 0x00b6850b, 0x00a36c02, 0x008a5300, 0x00774604, 0x005e3501, 0x00482800, 0x00402401, 0x003a2104, 0x00361f06, 0x00361c08, 0x00331907, 0x002e1808, 0x002d1809, 0x002a1808, 0x00291808, 0x00281808, 0x00281808, 0x002b1908, 0x002c1a08, 0x002c1b07, 0x002d1c08, 0x002f1e09, 0x0034230a, 0x00342506, 0x00372805, 0x00392c03, 0x00423108, 0x00503808, 0x0068480c, 0x007d580a, 0x009c7610, 0x00c4a524, 0x00ccb519, 0x00cbba0f, 0x00c8bc06, 0x00c8bb03, 0x00c9b805, 0x00c9b40d, 0x00ae8d0a, 0x00805800, 0x006a4303, 0x00573904, 0x00483307, 0x00402c09, 0x003a2606, 0x00352304, 0x002e1e05, 0x00241908, 0x001a1102, 0x00191306, 0x0019150a, 0x0017130b, 0x00141109, 0x00121108, 0x00101108, 0x00101106, 0x000f1007, 0x000e1208, 0x000d1208, 0x000d120c, 0x000d130f, 0x000b1412, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001c221c, 0x001c221c, 0x001c211c, 0x001c201a, 0x00191e17, 0x0010140c, 0x000d1008, 0x00100f08, 0x00101109, 0x0014150c, 0x00141309, 0x00141306, 0x00191508, 0x00231b0c, 0x002c1f0c, 0x00332409, 0x003a2909, 0x003f2c09, 0x0048360c, 0x00574010, 0x006d4e0e, 0x00957217, 0x00c7a72c, 0x00ccb51e, 0x00cbba0d, 0x00c8bb0c, 0x00cbbb04, 0x00cab30b, 0x00ae8c08, 0x00825c00, 0x006e4a04, 0x00573a00, 0x00463000, 0x003d2c06, 0x00382807, 0x00322304, 0x002c1c03, 0x00281903, 0x00251606, 0x00241808, 0x00251809, 0x00231508, 0x00201409, 0x001c1408, 0x001c1408, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1508, 0x001c1408, 0x001c1408, 0x001c1308, 0x001c1307, 0x001c1408, 0x001e1508, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1305, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x001f1307, 0x001d1408, 0x001c1408, 0x001c1408, 0x00181004, 0x00140e01, 0x00181007, 0x00191208, 0x001c1307, 0x001c1408, 0x001e1508, 0x001f1507, 0x00231509, 0x00241409, 0x00201207, 0x00201207, 0x00211308, 0x00241409, 0x00241509, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00221509, 0x00201609, 0x00211408, 0x00211408, 0x001f1408, 0x001e1508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001f1408, 0x001f1408, 0x001d1205, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201406, 0x001f1204, 0x001e1204, 0x001e1204, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1205, 0x001e1205, 0x00201407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x00201508, 0x001f1608, 0x001d1408, 0x001c1407, 0x001c1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201207, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x00201709, 0x001d1207, 0x001b1005, 0x0020150a, 0x001f1409, 0x001d1207, 0x001d1207, 0x001e1308, 0x001e1308, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1307, 0x001b1206, 0x001b1207, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001e1407, 0x001e1407, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00211308, 0x00211308, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211409, 0x00221509, 0x00211408, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x0021140a, 0x0024170a, 0x00261708, 0x00291808, 0x002c1a08, 0x00311b08, 0x00351e07, 0x0039210b, 0x00442811, 0x004a2c0f, 0x005f380e, 0x00784b0f, 0x00ad8027, 0x00cca82d, 0x00cbaf18, 0x00ccb20d, 0x00ccb30a, 0x00ccb407, 0x00cbb408, 0x00c8b60b, 0x00c8b90d, 0x00c8ba10, 0x00caba0e, 0x00cbb809, 0x00cbb609, 0x00c8b408, 0x00c9b409, 0x00ccb10e, 0x00ccad0f, 0x00c8a60d, 0x00c09d09, 0x00ba9008, 0x00b27f04, 0x00a46f01, 0x009b6300, 0x00935a00, 0x008c5204, 0x00824807, 0x00704008, 0x00583102, 0x00482803, 0x00402303, 0x00382004, 0x00341e07, 0x00341c08, 0x00321a07, 0x002d1808, 0x002b170a, 0x00281809, 0x0028180b, 0x0028180b, 0x00281809, 0x00291909, 0x002c1a09, 0x002c1a08, 0x002c1a08, 0x002b1c08, 0x002e1f0a, 0x00322408, 0x00332605, 0x00372904, 0x003e2d07, 0x004b3408, 0x0060440c, 0x0075510a, 0x008f660b, 0x00b8941e, 0x00ccb41d, 0x00cbb911, 0x00c9bc0c, 0x00cabc06, 0x00ccb909, 0x00cab40c, 0x00b8980e, 0x00885f00, 0x006c4500, 0x00593c04, 0x00493405, 0x00412e09, 0x003b2707, 0x00362404, 0x002e1e04, 0x00241906, 0x001a1201, 0x001a1406, 0x001b180c, 0x0018140c, 0x00141109, 0x00131008, 0x00101108, 0x00101106, 0x000f1005, 0x000e1208, 0x000d1208, 0x000e130b, 0x000d130e, 0x000b1412, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001c221c, 0x001c221c, 0x001b211b, 0x001b2018, 0x00161b14, 0x000f120a, 0x000f0f08, 0x00100f08, 0x00111008, 0x0014150c, 0x00121108, 0x00141205, 0x00191608, 0x00231b0c, 0x002c1f0b, 0x00342408, 0x003c2809, 0x00442e0d, 0x004a340c, 0x005b400e, 0x0070500a, 0x00a07c1a, 0x00caac2c, 0x00ccb61c, 0x00ccbb0d, 0x00caba0d, 0x00ccb90a, 0x00c8ad0d, 0x00a17d01, 0x007d5704, 0x00674408, 0x00523704, 0x00412f01, 0x003c2c07, 0x00392808, 0x00332306, 0x002c1d04, 0x00251804, 0x00221608, 0x00211708, 0x00201409, 0x001f1409, 0x001c140a, 0x001c140a, 0x001c1409, 0x001a1408, 0x001b1407, 0x001b1407, 0x001a1407, 0x00181408, 0x001a1406, 0x001b1406, 0x001a1405, 0x00191304, 0x001a1304, 0x001c1305, 0x001e1206, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1308, 0x001c1106, 0x001c1206, 0x001c1106, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x00201508, 0x001e1407, 0x001e1407, 0x001f1407, 0x001f1307, 0x001d1408, 0x001c1408, 0x001c1408, 0x001b1206, 0x00160d01, 0x00181006, 0x001c1208, 0x001c1307, 0x001c1307, 0x001c1406, 0x001e1506, 0x00211408, 0x00221408, 0x00221408, 0x00211308, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00231409, 0x00211308, 0x00211308, 0x00211408, 0x00201508, 0x00211408, 0x00211408, 0x001f1408, 0x00201709, 0x00201508, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201406, 0x00201305, 0x00201305, 0x00201305, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x001f1206, 0x001f1206, 0x00201307, 0x00201407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201508, 0x001d1408, 0x001c1407, 0x001c1407, 0x001c1407, 0x001e1205, 0x001e1205, 0x001e1205, 0x001e1205, 0x001f1105, 0x001f1205, 0x001f1306, 0x001f1307, 0x001f1407, 0x00201307, 0x00201307, 0x001e1407, 0x001c1407, 0x001c1005, 0x001c1207, 0x001f1409, 0x001e1308, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001a1306, 0x00191306, 0x001a1407, 0x001b1407, 0x001a1307, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191306, 0x00191306, 0x001c1408, 0x001c1408, 0x001d1407, 0x001e1407, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001e1407, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001f1408, 0x0020150a, 0x0023170a, 0x0027180b, 0x00281808, 0x002e1908, 0x00321a08, 0x00371d07, 0x003a210b, 0x0042280e, 0x004c2d0a, 0x0060380a, 0x007c4f10, 0x00b08728, 0x00ccab27, 0x00ccb412, 0x00ccb508, 0x00ccb506, 0x00ccb605, 0x00cbb607, 0x00c9b50c, 0x00c8b60f, 0x00c9b510, 0x00cbb410, 0x00ccb10e, 0x00ccac0d, 0x00c9a710, 0x00c59e0e, 0x00be910c, 0x00b48406, 0x00a67501, 0x00a37000, 0x00a06700, 0x00a06100, 0x009f6100, 0x00a06504, 0x009e640b, 0x00885202, 0x00794402, 0x006c3e08, 0x00522d00, 0x00472804, 0x003e2204, 0x00382007, 0x00331d08, 0x00321c08, 0x002f1a08, 0x002b1909, 0x00271609, 0x0024180b, 0x0024180c, 0x0024180b, 0x0024180a, 0x00241708, 0x00261806, 0x00281908, 0x00291b0a, 0x002a1b0c, 0x002d1e0c, 0x0030220b, 0x00302408, 0x00342605, 0x003e2c08, 0x00463009, 0x00543b08, 0x006a4c0c, 0x00835809, 0x00a88218, 0x00cab023, 0x00cab715, 0x00c9bb10, 0x00cbbc0c, 0x00ccb80a, 0x00cab50c, 0x00bc9c0c, 0x008e6600, 0x006c4700, 0x005b3e02, 0x00493505, 0x00422f0a, 0x003c2506, 0x00362404, 0x002e2004, 0x00261a06, 0x001c1402, 0x00171102, 0x00191609, 0x0019150c, 0x00140f08, 0x00131008, 0x00111108, 0x00101106, 0x000f1005, 0x000e1208, 0x000d1208, 0x000e130b, 0x000d130e, 0x000c1312, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001c221c, 0x001c221c, 0x001b211b, 0x001c2019, 0x00161b14, 0x000f120a, 0x00100f08, 0x00110f08, 0x00121108, 0x0014140b, 0x00101005, 0x00141205, 0x001c1709, 0x00251c0c, 0x002e200c, 0x0036250a, 0x003e2a0c, 0x00493111, 0x00503710, 0x0060430f, 0x00755408, 0x00a8881e, 0x00ccb12c, 0x00ccb719, 0x00ccbb0d, 0x00c9b90c, 0x00ccb80b, 0x00c2a70d, 0x00946f00, 0x00744e04, 0x005d3d05, 0x004c3403, 0x00402e03, 0x003c2c08, 0x00392808, 0x00322305, 0x002a1b03, 0x00221601, 0x001e1405, 0x001d1407, 0x001c1409, 0x001c140b, 0x001c130c, 0x001c140c, 0x001b140c, 0x0019140a, 0x001b1407, 0x001b1407, 0x00191407, 0x00181407, 0x00181405, 0x00181404, 0x00181404, 0x00181404, 0x001a1404, 0x001c1404, 0x001e1304, 0x00201305, 0x001f1405, 0x00201507, 0x001f1406, 0x001e1405, 0x001e1406, 0x001c1107, 0x001e130a, 0x001f140b, 0x001d1208, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x00201508, 0x001e1407, 0x001e1407, 0x001e1306, 0x001f1307, 0x001e1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x00181004, 0x00191006, 0x001b1108, 0x001c1307, 0x001c1307, 0x001c1305, 0x001c1404, 0x00211408, 0x00221408, 0x00221408, 0x00211308, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00231409, 0x00211308, 0x00211308, 0x00211408, 0x00201508, 0x00211408, 0x00211408, 0x001f1408, 0x00201709, 0x00201508, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201406, 0x00201406, 0x00201305, 0x00201305, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x001f1206, 0x001f1206, 0x00201307, 0x00201407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001e1205, 0x001e1205, 0x001e1205, 0x001e1205, 0x001f1105, 0x001f1205, 0x001f1306, 0x001f1307, 0x001f1407, 0x00201307, 0x00201307, 0x001e1407, 0x001d1407, 0x001c1005, 0x001c1207, 0x001f1409, 0x001d1408, 0x001c1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001a1306, 0x00191306, 0x001a1407, 0x001b1407, 0x001a1307, 0x00191208, 0x00191208, 0x00191208, 0x00191308, 0x00191306, 0x00191306, 0x001b1508, 0x001c1408, 0x001d1407, 0x001e1407, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001e1407, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001f1408, 0x0020150a, 0x0023170a, 0x0027180a, 0x00291808, 0x002e1908, 0x00331a08, 0x00371d07, 0x003a2209, 0x00442a0c, 0x004c2f08, 0x00603807, 0x00805310, 0x00b88e2f, 0x00caab28, 0x00cbb414, 0x00ccb506, 0x00ccb506, 0x00ccb408, 0x00ccb308, 0x00cab00c, 0x00caaf10, 0x00c9a910, 0x00c6a00b, 0x00c09406, 0x00b88802, 0x00b07902, 0x00ab7101, 0x00a66800, 0x00a46600, 0x00a36400, 0x00a96c04, 0x00ac6e04, 0x00b6790d, 0x00bd8614, 0x00c4901a, 0x00c4941e, 0x009c6c05, 0x00804e00, 0x006c4004, 0x00502c00, 0x00442606, 0x003c2006, 0x00382008, 0x00331e09, 0x00301b08, 0x002c1a08, 0x00291909, 0x00241608, 0x0023160a, 0x0023160c, 0x0022170c, 0x0022170c, 0x00221608, 0x00221606, 0x00231607, 0x00261808, 0x0028190b, 0x002c1b0e, 0x002f200d, 0x00302009, 0x00332405, 0x003a2806, 0x0045300a, 0x004f380a, 0x00634910, 0x007d530e, 0x00987211, 0x00c5a825, 0x00c9b617, 0x00c9bb13, 0x00cbbb0f, 0x00cbb90d, 0x00ccb60c, 0x00c4a610, 0x00946d00, 0x006f4800, 0x005c3f01, 0x00483604, 0x00432f09, 0x003c2607, 0x00382505, 0x00302206, 0x00261b06, 0x001f1604, 0x00161001, 0x00171407, 0x001c180f, 0x0016110a, 0x00131008, 0x00111208, 0x00101106, 0x000f1005, 0x000e1208, 0x000e1208, 0x000e120c, 0x000d130e, 0x000c1311, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a221e, 0x001a221e, 0x001c211d, 0x001a211a, 0x00141810, 0x000e1108, 0x00101006, 0x00111006, 0x00131209, 0x00131409, 0x00101105, 0x00151307, 0x0021180c, 0x002a1b0d, 0x002f200c, 0x0036240a, 0x003e2a0b, 0x004a3210, 0x00543810, 0x00654512, 0x007c5a0d, 0x00b29224, 0x00ccb327, 0x00ccb716, 0x00cbb90d, 0x00c8b809, 0x00cab70c, 0x00b8990b, 0x00896100, 0x006d4802, 0x00583c04, 0x00483404, 0x003e2d04, 0x003c2a08, 0x00382608, 0x00312106, 0x00291c04, 0x00221703, 0x001c1405, 0x001c1407, 0x001b1309, 0x001b130c, 0x00191208, 0x00191208, 0x001a1108, 0x001b1007, 0x001b1206, 0x00191306, 0x00181306, 0x00181306, 0x00171406, 0x00171406, 0x00191608, 0x00181408, 0x001a1406, 0x001c1407, 0x001c1407, 0x001d1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001d1205, 0x001d1205, 0x00201307, 0x00201307, 0x001f1206, 0x00201408, 0x001d1205, 0x001e1306, 0x001f1408, 0x001f1408, 0x001e1508, 0x001d1409, 0x001c1408, 0x00191004, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1305, 0x001d1406, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00201307, 0x00201408, 0x001f1408, 0x00201609, 0x001f1408, 0x00201508, 0x00201508, 0x00201406, 0x00201406, 0x00201305, 0x00201305, 0x001e1407, 0x001e1407, 0x001d1205, 0x001f1408, 0x00211609, 0x001f1408, 0x001c1104, 0x001d1205, 0x001d1205, 0x001e1205, 0x001e1205, 0x001f1206, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201307, 0x00201408, 0x00201408, 0x001f1408, 0x001f1508, 0x001d1407, 0x001d1407, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1305, 0x00201508, 0x001c1104, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1107, 0x001e1107, 0x001e1107, 0x001e1107, 0x001e1206, 0x001e1205, 0x001f1306, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001e1205, 0x00201508, 0x001b1106, 0x001a1105, 0x001c1509, 0x001c1609, 0x001d1509, 0x001c1408, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1106, 0x001c1106, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1207, 0x001e1308, 0x001d1207, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1407, 0x001e1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00211408, 0x00211408, 0x00211408, 0x00221408, 0x00221408, 0x00211308, 0x00211308, 0x001f1408, 0x001f1408, 0x0020140a, 0x0023170a, 0x00261809, 0x002a1808, 0x002e1908, 0x00331a08, 0x00371d07, 0x003a2208, 0x00432a0b, 0x004d2e08, 0x00603908, 0x007c4f0a, 0x00bb912f, 0x00c9a827, 0x00ccb017, 0x00ccaf0b, 0x00ccab0b, 0x00caa50b, 0x00c59f09, 0x00be940c, 0x00b88a08, 0x00b07e02, 0x00ab7400, 0x00ad6b00, 0x00ab6800, 0x00a76700, 0x00aa6b04, 0x00ad710b, 0x00b37a10, 0x00bc8618, 0x00c59320, 0x00c89a20, 0x00cca520, 0x00ccab1c, 0x00ccac1c, 0x00c9a620, 0x00a47405, 0x00835101, 0x006a4002, 0x004f2b00, 0x00442509, 0x003c2008, 0x00371e08, 0x00321c08, 0x002f1b08, 0x002c1a08, 0x00281809, 0x00241609, 0x0023160a, 0x0023160a, 0x00211609, 0x00201608, 0x00201507, 0x00201606, 0x00211606, 0x00241808, 0x00251808, 0x00281a09, 0x002c1e09, 0x002c1d07, 0x00302005, 0x00382706, 0x0042300b, 0x004b360c, 0x00584010, 0x006f4d0c, 0x008a6411, 0x00bb9c26, 0x00cab61c, 0x00cbbb10, 0x00ccba0e, 0x00ccba0e, 0x00ccb80e, 0x00caad14, 0x009c7501, 0x00744d00, 0x005c4002, 0x00473704, 0x00433008, 0x003e2808, 0x00382606, 0x00312306, 0x00291c08, 0x00201705, 0x00181003, 0x00141005, 0x001c1910, 0x00161208, 0x00131107, 0x00101206, 0x000f1007, 0x000d0f05, 0x00101008, 0x00101109, 0x0010110c, 0x000e120f, 0x000b1210, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a221e, 0x001a221e, 0x001c221f, 0x00171d18, 0x000f140b, 0x000d1007, 0x00101006, 0x00131107, 0x0016140b, 0x00121208, 0x00101004, 0x00161408, 0x0023180d, 0x002d1c0f, 0x0030200c, 0x0038270c, 0x00402c0b, 0x004c330f, 0x00543810, 0x00664612, 0x00836111, 0x00b89928, 0x00ccb324, 0x00ccb813, 0x00cbba0c, 0x00c9b80b, 0x00cbb510, 0x00ad8d06, 0x00835a00, 0x006a4401, 0x00543804, 0x00443002, 0x003d2c04, 0x00392606, 0x00352305, 0x00301f04, 0x002a1c05, 0x00221703, 0x001c1404, 0x001c1407, 0x001b130a, 0x001b120c, 0x00181308, 0x00181308, 0x00191108, 0x001a1007, 0x001b1206, 0x00191306, 0x00181306, 0x00181306, 0x00171406, 0x00171406, 0x00191608, 0x00181408, 0x001a1406, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001d1205, 0x001d1205, 0x00201307, 0x00201307, 0x001f1206, 0x00201408, 0x001d1104, 0x001e1306, 0x00201508, 0x001f1408, 0x001f1608, 0x001f150a, 0x001e1409, 0x00180f04, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1306, 0x001f1507, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00201307, 0x00201408, 0x001f1408, 0x00201609, 0x001f1408, 0x00201508, 0x00201508, 0x00201406, 0x00201406, 0x00201305, 0x00201305, 0x001e1407, 0x001e1407, 0x001d1305, 0x001f1408, 0x0021170a, 0x001f1408, 0x001c1104, 0x001d1205, 0x001d1205, 0x001e1205, 0x001e1205, 0x00201408, 0x00221509, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201307, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1407, 0x001c1407, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1306, 0x00201508, 0x001c1104, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1206, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x00201508, 0x001a1106, 0x001b1105, 0x001c1509, 0x001b1609, 0x001c1509, 0x001c1408, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1106, 0x001c1106, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1207, 0x001c1106, 0x001d1208, 0x001d1408, 0x001c1407, 0x001e1508, 0x00201709, 0x00201608, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x001f1206, 0x001f1206, 0x001f1206, 0x001f1306, 0x00201307, 0x00201408, 0x00201308, 0x00211308, 0x00211308, 0x00211308, 0x00211308, 0x00201408, 0x00201408, 0x0021140a, 0x0024170a, 0x00261809, 0x002b1909, 0x002e1908, 0x00331a08, 0x00371e06, 0x003b2308, 0x00442b0d, 0x004e300b, 0x00603908, 0x00784a08, 0x00b5882d, 0x00c19824, 0x00c09816, 0x00bd8a0f, 0x00b58008, 0x00af7803, 0x00a77000, 0x00a26800, 0x00a36900, 0x00a46800, 0x00a56a01, 0x00a76c03, 0x00ab7408, 0x00b88416, 0x00c08f20, 0x00c59820, 0x00c9a221, 0x00cca820, 0x00ccac1c, 0x00cbad19, 0x00cab215, 0x00c8b313, 0x00c8b014, 0x00c8a61b, 0x009f7002, 0x00845104, 0x006b3f04, 0x004e2a00, 0x00442409, 0x003c2008, 0x00371e08, 0x00331c08, 0x002f1b08, 0x002b1908, 0x00281809, 0x00221509, 0x00221509, 0x00221509, 0x00201508, 0x001f1508, 0x001e1507, 0x001d1406, 0x001f1407, 0x00221809, 0x00241809, 0x00261a08, 0x00281c07, 0x00291c05, 0x002c1f03, 0x00352605, 0x003f2f09, 0x0048340b, 0x00533d0e, 0x006a4c0e, 0x007e5b0e, 0x00ae8d1e, 0x00c9b41c, 0x00cbb90d, 0x00cbba0c, 0x00cbb90d, 0x00ccb910, 0x00ccb217, 0x00a17c02, 0x007a5200, 0x005f4204, 0x004b3a05, 0x0047340b, 0x00422c0c, 0x003a2808, 0x00332407, 0x002b1d08, 0x00231807, 0x00181003, 0x00141005, 0x0018170d, 0x0018140b, 0x00121006, 0x000f1005, 0x00101108, 0x000f1007, 0x00101109, 0x0010120a, 0x0010110c, 0x000e120d, 0x000b120e, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a221e, 0x001a221e, 0x001d231f, 0x00151a14, 0x000f120a, 0x000f1007, 0x00121107, 0x0017140a, 0x00151308, 0x00101006, 0x00101104, 0x0019160a, 0x00251a0f, 0x002c1c0e, 0x0033210d, 0x0039260a, 0x00422e0b, 0x004b340c, 0x00543a0f, 0x00684710, 0x00896814, 0x00bfa12c, 0x00ccb31f, 0x00ccb810, 0x00cbba09, 0x00cab60c, 0x00cab116, 0x00a68205, 0x007e5500, 0x00654000, 0x00523504, 0x00443004, 0x003b2804, 0x00372204, 0x00321f02, 0x002f1d04, 0x002a1c06, 0x00221804, 0x001c1402, 0x001a1405, 0x00191208, 0x0019110b, 0x00171208, 0x00181207, 0x00181107, 0x00181006, 0x001b1206, 0x00191306, 0x00181306, 0x00181306, 0x00171406, 0x00171406, 0x00181408, 0x00181508, 0x00191306, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001d1205, 0x001e1306, 0x00201508, 0x001f1408, 0x001f1408, 0x001f1409, 0x001f1409, 0x001b1005, 0x001c1005, 0x001c1307, 0x001c1307, 0x001c1306, 0x001f1607, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00201307, 0x00201408, 0x001f1408, 0x00201508, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201406, 0x00201406, 0x00201406, 0x00201406, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x00201609, 0x001f1408, 0x001d1306, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201408, 0x00211409, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1306, 0x00201408, 0x00201408, 0x00201508, 0x001f1608, 0x001c1407, 0x001c1407, 0x001d1306, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001f1409, 0x001f1409, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1206, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001b1206, 0x001b1206, 0x001c1408, 0x001a1508, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1005, 0x001e1308, 0x001f1508, 0x001c1406, 0x001c1306, 0x001c1407, 0x001d1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00211308, 0x00211308, 0x00211308, 0x00211308, 0x00201408, 0x00201408, 0x0021140a, 0x0024160a, 0x00281709, 0x002b1909, 0x002f1a09, 0x00341b0a, 0x00381e06, 0x003c2409, 0x00462c10, 0x0053320e, 0x005f380c, 0x00703e08, 0x0088540b, 0x00925f02, 0x00945d00, 0x009c5a00, 0x009c5c00, 0x009b5c00, 0x009c6002, 0x00a56c03, 0x00aa7309, 0x00b37c11, 0x00be8c1c, 0x00c2951c, 0x00c8a020, 0x00caa720, 0x00ccac21, 0x00ccb01b, 0x00ccb116, 0x00cbb413, 0x00cbb60f, 0x00c9b70c, 0x00c8b808, 0x00c5b609, 0x00cab414, 0x00c4a014, 0x009e6e04, 0x00835006, 0x00663a03, 0x004d2802, 0x00422509, 0x003b2008, 0x00361d08, 0x00311b08, 0x002f1c0a, 0x00291808, 0x00271709, 0x00221509, 0x00211408, 0x001e1205, 0x001d1205, 0x001d1508, 0x001c1407, 0x001c1408, 0x001c1408, 0x001e1409, 0x00201609, 0x00231808, 0x00251b07, 0x00281d05, 0x002a1f04, 0x00322404, 0x003a2c05, 0x00433108, 0x004e3b0c, 0x0060440c, 0x0075520c, 0x00a07e16, 0x00c9af1f, 0x00ccba10, 0x00ccbb0c, 0x00cbb90d, 0x00ccba0e, 0x00ccb214, 0x00ac880b, 0x007c5400, 0x00604001, 0x004f3b05, 0x00463309, 0x00432b0b, 0x003c280a, 0x00322305, 0x002c1c08, 0x00241805, 0x00191104, 0x00130e04, 0x0017140b, 0x001a150c, 0x00141006, 0x000f1007, 0x000f1007, 0x000f1007, 0x00101009, 0x00101009, 0x000e1008, 0x0010140d, 0x000b120c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231c, 0x001a231c, 0x001d241e, 0x00151a13, 0x000f120a, 0x000f1007, 0x00111006, 0x00141108, 0x00141109, 0x00101007, 0x00111206, 0x001c190e, 0x00281c11, 0x002e1d0f, 0x0033220d, 0x003b280c, 0x00422f0c, 0x004b360d, 0x00573c0f, 0x006c4b10, 0x008c6c16, 0x00c5a830, 0x00cab41d, 0x00ccb90e, 0x00cbbb06, 0x00cbb60c, 0x00c7ac16, 0x009c7702, 0x00785000, 0x00623d02, 0x00503404, 0x00442f07, 0x003a2807, 0x00372205, 0x00331e03, 0x002d1d04, 0x00291d08, 0x00221805, 0x001c1404, 0x00191306, 0x00191208, 0x0019110b, 0x00171208, 0x00171307, 0x00181207, 0x00171106, 0x001b1206, 0x00191306, 0x00181306, 0x00181306, 0x00181406, 0x00171406, 0x00181408, 0x00181508, 0x00191306, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001d1205, 0x001e1306, 0x00201508, 0x001f1408, 0x001f1408, 0x001f1409, 0x001f1409, 0x001e1308, 0x001b1005, 0x001c1307, 0x001c1307, 0x001c1306, 0x001f1507, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00201307, 0x00201408, 0x001f1408, 0x00201508, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201406, 0x00201406, 0x00201406, 0x00201406, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x00201609, 0x001f1408, 0x001d1306, 0x001e1407, 0x001f1407, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1306, 0x00201307, 0x00201307, 0x001f1408, 0x001c1407, 0x001c1407, 0x001c1407, 0x001d1306, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1306, 0x001c1305, 0x001c1406, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001b1206, 0x001b1206, 0x001c1408, 0x001a1508, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001e1308, 0x001d1207, 0x001c1205, 0x001c1407, 0x001d1408, 0x001c1407, 0x001d1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201207, 0x00201207, 0x00211308, 0x00211308, 0x00201408, 0x00201408, 0x0021140a, 0x0024160a, 0x00281709, 0x002b1909, 0x00301b0a, 0x00341c0b, 0x00391f09, 0x003e260c, 0x00492f10, 0x00563612, 0x00643d0d, 0x00754408, 0x00865004, 0x00905800, 0x00985f01, 0x00a36608, 0x00aa710e, 0x00b17c14, 0x00ba891a, 0x00bd9218, 0x00c49c1c, 0x00cca925, 0x00ccac24, 0x00ccac1a, 0x00ccaf14, 0x00ccb10f, 0x00ccb50c, 0x00ccb507, 0x00ccb507, 0x00cab709, 0x00c9b80b, 0x00c8b807, 0x00c8b804, 0x00c8b708, 0x00ccb014, 0x00be9710, 0x00986500, 0x00804c04, 0x00623700, 0x004a2501, 0x0042240b, 0x003a2008, 0x00341e08, 0x00301b08, 0x002f1c0b, 0x00281808, 0x00261609, 0x00221509, 0x00201508, 0x001d1306, 0x001c1307, 0x001c1408, 0x00191408, 0x00191407, 0x001b1408, 0x001b1308, 0x001c1408, 0x00201806, 0x00231905, 0x00261d05, 0x00281f02, 0x00312404, 0x00382b05, 0x003e2f04, 0x00493809, 0x005a420c, 0x0070500e, 0x00967311, 0x00c6a81f, 0x00ccb811, 0x00ccbb0c, 0x00cbb90d, 0x00ccb90f, 0x00ccb414, 0x00af8c0c, 0x00805800, 0x00644200, 0x00513c07, 0x00463309, 0x00422a0a, 0x003c280a, 0x00332305, 0x002f1e09, 0x00271a08, 0x001c1507, 0x00140f04, 0x00141206, 0x001b150c, 0x00141006, 0x000f1007, 0x000f1007, 0x000f1007, 0x00101009, 0x00101009, 0x000e1008, 0x0010140c, 0x000b130c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231c, 0x001c221c, 0x001d211c, 0x00141710, 0x0010120a, 0x00101007, 0x00121108, 0x00131008, 0x000e0c03, 0x00131007, 0x00181409, 0x00201a0e, 0x00281c0e, 0x002f1d0c, 0x0034220c, 0x003b280c, 0x0041300d, 0x0049370f, 0x00583c0e, 0x00704c10, 0x00957417, 0x00c9ad2c, 0x00ccb617, 0x00cab909, 0x00ccb905, 0x00ccb80d, 0x00c2a312, 0x00946d00, 0x00744d00, 0x005d3c00, 0x004c3404, 0x00422e07, 0x003a2804, 0x00342302, 0x002e1f04, 0x002b1d06, 0x00281c08, 0x00201706, 0x00191304, 0x00181305, 0x00181207, 0x00161008, 0x00181207, 0x00181207, 0x00181207, 0x00171106, 0x00171106, 0x00171106, 0x00181308, 0x00191208, 0x00181207, 0x00181207, 0x00181308, 0x00191408, 0x001a1408, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001c1407, 0x001c1407, 0x00181304, 0x001b1405, 0x001c1508, 0x001b1204, 0x001d1205, 0x001e1407, 0x001f1307, 0x00211408, 0x00211408, 0x00201307, 0x001f1307, 0x001e1407, 0x001d1306, 0x001e1407, 0x001e1408, 0x001f1409, 0x0020150a, 0x001c1408, 0x00170e02, 0x001c140a, 0x001c140a, 0x001c1408, 0x001d1508, 0x00201408, 0x00211308, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00211408, 0x00211408, 0x00201508, 0x0022170a, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001d1207, 0x001e1308, 0x001d1307, 0x001f1508, 0x001f1608, 0x001c1406, 0x001c1104, 0x001d1205, 0x001d1205, 0x001f1408, 0x00201609, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1409, 0x001d1207, 0x001c1106, 0x001d1207, 0x001f1408, 0x00201508, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001c1104, 0x001a1003, 0x001b1105, 0x001c1308, 0x001b1206, 0x001b1206, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001d1408, 0x001e1308, 0x001d1208, 0x001c1005, 0x001c1106, 0x001a1105, 0x001a1105, 0x001b1407, 0x00191407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201507, 0x00211508, 0x00231409, 0x0025170b, 0x0028180a, 0x002c1a0a, 0x00301b0a, 0x00341c0b, 0x003b1f09, 0x0042240e, 0x004b2c10, 0x005c3b11, 0x006c4610, 0x008c5c18, 0x00a4711c, 0x00b4821b, 0x00b98d19, 0x00c49c1d, 0x00cba31f, 0x00cba61b, 0x00ccab19, 0x00ccae16, 0x00ccb014, 0x00ccb112, 0x00cbb310, 0x00cab410, 0x00c9b40d, 0x00ccb40b, 0x00ccb408, 0x00c8b807, 0x00c8b708, 0x00c8b40a, 0x00cab50d, 0x00ccb80e, 0x00ccb508, 0x00cab00c, 0x00ccac1b, 0x00b88910, 0x00915c00, 0x007f4d05, 0x005d3400, 0x00492603, 0x003e2308, 0x00371d06, 0x00341c09, 0x002f1b0a, 0x002c1c09, 0x00251808, 0x00211708, 0x001f1608, 0x001e140b, 0x001c140a, 0x001b1309, 0x00191209, 0x00181207, 0x00181308, 0x00181308, 0x00191408, 0x00191408, 0x001c1608, 0x00211908, 0x00231907, 0x00291e07, 0x00302306, 0x00372a07, 0x003b2d05, 0x0047380c, 0x00553e0d, 0x006c4d10, 0x008a6711, 0x00c2a122, 0x00ccb717, 0x00cbb90d, 0x00cbba0c, 0x00ccb90f, 0x00ccb413, 0x00b7930f, 0x00875e00, 0x00684401, 0x00543c06, 0x00473309, 0x00422b0b, 0x003c2709, 0x00342304, 0x002f1f05, 0x00271a04, 0x001e1604, 0x00151101, 0x00101002, 0x0017160a, 0x00151309, 0x00110f07, 0x000f1007, 0x000f1007, 0x000e1008, 0x000d1008, 0x000e110c, 0x000d130d, 0x000b130c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231b, 0x001c221b, 0x00181d16, 0x0010140b, 0x0010120a, 0x00101007, 0x00121108, 0x00111008, 0x000d0c02, 0x00141006, 0x001c1509, 0x00231b0e, 0x00281c0b, 0x002f1e0a, 0x0034220a, 0x003b2a0c, 0x0041310c, 0x004b3810, 0x005b3e0e, 0x00745111, 0x00a17f1d, 0x00ccb029, 0x00cbb813, 0x00cab908, 0x00ccb905, 0x00ccb40c, 0x00ba9b0f, 0x00886200, 0x006e4900, 0x00563800, 0x00483202, 0x003c2c04, 0x00352402, 0x00322001, 0x002d1e04, 0x00291c08, 0x00271c0a, 0x00201708, 0x00191306, 0x00181305, 0x00181207, 0x00161007, 0x00151108, 0x00151108, 0x00151107, 0x00141007, 0x00141005, 0x00141005, 0x00151106, 0x00181308, 0x00181207, 0x00181207, 0x00181308, 0x00181308, 0x00191308, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001a1507, 0x001a1507, 0x00191405, 0x001a1507, 0x001c1407, 0x001e1508, 0x00201609, 0x001e1407, 0x001d1104, 0x001f1306, 0x00201408, 0x00201307, 0x001f1407, 0x001e1306, 0x001d1306, 0x001e1407, 0x001e1408, 0x001f1409, 0x0020150a, 0x001f150a, 0x00180f03, 0x001b1108, 0x001c1208, 0x001b1407, 0x001c1407, 0x00201408, 0x00211308, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00211308, 0x00211308, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00211408, 0x00211408, 0x00201508, 0x0022170a, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1207, 0x001c1307, 0x001f1608, 0x001f1608, 0x001c1406, 0x001c1204, 0x001d1205, 0x001d1205, 0x001e1407, 0x00201508, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001e1308, 0x001e1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001c1004, 0x001a1105, 0x001c1308, 0x001b1206, 0x001b1206, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001b1206, 0x001c1307, 0x001a1105, 0x001a1105, 0x001b1407, 0x00191407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001c1408, 0x001c1408, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1308, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201507, 0x00211507, 0x0024150a, 0x0026180b, 0x0028180a, 0x002c190a, 0x00311c0c, 0x00351c0c, 0x003b1f0b, 0x00442610, 0x00502d0f, 0x005c3a0c, 0x00704609, 0x00ad7e2d, 0x00cb9e34, 0x00cca529, 0x00cba820, 0x00ccae18, 0x00ccaf14, 0x00ccb00f, 0x00ccb10c, 0x00ccb209, 0x00ccb309, 0x00ccb408, 0x00ccb608, 0x00c9b808, 0x00cab808, 0x00cbb605, 0x00cab604, 0x00c9b804, 0x00c9b707, 0x00cab409, 0x00cab00a, 0x00cbae10, 0x00caa913, 0x00c59f12, 0x00b78a0e, 0x00a06d04, 0x008b5300, 0x007c4c08, 0x00583000, 0x004a2805, 0x003e2308, 0x00361d06, 0x00311c0a, 0x002d1a0b, 0x00281a08, 0x00231705, 0x00201608, 0x001c1509, 0x001c140c, 0x001c140c, 0x001b130b, 0x00181108, 0x00181008, 0x00181309, 0x0018130a, 0x0019140b, 0x0019140b, 0x001c150b, 0x0021180b, 0x00231809, 0x002a1d0a, 0x00312208, 0x00372a08, 0x00392c05, 0x00423409, 0x00523b0c, 0x00684b12, 0x00846113, 0x00bb9820, 0x00ccb419, 0x00cbb90f, 0x00cbba0c, 0x00ccba0d, 0x00ccb613, 0x00ba970f, 0x008c6000, 0x006b4400, 0x00553a05, 0x00483408, 0x00432b0a, 0x003c2809, 0x00352404, 0x00302007, 0x00281c04, 0x00201604, 0x00161102, 0x00100f01, 0x00141408, 0x0018160e, 0x00121008, 0x00101007, 0x00101108, 0x000d1008, 0x000c1108, 0x000d110c, 0x000d130e, 0x000c130c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231b, 0x001c221b, 0x00131810, 0x00101009, 0x0011110a, 0x00110f07, 0x00121008, 0x00100f06, 0x000e0b02, 0x00141004, 0x001c1608, 0x00231a0c, 0x00291c0a, 0x002f1e06, 0x00352408, 0x003b2b09, 0x0041320b, 0x004c390d, 0x005d3f0d, 0x00795411, 0x00a98822, 0x00caaf22, 0x00cab910, 0x00c8ba08, 0x00cab805, 0x00cbb00c, 0x00b18e0b, 0x00835c00, 0x00694700, 0x00543901, 0x00443003, 0x00382805, 0x00312102, 0x002f1f01, 0x002c1c05, 0x00281b08, 0x00251909, 0x00201709, 0x001b1407, 0x00161205, 0x00151106, 0x00171008, 0x00141008, 0x00121008, 0x00121008, 0x00121008, 0x00141006, 0x00121006, 0x00131006, 0x00151108, 0x00161307, 0x00161307, 0x00181308, 0x00181308, 0x00191308, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x00191306, 0x00191306, 0x00191405, 0x00191405, 0x00191405, 0x001a1507, 0x001c1508, 0x001e1508, 0x001f1408, 0x001f1408, 0x00211408, 0x00211408, 0x00211408, 0x001f1306, 0x001d1105, 0x001e1407, 0x001e1407, 0x00201609, 0x0023180c, 0x0021160c, 0x0020150a, 0x001f160a, 0x00191004, 0x00191006, 0x001a1208, 0x001c1408, 0x001c1407, 0x00201408, 0x00211308, 0x00221408, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00241409, 0x00221509, 0x00201408, 0x00201609, 0x00211609, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1207, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1305, 0x001c1306, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1307, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001b1406, 0x001b1405, 0x001c1406, 0x001c1407, 0x001c1407, 0x001c1307, 0x001c1307, 0x001a1105, 0x001c1408, 0x001b1206, 0x001b1206, 0x001b1407, 0x00191407, 0x001b1407, 0x001b1405, 0x001b1405, 0x001b1405, 0x001e1409, 0x001c1408, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1207, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001a1306, 0x001a1306, 0x001a1306, 0x001a1306, 0x001b1204, 0x001b1204, 0x001c1305, 0x001c1305, 0x001c1307, 0x001c1307, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00201609, 0x00221608, 0x0024150a, 0x0028180b, 0x002c1a0b, 0x002c1a08, 0x00311c0c, 0x0036200d, 0x003b220a, 0x0044270d, 0x00543110, 0x00603b0c, 0x00784d0c, 0x00b88b2b, 0x00cca828, 0x00ccae1b, 0x00cab214, 0x00ccb40c, 0x00ccb40b, 0x00cbb408, 0x00cbb406, 0x00cbb406, 0x00cbb406, 0x00cab405, 0x00cab406, 0x00c9b407, 0x00cab307, 0x00ccb308, 0x00ccb006, 0x00caad08, 0x00cbab0b, 0x00caa70f, 0x00c09807, 0x00b78907, 0x00ac7a04, 0x00a47000, 0x00986100, 0x008f5600, 0x00844e04, 0x0077480b, 0x00512b00, 0x00442402, 0x003c2107, 0x00361d08, 0x00321c0a, 0x002f1d0d, 0x002a1b0a, 0x00231707, 0x00201508, 0x001c1409, 0x001c140a, 0x001b130b, 0x00191209, 0x00191209, 0x0018120a, 0x0018120b, 0x0018120b, 0x0018130c, 0x0019130c, 0x001a140c, 0x001e1409, 0x0022170a, 0x00291c0b, 0x00302108, 0x00342808, 0x00382b06, 0x00403008, 0x0051390c, 0x00644810, 0x00825d13, 0x00b28e1d, 0x00ccb31c, 0x00cab810, 0x00ccbb0b, 0x00ccbb0b, 0x00ccb70e, 0x00bf9d11, 0x00906400, 0x006d4400, 0x00583b04, 0x00493407, 0x00432c08, 0x003e2807, 0x00372403, 0x00322007, 0x002a1c04, 0x00241a08, 0x00171102, 0x000f0e00, 0x00121207, 0x0018160e, 0x0013100a, 0x00101007, 0x00101108, 0x000d1008, 0x000c1108, 0x000c100a, 0x000d110d, 0x000c120c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231b, 0x001c221b, 0x0010140d, 0x00101009, 0x00101009, 0x00121008, 0x00121008, 0x000f0d03, 0x00100d02, 0x00171206, 0x001f1808, 0x00241b0a, 0x00291c08, 0x002f1e04, 0x00352406, 0x003c2c09, 0x0042330a, 0x004c390c, 0x005f410d, 0x007e5811, 0x00b49127, 0x00ccb31f, 0x00c9b80b, 0x00c6b906, 0x00cab808, 0x00cbb010, 0x00ac880a, 0x007f5600, 0x00674402, 0x00523a04, 0x00403004, 0x00362907, 0x002f2204, 0x002d1f04, 0x002c1b07, 0x00271908, 0x0024180a, 0x001f160a, 0x001a1307, 0x00151104, 0x00141005, 0x00151007, 0x0015130a, 0x00131008, 0x00121008, 0x00111008, 0x00121008, 0x00121008, 0x00121008, 0x00131008, 0x00151106, 0x00161307, 0x00181308, 0x00181308, 0x00191308, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x00191306, 0x00191306, 0x00191405, 0x00191405, 0x00191405, 0x00191406, 0x001c1407, 0x001c1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00211408, 0x001f1206, 0x001e1206, 0x001e1407, 0x001d1205, 0x001f1408, 0x00201609, 0x001f1409, 0x001e1308, 0x0020170c, 0x001c1308, 0x00191006, 0x001b1309, 0x001c1408, 0x001c1407, 0x00201408, 0x00211308, 0x00221408, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00241409, 0x00221509, 0x00201408, 0x00201609, 0x00211609, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1207, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1307, 0x001c1407, 0x001c1406, 0x001c1305, 0x001c1306, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1307, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191405, 0x00191405, 0x001a1406, 0x001a1507, 0x001c1407, 0x001b1407, 0x001b1307, 0x00181105, 0x001c1408, 0x001b1205, 0x001a1105, 0x001c1408, 0x00191407, 0x001b1407, 0x001b1405, 0x001b1405, 0x001b1405, 0x001c1408, 0x001c1307, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1408, 0x001c1308, 0x001c1307, 0x001a1306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00181306, 0x00181306, 0x00191306, 0x00191306, 0x00191304, 0x00191304, 0x001b1204, 0x001b1204, 0x001c1307, 0x001c1307, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201609, 0x00221608, 0x0025170b, 0x0028180b, 0x002c1a0a, 0x002c1a08, 0x00311c0c, 0x0037200e, 0x003d260c, 0x00472c0d, 0x00583411, 0x00694011, 0x00845915, 0x00bf952e, 0x00ccac20, 0x00cab310, 0x00c7b50c, 0x00c9b708, 0x00c9b707, 0x00c8b606, 0x00cab507, 0x00cab408, 0x00cab408, 0x00cab20a, 0x00ccb10d, 0x00ccb00f, 0x00ccaa0d, 0x00caa50c, 0x00c69c08, 0x00c09007, 0x00b48001, 0x00ad7500, 0x00a56900, 0x00a46401, 0x00a26101, 0x009f6001, 0x00985804, 0x008a4c01, 0x00824c0a, 0x006f400b, 0x004d2800, 0x00462605, 0x003c2008, 0x00361d08, 0x00301a08, 0x002d1b0b, 0x00281908, 0x00221606, 0x00201508, 0x001c140a, 0x001b1308, 0x00191209, 0x00181109, 0x0018100a, 0x00181009, 0x0018110a, 0x0018110b, 0x0018120c, 0x0019130e, 0x001a130c, 0x001c140a, 0x0022170c, 0x0027190a, 0x002f2009, 0x00332508, 0x00382a08, 0x00403009, 0x004f380b, 0x00614410, 0x007d5813, 0x00ac881d, 0x00cbb120, 0x00cab812, 0x00ccbb0c, 0x00ccbc09, 0x00ccb90e, 0x00c1a312, 0x00936801, 0x006f4400, 0x00583b02, 0x004b3507, 0x00442d06, 0x003f2906, 0x00382403, 0x00342008, 0x002c1c05, 0x00251a08, 0x00181103, 0x00111004, 0x000f1004, 0x0017140c, 0x0015130c, 0x000f0f05, 0x000d0f05, 0x000d1008, 0x000c1108, 0x000b100a, 0x000d110d, 0x000c120c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00192219, 0x001a2018, 0x000f120c, 0x00101009, 0x00111009, 0x00141109, 0x00141109, 0x00100e04, 0x00120f04, 0x00181406, 0x00201808, 0x00241c07, 0x00291e06, 0x002e1d04, 0x00342305, 0x003c2c06, 0x00423408, 0x004e3b0b, 0x00654710, 0x00805910, 0x00ba992b, 0x00ccb41c, 0x00cab90a, 0x00c8bb09, 0x00cab80a, 0x00cab112, 0x00a48008, 0x007a5101, 0x00623f04, 0x00503806, 0x00413006, 0x00362708, 0x002d2104, 0x002b1f05, 0x002b1a08, 0x0027190a, 0x0024180b, 0x001f150a, 0x00181308, 0x00141005, 0x00141107, 0x00131008, 0x0017140d, 0x0014110a, 0x00100d06, 0x000f0e06, 0x00121008, 0x00131008, 0x00131007, 0x00131108, 0x00141208, 0x00151208, 0x00171208, 0x00181207, 0x00191207, 0x001a1306, 0x001a1306, 0x001b1407, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1307, 0x001b1307, 0x001b1406, 0x001a1406, 0x001a1406, 0x001a1406, 0x001b1405, 0x001c1305, 0x001e1407, 0x001e1407, 0x001d1104, 0x00201408, 0x00201408, 0x00201408, 0x001f1407, 0x001f1408, 0x001e1407, 0x001d1205, 0x001e1408, 0x001d1206, 0x001d1206, 0x0020160a, 0x001d1308, 0x001a1005, 0x001a1308, 0x001b1408, 0x001c1407, 0x00201509, 0x00221408, 0x00221408, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00211408, 0x00221408, 0x00231509, 0x00231509, 0x00231509, 0x00221509, 0x001f1306, 0x00201408, 0x001f1408, 0x001f1407, 0x001c1104, 0x001c1104, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001c1307, 0x001c1307, 0x001c1206, 0x001b1106, 0x001c1206, 0x001b1407, 0x001c1407, 0x001c1306, 0x001c1307, 0x001d1407, 0x001d1407, 0x001d1306, 0x001d1306, 0x001e1407, 0x001d1305, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1306, 0x001d1306, 0x001d1207, 0x001d1208, 0x001d1207, 0x001d1207, 0x001c1106, 0x001b1005, 0x001c1005, 0x001c1106, 0x001c1106, 0x001d1206, 0x001d1206, 0x001d1206, 0x001d1307, 0x001e1308, 0x001e1308, 0x001c1105, 0x001c1105, 0x001a1105, 0x001a1105, 0x001a1105, 0x001a1105, 0x00191105, 0x00191105, 0x00191105, 0x001a1206, 0x001b1306, 0x001b1407, 0x001b1407, 0x001b1407, 0x001a1406, 0x00191306, 0x00191306, 0x00181004, 0x00191306, 0x00191105, 0x00181105, 0x001c1408, 0x001a1405, 0x001b1406, 0x001c1406, 0x001c1406, 0x001c1406, 0x001c1408, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1308, 0x001c1307, 0x001c1307, 0x001a1306, 0x00191306, 0x00191306, 0x001a1306, 0x001a1306, 0x00191407, 0x001b1408, 0x001b1408, 0x001b1408, 0x001c1408, 0x001c1408, 0x001c1308, 0x001c1308, 0x001c1408, 0x001c1408, 0x001e1409, 0x001c1408, 0x001c1408, 0x001c1307, 0x001c1307, 0x001c1307, 0x001d1207, 0x001d1207, 0x001d1208, 0x001d1208, 0x001e1308, 0x001e1408, 0x001f1408, 0x001f1409, 0x001f1408, 0x001f1407, 0x001f1407, 0x001f1408, 0x00201509, 0x0021170a, 0x00231609, 0x0028190c, 0x002b1b0c, 0x002e1c0d, 0x00301c0b, 0x00331c0b, 0x0038200d, 0x003e270c, 0x00482d0e, 0x005a3513, 0x006d4414, 0x008c6214, 0x00c49c28, 0x00ccae18, 0x00cbb209, 0x00cab408, 0x00cbb608, 0x00cbb70b, 0x00cbb408, 0x00ccb208, 0x00ccb00e, 0x00ccac10, 0x00cca814, 0x00c7a010, 0x00c0940c, 0x00b58604, 0x00b17c01, 0x00ac7200, 0x00a66800, 0x00a66700, 0x00a66601, 0x00a76805, 0x00ab6d09, 0x00b57a11, 0x00be8418, 0x00b47918, 0x00915707, 0x00824d0b, 0x00683a06, 0x004c2700, 0x00422404, 0x003a2008, 0x00351c07, 0x002e1b08, 0x002b1809, 0x00281808, 0x00241707, 0x001e1405, 0x001b1206, 0x00191208, 0x00181208, 0x00181009, 0x0018100a, 0x0017100a, 0x00161009, 0x00171009, 0x0018110b, 0x0018120c, 0x0018120b, 0x001a1208, 0x001e1408, 0x00271b0c, 0x002e2008, 0x00322408, 0x00382808, 0x003f2f08, 0x004d360b, 0x005e400f, 0x007a5412, 0x00a5801b, 0x00caaf24, 0x00cbb615, 0x00ccbb0c, 0x00ccbb0a, 0x00ccba0f, 0x00c4a614, 0x00996e04, 0x00704400, 0x00593901, 0x004b3606, 0x00442e06, 0x003f2906, 0x00382404, 0x00342106, 0x002e1c05, 0x00281b0a, 0x001a1404, 0x00111005, 0x000d0c03, 0x0014140c, 0x0014130a, 0x00101007, 0x000e0f05, 0x000d1008, 0x000d1009, 0x000c0f09, 0x000c100c, 0x000c110c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001c251c, 0x00151c14, 0x000f110b, 0x00101009, 0x0013110b, 0x00141109, 0x00121008, 0x000f0c04, 0x00141007, 0x001b1708, 0x00211a07, 0x00251d05, 0x002a1f06, 0x00312008, 0x00372608, 0x003c2d06, 0x00433408, 0x004c3808, 0x0064440c, 0x00856013, 0x00c09f2e, 0x00ccb41c, 0x00cbba0c, 0x00c9bc0b, 0x00cbb80d, 0x00c8b011, 0x00a07c03, 0x00784f02, 0x00603e07, 0x004e3808, 0x00402f06, 0x00382608, 0x002e2105, 0x00291d06, 0x002a1909, 0x0026180b, 0x0022160a, 0x001d1409, 0x00181308, 0x00141004, 0x00101006, 0x000f1007, 0x00100f08, 0x00110e08, 0x0013100a, 0x0011100a, 0x00121007, 0x00110f07, 0x00131107, 0x00131107, 0x00131107, 0x00141107, 0x00171208, 0x00181107, 0x00181207, 0x00191306, 0x001a1306, 0x001b1407, 0x001b1407, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1405, 0x001c1305, 0x001e1407, 0x001e1407, 0x001e1205, 0x0023160a, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201508, 0x00201508, 0x0020150a, 0x001f1409, 0x00170e03, 0x00171004, 0x001b1508, 0x001d1407, 0x00201307, 0x00211308, 0x00211308, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00211408, 0x00211408, 0x00211408, 0x00221509, 0x00211408, 0x00211408, 0x00201408, 0x00221509, 0x00221509, 0x00201609, 0x00201508, 0x001d1305, 0x001d1305, 0x001d1306, 0x001e1306, 0x001d1306, 0x001d1306, 0x001c1308, 0x001c1308, 0x001b1206, 0x001b1206, 0x001a1306, 0x001b1407, 0x001c1408, 0x001c1308, 0x001c1408, 0x001d1407, 0x001d1407, 0x001d1306, 0x001d1306, 0x001d1306, 0x001d1306, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1306, 0x001d1306, 0x001d1306, 0x001d1208, 0x001d1208, 0x001d1207, 0x001d1207, 0x001d1208, 0x001e1308, 0x001f1409, 0x001f1409, 0x001f1409, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1106, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001a1306, 0x001b1407, 0x001b1408, 0x001c1408, 0x001c1408, 0x001b1408, 0x001a1306, 0x00191206, 0x001b1408, 0x00181105, 0x00181004, 0x001c1509, 0x001a1304, 0x001c1406, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001a1306, 0x00191306, 0x00191306, 0x00191306, 0x00191206, 0x00181105, 0x00181105, 0x00181105, 0x00181105, 0x001b1206, 0x001b1206, 0x001a1105, 0x001a1105, 0x001a1105, 0x001a1105, 0x001b1206, 0x001c1307, 0x001c1307, 0x001e1409, 0x001e1409, 0x001f150a, 0x001f1409, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001c1106, 0x001d1207, 0x001d1205, 0x001e1407, 0x001e1407, 0x00201609, 0x0022170a, 0x00221509, 0x00241608, 0x00281809, 0x002e1a0b, 0x002f1a09, 0x00331c0b, 0x0039200d, 0x003f270c, 0x00492c0e, 0x005c3814, 0x00714617, 0x00936618, 0x00c7a02b, 0x00ccac19, 0x00ccae0e, 0x00cbad0f, 0x00caa912, 0x00c8a70f, 0x00c8a20c, 0x00c39b08, 0x00ba8f07, 0x00b18303, 0x00ac7801, 0x00a67100, 0x00a36c00, 0x00a36a01, 0x00a36702, 0x00a76804, 0x00ab6d08, 0x00b0770f, 0x00b98417, 0x00c2901d, 0x00c89c24, 0x00cca324, 0x00cca421, 0x00bd8c17, 0x00925e04, 0x00804c08, 0x00643804, 0x004a2700, 0x00402202, 0x00371d04, 0x00301a04, 0x00301c08, 0x002a1909, 0x00261704, 0x00231504, 0x001f1305, 0x001b1106, 0x00191208, 0x00181308, 0x0017110a, 0x0017100b, 0x0017100b, 0x0017110a, 0x0017110a, 0x0017110a, 0x0018120c, 0x0017130b, 0x001a1308, 0x001c1408, 0x00291d0d, 0x002e2008, 0x00312407, 0x00382807, 0x003f2f08, 0x004e360c, 0x005c3f0e, 0x00785213, 0x00a27c1a, 0x00c9ad26, 0x00ccb717, 0x00ccbb0d, 0x00ccbb0d, 0x00cbba10, 0x00c4a813, 0x009d7005, 0x00744800, 0x00593c03, 0x004b3508, 0x00442e06, 0x003f2906, 0x00382405, 0x00342006, 0x00301c05, 0x002a1c0c, 0x001f1809, 0x00101005, 0x000d0c04, 0x0014130c, 0x0014130a, 0x00101007, 0x00101007, 0x000f1008, 0x000e110a, 0x000e100c, 0x000e110d, 0x000e130e, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00222922, 0x001b2018, 0x00151811, 0x00171610, 0x001a1812, 0x001c1810, 0x0017140c, 0x0016130b, 0x001e1910, 0x00231d10, 0x0027200d, 0x002c210b, 0x0030250c, 0x00382810, 0x003d2c0f, 0x0044350f, 0x004c3c10, 0x00554011, 0x006b4c13, 0x00906b1c, 0x00c5a534, 0x00ccb41e, 0x00cbbb0d, 0x00c9bb0c, 0x00cbb80f, 0x00c8ae11, 0x009e7901, 0x007b5004, 0x00624008, 0x00513c0d, 0x0045330b, 0x00402c0e, 0x0035280d, 0x0030240c, 0x002d1c0d, 0x00281b0e, 0x0025180d, 0x0020180c, 0x001e180d, 0x0019160b, 0x0016150b, 0x0014160c, 0x0016150e, 0x001b1812, 0x0017140e, 0x0015140e, 0x0018160d, 0x0018160e, 0x0018160c, 0x0019170d, 0x0018180d, 0x001a170d, 0x001d180e, 0x001f180e, 0x0020180d, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0021180c, 0x0021180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020190b, 0x00221a0c, 0x00241a0e, 0x00241a0e, 0x0025190d, 0x002a1e12, 0x00281b0f, 0x0025180c, 0x0024180c, 0x0024190d, 0x0024190c, 0x0024180c, 0x0024190c, 0x00271c10, 0x00281d10, 0x00281d12, 0x00281d12, 0x0020170c, 0x0020190c, 0x0020190d, 0x00231a0c, 0x00251a0d, 0x00281a0f, 0x0027190d, 0x0026190d, 0x0026180c, 0x0027180c, 0x0027180c, 0x0027180d, 0x0026190d, 0x00261a0e, 0x00281b0f, 0x00281b10, 0x00271a0e, 0x00281b0f, 0x00281b10, 0x00271a0e, 0x0025190d, 0x0024180c, 0x0024180c, 0x00251a0d, 0x0024190c, 0x0024190c, 0x0023180c, 0x0024190c, 0x0024190c, 0x00231a0e, 0x00231a0e, 0x0022190d, 0x0022190d, 0x0021190d, 0x0020190d, 0x0021190e, 0x0022190e, 0x0022190d, 0x00231a0d, 0x00241a0d, 0x0024190c, 0x0024190c, 0x0024190c, 0x0024190c, 0x00251b0e, 0x00251b0f, 0x00251b0e, 0x00261c0f, 0x00251b0e, 0x00251b0e, 0x00251a10, 0x00251a10, 0x0024190f, 0x0024190f, 0x0024190f, 0x0024180e, 0x0024190f, 0x0024190f, 0x0024190f, 0x0024190f, 0x0024190e, 0x0024190e, 0x0024190e, 0x0024190e, 0x0024190e, 0x0022180c, 0x0022180c, 0x0021180d, 0x0021180d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0021180d, 0x0022190d, 0x00221a0e, 0x00221b0f, 0x00211a0e, 0x0020190e, 0x00211a0e, 0x00211a0e, 0x00211a0e, 0x00211a0f, 0x00231c10, 0x0020190d, 0x00201a0e, 0x00241c11, 0x00231c0f, 0x00221b0d, 0x0020190a, 0x00211a0c, 0x00221b0c, 0x00231a0e, 0x00231a0e, 0x00221a0e, 0x0022190e, 0x0022190e, 0x0022190e, 0x0022190e, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190e, 0x0022190e, 0x0022190e, 0x0022190e, 0x0021180d, 0x0021180d, 0x0020190d, 0x0020190d, 0x0020190d, 0x0020190d, 0x0020190d, 0x0020190d, 0x00201a0e, 0x00201a0e, 0x00211a0e, 0x00231a0f, 0x00231a0f, 0x0022190e, 0x0022190e, 0x0022190e, 0x0022190e, 0x00231a0f, 0x00231a0e, 0x00231a10, 0x00231a0f, 0x00221a0f, 0x00221a0f, 0x0024190f, 0x0024190f, 0x0024190f, 0x0024190e, 0x0024190e, 0x0024180e, 0x0024180e, 0x0024190e, 0x0024190e, 0x00251c0f, 0x00251c0f, 0x00241a0d, 0x00261c10, 0x00271c10, 0x00281b10, 0x002c1e10, 0x00302010, 0x00342112, 0x0036210f, 0x00382110, 0x003d2512, 0x00442c12, 0x004e3113, 0x00623d1b, 0x00744819, 0x0092641b, 0x00c4982e, 0x00c39c17, 0x00bf9a0b, 0x00b89208, 0x00b08506, 0x00aa7d02, 0x00a47400, 0x009f6c00, 0x009c6800, 0x009c6601, 0x00a16704, 0x00a46709, 0x00ac6c14, 0x00b3741b, 0x00ba7c21, 0x00c48928, 0x00c6942a, 0x00c89d2b, 0x00cca42a, 0x00cca827, 0x00ccac22, 0x00cbad1c, 0x00ccad1b, 0x00b99210, 0x008f6000, 0x007f4e08, 0x00623804, 0x004c2c04, 0x00432606, 0x003e240c, 0x0038220c, 0x0034210f, 0x00301e0f, 0x002c1d0b, 0x00291c0c, 0x0024180b, 0x0021180c, 0x0020180d, 0x001f190e, 0x001f1811, 0x001f1812, 0x001e1811, 0x001d1810, 0x001e1811, 0x001f1811, 0x001f1812, 0x001e1911, 0x0020180f, 0x0022180d, 0x002e2313, 0x0032240d, 0x0034280b, 0x003c2c0b, 0x0044320c, 0x00513a11, 0x00604212, 0x00785212, 0x00a37c1b, 0x00c8ac25, 0x00ccb719, 0x00ccbb0f, 0x00ccbb0e, 0x00cbba10, 0x00c6a814, 0x00a27508, 0x007b4e04, 0x005f400b, 0x00503b0e, 0x0049330c, 0x00442e0d, 0x003f2a0c, 0x003b270d, 0x0036220c, 0x00302111, 0x00261e10, 0x0017160c, 0x0014130c, 0x00191811, 0x001b1b11, 0x00191810, 0x0017170e, 0x0014160e, 0x00141610, 0x00141510, 0x00131611, 0x00141813, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07}; \ No newline at end of file From 2a56f20e0ca5d2810ce4a0e99a8c6ba551f256a0 Mon Sep 17 00:00:00 2001 From: cowsed Date: Tue, 21 Feb 2023 17:23:11 -0500 Subject: [PATCH 179/243] Added Screen subsystem from testing yesterday. Just call StartScreen and it will start vibing no interference necessary Added total time spent in command controller --- include/splash.h | 3 +- include/subsystems/screen.h | 22 ++ src/subsystems/screen.cpp | 202 ++++++++++++++++++ .../command_structure/command_controller.cpp | 3 + 4 files changed, 229 insertions(+), 1 deletion(-) create mode 100644 include/subsystems/screen.h create mode 100644 src/subsystems/screen.cpp diff --git a/include/splash.h b/include/splash.h index bc02f97..d45932d 100644 --- a/include/splash.h +++ b/include/splash.h @@ -2,4 +2,5 @@ // file: clu.png int intense_milk_width = 420; int intense_milk_height = 246; -uint32_t intense_milk[103320] = {0x00152021, 0x00141f21, 0x00141d20, 0x00131d1f, 0x00131e1e, 0x00131e1e, 0x00141f1f, 0x00141f1f, 0x00141e20, 0x00131d1f, 0x00131d1f, 0x00131d1e, 0x00121c1c, 0x00111c1c, 0x00111c1a, 0x00111c1a, 0x00111c1a, 0x00111b19, 0x00111b19, 0x00111b19, 0x00111b19, 0x00101918, 0x00101918, 0x00101918, 0x00101918, 0x00101916, 0x00101916, 0x00101818, 0x00101817, 0x00101817, 0x00101817, 0x00101817, 0x00101817, 0x000f1817, 0x000f1816, 0x000e1816, 0x000d1714, 0x000d1714, 0x000d1714, 0x000c1613, 0x000c1512, 0x000c1512, 0x000e1611, 0x000e1611, 0x000e1611, 0x000e1511, 0x000d1410, 0x000c1410, 0x000c1410, 0x000c1410, 0x000c1410, 0x000c1410, 0x000c1410, 0x000c140f, 0x000c140e, 0x000c140d, 0x000c140d, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000f1310, 0x000d140e, 0x000d140e, 0x000c140c, 0x000c140c, 0x000c140c, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140f, 0x000b1410, 0x000b1510, 0x000c1510, 0x000c1511, 0x000c1512, 0x000c1610, 0x000c1611, 0x000c1710, 0x000f1610, 0x00101811, 0x000f1814, 0x00101914, 0x00101a17, 0x00101a17, 0x00101916, 0x00101915, 0x00101918, 0x00101918, 0x00101918, 0x000f1a18, 0x000f1b18, 0x000e1c19, 0x000c1d19, 0x000c1c19, 0x000d1c19, 0x000d1c19, 0x000d1c19, 0x000f1c19, 0x000e1b18, 0x000e1918, 0x000f1a18, 0x000f1a18, 0x00111c1a, 0x00121b18, 0x00111c18, 0x00101b17, 0x00141c19, 0x002d3030, 0x00454545, 0x00403e3e, 0x00444040, 0x00484446, 0x004a4649, 0x004a484b, 0x00494448, 0x004a4244, 0x004b4040, 0x004a3d3b, 0x004c3e3a, 0x0050403c, 0x004c3b35, 0x00493833, 0x00473530, 0x00473630, 0x0045322e, 0x00473430, 0x00413831, 0x0039322c, 0x00342c26, 0x00322b25, 0x0038332c, 0x00372e26, 0x003a2a22, 0x00412c23, 0x003e1e15, 0x00401b10, 0x003d1c0d, 0x003a1e09, 0x00462812, 0x0050301a, 0x004c2c16, 0x004e2c1a, 0x004f2c1c, 0x00492515, 0x00442210, 0x004c2e18, 0x00573a1f, 0x005e3419, 0x0064391c, 0x00673b1a, 0x00633914, 0x00643a18, 0x00532b0a, 0x004e2508, 0x00532a10, 0x005c3418, 0x005e3818, 0x00603a1a, 0x005c3515, 0x00573113, 0x00593417, 0x00583416, 0x005a3414, 0x005d3716, 0x00613819, 0x00643c1c, 0x006c4220, 0x00673d18, 0x00653c16, 0x00633a16, 0x00603414, 0x00633815, 0x00683c18, 0x006e441c, 0x006e421b, 0x00643910, 0x006a3f18, 0x005b320b, 0x00643c15, 0x00633b16, 0x00613b16, 0x00603a16, 0x005d3818, 0x00583414, 0x005b3518, 0x004c280b, 0x004a2508, 0x00502b0c, 0x005c3416, 0x00613719, 0x0061371a, 0x005e3716, 0x00502c0b, 0x003c220c, 0x00311c0c, 0x00261810, 0x00201414, 0x0017140d, 0x00141509, 0x0015160c, 0x001a1a10, 0x0018170f, 0x00191910, 0x0018180f, 0x0016160d, 0x0016160d, 0x0016160d, 0x0016160d, 0x0015170c, 0x0018160c, 0x001a160c, 0x00201810, 0x00281d16, 0x00342720, 0x00302a24, 0x00312924, 0x00302b24, 0x00282a20, 0x001b2420, 0x00182623, 0x00182824, 0x00152824, 0x00152824, 0x00152724, 0x00172625, 0x00182627, 0x00182627, 0x00182627, 0x00172526, 0x00162424, 0x00162425, 0x00172526, 0x00182526, 0x00172524, 0x00162423, 0x00152420, 0x00142320, 0x00152220, 0x0013201d, 0x00131f1e, 0x0013201f, 0x00121f1e, 0x00101d1d, 0x00101c1c, 0x000f1c1b, 0x00101b1b, 0x00101a1a, 0x000f1819, 0x000f1818, 0x000e1814, 0x000e1611, 0x000e170f, 0x000e170e, 0x000e1610, 0x00101610, 0x00101610, 0x00101610, 0x00101510, 0x0010140f, 0x000e140e, 0x000d140e, 0x000c140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000e140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1417, 0x000b1517, 0x00091416, 0x000a1417, 0x000b1616, 0x000c1716, 0x000c1716, 0x000c1717, 0x000c1718, 0x000c1819, 0x000d1819, 0x000d1818, 0x000c1818, 0x000c1716, 0x000c1715, 0x000c1715, 0x000c1715, 0x000c1514, 0x000c1514, 0x000c1514, 0x000c1514, 0x000b1413, 0x000b1413, 0x000b1413, 0x000b1413, 0x000a1410, 0x000a1410, 0x00091211, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081010, 0x0008100f, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00040e0b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d07, 0x00050d07, 0x00050d06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c08, 0x00060c07, 0x00060c07, 0x00050d05, 0x00050d05, 0x00050d05, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040f09, 0x00040f0a, 0x00040f0b, 0x00050f0a, 0x0005100a, 0x00061008, 0x00070f08, 0x00070f08, 0x0005100a, 0x0006100b, 0x0006100c, 0x0007110d, 0x0008120f, 0x0008120f, 0x00091311, 0x00091311, 0x00091311, 0x00081311, 0x00081412, 0x00071512, 0x00051612, 0x00061612, 0x00061512, 0x00061512, 0x00071512, 0x00081412, 0x00081411, 0x00081311, 0x00081311, 0x00081311, 0x000a1613, 0x000b1411, 0x000c1613, 0x000c1310, 0x001c2220, 0x00343734, 0x00343433, 0x00302c2c, 0x003a3436, 0x00464042, 0x00403c3d, 0x00393436, 0x003b3537, 0x003e3536, 0x003c3130, 0x003a2d2a, 0x003e2f29, 0x0044352f, 0x00483831, 0x003e2d26, 0x0032211a, 0x002d1c14, 0x00301d16, 0x0033241c, 0x0034271f, 0x00332820, 0x00342920, 0x002e241c, 0x00281e15, 0x00302219, 0x00342118, 0x00341e13, 0x00402216, 0x00472515, 0x00452513, 0x00371802, 0x00381802, 0x003a1a06, 0x00452410, 0x004c2c14, 0x004d2b14, 0x00502d15, 0x004c2a10, 0x00432304, 0x004c2d0e, 0x005d3315, 0x00603415, 0x00603514, 0x00623814, 0x005f3612, 0x005a320f, 0x004f2708, 0x00482001, 0x004c2406, 0x005b3414, 0x005a3413, 0x00552f10, 0x004f280b, 0x00441f04, 0x004d280b, 0x00583113, 0x005b3414, 0x005f3715, 0x00613a16, 0x00694019, 0x00643c14, 0x00653c14, 0x00633915, 0x00582e0d, 0x00582e0d, 0x00613612, 0x00683d18, 0x00633811, 0x00643813, 0x00603610, 0x005b320c, 0x00603711, 0x005d3510, 0x005d3611, 0x005d3814, 0x005c3616, 0x00583314, 0x00542f11, 0x00462104, 0x00421d00, 0x00553013, 0x005b3416, 0x00633a1c, 0x005c3416, 0x00542f10, 0x00472407, 0x00341904, 0x002c1709, 0x0021120a, 0x001b100d, 0x0016110b, 0x00151409, 0x00141309, 0x0018170e, 0x00131108, 0x00121007, 0x00121007, 0x00111108, 0x00111108, 0x00111108, 0x00111108, 0x00101206, 0x00101105, 0x00100e04, 0x00161007, 0x00191008, 0x001e140c, 0x00241c15, 0x00251c16, 0x0028211a, 0x0026271e, 0x0018201c, 0x0014201d, 0x0010201d, 0x000f211c, 0x000f201d, 0x0010201f, 0x0010201f, 0x00101f20, 0x00112020, 0x00112020, 0x00122021, 0x00112020, 0x00101f20, 0x00101e1f, 0x000f1d1e, 0x000f1d1c, 0x000d1c1b, 0x000c1c18, 0x000c1b18, 0x000d1a18, 0x000a1814, 0x000a1716, 0x000a1716, 0x00091615, 0x00081514, 0x00081414, 0x00071413, 0x00071313, 0x00071212, 0x00061111, 0x00061010, 0x00050f0c, 0x00060e09, 0x00060e06, 0x00060e06, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c07, 0x00050c06, 0x00050c06, 0x00040c06, 0x00040c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060b06, 0x00060b06, 0x00060b06, 0x00060b06, 0x00060b06, 0x00060b06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000b1517, 0x000b1517, 0x00091416, 0x00081415, 0x000a1414, 0x000a1414, 0x000a1414, 0x000a1414, 0x000b1516, 0x000b1517, 0x000b1517, 0x000b1516, 0x000b1515, 0x000a1414, 0x000a1513, 0x000b1413, 0x000b1413, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x00091211, 0x00091211, 0x0008120f, 0x0008120f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0006100e, 0x0006100d, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x00050c0a, 0x00060d0b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c09, 0x00070d08, 0x00070d08, 0x00060e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d09, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00060e09, 0x00060e09, 0x0005100a, 0x0005100a, 0x0006100c, 0x0007110d, 0x0007110d, 0x0008120f, 0x00091211, 0x00091211, 0x000a1412, 0x00081412, 0x00081413, 0x00081613, 0x00061512, 0x00061512, 0x00061512, 0x00061512, 0x00061512, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x000a1410, 0x000c1310, 0x00171b19, 0x00292c2b, 0x002e2d2c, 0x002c2828, 0x00393433, 0x00484041, 0x004e4545, 0x00474040, 0x003f3838, 0x00372e2d, 0x00312524, 0x00322420, 0x0034241e, 0x0034241c, 0x00312319, 0x003b2b22, 0x0044332a, 0x00402f25, 0x002e1e14, 0x002c190e, 0x0028170c, 0x0029180d, 0x002a190d, 0x002c1b10, 0x00312015, 0x00342219, 0x002c1910, 0x002c180c, 0x00341f10, 0x00381e0e, 0x00482816, 0x0052311c, 0x00502f17, 0x0041200b, 0x003d1c08, 0x003e1c08, 0x0045250e, 0x00503017, 0x004e2c11, 0x00502d10, 0x00563114, 0x004a2404, 0x00522808, 0x005e3214, 0x00592d0c, 0x00603611, 0x00643b14, 0x00633a14, 0x005c3411, 0x00502808, 0x00502808, 0x00542c0c, 0x005c3414, 0x00532c0c, 0x00451f04, 0x0048210c, 0x00462007, 0x00552f12, 0x005c3516, 0x005e3713, 0x00623b13, 0x00653c13, 0x00643c11, 0x00613810, 0x00623814, 0x00552c0a, 0x00522807, 0x00613817, 0x00653c18, 0x00582f0c, 0x005e3411, 0x005c330e, 0x005c340e, 0x005c340f, 0x005a330d, 0x0058310d, 0x005c3513, 0x00583112, 0x00583315, 0x00502b0f, 0x00462003, 0x00512c0f, 0x00563013, 0x005e3819, 0x0060391b, 0x005b3518, 0x0049260d, 0x003c1a03, 0x00301707, 0x00281307, 0x0023140b, 0x001d130c, 0x0019140c, 0x0019160c, 0x0018140c, 0x0016120a, 0x0014110a, 0x00141109, 0x00121008, 0x00131209, 0x0013130a, 0x00131209, 0x00131209, 0x00111308, 0x00101207, 0x000f1004, 0x00131006, 0x00161008, 0x00181108, 0x001c130c, 0x00271a15, 0x00251b15, 0x00242119, 0x001d231e, 0x00141d1c, 0x00121f1c, 0x0010201c, 0x0010201d, 0x0010201f, 0x00112020, 0x00122021, 0x00122021, 0x00112020, 0x00101f20, 0x00101e1f, 0x00101e1f, 0x00101e1f, 0x00101e1f, 0x000f1d1c, 0x000e1c1b, 0x000c1b18, 0x000b1a17, 0x000b1816, 0x000a1814, 0x00091615, 0x00091615, 0x000a1514, 0x000a1414, 0x00081414, 0x00081313, 0x00081212, 0x00071010, 0x00061010, 0x0006100f, 0x00050f0c, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000b1517, 0x000b1517, 0x00091416, 0x00081414, 0x000a1414, 0x000a1513, 0x000a1414, 0x000a1414, 0x000b1515, 0x000b1515, 0x000b1515, 0x000b1515, 0x000b1515, 0x000a1414, 0x000a1513, 0x000b1413, 0x000b1413, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091310, 0x00091310, 0x00091310, 0x0008120f, 0x0008120f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0006100e, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00040e09, 0x00050d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d08, 0x00070d08, 0x00060e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d09, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100c, 0x0007110d, 0x0007110d, 0x0008120f, 0x00091310, 0x00091310, 0x000a1412, 0x00081412, 0x00081413, 0x00081613, 0x00061512, 0x00061512, 0x00061512, 0x00061512, 0x00061512, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081410, 0x000a1410, 0x000c1210, 0x00101512, 0x001e201d, 0x00323030, 0x00464340, 0x00554d4c, 0x004f4645, 0x00443c3b, 0x00423838, 0x00403837, 0x003d3331, 0x003b2e2c, 0x00382924, 0x0034241c, 0x0034271c, 0x00392c22, 0x002f2217, 0x0034261a, 0x00433428, 0x00443428, 0x00312014, 0x00281608, 0x002b170a, 0x002a1808, 0x002b1708, 0x002c1609, 0x00331a10, 0x00371f14, 0x00321b0e, 0x002e1607, 0x00311905, 0x00442810, 0x004a2810, 0x00553218, 0x0058351a, 0x0046240c, 0x00391802, 0x003d1c07, 0x0043220e, 0x004f2c16, 0x00522e14, 0x004c260a, 0x005b3013, 0x0054280c, 0x00532909, 0x005d3210, 0x005c330d, 0x00623912, 0x00643b14, 0x00603813, 0x0059310d, 0x00532b09, 0x00532a09, 0x00583110, 0x00563010, 0x00452005, 0x00401905, 0x00442008, 0x0049240a, 0x00583114, 0x00643c15, 0x00633a11, 0x00653d11, 0x00643c10, 0x005e350c, 0x005e3510, 0x00512908, 0x004d2505, 0x00593210, 0x0055300e, 0x00542c0b, 0x005c3410, 0x00552e0a, 0x005f3713, 0x00562f0a, 0x0056300a, 0x0056300c, 0x00583210, 0x00542f10, 0x00553013, 0x004c280c, 0x00482306, 0x004e2b0d, 0x004f2c0e, 0x005b3718, 0x00573311, 0x00502c0e, 0x003c1a03, 0x00331604, 0x002d1408, 0x00251207, 0x0024140b, 0x001d140a, 0x00191309, 0x00181108, 0x001b150d, 0x001a150e, 0x00141009, 0x00100e06, 0x000f0e05, 0x000e0e05, 0x000e0e05, 0x000e0f06, 0x00101007, 0x00121107, 0x00131308, 0x00111308, 0x00141308, 0x00151308, 0x00181108, 0x001c120b, 0x0022150f, 0x00251b13, 0x00211d15, 0x0020241f, 0x00141e1b, 0x00101d1a, 0x0010201c, 0x0010201d, 0x0011201f, 0x00112020, 0x00122021, 0x00122021, 0x00112020, 0x00101f20, 0x00101e1f, 0x00101e1f, 0x00101e1d, 0x00101e1d, 0x000f1d1c, 0x000e1c1b, 0x000c1b18, 0x000b1a17, 0x000b1816, 0x000a1814, 0x00091615, 0x00091615, 0x000a1514, 0x000a1414, 0x00081414, 0x00081313, 0x00081212, 0x00071011, 0x00061010, 0x0006100e, 0x00050f0c, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1414, 0x00091414, 0x00081414, 0x00081313, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00091413, 0x000a1513, 0x000a1414, 0x000b1414, 0x000b1413, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x00091211, 0x00091310, 0x00091310, 0x00091310, 0x0008120f, 0x0008120f, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100d, 0x0006100e, 0x0006100d, 0x0006100c, 0x0006100c, 0x0008100c, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d05, 0x00040d07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008120d, 0x0008120d, 0x0007130f, 0x0007130f, 0x00081311, 0x00081311, 0x00081412, 0x00071512, 0x00061512, 0x00071512, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081510, 0x00081510, 0x00091410, 0x000f1514, 0x00101514, 0x00171c18, 0x00323633, 0x00424340, 0x004a4b48, 0x00424040, 0x00312e2c, 0x00302a28, 0x00342c2c, 0x00383132, 0x00413837, 0x003c3330, 0x003d342f, 0x00383128, 0x002f291e, 0x002f271d, 0x003c3128, 0x0033271e, 0x0035261d, 0x00403227, 0x00403126, 0x002c1c10, 0x00271708, 0x00291807, 0x002a1604, 0x002e1806, 0x00301709, 0x00351a0d, 0x00412718, 0x003e2411, 0x003e200c, 0x00401d08, 0x004c2910, 0x00512c10, 0x00543011, 0x00563315, 0x00462409, 0x00411f08, 0x003b1905, 0x003f1c0c, 0x004b2814, 0x004d2a10, 0x004c2807, 0x00553010, 0x00583212, 0x00562e0b, 0x005c320d, 0x0060350d, 0x00643b12, 0x00633a13, 0x00582f0b, 0x00552c0a, 0x00522b09, 0x00502a0b, 0x004e290c, 0x0045240a, 0x00351700, 0x003f1e09, 0x004b2813, 0x004c260c, 0x0068401b, 0x00623911, 0x00643b10, 0x00643c10, 0x005c350c, 0x005b3410, 0x004c2607, 0x00442105, 0x004c2a0e, 0x00462406, 0x004d280a, 0x00583212, 0x0055300f, 0x005a3412, 0x004d2804, 0x00542d0b, 0x004f2704, 0x00532c0c, 0x00522c0e, 0x00502c10, 0x00452409, 0x00482810, 0x00412008, 0x00492810, 0x004c2c11, 0x004a2c0f, 0x003e2106, 0x002e1300, 0x002c1404, 0x00291409, 0x0024120a, 0x0022150b, 0x001c140a, 0x00191408, 0x0018140b, 0x001e1a10, 0x00130f06, 0x00120f07, 0x00100f06, 0x000e0c04, 0x00121008, 0x0016140c, 0x0016140c, 0x00141309, 0x00141208, 0x00141208, 0x00141208, 0x00161409, 0x00161208, 0x0018140b, 0x001b130b, 0x001e130c, 0x00241b13, 0x00201f14, 0x0020251d, 0x0017211d, 0x00101e1b, 0x00111f1d, 0x00121f1e, 0x0013201f, 0x0013201f, 0x0013201f, 0x0011201f, 0x0011201f, 0x000f201e, 0x000f1d1d, 0x000f1d1d, 0x000f1d1c, 0x000f1d1c, 0x00101c1c, 0x000f1c1b, 0x000c1918, 0x000c1918, 0x000c1716, 0x000b1515, 0x000b1515, 0x000a1414, 0x00091414, 0x00081414, 0x00081313, 0x00081313, 0x00081211, 0x0007100f, 0x0006100e, 0x0006100e, 0x00050f0c, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1414, 0x00091414, 0x00081414, 0x00081311, 0x00081412, 0x00081410, 0x00081410, 0x00081410, 0x00081411, 0x00081412, 0x00091412, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x00081110, 0x0008120f, 0x00091310, 0x0009130e, 0x0008120d, 0x0007110c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0008100c, 0x00070f0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040d08, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008120d, 0x0008120d, 0x0007130f, 0x0007130f, 0x00081410, 0x00081410, 0x00081411, 0x00071512, 0x00061512, 0x00071512, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081513, 0x00061510, 0x00071510, 0x000c1410, 0x000c130f, 0x00121714, 0x002d312e, 0x00454845, 0x004c4d4b, 0x003d3e3c, 0x00333130, 0x00353231, 0x00373333, 0x00353130, 0x00332d2d, 0x00322d2c, 0x003d3635, 0x003e3935, 0x003c3833, 0x0037342d, 0x00342e28, 0x00312821, 0x00382c24, 0x00362822, 0x0031241c, 0x0041342a, 0x00403228, 0x00302015, 0x002b1a0b, 0x002c1807, 0x00301b08, 0x00341b0a, 0x00371c0c, 0x00371b09, 0x003c1f0c, 0x004b2914, 0x0048230d, 0x004c250c, 0x004f280c, 0x00502a09, 0x00583410, 0x005a3718, 0x004d2810, 0x00421e0c, 0x003e1a0c, 0x003f1d0b, 0x00482710, 0x004e2f12, 0x00442406, 0x004e2b0a, 0x005c3512, 0x0058300d, 0x005b300b, 0x00643a15, 0x00643b15, 0x005e3411, 0x00532a08, 0x004e2807, 0x00492507, 0x00442207, 0x0040230c, 0x00371d07, 0x00351a06, 0x00482915, 0x0044200a, 0x00673e1f, 0x00623b17, 0x005b340d, 0x005c350e, 0x0058330d, 0x00502a0a, 0x00462208, 0x00402008, 0x0041220d, 0x00402008, 0x004c280f, 0x004d280e, 0x00583315, 0x00512e0e, 0x004c2909, 0x004e290a, 0x004f2809, 0x00522c0c, 0x00502c0f, 0x00472509, 0x003f2008, 0x003d200a, 0x00391c08, 0x003c1f0a, 0x0040240c, 0x003e240c, 0x00311804, 0x002a1403, 0x00291408, 0x0028170c, 0x00231208, 0x0021140a, 0x001e1408, 0x001c1509, 0x001e180b, 0x00191208, 0x00171107, 0x00140e04, 0x00120e04, 0x00141007, 0x00151108, 0x00141006, 0x00140f06, 0x00151006, 0x00151005, 0x00181207, 0x00191408, 0x001a1409, 0x00181308, 0x00191408, 0x001a140a, 0x001f140b, 0x0021180f, 0x00211f14, 0x0023251d, 0x0018211c, 0x00101e1a, 0x00101f1d, 0x00111f1e, 0x00121f1e, 0x0013201f, 0x0013201f, 0x0011201f, 0x0011201f, 0x000f201e, 0x000f1d1c, 0x000f1d1c, 0x000f1d1c, 0x000f1d1c, 0x00101c1c, 0x000d1a19, 0x000c1918, 0x000b1818, 0x000c1716, 0x000b1515, 0x000b1614, 0x000a1513, 0x00081412, 0x00081311, 0x00081311, 0x00081311, 0x00081210, 0x0007100d, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081414, 0x00081414, 0x00081313, 0x00081311, 0x00081311, 0x00081410, 0x00081410, 0x00081410, 0x00081311, 0x00081311, 0x00081311, 0x00091211, 0x00091211, 0x00091211, 0x00091211, 0x000a1211, 0x000a1211, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0008120f, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x00060f0c, 0x00070e0c, 0x00060e09, 0x00050d08, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00050e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f0b, 0x00030f0b, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007130f, 0x0007130f, 0x0008120f, 0x0008120f, 0x00081310, 0x00081412, 0x00081412, 0x00081412, 0x00081513, 0x00081513, 0x00081412, 0x000c1816, 0x000c1816, 0x00081513, 0x00071711, 0x00081610, 0x000c1510, 0x000d1411, 0x00292c2b, 0x00444443, 0x004e4c4c, 0x004c4a48, 0x003c3c3a, 0x0041403f, 0x002e2c2b, 0x00201c1b, 0x00201d1c, 0x00252322, 0x002f2d2c, 0x00343031, 0x00353334, 0x003c3b3b, 0x003c3839, 0x00332c2c, 0x00342c27, 0x002e231d, 0x00382b24, 0x00342720, 0x0033251f, 0x00453830, 0x0044362c, 0x00322215, 0x002e1b0b, 0x002f1a08, 0x00311b08, 0x00341908, 0x003b1e09, 0x003f1f08, 0x0045230e, 0x004b250f, 0x004e2810, 0x0051280c, 0x00502807, 0x00522c08, 0x00593313, 0x00613b1e, 0x0059341c, 0x00441f08, 0x003c1b04, 0x003a1c07, 0x0041260f, 0x004d3115, 0x00472708, 0x00543010, 0x005f3817, 0x00552c0b, 0x005c3110, 0x00653a19, 0x00603614, 0x00542a0b, 0x00482405, 0x00422104, 0x003c1e04, 0x00381d08, 0x0039200d, 0x00301705, 0x003a1e0c, 0x003b1907, 0x005a341b, 0x005c3418, 0x00542d0c, 0x00542f0d, 0x00512d0e, 0x00472409, 0x00401f0a, 0x003b1d0c, 0x00381b0d, 0x00402212, 0x00401f0d, 0x0045220d, 0x0049270e, 0x004b290e, 0x0048250b, 0x004b290e, 0x004c290c, 0x00502d0f, 0x004d2c0d, 0x003e1e03, 0x00391d06, 0x00311a06, 0x00301806, 0x002e1805, 0x003a2311, 0x00311c0b, 0x00281506, 0x00241205, 0x00221407, 0x00201208, 0x00201409, 0x00201108, 0x00211309, 0x0022150b, 0x001d1006, 0x001a0d03, 0x001f1408, 0x0021160b, 0x0020160b, 0x001e150a, 0x001e150a, 0x001b1207, 0x001b1206, 0x001b1207, 0x0020170b, 0x0020170b, 0x0020170b, 0x001f160b, 0x001a1207, 0x00181105, 0x001a1308, 0x001f140b, 0x0021140c, 0x00251c13, 0x0026221a, 0x001b201a, 0x00101d18, 0x00101f1c, 0x00101e1d, 0x00101e1d, 0x00101e1d, 0x00101e1d, 0x00101e1d, 0x00111f1e, 0x00101e1d, 0x000e1c1b, 0x000e1c1b, 0x000e1c1b, 0x000e1c1b, 0x000f1c1b, 0x000d1a19, 0x000c1918, 0x000b1818, 0x000b1614, 0x000a1514, 0x000a1513, 0x00091412, 0x00091310, 0x00091310, 0x00081310, 0x0008120f, 0x0008120f, 0x0007100d, 0x0006100c, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081414, 0x00081414, 0x00081313, 0x00081311, 0x00081311, 0x00081410, 0x00081410, 0x00081410, 0x00081310, 0x00081311, 0x00081211, 0x00091211, 0x00091211, 0x00091211, 0x00091211, 0x000a1211, 0x000a1211, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0008120f, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x00070e0c, 0x00060e09, 0x00040c08, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f0b, 0x00030f0b, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007130f, 0x0007130f, 0x00081310, 0x0008120f, 0x00081310, 0x00081412, 0x00081412, 0x00081412, 0x00081513, 0x00081513, 0x00091513, 0x00101c1a, 0x000f1c19, 0x00081513, 0x00061711, 0x00081610, 0x000e1712, 0x001e2321, 0x00404442, 0x004f4d4c, 0x004f4949, 0x004b4646, 0x00413e3d, 0x003c3a39, 0x003c3a39, 0x00363434, 0x002e2c2a, 0x00262623, 0x00282827, 0x00303030, 0x00323135, 0x00333137, 0x003b363c, 0x003e363a, 0x00332a28, 0x00322623, 0x002e201b, 0x003c2f2a, 0x003a2c28, 0x00342720, 0x0044342c, 0x00433126, 0x00362213, 0x00351f0c, 0x00341c09, 0x00381e09, 0x00381904, 0x00422009, 0x0048230c, 0x004a240e, 0x00502911, 0x00542b10, 0x00532b0e, 0x00512b0b, 0x00552f0e, 0x005c3514, 0x0065401c, 0x0054300e, 0x00401f00, 0x00371b01, 0x00341a02, 0x00472d13, 0x0054341a, 0x004e2c0e, 0x00593415, 0x005c3314, 0x00522606, 0x005a2f0e, 0x005f3414, 0x00583012, 0x004b270a, 0x00442409, 0x003c1e07, 0x00321905, 0x00301b0a, 0x00341d0d, 0x00371c0d, 0x00371809, 0x004e2b16, 0x00543018, 0x00492509, 0x00452306, 0x00432205, 0x003c1c06, 0x00371808, 0x00381c10, 0x0031180c, 0x00361b0e, 0x00351608, 0x003e1d0c, 0x00442510, 0x0046280f, 0x003f2006, 0x004a2910, 0x004e2c11, 0x00533113, 0x0048290c, 0x00391c02, 0x00341a04, 0x00281605, 0x002c1a09, 0x002b1808, 0x00301d0f, 0x002b1a0c, 0x00231306, 0x00201305, 0x001e1407, 0x001d1408, 0x001f1308, 0x001e0f04, 0x0026150b, 0x0028170d, 0x002a180e, 0x002d1c11, 0x002d1c11, 0x002b1b10, 0x0028180e, 0x0024150a, 0x0024160b, 0x0026190e, 0x0026190e, 0x0025180c, 0x0022170b, 0x0022170a, 0x00201609, 0x00201609, 0x0021160a, 0x001f1408, 0x0020170b, 0x0024170e, 0x0024140c, 0x00281813, 0x00291f18, 0x001e1f18, 0x00111d18, 0x000e1e1c, 0x00101d1c, 0x00101c1c, 0x00101c1c, 0x00101c1c, 0x000f1d1c, 0x00101e1d, 0x000f1d1c, 0x000e1c1b, 0x000e1c1b, 0x000c1c1a, 0x000c1c1a, 0x000e1b1a, 0x000c1918, 0x000c1918, 0x000a1814, 0x000b1614, 0x000a1512, 0x00081411, 0x00081410, 0x0009140f, 0x0009130e, 0x0009120e, 0x0008120d, 0x0008120d, 0x0007110c, 0x0006100b, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091413, 0x00091413, 0x00081412, 0x00081311, 0x00071210, 0x00071310, 0x00071310, 0x00071310, 0x00081211, 0x00081211, 0x00091211, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00091110, 0x00091110, 0x00081010, 0x0008110e, 0x0007110e, 0x0007110c, 0x0008110c, 0x0007110c, 0x0005100b, 0x0005100a, 0x0005100b, 0x0005100b, 0x0004100b, 0x0004100b, 0x0005100b, 0x00060f0b, 0x00060e0a, 0x00050e0a, 0x00060e0a, 0x00060e0a, 0x00060e0a, 0x00060e0a, 0x00060e09, 0x00050e09, 0x00050e08, 0x00060d08, 0x00060d08, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00050d09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e08, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0005100a, 0x0004100a, 0x0006120c, 0x0008110d, 0x0008110d, 0x0008120f, 0x00091410, 0x00091210, 0x00091210, 0x00091211, 0x00081311, 0x00081412, 0x00081412, 0x00091412, 0x00091512, 0x000c1613, 0x0016201d, 0x00101c19, 0x00081612, 0x00091813, 0x000b1713, 0x0018201c, 0x003d3f3e, 0x004d4a4b, 0x00494645, 0x003f3a3a, 0x00332f2f, 0x002a2626, 0x00312f2e, 0x00393837, 0x00444442, 0x003e3e3c, 0x002c2d2b, 0x00222421, 0x00272828, 0x002c2f32, 0x002c2f34, 0x0036383c, 0x00383437, 0x00393030, 0x00372b28, 0x00352924, 0x00362a24, 0x00392c28, 0x003a2d27, 0x00332119, 0x00412d22, 0x00422d1d, 0x0038210d, 0x00381e09, 0x00442913, 0x003c1e08, 0x003c1903, 0x0049260e, 0x00512d15, 0x00532c13, 0x00562e14, 0x00583114, 0x00542c0e, 0x00502a08, 0x0058330c, 0x0058340f, 0x005f3a16, 0x00523011, 0x003b1d04, 0x00311703, 0x00381c09, 0x004d3018, 0x00543419, 0x004f2c0d, 0x00593112, 0x00572e0e, 0x004c2000, 0x00552c0c, 0x00552f10, 0x004c2b0f, 0x0048260e, 0x00381904, 0x00311804, 0x002d1809, 0x002c1508, 0x002d1608, 0x002e1504, 0x003c200c, 0x00462813, 0x003c2008, 0x00391c05, 0x00381b07, 0x00341807, 0x0030160a, 0x00331b10, 0x002c140a, 0x002d1408, 0x00351a0f, 0x0034190c, 0x00402511, 0x00391d05, 0x003b1d05, 0x00482910, 0x004e2e12, 0x004c2c10, 0x0044270c, 0x00341904, 0x002e1806, 0x00231406, 0x00251608, 0x002c1b0d, 0x002c1a0c, 0x00251608, 0x001e1103, 0x001d1203, 0x00201408, 0x0021170c, 0x00201409, 0x002b1b10, 0x002e1c10, 0x002f1a0d, 0x00361f11, 0x00382114, 0x00341f10, 0x002f1b0c, 0x002d190c, 0x0029180b, 0x0027170a, 0x00241509, 0x0024150a, 0x0024180c, 0x0022180b, 0x00201608, 0x001f1408, 0x00201408, 0x0022170c, 0x0023180c, 0x0022190e, 0x0028180e, 0x002c140c, 0x002c160e, 0x002c1c16, 0x001f1d18, 0x00121c18, 0x000e1e1b, 0x00101d1c, 0x000f1c1b, 0x000f1c1b, 0x00101c1c, 0x00101c1c, 0x00101d1c, 0x000e1c1b, 0x000d1c1a, 0x000c1c1a, 0x000c1b19, 0x000d1b19, 0x000d1a19, 0x000c1918, 0x000c1716, 0x000b1715, 0x000b1514, 0x00091414, 0x00081411, 0x00081510, 0x00081410, 0x0008140f, 0x0008120c, 0x0007100b, 0x0006100a, 0x0006100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d0a, 0x00050d09, 0x00050d09, 0x00050d07, 0x00050d06, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1513, 0x00091413, 0x00081412, 0x00081311, 0x00071210, 0x00071210, 0x00071210, 0x00071210, 0x00081211, 0x00091211, 0x00091211, 0x00081110, 0x00081010, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0007110d, 0x0007110c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00040f09, 0x00040f09, 0x00060f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x0005110b, 0x0007110d, 0x0007110d, 0x0007110d, 0x00091310, 0x00091211, 0x00091211, 0x00091211, 0x00081311, 0x00081412, 0x00081412, 0x00091412, 0x000a1511, 0x000c1613, 0x001b2420, 0x0018211e, 0x00091511, 0x000c1814, 0x0016201c, 0x00343938, 0x004d4c4c, 0x00443e40, 0x003b3736, 0x002c2828, 0x00252221, 0x001f1e1c, 0x00242221, 0x002a2b28, 0x00373836, 0x0040423f, 0x003c3d3b, 0x002d2e2c, 0x00232422, 0x00272827, 0x00282a29, 0x00353736, 0x003d3a39, 0x00352b2a, 0x003b2e2b, 0x00423530, 0x003f322c, 0x00392c27, 0x003e312a, 0x00402c24, 0x00342013, 0x00442b1c, 0x004b301c, 0x0041240f, 0x00472812, 0x004c2b15, 0x0045230d, 0x003c1801, 0x004c2810, 0x00532c14, 0x00573016, 0x00593217, 0x00563011, 0x00502c08, 0x00542f0a, 0x00512c08, 0x00502c0c, 0x00553315, 0x0043240e, 0x00341808, 0x002f1405, 0x003b1c0b, 0x0053321b, 0x00512d13, 0x004c2607, 0x00562f10, 0x00512a0b, 0x00482001, 0x004a2407, 0x0048250c, 0x0045240d, 0x00391b06, 0x00311706, 0x002a1508, 0x002a1608, 0x002c1608, 0x002c1606, 0x00341d0c, 0x003a2310, 0x00351c09, 0x00321906, 0x00301808, 0x002c1508, 0x002a1409, 0x002d170c, 0x002b150b, 0x002b1408, 0x00321a0e, 0x002f180a, 0x0037200e, 0x00331a04, 0x00351b04, 0x00482a13, 0x0047280f, 0x0045270d, 0x003c1e09, 0x002e1607, 0x00241206, 0x00201408, 0x0025180c, 0x002a1b0e, 0x00281808, 0x00211202, 0x001e1001, 0x00211406, 0x0024170a, 0x00281a10, 0x0026180c, 0x002a180c, 0x00301b0e, 0x00392213, 0x003a2010, 0x00381e0e, 0x00371c0c, 0x0031190b, 0x002e180a, 0x00291508, 0x00241409, 0x0024140c, 0x0022130b, 0x00201309, 0x001c1208, 0x001a1107, 0x001a1006, 0x00191005, 0x001a1005, 0x001a1006, 0x001c1308, 0x0026140c, 0x002f170f, 0x00341b11, 0x002c1c15, 0x00201c18, 0x00131c16, 0x000e1d1b, 0x00101d1c, 0x000f1c1b, 0x000e1b1a, 0x000e1b1a, 0x000e1b1a, 0x000e1b1a, 0x000d1c1a, 0x000c1c1a, 0x000c1c1a, 0x000d1a19, 0x000d1a19, 0x000c1918, 0x000b1818, 0x000c1716, 0x000c1716, 0x000b1515, 0x00081414, 0x00081412, 0x00081510, 0x00081410, 0x0007130e, 0x0007120c, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1513, 0x00091413, 0x00081412, 0x00081311, 0x00071210, 0x00071210, 0x00081210, 0x00081110, 0x00081110, 0x00091110, 0x00091110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0006100c, 0x0005100a, 0x00040e09, 0x00040e08, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x00030e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x0005110b, 0x0007110d, 0x0007110d, 0x0007110d, 0x0008120f, 0x00091110, 0x00091110, 0x00091211, 0x00091211, 0x00091312, 0x00091412, 0x00091412, 0x000b1411, 0x000c1613, 0x00202725, 0x00202724, 0x000d1411, 0x00171c1a, 0x00303534, 0x00464b48, 0x00454445, 0x00373435, 0x002c2b2a, 0x001d1c1b, 0x00141311, 0x000f100e, 0x000c0e0c, 0x0010110f, 0x00181a18, 0x002c2e2c, 0x003c3d3b, 0x003f3d3c, 0x0034302c, 0x00302a24, 0x003b332d, 0x0038302a, 0x00413833, 0x00423632, 0x003a2c27, 0x00473930, 0x0044372c, 0x0042342a, 0x00403127, 0x00493328, 0x00442c1d, 0x003e2411, 0x004f311c, 0x0054341d, 0x00502e18, 0x004c2813, 0x00512e16, 0x004a250d, 0x004b240b, 0x00542e14, 0x00573014, 0x00583114, 0x00593412, 0x0054300c, 0x00522e09, 0x00502c08, 0x00442000, 0x00462407, 0x00482813, 0x003b1f0f, 0x0034180c, 0x0036190c, 0x00442412, 0x00513018, 0x0049270c, 0x00482408, 0x00522c10, 0x00482106, 0x00432004, 0x00412008, 0x00432410, 0x003c1f0c, 0x00311909, 0x00241204, 0x00281608, 0x00281606, 0x00291605, 0x002f1a0b, 0x00321c0c, 0x00301a08, 0x002e1807, 0x002d1807, 0x00281406, 0x00271408, 0x0028150a, 0x00281509, 0x002a1508, 0x002c180b, 0x002c1709, 0x00301b0c, 0x00311a08, 0x00321804, 0x00452814, 0x003f2009, 0x003c2008, 0x00331906, 0x00291405, 0x00231308, 0x001c1409, 0x00241a0e, 0x0026180b, 0x00221404, 0x00201101, 0x00201203, 0x00241608, 0x00281a0c, 0x002b1b0f, 0x0028180c, 0x00301c0f, 0x00341c0c, 0x003d2211, 0x003c1f0e, 0x00371a09, 0x00381d0c, 0x00341909, 0x002d1709, 0x00291409, 0x0026140c, 0x0023140c, 0x0021110a, 0x0020120a, 0x001e140b, 0x001f150c, 0x001f140c, 0x001f140c, 0x001e140b, 0x001c1209, 0x001a1007, 0x001f1007, 0x00231208, 0x002a180c, 0x002c1c14, 0x00241c16, 0x00181a14, 0x00101b17, 0x000e1c1a, 0x000e1b1a, 0x000d1a19, 0x000d1918, 0x000d1919, 0x000d1919, 0x000c1a18, 0x000c1b19, 0x000d1c1a, 0x000d1a19, 0x000c1818, 0x000b1818, 0x000a1716, 0x000b1515, 0x000b1515, 0x000a1414, 0x00081414, 0x00071411, 0x00061410, 0x0006130f, 0x0006120d, 0x0007120c, 0x0006100b, 0x00050f0a, 0x0005100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e0a, 0x00060e09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091513, 0x00091413, 0x00081412, 0x00081311, 0x00071210, 0x00071210, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0007100d, 0x0005100a, 0x00040e09, 0x00040d08, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x00030f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x0005110b, 0x0007110d, 0x0008120e, 0x0008120f, 0x0008110e, 0x00091010, 0x00091010, 0x00091211, 0x000a1311, 0x00091312, 0x00091412, 0x000a1412, 0x000b1411, 0x000d1613, 0x00272e2c, 0x002c2f2e, 0x001f201f, 0x00393939, 0x004c4c4c, 0x00474848, 0x003a3939, 0x002e2f2f, 0x001f2020, 0x00111413, 0x000c100c, 0x000e110e, 0x000e100e, 0x00101210, 0x00101310, 0x00181b18, 0x00302f2d, 0x0044403e, 0x004a403c, 0x0040322a, 0x00403126, 0x0044372b, 0x003c2e24, 0x00463730, 0x00483830, 0x00403024, 0x004a3c2d, 0x00463829, 0x00443426, 0x00493124, 0x004c3322, 0x004c311c, 0x00472810, 0x004f2e15, 0x0058361c, 0x00573219, 0x00583017, 0x005c371b, 0x00532c0f, 0x00492204, 0x00502a0c, 0x005c3515, 0x005a3312, 0x0058310f, 0x0054300a, 0x00522d08, 0x004e2a08, 0x00432002, 0x003b1b04, 0x00371b0c, 0x00341910, 0x00301509, 0x003c200e, 0x00442510, 0x00472610, 0x00422009, 0x0047230d, 0x0047240d, 0x003d1d06, 0x00381a04, 0x003b1e0c, 0x00361c0a, 0x00301b0c, 0x00251506, 0x00241606, 0x00261506, 0x00261606, 0x002b1809, 0x002e1c0c, 0x002b1707, 0x002c1808, 0x002a1606, 0x00261406, 0x00261408, 0x00261408, 0x00271609, 0x00281809, 0x00291609, 0x002a1809, 0x002c1809, 0x002f1909, 0x00341d0c, 0x003c2210, 0x00381e08, 0x00371c08, 0x002c1504, 0x0029160a, 0x001f1108, 0x001c140a, 0x00241a0f, 0x0024180b, 0x00211406, 0x00201304, 0x00201304, 0x00241608, 0x00281a0c, 0x002a180c, 0x00331e10, 0x00341c0d, 0x00381e0d, 0x003c200c, 0x00381905, 0x003e200c, 0x003c1f0b, 0x00331806, 0x002d1407, 0x002b150a, 0x0026140c, 0x0021100a, 0x0021100a, 0x0022140c, 0x001f140c, 0x001e140b, 0x00221710, 0x001c120b, 0x001f140b, 0x001e140b, 0x0020130b, 0x001f160b, 0x001c1305, 0x00221708, 0x00281c0f, 0x00271d14, 0x001c1a14, 0x00101914, 0x000c1b17, 0x000d1a19, 0x000d1918, 0x000d1818, 0x000c1918, 0x000d181a, 0x000c1918, 0x000b1a18, 0x000d1c1a, 0x000c1918, 0x000a1817, 0x000b1817, 0x00091615, 0x000a1414, 0x000a1414, 0x00081414, 0x00081313, 0x00051310, 0x0005130f, 0x0006120e, 0x0006120c, 0x0008120c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081412, 0x00081412, 0x00081411, 0x00081311, 0x00081311, 0x00081311, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0006100e, 0x0007100d, 0x0008120e, 0x0007110b, 0x0005100a, 0x00040f09, 0x00050f0a, 0x00050f0a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x00060f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00040d08, 0x00040d08, 0x00050d09, 0x00050d09, 0x00060d09, 0x00060d09, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00060e08, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00050e09, 0x00040e09, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x00040f09, 0x0005110b, 0x0007110d, 0x0008130f, 0x00091310, 0x00091310, 0x0009110f, 0x0009120f, 0x00091210, 0x00081411, 0x00081412, 0x00091412, 0x000c1412, 0x000c1411, 0x000f1514, 0x002c3130, 0x00383a39, 0x00403e3d, 0x00534f4f, 0x004c4949, 0x003c3c3c, 0x00343434, 0x00292c2b, 0x001e2322, 0x00191d1d, 0x00181c1a, 0x00161917, 0x00111310, 0x00101110, 0x00101210, 0x00121311, 0x001b1918, 0x00342c2a, 0x004b3e37, 0x00534036, 0x004c3729, 0x004b3728, 0x0048372b, 0x003c2c23, 0x004e3e32, 0x00463428, 0x00463224, 0x004e392b, 0x004c3828, 0x004c3424, 0x004d3320, 0x00563823, 0x0053321b, 0x004c2a10, 0x00532e14, 0x005c351a, 0x005c3518, 0x005e3618, 0x005d3716, 0x00563010, 0x00462000, 0x00542d0d, 0x005c3414, 0x005b3410, 0x0058320c, 0x00542d0a, 0x00542e0a, 0x004b2708, 0x0043220b, 0x00371b09, 0x002f160b, 0x0030170a, 0x002f1504, 0x00381f0d, 0x003f2110, 0x003c1d0c, 0x00391a09, 0x00412310, 0x003c1e0a, 0x00361905, 0x00321804, 0x00321906, 0x00301a09, 0x0029190b, 0x00211304, 0x00241607, 0x00241606, 0x00261807, 0x00291a0a, 0x00271607, 0x00291909, 0x00281707, 0x00271708, 0x00241408, 0x00241508, 0x0027170a, 0x0028180a, 0x00281608, 0x002a1808, 0x002b1707, 0x002c1808, 0x00372010, 0x00341d0c, 0x00341b0a, 0x002e1807, 0x00281404, 0x0027170a, 0x001a0f04, 0x001c150a, 0x0022190d, 0x00201609, 0x00201407, 0x00211306, 0x00211307, 0x00251609, 0x0029180c, 0x00331e10, 0x00382011, 0x00361c0b, 0x003b1f0a, 0x0040210c, 0x003f1f0b, 0x00442410, 0x00381a05, 0x00331706, 0x0031190e, 0x002f1810, 0x0024140c, 0x0021130c, 0x001e1109, 0x001c1108, 0x00181007, 0x00140f04, 0x00150e06, 0x00150f06, 0x00150f06, 0x00150f06, 0x00180e06, 0x00161107, 0x00141305, 0x00191508, 0x0020180c, 0x00241a10, 0x001e1c14, 0x00141b11, 0x000f1a14, 0x000f1917, 0x000e1918, 0x000d1919, 0x000d191a, 0x000c181a, 0x000c1918, 0x000b1a18, 0x000c1c18, 0x000c1918, 0x000a1816, 0x000a1816, 0x00091614, 0x00091414, 0x00091414, 0x00081413, 0x00081312, 0x00051310, 0x0006130f, 0x0007120e, 0x0006110c, 0x0008120d, 0x0008120d, 0x0006100b, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f09, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050d09, 0x00040d07, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00061411, 0x00061411, 0x00071411, 0x00071411, 0x00081311, 0x00091311, 0x00091211, 0x00081110, 0x00081210, 0x0008120d, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110d, 0x0008110e, 0x0008120e, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0005100a, 0x00061009, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0007100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x0004100a, 0x0004100a, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110f, 0x0009130f, 0x00081410, 0x00081510, 0x00091511, 0x000a1511, 0x000c1411, 0x000e1513, 0x00151b19, 0x00303332, 0x00444444, 0x004c4b49, 0x004d4a49, 0x00423f3e, 0x00373735, 0x00333434, 0x002e3232, 0x00283030, 0x00262c2c, 0x00292c2b, 0x00222422, 0x00191817, 0x00131410, 0x00131310, 0x00151412, 0x001b1715, 0x002c2421, 0x003d3028, 0x0048372c, 0x00543e31, 0x004b3728, 0x004c3b2c, 0x00402f22, 0x00443428, 0x004f3b2f, 0x004a3426, 0x004a3023, 0x00543929, 0x00503524, 0x00513521, 0x00533620, 0x00583820, 0x00553418, 0x00522d10, 0x00552d10, 0x005d3415, 0x00663e1c, 0x00613a18, 0x00603917, 0x00552d0c, 0x00482000, 0x0057300e, 0x00643c19, 0x00603a16, 0x005c3410, 0x0058300b, 0x005b3515, 0x00502f15, 0x003f200d, 0x00301608, 0x002f1606, 0x002c1604, 0x002f1908, 0x00381d10, 0x00351b0c, 0x0034180a, 0x0036190c, 0x003a200e, 0x00341a06, 0x002f1604, 0x00311805, 0x00311c0b, 0x002d190c, 0x00241304, 0x00241406, 0x00231606, 0x00241808, 0x00281a0b, 0x00261708, 0x002b1b0c, 0x0028180c, 0x0028180a, 0x00241408, 0x00241407, 0x0028180b, 0x002a1a0c, 0x00271506, 0x002c1808, 0x002b1604, 0x002e1808, 0x00321b0c, 0x00311a0a, 0x002f180a, 0x002b1606, 0x00261505, 0x00211405, 0x001c1103, 0x001d1609, 0x001f1608, 0x00201408, 0x00221408, 0x00241508, 0x0026170b, 0x0028150b, 0x002b160c, 0x00321709, 0x00361b0b, 0x00381c09, 0x003c1f09, 0x0043230c, 0x00482810, 0x0041210c, 0x003a1c08, 0x00361a0b, 0x0031180e, 0x0028130c, 0x0023120c, 0x001c100a, 0x00161008, 0x00110f04, 0x000e0d03, 0x000c0d02, 0x000d0d02, 0x000d0d02, 0x000d0c04, 0x000c0c03, 0x000e0b04, 0x00090c02, 0x00060c02, 0x000a0e04, 0x00140d07, 0x0018120a, 0x001b1910, 0x001a1e12, 0x00131a12, 0x00101814, 0x00101818, 0x000e1819, 0x000d181a, 0x000c181a, 0x000a1819, 0x000a1916, 0x000a1916, 0x000a1814, 0x000a1814, 0x00081613, 0x00081412, 0x00081510, 0x00081510, 0x00081510, 0x00071410, 0x00051310, 0x0007130f, 0x0006100c, 0x0006100c, 0x0006100b, 0x0006100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00070f09, 0x00060e08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00051411, 0x00051411, 0x00071411, 0x00071411, 0x00081412, 0x000a1412, 0x00091211, 0x00081110, 0x0008120f, 0x0008120d, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0006100c, 0x00040e0b, 0x00040e09, 0x00051008, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x0004100a, 0x0004100a, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110d, 0x0009130e, 0x00081410, 0x00081510, 0x00081611, 0x000a1511, 0x000c1511, 0x00131816, 0x00202422, 0x00343534, 0x004e4e4e, 0x004e4c4d, 0x00444244, 0x00383839, 0x00343636, 0x00303535, 0x002d3434, 0x00272e30, 0x00252a2c, 0x00202224, 0x00242120, 0x00282724, 0x00201d1b, 0x00191513, 0x00181412, 0x0015120e, 0x001d1912, 0x002f241b, 0x003d2e22, 0x00443324, 0x004b3a2a, 0x004f3e30, 0x004a3a2c, 0x00412f23, 0x00453126, 0x00503b2e, 0x00472e21, 0x00493120, 0x004f3824, 0x004e3721, 0x00533720, 0x0054371d, 0x005e3f24, 0x005b381a, 0x00522c0e, 0x00542c0b, 0x005c3513, 0x006e4622, 0x00653d1a, 0x00603817, 0x00542c0c, 0x00482201, 0x005b3614, 0x00643e1c, 0x00643c1a, 0x00552e0b, 0x00573210, 0x005a381c, 0x0051311a, 0x0040230e, 0x00311502, 0x002c1403, 0x002e1708, 0x00321b0d, 0x0030180a, 0x002f1508, 0x00301809, 0x00371f0e, 0x00331c0a, 0x002f1605, 0x00301808, 0x00321b0c, 0x002e1909, 0x00291607, 0x00261406, 0x00241506, 0x00261708, 0x002b180b, 0x00281608, 0x002c190c, 0x002a180c, 0x0029180a, 0x00271408, 0x00261406, 0x0028180b, 0x002c1c0d, 0x00281506, 0x002c1707, 0x002c1504, 0x00301908, 0x00321b0b, 0x002f1809, 0x002e1709, 0x00281505, 0x00241404, 0x00201403, 0x00201406, 0x00211609, 0x00211408, 0x00241408, 0x00271509, 0x00271408, 0x0029170b, 0x002c180c, 0x002e160b, 0x0033180b, 0x0036190a, 0x00381c08, 0x003c200a, 0x00492912, 0x004c2b12, 0x0044240f, 0x0040240f, 0x003a2010, 0x002f170d, 0x0026130b, 0x001f1009, 0x00140d04, 0x000f0f04, 0x000c0d01, 0x00090f04, 0x00090f04, 0x000a0f04, 0x000b0e04, 0x000a0e05, 0x00080d05, 0x00080d04, 0x00060d04, 0x00050c04, 0x00050c02, 0x00090902, 0x000c0b03, 0x00111008, 0x00191912, 0x00181c15, 0x00101814, 0x000e1716, 0x000c1717, 0x000b1618, 0x00081717, 0x00091816, 0x00091814, 0x00091813, 0x000a1714, 0x000a1814, 0x00081412, 0x00051310, 0x00081510, 0x00081510, 0x00081410, 0x00071410, 0x00051310, 0x0006110e, 0x0005100c, 0x0005100b, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071411, 0x00071411, 0x00071411, 0x00071411, 0x00081412, 0x000a1412, 0x00091211, 0x00081110, 0x0008110e, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0007110d, 0x00050f0c, 0x0005100a, 0x00051008, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x0004100a, 0x0004100a, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110d, 0x0009130e, 0x0008140f, 0x00081410, 0x00081611, 0x000a1510, 0x000b120e, 0x00111512, 0x002c2e2b, 0x00484847, 0x004a4a4a, 0x00404244, 0x00363839, 0x00303335, 0x002e3234, 0x002c3234, 0x002b3434, 0x002b3235, 0x00292e30, 0x00292b2c, 0x00272524, 0x002a2622, 0x002a2521, 0x0025201c, 0x001c1713, 0x001b1813, 0x001e1a14, 0x00272014, 0x0034281c, 0x00392a1b, 0x003c2d1d, 0x00463628, 0x004f3d2f, 0x00473428, 0x003a281c, 0x00453224, 0x004a3427, 0x00422c1b, 0x004c3622, 0x004d3821, 0x004d361f, 0x0053391f, 0x00563a1d, 0x00604022, 0x005a3818, 0x00593413, 0x00562f0d, 0x00623a18, 0x0068401f, 0x005d3715, 0x005b3414, 0x004f2809, 0x00482103, 0x00563113, 0x00653e20, 0x0060381b, 0x00502a0c, 0x004c280c, 0x004c2c11, 0x004e2e15, 0x003f220c, 0x00341807, 0x002d1405, 0x002c1508, 0x002d160a, 0x002d160a, 0x002d1608, 0x002e1909, 0x00331e0e, 0x00301c0c, 0x002d1709, 0x0030190b, 0x00301c0d, 0x002c1809, 0x00271507, 0x00241506, 0x002a170a, 0x002a1609, 0x002c190c, 0x002e180c, 0x002b180c, 0x002b170c, 0x002c180b, 0x00271406, 0x0028170a, 0x002c1c0d, 0x002b1808, 0x002d1908, 0x00301a08, 0x00331c0c, 0x00341c0c, 0x0030190a, 0x002e1809, 0x002a1808, 0x00261404, 0x00231505, 0x00241709, 0x0025170b, 0x00241409, 0x00281509, 0x002c180d, 0x002c170c, 0x002f1a0e, 0x00392014, 0x00371b10, 0x00381b0d, 0x00351808, 0x00351905, 0x003f220d, 0x004b2a14, 0x004b2a12, 0x00492814, 0x00402410, 0x00311808, 0x00281308, 0x00221008, 0x00190f06, 0x00130d04, 0x000d0f03, 0x000c0f03, 0x00091003, 0x00081004, 0x00091008, 0x00091008, 0x00080f07, 0x00080f07, 0x00040f06, 0x00060e06, 0x00070e06, 0x00070e06, 0x00060e06, 0x00080d04, 0x000a0c04, 0x0014120d, 0x00181914, 0x00101714, 0x000c1414, 0x000c1515, 0x000b1517, 0x00091617, 0x00091615, 0x00091714, 0x00091712, 0x00081513, 0x00081513, 0x00081412, 0x00081412, 0x00081510, 0x00081510, 0x00071410, 0x0005130f, 0x0004120f, 0x0005100d, 0x0005100c, 0x0005100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00060e09, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071411, 0x00071411, 0x00071411, 0x00071411, 0x00081311, 0x00091211, 0x00081110, 0x00081110, 0x0008110e, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007100c, 0x0006100c, 0x0006100c, 0x00040d0a, 0x00040e0a, 0x0006100c, 0x00050f0c, 0x0005100a, 0x00051008, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c08, 0x00060c08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x0004100a, 0x0004100a, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110d, 0x0009130e, 0x0008140f, 0x00081410, 0x00081610, 0x000a1510, 0x00101713, 0x002d302e, 0x0050514f, 0x003e3c3c, 0x00313031, 0x002c2d2f, 0x00222426, 0x0024282b, 0x00282d2f, 0x00283032, 0x00263032, 0x00252d30, 0x0024292b, 0x00242628, 0x00252422, 0x0025231e, 0x0027201c, 0x0029231d, 0x002c261f, 0x001e1812, 0x001c180e, 0x0021180e, 0x002c2010, 0x00322616, 0x0037291a, 0x00372718, 0x00443224, 0x00443327, 0x00402f22, 0x00352315, 0x00473324, 0x0045301f, 0x003f2b18, 0x004d3823, 0x004e3822, 0x004a331a, 0x00563c20, 0x00543519, 0x005f3d1f, 0x005c3a1a, 0x005d3817, 0x0058300f, 0x005d3614, 0x005e3715, 0x00532c0c, 0x005c3517, 0x004a2408, 0x00401a00, 0x00532e13, 0x005d361c, 0x00593318, 0x004c280e, 0x00432107, 0x003c1c02, 0x003f2209, 0x00371c09, 0x0032190a, 0x002c1708, 0x002c170a, 0x002c180b, 0x002b1809, 0x002b1808, 0x002d190b, 0x00321e0f, 0x00311c0d, 0x002d180a, 0x00301a0d, 0x002e190c, 0x00281608, 0x00251406, 0x002d180b, 0x002d180b, 0x002e180c, 0x002e180c, 0x002d180c, 0x002c180c, 0x002c190c, 0x00291607, 0x00281708, 0x002e1d0d, 0x002f1a0b, 0x00321c0a, 0x00321c0a, 0x00331c0c, 0x00341d0d, 0x0030190a, 0x002f190a, 0x002d190a, 0x00281808, 0x00281809, 0x0028180b, 0x0028160c, 0x00281308, 0x0030170c, 0x00341b0d, 0x00361d0e, 0x00392010, 0x00432617, 0x00391c0c, 0x003a1c0c, 0x00361807, 0x003b1f0b, 0x00452812, 0x004a2a13, 0x004b2b13, 0x00472712, 0x00381c08, 0x002c1404, 0x00241306, 0x00201207, 0x00191007, 0x00140f06, 0x00121006, 0x00101008, 0x000c0f04, 0x000c1006, 0x000c0e08, 0x000c0e08, 0x000b0d07, 0x000a0e07, 0x00051008, 0x00070d08, 0x00090c08, 0x00080c08, 0x00050f06, 0x00060e06, 0x00080b04, 0x000e0e09, 0x00161814, 0x00101614, 0x000c1414, 0x000c1616, 0x000b1517, 0x00091617, 0x00091615, 0x00091714, 0x00091712, 0x00091513, 0x000a1513, 0x00081412, 0x00081412, 0x00081410, 0x00081410, 0x00081410, 0x0007130f, 0x0004120f, 0x0005100d, 0x0005100c, 0x0005100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00060e09, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071411, 0x00071411, 0x00071210, 0x00071210, 0x00081311, 0x00081311, 0x00081110, 0x0007100f, 0x0007100f, 0x0007110e, 0x0007110d, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0005100a, 0x00040e09, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040d09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00041008, 0x00031008, 0x00041008, 0x00041009, 0x00050f0c, 0x0007110d, 0x0008120f, 0x0008120f, 0x0008120f, 0x0008120f, 0x00081310, 0x0007140f, 0x0008150f, 0x000c1510, 0x00202622, 0x00484c48, 0x0040413d, 0x0032302f, 0x001e1d1e, 0x0019181b, 0x0027282c, 0x00292e30, 0x002a2f33, 0x00293034, 0x002a3537, 0x00283034, 0x00262b2d, 0x00242627, 0x00252422, 0x0024201e, 0x00201c18, 0x00231c17, 0x002b241c, 0x002b241b, 0x00231a10, 0x00271c0f, 0x002b1c0e, 0x002c1f0f, 0x00312415, 0x00312316, 0x00302014, 0x003f2f22, 0x00433125, 0x003e2c20, 0x003a2618, 0x003d2a1b, 0x003f2c1b, 0x003f2c1a, 0x004d3824, 0x004c3521, 0x00462e17, 0x00543921, 0x0054351c, 0x00614024, 0x005c381a, 0x00593314, 0x00593214, 0x00583010, 0x00572e0f, 0x005a3013, 0x005b3216, 0x00482107, 0x00441e06, 0x0048240d, 0x004f2b14, 0x004f2a14, 0x0044230c, 0x00391c01, 0x00371b04, 0x00371c0c, 0x00321a0c, 0x002f1a0c, 0x002c180b, 0x002d180b, 0x002c170a, 0x002c170a, 0x002e190b, 0x00331d0f, 0x00331d0f, 0x00301a0b, 0x0030180a, 0x002d180a, 0x002b1607, 0x002a1304, 0x0030180a, 0x00321b0d, 0x0030180a, 0x002e180c, 0x0030180c, 0x002e180c, 0x002f1a0b, 0x002c190a, 0x002f1b0b, 0x00321a0a, 0x00341809, 0x00361809, 0x00351c0a, 0x00341c09, 0x00331c0a, 0x00321c0b, 0x00321c0c, 0x00301909, 0x002d1808, 0x002e1a0b, 0x002e180b, 0x0030180c, 0x00361a0e, 0x003c1d0f, 0x0043200f, 0x00472510, 0x004a2810, 0x0048260f, 0x0043210a, 0x0043200c, 0x003c1c07, 0x0042230e, 0x00452811, 0x00482811, 0x0044210c, 0x003e1e09, 0x00381b08, 0x002e1807, 0x00271607, 0x00211407, 0x001c1207, 0x00181108, 0x00140f08, 0x00141008, 0x00141109, 0x00101007, 0x0013120b, 0x00111009, 0x00101009, 0x000c0d08, 0x000e100a, 0x000c0d08, 0x000b0d07, 0x00080c05, 0x00080c04, 0x00080c03, 0x00080b02, 0x000c1007, 0x00141814, 0x000f1514, 0x000b1514, 0x000c1714, 0x000c1614, 0x00091615, 0x00091615, 0x00081513, 0x00091513, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x000a1410, 0x000a1410, 0x0008120f, 0x0008120f, 0x00071210, 0x0006110d, 0x0004100c, 0x0004100b, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00040e07, 0x00030c06, 0x00030c06, 0x00030c06, 0x00040c09, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071411, 0x00071411, 0x00071210, 0x00071210, 0x00071210, 0x00071210, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007110e, 0x0008120e, 0x00050f0b, 0x00030d08, 0x0005100a, 0x0005100a, 0x00040e09, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040d09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00041008, 0x00031008, 0x00041008, 0x00041009, 0x00050f0c, 0x0007110d, 0x0008120f, 0x0008120f, 0x0008120f, 0x0008120f, 0x00081310, 0x0008140f, 0x0009140f, 0x000f1813, 0x003c403d, 0x003c403c, 0x0021231f, 0x00181817, 0x00202020, 0x002c2b2e, 0x00292b2e, 0x002c2f31, 0x002a2f33, 0x00283033, 0x002b3537, 0x002c3437, 0x00282d2f, 0x00252728, 0x00262424, 0x0023201e, 0x00241f1d, 0x00271f1c, 0x00282018, 0x00342a20, 0x002c2014, 0x002b1c0e, 0x002e1d0e, 0x002f1e0f, 0x002f2011, 0x002f2013, 0x002c1d10, 0x002e2013, 0x003a2a1d, 0x00433226, 0x00413022, 0x00352416, 0x00362415, 0x003b2a19, 0x00402e1d, 0x00483423, 0x0047321f, 0x0049301c, 0x00573c24, 0x00513318, 0x00603e22, 0x00543014, 0x00583216, 0x00573114, 0x00542d0f, 0x00562e10, 0x00573014, 0x00502c12, 0x00432009, 0x00401e09, 0x0044220c, 0x00482711, 0x00482810, 0x003c1f06, 0x00371c07, 0x00341b0b, 0x00311b0c, 0x002f1b0d, 0x002c190c, 0x002a1408, 0x002d180b, 0x002d180b, 0x002d180a, 0x00331c0e, 0x00341c0f, 0x00321b0c, 0x002e1809, 0x002d1809, 0x002c1708, 0x002c1406, 0x0030180a, 0x00321b0d, 0x0030190b, 0x002f190c, 0x0030180c, 0x002e180c, 0x002f190b, 0x00331e0d, 0x00361e0d, 0x00381d0c, 0x003a1c0c, 0x003e1e0e, 0x003a1c08, 0x003b1f08, 0x003b1f0a, 0x00391e09, 0x00381e0a, 0x00361c08, 0x00341907, 0x00341c0a, 0x00371c0a, 0x003f2010, 0x00442310, 0x0047230f, 0x004c260e, 0x00502a0f, 0x00542e10, 0x00542e10, 0x00502a0c, 0x004c280c, 0x00462108, 0x004c2b14, 0x0044240d, 0x0044240c, 0x003f1f07, 0x003a1a05, 0x00381c08, 0x00301a07, 0x00281608, 0x00241408, 0x00201308, 0x001b1008, 0x00181008, 0x00171009, 0x00161109, 0x00120f07, 0x00100c04, 0x00131008, 0x0015130b, 0x00121008, 0x0014110a, 0x00111009, 0x00111009, 0x00101008, 0x000f0f06, 0x000f0f06, 0x000e0e04, 0x00111108, 0x00151811, 0x000f1511, 0x000a1410, 0x000a1511, 0x000b1412, 0x000a1514, 0x000a1414, 0x00081412, 0x00081412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x000a1410, 0x00091310, 0x0008120f, 0x0008120f, 0x00071210, 0x0006110e, 0x0005100c, 0x0004100b, 0x00060f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00040e07, 0x00030c06, 0x00030c06, 0x00030c06, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00071210, 0x00071210, 0x00071210, 0x00071210, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007110e, 0x0007110d, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00041008, 0x00041008, 0x00051109, 0x00041008, 0x00040e0b, 0x0006100c, 0x0007110d, 0x00091310, 0x0008120f, 0x0007110d, 0x0008120e, 0x0008130e, 0x0008140e, 0x00202923, 0x003b403b, 0x002b2e29, 0x001f1f1b, 0x00242221, 0x002c2c2d, 0x0029292c, 0x0026272c, 0x0025282c, 0x00272c30, 0x00262e31, 0x002c3437, 0x002d3438, 0x002e3334, 0x002c2e30, 0x00282828, 0x00201d1c, 0x001f1a18, 0x00211815, 0x00251c14, 0x002c2116, 0x00362819, 0x00342212, 0x00301c0c, 0x00301d0d, 0x002e1f10, 0x002c1f11, 0x002c1d10, 0x002c1e11, 0x00312416, 0x00372a1c, 0x003c2d20, 0x003a2b1e, 0x00362819, 0x00382a1b, 0x003c2c1d, 0x003f2e20, 0x00402e1d, 0x00432e1b, 0x004c331e, 0x0052371f, 0x0054351c, 0x0058381d, 0x00512e15, 0x00543216, 0x00583417, 0x00542e0f, 0x00502c0f, 0x004b280e, 0x0044240c, 0x0040200a, 0x0040200c, 0x0040200c, 0x0043240d, 0x0041240e, 0x00391e0a, 0x00341c0b, 0x0030190b, 0x002e1a0c, 0x002e1a0e, 0x002c170a, 0x002d180b, 0x002c170a, 0x002d180b, 0x002f180c, 0x0030190c, 0x00361f10, 0x002d1608, 0x002e180a, 0x00301b0c, 0x002d1608, 0x0030180b, 0x00321b0d, 0x0030190b, 0x0030180c, 0x0030180c, 0x0030180c, 0x00311a0a, 0x00361f0d, 0x0039200d, 0x003c1f0a, 0x00422110, 0x00401d0b, 0x00401d06, 0x0044220a, 0x00402008, 0x00402009, 0x0040220a, 0x0040200b, 0x003c1e08, 0x003e200b, 0x0044240e, 0x00492810, 0x004c2810, 0x00572f14, 0x005c3114, 0x005d3310, 0x00603611, 0x005f340f, 0x005a300b, 0x00512907, 0x00492405, 0x00462309, 0x0044210a, 0x0044220b, 0x00401d06, 0x0040200c, 0x00351804, 0x00321807, 0x002c1608, 0x00281409, 0x0024140c, 0x0024150d, 0x001e140c, 0x001a110b, 0x00170f08, 0x0017100a, 0x001a140c, 0x0018130c, 0x0018120c, 0x0019140c, 0x001a150c, 0x00181209, 0x00161008, 0x00151108, 0x00151109, 0x0014110a, 0x0014120c, 0x0017140f, 0x00151610, 0x000d140d, 0x000b150e, 0x000a140e, 0x000a1410, 0x000a1412, 0x000a1412, 0x00091311, 0x00091311, 0x00091211, 0x00091211, 0x00081110, 0x00081110, 0x00091310, 0x000a1410, 0x0007110d, 0x0007110d, 0x0006110f, 0x0005100d, 0x0004100c, 0x0004100b, 0x00060f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00040e07, 0x00030c06, 0x00030c06, 0x00030c06, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00071210, 0x00071210, 0x00071210, 0x0007130f, 0x0007110d, 0x0007110d, 0x0007100e, 0x0007110e, 0x0007110d, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00050e08, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00041008, 0x00041008, 0x00051109, 0x00041008, 0x00040e0a, 0x0006100c, 0x0007110d, 0x00091310, 0x0008120f, 0x0007110d, 0x0008120e, 0x0008130e, 0x000b1610, 0x002b342e, 0x00313731, 0x00242621, 0x0022231f, 0x002b2b29, 0x00242526, 0x00242528, 0x0026282d, 0x0022252a, 0x00242a2c, 0x00262e2f, 0x00262e2f, 0x002a3034, 0x002f3334, 0x00323436, 0x00313233, 0x002a2827, 0x0024201c, 0x00211915, 0x00251d14, 0x002b1c11, 0x003a281a, 0x003b2715, 0x00321d0b, 0x00311c0b, 0x002c1c0d, 0x002b1c0f, 0x002b1c0f, 0x002b1e10, 0x002c2113, 0x00332819, 0x0033281a, 0x00372b1c, 0x003c2f21, 0x00382c1e, 0x00392d1f, 0x003d2f22, 0x00403021, 0x003f2d1e, 0x00432f1d, 0x00452f1b, 0x004b301b, 0x0052351e, 0x0053341d, 0x004d2f16, 0x004f2f13, 0x00523013, 0x004a2a0c, 0x004a2b12, 0x00462810, 0x0042250e, 0x003e200c, 0x003c1e09, 0x003d200a, 0x0040230e, 0x003f2410, 0x00381f0e, 0x00311a0c, 0x002f1b0c, 0x002f1b0f, 0x002f190c, 0x002c1709, 0x002b1507, 0x002c1709, 0x00311c0e, 0x00301a0b, 0x00341e10, 0x00301a0b, 0x00301b0c, 0x00301b0c, 0x002d1608, 0x0030190c, 0x00331c0e, 0x00311a0c, 0x00311a0d, 0x0030180c, 0x0030180c, 0x00321908, 0x00381e0c, 0x00402510, 0x0043240e, 0x0044230d, 0x0046220d, 0x00452007, 0x004d280c, 0x004c280c, 0x004c280d, 0x004b280d, 0x0048260d, 0x0046240b, 0x0048260c, 0x004d290f, 0x00542f14, 0x005c3517, 0x00633817, 0x00633512, 0x00653811, 0x00693c12, 0x0064370e, 0x00603309, 0x00582e06, 0x004e2804, 0x00482205, 0x0048240e, 0x0045240d, 0x0043220c, 0x00452510, 0x00381c09, 0x00341b08, 0x002d1507, 0x00291408, 0x0027160c, 0x0025160e, 0x0021160f, 0x001d140e, 0x001b130c, 0x001a130c, 0x0019120c, 0x001a130c, 0x0019120a, 0x0019120a, 0x00181008, 0x00160e06, 0x00181008, 0x00181008, 0x00171208, 0x00151208, 0x0015120a, 0x0017140d, 0x0015150f, 0x000e140c, 0x000b140c, 0x0009140d, 0x0008140f, 0x00091311, 0x00091311, 0x00091211, 0x00091211, 0x00091310, 0x00091310, 0x00081210, 0x00081210, 0x00091310, 0x000a1410, 0x0007110d, 0x0007110d, 0x0006100d, 0x00050f0c, 0x00050f0c, 0x0005100b, 0x00060f09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e08, 0x00040f08, 0x00051009, 0x00051008, 0x00040e07, 0x00030c06, 0x00030c06, 0x00030c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00081110, 0x0008120f, 0x0008120f, 0x0008120f, 0x0007110d, 0x0007110d, 0x0007100e, 0x0007110e, 0x0007110d, 0x0006100c, 0x0005100a, 0x0005100a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00040d06, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00050c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00030e07, 0x00020e07, 0x00020e07, 0x00020e07, 0x0005100a, 0x0005100a, 0x00040e09, 0x0006100b, 0x0007110d, 0x0007110d, 0x0008120e, 0x0008120e, 0x00101a14, 0x002b342c, 0x00282d27, 0x00242620, 0x0023241f, 0x00282827, 0x002a2c2c, 0x00282a2d, 0x00272a2c, 0x0024292c, 0x00202728, 0x00202728, 0x001d2425, 0x00212628, 0x00282c30, 0x002c2f32, 0x00303032, 0x0031302d, 0x00302c28, 0x002e2721, 0x002c2319, 0x002e1f14, 0x00341f10, 0x003b2414, 0x003c2513, 0x0035210f, 0x002f1d0f, 0x002d1d0e, 0x002c1e0e, 0x002f2211, 0x00322514, 0x00342817, 0x00352818, 0x00352818, 0x0038291a, 0x003b2c1d, 0x003b2c1e, 0x003c2c1f, 0x003c2c20, 0x003b2a1c, 0x003d2b1b, 0x0041301c, 0x0044311f, 0x0047311f, 0x004c3422, 0x0049301d, 0x00482e19, 0x004b2c18, 0x0050311b, 0x00482c13, 0x00442710, 0x00432510, 0x003e230d, 0x003b1f09, 0x00381c08, 0x00381c08, 0x0039200d, 0x00381f0f, 0x00311a0c, 0x00301a0d, 0x00301a0d, 0x00301b0d, 0x002e1b0c, 0x002f1c0c, 0x002c1809, 0x002c190a, 0x002e1c0c, 0x002d1c0c, 0x002f1c0d, 0x00311c0d, 0x00301a0c, 0x0030190b, 0x00331b0d, 0x00341c0e, 0x00331b0d, 0x00331a0e, 0x0033190d, 0x0034180c, 0x00351906, 0x0040200a, 0x0046270e, 0x0047280c, 0x0049280b, 0x004f2a0b, 0x004d2705, 0x00552d0c, 0x00542b09, 0x00562c0b, 0x00592f0f, 0x00582d0e, 0x00552b0c, 0x005a2e10, 0x005d3311, 0x00603713, 0x00663b14, 0x006c3d14, 0x006e3d14, 0x006f3d10, 0x006e3d10, 0x006e3c0f, 0x0068380b, 0x0060330b, 0x00582c07, 0x00542a0b, 0x004d250c, 0x0046240a, 0x0046240c, 0x0045240e, 0x00401f0c, 0x003a1c09, 0x00331808, 0x002c1708, 0x0028180a, 0x0026180d, 0x0024150c, 0x0020140b, 0x0020140c, 0x001c1209, 0x001f140c, 0x0020140c, 0x001f140c, 0x001f140c, 0x001e150c, 0x001e150c, 0x001e150b, 0x001c1309, 0x001c1309, 0x001c140a, 0x001c140b, 0x001a150c, 0x0018140d, 0x0014110e, 0x000d120d, 0x0009140c, 0x0006120c, 0x00081110, 0x00091211, 0x00091211, 0x00091310, 0x0009130d, 0x0008120c, 0x0009140d, 0x0009140d, 0x0007110c, 0x0008100c, 0x0007100b, 0x0007100b, 0x0007100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0a, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00081110, 0x0008120f, 0x0008120f, 0x0008120d, 0x0007110c, 0x0007110c, 0x0007110e, 0x0007110e, 0x0007110d, 0x0005100b, 0x0005100a, 0x0005100a, 0x00040e09, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00050c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00030e07, 0x00020e07, 0x00020e07, 0x00020e07, 0x0005100a, 0x0005100a, 0x00040e09, 0x0006100b, 0x0006100c, 0x0007110d, 0x0008120f, 0x0008120e, 0x000f1812, 0x00212822, 0x002a2e27, 0x002d3029, 0x002d2e28, 0x002c2f2c, 0x002c2f30, 0x002a2d30, 0x00282d31, 0x00292e31, 0x002b3234, 0x00282e30, 0x00242b2c, 0x00202426, 0x001f2126, 0x00232628, 0x00282a2c, 0x002b2a27, 0x002a2520, 0x002c241f, 0x0030271d, 0x0034251b, 0x00372316, 0x00372111, 0x0037200e, 0x00392210, 0x00342011, 0x00342111, 0x00342513, 0x00382815, 0x00382816, 0x003a2917, 0x003a2917, 0x003a2917, 0x003a2817, 0x003a2717, 0x003d2b1b, 0x003e2c1c, 0x003e2b1d, 0x003c281b, 0x003c2818, 0x003d2b18, 0x00402d1a, 0x00402f1b, 0x00402f1a, 0x00402f19, 0x004c3622, 0x00472a17, 0x00492c18, 0x00492c17, 0x00462b14, 0x00412611, 0x003d230d, 0x003a200a, 0x003a1f0b, 0x00381c09, 0x00351b0a, 0x00361d0e, 0x00321b0f, 0x00301a0d, 0x00321b0f, 0x00331c0f, 0x00331d0c, 0x00301b0a, 0x002e1808, 0x002d1808, 0x002f1c0a, 0x002f1c0a, 0x00301c0c, 0x00311b0b, 0x00321a0a, 0x0034190a, 0x00361b0c, 0x00371c0d, 0x00341a0c, 0x00351a0c, 0x00371b0d, 0x00391b0c, 0x003c1c08, 0x0047240a, 0x004c290c, 0x004e2909, 0x00552f0d, 0x005b320f, 0x00582c08, 0x005f320d, 0x005f300c, 0x0061320e, 0x00643510, 0x0062340e, 0x0061320c, 0x0065350f, 0x00693813, 0x006a3c12, 0x006d3d10, 0x00703c0f, 0x00733e0d, 0x0075400c, 0x0076400e, 0x0075400e, 0x00703c0a, 0x0069380c, 0x0061320b, 0x005b2c0c, 0x00512809, 0x004a2608, 0x0049260a, 0x0049250c, 0x0046220b, 0x00401f09, 0x00391c07, 0x00311a07, 0x002b1908, 0x00281809, 0x00251508, 0x00211307, 0x001f1205, 0x00201508, 0x0024170c, 0x0024170c, 0x00201509, 0x00201509, 0x0020140a, 0x0020140a, 0x001f150a, 0x0021170c, 0x0020160b, 0x0020150a, 0x001e150a, 0x001c1509, 0x001a150f, 0x00171410, 0x0010140d, 0x0008140c, 0x0006120c, 0x00081110, 0x00081110, 0x00091211, 0x00091310, 0x0008120c, 0x0008120c, 0x0008120b, 0x0008120b, 0x0009100c, 0x000a100c, 0x00090f0b, 0x00090f0b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00040c07, 0x00040c06, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00081110, 0x0008120f, 0x0008120f, 0x0008120d, 0x0008100c, 0x0008100c, 0x0008110c, 0x0007110d, 0x0006100c, 0x00050f0b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c05, 0x00040c04, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00050c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00030e07, 0x00020e07, 0x00020e07, 0x00020e07, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x00040e0b, 0x0007110d, 0x000a140f, 0x0009130d, 0x000f1710, 0x001f2720, 0x002b2f28, 0x0031332d, 0x0031302c, 0x002f302e, 0x00303434, 0x00303335, 0x002d3236, 0x002b3034, 0x00282f34, 0x00272b30, 0x00272c30, 0x00282c2e, 0x0025282b, 0x0026292c, 0x00242627, 0x00252320, 0x0024201a, 0x00271f18, 0x002c2118, 0x00392c20, 0x00413022, 0x00463020, 0x00432a18, 0x003b2210, 0x00371d0c, 0x00382310, 0x003d2a17, 0x0044301c, 0x0046301d, 0x00472f1d, 0x00452e1c, 0x00432b18, 0x00422b18, 0x00442c1a, 0x00442c1a, 0x00442c1c, 0x00422b1c, 0x0040281a, 0x00402917, 0x00402b16, 0x00402d17, 0x00402e18, 0x00402d16, 0x0043301a, 0x00442e19, 0x004a3320, 0x00442a18, 0x00442b17, 0x00442a16, 0x00402712, 0x003b240f, 0x0039220c, 0x0038200b, 0x003a1e0d, 0x00331809, 0x0031180b, 0x00311a0d, 0x00321a0e, 0x00341b10, 0x00351c0f, 0x00341c0c, 0x00331a09, 0x00321a08, 0x00311a08, 0x00301a08, 0x002f1908, 0x00301a08, 0x00321b09, 0x00341808, 0x00371b0b, 0x00371a0b, 0x00371a0b, 0x00361909, 0x00371a0b, 0x00391b0b, 0x003c1c0c, 0x00401f09, 0x004f2a10, 0x00573010, 0x00552c08, 0x005c310c, 0x0061340c, 0x00603009, 0x0067360f, 0x0068340d, 0x006c3810, 0x006e3b12, 0x006b3810, 0x006b370d, 0x006c380e, 0x006d390d, 0x00713e0f, 0x0074400e, 0x0079420e, 0x007e440f, 0x007e440e, 0x007e440f, 0x007d4410, 0x007a400d, 0x00713d0d, 0x0067350c, 0x0060300c, 0x00592e0c, 0x00502909, 0x004e2909, 0x004c2609, 0x00462108, 0x0044220b, 0x0041230e, 0x00371c0a, 0x002c1808, 0x00281808, 0x00251305, 0x00231205, 0x00231407, 0x00231608, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x0020160b, 0x0020160b, 0x001f1409, 0x001f1409, 0x00201409, 0x0020140a, 0x001f1409, 0x001d1409, 0x001c140e, 0x00181411, 0x00141610, 0x0009140c, 0x0005110c, 0x00091010, 0x00081110, 0x0008120f, 0x0009110f, 0x0008120c, 0x0008110b, 0x0007110a, 0x0008110a, 0x00090f0b, 0x00090f0b, 0x00080e0a, 0x00080e0a, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070c0b, 0x00070c0b, 0x00070c0b, 0x00070c0b, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00091211, 0x0008120f, 0x0008120f, 0x0007110c, 0x0008100b, 0x0008100c, 0x0007100c, 0x0006100c, 0x00050f0c, 0x00050f0b, 0x0005100a, 0x00050f0a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c05, 0x00040c04, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00050c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00030e07, 0x00020e07, 0x00020e07, 0x00020e07, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x00040e0b, 0x0006100c, 0x0008120d, 0x0009140d, 0x00131c14, 0x001f261f, 0x00282b24, 0x0031312c, 0x00353530, 0x00313130, 0x002d3132, 0x00303335, 0x002e3337, 0x002d3238, 0x002c3338, 0x002e3338, 0x00292e33, 0x00292f30, 0x00292c2f, 0x00252829, 0x00242424, 0x00252220, 0x002a241f, 0x002c241e, 0x002b2018, 0x0034281c, 0x003d2d20, 0x00463020, 0x004c3120, 0x00492d1b, 0x00432917, 0x00442e1a, 0x0049331c, 0x004c341f, 0x00503420, 0x00523521, 0x00513420, 0x004d311d, 0x004b301c, 0x004b311c, 0x004b311c, 0x004c311f, 0x00482f1d, 0x00452c1b, 0x00442c18, 0x00452d17, 0x00442e16, 0x00432d15, 0x00412b14, 0x00422c16, 0x00402814, 0x00442b18, 0x00452d1a, 0x00422a18, 0x003f2915, 0x003d2713, 0x003a250f, 0x0038230c, 0x0037200c, 0x00371c0c, 0x00351b0c, 0x0031180b, 0x0030180c, 0x0031180c, 0x0034180c, 0x0035180c, 0x00371b0c, 0x00371c0b, 0x00371c0a, 0x00361c0a, 0x00341c09, 0x00331c08, 0x00341c08, 0x00381c0a, 0x00351806, 0x00381a09, 0x00371908, 0x00381a09, 0x003a1b0a, 0x003b1c0b, 0x00422210, 0x0043210e, 0x0048240d, 0x00563014, 0x005c3210, 0x0060340d, 0x00683811, 0x006c3c12, 0x006b370d, 0x00733c12, 0x00703a0f, 0x00733b10, 0x00743d11, 0x00723b0e, 0x00703a0c, 0x00773e10, 0x0077400f, 0x007b4411, 0x00804812, 0x00844a11, 0x00874a11, 0x00884a11, 0x00884912, 0x00854811, 0x0080430c, 0x00753f0e, 0x006b370a, 0x0063320b, 0x005d310e, 0x00562d0c, 0x00532c0c, 0x0050280b, 0x004f270d, 0x004d2810, 0x0044220c, 0x00391c0b, 0x00301807, 0x002a1607, 0x00281509, 0x0028170b, 0x00241406, 0x00201305, 0x001f1408, 0x001f1408, 0x00201609, 0x00201508, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201408, 0x001f1408, 0x001d140c, 0x00181411, 0x0014160f, 0x000a140c, 0x0006110c, 0x00091010, 0x00081110, 0x0008120f, 0x0008100d, 0x0008110b, 0x0007110a, 0x0007110a, 0x0007110a, 0x0006100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00080c0b, 0x00080c0b, 0x00080c0b, 0x00080c0b, 0x00070b07, 0x00060b06, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x00091310, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0a, 0x00040e09, 0x00050f0a, 0x00040e09, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d0a, 0x00070e0d, 0x00040c0a, 0x00040c0a, 0x00040c08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00070f08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060d08, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e0b, 0x00060d0b, 0x0008100c, 0x0008100d, 0x000b130d, 0x00182018, 0x001d231c, 0x00252923, 0x0033342e, 0x00343530, 0x00323432, 0x00303434, 0x002f3335, 0x002c3034, 0x002c3036, 0x002e3338, 0x0032373c, 0x0033363b, 0x00323538, 0x00303334, 0x002a2c2d, 0x00262626, 0x0024211f, 0x0028211e, 0x002e241f, 0x002c2118, 0x00322619, 0x003a2c1c, 0x00442f1e, 0x004a301d, 0x004e3320, 0x004f3520, 0x004e331e, 0x0050351d, 0x0053341c, 0x0054341c, 0x00593820, 0x00583821, 0x00593822, 0x00573720, 0x00573821, 0x00563820, 0x0054341e, 0x0050331c, 0x0050321b, 0x0050331c, 0x004c2f18, 0x00442a13, 0x00442b12, 0x00452c14, 0x00442913, 0x00412813, 0x003e2610, 0x003f2613, 0x00422a17, 0x003f2713, 0x003d2610, 0x003c2510, 0x003a2310, 0x0038210d, 0x00371f0d, 0x00341c0c, 0x00331c0c, 0x00301909, 0x00351c0c, 0x00371c0c, 0x003a200d, 0x003c220e, 0x003d220e, 0x003a1e0a, 0x003d220e, 0x00381c08, 0x003a1e0a, 0x00402410, 0x003d200c, 0x003a1a08, 0x003b1b08, 0x003c1c09, 0x003e1e0b, 0x00401e0b, 0x0044230f, 0x004b2711, 0x004f2a10, 0x00562f0f, 0x005d330f, 0x0064360f, 0x006b380f, 0x00713c10, 0x00753f12, 0x00763e0f, 0x00763e0d, 0x00753d0c, 0x00783f0f, 0x007b4110, 0x00783f0c, 0x007c4210, 0x007f4512, 0x00824814, 0x00874912, 0x00884910, 0x00874910, 0x008b4c13, 0x008b4c14, 0x008b4c14, 0x008a4a14, 0x00874810, 0x007c410c, 0x00703c08, 0x0067350a, 0x0060300c, 0x005c2c0c, 0x00582c0d, 0x0054280c, 0x00562d12, 0x004c240b, 0x0047220c, 0x003a1a07, 0x00321808, 0x002d1608, 0x002a160b, 0x00281609, 0x00271609, 0x00221407, 0x0022170a, 0x0023180b, 0x00221509, 0x00221509, 0x00221509, 0x00211408, 0x00241509, 0x00201207, 0x00211308, 0x00231409, 0x0023150a, 0x0023170a, 0x0020180c, 0x001a170f, 0x0015160f, 0x000f110c, 0x0009100b, 0x00091010, 0x0007130f, 0x0007110d, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x00040e09, 0x0005100a, 0x0007100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x000a1410, 0x0007110d, 0x0007110d, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x00050f0c, 0x0005100b, 0x00040f0a, 0x00040e09, 0x0006100b, 0x00040e09, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00080d08, 0x00080d0a, 0x00070e0c, 0x00040c0a, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00080f0b, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e0b, 0x00070e0c, 0x00070e0c, 0x0008100c, 0x000b130d, 0x00182018, 0x001f241d, 0x002b2c26, 0x0032332d, 0x0033342f, 0x00303230, 0x002f3233, 0x002c2f32, 0x00282c30, 0x00282d31, 0x002c3034, 0x002e3337, 0x00303338, 0x00303335, 0x002c3030, 0x002c2d2d, 0x002b2b29, 0x00282420, 0x0027201d, 0x002c211e, 0x002f241c, 0x0034281a, 0x00382819, 0x00422d1c, 0x00472e1b, 0x004b301e, 0x004e3420, 0x00523620, 0x00563820, 0x0059381d, 0x005e3b1f, 0x00633e22, 0x00664027, 0x00674228, 0x00603c22, 0x005f3b20, 0x005e3a20, 0x005d3a20, 0x005a381d, 0x0057351a, 0x00563419, 0x00533018, 0x004c2e14, 0x00492d12, 0x00482c12, 0x00492c15, 0x00472c14, 0x00442813, 0x00432812, 0x00412511, 0x003e240e, 0x003f250f, 0x003f2510, 0x003e2410, 0x003c220e, 0x003b210d, 0x003a200d, 0x00381e0c, 0x00351b0a, 0x00371c0a, 0x003b1f0b, 0x0040240d, 0x0041240d, 0x0040240c, 0x003e1f08, 0x0042230c, 0x0040200a, 0x0045240e, 0x00472610, 0x0042210c, 0x00401d08, 0x00401d08, 0x0044220c, 0x0046240e, 0x0048240e, 0x004c2710, 0x00512b10, 0x00562e0f, 0x00603511, 0x00683a10, 0x006c3a0e, 0x00713c10, 0x00784112, 0x007c4313, 0x00804412, 0x00804412, 0x007f440f, 0x00824712, 0x00844814, 0x00804510, 0x00834811, 0x00844a13, 0x00874b13, 0x008c4c14, 0x008b4c11, 0x008b4c11, 0x008e4e14, 0x008e4f16, 0x008e4f16, 0x008c4c14, 0x008a4b12, 0x0081450e, 0x0074400a, 0x006b380b, 0x0061310b, 0x005f2e0d, 0x005d3010, 0x005c3013, 0x00582c11, 0x0052280e, 0x0049230b, 0x00401f0b, 0x003a1d0e, 0x002e1508, 0x002c180c, 0x002b180c, 0x0027170a, 0x00221407, 0x00201408, 0x00201609, 0x00201609, 0x0022170a, 0x0023160c, 0x0022150b, 0x00201308, 0x001d1005, 0x001c1005, 0x00201208, 0x00201308, 0x001f1308, 0x001d150a, 0x001d1810, 0x00191710, 0x0011100c, 0x000c100c, 0x00091012, 0x0007130f, 0x0006110d, 0x0005100a, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x00050f0a, 0x00010c06, 0x00060f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x000a1410, 0x0008110e, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x0006100b, 0x00040e09, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00080d08, 0x00080d0a, 0x00070e0c, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00071007, 0x00071007, 0x00051008, 0x00051008, 0x00040f08, 0x00050f08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00050c06, 0x00040b04, 0x00040b04, 0x00030c04, 0x00030c04, 0x00040d07, 0x00040d07, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040e09, 0x0005100a, 0x00050f0c, 0x00070e0c, 0x00070e0c, 0x0008100c, 0x000b110c, 0x0019201a, 0x001f241e, 0x00242622, 0x002a2b27, 0x0030302c, 0x00313431, 0x00303434, 0x002d3034, 0x00292e32, 0x002d3236, 0x002d3236, 0x002b2e32, 0x00292c30, 0x002c2e30, 0x002c2e2f, 0x00282828, 0x002a2827, 0x002b2824, 0x002b2421, 0x002a201c, 0x0030241c, 0x003a2c20, 0x003c2c1c, 0x00412c1b, 0x0048301e, 0x004b3020, 0x004d3320, 0x00523420, 0x005d3c27, 0x00603c23, 0x00664023, 0x006a4224, 0x006c4426, 0x006d4528, 0x006b4425, 0x00684224, 0x00653f20, 0x00633c1e, 0x00603a19, 0x005d3717, 0x00593314, 0x00593214, 0x00563313, 0x00513010, 0x004d2c0f, 0x004c2b0f, 0x004c2b0f, 0x004a2b0f, 0x0048290e, 0x0045250e, 0x0042220a, 0x0046270f, 0x0040230b, 0x0041220c, 0x0042230c, 0x0042230d, 0x0041220d, 0x003f200c, 0x0040200c, 0x0044240e, 0x00482810, 0x0049270d, 0x0048270b, 0x004a280c, 0x0049260a, 0x00482409, 0x004b260b, 0x004f2a0f, 0x004e290d, 0x00492408, 0x00482106, 0x004a2409, 0x004d250b, 0x004c240b, 0x0050280d, 0x00582d12, 0x005e3113, 0x00633512, 0x00693910, 0x006d3b0f, 0x00744010, 0x007b4411, 0x007e4411, 0x00824710, 0x00854911, 0x0086480f, 0x00884a10, 0x00894c13, 0x008a4c13, 0x008b4d12, 0x008b4d13, 0x008a4d12, 0x008b4d12, 0x008d4e11, 0x008d4e11, 0x008e4f12, 0x00905116, 0x00905016, 0x008f5015, 0x008f4f14, 0x008d4f14, 0x00874c12, 0x007b440e, 0x006e3c0d, 0x0062320a, 0x0060300d, 0x00603210, 0x00603516, 0x00572c0f, 0x00542a0e, 0x00492309, 0x00482710, 0x00351806, 0x00341c0d, 0x002c180c, 0x0029180c, 0x0028180b, 0x00231508, 0x00201408, 0x001d1205, 0x001e1308, 0x001f1407, 0x001f1408, 0x001f1408, 0x001f1308, 0x001d1106, 0x001c1107, 0x001d1208, 0x001e1209, 0x001b1108, 0x00181005, 0x00171209, 0x0018160e, 0x0014130c, 0x000c100c, 0x00081010, 0x0006110d, 0x0006100c, 0x00070f0a, 0x0006100b, 0x0008120c, 0x0006100b, 0x0005100a, 0x0007110c, 0x0007110c, 0x00050e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x000a1410, 0x0008110e, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x0006100b, 0x00040e09, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00080d08, 0x00080d08, 0x00070f0a, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040e09, 0x0005100a, 0x00050f0c, 0x00050f0c, 0x00070e0c, 0x0008100c, 0x000a100b, 0x00171d18, 0x001a201a, 0x00212520, 0x00292a26, 0x0030302c, 0x00313433, 0x00313437, 0x00313438, 0x002f3438, 0x002c3034, 0x00282d31, 0x0026282d, 0x00222529, 0x00242627, 0x00272928, 0x00272725, 0x00272623, 0x002e2926, 0x00362e2a, 0x002e221c, 0x002d2218, 0x003a2c20, 0x00423122, 0x00442f1d, 0x00493120, 0x004d3423, 0x00503623, 0x00543623, 0x0063422c, 0x006b462d, 0x0072492b, 0x00774c2d, 0x00764a2b, 0x00714726, 0x00704724, 0x006b4420, 0x0069421f, 0x00683e1b, 0x00663c18, 0x00643c17, 0x00623815, 0x00633715, 0x00603814, 0x005b3511, 0x0058310f, 0x00563010, 0x0054300f, 0x00532e10, 0x00522d0f, 0x004d280c, 0x00482509, 0x004c280d, 0x004b280d, 0x004a260e, 0x004a260e, 0x0049260e, 0x0047240b, 0x004c2810, 0x004c2810, 0x004d2a10, 0x00502b10, 0x00502c0e, 0x00532d0d, 0x00542d0d, 0x00542c0c, 0x00522a0b, 0x00562c0c, 0x00582d0f, 0x00572c0d, 0x00512708, 0x00532708, 0x0055290b, 0x0054290b, 0x0054290b, 0x005c2e10, 0x00623414, 0x00653613, 0x006a3912, 0x00703d10, 0x00794311, 0x00804813, 0x00824a12, 0x00844a10, 0x00884c10, 0x00894c0e, 0x00894c0d, 0x008c4c0f, 0x008d5010, 0x008c4e10, 0x008d4e10, 0x008d4e10, 0x008d4e10, 0x008d4e10, 0x00905013, 0x008f5011, 0x008f5011, 0x00905214, 0x00905114, 0x008f5014, 0x008f5013, 0x008e4f12, 0x00884e10, 0x007c470d, 0x006f3c0b, 0x0068380d, 0x0062320c, 0x0060320d, 0x005c330f, 0x0059300f, 0x00562c0d, 0x0050290c, 0x00422009, 0x0040240f, 0x00341b0a, 0x002b170c, 0x00281709, 0x00251508, 0x00221406, 0x00201308, 0x001c1104, 0x001b1005, 0x001b1104, 0x001a1105, 0x00191105, 0x00181105, 0x00181004, 0x00191006, 0x001c1208, 0x001c140a, 0x001e140b, 0x001c140a, 0x00181007, 0x0016120b, 0x0013130c, 0x000d100c, 0x00080f0e, 0x0005100c, 0x0006100b, 0x00080f0a, 0x0007100b, 0x0009130d, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00050d09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0007130f, 0x00081410, 0x0008130f, 0x0007110d, 0x0006100d, 0x0006100d, 0x0006100c, 0x0006100c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c09, 0x00040c08, 0x00040d08, 0x00040e07, 0x00040d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c07, 0x00060d06, 0x00050c06, 0x00050c05, 0x00050c05, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00060d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060f09, 0x00040e0a, 0x0005100a, 0x0005100b, 0x0008100c, 0x00080f09, 0x00161b16, 0x001c211c, 0x00212520, 0x002c2e2a, 0x0030322f, 0x00303232, 0x002e3134, 0x00303237, 0x002d3036, 0x002c2f34, 0x002b3034, 0x00272a2f, 0x0024282a, 0x00242525, 0x00222421, 0x0021221f, 0x0022201c, 0x0027221e, 0x00342c28, 0x00392e27, 0x0032261b, 0x0037291a, 0x00423120, 0x004a3424, 0x004a3422, 0x004c3422, 0x00503825, 0x005a3d2c, 0x00684834, 0x006f4932, 0x00754c2d, 0x007b4f2e, 0x007d4f2d, 0x007b4c29, 0x00784823, 0x0074441f, 0x0073441d, 0x0071421c, 0x006c3e18, 0x006a3c15, 0x00683b14, 0x00683a14, 0x00653a12, 0x00633910, 0x005f360c, 0x005e360d, 0x005c340f, 0x00593110, 0x00572f0d, 0x00542d0d, 0x00522c0c, 0x00512c0c, 0x00522e0e, 0x00512d0d, 0x00512d0d, 0x00512c0e, 0x00512a0c, 0x00542e10, 0x00542e0f, 0x00512b0b, 0x00542c0c, 0x00572f0e, 0x0059300d, 0x005b3210, 0x005c3110, 0x005c310f, 0x005d300f, 0x005e3110, 0x005f3210, 0x005e300f, 0x005c2e0d, 0x005d2f0c, 0x005e2f0c, 0x005e2f0b, 0x0062340d, 0x00673810, 0x006c3c10, 0x00713e11, 0x00774011, 0x007f4513, 0x00844910, 0x00874c10, 0x008c5013, 0x008e5014, 0x008e5010, 0x008c4d0e, 0x00904f0e, 0x00925010, 0x00935010, 0x00935010, 0x00925010, 0x00925010, 0x00925010, 0x00905311, 0x00905310, 0x00905110, 0x00905212, 0x00905111, 0x00905111, 0x00905010, 0x008f5010, 0x008a4c0e, 0x0081460c, 0x00743e09, 0x006d380c, 0x006a3911, 0x00633610, 0x005d310e, 0x005c3310, 0x005a300f, 0x00552b0d, 0x004c280d, 0x0040200b, 0x00341906, 0x002c1709, 0x002a170a, 0x00261408, 0x00211205, 0x001e1205, 0x001c1106, 0x001c1206, 0x001a1106, 0x001a1208, 0x001b1409, 0x001b1409, 0x001c140a, 0x001a1208, 0x00191208, 0x001c140a, 0x001e160d, 0x001f170e, 0x001c140c, 0x001c140c, 0x0018140d, 0x0011130d, 0x00080f0e, 0x0004100c, 0x0005100c, 0x00080e0a, 0x0006100b, 0x0006100b, 0x0007100a, 0x0007100a, 0x00050e09, 0x00050e09, 0x00040c08, 0x00040c08, 0x00040d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00060d08, 0x00060c08, 0x00050c08, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c08, 0x00070d09, 0x00060d08, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006130f, 0x0006130f, 0x0006110d, 0x0006110d, 0x0006110d, 0x0006110d, 0x0006100c, 0x0006100c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x0004100a, 0x0005100a, 0x000c120e, 0x000c130d, 0x00161c16, 0x00212520, 0x00282c28, 0x00303430, 0x002e322d, 0x00262828, 0x00232629, 0x00272a2e, 0x002c2f35, 0x0033353c, 0x0033383c, 0x002e3035, 0x002b2e30, 0x00292b2a, 0x00262825, 0x00242521, 0x00252420, 0x0026211d, 0x002a211d, 0x00352b21, 0x003c2e21, 0x00382819, 0x00433020, 0x004c3826, 0x004e3826, 0x004e3827, 0x00543e2d, 0x00624634, 0x006c4b38, 0x00704b34, 0x00795033, 0x007f5234, 0x00825231, 0x0080502c, 0x007d4a25, 0x007c4821, 0x007a4820, 0x0078461e, 0x0076441c, 0x0073421a, 0x00703f18, 0x006c3d13, 0x006c3d13, 0x006c3c11, 0x00683b10, 0x0066380d, 0x00643810, 0x00633610, 0x005f340f, 0x005c330e, 0x005c330e, 0x005b340e, 0x005b340e, 0x0058310d, 0x0058310d, 0x0059310d, 0x005a310d, 0x005c3410, 0x005e340f, 0x005c320c, 0x005f340f, 0x00623811, 0x00643813, 0x00643812, 0x00663812, 0x00673812, 0x00683812, 0x00683813, 0x00693914, 0x00683812, 0x00683711, 0x00683711, 0x00683810, 0x0068380e, 0x006c3c0e, 0x00704010, 0x00744110, 0x00794410, 0x00804710, 0x00874b14, 0x008b4e11, 0x008e5011, 0x008f5012, 0x00905113, 0x00905112, 0x00915010, 0x00935010, 0x00965111, 0x00975111, 0x00965211, 0x00955211, 0x00955211, 0x00945110, 0x00905110, 0x00905210, 0x00905111, 0x00905111, 0x00915110, 0x00915110, 0x0090500e, 0x0090500e, 0x008c4d10, 0x0086490d, 0x007c400d, 0x0070380b, 0x006b3810, 0x00663610, 0x00633410, 0x005d3310, 0x005a2f0d, 0x00562b0c, 0x004f280e, 0x0043200b, 0x00371906, 0x002d1808, 0x002b170a, 0x0029180c, 0x00251508, 0x00211408, 0x00201409, 0x001f150a, 0x001c140a, 0x001c140a, 0x001c140a, 0x001c1409, 0x001c1409, 0x00181207, 0x00181106, 0x00181108, 0x001b140c, 0x001c150c, 0x001d140c, 0x0020140e, 0x001c140e, 0x0014130c, 0x00080f0c, 0x0004100c, 0x00050f0c, 0x00080e0a, 0x0006100a, 0x0005100a, 0x0008100b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c08, 0x00080e08, 0x00070d07, 0x00070e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d02, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071410, 0x00071410, 0x0007120e, 0x0006120e, 0x0006110d, 0x0005110c, 0x0006100c, 0x0006100c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x0004100a, 0x0005100a, 0x0009120d, 0x000c130e, 0x00181c18, 0x00262924, 0x002c302b, 0x002c2f2a, 0x002c2e2a, 0x002c2e2d, 0x002c2f32, 0x00313438, 0x0035383e, 0x0034373d, 0x0033363b, 0x00303136, 0x00282c2d, 0x002a2c2b, 0x002a2c2a, 0x002a2b28, 0x002c2a25, 0x002c2723, 0x002d2520, 0x002f2419, 0x003c2f21, 0x003e2e1f, 0x00443021, 0x004c3627, 0x004e3827, 0x004e3828, 0x00543c2c, 0x00614535, 0x006d4c3b, 0x0075503c, 0x0080573a, 0x00845739, 0x00835433, 0x0084512f, 0x00824e28, 0x00804c25, 0x007e4b23, 0x007c4a21, 0x007c4920, 0x007b481e, 0x0078451c, 0x00754218, 0x00734016, 0x00714014, 0x006e3c10, 0x006c3910, 0x006c3b10, 0x00693a0e, 0x0067370c, 0x0064370c, 0x0063370c, 0x0062350f, 0x0061360f, 0x0061370e, 0x0062370f, 0x0063360d, 0x0063370e, 0x00683810, 0x00673810, 0x0067380e, 0x00693c10, 0x006c3c12, 0x006c3c12, 0x006e3d12, 0x006f3d11, 0x00703d12, 0x00713e13, 0x00713e14, 0x00723e14, 0x00713d13, 0x00703c11, 0x00703c11, 0x00703c10, 0x00713c0e, 0x0075400f, 0x0079440f, 0x007d450e, 0x00834810, 0x00884a0f, 0x008c4c10, 0x008f4f10, 0x00925013, 0x00935113, 0x00935113, 0x00935112, 0x00945112, 0x00965011, 0x00985011, 0x00985111, 0x00975210, 0x00975211, 0x00965111, 0x00955211, 0x00935311, 0x00905210, 0x00905111, 0x00915111, 0x0090500e, 0x0090500e, 0x0090500f, 0x0090500e, 0x008d4e10, 0x00884a10, 0x007d420e, 0x00743c0e, 0x006c380d, 0x0068380f, 0x00683811, 0x0060330e, 0x00592c0a, 0x00562b0c, 0x004f280e, 0x0044200c, 0x00391c09, 0x00301b0b, 0x00291508, 0x0028170b, 0x00271709, 0x0024150a, 0x0021140a, 0x0020160c, 0x001e170d, 0x001d150c, 0x001d150c, 0x001b1409, 0x00181107, 0x00181208, 0x00141006, 0x00130e04, 0x00171108, 0x0018130a, 0x001b130c, 0x001f140e, 0x001c150f, 0x0015140d, 0x000c110d, 0x0007110c, 0x00050f0c, 0x00080e0b, 0x0006100a, 0x0005100a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050c08, 0x00050c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d06, 0x00050c05, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060c05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c08, 0x00080e08, 0x00070e05, 0x00070e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d02, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x0007130f, 0x0007130f, 0x0006110d, 0x0005110b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00030f09, 0x00050e09, 0x00070d09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x0004100a, 0x0005100a, 0x0009120c, 0x000e1610, 0x001e241e, 0x00282b27, 0x002a2c28, 0x002d302c, 0x002d302c, 0x002c2e2d, 0x002a2d30, 0x002a2d32, 0x002d3037, 0x002c3036, 0x002d3034, 0x002e2f34, 0x002d2f32, 0x002b2c2d, 0x002a2c2b, 0x002b2c28, 0x002c2b26, 0x002d2824, 0x00302622, 0x0035291f, 0x003b2c20, 0x00413021, 0x00493526, 0x004a3426, 0x004c3426, 0x00503829, 0x005c4335, 0x006b4e40, 0x00755445, 0x007b5644, 0x0080563a, 0x00835538, 0x00855434, 0x00875431, 0x0086512c, 0x00845028, 0x00824e25, 0x00804c24, 0x007f4b22, 0x007d481f, 0x007c481d, 0x007c471c, 0x007c4519, 0x007a4317, 0x00784013, 0x00753e10, 0x00743f10, 0x00723c0e, 0x006e3b0b, 0x006d3c0b, 0x006c3b0c, 0x006b3a0f, 0x006b3a10, 0x006b3a0e, 0x006c3c0f, 0x006c3c0e, 0x006d3b0e, 0x00703e10, 0x00713e0f, 0x00734010, 0x00764311, 0x00774413, 0x00784313, 0x00784312, 0x007a4311, 0x007a4412, 0x007c4312, 0x007c4313, 0x007c4313, 0x007b4211, 0x007c4010, 0x007c4010, 0x007c410f, 0x007c420d, 0x0080460f, 0x0082480f, 0x00874b11, 0x008c4d14, 0x00914f14, 0x00945013, 0x00965114, 0x00965415, 0x00975415, 0x00975414, 0x00985414, 0x00995312, 0x009b5212, 0x009c5212, 0x009c5211, 0x00985411, 0x00985412, 0x00985414, 0x00985414, 0x00945412, 0x00915110, 0x00915111, 0x00915111, 0x00945110, 0x00945211, 0x00915210, 0x00915110, 0x008d4e10, 0x00884910, 0x007d420e, 0x00753c0f, 0x006e380d, 0x006c380e, 0x006b3810, 0x0064350f, 0x005e300d, 0x00582c0e, 0x004c240b, 0x0046210c, 0x003a1d0a, 0x002e1808, 0x00281406, 0x00261408, 0x00231407, 0x00201307, 0x001d1106, 0x001a1007, 0x00181008, 0x00181006, 0x00171005, 0x001b1409, 0x001b140b, 0x001c160d, 0x0018140b, 0x00151208, 0x00120f06, 0x00130e06, 0x001a110b, 0x001f140e, 0x001d150f, 0x0016140e, 0x0010130f, 0x0009110d, 0x00070f0c, 0x00080e0c, 0x0006100a, 0x0005100a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d06, 0x00050d05, 0x00060d03, 0x00060d03, 0x00060d03, 0x00060d04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c06, 0x00080f06, 0x00070e04, 0x00070e04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d02, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x0008130f, 0x0008120e, 0x0006110c, 0x0006110b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051009, 0x00040f08, 0x00040d08, 0x00030d08, 0x00040d08, 0x00040d08, 0x00040e08, 0x00040e08, 0x00050d08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050c08, 0x00050c08, 0x00050d07, 0x00050d06, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00050c07, 0x00050c06, 0x00050c06, 0x00040c06, 0x00040c06, 0x00050c07, 0x00050c07, 0x00050c06, 0x00040c06, 0x00050c06, 0x00050c07, 0x00050c07, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040d09, 0x00040d09, 0x00040d09, 0x00040d09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040f09, 0x00050e09, 0x00060e09, 0x00080c09, 0x00060e09, 0x00050e09, 0x00050e08, 0x00040e08, 0x00041009, 0x00051009, 0x000b140d, 0x00161e18, 0x00242a24, 0x00252823, 0x001c1f1a, 0x001c1e19, 0x001a1c18, 0x001c1f1e, 0x00202325, 0x00292c30, 0x00303439, 0x00313439, 0x00313438, 0x002f3034, 0x002b2c30, 0x002a2c2d, 0x00282b29, 0x00262624, 0x00282722, 0x002d2824, 0x00312721, 0x0033271d, 0x003a2c1f, 0x00443323, 0x004c3728, 0x0050382b, 0x00543c2e, 0x00563f30, 0x005c4436, 0x006c5042, 0x00775748, 0x007c5847, 0x00825a40, 0x00865a3e, 0x00885838, 0x008a5734, 0x0088542e, 0x0086512b, 0x00855028, 0x00854f26, 0x00834c23, 0x00814b20, 0x0080491f, 0x0080481c, 0x0081481a, 0x00834918, 0x00834a18, 0x007e4612, 0x007c4410, 0x007a420f, 0x0076400c, 0x0074400c, 0x0074400b, 0x00723d0d, 0x00723f0c, 0x00723f0c, 0x0073400c, 0x00743f0c, 0x00743f0b, 0x0078420d, 0x0078420c, 0x007c4610, 0x007e4811, 0x00804811, 0x00804911, 0x00814810, 0x00814810, 0x00834810, 0x00844911, 0x00844911, 0x00844810, 0x00834810, 0x0083460f, 0x00844610, 0x0084470e, 0x0084480f, 0x0085490c, 0x00874a0d, 0x008e4d12, 0x00925014, 0x00975314, 0x00995414, 0x00995412, 0x00995411, 0x009a5412, 0x009a5412, 0x009a5411, 0x009b5411, 0x009c5310, 0x009c5210, 0x009c5310, 0x00995410, 0x009a5411, 0x009b5414, 0x00995515, 0x00945212, 0x0091500f, 0x00915111, 0x00935111, 0x00955312, 0x00965413, 0x00955413, 0x00935311, 0x008e5011, 0x00874b11, 0x007d420e, 0x00773c0e, 0x00703a0d, 0x006e380e, 0x006c380f, 0x0067360f, 0x0061330f, 0x00592e0e, 0x004f280c, 0x0046220b, 0x003c1c09, 0x002c1705, 0x002a1707, 0x00241407, 0x00201204, 0x001d1205, 0x001b1005, 0x00160c04, 0x00140c04, 0x00130c02, 0x00120b01, 0x00130c03, 0x00140d04, 0x00130f06, 0x00121108, 0x00141309, 0x0017150d, 0x0019140d, 0x001c110c, 0x00201410, 0x001f1711, 0x0018150f, 0x0010130e, 0x0009110c, 0x0008100c, 0x00080d0c, 0x00050f09, 0x00050f09, 0x00060e09, 0x00060e08, 0x00050d09, 0x00050d09, 0x00060d08, 0x00060d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c06, 0x00070e07, 0x00070d05, 0x00070d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c04, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x0008120f, 0x0008120d, 0x0007110c, 0x0007110c, 0x0006100b, 0x0005100a, 0x00051009, 0x00040f08, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c09, 0x00040c09, 0x00060e0b, 0x00060e0a, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050c07, 0x00060d07, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00041008, 0x0008110a, 0x00121b14, 0x00222822, 0x00191c18, 0x000b0d08, 0x0010130e, 0x00161814, 0x00222424, 0x00282c2e, 0x00272a2e, 0x002b2e32, 0x002d3034, 0x002e3035, 0x002d2e33, 0x002c2e31, 0x002a2c2c, 0x00272828, 0x00242423, 0x00282724, 0x002f2823, 0x00312721, 0x0034281e, 0x003d2d21, 0x00443022, 0x004d3628, 0x00543c2e, 0x00583f31, 0x005a4134, 0x005e4738, 0x00684d3f, 0x00735344, 0x007a5546, 0x00855c48, 0x00885d42, 0x0089593a, 0x008a5734, 0x0088532e, 0x0087512b, 0x00885129, 0x00885027, 0x00875026, 0x00864f24, 0x00885023, 0x00884e20, 0x00864c1b, 0x00864a16, 0x00864c15, 0x00884c15, 0x00834a12, 0x00814810, 0x007e450f, 0x007e440f, 0x007d440e, 0x007c430d, 0x007c430c, 0x007e450d, 0x007e450c, 0x007e440d, 0x007f440c, 0x0082480e, 0x0082480f, 0x00844a12, 0x00874a12, 0x00884c10, 0x00884c10, 0x00884d10, 0x008a4c10, 0x008a4c12, 0x00894b11, 0x00894b10, 0x00884b0f, 0x00884b0f, 0x008a4c10, 0x008a4c12, 0x008a4c12, 0x008b4d12, 0x008d5012, 0x008f5111, 0x00945010, 0x00955210, 0x009a5612, 0x009c5711, 0x009f5612, 0x00a05713, 0x009e5511, 0x009e5511, 0x009e5512, 0x009e5513, 0x009e5512, 0x009d5411, 0x009d5510, 0x009c5712, 0x009c5714, 0x00995412, 0x00995414, 0x00955213, 0x00915010, 0x00915010, 0x00945010, 0x00945211, 0x00965413, 0x00965413, 0x00935311, 0x008e5011, 0x00884c13, 0x007e430e, 0x00773d0e, 0x00743c0e, 0x006f390c, 0x006c380d, 0x006b3810, 0x0063350f, 0x005b300d, 0x0050290b, 0x0048240a, 0x003c1d07, 0x00301907, 0x002a1707, 0x00251406, 0x00201305, 0x001c1304, 0x001c1307, 0x001a1308, 0x001a1209, 0x00191209, 0x00181109, 0x00171008, 0x00140f06, 0x00100d04, 0x00100e05, 0x00121008, 0x00141109, 0x0017110a, 0x001c100c, 0x00201410, 0x00201812, 0x0018150f, 0x0010120c, 0x0008110a, 0x0008100b, 0x00070c0b, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x0008120f, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100a, 0x0005100a, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040c04, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c08, 0x00040c08, 0x0008100b, 0x0008100b, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0004100a, 0x0005100b, 0x000c160f, 0x001e241f, 0x001c1f1a, 0x00171914, 0x001c1e1a, 0x002c2e2a, 0x00303330, 0x002f3333, 0x002b2d31, 0x002b2e32, 0x002c3034, 0x002d3034, 0x002e2f34, 0x002e2f32, 0x002c2d2f, 0x00292b2c, 0x00292a28, 0x002f2d2a, 0x002a241f, 0x00302520, 0x00372a20, 0x003f3023, 0x00453224, 0x004d3729, 0x00543c2e, 0x00583e31, 0x00583f32, 0x005c4436, 0x006b5042, 0x0078574b, 0x00805c4e, 0x00885f4b, 0x00895c44, 0x008a593a, 0x008a5634, 0x0089532c, 0x00875128, 0x008a5328, 0x008a5328, 0x00895227, 0x00885224, 0x008a5223, 0x00895221, 0x008b501c, 0x008c4f18, 0x008b4f17, 0x008c5015, 0x008c5015, 0x008a4e14, 0x00884c11, 0x00874b10, 0x00874a10, 0x00854a0f, 0x00854a0f, 0x00884c12, 0x00884c12, 0x008a4c10, 0x008a4c10, 0x008c4e13, 0x008c4f14, 0x008f4f15, 0x00905017, 0x00905014, 0x00905011, 0x00905011, 0x00905112, 0x00905113, 0x00905113, 0x00905213, 0x00905113, 0x00905112, 0x00905013, 0x00905015, 0x00905016, 0x00905114, 0x00905212, 0x00925311, 0x00965110, 0x00985310, 0x009d5811, 0x009f5810, 0x00a15812, 0x00a25914, 0x00a05813, 0x00a05713, 0x00a05713, 0x00a05713, 0x009f5612, 0x009f5612, 0x009e5611, 0x009d5712, 0x009c5713, 0x00995412, 0x00985313, 0x00965211, 0x00935010, 0x00925010, 0x0094500f, 0x00945010, 0x00955412, 0x00955412, 0x00935211, 0x008e5013, 0x00884d14, 0x00804410, 0x00783e0e, 0x00743c0d, 0x00703b0c, 0x00703c0f, 0x006e3c11, 0x0064370d, 0x005b300b, 0x00502a09, 0x00482509, 0x003d1d06, 0x00331a08, 0x00291304, 0x00271407, 0x00221306, 0x001e1405, 0x001e1308, 0x001d1108, 0x001c110a, 0x001c120b, 0x001c130c, 0x001d140c, 0x001b130a, 0x00191209, 0x00181109, 0x00140d06, 0x00140d06, 0x00170e08, 0x001a1009, 0x001f140e, 0x001e1710, 0x0018140c, 0x0011110c, 0x0008100a, 0x0007110c, 0x00080f0b, 0x00081009, 0x00081009, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x0008120e, 0x0007110c, 0x0006100b, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040c03, 0x00040c06, 0x00040d07, 0x00050e08, 0x00050d08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00050f0c, 0x0004100c, 0x00040f0c, 0x00050f0a, 0x00151a16, 0x00242520, 0x00252621, 0x00282824, 0x002d2f2b, 0x00303230, 0x00303334, 0x00303436, 0x00313438, 0x00323539, 0x00323539, 0x00313236, 0x002e2f32, 0x002e2f32, 0x002b2c2f, 0x002a2a2a, 0x00282623, 0x002c231f, 0x00302520, 0x00372821, 0x003f3024, 0x00453224, 0x004d382b, 0x00584034, 0x005e4238, 0x005f4438, 0x00684f44, 0x0075584c, 0x007f6054, 0x00815d52, 0x00885f4b, 0x008a5d44, 0x008c5b3c, 0x008a5533, 0x008a542d, 0x00895429, 0x00895325, 0x00895324, 0x00895324, 0x008a5322, 0x008a5320, 0x008a5320, 0x008c511b, 0x008f5018, 0x00915318, 0x00905116, 0x00905113, 0x00905113, 0x008f5011, 0x00905010, 0x00915013, 0x00915013, 0x00915012, 0x00905011, 0x00904f10, 0x00915011, 0x00914f11, 0x00935013, 0x00945214, 0x00945116, 0x00975215, 0x00965414, 0x00965413, 0x00965411, 0x00965411, 0x00945410, 0x0092520f, 0x00925210, 0x00935210, 0x00935211, 0x00935313, 0x00935214, 0x00935214, 0x00935314, 0x00985817, 0x009b5a16, 0x009e5814, 0x009f5812, 0x00a05910, 0x00a1590f, 0x00a05810, 0x00a05811, 0x00a15812, 0x00a15812, 0x00a15813, 0x00a05713, 0x009f5712, 0x009f5612, 0x009d5511, 0x009c5611, 0x009c5513, 0x009a5311, 0x0096500f, 0x0094500c, 0x0094500c, 0x0094500e, 0x0094510f, 0x0096500f, 0x00955210, 0x00955312, 0x00925112, 0x008e5013, 0x00884c14, 0x00844814, 0x007b4110, 0x00763e0e, 0x00713d0c, 0x00703c0d, 0x006e3c10, 0x00673a0e, 0x005d340b, 0x00522b08, 0x004a2507, 0x00401d05, 0x00381c0c, 0x002f1508, 0x002c180b, 0x0029190c, 0x0026190c, 0x0026190f, 0x0023160d, 0x0023150f, 0x0020150e, 0x0020150e, 0x0022160f, 0x0022160f, 0x0020150c, 0x0020140c, 0x001e1309, 0x001e1309, 0x001e140a, 0x001f140b, 0x0020150c, 0x001f160c, 0x0019140b, 0x0013110c, 0x00080f08, 0x00051008, 0x00070f0a, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x0008120e, 0x0007110c, 0x0006100b, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c05, 0x00040c04, 0x00040c06, 0x00040d07, 0x00050e08, 0x00050d07, 0x00040c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050f0c, 0x00050f0c, 0x0004100c, 0x0005100c, 0x0005100d, 0x0007110e, 0x00101611, 0x001c1d18, 0x00272824, 0x002c2c28, 0x002c2c2b, 0x00303231, 0x00303335, 0x00303337, 0x00303338, 0x00303338, 0x00303438, 0x00323438, 0x002f3034, 0x002c2e31, 0x00282a2b, 0x00282827, 0x002e2c29, 0x002c2420, 0x00302420, 0x003a2b24, 0x00423228, 0x00453427, 0x00503c2f, 0x005c4438, 0x005c4238, 0x005f4439, 0x006c5246, 0x0074584c, 0x007d5d53, 0x00836054, 0x008c6450, 0x008b5e47, 0x008c5a3b, 0x008a5731, 0x008b552c, 0x008b5629, 0x008c5526, 0x008b5524, 0x008b5322, 0x008c5220, 0x008b521e, 0x008b521c, 0x008c5018, 0x00925318, 0x0097581c, 0x0097561a, 0x00945415, 0x00945211, 0x00945110, 0x00945211, 0x00965413, 0x00965413, 0x00965413, 0x00945110, 0x00945110, 0x00955211, 0x00955211, 0x00955211, 0x00955211, 0x00975013, 0x00985212, 0x00985414, 0x00995614, 0x00995611, 0x00995610, 0x00995610, 0x00995610, 0x00985512, 0x00985412, 0x00985412, 0x00985413, 0x00985414, 0x00985414, 0x00995515, 0x009a5713, 0x009c5813, 0x009f5812, 0x009f5811, 0x00a0580e, 0x00a35a0f, 0x00a25a10, 0x00a25a11, 0x00a15810, 0x00a15810, 0x00a15811, 0x00a15812, 0x009f5810, 0x009f5710, 0x009d5610, 0x009c5611, 0x009c5613, 0x00995311, 0x0096500f, 0x0095500b, 0x0094510c, 0x0094510d, 0x0094510d, 0x00975110, 0x00975310, 0x00955312, 0x00925212, 0x008e4f13, 0x00884c13, 0x00834811, 0x007f4514, 0x007b4310, 0x0076400f, 0x00723e0f, 0x006e3c0e, 0x00693b0d, 0x0060360c, 0x00542d08, 0x004c2605, 0x00401f04, 0x003a1d0b, 0x00311809, 0x002b1408, 0x00281609, 0x0024160a, 0x0023160b, 0x00201409, 0x0020120a, 0x001d1209, 0x001c1108, 0x001c1108, 0x001d1108, 0x001e1107, 0x00201409, 0x0022150b, 0x00201409, 0x001e1409, 0x001e1308, 0x001d1308, 0x001c1309, 0x001a140c, 0x0013120b, 0x000a0f08, 0x00050f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x0008120e, 0x0007110d, 0x0007110c, 0x0005100a, 0x00040f08, 0x00051008, 0x00051008, 0x00060f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050e06, 0x00060e06, 0x00050e06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x0005100a, 0x0005110b, 0x0005100c, 0x0004110c, 0x0006100e, 0x00091110, 0x000d130e, 0x0020221e, 0x002f302c, 0x00343433, 0x00343434, 0x002f3132, 0x002b2e30, 0x002b2e32, 0x002d3037, 0x00303238, 0x0032343b, 0x0034353a, 0x00323437, 0x002e3033, 0x002c2d30, 0x002b2b2c, 0x002a2827, 0x002c2320, 0x002e211f, 0x00372822, 0x00423229, 0x004c3a2e, 0x00544033, 0x005b4438, 0x005d4439, 0x0062483c, 0x00684d43, 0x0074574d, 0x0085645c, 0x0089645b, 0x008c6453, 0x008c624a, 0x008c5c3c, 0x008c5934, 0x008d582e, 0x008d572a, 0x008c5625, 0x008d5423, 0x00915523, 0x008f531f, 0x008e521c, 0x008f531a, 0x008f5218, 0x00905418, 0x0096561a, 0x0098561a, 0x00985616, 0x00995514, 0x00985413, 0x00975312, 0x00975312, 0x00985414, 0x00985414, 0x00985414, 0x00985414, 0x00965411, 0x00965510, 0x0098540e, 0x0098540e, 0x0098540e, 0x00985410, 0x009a5512, 0x009c5713, 0x009c5813, 0x009c5812, 0x009c5711, 0x009c5711, 0x009c5711, 0x009c5711, 0x009c5711, 0x009c5812, 0x009c5812, 0x009c5812, 0x009c5812, 0x00a05914, 0x00a35c17, 0x00a25c13, 0x00a35c14, 0x00a45a10, 0x00a45a10, 0x00a35b10, 0x00a15c10, 0x00a05b10, 0x00a05b10, 0x00a0580f, 0x009f570f, 0x009f5810, 0x009c5510, 0x009a530e, 0x009a530f, 0x009a5310, 0x0098530f, 0x0096500d, 0x0096510c, 0x0096500d, 0x0097520e, 0x0097520e, 0x0098530f, 0x00975311, 0x00955314, 0x00925212, 0x008c4d10, 0x00884c13, 0x00844912, 0x00804711, 0x007f4713, 0x007c4514, 0x00784413, 0x00713d10, 0x0069390c, 0x0064340c, 0x005a2d08, 0x004d2404, 0x00482408, 0x00381c07, 0x002f1704, 0x002a1406, 0x00241307, 0x00231509, 0x00211408, 0x00201409, 0x00201408, 0x001d1205, 0x001b1004, 0x001c1205, 0x001d1307, 0x001e1308, 0x001e1407, 0x001f1408, 0x001e1408, 0x001e1508, 0x001f150b, 0x0020160c, 0x00231710, 0x00201713, 0x0014130d, 0x000b0f08, 0x00071007, 0x00051008, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c07, 0x00080e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0008120e, 0x0007110d, 0x0007110d, 0x0007110c, 0x0005100a, 0x00040f08, 0x00051008, 0x00051008, 0x00060f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050e06, 0x00060e06, 0x00050e06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040d08, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x0005100a, 0x0005110b, 0x0004110b, 0x0004130c, 0x0006100b, 0x000a100d, 0x0010140f, 0x00272824, 0x00353633, 0x002e2e2e, 0x00272728, 0x002a2b2e, 0x002f3234, 0x00303237, 0x002c2f35, 0x00282a30, 0x0024272c, 0x00242529, 0x0028292c, 0x002a2c2f, 0x002e2f31, 0x002c2c2c, 0x002b2926, 0x002e2722, 0x00312522, 0x00372823, 0x00423229, 0x004c3a2f, 0x00544034, 0x005c4439, 0x005d453a, 0x0063493d, 0x006f5449, 0x007f6159, 0x008a6a62, 0x008a665d, 0x008e6656, 0x008f644d, 0x008f5f40, 0x00905c38, 0x00905c30, 0x00905a2c, 0x008f5828, 0x00905624, 0x00925523, 0x00915420, 0x0090541d, 0x0091551b, 0x0090541a, 0x0093561c, 0x0097571c, 0x00985819, 0x009a5718, 0x009b5815, 0x009a5714, 0x00995614, 0x00995614, 0x009a5615, 0x00995515, 0x009a5515, 0x009a5616, 0x00995614, 0x00995613, 0x00995610, 0x009b5711, 0x009c5711, 0x009c5613, 0x009c5714, 0x009c5814, 0x009c5814, 0x009c5812, 0x009c5712, 0x009c5711, 0x009c5711, 0x009c5711, 0x009c5711, 0x009d5813, 0x009d5813, 0x009d5813, 0x009c5812, 0x00a15a15, 0x00a35c17, 0x00a25c14, 0x00a35c14, 0x00a45a11, 0x00a45a10, 0x00a45c13, 0x00a45d13, 0x00a05b10, 0x009f580e, 0x009f570e, 0x009d540f, 0x009c5510, 0x009b540f, 0x009b5410, 0x009b540f, 0x00995310, 0x00985410, 0x0096500d, 0x0097520e, 0x0097520e, 0x0097520e, 0x0096500d, 0x0096500d, 0x0094500f, 0x00935011, 0x00904f0f, 0x008c4d10, 0x00884d13, 0x00844912, 0x00804711, 0x007e4510, 0x007b4310, 0x0075400e, 0x00713d0e, 0x006c3b0c, 0x0064340b, 0x005b2d08, 0x00502506, 0x00472207, 0x00371a04, 0x00301603, 0x002b1306, 0x00251207, 0x00231308, 0x00231308, 0x00231208, 0x00221208, 0x00201207, 0x00241509, 0x0025170c, 0x00221509, 0x00211509, 0x00201609, 0x0022170a, 0x0022170a, 0x0020180b, 0x0020170c, 0x0022160e, 0x00231710, 0x00201712, 0x0014130d, 0x000c0f08, 0x00071007, 0x00051007, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c07, 0x00080e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0008120e, 0x0007110d, 0x0007110d, 0x0007110c, 0x0005100a, 0x00040f08, 0x00070f08, 0x00070f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040f06, 0x00040f08, 0x00020e08, 0x0004100a, 0x00041009, 0x00030e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00041008, 0x00051109, 0x00051109, 0x00071009, 0x000a110b, 0x00141711, 0x002c2f29, 0x00313330, 0x002b2b2c, 0x002c2c2e, 0x002f3033, 0x00303335, 0x00303336, 0x002c3034, 0x002c2f33, 0x00282c30, 0x0027282a, 0x00282a2c, 0x002d2f30, 0x002e3031, 0x002b2b2b, 0x002c2926, 0x00302824, 0x00342822, 0x00392a24, 0x0043332b, 0x004c3a30, 0x00554335, 0x00584236, 0x0060473c, 0x00684e44, 0x00745b51, 0x0084665e, 0x00886862, 0x0088655f, 0x008d6457, 0x00906451, 0x00916045, 0x00905c3b, 0x00905a30, 0x008f582b, 0x008f5827, 0x00905624, 0x00915422, 0x00905420, 0x0091541f, 0x0092561d, 0x0092561c, 0x0095581e, 0x0098581c, 0x0099581a, 0x009e5a18, 0x009e5914, 0x009e5814, 0x009c5613, 0x009c5714, 0x009c5614, 0x009a5412, 0x009a5513, 0x009b5514, 0x009c5516, 0x009c5614, 0x009c5612, 0x009c5610, 0x009c5814, 0x009b5514, 0x00995412, 0x009c5715, 0x009c5814, 0x009c5814, 0x009c5814, 0x009c5814, 0x009d5814, 0x009d5814, 0x009e5915, 0x009d5814, 0x009e5915, 0x009d5814, 0x009f5a16, 0x00a05917, 0x00a15b17, 0x00a35c14, 0x00a35c15, 0x00a45a12, 0x00a45a12, 0x00a25a10, 0x00a45c12, 0x00a45c12, 0x00a35b10, 0x00a05810, 0x009f5712, 0x009e5613, 0x009c5412, 0x009b5411, 0x009c5512, 0x009c5512, 0x00995410, 0x009a5411, 0x009a5411, 0x009a5411, 0x00985410, 0x00985410, 0x00995412, 0x00965210, 0x00945112, 0x008d4d10, 0x008a4c10, 0x00874b11, 0x00834811, 0x00814611, 0x00804712, 0x007c430f, 0x00753f0d, 0x00713c0c, 0x006c3b0d, 0x0066380c, 0x005c300b, 0x00502607, 0x00472005, 0x003b1905, 0x00331604, 0x0030160a, 0x002d170c, 0x0029170d, 0x00261409, 0x0027140a, 0x0028150b, 0x0027170c, 0x0028180c, 0x0025140c, 0x0024150c, 0x0024150c, 0x0023160c, 0x0023160a, 0x0022160a, 0x00201508, 0x001e1408, 0x00190e04, 0x001c1008, 0x001d140e, 0x0015130c, 0x000d1009, 0x00080f07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c06, 0x00060c07, 0x00080e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0008120e, 0x0007110d, 0x0007110d, 0x0007110c, 0x0005100a, 0x00040f08, 0x00070f08, 0x00070f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040e06, 0x00040e06, 0x00040e06, 0x00040f07, 0x00040f08, 0x00020f09, 0x00020f08, 0x00020e08, 0x00020e08, 0x00020e08, 0x00020e08, 0x00030f09, 0x00030f09, 0x00040f08, 0x00040f08, 0x00051008, 0x00041008, 0x00041007, 0x00041007, 0x00071008, 0x000e150d, 0x001a1f18, 0x00222520, 0x00252724, 0x002e2e2e, 0x002d2d30, 0x002a2c2f, 0x00282c2e, 0x002b2e30, 0x00282b30, 0x00282d31, 0x00292d31, 0x0028292c, 0x0028292b, 0x002c2d2f, 0x002d2d30, 0x002b2b2a, 0x002d2a26, 0x00312823, 0x00342822, 0x003c2c28, 0x0047372e, 0x00503f34, 0x005a483b, 0x005a4438, 0x0060483d, 0x006c5248, 0x00755b51, 0x007f6159, 0x00866761, 0x008b6861, 0x008f675b, 0x00936756, 0x00906046, 0x008e5b3b, 0x008d5830, 0x008d5629, 0x008e5524, 0x008f5523, 0x00925523, 0x0090541f, 0x0091541f, 0x0092561d, 0x0092561c, 0x0095581e, 0x0098581c, 0x009b591b, 0x009e5a18, 0x009e5913, 0x009e5914, 0x009e5914, 0x009e5914, 0x009c5711, 0x009b5610, 0x009b5512, 0x009c5714, 0x009d5515, 0x009e5715, 0x009e5714, 0x009c5611, 0x009e5713, 0x009b5512, 0x00995410, 0x009c5714, 0x009c5813, 0x009c5812, 0x009c5812, 0x009c5813, 0x009e5915, 0x00a15c18, 0x00a05b18, 0x009e5915, 0x009f5a16, 0x009f5a14, 0x009e5914, 0x009f5813, 0x009f5813, 0x00a05911, 0x00a05a13, 0x00a35a11, 0x00a45a12, 0x00a0590f, 0x00a25a10, 0x00a45c12, 0x00a25a10, 0x009f5710, 0x009e5510, 0x009c5412, 0x009c5411, 0x009b5410, 0x009c5412, 0x009b5412, 0x00995410, 0x009a5511, 0x009c5713, 0x009c5713, 0x009a5511, 0x009a5411, 0x009b5514, 0x00985412, 0x00935112, 0x008e4e10, 0x0087490d, 0x0085490f, 0x00834810, 0x0080460f, 0x00804610, 0x007c4510, 0x00753f0d, 0x00713c0c, 0x006c3a0c, 0x00643409, 0x00592c08, 0x004f2506, 0x004a2409, 0x003e1d09, 0x00361907, 0x002f1509, 0x002c160c, 0x0029160c, 0x00261409, 0x002a180d, 0x0029180d, 0x0028170c, 0x0029170d, 0x0028170e, 0x0028180f, 0x00271910, 0x0022150b, 0x00201308, 0x001f1407, 0x001e1306, 0x001e1408, 0x001b0f04, 0x001b0f06, 0x001a100b, 0x00121009, 0x000a0c06, 0x00080f07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c07, 0x00080e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0007110c, 0x0007110c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00071009, 0x000e150f, 0x00181f17, 0x001f241c, 0x001f211e, 0x00272928, 0x00262828, 0x00242527, 0x00242428, 0x00242729, 0x002a2f33, 0x00282d30, 0x00262c2f, 0x002c3031, 0x002e302f, 0x00302f31, 0x002e2c2c, 0x002d2c2a, 0x002d2a26, 0x002d2820, 0x00342824, 0x003c2d28, 0x00493830, 0x00564438, 0x00574438, 0x00594238, 0x0061493f, 0x006c544b, 0x00735851, 0x007c5e58, 0x00856560, 0x0088655f, 0x008e675c, 0x008d6353, 0x008d5d45, 0x008c593a, 0x008d5730, 0x008d5528, 0x00905525, 0x008f5422, 0x00915321, 0x00945623, 0x00945620, 0x0094571d, 0x0094571d, 0x0096571d, 0x0098581b, 0x009c5819, 0x009d5817, 0x009d5814, 0x009d5813, 0x00a05b15, 0x00a05b15, 0x009d5813, 0x009c5711, 0x009d5612, 0x009f5715, 0x009e5716, 0x009f5816, 0x009e5714, 0x009d5611, 0x009c5611, 0x009c5611, 0x009d5612, 0x009d5614, 0x009d5712, 0x009c5812, 0x009c5712, 0x009c5614, 0x009c5614, 0x009a5714, 0x009a5814, 0x009d5a15, 0x009d5a15, 0x009e5914, 0x009f5a14, 0x009d5811, 0x009c5710, 0x00a05910, 0x00a05912, 0x00a05810, 0x00a05810, 0x00a15a10, 0x00a45c12, 0x00a35b12, 0x00a25a11, 0x009f5710, 0x009f5710, 0x009d5611, 0x009c5510, 0x009c5511, 0x009c5512, 0x009c5611, 0x009b5610, 0x009b5610, 0x009c5613, 0x009c5613, 0x009c5614, 0x00985411, 0x00985310, 0x00945111, 0x00935011, 0x008e4f0f, 0x008b4e10, 0x0085490e, 0x0084480f, 0x0080450f, 0x007f4610, 0x007d4511, 0x0078400f, 0x00723d0d, 0x006c390c, 0x00653409, 0x005d300c, 0x004f2407, 0x00452005, 0x003b1a07, 0x00341706, 0x002e150a, 0x002c160d, 0x0029160a, 0x00261408, 0x00261408, 0x00261408, 0x00271509, 0x0026150c, 0x0026160c, 0x0024170f, 0x0023160d, 0x0020140a, 0x001d1308, 0x001c1005, 0x001c1204, 0x001f1609, 0x0020140a, 0x001f120a, 0x001c130c, 0x0013100a, 0x000b0d07, 0x00091009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0c, 0x00060d0b, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d07, 0x00060e07, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0007110c, 0x0007110c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100b, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00040f08, 0x00051008, 0x00071008, 0x000e150e, 0x00181d16, 0x0020241d, 0x0020221e, 0x00212421, 0x00282a2a, 0x002e3031, 0x002f3033, 0x002e2f32, 0x002a2d31, 0x00252a2e, 0x002a2f32, 0x00353738, 0x00363535, 0x00353134, 0x00332e30, 0x00302c2b, 0x002c2823, 0x002d2720, 0x00342824, 0x003c2c27, 0x00493830, 0x00514035, 0x00544034, 0x005a4338, 0x00614940, 0x006c544b, 0x00745952, 0x007b5e58, 0x0084645f, 0x0088645e, 0x00906860, 0x008c6153, 0x008b5b45, 0x008a573a, 0x008c5530, 0x008d5427, 0x00905625, 0x00945827, 0x00965826, 0x00975824, 0x00975823, 0x00965820, 0x0096581f, 0x0095571d, 0x0098561a, 0x00995717, 0x009b5814, 0x009c5812, 0x009c5812, 0x009b5610, 0x009b5610, 0x009a5510, 0x009b5610, 0x009c5510, 0x009c5612, 0x009e5513, 0x009e5513, 0x009e5511, 0x009c530d, 0x009e5610, 0x009e5610, 0x00a15812, 0x00a05813, 0x00a05812, 0x009e5713, 0x009d5712, 0x009c5612, 0x009c5612, 0x009c5613, 0x009c5712, 0x009c5814, 0x009d5812, 0x009e5813, 0x00a05913, 0x00a35c16, 0x00a76017, 0x00a75f16, 0x00a75e18, 0x00a75c15, 0x00a75c15, 0x00a55d14, 0x00a55d14, 0x00a35b12, 0x00a25a11, 0x009f570f, 0x009f570f, 0x009d5610, 0x009c5610, 0x009c5611, 0x009c5611, 0x009c5611, 0x009b5610, 0x009c5711, 0x009c5613, 0x009c5613, 0x009c5614, 0x00985411, 0x00985310, 0x00955111, 0x00915010, 0x008e500f, 0x00884b0d, 0x00874c10, 0x00864a10, 0x00834810, 0x00804611, 0x00804815, 0x007c4414, 0x00743f10, 0x006f3c0f, 0x0068380d, 0x005c2f0b, 0x004d2306, 0x00441e05, 0x003b1b08, 0x00331707, 0x002c140a, 0x002a160c, 0x00241407, 0x00211104, 0x00241508, 0x00241408, 0x00231407, 0x00201309, 0x001f1308, 0x001d130a, 0x001d140a, 0x001c1308, 0x001d1409, 0x001e1508, 0x001f1608, 0x001f1509, 0x0020150b, 0x0022160d, 0x00201610, 0x0017140d, 0x000e110b, 0x00091009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0c, 0x00060d0b, 0x00040c09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d07, 0x00060e08, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006100b, 0x0006100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070e0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00050f0a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00051008, 0x00040f08, 0x00040f08, 0x00051008, 0x00070f08, 0x00070f08, 0x00070e08, 0x000e140c, 0x00181e17, 0x0021251e, 0x00252724, 0x002b2c2a, 0x002c2e2d, 0x002c2e2f, 0x002e3030, 0x00303134, 0x00333437, 0x0034383a, 0x00333437, 0x00323032, 0x00322e30, 0x00332c2e, 0x00342c2e, 0x00322b29, 0x00302924, 0x00332a23, 0x003a2e28, 0x0040322b, 0x00493830, 0x004e3c33, 0x00523f35, 0x005a433a, 0x00644c44, 0x006d544c, 0x00745c53, 0x00795d56, 0x0082635c, 0x00886660, 0x008e665f, 0x008a5f53, 0x008b5b47, 0x008b583c, 0x008c5531, 0x008f5728, 0x00915826, 0x00945828, 0x00975826, 0x00975824, 0x00975823, 0x00995c22, 0x009a5c23, 0x009b5c22, 0x009d5c1f, 0x009e5c1b, 0x00a05c17, 0x00a15b14, 0x00a15b14, 0x009f5812, 0x009f5812, 0x00a05912, 0x00a05912, 0x00a45b14, 0x00a45c17, 0x00a65b17, 0x00a65c17, 0x00a65c15, 0x00a35911, 0x00a35910, 0x00a35911, 0x00a15710, 0x009e540d, 0x009d540c, 0x009d550f, 0x009d540d, 0x009e560f, 0x009f5811, 0x009f5814, 0x00a05914, 0x00a05a15, 0x00a35c16, 0x00a45c16, 0x00a86017, 0x00a86018, 0x00a86016, 0x00a85f15, 0x00a85e16, 0x00a85c14, 0x00a85c14, 0x00a75d14, 0x00a55c12, 0x00a35911, 0x00a35911, 0x00a35b12, 0x00a05810, 0x009e5810, 0x009c5610, 0x009c550f, 0x009c5510, 0x009c5611, 0x009c5711, 0x009c5712, 0x009e5915, 0x009c5814, 0x009c5614, 0x009a5413, 0x00985213, 0x00955111, 0x00915010, 0x008e4f0f, 0x00884b0d, 0x00884c10, 0x00864a10, 0x00834710, 0x00804511, 0x00804714, 0x00804718, 0x00774012, 0x00703b0d, 0x0068360b, 0x0060330e, 0x00502609, 0x00441f05, 0x00391906, 0x00301605, 0x002c1409, 0x0028130a, 0x00251408, 0x00261509, 0x0028180b, 0x00241408, 0x00231508, 0x00201409, 0x00191007, 0x00150d05, 0x00150e06, 0x00181007, 0x00191208, 0x001b1407, 0x001d1507, 0x001c1307, 0x0020140a, 0x0020120b, 0x00201813, 0x00191710, 0x000c0f08, 0x00080e08, 0x00060e09, 0x00050e08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0c, 0x00060d0b, 0x00040c09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d07, 0x00060e08, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006100b, 0x0006100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e07, 0x00030d06, 0x00040f08, 0x00051008, 0x00070f08, 0x00081009, 0x00070e08, 0x000d140c, 0x00181e17, 0x00242821, 0x002d2e2b, 0x0030302f, 0x00303231, 0x002f3032, 0x00303133, 0x00313334, 0x00323437, 0x00333337, 0x00313034, 0x00322e30, 0x00362f31, 0x00382e31, 0x0034282b, 0x00342828, 0x00352b27, 0x00362c24, 0x00392f28, 0x003f322a, 0x00483930, 0x004f3e34, 0x00544338, 0x005c473e, 0x00665047, 0x0070584f, 0x00755d54, 0x00795d57, 0x0080625c, 0x00886661, 0x008e6660, 0x00895f54, 0x008c5c49, 0x008e5b42, 0x008f5834, 0x0091592c, 0x00925927, 0x00945825, 0x00955624, 0x00955623, 0x00955721, 0x00975920, 0x00995c22, 0x009b5c22, 0x009d5c20, 0x009e5c1b, 0x00a15b17, 0x00a25c14, 0x00a25c14, 0x00a45e15, 0x00a45d14, 0x00a35d14, 0x00a45c14, 0x00a45b14, 0x00a45b13, 0x00a85f17, 0x00a96017, 0x00aa5e14, 0x00a75c11, 0x00a95e14, 0x00aa5e15, 0x00aa5e15, 0x00a85c13, 0x00a45b10, 0x00a45b10, 0x00a55c11, 0x00a75d13, 0x00a65d14, 0x00a55c18, 0x00a55d17, 0x00a55d17, 0x00a65d15, 0x00a85e16, 0x00a96017, 0x00a96016, 0x00a96015, 0x00ac6017, 0x00ac6018, 0x00ab6016, 0x00ab6014, 0x00a95d14, 0x00a65b12, 0x00a45a12, 0x00a35b12, 0x00a35b12, 0x00a15910, 0x009e5710, 0x009f5811, 0x00a05913, 0x009f5813, 0x009f5814, 0x009d5813, 0x009d5813, 0x009e5915, 0x009d5814, 0x009c5715, 0x009b5614, 0x00995414, 0x00975312, 0x00915010, 0x008d4f0f, 0x00884c0e, 0x00874c10, 0x0085490f, 0x0083470f, 0x00804510, 0x00804714, 0x007f4617, 0x00794214, 0x00703c0e, 0x0068360b, 0x0060330f, 0x0052280b, 0x00452007, 0x003a1a08, 0x00321706, 0x002c1409, 0x00281309, 0x00251408, 0x00251709, 0x00261609, 0x0026180c, 0x00231709, 0x001e1409, 0x00171005, 0x00130d04, 0x00100c03, 0x00130d04, 0x00181208, 0x00191408, 0x001a1405, 0x001b1306, 0x001c1107, 0x00180c04, 0x001b140d, 0x00161710, 0x000d110a, 0x00080e08, 0x00060e08, 0x00040d07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0c, 0x00060d0b, 0x00040c09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d07, 0x00060e08, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e07, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c08, 0x00080c08, 0x00080c07, 0x00080c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040a04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x000a120a, 0x00181f18, 0x00282a24, 0x0032302d, 0x00343433, 0x00343534, 0x00353738, 0x00323435, 0x00383839, 0x0038383a, 0x00373538, 0x00312f31, 0x00342c30, 0x00383033, 0x002e2528, 0x002e2426, 0x00382c2d, 0x00372d29, 0x00332b23, 0x00382f28, 0x0040332d, 0x00493b34, 0x0053433b, 0x005c4b42, 0x005f4942, 0x00675048, 0x006c554d, 0x00755c55, 0x007c5f58, 0x0082645e, 0x00856560, 0x0089675f, 0x008a6457, 0x00895e48, 0x008c5c41, 0x008f5835, 0x00935a30, 0x00935929, 0x00935824, 0x00945524, 0x00925420, 0x00975924, 0x00985a21, 0x00985b21, 0x00995b20, 0x009d5b1e, 0x009f5c1c, 0x009f5a14, 0x00a05b10, 0x00a05b10, 0x00a25a10, 0x00a1590f, 0x00a25a11, 0x00a15910, 0x00a35910, 0x00a65c13, 0x00a65c12, 0x00a85e13, 0x00a95e13, 0x00aa5f12, 0x00aa5f14, 0x00aa5f14, 0x00a95e13, 0x00a95e13, 0x00a96014, 0x00a85f13, 0x00a85e14, 0x00a75d14, 0x00a45c13, 0x00a45c14, 0x00a45c14, 0x00a85f17, 0x00a85e16, 0x00a95d14, 0x00ac6018, 0x00a95d14, 0x00ab6017, 0x00ab6015, 0x00ac6018, 0x00ac5f14, 0x00ab5e14, 0x00ab5e14, 0x00a95e13, 0x00a45b11, 0x00a45c12, 0x00a35b10, 0x00a1590f, 0x00a25a11, 0x00a25a11, 0x00a15a13, 0x00a05a13, 0x00a05912, 0x009f5813, 0x009f5813, 0x00a05814, 0x009f5814, 0x009c5514, 0x00995210, 0x00965010, 0x00945010, 0x00915010, 0x008f5010, 0x008c4f10, 0x00864b0c, 0x0084490e, 0x0082460e, 0x00814610, 0x00814813, 0x007f4714, 0x007a4312, 0x00703c0c, 0x00673509, 0x005c300b, 0x00512709, 0x00462008, 0x003a1a08, 0x002f1404, 0x002b1208, 0x002a170d, 0x00241507, 0x00231508, 0x00201409, 0x001c1408, 0x001c1408, 0x001b1408, 0x001a140a, 0x00181308, 0x00161106, 0x00131004, 0x00120f04, 0x00141005, 0x00151105, 0x00181106, 0x001b1108, 0x001b110a, 0x0018120b, 0x000e1008, 0x00090e07, 0x00060e06, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00060e09, 0x00060d0a, 0x00060e09, 0x00060e08, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e07, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c08, 0x00080c08, 0x00080c07, 0x00080c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040a04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00081109, 0x001d231c, 0x002d2d28, 0x0032302e, 0x00353434, 0x00343636, 0x00353738, 0x00323435, 0x0038383a, 0x0038383a, 0x00383638, 0x00383437, 0x00363034, 0x00342e30, 0x00342e31, 0x00362f30, 0x00342d2c, 0x00322925, 0x00322c25, 0x00383029, 0x003a2f2a, 0x00483b36, 0x0056473f, 0x0055443c, 0x005c4840, 0x00665149, 0x006f5850, 0x007b615b, 0x007f635c, 0x0081645d, 0x00856560, 0x0089665d, 0x008a6457, 0x00895f49, 0x008c5c42, 0x00905a38, 0x00925832, 0x0093582c, 0x00935726, 0x00955725, 0x00985925, 0x00985b25, 0x00985b22, 0x00985b21, 0x00995b20, 0x009d5c1f, 0x009f5c1c, 0x009f5914, 0x00a05a0f, 0x00a05a0f, 0x00a0580e, 0x00a1590f, 0x00a15810, 0x00a15810, 0x00a35910, 0x00a65c13, 0x00a75d14, 0x00a85e14, 0x00a95e13, 0x00aa5f14, 0x00aa5f14, 0x00aa5f14, 0x00a95e13, 0x00a95e13, 0x00a96014, 0x00a85f13, 0x00a85e14, 0x00a75d14, 0x00a45c12, 0x00a45c12, 0x00a35b11, 0x00a65c14, 0x00a75c15, 0x00a75d14, 0x00a65c13, 0x00a75c13, 0x00aa5e15, 0x00ac6016, 0x00ac6018, 0x00ac5f14, 0x00ab5e14, 0x00ac5f14, 0x00a95e13, 0x00a55c12, 0x00a25c12, 0x00a25b10, 0x00a25a10, 0x00a25a10, 0x00a25a11, 0x00a15a12, 0x00a05a13, 0x00a05a13, 0x00a05814, 0x00a05814, 0x00a05814, 0x00a05814, 0x009c5514, 0x009a5311, 0x00965011, 0x00945110, 0x00915010, 0x008f5010, 0x00894c0d, 0x00874c0e, 0x00864a0e, 0x0084480e, 0x0081470e, 0x007f460f, 0x007e4611, 0x007a4310, 0x00703c0b, 0x00673509, 0x005c300b, 0x00512709, 0x00452008, 0x00381908, 0x00321708, 0x002c140b, 0x0027140a, 0x00241508, 0x00221409, 0x001f150b, 0x001c140a, 0x001a140a, 0x00191407, 0x001a140a, 0x00181308, 0x00181207, 0x00181308, 0x00181308, 0x00181309, 0x00181308, 0x00171208, 0x00181109, 0x001a110c, 0x0016130c, 0x000d1209, 0x00091008, 0x00060e06, 0x00070e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060d0a, 0x00060d0a, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e07, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c07, 0x00080c07, 0x00080c05, 0x00080c04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00060f08, 0x00081008, 0x001b201a, 0x002e2e28, 0x0033302d, 0x00353434, 0x00343535, 0x00313436, 0x00303334, 0x00363839, 0x0037383a, 0x00323134, 0x00302f32, 0x002f2b30, 0x002f2a2f, 0x00353134, 0x00332f30, 0x00312d2b, 0x00322d28, 0x00312c25, 0x0038312c, 0x003f3530, 0x004e403c, 0x00574944, 0x0052433c, 0x00604d48, 0x0069544e, 0x00705953, 0x007c635e, 0x007e625c, 0x00846660, 0x00866660, 0x0089675e, 0x008a6558, 0x008c614d, 0x008c5d44, 0x0090583a, 0x00945a35, 0x0094592e, 0x00935828, 0x00925521, 0x00975823, 0x00985b24, 0x00985b21, 0x00985c20, 0x00995b1f, 0x009d5c1f, 0x009f5c1c, 0x009e5914, 0x009c570c, 0x009d570c, 0x009f580d, 0x00a0590f, 0x00a05810, 0x00a05810, 0x00a55b13, 0x00a55b14, 0x00a75b14, 0x00a85c15, 0x00a85c14, 0x00a95d14, 0x00aa5e15, 0x00aa5f14, 0x00a75c11, 0x00a75c11, 0x00a75c11, 0x00a85c12, 0x00a85d13, 0x00a65c13, 0x00a45a10, 0x00a35b10, 0x00a35b10, 0x00a25a11, 0x00a45c14, 0x00a85e14, 0x00a55c12, 0x00a55c12, 0x00a55c12, 0x00ac6016, 0x00ac6018, 0x00ad6016, 0x00ad6016, 0x00ac5f14, 0x00ac6016, 0x00a75d14, 0x00a25c11, 0x00a25a0f, 0x00a25a0e, 0x00a35b10, 0x00a35b10, 0x00a35b12, 0x00a35b12, 0x00a25913, 0x00a15812, 0x00a05912, 0x009f5811, 0x009d5711, 0x009c5412, 0x00995411, 0x00985210, 0x00965211, 0x00945313, 0x00905110, 0x00894c0d, 0x00874c0e, 0x00864a0e, 0x0084480e, 0x0081470c, 0x0080480f, 0x00804912, 0x007a4410, 0x00703c0b, 0x006c3a0d, 0x0062340f, 0x004f2406, 0x00462007, 0x00391a07, 0x002f1404, 0x002c160b, 0x00241108, 0x00201208, 0x001d1006, 0x001b100a, 0x001c120c, 0x00191408, 0x00191407, 0x001a140a, 0x0019140b, 0x00151005, 0x00151005, 0x00171006, 0x00181108, 0x00181208, 0x00181108, 0x0018100a, 0x001a120c, 0x0016140e, 0x000e110b, 0x000a0f08, 0x00070e06, 0x00070e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060d0a, 0x00060d0a, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e07, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c05, 0x00080c05, 0x00080c04, 0x00080c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00060f08, 0x00081008, 0x0010140d, 0x00282824, 0x0033322f, 0x00353434, 0x00343536, 0x00303436, 0x002f3234, 0x002e3134, 0x002d3032, 0x00303134, 0x002d2e31, 0x00333337, 0x00343337, 0x00343335, 0x00313131, 0x0031302e, 0x0035322d, 0x00312d27, 0x0038322c, 0x00443a36, 0x004a3c39, 0x0050423e, 0x00544642, 0x0064514e, 0x0069554f, 0x00715a54, 0x00785f5b, 0x007c605a, 0x00846660, 0x00876761, 0x0088655d, 0x00886357, 0x008c614e, 0x008d5e45, 0x0090593d, 0x00915636, 0x0090552c, 0x00925628, 0x00945723, 0x00985924, 0x00985b24, 0x00985b21, 0x00985c20, 0x00995b1f, 0x009c5b1e, 0x009c5a1a, 0x009c5813, 0x009c570e, 0x009c570e, 0x009e560e, 0x00a1590f, 0x00a35b12, 0x00a35b12, 0x00a55b14, 0x00a55b14, 0x00a75b14, 0x00a95d16, 0x00a85c15, 0x00aa5e16, 0x00ac5f16, 0x00ab5e14, 0x00a85b11, 0x00a85b11, 0x00a85c11, 0x00a85d12, 0x00a85e14, 0x00a65c13, 0x00a45a10, 0x00a45b10, 0x00a55c12, 0x00a55b14, 0x00a65c14, 0x00a85e14, 0x00a85e14, 0x00a85f15, 0x00aa6017, 0x00ab6118, 0x00ac6118, 0x00ad6016, 0x00ad6016, 0x00ad6016, 0x00ac6016, 0x00a85f15, 0x00a45e14, 0x00a45d11, 0x00a45d11, 0x00a45c11, 0x00a35b10, 0x00a35b11, 0x00a35b12, 0x00a25a11, 0x00a15812, 0x00a05912, 0x00a05912, 0x009d5711, 0x009c5412, 0x00995410, 0x00985411, 0x00975312, 0x00945314, 0x00905111, 0x008a4d0e, 0x00874c0f, 0x0085490f, 0x0084480e, 0x0082480d, 0x0081480e, 0x007f4810, 0x007a440e, 0x00713d0a, 0x006a380a, 0x0062340f, 0x00522808, 0x00452006, 0x00391906, 0x00321707, 0x002c160b, 0x00241208, 0x00201208, 0x001c0f07, 0x00190e08, 0x00180e09, 0x00181008, 0x001a140a, 0x0019140b, 0x001b150c, 0x00171108, 0x00151005, 0x00160f06, 0x00181008, 0x00181008, 0x00161008, 0x0018110a, 0x0019110c, 0x0016140e, 0x000f120c, 0x000a0f08, 0x00080f07, 0x00080f07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e0a, 0x00060d0a, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050c07, 0x00060c07, 0x00060d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00050d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040d07, 0x00070e08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060d08, 0x00060d08, 0x00060c07, 0x00040c05, 0x00050c06, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00051009, 0x00051008, 0x00081008, 0x000a1108, 0x000c0f0a, 0x00202020, 0x00383639, 0x003d3b40, 0x00393b40, 0x00323739, 0x002f3234, 0x002c3032, 0x002c2f31, 0x002e3134, 0x00303335, 0x00313437, 0x00313436, 0x00313334, 0x00303332, 0x00313330, 0x0034342e, 0x0034312b, 0x0038312d, 0x00403733, 0x00493e3a, 0x00514340, 0x005c4e4a, 0x0063504c, 0x00685450, 0x00705a54, 0x00745b56, 0x007c5f5c, 0x00846660, 0x0084655e, 0x0087645c, 0x00886357, 0x008c614f, 0x008d5e46, 0x0090593c, 0x00905736, 0x0090562c, 0x0093582a, 0x00975a25, 0x00985b24, 0x00985a22, 0x00995922, 0x0098591f, 0x009a591e, 0x009c5a1b, 0x009c5817, 0x009c5713, 0x009e5710, 0x009f5710, 0x00a15810, 0x00a45b11, 0x00a75d14, 0x00a75d14, 0x00a55a11, 0x00a55a11, 0x00a85c14, 0x00a95d15, 0x00ac6018, 0x00ab6016, 0x00ac5f14, 0x00ad5f15, 0x00ac5e14, 0x00ac5e14, 0x00ab5f14, 0x00aa5f14, 0x00a85d14, 0x00a75c13, 0x00a75c13, 0x00a55a10, 0x00a85c14, 0x00a95e17, 0x00a95e17, 0x00a85e15, 0x00a85f16, 0x00ab6018, 0x00ac611a, 0x00ac6218, 0x00ac6118, 0x00ac5f14, 0x00ad6014, 0x00ad6014, 0x00ad6115, 0x00ac5f14, 0x00aa5e14, 0x00a85f14, 0x00a85f13, 0x00a75e13, 0x00a75d12, 0x00a65c14, 0x00a45a12, 0x00a35912, 0x00a25a14, 0x00a25a14, 0x00a15913, 0x009e5810, 0x009a540f, 0x00995410, 0x00985411, 0x00955210, 0x00925313, 0x00905112, 0x008a4d10, 0x00874a10, 0x00864910, 0x00854810, 0x00874c13, 0x00824810, 0x007e4610, 0x0079430f, 0x006f3b08, 0x006a3808, 0x0063330c, 0x00552b0b, 0x00462006, 0x003a1b06, 0x00341806, 0x002c1508, 0x00251408, 0x00211409, 0x0020140b, 0x00180c07, 0x00170d08, 0x00150d07, 0x00150f08, 0x0019120b, 0x001c140c, 0x001b140b, 0x00191209, 0x00181108, 0x00181008, 0x00181008, 0x00161007, 0x00160f08, 0x0019130c, 0x00181610, 0x0010100b, 0x000a0e07, 0x00070e06, 0x00080d06, 0x00080e08, 0x00060d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d08, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00050d07, 0x00060d08, 0x00060d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00050c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x0005100a, 0x00051008, 0x00050f07, 0x00091008, 0x00181b16, 0x00303030, 0x003c3b40, 0x0038383e, 0x002e3034, 0x00252a2c, 0x0025282b, 0x00292c2f, 0x00292c2f, 0x002b2e30, 0x002f3234, 0x00303436, 0x00303335, 0x00303234, 0x00313433, 0x00333432, 0x00363730, 0x00383530, 0x003b3430, 0x003e3432, 0x00463a38, 0x00504240, 0x005e504c, 0x0064524e, 0x006b5852, 0x00705b55, 0x0079605c, 0x00806460, 0x00846661, 0x0085665e, 0x0088665e, 0x008b6559, 0x008f6450, 0x008f6049, 0x00905b3e, 0x00905837, 0x00915930, 0x00955c2d, 0x00975c28, 0x00985c24, 0x009a5a24, 0x009a5a24, 0x00995a21, 0x009c5c20, 0x009f5b1d, 0x009f5a19, 0x00a05916, 0x00a15814, 0x00a15812, 0x00a45a11, 0x00a65c12, 0x00a45b0e, 0x00a45b0d, 0x00a55a0e, 0x00a55a0e, 0x00a85c11, 0x00aa5f14, 0x00ad6018, 0x00ad6016, 0x00ad6014, 0x00af6116, 0x00ae6116, 0x00ae6116, 0x00ad6116, 0x00ac6014, 0x00ab6014, 0x00ab6015, 0x00ab6015, 0x00a95e14, 0x00ab6017, 0x00a95d14, 0x00a85c14, 0x00a85f15, 0x00ab6118, 0x00ac6219, 0x00b0651c, 0x00b0651c, 0x00af651a, 0x00af6418, 0x00af6417, 0x00af6315, 0x00af6315, 0x00af6315, 0x00af6215, 0x00ae6318, 0x00ac6318, 0x00ab6116, 0x00ab6015, 0x00ab6018, 0x00a85f17, 0x00a65c15, 0x00a45c16, 0x00a45c16, 0x00a35b14, 0x00a05811, 0x009d5812, 0x009c5814, 0x009a5714, 0x00965412, 0x00935413, 0x008f5214, 0x008c4e13, 0x00894c12, 0x00874911, 0x00884914, 0x00874a13, 0x00834913, 0x00804814, 0x007b4412, 0x00703c0a, 0x006c3809, 0x0063330c, 0x00552b0a, 0x00482207, 0x003c1c08, 0x00341805, 0x002b1508, 0x00251408, 0x00221408, 0x0020160a, 0x001e120a, 0x00191008, 0x00150e08, 0x00140d06, 0x00160e08, 0x001a120a, 0x001c140c, 0x001c140c, 0x001a130a, 0x00181008, 0x00171007, 0x00160f07, 0x00160f07, 0x00171109, 0x0016140e, 0x0010100b, 0x000a0d07, 0x00070e06, 0x00080d06, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00050c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060d08, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x0004100a, 0x00041008, 0x00030c04, 0x00091007, 0x00262a23, 0x003a3b38, 0x00343435, 0x0027262b, 0x001b1c1f, 0x00181d1e, 0x00202526, 0x002a2f30, 0x00292e2f, 0x00282b2d, 0x002e3134, 0x00303336, 0x00303236, 0x00323336, 0x00323434, 0x00343735, 0x00333330, 0x00302f2a, 0x0036312e, 0x00433b38, 0x004a3e3c, 0x00504341, 0x005e504e, 0x0064534e, 0x006b5852, 0x00745e58, 0x007d6461, 0x007f625f, 0x00826460, 0x0084655d, 0x0088655c, 0x008c655b, 0x00906454, 0x0090624c, 0x00915d40, 0x00905a38, 0x00935c32, 0x00945d2e, 0x00965c26, 0x00985c24, 0x009c5c26, 0x009d5d26, 0x009c5c24, 0x009d5d22, 0x00a05d1f, 0x00a25e1c, 0x00a55e1a, 0x00a65e18, 0x00a86017, 0x00ab6117, 0x00ac6417, 0x00ad6416, 0x00ad6416, 0x00ac6114, 0x00ac6114, 0x00ac6214, 0x00b06518, 0x00b06416, 0x00b06416, 0x00ae6114, 0x00ae6114, 0x00ac5f12, 0x00aa5c10, 0x00aa5e10, 0x00ab5f11, 0x00aa5e12, 0x00a95d11, 0x00a85d11, 0x00a75c10, 0x00aa6014, 0x00ac6218, 0x00ae641a, 0x00b1691e, 0x00b36b20, 0x00b46c21, 0x00b66e23, 0x00b46c21, 0x00b36a1e, 0x00b1681b, 0x00b36a1b, 0x00b36a1a, 0x00b36a19, 0x00b56a1b, 0x00b4691b, 0x00b2681a, 0x00ae6418, 0x00ab6116, 0x00aa6014, 0x00a95d14, 0x00a65b13, 0x00a55a12, 0x00a45c14, 0x00a45c14, 0x00a25a13, 0x00a05811, 0x009e5913, 0x009f5a14, 0x009c5814, 0x00965413, 0x00945414, 0x00905314, 0x008f5114, 0x008c4f14, 0x008a4c14, 0x00884a14, 0x00864913, 0x00824812, 0x00824a18, 0x00804817, 0x0074400e, 0x006c380a, 0x0064340b, 0x00552908, 0x00452003, 0x003c1b05, 0x00331704, 0x00291405, 0x00241406, 0x00231708, 0x0021170b, 0x001f140b, 0x001e140c, 0x001b130c, 0x0018110a, 0x00160e07, 0x00170f06, 0x00191209, 0x001c140c, 0x001e150d, 0x001e150d, 0x001c140c, 0x001b140c, 0x001c150d, 0x001c150e, 0x0019180f, 0x0012120c, 0x000b0d07, 0x00080d06, 0x00080d06, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00050c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060d08, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x0004100a, 0x00041008, 0x00040e08, 0x00151c15, 0x0030342c, 0x00282b26, 0x001a1c19, 0x00151818, 0x00141818, 0x00181c1c, 0x00212625, 0x00252a2a, 0x00292f2f, 0x002e3134, 0x00313539, 0x0033363c, 0x0034373c, 0x0036383b, 0x00343638, 0x00343635, 0x00323331, 0x00323230, 0x00383434, 0x003e3836, 0x00443a39, 0x00514644, 0x00625453, 0x00615350, 0x00685650, 0x00715e58, 0x0079605e, 0x007e6060, 0x00836460, 0x0085655e, 0x0087645e, 0x008b655b, 0x00906454, 0x0090614c, 0x00905f40, 0x00905c3a, 0x00915d32, 0x00935e2e, 0x00945e26, 0x009a5e26, 0x009d5d26, 0x009e5e27, 0x009e5e26, 0x009e5e22, 0x00a15d20, 0x00a35e1c, 0x00a55e18, 0x00a86016, 0x00aa6218, 0x00ad6418, 0x00ae6415, 0x00ad6414, 0x00ac6414, 0x00ae6314, 0x00ad6314, 0x00b36919, 0x00b66c1d, 0x00b56b1b, 0x00b56b1b, 0x00b56a1b, 0x00b5691a, 0x00b66b1c, 0x00b26617, 0x00b06516, 0x00b36818, 0x00b36818, 0x00b3681a, 0x00b3681a, 0x00b36b1c, 0x00b56d1f, 0x00b66e21, 0x00b46c1f, 0x00b36c20, 0x00b36d20, 0x00b56f21, 0x00b56f21, 0x00b26c1d, 0x00ad6717, 0x00b16a19, 0x00b46c1b, 0x00b46d1a, 0x00b46c1a, 0x00b66c1c, 0x00b46c1b, 0x00b46a1b, 0x00b06718, 0x00ac6418, 0x00ab6015, 0x00a95e14, 0x00a85c14, 0x00a65b12, 0x00a45b13, 0x00a15910, 0x00a05810, 0x009e560e, 0x009d5810, 0x009e5a11, 0x009b5813, 0x00945310, 0x00945414, 0x00905314, 0x00905214, 0x008c5013, 0x008c4e14, 0x00894b13, 0x00874913, 0x00804811, 0x00804816, 0x007e4715, 0x00754110, 0x00703c0c, 0x0068360e, 0x00582c0a, 0x00462102, 0x003c1a04, 0x00321602, 0x00281404, 0x00231404, 0x00221808, 0x0022170b, 0x001e140b, 0x001e140c, 0x001c150b, 0x001c150a, 0x001c140a, 0x00191208, 0x00181007, 0x00181108, 0x001b130a, 0x001c140c, 0x001c140c, 0x001c140c, 0x001c150d, 0x001c170f, 0x0019170f, 0x00100f09, 0x00090c06, 0x00080d06, 0x00080d06, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c06, 0x00050c06, 0x00050d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c09, 0x00050d08, 0x00050d08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050e08, 0x00060d07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040d09, 0x00050e09, 0x00040e09, 0x0004100a, 0x00041009, 0x00060f08, 0x00101710, 0x001c211b, 0x001a1e18, 0x001b1f1b, 0x001c1f1d, 0x00181b1a, 0x001c201f, 0x00252928, 0x002c3131, 0x00303636, 0x0034383a, 0x0034373c, 0x0036383e, 0x0034383c, 0x00343438, 0x00303234, 0x00303332, 0x00323432, 0x00303030, 0x00313030, 0x003c3636, 0x00484040, 0x00544a49, 0x005a4e4d, 0x005b4e4a, 0x00665651, 0x00715e59, 0x00785f5c, 0x007e6160, 0x00856763, 0x00866760, 0x0088655c, 0x008a645a, 0x008e6454, 0x008e624e, 0x008f5e44, 0x008e5c3c, 0x00915d35, 0x00935e2f, 0x00955f29, 0x00995e28, 0x009c5f28, 0x009f5f27, 0x009f5e25, 0x009f5e23, 0x00a05f20, 0x00a35e1d, 0x00a46019, 0x00a86116, 0x00ab6417, 0x00ae6416, 0x00b06414, 0x00b16614, 0x00b26714, 0x00ac6210, 0x00ad6411, 0x00b06815, 0x00b36b18, 0x00b66c1a, 0x00b66c1a, 0x00b66c1a, 0x00b66c1a, 0x00b56b18, 0x00b86d1b, 0x00b86e1c, 0x00b86e1c, 0x00b86f1d, 0x00ba701f, 0x00b86f1e, 0x00b46e1c, 0x00b6701e, 0x00b46e1e, 0x00b36c1c, 0x00b06c1b, 0x00b06c1b, 0x00b46f1f, 0x00b46f1f, 0x00b46f1f, 0x00b26d1b, 0x00b36d1c, 0x00b06b18, 0x00b26c18, 0x00b36c18, 0x00b66f1c, 0x00b46c19, 0x00b16718, 0x00ae6418, 0x00ac6117, 0x00aa6018, 0x00a85f15, 0x00a55c13, 0x00a35a10, 0x00a05910, 0x009f580f, 0x009f570e, 0x009d570d, 0x009d580f, 0x009c5810, 0x00995713, 0x00955412, 0x00955513, 0x00925313, 0x00905213, 0x008e5012, 0x008c4f13, 0x00894c12, 0x00854b12, 0x00804710, 0x007d4510, 0x007c4513, 0x0074400f, 0x00703d0d, 0x006c3a11, 0x005c300c, 0x00492405, 0x003d1c05, 0x00331603, 0x00281404, 0x00231405, 0x00211708, 0x00211609, 0x001f150a, 0x001e140b, 0x001c1409, 0x001b1407, 0x001e170d, 0x001e180d, 0x001c150a, 0x00181207, 0x00171007, 0x00181108, 0x00181008, 0x00181209, 0x00181109, 0x00141009, 0x0014120b, 0x000c0d08, 0x00080c06, 0x00070e07, 0x00070e07, 0x00060e08, 0x00050d07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00050c07, 0x00050d07, 0x00050d07, 0x00050c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00080c09, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00060f08, 0x00060e07, 0x000f140f, 0x00131812, 0x001d2220, 0x00202423, 0x00252928, 0x002c302f, 0x00303432, 0x002d3334, 0x002e3435, 0x00303437, 0x00313437, 0x00313438, 0x002f3234, 0x00303235, 0x002e3031, 0x002d302f, 0x002b2d2c, 0x002c2c2d, 0x00303030, 0x00383434, 0x00443d3e, 0x004d4545, 0x00534948, 0x005a4f4c, 0x00645752, 0x0074615c, 0x007a605e, 0x007f6260, 0x00856763, 0x00866760, 0x0088655c, 0x008a645b, 0x008c6457, 0x008e6352, 0x008e604a, 0x008e5d41, 0x00905e38, 0x00945e33, 0x00965e2c, 0x009a602c, 0x009c6029, 0x009e6028, 0x009f5e26, 0x009f5e24, 0x00a05f22, 0x00a25f20, 0x00a4601b, 0x00a56116, 0x00a96215, 0x00ae6416, 0x00b06515, 0x00b16414, 0x00b26514, 0x00b16715, 0x00b26b18, 0x00b36b18, 0x00b36b18, 0x00b56c1b, 0x00b56c1b, 0x00b46c19, 0x00b46c19, 0x00b56b19, 0x00b66c19, 0x00b56c19, 0x00b66c1a, 0x00b66d1c, 0x00b76d1c, 0x00b56d1c, 0x00b46d1c, 0x00b46c1c, 0x00b36c1c, 0x00b36c1c, 0x00b26d1d, 0x00b36e1d, 0x00b36e1e, 0x00b36e1e, 0x00b36e1e, 0x00b46f1d, 0x00b46f1d, 0x00b4701d, 0x00b46e1c, 0x00b46e1c, 0x00b46d1b, 0x00b36c19, 0x00af6718, 0x00ae6319, 0x00ab6018, 0x00a96018, 0x00a76017, 0x00a15c11, 0x009e580e, 0x00a0580f, 0x009f580f, 0x009f580f, 0x009f580f, 0x009f5810, 0x009c570f, 0x00995715, 0x00985614, 0x00955513, 0x00945212, 0x00915211, 0x008e5010, 0x008c5011, 0x00894d11, 0x00874c14, 0x00814810, 0x007c4410, 0x007c4511, 0x0073400c, 0x006e390b, 0x0069380f, 0x005d310c, 0x004c2808, 0x00401e09, 0x00331604, 0x00291407, 0x00241407, 0x001f1404, 0x001e1406, 0x001e140a, 0x001f140c, 0x001d160b, 0x001c1409, 0x00191408, 0x001b150a, 0x001a140a, 0x001a140a, 0x001a140c, 0x0019140a, 0x00171008, 0x00161008, 0x00141008, 0x0014100b, 0x0014130e, 0x000d0e0a, 0x00080d08, 0x00040f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00050d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00081009, 0x00080f0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00080c09, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00051009, 0x0005100a, 0x0008100a, 0x00080f09, 0x000d140f, 0x00161b17, 0x00222623, 0x00242827, 0x00323634, 0x00313534, 0x00303433, 0x002d3334, 0x002e3335, 0x00303337, 0x002f3234, 0x00303435, 0x002d3033, 0x002b2c30, 0x00282a2c, 0x002a2c2c, 0x00292b2c, 0x002a2c2d, 0x00313132, 0x003e3b3c, 0x00464141, 0x00484241, 0x004d4544, 0x005a4e4c, 0x00645853, 0x0075625d, 0x007b625f, 0x007f6461, 0x00856762, 0x00876760, 0x0087655c, 0x0089665d, 0x008d665b, 0x008c6557, 0x008e614d, 0x008d5f44, 0x00905f3c, 0x00936034, 0x00966030, 0x0099602e, 0x009b602c, 0x009d602b, 0x009f6028, 0x009f6025, 0x00a06022, 0x00a16020, 0x00a2601a, 0x00a46118, 0x00a86218, 0x00ad6418, 0x00b06417, 0x00b16616, 0x00b36818, 0x00b56d1c, 0x00b6701e, 0x00b36b19, 0x00b36b19, 0x00b36b19, 0x00b36b19, 0x00b46a19, 0x00b36918, 0x00b46918, 0x00b56a19, 0x00b46a19, 0x00b46b19, 0x00b46c1a, 0x00b46c1a, 0x00b46c1b, 0x00b36c1c, 0x00b36c1c, 0x00b46c1c, 0x00b46d1e, 0x00b46f1f, 0x00b46f1f, 0x00b46e1e, 0x00b36d1d, 0x00b36d1d, 0x00b46e1e, 0x00b67020, 0x00b67020, 0x00b56f1f, 0x00b46c1c, 0x00b16b1b, 0x00b06819, 0x00ae6518, 0x00ac6218, 0x00a75e15, 0x00a55e17, 0x00a45e17, 0x00a15b13, 0x009e5811, 0x009f5811, 0x009f5811, 0x009f5812, 0x00a05913, 0x009f5912, 0x009b5610, 0x009a5715, 0x00985514, 0x00955413, 0x00945210, 0x00905010, 0x008c4d0f, 0x008b4e10, 0x00884d11, 0x00884e14, 0x00844b13, 0x007e4611, 0x007c4511, 0x00733f0c, 0x006d390a, 0x00663409, 0x005d300a, 0x004f2a09, 0x00401e09, 0x00331705, 0x00291507, 0x00241408, 0x001d1205, 0x001c1105, 0x001c1209, 0x001c110b, 0x001b130b, 0x001c140d, 0x001c160e, 0x00171108, 0x00161008, 0x0019140b, 0x001a140b, 0x00181208, 0x00161008, 0x00151008, 0x00141008, 0x0015110c, 0x0014140f, 0x000c0f0b, 0x00080d08, 0x00050f08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00050d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00060c08, 0x00080c08, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00070f08, 0x00070f08, 0x00080e09, 0x00080f0b, 0x000f1410, 0x00151a17, 0x00222624, 0x00313534, 0x00343837, 0x00313534, 0x00303433, 0x002a3030, 0x002a3030, 0x00292c2e, 0x0025282a, 0x00242828, 0x00242828, 0x00262829, 0x00252728, 0x00282a2b, 0x002c2d2f, 0x002f3032, 0x00333334, 0x003a3738, 0x00403b3c, 0x00464040, 0x004e4644, 0x005b4f4d, 0x00645853, 0x0073605c, 0x007b625f, 0x007f6462, 0x00836761, 0x00886862, 0x0085665d, 0x00896860, 0x008d6961, 0x008c645c, 0x008c6250, 0x008c6046, 0x0090603d, 0x00916036, 0x00956031, 0x00996130, 0x009c602e, 0x009c602b, 0x009d6029, 0x009e6026, 0x009d6022, 0x009e601e, 0x009f601b, 0x00a3611a, 0x00a7621b, 0x00aa6218, 0x00ac6216, 0x00b16718, 0x00b46c1a, 0x00b46d1b, 0x00b06a18, 0x00b06918, 0x00b46c1a, 0x00b36918, 0x00b36918, 0x00b56b1a, 0x00b36918, 0x00b26515, 0x00b26515, 0x00b26718, 0x00b46918, 0x00b46a19, 0x00b46a19, 0x00b46a1a, 0x00b36a1b, 0x00b46b1c, 0x00b46b1c, 0x00b46c1c, 0x00b36c1c, 0x00b36c1c, 0x00b16b1b, 0x00b16b1b, 0x00b26b1b, 0x00b46d1e, 0x00b46c1d, 0x00b36c1c, 0x00b26b1c, 0x00b0681b, 0x00b0681b, 0x00ad6618, 0x00ac6418, 0x00a75f14, 0x00a35c12, 0x00a05c13, 0x00a05c15, 0x009e5813, 0x009e5712, 0x009f5813, 0x009f5813, 0x009f5813, 0x00a05914, 0x009e5814, 0x009b5512, 0x009a5714, 0x00985412, 0x00965413, 0x00945211, 0x00935111, 0x008e4e10, 0x008a4d10, 0x00884d11, 0x00884d14, 0x00854b13, 0x00814814, 0x007c4612, 0x0074400f, 0x00703b0c, 0x006b380d, 0x005d2f0a, 0x00502a09, 0x00401f08, 0x00341805, 0x002a1508, 0x00241409, 0x0021150c, 0x0020140c, 0x001c120c, 0x00190f0b, 0x00170f09, 0x0018100a, 0x0019130c, 0x001a140d, 0x0018130a, 0x00181309, 0x00181108, 0x00181108, 0x00181108, 0x00181109, 0x0018120c, 0x0018140f, 0x00181611, 0x000d100c, 0x00080e08, 0x00050f08, 0x00040c06, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00050d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e05, 0x00040d05, 0x00060c05, 0x00060c05, 0x00080c05, 0x00060c05, 0x00060c05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00060c08, 0x00060c08, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00060f08, 0x00070f08, 0x00080e09, 0x00080f0a, 0x00101611, 0x00171c18, 0x002c302e, 0x00313534, 0x00323534, 0x00303433, 0x002e3130, 0x00262b2c, 0x00212526, 0x00242726, 0x00232625, 0x00212526, 0x00242728, 0x00252728, 0x00282a2b, 0x00303133, 0x002d2f30, 0x002d2f30, 0x00313134, 0x00393838, 0x00403b3d, 0x00484243, 0x00534b48, 0x005d5250, 0x00655954, 0x00705d59, 0x007a605e, 0x007e6360, 0x00846863, 0x00876b64, 0x00876a60, 0x008b6a63, 0x008b6861, 0x008d6760, 0x008f6556, 0x008f624c, 0x00906040, 0x00926038, 0x00956032, 0x00986031, 0x009b602d, 0x009c6029, 0x009d6028, 0x009d6025, 0x009c5e20, 0x009b5d1c, 0x009d5d19, 0x00a2601a, 0x00a7621c, 0x00a66017, 0x00a86015, 0x00ab6214, 0x00ae6516, 0x00ac6616, 0x00aa6414, 0x00ab6414, 0x00ae6516, 0x00ae6314, 0x00ae6414, 0x00b16717, 0x00b16717, 0x00b26616, 0x00b36616, 0x00b16616, 0x00b16718, 0x00b06517, 0x00af6416, 0x00b06618, 0x00b36a1c, 0x00b3691c, 0x00b2681c, 0x00b1681b, 0x00af681a, 0x00ae6618, 0x00af6719, 0x00ae6719, 0x00af681a, 0x00b16b1c, 0x00af681a, 0x00af681c, 0x00af681c, 0x00af681c, 0x00ae681c, 0x00ab6418, 0x00a96115, 0x00a55e14, 0x00a05b12, 0x009e5a11, 0x009e5912, 0x009d5812, 0x009e5712, 0x009f5813, 0x009f5813, 0x009e5712, 0x009c5510, 0x009d5714, 0x009e5714, 0x009c5815, 0x00995513, 0x00985413, 0x00965312, 0x00945212, 0x00904f10, 0x008c4d10, 0x008a4c11, 0x00884c13, 0x00854a13, 0x00844815, 0x00804815, 0x0076400e, 0x00703c0c, 0x006d380d, 0x005e2f09, 0x00502a0a, 0x0043200b, 0x00341805, 0x002a1508, 0x0024140a, 0x0021150c, 0x0020150e, 0x001e140f, 0x001a0f0b, 0x00160e09, 0x00150f0a, 0x0015100a, 0x0018130c, 0x0018120b, 0x0018120b, 0x0018110a, 0x00171009, 0x00181208, 0x00181208, 0x001a140c, 0x001d1710, 0x001a1913, 0x000d100c, 0x00080e08, 0x00050f08, 0x00040c06, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c06, 0x00060c06, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060c05, 0x00060c05, 0x00080c05, 0x00060c05, 0x00060c05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00090d0a, 0x00060c08, 0x00060c07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100a, 0x00040c08, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00040c06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00070f0a, 0x0008100c, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00070f08, 0x00080e08, 0x00080f09, 0x00101410, 0x00262b25, 0x0030332f, 0x00343734, 0x002f3130, 0x00282c2b, 0x00222624, 0x00232627, 0x00202424, 0x00252928, 0x001d2020, 0x001e2222, 0x00272a2b, 0x0028292b, 0x00313334, 0x002c2d2f, 0x002a2c2f, 0x002d3032, 0x00313334, 0x00363536, 0x003e3a3c, 0x00494244, 0x00534b4b, 0x005d5150, 0x00685c56, 0x00725f59, 0x007b605c, 0x007e6360, 0x00846764, 0x00856c64, 0x00876a60, 0x008b6a62, 0x008b6861, 0x008c6660, 0x0090645b, 0x00906150, 0x00905f42, 0x00935e39, 0x00965f35, 0x00985f32, 0x009a5f2c, 0x009c5f28, 0x009c5f26, 0x009c5f24, 0x009c5d20, 0x009b5c1b, 0x009c5c18, 0x009e5c16, 0x00a15c17, 0x00a15b16, 0x00a35a14, 0x00a55e14, 0x00a55e14, 0x00a55d13, 0x00a96014, 0x00a96014, 0x00a96014, 0x00aa5f14, 0x00ac6014, 0x00b06418, 0x00ac6214, 0x00b06617, 0x00b3681c, 0x00b2681b, 0x00af6417, 0x00ac6316, 0x00ac6217, 0x00ac6317, 0x00ac6418, 0x00ac6318, 0x00ac6318, 0x00ac6318, 0x00ac6217, 0x00ab6116, 0x00aa6115, 0x00ac6217, 0x00ab6218, 0x00ab6118, 0x00a86016, 0x00a96118, 0x00a96118, 0x00aa6218, 0x00a86117, 0x00a65f14, 0x00a55e14, 0x00a25b12, 0x009f5a12, 0x009e5a12, 0x009c5811, 0x009c5812, 0x009e5912, 0x00a05814, 0x00a05814, 0x009e5712, 0x009f5813, 0x009f5814, 0x009f5814, 0x009c5816, 0x009c5614, 0x00985412, 0x00985411, 0x00955312, 0x00905010, 0x008d4e11, 0x00894b11, 0x00874b13, 0x00864912, 0x00844814, 0x00804714, 0x00784210, 0x0075400f, 0x006f3a0f, 0x0062300a, 0x00582c0c, 0x0048220a, 0x003a1a08, 0x002b1507, 0x0024140a, 0x0020140c, 0x001f140d, 0x001f130e, 0x001e130e, 0x0018120d, 0x0014100a, 0x0015100b, 0x0014100a, 0x0017120c, 0x0016120a, 0x00151008, 0x00171008, 0x00181308, 0x001a1409, 0x001d170d, 0x001f1810, 0x00191710, 0x000c0e09, 0x00070d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c06, 0x00060d04, 0x00060d04, 0x00060d03, 0x00060e01, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00090d0a, 0x00060c08, 0x00060c07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100a, 0x00040c08, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c0a, 0x00040c08, 0x00060e09, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00070f0a, 0x0008100c, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00070f08, 0x00080e08, 0x00080f08, 0x00121711, 0x00252a24, 0x002d312d, 0x002d2f2c, 0x00222422, 0x00202422, 0x00202422, 0x001b1f20, 0x00222526, 0x00242828, 0x00262a2a, 0x002a2d30, 0x002d3034, 0x002f3034, 0x002e2f32, 0x002a2c2d, 0x002b2c30, 0x002d3132, 0x00313334, 0x00363435, 0x00413e40, 0x004c4648, 0x00504848, 0x005a4f4c, 0x006c5d58, 0x0074615c, 0x007b605c, 0x007d635f, 0x00846865, 0x00856c64, 0x00876a60, 0x008b6a63, 0x008b6861, 0x008b645f, 0x0090645c, 0x00906150, 0x00905f42, 0x00935e39, 0x00955e34, 0x00985d31, 0x009b5e2c, 0x009c5e28, 0x009d5e26, 0x009d5d24, 0x009c5c20, 0x009b5b19, 0x009a5a16, 0x009b5914, 0x009c5815, 0x009f5814, 0x00a05814, 0x009f5912, 0x00a05911, 0x00a35b14, 0x00a55d16, 0x00a65e16, 0x00a65e16, 0x00a45b12, 0x00a75d14, 0x00a85f15, 0x00a65d11, 0x00a75e12, 0x00aa6016, 0x00aa6218, 0x00a96118, 0x00ab6419, 0x00a96119, 0x00a55d15, 0x00a75f16, 0x00a86017, 0x00a86017, 0x00a86018, 0x00a65e15, 0x00a96119, 0x00a96118, 0x00a55d14, 0x00a45c14, 0x00a45c15, 0x00a55f18, 0x00a45e17, 0x00a45e17, 0x00a45e17, 0x00a45f17, 0x00a45d16, 0x00a15c14, 0x00a05912, 0x009e5813, 0x009c5814, 0x009b5814, 0x009c5812, 0x009c5913, 0x009d5814, 0x009e5915, 0x009f5a16, 0x009f5a16, 0x009e5916, 0x009d5816, 0x009d5816, 0x009c5614, 0x00985412, 0x00985411, 0x00955412, 0x00915111, 0x008f5013, 0x00894d13, 0x00874b13, 0x00854811, 0x00844814, 0x00804714, 0x00794210, 0x00784311, 0x00703c0f, 0x0066340d, 0x00582b0a, 0x004b2208, 0x0041200a, 0x002d1506, 0x00251408, 0x001e120b, 0x001c130c, 0x001e140c, 0x001e160d, 0x001e160e, 0x001c140e, 0x00150f08, 0x00171009, 0x0018120b, 0x0018100a, 0x0018110a, 0x0019140b, 0x001b150c, 0x001c170c, 0x00201910, 0x001c160f, 0x0013110b, 0x00080c07, 0x00040b05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d03, 0x00060d03, 0x00060d04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00090d0a, 0x00060c08, 0x00060c07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100a, 0x00040c08, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00060e08, 0x00051007, 0x00051007, 0x00051007, 0x00040e05, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070d08, 0x00070d08, 0x00080c08, 0x000a0e09, 0x00151915, 0x00242823, 0x00292d29, 0x002a2c2a, 0x00222422, 0x00212524, 0x00202423, 0x00272b2b, 0x00292c2d, 0x002b2e2f, 0x002c3030, 0x002b2e30, 0x00272a2c, 0x00292b2e, 0x0025282b, 0x0026282b, 0x002b2c30, 0x002c2f31, 0x002e3030, 0x003a383b, 0x00434043, 0x00484243, 0x0052494a, 0x00605452, 0x006c5d58, 0x0074605c, 0x007b605c, 0x007d625e, 0x00836864, 0x00866b64, 0x00886a62, 0x008c6b64, 0x008c6864, 0x008c6660, 0x008f645b, 0x00906150, 0x008f5d41, 0x00925d3a, 0x00955e34, 0x00985d31, 0x009b5e2c, 0x009c5e29, 0x009d5e25, 0x009a5b20, 0x0099591b, 0x00995918, 0x00995915, 0x00995817, 0x009a5716, 0x009b5415, 0x009c5414, 0x009c5614, 0x009b5613, 0x009c5714, 0x009e5815, 0x009e5814, 0x009f5814, 0x009d5712, 0x00a05813, 0x00a05913, 0x00a05a12, 0x00a05911, 0x00a05912, 0x00a05912, 0x00a45c15, 0x00a75f18, 0x00a65e18, 0x00a55d17, 0x00a45b15, 0x00a45c15, 0x00a55c16, 0x00a65e18, 0x00a65e18, 0x00a75f18, 0x00a45c16, 0x00a35a14, 0x00a45b17, 0x00a45c18, 0x00a35c18, 0x00a45c18, 0x00a35c17, 0x00a35c17, 0x00a15c17, 0x00a05914, 0x009f5813, 0x009c5411, 0x009a5412, 0x00995513, 0x00995514, 0x009a5714, 0x009a5614, 0x009a5513, 0x009c5614, 0x009c5815, 0x009e5817, 0x009e5818, 0x009c5716, 0x009b5514, 0x00995412, 0x00955210, 0x00955210, 0x00945110, 0x00925212, 0x008f5013, 0x00894d12, 0x00874b13, 0x00844912, 0x00814814, 0x007f4814, 0x007e4816, 0x007a4413, 0x00743f12, 0x00683710, 0x00633413, 0x00502409, 0x003f1a04, 0x00301404, 0x00261407, 0x001f130c, 0x001d110b, 0x001c120a, 0x001e140c, 0x001f150c, 0x0020160c, 0x001c140b, 0x001b1308, 0x001b1208, 0x001a1008, 0x001b1309, 0x001c140a, 0x001c140b, 0x001c140d, 0x001b130e, 0x0017120d, 0x0011100c, 0x00080c08, 0x00050c06, 0x00040d07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c08, 0x00060c05, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c08, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080e0a, 0x00060c08, 0x00060c07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100a, 0x00040c08, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00040c08, 0x00040c08, 0x00040d07, 0x00061007, 0x00051007, 0x00051007, 0x00040e05, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x0004100a, 0x0004100a, 0x0004100a, 0x0005100a, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d08, 0x0009100a, 0x00151a14, 0x00242822, 0x00272b28, 0x00272927, 0x00282b29, 0x00242827, 0x002e3131, 0x002f3334, 0x002c3030, 0x00242829, 0x00222526, 0x00272a2c, 0x00242729, 0x0027282b, 0x002a2c2e, 0x002d2f32, 0x002a2c2f, 0x002c2f31, 0x00343537, 0x003c3a3c, 0x00434041, 0x00484344, 0x00554c4d, 0x00645858, 0x006f5f5c, 0x0076605c, 0x007c615d, 0x007d625f, 0x00836864, 0x00856a64, 0x00886a63, 0x008c6b64, 0x008c6964, 0x008d6760, 0x008f6459, 0x00906150, 0x008f5d41, 0x00925d3a, 0x00955c34, 0x00975c30, 0x00995c2b, 0x009a5c28, 0x009a5c23, 0x0098581c, 0x00955718, 0x00965515, 0x00965714, 0x00955714, 0x00965515, 0x00985314, 0x00985314, 0x00985413, 0x00985413, 0x00985414, 0x009a5615, 0x00995513, 0x00995413, 0x00995413, 0x009c5814, 0x009d5814, 0x009d5814, 0x009d5814, 0x009d5814, 0x009f5813, 0x009f5813, 0x009f5813, 0x009f5813, 0x009d5712, 0x009c5512, 0x009c5612, 0x009d5713, 0x009f5814, 0x00a05814, 0x00a05915, 0x00a05915, 0x00a05814, 0x009f5916, 0x00a05a18, 0x00a05c18, 0x009f5a18, 0x009e5a15, 0x009d5814, 0x009c5815, 0x009a5513, 0x00985310, 0x00985311, 0x00985313, 0x00975414, 0x00955414, 0x00945413, 0x00965412, 0x00955213, 0x00965314, 0x00985515, 0x00995718, 0x009a5718, 0x00985414, 0x00985413, 0x00985413, 0x00945210, 0x00945110, 0x00945110, 0x00925212, 0x00905114, 0x008b4e11, 0x00884c14, 0x00834a12, 0x007f4611, 0x007c4512, 0x007c4814, 0x007d4816, 0x00764012, 0x006f3c13, 0x00643411, 0x00582a0c, 0x00472108, 0x00301503, 0x00271306, 0x001f140c, 0x001c120b, 0x00181008, 0x00180f07, 0x001a1208, 0x001c1409, 0x001d150b, 0x0020180c, 0x001d140b, 0x001b1308, 0x001c1208, 0x001c1309, 0x001b120b, 0x0018120c, 0x0018110c, 0x00171210, 0x0010110d, 0x00080c08, 0x00050c06, 0x00040d07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00070e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c08, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c09, 0x00060c08, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060c08, 0x000b110d, 0x00101612, 0x00141916, 0x00212423, 0x00242625, 0x00252726, 0x00282c2c, 0x00303434, 0x002d3033, 0x00232628, 0x00242729, 0x002a2d30, 0x00242729, 0x0024282a, 0x0025272a, 0x002c2c30, 0x002c2d30, 0x002c2e31, 0x0034383a, 0x0035383b, 0x00383639, 0x00403c3d, 0x00444041, 0x005a5252, 0x00675959, 0x00705e5c, 0x00755f5d, 0x007b605e, 0x007f6460, 0x00846764, 0x00836864, 0x00886a66, 0x008f6d6c, 0x00906c68, 0x00906a65, 0x0091665c, 0x00926451, 0x00916044, 0x00925d3a, 0x00945c31, 0x00985c30, 0x0096592a, 0x00955826, 0x00955920, 0x00935619, 0x00915416, 0x00905113, 0x008d5010, 0x008e5010, 0x00905010, 0x00914e0f, 0x00914d0e, 0x00904e0c, 0x00925010, 0x00955311, 0x00965514, 0x00975514, 0x00955412, 0x00945211, 0x00955412, 0x00985412, 0x00985311, 0x00995412, 0x00995412, 0x009a5411, 0x009b5410, 0x009a5310, 0x009a5310, 0x009a5412, 0x00985311, 0x0096500f, 0x00985311, 0x009a5513, 0x009c5614, 0x009b5514, 0x009a5413, 0x00995413, 0x00975514, 0x00985716, 0x00985716, 0x00975614, 0x00975614, 0x00965413, 0x00945414, 0x00935013, 0x00914e11, 0x00924e11, 0x00935014, 0x00904f13, 0x008a4b0f, 0x00884c0e, 0x008b4e10, 0x008c4d10, 0x008b4c0e, 0x008c4d10, 0x008e5012, 0x00905013, 0x00915113, 0x00925012, 0x00915012, 0x00945314, 0x00975618, 0x00965517, 0x00925214, 0x008f5010, 0x008b4d0f, 0x00884c13, 0x00834914, 0x007e4613, 0x007c4514, 0x007d4814, 0x007d4612, 0x00794211, 0x00723e10, 0x006c3c12, 0x005a2c0a, 0x004a2306, 0x00341804, 0x00281305, 0x001e1408, 0x001c1308, 0x00191208, 0x00151009, 0x00130d08, 0x00140f08, 0x0019130c, 0x001b140e, 0x001d140c, 0x001e140c, 0x0020140d, 0x0024140f, 0x00191008, 0x0015110a, 0x0016110c, 0x00181310, 0x0010120c, 0x00070e06, 0x00040c04, 0x00040e05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e07, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040c06, 0x00030c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040f08, 0x00040f08, 0x00060e08, 0x00070f0a, 0x0008100c, 0x000a0f0c, 0x00141815, 0x001c1e1d, 0x00222424, 0x002b2e2f, 0x002c2f30, 0x0025282b, 0x002b2e30, 0x00282c2e, 0x00232628, 0x001d2023, 0x0025272a, 0x00282a2d, 0x002f3033, 0x002c2d30, 0x002c2d31, 0x00313435, 0x00323437, 0x00353435, 0x003b3838, 0x00484444, 0x00595150, 0x00645756, 0x00725f5c, 0x0078605d, 0x007c615d, 0x00806561, 0x00846865, 0x00846965, 0x00896c69, 0x0090706f, 0x00916d6a, 0x00916b67, 0x0094685c, 0x00946654, 0x00946248, 0x00945f3c, 0x00985f36, 0x0094592e, 0x00905628, 0x00905624, 0x00905620, 0x008d541a, 0x008c5217, 0x008a4e14, 0x00884d11, 0x008a4e10, 0x008c4c10, 0x008c4b0f, 0x008c4b0e, 0x008c4c0e, 0x008f4e10, 0x00905011, 0x00915112, 0x00915011, 0x00905010, 0x00904f10, 0x00915112, 0x00955111, 0x00975011, 0x00975011, 0x00975011, 0x00965010, 0x00965010, 0x00965010, 0x0095500f, 0x00965110, 0x00955112, 0x00945010, 0x00945010, 0x00945111, 0x00965212, 0x00945111, 0x00945010, 0x00945010, 0x00905112, 0x00925414, 0x008e5011, 0x008e5011, 0x008e5010, 0x008d5012, 0x008c4e14, 0x00884b11, 0x00884810, 0x00884910, 0x00874a12, 0x007f440c, 0x00753c05, 0x00764006, 0x00784108, 0x00773e05, 0x00773d04, 0x00794006, 0x007c4409, 0x0080440a, 0x00804409, 0x00854a0e, 0x00884c10, 0x008c4f13, 0x00905215, 0x008f5114, 0x008b4e11, 0x008a4e11, 0x00894d11, 0x00874c13, 0x00834914, 0x00804814, 0x007e4817, 0x007f4814, 0x007c4511, 0x007a4312, 0x00754013, 0x00703f13, 0x0063330c, 0x00522a0a, 0x003a1c04, 0x002e1807, 0x00201305, 0x001d1406, 0x001a1308, 0x00171208, 0x00161008, 0x00140e08, 0x00160f08, 0x0019120b, 0x001b1109, 0x001e140b, 0x00251810, 0x002c1a13, 0x0020140c, 0x001a140a, 0x00171109, 0x0019150f, 0x0011130c, 0x00080f07, 0x00040c04, 0x00040e05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00030c06, 0x00030c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050d09, 0x00060c08, 0x00080e0b, 0x00181c19, 0x00282828, 0x002d2d2d, 0x002b2c2e, 0x00282c2c, 0x00272a2c, 0x00212728, 0x00212427, 0x00232628, 0x002a2b2e, 0x002c2e31, 0x002c2c30, 0x002c2d30, 0x002c2e30, 0x00333435, 0x00303437, 0x002e3031, 0x00353334, 0x003e3a3a, 0x004c4646, 0x005d5453, 0x00675956, 0x0073605c, 0x0078615c, 0x007b625d, 0x007e6360, 0x00846865, 0x00856b67, 0x008d706d, 0x00937372, 0x00916e6c, 0x008f6a65, 0x0092675c, 0x00926451, 0x00936248, 0x00945f3d, 0x00915a34, 0x008d562d, 0x008c5428, 0x00885021, 0x00834e1c, 0x00804c18, 0x00824d18, 0x00844e18, 0x00834c15, 0x00844b13, 0x00864a14, 0x00884a14, 0x00884912, 0x00894b10, 0x008c4d12, 0x008c4d12, 0x008b4c11, 0x008c4c11, 0x008a4c10, 0x008c4d11, 0x008d4e13, 0x00914f14, 0x00935014, 0x00945014, 0x00945015, 0x00945114, 0x00945114, 0x00935013, 0x00935013, 0x00925014, 0x00914f14, 0x00904e11, 0x00904e11, 0x00904e11, 0x008f4d10, 0x008f4d10, 0x008f4d10, 0x008e4d11, 0x00894d10, 0x00894e12, 0x00894f11, 0x00864c0f, 0x00844b10, 0x00824810, 0x007d4410, 0x007c4211, 0x007c4312, 0x00784010, 0x00703b0c, 0x006c380a, 0x006a380b, 0x0067380a, 0x00653408, 0x00673508, 0x00673506, 0x00683706, 0x006c3a07, 0x00713d09, 0x0077400d, 0x00743f0b, 0x00763f0a, 0x007a420d, 0x00804610, 0x007c430d, 0x007c420c, 0x00814812, 0x00844b15, 0x00854b14, 0x00844b14, 0x00834b18, 0x007e4918, 0x007d4714, 0x007c4410, 0x00794211, 0x00764214, 0x00724011, 0x006b3a0d, 0x00582e08, 0x00412105, 0x00311904, 0x00251605, 0x00201404, 0x001c1104, 0x00191206, 0x001a1207, 0x001a1209, 0x001b1109, 0x001c1208, 0x001c1107, 0x001e1006, 0x0025140c, 0x0027140a, 0x0025150c, 0x0020150c, 0x001c140c, 0x0019160d, 0x0010140b, 0x00071007, 0x00051008, 0x00040f08, 0x00040f08, 0x00060e06, 0x00060e06, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00080f0a, 0x000c110e, 0x001e2120, 0x00303131, 0x002b2b2b, 0x00282a2b, 0x0025282a, 0x0026292c, 0x00272c2e, 0x002b2e30, 0x002b2e30, 0x002c2e31, 0x002e2d31, 0x00292b2e, 0x002d2f32, 0x00303233, 0x00303234, 0x002d3030, 0x00303334, 0x00333032, 0x00403c3c, 0x00514a49, 0x00615856, 0x006b5d5a, 0x0074605c, 0x007c6460, 0x007c635f, 0x007e635f, 0x00846a66, 0x00886c69, 0x00927572, 0x00937373, 0x0091706c, 0x00906c67, 0x0090665a, 0x0090614f, 0x00906045, 0x00905d3c, 0x008b5632, 0x00804c26, 0x007d4920, 0x007a461c, 0x00764516, 0x00714210, 0x006f3f0e, 0x00754413, 0x007a4815, 0x007b4612, 0x007c4512, 0x007f4513, 0x00804411, 0x0081460f, 0x00844810, 0x00854912, 0x00844810, 0x00844910, 0x00834710, 0x00844910, 0x00864b12, 0x008a4c13, 0x008c4c13, 0x008c4c13, 0x008c4c14, 0x008c4d13, 0x008c4e13, 0x008d4e13, 0x008f4e14, 0x008d4e13, 0x008a4b12, 0x00884911, 0x00884911, 0x00884911, 0x00884810, 0x00884810, 0x00884810, 0x00864810, 0x00824a10, 0x007f480f, 0x007d470e, 0x007a440c, 0x0075400c, 0x00723d0c, 0x00703c0d, 0x006c380a, 0x00663409, 0x00613108, 0x005c2d05, 0x00582b04, 0x00542a04, 0x00542c08, 0x00582d09, 0x00582d08, 0x00582d06, 0x005b3006, 0x00603408, 0x00643409, 0x0068380c, 0x0068380a, 0x00683808, 0x00683607, 0x00673303, 0x006c3808, 0x00723f0e, 0x007b4515, 0x007d4816, 0x007f4813, 0x00844c16, 0x00844d1a, 0x007e4917, 0x007c4614, 0x007b4310, 0x00784110, 0x00774213, 0x00764314, 0x006e3c0c, 0x0062350c, 0x00492606, 0x00351901, 0x00291604, 0x00231405, 0x00211406, 0x00201407, 0x00201408, 0x00201409, 0x0023170c, 0x0023170c, 0x0024150c, 0x0026150b, 0x0029150b, 0x002e180c, 0x00321e13, 0x00291910, 0x0020140b, 0x0018140b, 0x000b1007, 0x00071007, 0x00051008, 0x00031008, 0x00040f08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e06, 0x00060e06, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0009100c, 0x00151a17, 0x00232524, 0x00282828, 0x00222222, 0x00242726, 0x00242728, 0x00262b2d, 0x00282d2f, 0x0024282b, 0x00232428, 0x0029292c, 0x002c2b2f, 0x002c2e30, 0x002d2f30, 0x002f3032, 0x002e3030, 0x002d2f30, 0x002f2f2f, 0x00323031, 0x00433e3d, 0x00514a49, 0x00635958, 0x006d605c, 0x0076645f, 0x007e6761, 0x007d6460, 0x007d625e, 0x00856b67, 0x00886e6b, 0x00917572, 0x00917471, 0x00906f6a, 0x008c6963, 0x008d6758, 0x008b6250, 0x00865940, 0x00845637, 0x00825534, 0x00764926, 0x006e411e, 0x006c3f1d, 0x00714421, 0x006d401c, 0x00683b18, 0x00683a16, 0x006c3f14, 0x006e3f10, 0x00713f10, 0x00733e10, 0x00743d0f, 0x00753c0d, 0x00783e0f, 0x007b4112, 0x007f4515, 0x007b420f, 0x007b420d, 0x007e450f, 0x0080480f, 0x00834910, 0x00834910, 0x00844910, 0x00844910, 0x0084490f, 0x00884c11, 0x0084480d, 0x00874a0e, 0x00894c11, 0x00884812, 0x00854712, 0x00814411, 0x00824513, 0x00844713, 0x00834411, 0x007f440f, 0x007a410c, 0x0077400c, 0x0077400d, 0x0074400f, 0x006c3a0c, 0x0065360b, 0x0060330b, 0x005d330c, 0x0058300b, 0x00542b0a, 0x00522b0b, 0x004f2908, 0x004c2907, 0x004c2906, 0x004f2808, 0x00502808, 0x00542807, 0x00542805, 0x00542806, 0x005d320e, 0x00643814, 0x00643712, 0x005f340e, 0x005e320b, 0x0060310b, 0x0060320c, 0x0064340c, 0x0067380e, 0x006e3e12, 0x00744114, 0x00784413, 0x007d4815, 0x007f4918, 0x007e4918, 0x007b4714, 0x00794310, 0x00784211, 0x00784212, 0x00764212, 0x00743d0d, 0x006d3a10, 0x00542b09, 0x00381800, 0x002c1304, 0x00281408, 0x00251509, 0x00261507, 0x00261508, 0x002a190d, 0x002e190f, 0x002c150c, 0x002c150c, 0x00311b10, 0x00341d10, 0x00331b0d, 0x003c2518, 0x002c1a0f, 0x001e1308, 0x00131006, 0x00080d04, 0x00060e08, 0x00040f08, 0x00031008, 0x00040f08, 0x00070f09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060d0b, 0x00060d0b, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00080f08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040c06, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x000f130b, 0x000f130b, 0x0014180d, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130b, 0x000f130b, 0x000f130b, 0x0014180f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e06, 0x00060f04, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x000b110d, 0x00181e1a, 0x00242624, 0x00282828, 0x00242424, 0x00242625, 0x00242527, 0x001c2124, 0x001b2021, 0x001f2324, 0x00282a2d, 0x002d2c30, 0x00323135, 0x00323234, 0x00303133, 0x002d2f30, 0x002c2e2f, 0x00262828, 0x002c2c2c, 0x00373333, 0x003f3a3a, 0x00544d4e, 0x00665c5c, 0x00716260, 0x00796864, 0x007e6764, 0x00806863, 0x00806561, 0x00846865, 0x00856c68, 0x008c726e, 0x008f706e, 0x00886864, 0x0084645c, 0x007c594a, 0x00795441, 0x007c563e, 0x00754d33, 0x00704729, 0x00684020, 0x00643c1c, 0x00633a1c, 0x00653d1e, 0x00673d1e, 0x0064391a, 0x00603414, 0x005e330e, 0x0063370d, 0x0065370c, 0x0067380d, 0x0069360c, 0x006a360b, 0x006c360b, 0x006e380c, 0x00713b0f, 0x00733c0c, 0x00733d0b, 0x0077400b, 0x0078420c, 0x0078420c, 0x0078410c, 0x007c430d, 0x007c440c, 0x0080450f, 0x00844910, 0x0081460e, 0x0083480e, 0x00854911, 0x00844711, 0x00804510, 0x007b400f, 0x007b4010, 0x007a3f10, 0x00763d0d, 0x00733c0c, 0x006e3b09, 0x006c3808, 0x006b3909, 0x0068390c, 0x0060340a, 0x00592f08, 0x00552c09, 0x00502909, 0x004c2809, 0x004a270a, 0x004a270c, 0x0049280c, 0x004a280a, 0x004b2a09, 0x004c2909, 0x004f2809, 0x00512708, 0x00522807, 0x00532908, 0x00572d0a, 0x00582e0b, 0x005c3310, 0x005c340e, 0x0059300a, 0x00582d08, 0x00582c08, 0x005c2f09, 0x0060340c, 0x0064360c, 0x00693a0c, 0x006f3f10, 0x00754312, 0x007a4516, 0x007c4617, 0x007a4513, 0x00784210, 0x00784212, 0x00794314, 0x00784414, 0x00784010, 0x00733d10, 0x005c300e, 0x003b1b02, 0x002b0f01, 0x00261105, 0x00261409, 0x002c180c, 0x002f1b0d, 0x00321e10, 0x0030180c, 0x0034180d, 0x0031180c, 0x00371d11, 0x00382012, 0x00301808, 0x00381f13, 0x00301d12, 0x001a0f04, 0x00100c03, 0x00080d04, 0x00060e08, 0x00040f08, 0x00031008, 0x00040f08, 0x00070f0a, 0x00050d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060f08, 0x00070e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x000f130b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00071007, 0x00040e04, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x000a110c, 0x001b201c, 0x00242624, 0x00242323, 0x00201f20, 0x001d1e1e, 0x00202123, 0x00202426, 0x00222729, 0x00272a2c, 0x00303134, 0x002e2d31, 0x00303033, 0x00323032, 0x00303032, 0x002b2b2b, 0x002a2b2b, 0x00282828, 0x002b2b2a, 0x00343030, 0x003e3939, 0x00565050, 0x006b5f60, 0x00756665, 0x007b6864, 0x007e6864, 0x00816864, 0x00806664, 0x00816866, 0x00846d68, 0x008c736f, 0x008a6e6c, 0x007c5f59, 0x00785950, 0x006d503f, 0x006c4d3a, 0x00694834, 0x006b4630, 0x00654328, 0x00664428, 0x00634225, 0x005c3b1e, 0x00603c1f, 0x00603d20, 0x00603c1e, 0x005c3818, 0x005c3613, 0x005c3612, 0x005c340e, 0x005b310c, 0x00643711, 0x0063360f, 0x0061340b, 0x0063340c, 0x0063350c, 0x00693b0f, 0x006d3e10, 0x006c3d0d, 0x006f3f0c, 0x00723e0e, 0x00743e0c, 0x0075400e, 0x00794110, 0x007b4310, 0x007b420f, 0x007b420e, 0x007c430e, 0x007c440e, 0x007d4410, 0x007a4210, 0x00743d0e, 0x006f390c, 0x006e3810, 0x0069360f, 0x0068380e, 0x0061340a, 0x005e3207, 0x005d3308, 0x005d350c, 0x005a340f, 0x00552f0e, 0x00522c0f, 0x004e2a10, 0x004b2910, 0x0046240b, 0x0045230c, 0x0045240c, 0x0048280e, 0x004b2910, 0x00502c14, 0x00522a10, 0x00502809, 0x00532909, 0x00542808, 0x00552908, 0x005d310f, 0x00643816, 0x005c300d, 0x00572c09, 0x00562c08, 0x005b300c, 0x005c300d, 0x005a2f0a, 0x005d330b, 0x00603409, 0x0064390c, 0x006c3e10, 0x00754416, 0x00794418, 0x00794314, 0x00784112, 0x00784112, 0x00794314, 0x00794412, 0x0078410f, 0x00703b0b, 0x00633711, 0x00442509, 0x002f1301, 0x00261106, 0x0027140c, 0x0029140a, 0x002c160b, 0x002f170b, 0x00321708, 0x00371b09, 0x00341808, 0x003f2517, 0x00351c0e, 0x00301609, 0x00381f14, 0x00342016, 0x00180c02, 0x000f0c04, 0x00080e07, 0x00051008, 0x0005100a, 0x0004100a, 0x0005100a, 0x00070f08, 0x00050d06, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040d07, 0x00050d07, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180b, 0x00191c0b, 0x0014180a, 0x00191c0a, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x00191c0a, 0x00141809, 0x00191c0b, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00071007, 0x00040e04, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e06, 0x00060e06, 0x00060e06, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00080f0a, 0x00121714, 0x00212321, 0x00232222, 0x00222222, 0x00262827, 0x00292b2c, 0x002c2f31, 0x002d3334, 0x00323538, 0x00343538, 0x00323034, 0x00323134, 0x00353336, 0x002c2b2d, 0x002b2b2b, 0x002b2b2b, 0x00282928, 0x002c2c2a, 0x00363332, 0x00413d3c, 0x00595352, 0x006e6262, 0x00796866, 0x007c6864, 0x007f6864, 0x00806964, 0x00806664, 0x00826967, 0x00846d68, 0x00846c69, 0x007c615e, 0x00755953, 0x006f5348, 0x006e5440, 0x006e5440, 0x00674a37, 0x0061422d, 0x005b3e25, 0x00573a20, 0x005a3c20, 0x005c3e22, 0x005a3c1e, 0x00583a1c, 0x0058391b, 0x00573718, 0x00583817, 0x00583513, 0x00573211, 0x00593412, 0x00583210, 0x0057300d, 0x0058320e, 0x005c3410, 0x005c3410, 0x005e350f, 0x00613810, 0x0063380d, 0x00643a0c, 0x0069380e, 0x006c380e, 0x006c3910, 0x00703b12, 0x00723d0f, 0x00743e0c, 0x0075400f, 0x00773f0f, 0x0076400c, 0x0074400c, 0x00713f0c, 0x006d3c0d, 0x0066370c, 0x00623410, 0x005c310e, 0x005a300d, 0x0059340c, 0x00573109, 0x00553209, 0x00563610, 0x00563614, 0x004d2d0f, 0x004a2a0e, 0x0044240c, 0x003d2009, 0x003c1d06, 0x003c1b04, 0x003c1d04, 0x003f2008, 0x0041220c, 0x00482511, 0x0049240c, 0x004e2708, 0x00542a08, 0x005b2f0d, 0x005c2f0d, 0x005a2e0c, 0x005a2f0c, 0x005c300c, 0x005d320d, 0x005d330c, 0x00603410, 0x005c3310, 0x00542b05, 0x005b310b, 0x005d340a, 0x0062390d, 0x00693f11, 0x00734317, 0x00754117, 0x00784014, 0x00774011, 0x00784112, 0x007a4414, 0x007b4514, 0x007b440d, 0x00733d0a, 0x00693c15, 0x004a2b0c, 0x00321701, 0x00271105, 0x0028150d, 0x0029140d, 0x002e160d, 0x0033190d, 0x00381c0b, 0x003b1e08, 0x003d230f, 0x003a2111, 0x002c1406, 0x002c1408, 0x00361f14, 0x00382419, 0x00140b00, 0x00100c06, 0x00081008, 0x00051008, 0x0005100a, 0x0004100a, 0x0005100a, 0x00071008, 0x00050e04, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00040c06, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050f08, 0x00050f08, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180e, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x001d200a, 0x00191c09, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2008, 0x00202309, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d200a, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c0a, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d08, 0x00040d08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00050e06, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00070e09, 0x000a100c, 0x00181c1a, 0x00252726, 0x00292b2a, 0x002c2d2c, 0x002a2e2c, 0x002b2e2f, 0x002e3132, 0x00353738, 0x0039393b, 0x00353235, 0x00343033, 0x002f2d2e, 0x002c2a2b, 0x00302f2f, 0x00302f2e, 0x00302e2d, 0x00323030, 0x00383735, 0x00413e3e, 0x005c5454, 0x00736464, 0x007b6967, 0x007d6964, 0x007f6964, 0x00816866, 0x00806865, 0x00816a67, 0x00846d6b, 0x00836b6a, 0x007a615d, 0x00735a50, 0x006a5345, 0x0067503c, 0x0068503b, 0x00664c39, 0x00604530, 0x0062472f, 0x00604429, 0x005d4024, 0x005a3b1d, 0x00533517, 0x00503314, 0x004e3214, 0x00513415, 0x00523412, 0x00583714, 0x005b3918, 0x00543314, 0x004d2c0d, 0x004e2c0c, 0x00523010, 0x00523010, 0x00543412, 0x0054340f, 0x0058350e, 0x0059360c, 0x005b360b, 0x005f340a, 0x0063340a, 0x0065360b, 0x006a390d, 0x006c3a10, 0x00703c12, 0x00764214, 0x007a4514, 0x00794311, 0x00743e0d, 0x00703c0c, 0x006b3c0e, 0x0062360a, 0x0059310b, 0x00552f0a, 0x00573410, 0x00573411, 0x00573310, 0x00502d0c, 0x004c2a0c, 0x00442609, 0x003b2007, 0x00381c08, 0x00341a08, 0x00331a09, 0x00361c0c, 0x00341a08, 0x00391e0b, 0x00391f0b, 0x00442917, 0x00482c18, 0x0050331a, 0x00503111, 0x0054340e, 0x005a340e, 0x005c340e, 0x005c320d, 0x005e3410, 0x005e350e, 0x005e350e, 0x005e350e, 0x0060340f, 0x005b310c, 0x005b310c, 0x005c320d, 0x005d340c, 0x005e3710, 0x00643c14, 0x006b3e15, 0x006e3f14, 0x00734012, 0x00784112, 0x00794314, 0x007b4516, 0x007d4816, 0x007e4711, 0x007a4310, 0x006f3f15, 0x00562d0f, 0x00381700, 0x002b1304, 0x0025140c, 0x0027130d, 0x002e170c, 0x00351c0f, 0x003e200e, 0x0040200c, 0x00412713, 0x00301808, 0x00281104, 0x00281007, 0x00382016, 0x00372418, 0x00130d03, 0x000a1007, 0x00051008, 0x0005100a, 0x00060f0a, 0x0005100a, 0x0004100a, 0x00051007, 0x00040e04, 0x00040f04, 0x00040f06, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00050e07, 0x00050e07, 0x00060e08, 0x00050e07, 0x00040f06, 0x00050f07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00030c08, 0x00030c08, 0x00030c08, 0x00030c08, 0x00040e08, 0x00040e08, 0x00040d08, 0x00040d08, 0x00040e08, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060f09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00060e08, 0x00060e07, 0x00060e08, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00030c04, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00060d07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00050c06, 0x00040c07, 0x00070e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2009, 0x001d2008, 0x001d2008, 0x00202308, 0x00202308, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202308, 0x00202308, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c09, 0x00191c0a, 0x00191c0a, 0x00191c0c, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d05, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x000b100d, 0x001c201f, 0x002c302f, 0x00323534, 0x00303434, 0x00303334, 0x00333737, 0x00343536, 0x00313032, 0x002c282a, 0x00292528, 0x002e2c2c, 0x00333030, 0x00343231, 0x00353432, 0x00333130, 0x00353432, 0x00393836, 0x00413e3e, 0x005f5454, 0x00746463, 0x007c6966, 0x007d6a64, 0x00806964, 0x00816866, 0x00826967, 0x00806966, 0x00806865, 0x007a6261, 0x00745c58, 0x006f584f, 0x00695445, 0x0066503d, 0x0068503c, 0x00664c38, 0x00614630, 0x005e4129, 0x005d4024, 0x00604022, 0x00684427, 0x00644121, 0x005c3c1d, 0x00563818, 0x00543716, 0x00543714, 0x00563816, 0x005a3c1c, 0x0056381b, 0x00503114, 0x0046290d, 0x00422509, 0x0043260a, 0x00452a0c, 0x004c3210, 0x00533612, 0x00583914, 0x005a3912, 0x005c360e, 0x005d340c, 0x0062380c, 0x0064380c, 0x0068380e, 0x006d3c14, 0x00733f13, 0x00764010, 0x0078400f, 0x00753c0c, 0x00703b0d, 0x0068380c, 0x005f340a, 0x0059310a, 0x00542f0a, 0x00522f0e, 0x00502f10, 0x004c2b0c, 0x00462408, 0x00402108, 0x00371a03, 0x00341c07, 0x002f1907, 0x00291707, 0x00271708, 0x00261609, 0x00281708, 0x00281507, 0x002e1b0b, 0x002f1c0c, 0x0034200d, 0x003c240f, 0x00442c10, 0x004c3112, 0x00533313, 0x00563312, 0x00583210, 0x005b3512, 0x005b3611, 0x005c3710, 0x005c3510, 0x005e3410, 0x005c320d, 0x005c320d, 0x005b310c, 0x005b310c, 0x005b330f, 0x00603614, 0x00673b14, 0x006c3f13, 0x00734113, 0x007a4414, 0x007b4514, 0x007c4516, 0x007e4817, 0x007e4713, 0x007c4411, 0x00724016, 0x00603213, 0x00401c04, 0x002c1403, 0x00241309, 0x0024130a, 0x002b1609, 0x00331c0c, 0x003f2010, 0x00472615, 0x00381b09, 0x002c1301, 0x002b1003, 0x002c1108, 0x003d2418, 0x00362317, 0x00121005, 0x00081209, 0x0004110b, 0x0006100c, 0x00080f0b, 0x0005100a, 0x0004100a, 0x00040f08, 0x00040e05, 0x00040f05, 0x00040f06, 0x00040d07, 0x00040c08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00050e07, 0x00040f05, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00060d07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00040c06, 0x00030d06, 0x00051008, 0x00040f08, 0x00040f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180e, 0x0014180b, 0x0014180b, 0x00191c0b, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2008, 0x001d2008, 0x00202308, 0x00202309, 0x00202309, 0x0024250b, 0x0024250b, 0x0024250b, 0x0024250c, 0x0024250c, 0x0026280c, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280c, 0x0026280c, 0x0024250c, 0x0024250c, 0x0024250b, 0x0024250b, 0x0024250b, 0x0024250b, 0x00202309, 0x00202309, 0x00202308, 0x001d2008, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c09, 0x00191c0a, 0x00191c0c, 0x0014180b, 0x0014180c, 0x0014180d, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00050d08, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00070f0b, 0x00111815, 0x00282d2b, 0x00343936, 0x00313534, 0x00303334, 0x00363638, 0x00373838, 0x00302e30, 0x00322e30, 0x00332f30, 0x00333030, 0x00343030, 0x003a3535, 0x00393635, 0x003b3938, 0x00363433, 0x00353331, 0x00403c3b, 0x00605456, 0x00746363, 0x007d6966, 0x00806a64, 0x00816965, 0x00826967, 0x00826868, 0x007e6764, 0x007a6460, 0x00735c59, 0x006d5652, 0x006e5850, 0x00685348, 0x00654e3f, 0x00674e3c, 0x00674d38, 0x00644830, 0x005f4226, 0x005e3d20, 0x00623e1e, 0x00643e1e, 0x00623c1c, 0x005d3b1c, 0x005a381a, 0x0059391a, 0x00563919, 0x004d3214, 0x004a2e14, 0x00442a10, 0x00402510, 0x003c230d, 0x00381f0c, 0x0038200c, 0x0039220b, 0x003b250b, 0x0040270a, 0x00472c0e, 0x004e3112, 0x00553412, 0x005a3511, 0x00623c17, 0x00603810, 0x0063350c, 0x006c3c11, 0x00744012, 0x00774310, 0x007a4310, 0x00743c0c, 0x006f3a0c, 0x0067380a, 0x005e3408, 0x00583008, 0x00522c0a, 0x004b270b, 0x0048260c, 0x00402209, 0x003a1d08, 0x00351a06, 0x002c1503, 0x00261403, 0x00221302, 0x001d1104, 0x001a1105, 0x00191407, 0x001c170b, 0x00160f03, 0x00180e02, 0x00140b00, 0x00190f02, 0x00201104, 0x00261606, 0x0033210e, 0x003f2812, 0x00472c16, 0x004c3017, 0x00513518, 0x00533414, 0x00523410, 0x00563412, 0x005a3413, 0x005a3311, 0x005b3210, 0x0059300e, 0x00582f0c, 0x0058300f, 0x005e3412, 0x00663a14, 0x006c3f13, 0x00714011, 0x00774012, 0x00784313, 0x007b4415, 0x007d4718, 0x007c4716, 0x007b4412, 0x00734014, 0x00663714, 0x00462105, 0x002e1402, 0x00261509, 0x00241409, 0x002a1508, 0x00321809, 0x003f2011, 0x004a2819, 0x00381808, 0x00341405, 0x00341405, 0x00321404, 0x00422518, 0x00332015, 0x00110e05, 0x0008120c, 0x0004120c, 0x0008100c, 0x00090f0c, 0x0008100b, 0x0005100b, 0x00051009, 0x00040f07, 0x00051008, 0x00051008, 0x00050d09, 0x00040c09, 0x00060d0a, 0x00060d0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f07, 0x00070f08, 0x00070f08, 0x00060f08, 0x00040f05, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00041008, 0x00041008, 0x00041008, 0x00050f08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00050d07, 0x00050d07, 0x00040c07, 0x00040c07, 0x00040d07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x00202308, 0x0024250b, 0x0024250b, 0x0024250c, 0x0026280c, 0x0026280b, 0x0026280b, 0x00292b0b, 0x0026280a, 0x00292b0b, 0x00292b0b, 0x00292b0a, 0x002c2d0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x002c2d0a, 0x002c2d0b, 0x00292b0b, 0x00292b0b, 0x0026280a, 0x00292b0b, 0x0026280a, 0x00292b0b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280c, 0x0024250c, 0x0024250b, 0x0024250b, 0x00202309, 0x001d2008, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c09, 0x00040c09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d09, 0x0008100d, 0x00161d1a, 0x002c322e, 0x00383d3c, 0x00383a3c, 0x003d3d3f, 0x00363636, 0x00323031, 0x00343032, 0x00383435, 0x00383434, 0x00363130, 0x00383232, 0x00393535, 0x003b3838, 0x00343332, 0x00343130, 0x00433f3e, 0x00645758, 0x00756162, 0x007f6966, 0x00816a65, 0x00836a66, 0x00826967, 0x00826968, 0x00806868, 0x007d6663, 0x006e5851, 0x0068514b, 0x00665048, 0x00644d44, 0x0061493c, 0x00644938, 0x00654b34, 0x00654b2f, 0x00634425, 0x00613f1e, 0x0065401c, 0x00663d1b, 0x00643b1a, 0x005f381a, 0x005c3819, 0x00593718, 0x00513415, 0x00442d12, 0x003c260e, 0x00301905, 0x002e1807, 0x002b1808, 0x002b1809, 0x002d190b, 0x002d1a0a, 0x00301e0a, 0x00341f08, 0x00372008, 0x003d240c, 0x0046290c, 0x004f2f0f, 0x005c3a19, 0x005e3815, 0x00683c14, 0x00714013, 0x00744110, 0x0076400b, 0x0078400c, 0x00743b0b, 0x006e390c, 0x006a3b0d, 0x0061360b, 0x00593109, 0x00542d0c, 0x0049240c, 0x00401f0b, 0x00381c08, 0x00311a06, 0x00291504, 0x00241303, 0x00201304, 0x001e1406, 0x001b1206, 0x00181208, 0x0017140b, 0x0018160f, 0x00141009, 0x00110d04, 0x000f0e07, 0x000a0a03, 0x000d0c06, 0x00140f09, 0x0018100b, 0x00170c01, 0x00231407, 0x002c1c08, 0x0038230b, 0x00442c10, 0x004c3113, 0x004c2e11, 0x00523113, 0x00543010, 0x00542e0f, 0x00542f0f, 0x00563010, 0x00593210, 0x005f3513, 0x00643911, 0x006c4013, 0x00744314, 0x00794314, 0x00794313, 0x007c4517, 0x007e481b, 0x007d4719, 0x007c4414, 0x00733f12, 0x006a3b14, 0x004b2708, 0x00341a04, 0x002c1a0b, 0x00281709, 0x002b1609, 0x0032180b, 0x00402011, 0x004c2819, 0x00421d10, 0x003e190c, 0x003c1808, 0x003d1907, 0x004c2b1c, 0x002f1c10, 0x00121008, 0x0008120e, 0x0005130c, 0x0008100d, 0x0009100c, 0x0008100b, 0x0005110b, 0x0006100b, 0x00041009, 0x00051009, 0x00051009, 0x00060d0b, 0x00050d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060f07, 0x00060f08, 0x00060e08, 0x00060f08, 0x00040f05, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040f08, 0x00021008, 0x00021008, 0x00021008, 0x00041008, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040d06, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c09, 0x00191c09, 0x001d2008, 0x00202308, 0x00202308, 0x0020230a, 0x0024250b, 0x0024250b, 0x0026280b, 0x00292b0b, 0x00292b0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x002d2f0b, 0x0030310c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x002d2f0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x00292b0a, 0x00292b0a, 0x002c2d0a, 0x00292b0b, 0x00292b0b, 0x0026280b, 0x0026280c, 0x0024250c, 0x0024250b, 0x00202309, 0x00202308, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f09, 0x00060e08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c09, 0x00040c09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00040d08, 0x00040d08, 0x00040d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d06, 0x00050d06, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00070c07, 0x00070c07, 0x00050c07, 0x00050c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00060e0a, 0x00060e0a, 0x00060e0a, 0x00060f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050e08, 0x00050e08, 0x00050d09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d09, 0x00040d09, 0x00040d09, 0x00040d09, 0x00040d09, 0x00040d09, 0x00050e0a, 0x000b1410, 0x00141c18, 0x00272f2a, 0x00383d39, 0x00393c3c, 0x00404040, 0x00393838, 0x00343132, 0x00343032, 0x00373233, 0x003d3836, 0x003d3836, 0x003b3735, 0x003d3a39, 0x00373534, 0x00383635, 0x00373332, 0x00454040, 0x0066595b, 0x00766363, 0x007f6866, 0x00826b66, 0x00846c67, 0x00826968, 0x00836a69, 0x00846c6a, 0x007d6560, 0x006e5850, 0x00654f47, 0x00644d45, 0x00614b43, 0x0060483a, 0x00624834, 0x0064472e, 0x00634526, 0x00654420, 0x00603f1a, 0x005e3a15, 0x005f3b14, 0x005e3816, 0x00583416, 0x004d2d11, 0x0043250c, 0x00341c04, 0x00241400, 0x00231304, 0x001a0b00, 0x00201105, 0x00211207, 0x00231409, 0x0025160b, 0x0027180b, 0x00281909, 0x002c1b08, 0x00301c08, 0x00341e0a, 0x00381e07, 0x0043240a, 0x00543113, 0x00613c19, 0x006f421a, 0x00784417, 0x00784210, 0x007b410b, 0x007c420c, 0x00783f0c, 0x00743d0a, 0x00703e0b, 0x00693908, 0x0062340c, 0x0059300d, 0x0049240b, 0x003e1d0b, 0x00301a07, 0x00281403, 0x00241304, 0x00221207, 0x0022150b, 0x001d1108, 0x001c1109, 0x001f150d, 0x00231a14, 0x002c231c, 0x00211811, 0x001d140d, 0x0014100c, 0x0010110f, 0x00292825, 0x00120f0c, 0x001c130f, 0x0020140d, 0x002c1d14, 0x00261507, 0x00200d00, 0x00281300, 0x00321b04, 0x0039200c, 0x003f240c, 0x0042250c, 0x0045270c, 0x0049280c, 0x004e2c10, 0x00563011, 0x00603712, 0x00643910, 0x006c3f10, 0x00754312, 0x00794210, 0x007a4312, 0x007c4517, 0x007e471b, 0x007d461b, 0x007c4315, 0x00713c10, 0x006d3d13, 0x00522d09, 0x003a1d02, 0x00311c09, 0x002c190b, 0x002c170b, 0x0031180a, 0x003f1f10, 0x004c2819, 0x004f2618, 0x00471d0d, 0x00431908, 0x004d2412, 0x00533020, 0x0028170e, 0x0010110d, 0x0009110f, 0x0008110f, 0x00081010, 0x0009100f, 0x0007100c, 0x0005110b, 0x0006110b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f0b, 0x00050d0a, 0x00050d0a, 0x00050d0a, 0x00050d09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040f07, 0x00040f07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d09, 0x00040d09, 0x00040e0a, 0x00040e0a, 0x0005100a, 0x00050f0a, 0x00040f09, 0x00040e08, 0x00040f08, 0x00041008, 0x00041008, 0x00041008, 0x00040f08, 0x00060e09, 0x00050d09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060d08, 0x00060d08, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d06, 0x00050d06, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e08, 0x00040e08, 0x00040e08, 0x00040e08, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c04, 0x00060c04, 0x00060c04, 0x00060c05, 0x00050c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x0020230a, 0x0024250c, 0x0026280c, 0x0026280b, 0x00292b0a, 0x00292b0a, 0x002d2f0a, 0x002d2f0b, 0x0030310c, 0x0030310c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0034350c, 0x0034350c, 0x0032330c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0b, 0x0026280a, 0x0026280b, 0x0024250b, 0x0024250b, 0x00202309, 0x00202308, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c09, 0x0014180a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e0b, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x0008100c, 0x000d1510, 0x001c2420, 0x00323834, 0x0030322f, 0x00383735, 0x003f3a3c, 0x00342e30, 0x00363031, 0x00363030, 0x00403837, 0x00413c39, 0x00373430, 0x00393837, 0x003a3837, 0x00393535, 0x00383333, 0x00464040, 0x0066595b, 0x00776464, 0x007f6867, 0x00836b66, 0x00856c68, 0x00836a68, 0x00836a69, 0x00806766, 0x00765e58, 0x0071594f, 0x006b5248, 0x00674e44, 0x00644c3f, 0x00644a39, 0x00634631, 0x0064452b, 0x00634224, 0x0060401c, 0x00593916, 0x00553713, 0x00563815, 0x00482b0d, 0x00381f05, 0x00291502, 0x001c0d00, 0x00140900, 0x00130b03, 0x00140c04, 0x00171007, 0x001c140a, 0x0024170e, 0x0023150c, 0x0021140a, 0x0021140a, 0x00241409, 0x0028170b, 0x002b170a, 0x00311b0d, 0x00391e0d, 0x00462711, 0x00543114, 0x0068401f, 0x00784822, 0x00824c1f, 0x00884c1a, 0x008f5018, 0x00915118, 0x008c4f15, 0x00884c13, 0x00844c11, 0x007b440d, 0x006b370a, 0x005f300b, 0x00512a0c, 0x00432109, 0x00331b07, 0x00291502, 0x00281404, 0x00251508, 0x0023140b, 0x00201009, 0x0022110b, 0x00281810, 0x00302015, 0x003d2d21, 0x00372619, 0x002e1c10, 0x002c1f14, 0x00251d14, 0x002c2118, 0x002c1e12, 0x002d1c0d, 0x003b2113, 0x00482e1c, 0x00402814, 0x0037200b, 0x002c1401, 0x00291000, 0x002f1705, 0x00321a06, 0x00341a06, 0x00391d06, 0x0048270f, 0x004f2c12, 0x005a3310, 0x00653b14, 0x006a3d10, 0x00704010, 0x00774410, 0x007b4410, 0x007b4313, 0x007c4417, 0x007f471a, 0x007d461b, 0x007b4216, 0x00713c0f, 0x006d3c10, 0x005c330c, 0x00401f00, 0x00361b05, 0x002e1909, 0x002f190d, 0x0033190c, 0x0040200f, 0x004e2916, 0x00562c18, 0x004c200d, 0x00491d09, 0x005d311c, 0x004e2c1a, 0x001f120c, 0x000e1311, 0x000a120f, 0x000c1010, 0x00091111, 0x00091110, 0x0008110e, 0x0006120b, 0x0006120a, 0x0004100a, 0x0005110b, 0x0005110b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040f07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060d03, 0x00060d04, 0x00060c06, 0x00040b04, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280c, 0x0026280b, 0x00292b0a, 0x002c2d0a, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0034350c, 0x0036370c, 0x0036370c, 0x0036370c, 0x0036370c, 0x0036370b, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0036370c, 0x0036370c, 0x0036370c, 0x0038380c, 0x0038380c, 0x0036370c, 0x0034350c, 0x0034350c, 0x0034350c, 0x0032330c, 0x0034350c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x00292b0a, 0x00292b0b, 0x0026280b, 0x0024250b, 0x0024250b, 0x00202309, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e0b, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040c08, 0x00040c08, 0x00050e09, 0x0008100b, 0x0009110c, 0x00141c17, 0x002b302c, 0x0030332e, 0x00343330, 0x00423b3b, 0x00312828, 0x00322828, 0x00322928, 0x00372e2c, 0x00403935, 0x003d3938, 0x003c3a39, 0x003c3c3b, 0x003b3838, 0x00373131, 0x00484142, 0x00655658, 0x00796464, 0x00806a68, 0x00846b67, 0x00866c69, 0x00846a68, 0x00826868, 0x007c6262, 0x00735954, 0x00705649, 0x006c5345, 0x00684d40, 0x00654a3b, 0x00644837, 0x005e432f, 0x00593d24, 0x00553920, 0x0054381c, 0x004c3316, 0x0041280c, 0x002e1500, 0x00261200, 0x001c0d01, 0x00170c03, 0x00100a04, 0x001d1a19, 0x001f1c1c, 0x00120e08, 0x00181104, 0x00241a0a, 0x002d2011, 0x0028170c, 0x0026160e, 0x0022130c, 0x00211108, 0x00261409, 0x00281409, 0x002d180b, 0x003c2010, 0x004b2a14, 0x00553315, 0x006e4623, 0x00825029, 0x008a5226, 0x0092551f, 0x009a581a, 0x009c5b18, 0x00985615, 0x00945314, 0x00905014, 0x00844a10, 0x00733a09, 0x00633206, 0x00562c09, 0x00482407, 0x003a1c04, 0x00301701, 0x002f1804, 0x002c1706, 0x002b1608, 0x002c1508, 0x002d1408, 0x002e1508, 0x00331b0b, 0x003f2414, 0x00402715, 0x00361e0c, 0x003b2310, 0x00402812, 0x004a3017, 0x004f3217, 0x00543418, 0x00613c20, 0x00654224, 0x00613f1e, 0x00583816, 0x004e2c11, 0x0046250c, 0x00412008, 0x0044240a, 0x00442309, 0x004a2409, 0x004e2608, 0x00582c0d, 0x0062340d, 0x006c3d0f, 0x00744012, 0x00774310, 0x007b4511, 0x007c4511, 0x007c4512, 0x007c4416, 0x007d4519, 0x007d461b, 0x007c4318, 0x00733c10, 0x006f3c10, 0x0061340c, 0x00482300, 0x00391c04, 0x00301907, 0x00311b0e, 0x00351b0c, 0x003f1f0c, 0x004d2811, 0x00583017, 0x0050240c, 0x004b2006, 0x005f341a, 0x00462512, 0x001c130c, 0x000c1513, 0x00081310, 0x000c1210, 0x00091213, 0x000a1211, 0x0008120f, 0x0007130c, 0x0006120b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040f07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060d04, 0x00060c06, 0x00060c07, 0x00040b05, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280b, 0x00292b0b, 0x002c2d0a, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0032330c, 0x0034350c, 0x0038380c, 0x0038380c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x003b3c0d, 0x003b3c0d, 0x003b3c0c, 0x003b3c0d, 0x003b3c0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003b3c0d, 0x003b3c0d, 0x003c3e0d, 0x003b3c0c, 0x003c3e0d, 0x003b3c0d, 0x003b3c0d, 0x00393b0d, 0x003b3c0d, 0x00393b0c, 0x0038380c, 0x0038380c, 0x0036370c, 0x0036370c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x002c2d0a, 0x00292b0b, 0x0026280b, 0x0024250b, 0x0020230a, 0x00202309, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e0b, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00050d09, 0x00050d08, 0x0009110d, 0x000c140f, 0x0020241f, 0x0032332f, 0x00312f2b, 0x00443938, 0x00302423, 0x00281d1a, 0x002a1f1b, 0x0028201c, 0x0038302d, 0x0045403f, 0x00403e3f, 0x00404040, 0x003d3a3b, 0x00383133, 0x004c4444, 0x00645555, 0x00796564, 0x00806967, 0x00846b68, 0x00866c6a, 0x00846b68, 0x00836768, 0x007e6363, 0x00745954, 0x006c5144, 0x00674c3c, 0x00684b3c, 0x00634537, 0x005e402f, 0x00543925, 0x004d3420, 0x00432c17, 0x0034200b, 0x002b1904, 0x002e1c08, 0x00301e09, 0x0033200f, 0x00291b0c, 0x0022170d, 0x0019140c, 0x0022201f, 0x00242322, 0x00261f17, 0x00231808, 0x003a2b16, 0x003a2a15, 0x002a1706, 0x00251207, 0x00210f06, 0x00211006, 0x00271408, 0x002c1709, 0x002e1808, 0x003e2110, 0x004e2d18, 0x005b3518, 0x00724926, 0x0085532c, 0x008c5526, 0x00985c24, 0x00a3621e, 0x00a7641a, 0x00a45e15, 0x00a15a18, 0x00995415, 0x008c4b10, 0x00783e09, 0x00683505, 0x005a2e07, 0x004f2806, 0x00432005, 0x00381900, 0x003b1d06, 0x003a1e0a, 0x003c1d0b, 0x003e1e0c, 0x003f1e0c, 0x003f1d0b, 0x003e1d09, 0x0046240f, 0x004d2c15, 0x0054321b, 0x0058361c, 0x005e3a1b, 0x00653e1c, 0x006a421e, 0x00683f1a, 0x00623813, 0x00613810, 0x00643b10, 0x0060380d, 0x005d3410, 0x005d3412, 0x005c3512, 0x005f3814, 0x00643816, 0x00693c16, 0x006b3a13, 0x006e3c13, 0x00744110, 0x007c4814, 0x00804915, 0x00824914, 0x00814813, 0x007f4812, 0x00804615, 0x007c4413, 0x007b4215, 0x007b4419, 0x00794318, 0x00723c12, 0x00703c11, 0x0064370b, 0x00502803, 0x00422106, 0x00371c08, 0x0033190a, 0x00341908, 0x003f1e08, 0x004d280e, 0x00583014, 0x005a2f10, 0x00502506, 0x005d3414, 0x003e2008, 0x001a140d, 0x00081311, 0x00071512, 0x000b1410, 0x00091213, 0x00091213, 0x00071310, 0x0007130d, 0x0006130c, 0x0005110b, 0x0005110b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040f07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c08, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280b, 0x00292b0b, 0x002d2f0a, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0036370c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x003c3e0d, 0x003e400d, 0x003e400c, 0x003e400c, 0x0040400d, 0x0040400d, 0x0041420d, 0x0040400d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0040400d, 0x0040400d, 0x0040400d, 0x0040400d, 0x0041420d, 0x0040400d, 0x0040400e, 0x0040400d, 0x003e400c, 0x003e400c, 0x003e400c, 0x003e400d, 0x003c3e0d, 0x003b3c0d, 0x00393b0d, 0x00393b0c, 0x0038380c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002c2d0a, 0x002c2d0b, 0x0026280b, 0x0026280b, 0x0024250c, 0x00202309, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c07, 0x0008100c, 0x0008100b, 0x00141a14, 0x002a2d28, 0x002c2924, 0x00413633, 0x00302520, 0x001e120c, 0x0021150f, 0x00231a13, 0x0038302c, 0x004a4545, 0x00444244, 0x00404042, 0x003e3a3b, 0x003e3738, 0x004f4544, 0x00655754, 0x00796765, 0x00806a68, 0x00846c6b, 0x00866c6c, 0x00846969, 0x00836664, 0x007f6360, 0x00765851, 0x006c503d, 0x00664834, 0x005d402c, 0x00583826, 0x004d311d, 0x00432a16, 0x003a2410, 0x00301d0b, 0x00332111, 0x00342313, 0x00392614, 0x0044301b, 0x004b341f, 0x00402912, 0x0034200b, 0x00312010, 0x00302416, 0x0038291c, 0x00342414, 0x0035200c, 0x00402811, 0x003c240b, 0x00301801, 0x00311a07, 0x00321c0a, 0x00301b0a, 0x00351e0c, 0x0038200c, 0x003a200a, 0x0044240f, 0x00543019, 0x005f3618, 0x00744826, 0x0087542e, 0x008f5728, 0x009c6025, 0x00a6661f, 0x00ab6618, 0x00a85f12, 0x00a55b14, 0x009e5414, 0x00924b10, 0x007c410a, 0x006d3807, 0x00633309, 0x00592f0a, 0x0050290a, 0x00482305, 0x004a260c, 0x004b280f, 0x004c2810, 0x004e2810, 0x004f2710, 0x00502810, 0x004f270c, 0x00502a0d, 0x00542c0d, 0x00582f10, 0x005c3312, 0x005f3510, 0x005e340d, 0x0060350c, 0x0063380f, 0x0060350c, 0x0063380e, 0x00653c0f, 0x0064380c, 0x0064370c, 0x0068390f, 0x006c3c11, 0x00714014, 0x007a4819, 0x00804b1b, 0x00804a17, 0x00854c17, 0x008a5118, 0x008c5218, 0x008b5017, 0x00884c16, 0x00864b14, 0x00824913, 0x00814814, 0x007c4414, 0x007a4113, 0x00784115, 0x00744014, 0x00703d12, 0x006e3c11, 0x0065380c, 0x00512802, 0x00452407, 0x003b1e08, 0x00341909, 0x00341909, 0x003c1c08, 0x004a260c, 0x00583012, 0x00643817, 0x005c3010, 0x005c3412, 0x00341901, 0x0016140b, 0x00081514, 0x00071614, 0x000b1510, 0x000a1314, 0x00081412, 0x00071410, 0x0008140f, 0x0004130c, 0x0005110b, 0x0005110b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00040e09, 0x00040d08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0a, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c08, 0x00060c08, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250c, 0x0026280b, 0x00292b0b, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003b3c0d, 0x003c3e0d, 0x003e400c, 0x0040400d, 0x0041420d, 0x0043440e, 0x0043440e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0043440e, 0x0043440e, 0x0041420e, 0x0041420e, 0x0040400d, 0x0040400d, 0x003e400c, 0x003c3e0c, 0x003c3e0d, 0x00393b0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0b, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0024250c, 0x00202308, 0x00202308, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x0006100a, 0x000c130e, 0x0020241c, 0x002c2c24, 0x003e3731, 0x003e342e, 0x0024180f, 0x001f1208, 0x00281c14, 0x00382d2c, 0x00494444, 0x00464448, 0x00444146, 0x00403b3f, 0x003f3736, 0x004e4340, 0x006d5e5b, 0x007c6b67, 0x007f6a68, 0x00846c6c, 0x00886d70, 0x00866b6c, 0x00846865, 0x0081645c, 0x00765548, 0x006c4b34, 0x0066422c, 0x005c3822, 0x0054321b, 0x0043270f, 0x003e240f, 0x00462e1b, 0x004e3826, 0x00533b2c, 0x00593f2e, 0x005b3e28, 0x005e4025, 0x00614223, 0x00644424, 0x00644524, 0x00634122, 0x00603f20, 0x005c3c1f, 0x0059381f, 0x00512f18, 0x004c2813, 0x0048220e, 0x00442009, 0x00422108, 0x00442509, 0x0045260c, 0x004c2810, 0x00502c12, 0x004e290d, 0x004f2a0d, 0x005f381a, 0x00683c1c, 0x00784725, 0x008b5632, 0x0094592d, 0x00a06228, 0x00a86822, 0x00ab6619, 0x00ac6417, 0x00ae6119, 0x00a95c1a, 0x009c5417, 0x00874a13, 0x00773f0d, 0x006b380c, 0x0063350d, 0x005c330d, 0x00592f0d, 0x00592e10, 0x005e3116, 0x005f3318, 0x005e3116, 0x005c3015, 0x00603419, 0x00603413, 0x00592e0a, 0x00582d07, 0x005a2f09, 0x005c300a, 0x005d300b, 0x005e320c, 0x005c340c, 0x005c360d, 0x005c350d, 0x005c340c, 0x0061350f, 0x00663710, 0x006f3c11, 0x00784415, 0x007c4414, 0x00844918, 0x008b4c17, 0x008e5015, 0x00945418, 0x00985719, 0x00985919, 0x00975718, 0x00935418, 0x008d5017, 0x00884d14, 0x00854913, 0x00834815, 0x007d4412, 0x007b4214, 0x00764114, 0x00713d11, 0x006c3c10, 0x00683a10, 0x0062370c, 0x00502904, 0x003f1d00, 0x00371802, 0x0034180a, 0x00341910, 0x00391a0c, 0x0048240e, 0x00562e10, 0x00663918, 0x00653816, 0x00603718, 0x00331a04, 0x0013130c, 0x00071615, 0x00081517, 0x000c1411, 0x000a1414, 0x00081412, 0x00071411, 0x0005130f, 0x0004130c, 0x0005120c, 0x0007110c, 0x0007110c, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00021009, 0x00021009, 0x00021009, 0x00030f09, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00051007, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0b, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0045470e, 0x0047480e, 0x0047480e, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0047480e, 0x0048490e, 0x0047480e, 0x0047480e, 0x0045470e, 0x0045470e, 0x0044450e, 0x0043440e, 0x0041420e, 0x0041420e, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x00292b0a, 0x0026280b, 0x0024250c, 0x00202308, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040d08, 0x00040f09, 0x0006100b, 0x00121911, 0x00242820, 0x0038342f, 0x00463e37, 0x0031241c, 0x00231208, 0x00291811, 0x003c302e, 0x004d4446, 0x0048444a, 0x00464148, 0x00423c40, 0x00403837, 0x004f4440, 0x006c5d58, 0x007b6a66, 0x00806b6a, 0x00846c6f, 0x00886e71, 0x00886e6f, 0x008a6c66, 0x00846257, 0x00744e3c, 0x006e4629, 0x00643c1f, 0x005d3518, 0x00542c0f, 0x00532f12, 0x005e3d23, 0x006c4c35, 0x006c4d39, 0x00694836, 0x0065412d, 0x00664027, 0x00653c20, 0x00643915, 0x00643a13, 0x00653c14, 0x00643c14, 0x00603810, 0x005c340f, 0x00593010, 0x00542b10, 0x00522911, 0x00522810, 0x00552c10, 0x0058300f, 0x00593311, 0x005a3210, 0x00603414, 0x00643716, 0x00623412, 0x00613713, 0x006b401c, 0x00734623, 0x007c4c29, 0x008e5834, 0x00985f33, 0x00a0642c, 0x00a86826, 0x00ad681d, 0x00af671a, 0x00af651a, 0x00aa5e19, 0x009c5514, 0x008d4d14, 0x007d420c, 0x00763f10, 0x006e3b0f, 0x00693b10, 0x0065390f, 0x0062340e, 0x00633411, 0x00673817, 0x006c3c1c, 0x006f401f, 0x006e401c, 0x0070411b, 0x006a3c14, 0x0063340d, 0x0060300a, 0x005f2e08, 0x005e3009, 0x005d300b, 0x005b300b, 0x005b320a, 0x0060350d, 0x0065380f, 0x006a3a12, 0x006f3d13, 0x00774415, 0x00804a18, 0x00874d1a, 0x008d501c, 0x00935417, 0x00955414, 0x00995716, 0x009b5915, 0x009c5915, 0x009a5616, 0x00945315, 0x008f5014, 0x008b4d13, 0x00864912, 0x00834815, 0x007e4514, 0x007b4214, 0x00754013, 0x00703d10, 0x0069390e, 0x0064380e, 0x005a3209, 0x004e2805, 0x003e1d02, 0x00381b07, 0x00321709, 0x0031180e, 0x00381c0d, 0x0046240f, 0x00562e0f, 0x00663a15, 0x00683c18, 0x005f3818, 0x002f1801, 0x0013140c, 0x00081716, 0x00081517, 0x000c1410, 0x000a1513, 0x00081412, 0x00051411, 0x0004140f, 0x0004130c, 0x0005130c, 0x0006100b, 0x0006100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00021009, 0x00021009, 0x00021009, 0x00030f09, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d04, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00060e08, 0x00070f08, 0x00050e08, 0x00040d07, 0x00050e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00051007, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180b, 0x00191c0a, 0x00191c08, 0x001d2008, 0x0024250b, 0x0024250b, 0x00292b0b, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0040400d, 0x0043440e, 0x0044450e, 0x0047480e, 0x0048490f, 0x0048490f, 0x00494a0f, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d10, 0x004c4d10, 0x004c4d10, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004c4d10, 0x004c4d10, 0x004c4d10, 0x004c4d10, 0x004d4e10, 0x004c4d10, 0x004c4d0f, 0x004c4d0f, 0x004b4c0f, 0x004b4c0f, 0x004b4c0f, 0x004b4c10, 0x00494a0f, 0x00494a0f, 0x0048490f, 0x0047480e, 0x0045470e, 0x0045470e, 0x0043440e, 0x0041420e, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x003b3c0d, 0x0038380c, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0a, 0x0026280b, 0x0024250c, 0x00202308, 0x001d2008, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040d09, 0x0002100b, 0x00030f09, 0x0008120b, 0x00181d16, 0x002c2c24, 0x00474039, 0x0043342c, 0x002d1911, 0x0028140f, 0x00402f2f, 0x00504449, 0x004a444c, 0x0048404a, 0x00433c42, 0x00413737, 0x004f433f, 0x006b5c57, 0x007a6964, 0x007f6a6a, 0x00826c6f, 0x00866e72, 0x008a6e70, 0x008d6c67, 0x00896152, 0x007e5038, 0x007b4c27, 0x00774721, 0x00764620, 0x0074441f, 0x00774826, 0x007b4e31, 0x007b5036, 0x00795038, 0x00774e36, 0x0071472e, 0x006f4123, 0x006c3e1b, 0x006b3c12, 0x006a3c0e, 0x00673b0c, 0x0064390b, 0x0064390c, 0x0064390d, 0x00643810, 0x00603311, 0x005d3010, 0x005d2f0c, 0x00653610, 0x006a3910, 0x006c3c10, 0x006b3b0f, 0x00703d11, 0x00733e11, 0x00703c0e, 0x00704010, 0x00734417, 0x00794920, 0x00815028, 0x00905c37, 0x00986034, 0x00a0642c, 0x00a96824, 0x00af691f, 0x00b0681c, 0x00b0671a, 0x00ae6418, 0x00a25a12, 0x00944e10, 0x0088470c, 0x00804411, 0x0078400f, 0x00713e0b, 0x006e3c0b, 0x006e3a0c, 0x006e3a10, 0x00703b12, 0x00744017, 0x00754018, 0x00784318, 0x007b471b, 0x007a461b, 0x00774318, 0x00744015, 0x00713e14, 0x006c390f, 0x0068380f, 0x0067390f, 0x00683b0e, 0x006a3b0d, 0x006d3c0e, 0x00723c10, 0x00764010, 0x007f4714, 0x00874e16, 0x008e5118, 0x00935418, 0x00975515, 0x00995714, 0x009d5915, 0x009e5914, 0x009e5914, 0x009c5713, 0x00985412, 0x00915012, 0x008c4e13, 0x00874912, 0x00844815, 0x007d4412, 0x00784012, 0x00743e12, 0x006e3b10, 0x0068380f, 0x0063370f, 0x0058310a, 0x00472404, 0x003c1e04, 0x00391d0b, 0x00301809, 0x00301a0e, 0x00341a0b, 0x0040210b, 0x00542d0c, 0x00673912, 0x006a3d15, 0x00603814, 0x002f1801, 0x0014140c, 0x00081716, 0x00091618, 0x000c1410, 0x00081412, 0x00061514, 0x00071411, 0x0006130f, 0x0004140f, 0x0006120e, 0x0006100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00021009, 0x00021009, 0x00021009, 0x00030f09, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040e04, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00051007, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x0048490f, 0x00494a0f, 0x004b4c0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00515110, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00515110, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x004f5010, 0x004f5010, 0x004d4e0f, 0x004d4e0f, 0x004c4d0f, 0x004c4d0f, 0x004b4c0f, 0x00494a0f, 0x0048490f, 0x0047480e, 0x0045470e, 0x0044450e, 0x0041420e, 0x0040400d, 0x003e400d, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0a, 0x0026280c, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040d09, 0x00030f0b, 0x00030f09, 0x00041008, 0x000d160d, 0x0020211b, 0x003c3630, 0x0050423b, 0x003c271f, 0x002f1813, 0x00463434, 0x0055484c, 0x004d464e, 0x0048414b, 0x00443c41, 0x00403536, 0x004c403c, 0x00695b54, 0x00796865, 0x007e696c, 0x00826c70, 0x00886e73, 0x008c6e70, 0x008f6c65, 0x008a5e4d, 0x00855437, 0x008a582c, 0x008b572c, 0x00885429, 0x00865128, 0x00844f28, 0x0084502f, 0x00835233, 0x00825335, 0x007e5034, 0x00784a2c, 0x00704320, 0x006c3f16, 0x00683c10, 0x00653c0d, 0x00653d0e, 0x00673d10, 0x00653c10, 0x0062380d, 0x0060360c, 0x0061350d, 0x00663810, 0x006f3e13, 0x00784417, 0x00784111, 0x007c4514, 0x007a4511, 0x007d4812, 0x007b440d, 0x007e4810, 0x00804c16, 0x00824f1d, 0x00825022, 0x0088562c, 0x00925d38, 0x00975f33, 0x00a0642b, 0x00aa6924, 0x00af681c, 0x00af6718, 0x00b36a1c, 0x00b1671a, 0x00a65d13, 0x00995110, 0x008e480c, 0x0088480f, 0x0080430c, 0x007b4109, 0x00784008, 0x007c430e, 0x007b4210, 0x00794210, 0x007c4614, 0x007c4412, 0x007c4413, 0x007b4412, 0x007d4714, 0x00814a18, 0x00854e1e, 0x00865120, 0x00824f1c, 0x007c4b18, 0x007b4c19, 0x007a4c18, 0x007c4a18, 0x007f4815, 0x00804814, 0x00854b16, 0x008b5016, 0x0094571a, 0x00935415, 0x00965414, 0x00985413, 0x009f5a18, 0x00a05a17, 0x00a05a14, 0x009e5914, 0x009c5713, 0x00975412, 0x00905111, 0x008d4f14, 0x00894c16, 0x00844917, 0x007e4413, 0x00784213, 0x00743f14, 0x006e3c11, 0x00683810, 0x00623710, 0x0055300a, 0x00442102, 0x003a1c05, 0x00371c0b, 0x0030180a, 0x00301a0c, 0x00341c0c, 0x0040220c, 0x00552d0b, 0x00683910, 0x006c3d14, 0x00603814, 0x00301801, 0x0014140c, 0x00081817, 0x00091618, 0x000b1510, 0x00081412, 0x00061514, 0x00071411, 0x0006130f, 0x0004140f, 0x0005130f, 0x0008130f, 0x0009120e, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040e04, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00051007, 0x00040e05, 0x00040e05, 0x00040d05, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004b4c0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00525310, 0x00535410, 0x00535410, 0x00535410, 0x00545510, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00545510, 0x00545510, 0x00545510, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00525310, 0x00525310, 0x00515110, 0x00515110, 0x00505010, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004c4d0f, 0x004b4c0f, 0x00494a0f, 0x0047480e, 0x0045470e, 0x0043440e, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0024250c, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x00141810, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060c0b, 0x00080c0b, 0x00080d08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00070c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00051008, 0x0008110b, 0x0010140c, 0x002c2821, 0x0051443c, 0x0048352c, 0x0039221c, 0x004c3735, 0x00584b4c, 0x004a4549, 0x00484348, 0x00423a3e, 0x00403534, 0x004b3f3a, 0x00685953, 0x00796867, 0x007d686e, 0x00826b71, 0x00886f74, 0x008d6f71, 0x00906b67, 0x00906454, 0x00946143, 0x00946031, 0x00955f2e, 0x00945b29, 0x00925525, 0x00905425, 0x0090542a, 0x008e542e, 0x008a512d, 0x0085502a, 0x007d4b22, 0x0077441b, 0x00703e14, 0x006c3b0e, 0x006b3a0d, 0x006a3b0c, 0x006a3a0d, 0x006a3a0d, 0x006a3a0e, 0x006a3c0e, 0x00734414, 0x007e4c1b, 0x008a531d, 0x00885019, 0x008c531c, 0x008c531c, 0x008a4f16, 0x00884c10, 0x008a4d0e, 0x00894d11, 0x00874d14, 0x00885020, 0x0089542b, 0x008d5b34, 0x00936039, 0x00955e33, 0x00a0642a, 0x00ac6a23, 0x00af681c, 0x00af6718, 0x00b2691c, 0x00b06419, 0x00a45b10, 0x009a5010, 0x0090490b, 0x008c490d, 0x008a4910, 0x00864810, 0x0080440e, 0x00814510, 0x00814512, 0x00844814, 0x00874c18, 0x00874d18, 0x00844a15, 0x00824814, 0x00824814, 0x00844916, 0x00844a19, 0x00884d1b, 0x00844b17, 0x00834b15, 0x00844c16, 0x00844c17, 0x00854c18, 0x00884c16, 0x008c4e17, 0x00935118, 0x00985418, 0x009b5618, 0x009c5816, 0x009e5b17, 0x00a05a18, 0x00a05c19, 0x00a15c18, 0x009e5915, 0x009c5814, 0x00985410, 0x00945310, 0x00905111, 0x008d4e14, 0x00874c15, 0x00834815, 0x007e4715, 0x00784214, 0x00703c14, 0x006c3911, 0x0066370f, 0x005f340c, 0x00512907, 0x00441f03, 0x003a1a04, 0x00371b0b, 0x0035190d, 0x00321809, 0x00371c0a, 0x00472412, 0x005f3313, 0x006c3c10, 0x00714115, 0x006a401c, 0x00331803, 0x0014140c, 0x00081817, 0x00091618, 0x000c1610, 0x00081513, 0x00071614, 0x00081413, 0x00081410, 0x00051310, 0x00061411, 0x00061311, 0x0005110f, 0x0008110d, 0x0008100d, 0x00070e0c, 0x00060d0b, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f0a, 0x00050e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x0049490f, 0x00605710, 0x00645a10, 0x00645b10, 0x00665d10, 0x00685e10, 0x00685e11, 0x00685f11, 0x00686011, 0x00696012, 0x00696012, 0x00696011, 0x00696111, 0x00696112, 0x00696112, 0x00696011, 0x00696011, 0x00686011, 0x00686012, 0x00686012, 0x00686012, 0x00685f12, 0x00685f11, 0x00686011, 0x00686011, 0x00686012, 0x00685f12, 0x00665e12, 0x00665f11, 0x00655e11, 0x00655e11, 0x00645d11, 0x00645c10, 0x00635b10, 0x00605810, 0x00545210, 0x004d4e10, 0x004d4e10, 0x004c4d0f, 0x004b4c10, 0x0048490f, 0x0045470e, 0x0044450e, 0x0041420e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0024250b, 0x0020230a, 0x001d2008, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060d09, 0x00080c09, 0x00080d09, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00080c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x000c100c, 0x00282620, 0x0041372e, 0x00524138, 0x00402a21, 0x0045322c, 0x004f4140, 0x00484042, 0x00494245, 0x0040393b, 0x00403534, 0x004b3f3a, 0x00665852, 0x00786867, 0x007c696f, 0x00816c72, 0x00897074, 0x008d7074, 0x008f6c6a, 0x00906557, 0x00946344, 0x00976336, 0x00996232, 0x00985f2b, 0x00995c28, 0x00995a28, 0x0097592a, 0x00915628, 0x008c5426, 0x00885325, 0x00814c1e, 0x007d481a, 0x007e4819, 0x007d4a19, 0x00784413, 0x00754210, 0x00774412, 0x00784514, 0x007e4b1b, 0x00855220, 0x008c5924, 0x00915d24, 0x00945d23, 0x00915b20, 0x00945b20, 0x00945c20, 0x0093571c, 0x00925516, 0x008f5213, 0x008e5115, 0x008c501b, 0x008c5426, 0x008c5732, 0x00905d3b, 0x0094603b, 0x00935d32, 0x009e6028, 0x00a86720, 0x00ae681b, 0x00ad6617, 0x00b2681d, 0x00af641b, 0x00a45a14, 0x0098510f, 0x00904a0c, 0x008c490e, 0x008a4910, 0x00884a13, 0x00884a13, 0x00884912, 0x00864811, 0x008a4d16, 0x008f521b, 0x0092541e, 0x008f521b, 0x008c5018, 0x008b4e16, 0x00894c17, 0x00874814, 0x00864a15, 0x00864b15, 0x00874c15, 0x00874c15, 0x00884c16, 0x008c5019, 0x008d5017, 0x00935219, 0x0098541b, 0x009a5619, 0x00a25c1d, 0x00a4601d, 0x00a5601c, 0x00a6601d, 0x00a6611d, 0x00a35e1a, 0x009f5a16, 0x00995512, 0x00945110, 0x00935212, 0x00905014, 0x008c4e17, 0x00874a18, 0x00834718, 0x007c4316, 0x00774015, 0x006d3912, 0x00683610, 0x0063340d, 0x005c310c, 0x004f2708, 0x00421c04, 0x00391906, 0x00371b0d, 0x00381c10, 0x00371b0b, 0x003a1a07, 0x00502813, 0x00673814, 0x00734010, 0x00784717, 0x00794c25, 0x00371c05, 0x0014140c, 0x00081817, 0x00091618, 0x000c1610, 0x00081513, 0x00071614, 0x00081413, 0x00081410, 0x00051310, 0x00071411, 0x00061411, 0x0005120f, 0x0008110d, 0x0008100d, 0x00070e0c, 0x00060d0b, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x0014180f, 0x0014180b, 0x0014180a, 0x001d200a, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x00494a10, 0x00836f10, 0x00c39c15, 0x00c69d15, 0x00c69e15, 0x00c69e15, 0x00c59f15, 0x00c59f15, 0x00c59f16, 0x00c59f16, 0x00c59f16, 0x00c59f16, 0x00c49f16, 0x00c49f16, 0x00c49f16, 0x00c49f16, 0x00c49f17, 0x00c49f17, 0x00c49e17, 0x00c49e17, 0x00c49e17, 0x00c49e17, 0x00c49e17, 0x00c49e16, 0x00c49e16, 0x00c49e16, 0x00c49e16, 0x00c39d17, 0x00c39d17, 0x00c39d17, 0x00c39d16, 0x00c29c16, 0x00c29c16, 0x00c29c15, 0x00c19c15, 0x00bd9815, 0x00b19014, 0x00967c13, 0x00665d10, 0x00505010, 0x004d4e0f, 0x004b4c0f, 0x00494a10, 0x0047480e, 0x0044450d, 0x0041420e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060d09, 0x00080c09, 0x00080d09, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00080c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x0008100a, 0x00252620, 0x00322b24, 0x00504238, 0x00543f34, 0x004c362f, 0x004f3f3b, 0x004a3e3e, 0x004c4343, 0x00403838, 0x00403634, 0x00483d3a, 0x00625653, 0x00736766, 0x00786870, 0x00806d74, 0x00877378, 0x008d727a, 0x00906e6f, 0x0091665c, 0x00936349, 0x0098633b, 0x009a6334, 0x00995f29, 0x009b5e25, 0x009d5e28, 0x00985823, 0x0093561f, 0x00915620, 0x008c551e, 0x008c5420, 0x008a511e, 0x00874f1a, 0x00854d18, 0x00854c16, 0x00864e17, 0x0089511b, 0x008b521d, 0x008b531d, 0x008d541f, 0x0090561d, 0x0090571c, 0x00905719, 0x0091581a, 0x0094591c, 0x00975c1e, 0x00965a1c, 0x00945616, 0x00935618, 0x0093551c, 0x00945826, 0x00925830, 0x008e5838, 0x00905c3f, 0x00935f3d, 0x00945e33, 0x009c6027, 0x00a8651e, 0x00ad681b, 0x00aa6314, 0x00b3691f, 0x00af641c, 0x00a25b14, 0x0095500e, 0x008e4c0e, 0x008a4c0f, 0x00894c10, 0x00884b10, 0x00884b10, 0x008a4b11, 0x008b4c12, 0x008d4e12, 0x00915217, 0x0095561a, 0x0098591d, 0x00995a1d, 0x00955619, 0x00925318, 0x008d4d16, 0x00884a14, 0x00884912, 0x00884a12, 0x008a4c15, 0x008f5019, 0x00905019, 0x00925018, 0x00975418, 0x009a5619, 0x009c561a, 0x00a05a1b, 0x00a15c1a, 0x00a4601c, 0x00a86320, 0x00a5601c, 0x00a35e1a, 0x00a05b18, 0x00995514, 0x00935012, 0x00925015, 0x008c4d14, 0x00874914, 0x00814514, 0x007d4214, 0x00784014, 0x00753f15, 0x006c3810, 0x0068350e, 0x0062350c, 0x005c330d, 0x004e280a, 0x003f1c04, 0x00351806, 0x00341c0f, 0x00381c0f, 0x003c1e0e, 0x00421f09, 0x005b2d13, 0x00734018, 0x00834d18, 0x00804b16, 0x007b4b20, 0x00402309, 0x0014150d, 0x00081818, 0x000a1719, 0x000c1713, 0x00091714, 0x00081717, 0x000b1415, 0x00091411, 0x00071411, 0x00081412, 0x00061411, 0x0005120f, 0x0008110d, 0x0008100d, 0x0008100c, 0x00050c0a, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280c, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x00645810, 0x00c49c14, 0x00cca215, 0x00cba116, 0x00caa216, 0x00caa216, 0x00cba216, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba216, 0x00cba217, 0x00cca316, 0x00cca316, 0x00cba216, 0x00c49d16, 0x00987e12, 0x005c5710, 0x004f5010, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450d, 0x0041420e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002d2f0b, 0x00292b0a, 0x0026280b, 0x0020230a, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130d, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00060d08, 0x00080d08, 0x00080d08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00080c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f0a, 0x0005100b, 0x00232721, 0x0028251d, 0x0042382c, 0x005e4a3f, 0x00523c32, 0x0054403c, 0x00504040, 0x004e4441, 0x00403835, 0x003d3434, 0x00433a38, 0x005c5452, 0x006f6466, 0x0074666e, 0x007c6c72, 0x00847177, 0x008c737c, 0x00907074, 0x00906a60, 0x0090644c, 0x0094603a, 0x00966032, 0x00996029, 0x009c5f24, 0x009f5d25, 0x009e5d24, 0x009c5d20, 0x00955818, 0x008f5416, 0x008f5419, 0x0090541c, 0x0092551c, 0x008f5118, 0x008e5017, 0x008e5016, 0x00905218, 0x0092541c, 0x0093541c, 0x0094551c, 0x00905417, 0x00905415, 0x00905314, 0x0096581a, 0x00995c1c, 0x009c5f20, 0x009c5f1f, 0x009a5c1b, 0x0096591c, 0x00965822, 0x00965a2f, 0x00945b39, 0x008f583c, 0x00905c44, 0x00915f3f, 0x00935e33, 0x009c6128, 0x00aa6821, 0x00b16b1e, 0x00ab6316, 0x00b0651c, 0x00ac631c, 0x00a05b14, 0x0093500c, 0x008d4c0d, 0x00884a0d, 0x00874b0f, 0x00884b0f, 0x00884b10, 0x0088480c, 0x008e5011, 0x00935214, 0x00985718, 0x009a591a, 0x009d5c1d, 0x009c5c1b, 0x009b5a19, 0x009a581a, 0x0097561a, 0x00935219, 0x00905017, 0x008e4d14, 0x008d4d14, 0x00905017, 0x00905118, 0x00935016, 0x00985318, 0x009c5519, 0x009c5718, 0x00a05a1a, 0x00a15c1a, 0x00a45f1b, 0x00a35e18, 0x00a05a17, 0x009d5814, 0x00995513, 0x00955211, 0x00904e10, 0x008f4e13, 0x00894a12, 0x00834613, 0x007f4212, 0x007b4013, 0x00773f15, 0x00744015, 0x006b3910, 0x0068360e, 0x0063350c, 0x005d330e, 0x004b270b, 0x00391a04, 0x00311706, 0x00321b0f, 0x00381c0f, 0x003d1f0d, 0x004d260e, 0x00663416, 0x00814c1e, 0x0090581f, 0x00854e15, 0x00804e1f, 0x0046280d, 0x0014150d, 0x00081818, 0x000a1719, 0x000c1713, 0x00091714, 0x00081717, 0x000a1415, 0x00091411, 0x00071411, 0x00081412, 0x00061411, 0x0005120f, 0x0008110d, 0x0008100d, 0x0008100c, 0x0008100c, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f0a, 0x00050e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c10, 0x006c5f10, 0x00cca215, 0x00c59e15, 0x00927b13, 0x00927c13, 0x00927c14, 0x00927c14, 0x00937d14, 0x00947e14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f15, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00937d14, 0x00937d14, 0x00937d14, 0x00988014, 0x00a68914, 0x00bc9815, 0x00c9a116, 0x00cca316, 0x00cba216, 0x00b69315, 0x006f6210, 0x004f5010, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450d, 0x0041420e, 0x003c3e0c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050c06, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x0020241e, 0x00292a22, 0x00302b1e, 0x005c4c40, 0x00584139, 0x005d413f, 0x00593f40, 0x0054403f, 0x00433634, 0x003d3534, 0x00443b3c, 0x00514a4b, 0x006a6365, 0x0072676e, 0x007a6d73, 0x00817077, 0x00846d77, 0x00896c72, 0x008d6a67, 0x008e6454, 0x00915f41, 0x00925c37, 0x009a6030, 0x009c6027, 0x009e5e25, 0x00a36228, 0x00a66625, 0x00a36421, 0x009b5c1c, 0x0096581a, 0x0098581d, 0x0099581e, 0x0099581c, 0x00975519, 0x00965418, 0x00965519, 0x0096541a, 0x00945318, 0x00905013, 0x00905112, 0x00905212, 0x00975718, 0x009c5c1c, 0x009f5e1f, 0x00a26121, 0x00a1601e, 0x009c5e1c, 0x00995c20, 0x00965c2a, 0x00945d3b, 0x00935d46, 0x008e5a49, 0x008e5e4c, 0x00905f44, 0x00915c34, 0x009a5f28, 0x00a66520, 0x00ab641a, 0x00ab6119, 0x00aa6218, 0x00a96119, 0x00a05c14, 0x0092500c, 0x008b4a0b, 0x0087480c, 0x00864a0f, 0x00864a10, 0x00884a10, 0x008c4c11, 0x00905013, 0x00965314, 0x009b5815, 0x009d5a15, 0x00a05c16, 0x00a3601a, 0x00a35f1c, 0x00a15d1c, 0x009f5c1c, 0x009e5b1f, 0x009c591d, 0x009b581c, 0x00985519, 0x00985418, 0x0099561a, 0x009d581c, 0x00a15d20, 0x009e5a1c, 0x009f5919, 0x00a35d1c, 0x00a15c1a, 0x00a05b18, 0x00a05917, 0x009b5514, 0x00975411, 0x0092500e, 0x00904e0c, 0x008b4b0c, 0x0088480c, 0x0084450f, 0x007f4412, 0x007b4213, 0x00774114, 0x00723f15, 0x006d3c13, 0x00683910, 0x0064360e, 0x00633410, 0x005d3210, 0x004a260c, 0x00351802, 0x002e1605, 0x0030190c, 0x00381c0e, 0x00472411, 0x00592e11, 0x0074401c, 0x00904f20, 0x009c581b, 0x008f5213, 0x00814c1b, 0x004c2d12, 0x0013140b, 0x00091818, 0x00091618, 0x000c1512, 0x000a1714, 0x00071518, 0x00081416, 0x00081411, 0x00071411, 0x00051310, 0x00051310, 0x00061310, 0x0008120e, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0a, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003e400d, 0x0041420d, 0x0044450d, 0x0048490f, 0x004c4d0f, 0x006d6011, 0x00cca215, 0x00c29c15, 0x00595711, 0x00585810, 0x00595a12, 0x005b5b12, 0x005c5d11, 0x005c5d11, 0x005d5e12, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005e5f13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e13, 0x005d5e12, 0x005d5e12, 0x005c5d12, 0x005c5d12, 0x005c5d11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x00615e12, 0x007e7013, 0x00af8f14, 0x00caa216, 0x00cca316, 0x00c09a15, 0x00786911, 0x004f5010, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0043440e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x002c2d0b, 0x0026280c, 0x0020230a, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050c06, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c08, 0x00202420, 0x00252720, 0x00262418, 0x0052433a, 0x00644d46, 0x00684c48, 0x00583b3a, 0x00503938, 0x00423431, 0x00423a38, 0x00433c3b, 0x004c4645, 0x00696266, 0x00736870, 0x00796d74, 0x00807077, 0x00836d78, 0x00886c74, 0x008c6c6a, 0x008c6557, 0x008f5f48, 0x00905c3c, 0x009a6035, 0x009c602d, 0x009e5f29, 0x009d5d24, 0x00a05f20, 0x00a36420, 0x00a46424, 0x00a26123, 0x009c5b1d, 0x009c5a1c, 0x009c591c, 0x00985518, 0x00965416, 0x00955315, 0x00965416, 0x00935214, 0x00925114, 0x00945416, 0x00955414, 0x009b5a1a, 0x009d5c1c, 0x00a05f1d, 0x00a26220, 0x00a2601c, 0x009d5e1d, 0x00955920, 0x0092592c, 0x00945c40, 0x00915d4b, 0x0089584c, 0x008b5c4e, 0x008d5d44, 0x008e5a33, 0x00945b24, 0x00a05f1b, 0x00a65f17, 0x00a75d17, 0x00a65e16, 0x00a55e16, 0x009d5813, 0x00904e0b, 0x00874708, 0x0087480c, 0x0085480f, 0x00854910, 0x00884b13, 0x008c4c12, 0x00925014, 0x00975312, 0x009b5814, 0x009d5a14, 0x00a05d15, 0x00a36018, 0x00a3601a, 0x00a35f1d, 0x00a35f1f, 0x00a35f20, 0x00a05c1e, 0x00a05c1d, 0x00a05c1e, 0x00a05c1e, 0x00a25d1f, 0x00a25d1f, 0x00a15d1d, 0x009e5a1a, 0x009f5a18, 0x009d5816, 0x009a5413, 0x00995410, 0x00985311, 0x00924f0e, 0x0090500e, 0x008c4e0c, 0x00894c09, 0x00864808, 0x0084470c, 0x00824610, 0x007d4413, 0x00784314, 0x00764116, 0x00703f15, 0x006b3c14, 0x00653910, 0x0063360f, 0x00623411, 0x005c3111, 0x004c250f, 0x00341802, 0x002c1402, 0x0030180a, 0x00341908, 0x004a260f, 0x00653716, 0x007d451e, 0x0093501c, 0x009e5818, 0x008e500f, 0x007f4818, 0x004c2b10, 0x0014140b, 0x000a1818, 0x00091619, 0x000c1512, 0x000b1614, 0x00071518, 0x00081416, 0x00081511, 0x00071411, 0x00051310, 0x00051310, 0x00061310, 0x0008120e, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x006e6011, 0x00cca215, 0x00c29c16, 0x005c5910, 0x00595a12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5c11, 0x005b5b12, 0x005d5c12, 0x008b7713, 0x00c39c16, 0x00cca316, 0x00c29b15, 0x00746611, 0x004f5010, 0x004c4d0f, 0x0048490f, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130d, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050c06, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060d07, 0x001c1f1a, 0x00272821, 0x00232118, 0x00443831, 0x006f5853, 0x00694b46, 0x005a3936, 0x004d3732, 0x00483a34, 0x003b352f, 0x00403b38, 0x00454040, 0x00676164, 0x00736971, 0x00776b73, 0x007d6f76, 0x00806e7a, 0x00856c75, 0x00886b69, 0x00896558, 0x008e604e, 0x00905c42, 0x00965f3a, 0x009a5f31, 0x009f602e, 0x009f5f28, 0x009e5d22, 0x009d5d1c, 0x009e5e1c, 0x009f5f1d, 0x00a05e1f, 0x009e5c1d, 0x009c5819, 0x009a5618, 0x00985515, 0x00985515, 0x00975414, 0x009a5617, 0x009e5a1b, 0x00a25f1e, 0x00a05d1c, 0x00a05c1b, 0x00a05c1a, 0x00a05c1a, 0x00a05d1a, 0x009e5d1a, 0x009c5e1e, 0x00985d28, 0x00945c34, 0x00946047, 0x00936150, 0x00895c50, 0x00865b4f, 0x008c5c46, 0x008c5834, 0x00925824, 0x009c5c1a, 0x00a45d16, 0x00a65e17, 0x00a86018, 0x00a45c16, 0x0098540d, 0x008c4b08, 0x00874708, 0x0085460b, 0x0084480d, 0x0084490f, 0x00894c12, 0x008d4d13, 0x00935014, 0x00985413, 0x009a5713, 0x009d5a14, 0x009e5c13, 0x00a15e18, 0x00a25f19, 0x00a25e1d, 0x00a46020, 0x00a66221, 0x00a4601f, 0x00a5601f, 0x00a4611f, 0x00a76120, 0x00a76220, 0x00a66320, 0x00a25f1c, 0x00a05c1a, 0x009f5a16, 0x009c5614, 0x00985414, 0x00975111, 0x00945011, 0x008e4e0e, 0x008c4e0d, 0x00884c0c, 0x0086490a, 0x0084480a, 0x0081470f, 0x007e4511, 0x00784213, 0x00744014, 0x00704016, 0x006c3e17, 0x00653a14, 0x00623811, 0x00613612, 0x005e3413, 0x00593012, 0x004a230d, 0x00341501, 0x002a1201, 0x00301609, 0x003d1f09, 0x00542f10, 0x00703d18, 0x00854b1e, 0x00934f18, 0x0097510f, 0x00894809, 0x007b4417, 0x00482810, 0x0011130a, 0x00091715, 0x00081517, 0x000b1413, 0x00081514, 0x00081415, 0x00071314, 0x00051411, 0x00071411, 0x00051310, 0x00051310, 0x00061310, 0x0008120e, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x00494a0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005c5c12, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00606013, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x007a6c13, 0x00c09a15, 0x00cca316, 0x00bc9815, 0x00655d10, 0x004d4e10, 0x004b4c0f, 0x0048490f, 0x0044450e, 0x0040400d, 0x003c3e0c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x00292b0a, 0x0026280c, 0x00202309, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050c06, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050c07, 0x001b1e19, 0x00272822, 0x0023211a, 0x00362d28, 0x006e5754, 0x00674642, 0x00593531, 0x00533b32, 0x00473930, 0x0037322a, 0x003b3833, 0x00403c3a, 0x00605c5e, 0x0070666c, 0x0074696f, 0x00776b70, 0x007c6c75, 0x00826d74, 0x00836865, 0x00856458, 0x008c6053, 0x008e5d47, 0x00915c3b, 0x00945c32, 0x00995c2c, 0x009c5c28, 0x009c5b23, 0x009c5c1e, 0x009c5c1b, 0x009c5c19, 0x009d5c19, 0x009f5d1b, 0x00a05d1c, 0x009e5a18, 0x009e5a18, 0x00a05d1b, 0x00a05d1b, 0x00a25e1c, 0x00a25e1c, 0x00a6601f, 0x00a7621f, 0x00a4601c, 0x00a25d19, 0x009f5c18, 0x009f5c17, 0x009c5c1a, 0x009b5c1e, 0x00975c2a, 0x00945b37, 0x00915f46, 0x00905f50, 0x008c5f54, 0x00845b50, 0x00885a47, 0x008a5636, 0x00915627, 0x009c5a1d, 0x00a55d18, 0x00a9611b, 0x00ac641c, 0x00a15913, 0x0094500a, 0x008c4a08, 0x0088470a, 0x0085460c, 0x0084470d, 0x00854910, 0x008b4c13, 0x008e4c12, 0x00944f13, 0x00985314, 0x00975310, 0x009a5811, 0x009c5b12, 0x009e5c16, 0x00a05c18, 0x00a05c1c, 0x00a25e1d, 0x00a4601e, 0x00a4601e, 0x00a6601d, 0x00a5611d, 0x00a7611e, 0x00a7611e, 0x00a5621e, 0x00a4611d, 0x00a25f1a, 0x009f5a16, 0x009c5715, 0x00985414, 0x00945011, 0x00935013, 0x008d4e10, 0x00884c0e, 0x0084480a, 0x00824709, 0x00804508, 0x007e450e, 0x007b4311, 0x00764114, 0x00703e15, 0x006c3c15, 0x00683c16, 0x00643814, 0x00603712, 0x005e3412, 0x005c3414, 0x00583013, 0x0049220d, 0x00331401, 0x00281001, 0x002f1608, 0x0048280f, 0x00613818, 0x00764117, 0x00874919, 0x008d490e, 0x00904a06, 0x00864608, 0x007c4219, 0x00482710, 0x0011130b, 0x000b1615, 0x00081417, 0x000b1413, 0x00081514, 0x00081415, 0x00071314, 0x00051412, 0x00071411, 0x00051310, 0x00051310, 0x00061310, 0x0008120f, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x007c6e13, 0x00c49e16, 0x00cca316, 0x00ab8c14, 0x00545210, 0x004d4e0f, 0x00494a10, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d08, 0x00040d08, 0x00040d08, 0x00040c09, 0x00040c0a, 0x00060d0b, 0x00060d0a, 0x00070d09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080d09, 0x00080c09, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00060d09, 0x00060d09, 0x00060d09, 0x00060d09, 0x00060d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060d07, 0x00070d08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040c06, 0x00171c15, 0x00282b24, 0x0021201a, 0x002d2824, 0x006c5657, 0x00684642, 0x00653f2c, 0x00644431, 0x004c382c, 0x003c342f, 0x003b3833, 0x003c3836, 0x005a5458, 0x006b6268, 0x0073686d, 0x0073666b, 0x00786970, 0x007c696e, 0x007f6463, 0x00826259, 0x00886053, 0x008b5c48, 0x008d5a3d, 0x008e5833, 0x0093582a, 0x00945623, 0x00985822, 0x0098581f, 0x00975818, 0x00995c17, 0x009f5f19, 0x00a2601b, 0x00a35d1c, 0x00a35e1c, 0x00a45f1d, 0x00a35c1a, 0x00a05c18, 0x00a4601c, 0x00a6601d, 0x00a7611e, 0x00a4601c, 0x00a45f1b, 0x00a35f1b, 0x009f5c1a, 0x009c5918, 0x00995a19, 0x00985920, 0x00965c2d, 0x00935c38, 0x00905c44, 0x008d5c4d, 0x008b5d52, 0x00875c52, 0x00885a48, 0x008a5638, 0x00905628, 0x009c5c1f, 0x00a5601b, 0x00ac641c, 0x00ab631b, 0x00a15813, 0x00944f09, 0x008c4a08, 0x0088470a, 0x0087480c, 0x0084480e, 0x00854910, 0x008a4c11, 0x008d4c11, 0x00934e12, 0x00975113, 0x00975312, 0x00975411, 0x009a5814, 0x009d5c17, 0x009f5c19, 0x00a05c1a, 0x00a15d1c, 0x00a45f1c, 0x00a4601c, 0x00a7611d, 0x00a7621c, 0x00a5601b, 0x00a6601d, 0x00a6601d, 0x00a4601c, 0x00a05c18, 0x009d5915, 0x009a5714, 0x00975312, 0x00935011, 0x00905113, 0x008c4f11, 0x00864a0e, 0x0083480c, 0x0082450a, 0x0080440b, 0x007c4410, 0x00784212, 0x00724016, 0x006e3d17, 0x006c3d18, 0x00653917, 0x00603513, 0x00603514, 0x005e3413, 0x005d3414, 0x00593013, 0x0049220d, 0x00331403, 0x00281001, 0x00301807, 0x00533012, 0x006c3f18, 0x007c4415, 0x00864814, 0x008c4b10, 0x008c4806, 0x0087460c, 0x007c421a, 0x0044250e, 0x0011130a, 0x000a1614, 0x00081516, 0x000a1513, 0x00081513, 0x000a1414, 0x00081414, 0x00071412, 0x00081210, 0x00081110, 0x00081110, 0x0006100f, 0x0005100e, 0x0005100e, 0x0005100e, 0x0005100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0a, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e08, 0x00040e08, 0x00040d08, 0x00040d08, 0x00050e08, 0x00060e08, 0x00050e08, 0x00040e08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00050c08, 0x00060c08, 0x00060c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c09, 0x00040c09, 0x00040c08, 0x00040e08, 0x00040e08, 0x00040e08, 0x00040e08, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005d5b12, 0x005c5c11, 0x005c5d11, 0x00606013, 0x00606012, 0x00606012, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00626313, 0x00626313, 0x00626313, 0x00626313, 0x00626313, 0x00626313, 0x00626312, 0x00626312, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x00937c14, 0x00cba216, 0x00caa116, 0x00857212, 0x004d4e10, 0x004b4c0f, 0x0048490f, 0x0044450e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050f08, 0x00031008, 0x00031008, 0x00031008, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c09, 0x00060e0a, 0x00060e09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d07, 0x00060e06, 0x00060e06, 0x00040f06, 0x00031008, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00080d09, 0x00080d09, 0x00080d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040c06, 0x000e130c, 0x002b2c27, 0x00282621, 0x00282320, 0x00634f51, 0x0075524e, 0x00754c34, 0x006e4830, 0x00593e2e, 0x0044362e, 0x003f3831, 0x003c3836, 0x00534e50, 0x006c6368, 0x0073686c, 0x0071656a, 0x00786970, 0x007c686d, 0x007e6363, 0x007f6058, 0x00845d51, 0x00875b48, 0x0088573d, 0x00895534, 0x008d542a, 0x008f5322, 0x0091531f, 0x0092541c, 0x00925516, 0x00965816, 0x009c5a17, 0x009d5a17, 0x009e5917, 0x00a25c1b, 0x00a45e1c, 0x00a55e1c, 0x00a6601c, 0x00a6601d, 0x00a6601d, 0x00a4601c, 0x00a25c19, 0x009d5814, 0x009c5916, 0x009c5919, 0x00985619, 0x00955719, 0x00945620, 0x0094592f, 0x00935c38, 0x00905c43, 0x008e5c4c, 0x008a5c51, 0x00885e52, 0x008a5c49, 0x008b5839, 0x0091582a, 0x009c5c20, 0x00a6601c, 0x00ab641c, 0x00ab621b, 0x00a25812, 0x00954e0b, 0x00904c0c, 0x008b490d, 0x0088480d, 0x0085480f, 0x00854a0f, 0x00894c10, 0x008c4c10, 0x00904c13, 0x00944f13, 0x00955114, 0x00955412, 0x00985614, 0x009c5a17, 0x009e5c18, 0x00a05c18, 0x00a15c18, 0x00a35d1a, 0x00a45d1a, 0x00a4601c, 0x00a55f1a, 0x00a35e19, 0x00a4601c, 0x00a4601c, 0x00a3601b, 0x00a3601b, 0x009c5914, 0x009a5713, 0x00965212, 0x00915010, 0x008d4f11, 0x00894c10, 0x00874a0e, 0x0084470c, 0x0084440c, 0x0080430d, 0x007b4111, 0x00764014, 0x00703f16, 0x006b3c18, 0x00683916, 0x00623714, 0x005e3210, 0x005e3311, 0x005f3312, 0x005d3412, 0x005a3012, 0x0048230c, 0x00331405, 0x002b1104, 0x003a1f0e, 0x00593411, 0x0078481c, 0x00824915, 0x00834712, 0x0085470e, 0x008d4b0e, 0x00884811, 0x007a431a, 0x0040220b, 0x0012140a, 0x000b1514, 0x00091516, 0x000a1513, 0x00081513, 0x000a1414, 0x00081414, 0x00071412, 0x00081110, 0x00081110, 0x00081110, 0x0006100e, 0x00051010, 0x0005100e, 0x0005100e, 0x0005100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050c08, 0x00070c08, 0x00080c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005c5c12, 0x005c5d11, 0x00606013, 0x00606012, 0x00606012, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00626314, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00626313, 0x00626312, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x005e5f13, 0x005c5d11, 0x005c5c11, 0x00605c12, 0x00b79515, 0x00cca316, 0x00b69315, 0x00595510, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00141809, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050f08, 0x00031008, 0x00031008, 0x00031008, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d07, 0x00060e06, 0x00060e06, 0x00040f06, 0x00031008, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00050d07, 0x00040e08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040d07, 0x00090e08, 0x00232620, 0x0024241e, 0x0024201a, 0x005a4a49, 0x007c5d58, 0x00754c38, 0x0070472d, 0x0066432d, 0x00523929, 0x0045372c, 0x00403935, 0x004c484a, 0x00686265, 0x0070666a, 0x0070646a, 0x0075656c, 0x0078656a, 0x007d6264, 0x007f605c, 0x00825c52, 0x00845948, 0x0085563d, 0x00865432, 0x00885128, 0x00894f20, 0x008d501d, 0x008f501c, 0x00935519, 0x00945717, 0x00985616, 0x00985513, 0x009b5614, 0x009f5816, 0x00a05a17, 0x00a15b14, 0x00a45d18, 0x00a45f1a, 0x00a45f1b, 0x00a35e1a, 0x00a25c19, 0x00a15c18, 0x00a05c1b, 0x009a5818, 0x00975618, 0x0094571b, 0x00945621, 0x0092592f, 0x00935c3a, 0x008f5b41, 0x008e5c49, 0x008b5d50, 0x00885f50, 0x008c5e49, 0x008c5a3c, 0x0092592c, 0x009f6024, 0x00aa641f, 0x00af681f, 0x00b06820, 0x00a95f19, 0x009b5410, 0x00945010, 0x008e4d10, 0x008b4c12, 0x00874a10, 0x0083490e, 0x00864c10, 0x008a4c11, 0x008d4c14, 0x008f4d14, 0x00904f14, 0x00935013, 0x00965414, 0x009a5815, 0x009e5a18, 0x00a05a17, 0x00a05916, 0x00a15a17, 0x00a35b18, 0x00a45c18, 0x00a55c18, 0x00a45c18, 0x00a45e1b, 0x00a45f1b, 0x00a05d18, 0x009b5814, 0x009c5913, 0x00995512, 0x00955312, 0x00915011, 0x008d4e12, 0x008a4c10, 0x00874a0e, 0x0084460b, 0x0082420c, 0x00804110, 0x007a4014, 0x00743d15, 0x006e3d18, 0x00683b16, 0x00623713, 0x00603513, 0x005e3210, 0x005c3211, 0x005d3311, 0x005c3311, 0x00593010, 0x0049240c, 0x00351404, 0x00301404, 0x004c2c1a, 0x006c421e, 0x007b491b, 0x007d4411, 0x00783e0c, 0x007d420e, 0x008c4c14, 0x00894b15, 0x0078431a, 0x003a1e06, 0x0013140c, 0x000b1413, 0x00081415, 0x00081513, 0x00081513, 0x000a1414, 0x00081413, 0x00071412, 0x00081210, 0x00081110, 0x00081110, 0x0006100e, 0x00051010, 0x0005100e, 0x0004100d, 0x0004100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00050c08, 0x00070c08, 0x00080c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006e6011, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00626314, 0x00626313, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x005d5e12, 0x005c5d11, 0x005b5b12, 0x008c7914, 0x00caa116, 0x00cba216, 0x007b6a11, 0x004d4e10, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0036370c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0024250b, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040f08, 0x00031008, 0x00031008, 0x00031008, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d07, 0x00060e06, 0x00060e06, 0x00040f06, 0x00031008, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00080f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00061008, 0x00061008, 0x00050f08, 0x00050f08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00050e08, 0x00070d08, 0x001b1f18, 0x0022261f, 0x00222018, 0x004c423e, 0x007e6760, 0x00704937, 0x007d5034, 0x007a4f33, 0x0064422a, 0x004c3727, 0x00403833, 0x00474446, 0x00645e62, 0x006b6268, 0x0071656c, 0x0073656c, 0x00736165, 0x00786061, 0x007d605b, 0x00805b53, 0x00805748, 0x0082543c, 0x00825132, 0x00844f29, 0x00884f21, 0x008c501e, 0x008e501d, 0x0092541b, 0x00935518, 0x00955417, 0x00975414, 0x009b5514, 0x009e5814, 0x00a15c16, 0x00a45e16, 0x00a45f18, 0x00a15c18, 0x00a15c18, 0x00a05b18, 0x00a05b18, 0x009d5814, 0x009c5817, 0x00995718, 0x00955417, 0x0094541b, 0x00915423, 0x00905730, 0x00915b3c, 0x008e5a3f, 0x008e5c48, 0x008c5f4e, 0x0088604e, 0x008c5e48, 0x008f5c3d, 0x00945a2d, 0x00a16125, 0x00af6924, 0x00b46e23, 0x00b26a20, 0x00ab601b, 0x009c5411, 0x00965413, 0x00905012, 0x008c4e14, 0x00864c11, 0x0081490e, 0x0082490d, 0x00874c10, 0x00894c14, 0x00894c14, 0x00894d13, 0x008d4d12, 0x00945114, 0x00995314, 0x009e5616, 0x00a15818, 0x00a15816, 0x00a15815, 0x00a35a16, 0x00a45c18, 0x00a45c18, 0x00a25c17, 0x00a35c18, 0x00a25c18, 0x00a05b18, 0x009e5a15, 0x009c5812, 0x00985512, 0x00955312, 0x00925012, 0x008c4d11, 0x00894b10, 0x00874a0e, 0x00824509, 0x0080400c, 0x007f3e10, 0x00783e13, 0x00723b15, 0x006c3b16, 0x00653c15, 0x00633914, 0x00603513, 0x005e3410, 0x005c3311, 0x005c3311, 0x005c3110, 0x00582f0f, 0x004d280e, 0x003a1804, 0x003a1909, 0x0055301c, 0x006f421c, 0x00713d0f, 0x00713807, 0x006f3808, 0x00763c0d, 0x00854614, 0x00884a18, 0x00724016, 0x00331a01, 0x0013160e, 0x000b1413, 0x00081415, 0x00081412, 0x000a1513, 0x000b1412, 0x00081411, 0x00081412, 0x00081210, 0x00081110, 0x00081110, 0x0007100f, 0x00051010, 0x0005100e, 0x0004100d, 0x0004100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d06, 0x00040d06, 0x00050d06, 0x00070c06, 0x00080c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0047480e, 0x00494a10, 0x004d4e0f, 0x006e6011, 0x00cca216, 0x00c39d16, 0x00685f11, 0x00656012, 0x00686112, 0x00696412, 0x006a6414, 0x006b6513, 0x006b6513, 0x006b6513, 0x006c6613, 0x006c6613, 0x006c6613, 0x006c6613, 0x006c6613, 0x006c6713, 0x006c6813, 0x006c6713, 0x006c6713, 0x006c6713, 0x006c6713, 0x006c6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006d6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006a6614, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00616112, 0x00606012, 0x005e5f13, 0x005c5d11, 0x005c5c11, 0x00646012, 0x00c49e16, 0x00cca316, 0x009f8213, 0x004c4d10, 0x004c4d0f, 0x0048490f, 0x0044450d, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f09, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d06, 0x00040d06, 0x00050e07, 0x00050e07, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00050d07, 0x00050e06, 0x00050e06, 0x00050e06, 0x00050e08, 0x00050d09, 0x00050d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x0004100a, 0x0004100a, 0x00040f0a, 0x00040f0a, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f09, 0x00060e08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050e08, 0x00040e08, 0x00040f08, 0x00031008, 0x00040f09, 0x00050f08, 0x00050f08, 0x00050f08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050d07, 0x00060d08, 0x00060e08, 0x00060e09, 0x00050e09, 0x00050e09, 0x00040d09, 0x00060f09, 0x00060e09, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050f08, 0x00060e08, 0x00060d08, 0x00121812, 0x00222820, 0x00222118, 0x003e3834, 0x0076635e, 0x006e4e3c, 0x0081543b, 0x00815031, 0x006d4525, 0x00573a23, 0x0046382f, 0x00444041, 0x005f5b5f, 0x00686168, 0x006e646a, 0x0072646b, 0x00705e64, 0x00755e60, 0x00775c59, 0x007b5952, 0x007c5649, 0x007e543f, 0x007f5035, 0x0083502d, 0x00864f26, 0x008a5022, 0x008d5020, 0x008e521c, 0x00905218, 0x00965518, 0x00985618, 0x009d5817, 0x00a05b18, 0x00a25d17, 0x00a05c14, 0x009f5a14, 0x00a05c16, 0x00a05b18, 0x009e5915, 0x009e5915, 0x009f5917, 0x009c5818, 0x00975415, 0x00925215, 0x0090511b, 0x008e5121, 0x008c5430, 0x008d583c, 0x008f5d44, 0x008c5d4a, 0x008b5f50, 0x008b6150, 0x008d5f4b, 0x00905c41, 0x00975d32, 0x00a46228, 0x00b06924, 0x00b16c20, 0x00b1681e, 0x00b0661e, 0x00a55e16, 0x00985611, 0x00915313, 0x008c4e12, 0x00854a10, 0x0084480f, 0x0082480e, 0x00844910, 0x00854b13, 0x00854c15, 0x00854c14, 0x00884c11, 0x008d4d10, 0x00965014, 0x009c5215, 0x009d5415, 0x009d5514, 0x009f5714, 0x00a15917, 0x00a35b19, 0x00a25a18, 0x00a25b19, 0x00a35b19, 0x00a25c18, 0x009f5916, 0x009e5815, 0x009c5714, 0x00985411, 0x00945312, 0x00915010, 0x008a4c10, 0x0088480e, 0x0084460d, 0x0080430b, 0x007c3f0d, 0x00793c10, 0x00753e14, 0x006e3c15, 0x00693b16, 0x00653b17, 0x00643816, 0x00603514, 0x005d3411, 0x005c3311, 0x005c3311, 0x005c3210, 0x005a3111, 0x004e280f, 0x003d1a04, 0x00401a05, 0x005a301a, 0x00663512, 0x006c360b, 0x006d3608, 0x006c360d, 0x0070360d, 0x007e4012, 0x0081481b, 0x00663814, 0x002b1604, 0x00121510, 0x000b1412, 0x00081414, 0x00081412, 0x00081411, 0x000b1410, 0x00081410, 0x00071410, 0x00081210, 0x0008110f, 0x0008110f, 0x0007100e, 0x0008120f, 0x0007110f, 0x0005100c, 0x00040f0b, 0x0007110c, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x00050f0a, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040e0a, 0x00040e09, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f09, 0x00050f09, 0x00060f09, 0x00050e08, 0x00050e08, 0x00040f08, 0x00040f07, 0x00040f07, 0x00040f07, 0x00040f07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00040f07, 0x00040f07, 0x00040f07, 0x00040f07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f09, 0x00060e08, 0x00040d07, 0x00040d06, 0x00040d08, 0x00040d08, 0x00040d06, 0x00050c06, 0x00050d05, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00040d05, 0x00040e06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250b, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x00393b0c, 0x003c3e0c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004c4d0f, 0x006c6011, 0x00caa116, 0x00cba216, 0x00c69f16, 0x00c6a016, 0x00c6a017, 0x00c5a018, 0x00c5a018, 0x00c5a018, 0x00c5a018, 0x00c5a018, 0x00c5a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c49f18, 0x00c49f19, 0x00c49f19, 0x00c39f18, 0x00c39f18, 0x00c3a018, 0x00c3a018, 0x00c29f18, 0x00c29e18, 0x00c29e18, 0x00c29e18, 0x00bc9b18, 0x009e8716, 0x00696614, 0x00636414, 0x00626312, 0x00616112, 0x00606013, 0x00606013, 0x005e5f12, 0x005c5c11, 0x005c5b12, 0x00b49315, 0x00cca316, 0x00ae8d14, 0x004c4d10, 0x004c4d0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003c3e0c, 0x00393b0c, 0x0034350c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0024250b, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00070f0a, 0x00050d09, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x000b110b, 0x001b2219, 0x00212219, 0x00302c28, 0x006e625d, 0x00735a4b, 0x00835847, 0x00805032, 0x00744824, 0x00644023, 0x004a3428, 0x00443b3c, 0x005c585c, 0x00646068, 0x006b6369, 0x006e6169, 0x00706065, 0x00725d5f, 0x00745b59, 0x00785953, 0x007b584c, 0x007c5443, 0x007c513a, 0x00804f32, 0x00844e29, 0x00884f25, 0x008d5124, 0x008f5220, 0x0090531c, 0x0096571c, 0x00995819, 0x009c5919, 0x00a05c1a, 0x00a15d18, 0x00a05c15, 0x00a05c16, 0x00a15c18, 0x00a15c18, 0x009e5915, 0x009e5915, 0x009e5717, 0x00995415, 0x00945315, 0x00905014, 0x008d501a, 0x008b5023, 0x008d5634, 0x008d593f, 0x008b5c47, 0x00895c4c, 0x008b6051, 0x008d6354, 0x00916352, 0x00935f47, 0x00985e34, 0x00a66228, 0x00af6823, 0x00b26c1f, 0x00b46b1e, 0x00b0661a, 0x00a86114, 0x009c580f, 0x00955614, 0x008d4f11, 0x0086480e, 0x0082440d, 0x0080440c, 0x007f430c, 0x007c430c, 0x007a430c, 0x0079420c, 0x007e440c, 0x00854810, 0x008c4b14, 0x00914e15, 0x00955012, 0x00975310, 0x009b5514, 0x009d5618, 0x009e5718, 0x00a0581a, 0x00a35c1b, 0x00a45c1b, 0x00a35c1b, 0x00a05818, 0x009f5817, 0x009b5514, 0x00985412, 0x00945111, 0x008f4f0e, 0x00894a0f, 0x00884810, 0x0082430d, 0x007d400d, 0x00793f10, 0x00743c10, 0x00733f15, 0x006c3c18, 0x00683c17, 0x00653916, 0x00623714, 0x005e3414, 0x005c3211, 0x005c3311, 0x005c3110, 0x005a3010, 0x00583011, 0x004f280e, 0x00401b01, 0x00471e07, 0x005b2e17, 0x00653110, 0x00683208, 0x00683108, 0x006b3410, 0x00713711, 0x007a3c11, 0x007c451d, 0x005a3114, 0x00231206, 0x00101412, 0x00091514, 0x00081414, 0x00081414, 0x00081410, 0x000a120f, 0x0007130e, 0x0005130f, 0x0007120e, 0x0007110d, 0x0007110d, 0x0007110d, 0x0008110e, 0x0006100c, 0x0006100b, 0x00051009, 0x0007110b, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040d07, 0x00040d06, 0x00040c08, 0x00040c09, 0x00040d08, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0020230a, 0x00292b0b, 0x002c2d0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0048490f, 0x004c4d0f, 0x00535110, 0x009f8414, 0x00caa216, 0x00cba216, 0x00cba317, 0x00cba317, 0x00cba417, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cba419, 0x00a88d16, 0x00656414, 0x00626313, 0x00616112, 0x00616112, 0x00606012, 0x005e5f13, 0x005d5e11, 0x005c5c12, 0x00a78a14, 0x00cca316, 0x00b08f14, 0x004c4d10, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d06, 0x00040d06, 0x00040d06, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00070f0a, 0x00050d09, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00060e0a, 0x00060e09, 0x00070f08, 0x00111911, 0x001f211a, 0x00282823, 0x0068605b, 0x007d685e, 0x00846052, 0x007e5136, 0x007c4f28, 0x006e4624, 0x00503322, 0x00463835, 0x005c5559, 0x00645f68, 0x00696169, 0x006c6068, 0x006f6065, 0x00715e61, 0x00725c5b, 0x00745954, 0x0078584d, 0x007b5545, 0x007c523c, 0x007e4f34, 0x00814e2b, 0x00875027, 0x008c5226, 0x008e5322, 0x0090531f, 0x0096571f, 0x0098581c, 0x009b5718, 0x009e5a1b, 0x00a15e1b, 0x00a05c18, 0x00a05c16, 0x00a05c17, 0x00a15c18, 0x009d5814, 0x009d5816, 0x00985415, 0x00945214, 0x00904f14, 0x008b4c12, 0x00894e17, 0x00874d1f, 0x0085502c, 0x00845337, 0x00845641, 0x00855a4c, 0x00885f54, 0x008c6355, 0x00926657, 0x00926148, 0x00975e34, 0x00a56429, 0x00b06a25, 0x00b26c1f, 0x00b46a1c, 0x00b1661a, 0x00a85f14, 0x00a15b12, 0x00985613, 0x00904f11, 0x0088470d, 0x0081410b, 0x007e3f0a, 0x007b3c08, 0x00773c08, 0x00743c08, 0x00733c09, 0x00743c0a, 0x00773f0c, 0x007f4513, 0x00874a15, 0x008c4c12, 0x00904e10, 0x00945011, 0x00985216, 0x00995418, 0x00985315, 0x009c5819, 0x009f5818, 0x00a05818, 0x00a05819, 0x009e5718, 0x00995414, 0x00955212, 0x00905011, 0x008b4c0d, 0x0088490f, 0x00864610, 0x00804410, 0x007e4210, 0x00763d0e, 0x00703b0e, 0x00703e14, 0x006b3d17, 0x00663b15, 0x00633814, 0x00603513, 0x005c3311, 0x005c3211, 0x005d3412, 0x005b3010, 0x00582f0f, 0x00562f10, 0x004e290c, 0x00401c00, 0x0050280e, 0x005c3017, 0x0064300f, 0x00673109, 0x006a3309, 0x006b3410, 0x00733812, 0x00783c11, 0x0074411c, 0x004a290f, 0x00170d05, 0x000e1412, 0x00091413, 0x00071413, 0x00071413, 0x00081410, 0x0009120e, 0x0007130c, 0x0005130e, 0x0006110d, 0x0006100c, 0x0007100d, 0x0007100d, 0x00040e0b, 0x00040d0a, 0x0005100b, 0x0008110b, 0x00050f09, 0x0005100a, 0x0005100a, 0x00050f0a, 0x00050f0a, 0x00050f0a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e0a, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040d07, 0x00040d06, 0x00040d06, 0x00040d08, 0x00040d06, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c06, 0x00060c06, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0048490e, 0x004b4c0f, 0x004d4e0f, 0x00585410, 0x008b7612, 0x00957d13, 0x00967e13, 0x00978014, 0x00978014, 0x00988114, 0x00988214, 0x00998215, 0x009a8314, 0x009a8315, 0x009a8315, 0x009b8415, 0x009b8415, 0x009b8415, 0x009c8416, 0x009c8416, 0x009c8515, 0x009c8515, 0x009c8615, 0x009c8615, 0x009d8515, 0x009e8615, 0x009e8616, 0x009e8716, 0x009e8716, 0x009f8816, 0x009f8816, 0x009f8816, 0x009f8815, 0x00a08816, 0x00a08916, 0x00ba9918, 0x00cca519, 0x00c8a318, 0x00756c14, 0x00636414, 0x00626312, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5e11, 0x005c5c11, 0x00a08514, 0x00cca316, 0x00b09014, 0x004d4e10, 0x004f5010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x001d2009, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00060e08, 0x00060f06, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00070f0a, 0x00050d09, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e08, 0x000b130b, 0x00181d17, 0x00242720, 0x005a544f, 0x00816e6c, 0x007d5e59, 0x00785038, 0x007a4e28, 0x00784a25, 0x005f3c25, 0x0045332a, 0x00554c4e, 0x00645e68, 0x00676069, 0x006b6068, 0x006c5f65, 0x00705d60, 0x00705a58, 0x00725854, 0x0075584e, 0x00795747, 0x007a543f, 0x007c5036, 0x00804f2c, 0x00855128, 0x008a5329, 0x008d5425, 0x00905321, 0x0094561f, 0x0097561c, 0x009b591c, 0x009e5a1c, 0x009e5a1b, 0x009e5b18, 0x009c5814, 0x009d5814, 0x009e5915, 0x009b5612, 0x00985411, 0x00945214, 0x00904f14, 0x008a4c12, 0x0083460e, 0x00804711, 0x0080491a, 0x007c4924, 0x007e4e32, 0x007c4f3c, 0x007b5045, 0x0080584f, 0x00886055, 0x00906758, 0x0093644a, 0x00965f35, 0x00a6672c, 0x00b36e28, 0x00b26c20, 0x00b36a1c, 0x00b4671b, 0x00ac6117, 0x00a45c12, 0x009a5410, 0x00944f10, 0x0088450c, 0x00803f09, 0x007c3b08, 0x007c3c09, 0x007a3d0b, 0x00703607, 0x00693304, 0x00673204, 0x00673508, 0x006e3b0e, 0x00764010, 0x007e440f, 0x00884a10, 0x008f4d11, 0x00925014, 0x00945016, 0x00985418, 0x009a561b, 0x009c5818, 0x009c5818, 0x009b5518, 0x00985315, 0x00945011, 0x00904f10, 0x008c4d0f, 0x00894c0e, 0x00864810, 0x00834510, 0x007f4410, 0x007c4210, 0x00753f10, 0x00703c11, 0x006e3d14, 0x006a3d17, 0x00653a14, 0x00623713, 0x00603413, 0x005d3412, 0x005e3413, 0x005d3412, 0x005b3010, 0x00572e0d, 0x00552f0e, 0x004f2a0b, 0x00482102, 0x00572e10, 0x00613618, 0x00673411, 0x006c360e, 0x006f370e, 0x006e3813, 0x00713812, 0x00743c11, 0x00673a15, 0x00371d05, 0x00140e06, 0x000d1411, 0x00081412, 0x00051312, 0x00051312, 0x0008120f, 0x0009110d, 0x0007110c, 0x0006110d, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00040d0a, 0x0005100a, 0x0007110a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040d07, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d05, 0x00040e04, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c05, 0x00060c05, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c09, 0x00191c09, 0x001d2008, 0x0024250b, 0x0024250b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x0036370c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x00505010, 0x00525310, 0x00535411, 0x00555610, 0x00565711, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d13, 0x005d5e13, 0x005d5e13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606012, 0x00606012, 0x00606012, 0x00606013, 0x00606012, 0x00606012, 0x00616114, 0x00616114, 0x00616114, 0x00626314, 0x00626314, 0x00626314, 0x00636414, 0x00636414, 0x00736c14, 0x00c7a218, 0x00cca519, 0x00796f14, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x00606013, 0x005e5f12, 0x005c5c11, 0x00a08514, 0x00cca316, 0x00b09014, 0x004d4e10, 0x004f5010, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0036370c, 0x0034350c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e08, 0x00060f05, 0x00040e04, 0x00040e04, 0x00040e04, 0x00050d06, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d09, 0x00080e0a, 0x00060c08, 0x00080e0a, 0x00070c09, 0x00070c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060e0a, 0x00060e08, 0x00081008, 0x0010140e, 0x00242720, 0x004c4542, 0x00806e70, 0x007c5f5d, 0x00744f3c, 0x00774a28, 0x00794a26, 0x0069442c, 0x004e362d, 0x00514444, 0x00605860, 0x00666069, 0x006c6168, 0x006a5c62, 0x006e5c5e, 0x006c5859, 0x00705955, 0x0073584f, 0x0077584a, 0x00795644, 0x007a5139, 0x007e5030, 0x0083522c, 0x0088542b, 0x008c5427, 0x008e5523, 0x0090541f, 0x0093551c, 0x00965519, 0x00985418, 0x00985414, 0x00995413, 0x009c5715, 0x009c5615, 0x00995412, 0x00985411, 0x0092500e, 0x008c4c0f, 0x00884910, 0x0082450d, 0x007c400b, 0x00773e0b, 0x00723c0e, 0x006e3c16, 0x00784628, 0x00784934, 0x00784c3c, 0x007c5147, 0x00835a50, 0x008e6758, 0x0092674e, 0x00946038, 0x00a3662c, 0x00b06e27, 0x00b36d20, 0x00b3691c, 0x00b7691d, 0x00b06418, 0x00a45b12, 0x009c5410, 0x00954e11, 0x0089450c, 0x007d3b05, 0x007f3f08, 0x00925019, 0x0090501b, 0x008f501e, 0x00763b0d, 0x005f2800, 0x005f2e07, 0x0066360f, 0x006d3a11, 0x00733d0f, 0x007b400e, 0x0082450f, 0x00894a12, 0x008d4c14, 0x00904e14, 0x00945016, 0x00945214, 0x00945114, 0x00925013, 0x00914f11, 0x00915012, 0x008f4f11, 0x00884b0f, 0x00874b0f, 0x00834710, 0x0080440f, 0x007a400f, 0x00794110, 0x00743f12, 0x00703d12, 0x006c3d14, 0x006a3c16, 0x00653a14, 0x00623713, 0x00603513, 0x005d3412, 0x005e3413, 0x005f3414, 0x005b3110, 0x00552d0c, 0x00542e0d, 0x00502b0a, 0x004e2707, 0x005c3111, 0x00673a19, 0x006d3815, 0x00713914, 0x00733a11, 0x00743b14, 0x00753c14, 0x00703c12, 0x0056300f, 0x00231100, 0x0011100a, 0x000c1411, 0x00081410, 0x00051312, 0x00071210, 0x0008120f, 0x0008110d, 0x0007110c, 0x0006110d, 0x00050f0d, 0x00050f0c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00040e0b, 0x00040e09, 0x00051008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d09, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e09, 0x00060e09, 0x00060e08, 0x00050e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040e05, 0x00040e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060d06, 0x00060c05, 0x00060c05, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x002c2d0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x004f5010, 0x00515110, 0x00545510, 0x00565711, 0x00585810, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00686514, 0x00c6a219, 0x00cca519, 0x00796f14, 0x00636414, 0x00636414, 0x00626312, 0x00606013, 0x00606013, 0x005d5e12, 0x005c5c11, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d0f, 0x0048490f, 0x0044450e, 0x0040400d, 0x003b3c0c, 0x0038380c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0020230a, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x000c100b, 0x00161812, 0x003a3632, 0x00776868, 0x007b625f, 0x00714f3d, 0x00734829, 0x00764828, 0x00684130, 0x00593e36, 0x0052403f, 0x005d5359, 0x00645c64, 0x00685d64, 0x00695c62, 0x006c5a5c, 0x006c5858, 0x006e5855, 0x00705750, 0x0074584c, 0x00775849, 0x0079523d, 0x007d5137, 0x00805232, 0x0085542e, 0x00885429, 0x008a5424, 0x008c5420, 0x00905520, 0x0094561c, 0x0097561a, 0x00985517, 0x00995414, 0x00995414, 0x00985313, 0x00965214, 0x00905010, 0x008a4c0d, 0x0083480c, 0x007d440c, 0x0078400b, 0x00763e0f, 0x0070380a, 0x006d370c, 0x0075421c, 0x00895633, 0x008c5834, 0x008b5838, 0x0083543d, 0x00855a49, 0x008f6655, 0x00926852, 0x0094603e, 0x00a0632c, 0x00ad6b24, 0x00b46c20, 0x00b3681c, 0x00b4651a, 0x00b26519, 0x00a85d14, 0x009e5512, 0x00964e10, 0x008b440c, 0x0084410b, 0x008b4c12, 0x0098551c, 0x009c531a, 0x009d5418, 0x00904c15, 0x0071370b, 0x00572200, 0x00582507, 0x00613011, 0x00693612, 0x00703e14, 0x00794414, 0x00804812, 0x00844812, 0x00894b14, 0x008d4e14, 0x00904f15, 0x00904f15, 0x008e4f14, 0x008e4f13, 0x008f5014, 0x00884a0e, 0x0086480f, 0x0084460d, 0x007e430e, 0x0079400c, 0x00753d0b, 0x00723e0e, 0x00703f11, 0x006c3c10, 0x006c3c14, 0x006a3c16, 0x00663914, 0x00623713, 0x00603513, 0x005d3412, 0x00603514, 0x00603414, 0x005b3011, 0x00542c0c, 0x00542d0c, 0x00512a0c, 0x00502709, 0x005c3010, 0x006c3b19, 0x00703b15, 0x00733c14, 0x00743c11, 0x00753d10, 0x00744014, 0x00683c17, 0x003a2008, 0x00150d04, 0x000c100e, 0x00081410, 0x00081410, 0x0007130f, 0x0007130f, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100d, 0x00070e0f, 0x00070e0f, 0x00070e0d, 0x00070e0c, 0x00070e0d, 0x00070e0c, 0x00060e09, 0x00060e08, 0x00040e09, 0x00030f09, 0x0004100a, 0x00040f09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x00393b0d, 0x003c3e0c, 0x0041420e, 0x0044450d, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00515110, 0x00535410, 0x00555611, 0x00585810, 0x00585911, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca519, 0x00796f14, 0x00646414, 0x00626314, 0x00626312, 0x00616112, 0x00606012, 0x005d5e12, 0x005c5c11, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d0f, 0x00484910, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d09, 0x00080c08, 0x000a0e07, 0x002c2b26, 0x00736666, 0x007b625c, 0x00714f3c, 0x00734829, 0x00754828, 0x006d4632, 0x00604038, 0x00503936, 0x0056484c, 0x0060585e, 0x00655b62, 0x00685a60, 0x0068585a, 0x006a5656, 0x006a5654, 0x006c5650, 0x0071564d, 0x00745748, 0x00795441, 0x007c523b, 0x00805335, 0x00835430, 0x0085522b, 0x00865125, 0x00875020, 0x008c5420, 0x0090541c, 0x00915418, 0x00925214, 0x00925010, 0x00945011, 0x00935012, 0x00915014, 0x00894c10, 0x0082470e, 0x0078420b, 0x00733d09, 0x006c3607, 0x006c370b, 0x00683309, 0x007f4a20, 0x008e5830, 0x00945f36, 0x00945c30, 0x00945c33, 0x008f5c3a, 0x00906046, 0x00916752, 0x00966852, 0x0096603c, 0x00a0612b, 0x00aa6720, 0x00b0681c, 0x00b2661a, 0x00b4651a, 0x00b3661a, 0x00ac6016, 0x00a25815, 0x00964e11, 0x008b440c, 0x0089460f, 0x00925315, 0x009b581b, 0x009f5719, 0x00a05618, 0x00955018, 0x00854818, 0x005a2500, 0x00502001, 0x00572708, 0x0060300f, 0x00683812, 0x006e3c10, 0x00723d0b, 0x0078400d, 0x007f4410, 0x00834710, 0x00884810, 0x00884811, 0x008a4b13, 0x008a4c12, 0x00884a10, 0x0082440b, 0x0082440d, 0x007f410c, 0x00783f0b, 0x00733c09, 0x00733d0c, 0x00713f0f, 0x006f3e12, 0x006a3c10, 0x006a3c14, 0x00693c16, 0x00663914, 0x00633713, 0x00603513, 0x005c3311, 0x005e3413, 0x005e3113, 0x005a3010, 0x00542c0d, 0x00512b0c, 0x0050290a, 0x00502809, 0x005b3010, 0x006a3b19, 0x006f3d14, 0x00703d11, 0x006e3c0f, 0x006c3d0e, 0x006c3c13, 0x00532c0d, 0x00251000, 0x00100e06, 0x000b1310, 0x00081410, 0x0006120e, 0x0007130f, 0x0007130f, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x00070e0e, 0x00070e0d, 0x00070e0c, 0x00070f0a, 0x00070e0c, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00030c08, 0x0005100a, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0c, 0x0040400d, 0x0044450e, 0x0048490f, 0x004b4c0f, 0x004d4e10, 0x00505010, 0x00535410, 0x00545510, 0x00565710, 0x00585911, 0x00595a12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x00797014, 0x00636414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004f5010, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450d, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00141809, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e06, 0x00262521, 0x00736968, 0x00786058, 0x00704e39, 0x00744827, 0x00774925, 0x00724a33, 0x0067453b, 0x00503631, 0x00524244, 0x005f5659, 0x00645c61, 0x00685c61, 0x0069585b, 0x006b5858, 0x00695758, 0x006c5753, 0x006f584f, 0x0072584a, 0x00795444, 0x007d5440, 0x007f533a, 0x00825434, 0x0083522e, 0x00834f26, 0x00855024, 0x00885120, 0x008a511c, 0x008b5118, 0x008d5015, 0x008f4f12, 0x00905010, 0x008e4f10, 0x00884a0f, 0x0080450e, 0x0077400b, 0x00703c08, 0x00673305, 0x00623005, 0x005d2b04, 0x00713f18, 0x008b5730, 0x00935c33, 0x00986034, 0x009d602f, 0x009d6030, 0x009a613a, 0x00996444, 0x00996b53, 0x00976850, 0x00965e38, 0x00a26028, 0x00ac6820, 0x00ae671a, 0x00b06518, 0x00b06216, 0x00ae6115, 0x00a75c13, 0x00a25814, 0x00954d0f, 0x008c470c, 0x008c490d, 0x00945415, 0x009a5515, 0x009c5414, 0x009c5411, 0x00944f14, 0x00864817, 0x00643007, 0x00592c09, 0x00532508, 0x00562809, 0x005f3010, 0x00653710, 0x006c3c0d, 0x006f3c0c, 0x00743f0d, 0x007b4210, 0x00824510, 0x00844812, 0x00864913, 0x00854811, 0x0083450d, 0x0081430c, 0x0080410e, 0x007d3f0d, 0x00773f0e, 0x00713d0d, 0x006f3c0d, 0x006c3c10, 0x006b3c11, 0x006a3d12, 0x00683c14, 0x00673a14, 0x00643813, 0x00613613, 0x005f3411, 0x005c3311, 0x005a3010, 0x005a2d10, 0x00582e10, 0x00522b0c, 0x004d280b, 0x004c2809, 0x004c2808, 0x00562d0d, 0x00633714, 0x006b3b10, 0x006b3b10, 0x006a3e14, 0x00643c12, 0x00603615, 0x0044200a, 0x001d0c00, 0x000c0e08, 0x00081310, 0x0006110d, 0x0006110d, 0x0006110d, 0x0005100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00060d0c, 0x00060d0b, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00050c08, 0x00060c08, 0x00060c08, 0x00070d09, 0x00070d09, 0x00060c08, 0x00080f0b, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060d09, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004d4e0f, 0x00515110, 0x00525310, 0x00545511, 0x00565710, 0x00585910, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x00797014, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00031008, 0x00031008, 0x00031008, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f06, 0x0023241f, 0x00706665, 0x00745d55, 0x006e4c35, 0x00734825, 0x00764924, 0x00784c34, 0x00684638, 0x004c3129, 0x004d3d3c, 0x005b5154, 0x00625a5c, 0x00675b5f, 0x0068595b, 0x006b5859, 0x00685858, 0x006a5754, 0x006c554f, 0x006e544a, 0x00745345, 0x00795140, 0x007c503c, 0x007f5136, 0x00815130, 0x0081502a, 0x00814e23, 0x00864e20, 0x00874e1c, 0x00884e18, 0x00884e15, 0x00894d14, 0x008b4d11, 0x00874b0c, 0x0080470d, 0x00773f0c, 0x00703b0c, 0x0068380b, 0x00603006, 0x00542600, 0x00562703, 0x007b4b27, 0x00905f38, 0x00956035, 0x009c6338, 0x00a36132, 0x00a06234, 0x009e643e, 0x009d6748, 0x009c6c53, 0x0099684e, 0x00965c34, 0x00a05e24, 0x00aa651c, 0x00ac6418, 0x00ae6316, 0x00ac5e13, 0x00a6590d, 0x00a3580f, 0x009e5510, 0x00934c0c, 0x00904a0d, 0x008c4b0d, 0x00945414, 0x009a5613, 0x009c5412, 0x0098520d, 0x00904d0f, 0x007f430e, 0x006b370b, 0x005c2f0b, 0x00592e0d, 0x00572b0c, 0x00542809, 0x005c300c, 0x0065370d, 0x006b3b10, 0x006d3a0c, 0x00743f0f, 0x007c420e, 0x007e4410, 0x00804410, 0x0080440e, 0x0080430e, 0x007e420c, 0x007c3e0c, 0x00783c0b, 0x00753f10, 0x00703d0f, 0x006e3c0d, 0x006c3c10, 0x006a3d12, 0x00683e13, 0x00673c14, 0x00643913, 0x00613611, 0x00603512, 0x005e3412, 0x005c3212, 0x00572c0e, 0x00562b0e, 0x00562c0f, 0x00502b0b, 0x004c280a, 0x004c290b, 0x004c2808, 0x00522b0b, 0x00603412, 0x00623610, 0x00613612, 0x005c3514, 0x004f2c0c, 0x004f2a11, 0x00442613, 0x001c1002, 0x000b100a, 0x0007130f, 0x0007110d, 0x0007110d, 0x0007110d, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00060d0b, 0x00060e09, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e06, 0x00060f05, 0x00060e08, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00050c08, 0x00060c08, 0x00060c08, 0x00070d09, 0x00070d09, 0x00080c08, 0x000a0e0b, 0x00080c09, 0x00080c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004c4d0f, 0x00515110, 0x00525310, 0x00545511, 0x00565710, 0x00585910, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00626312, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x00797014, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00050e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x0008100b, 0x00060e0a, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100b, 0x0005110b, 0x0004100a, 0x0004100a, 0x00051009, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00050f06, 0x0010120c, 0x00564d4c, 0x006e5b53, 0x006c4c37, 0x00724828, 0x00784827, 0x00754a2d, 0x006c4833, 0x00573e31, 0x0050423e, 0x0058514f, 0x00605a5a, 0x00655c5d, 0x00695b5c, 0x00695858, 0x00685857, 0x00685553, 0x006a544f, 0x006c544c, 0x00715246, 0x00755143, 0x0078503e, 0x007a503b, 0x007e5134, 0x0080512e, 0x00835028, 0x00874e24, 0x00884c1d, 0x00884a18, 0x00894b18, 0x00884b18, 0x00844911, 0x007c450c, 0x0076400b, 0x006d3b09, 0x0066370b, 0x005e340e, 0x00542b05, 0x00542804, 0x005c300e, 0x00805230, 0x0094633e, 0x0095623b, 0x009a643b, 0x009d603b, 0x009c603e, 0x00996446, 0x00986850, 0x009b6c56, 0x00976447, 0x00955d30, 0x009b5b1f, 0x00a15b15, 0x00a55c13, 0x00a75c11, 0x00a4580e, 0x00a0560a, 0x009e540b, 0x0099520b, 0x00904a08, 0x008e4a0c, 0x008e4c10, 0x00915112, 0x00945412, 0x0091500d, 0x008e4c0b, 0x0088480e, 0x00783f0c, 0x00683409, 0x0063340f, 0x00623514, 0x005f3110, 0x00562908, 0x00582c0a, 0x005b300d, 0x00633610, 0x0068390d, 0x006b3b0c, 0x00703c0c, 0x00743d0c, 0x00763e0b, 0x00783e0c, 0x00773d0b, 0x00783d0c, 0x00773c0c, 0x00763c0c, 0x00733e10, 0x00703c10, 0x006c3b0e, 0x006a3c0e, 0x00693c15, 0x00673c16, 0x00663b14, 0x00633812, 0x00603613, 0x005e3412, 0x005c3313, 0x00562f10, 0x00532b0c, 0x00512a0c, 0x00532c0d, 0x00502b0d, 0x004d280b, 0x004d280e, 0x00472107, 0x004d270c, 0x00563014, 0x00583317, 0x00532f15, 0x0047260e, 0x003c1c06, 0x00442814, 0x003f2b17, 0x00251f0d, 0x000b1202, 0x00081409, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00090d0a, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00090d0a, 0x00090d0a, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00070c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004d4e0f, 0x00515110, 0x00525310, 0x00545511, 0x00565710, 0x00585910, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x00797014, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00616112, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00060e09, 0x0008100b, 0x0008100c, 0x0008100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005110b, 0x0005110b, 0x0004100a, 0x0004100a, 0x00041009, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00051008, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00041006, 0x00010800, 0x002e2927, 0x00645750, 0x006a523e, 0x00734f32, 0x00754c30, 0x0072492f, 0x00694530, 0x00533b2c, 0x00463832, 0x00544d4a, 0x005a5452, 0x00605756, 0x0068595b, 0x006b5b5b, 0x00665656, 0x00685453, 0x006a5450, 0x006c544c, 0x00705246, 0x00745042, 0x0076503c, 0x00784f39, 0x007a4e33, 0x007d4f2d, 0x00824e29, 0x00854e25, 0x00864c1f, 0x00854a1a, 0x00844918, 0x00804614, 0x007b440e, 0x00713d08, 0x006b3a07, 0x00673708, 0x005c3108, 0x00542b05, 0x00542a05, 0x005a2f0a, 0x00623614, 0x007f5034, 0x00906246, 0x00966548, 0x00946244, 0x00966044, 0x00956047, 0x0094624c, 0x00946452, 0x00936450, 0x008d5c3f, 0x008c5529, 0x0092541b, 0x00985412, 0x009c5410, 0x009e540f, 0x009e540e, 0x0098520c, 0x00945009, 0x008f4c09, 0x00894808, 0x0086480c, 0x00874b11, 0x008b4f14, 0x00884b10, 0x0084470c, 0x0080440d, 0x007b400e, 0x0070390c, 0x00643108, 0x0063320c, 0x006b3c18, 0x00643411, 0x00643410, 0x00552704, 0x00562a04, 0x005c3109, 0x00603409, 0x00643709, 0x0068390b, 0x006c3a0c, 0x00703b0b, 0x00703a0a, 0x00713c0c, 0x00713b0c, 0x00733d0e, 0x00743d0e, 0x00713d12, 0x006e3c10, 0x006c3c10, 0x00693c10, 0x00683c15, 0x00673c17, 0x00653a14, 0x00613712, 0x005f3511, 0x005d3512, 0x00593112, 0x00562f10, 0x00532c0f, 0x004e290b, 0x004c2709, 0x004c2609, 0x00482308, 0x004b230c, 0x00421c06, 0x0046220e, 0x00452611, 0x003e200e, 0x00381e0c, 0x002f1808, 0x00291405, 0x00352413, 0x00362919, 0x00282416, 0x0010150b, 0x00071008, 0x00060e09, 0x0009110d, 0x0008100c, 0x0008100b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00080e0a, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00070d09, 0x00070d09, 0x00080e0a, 0x00080e0a, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0041420d, 0x0044450e, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00505010, 0x00535410, 0x00555611, 0x00585810, 0x00585911, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f12, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x007a7014, 0x00646414, 0x00646414, 0x00636414, 0x00616112, 0x00616112, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00031008, 0x00031008, 0x00031008, 0x00031008, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x00050f0a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120d, 0x0008130d, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006110b, 0x0007110a, 0x0008110b, 0x0008120c, 0x0008120c, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x00061009, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00051008, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00031006, 0x0008130a, 0x000b0e08, 0x003f3a31, 0x00625441, 0x00654b32, 0x006b4834, 0x006e4831, 0x00633f29, 0x00503829, 0x00453831, 0x004f4846, 0x00565150, 0x005c5453, 0x00635456, 0x0069595a, 0x00675757, 0x00675452, 0x0067514c, 0x00685148, 0x00705144, 0x00735040, 0x00754e3c, 0x00784e38, 0x00784f33, 0x007a4f2f, 0x007f4e2b, 0x00804b26, 0x007e481c, 0x007c4517, 0x007b4414, 0x00784111, 0x00713f0c, 0x00693a08, 0x00643708, 0x005e330a, 0x00562d08, 0x00542d08, 0x005c340e, 0x00643915, 0x00643817, 0x0073472b, 0x00865940, 0x008e604b, 0x00875a44, 0x00845640, 0x00885a44, 0x00885b46, 0x00865b46, 0x00875c47, 0x00845739, 0x00875329, 0x008c501c, 0x008d4c11, 0x00904c0f, 0x00914c0e, 0x00934e10, 0x0090500e, 0x008d4f0f, 0x00884c0e, 0x0083480d, 0x007c440d, 0x00794510, 0x007a4614, 0x00754110, 0x00733d10, 0x00713b14, 0x0069340d, 0x005e2c06, 0x00602f08, 0x00693710, 0x006c3813, 0x006c3913, 0x006c3913, 0x00663510, 0x00592a03, 0x00562a02, 0x00582e05, 0x005c3108, 0x0062370c, 0x0065380e, 0x0069390c, 0x006c3b0d, 0x006d3b0c, 0x006f3c0e, 0x006d3c0d, 0x006e3c0d, 0x006d3c12, 0x006c3c12, 0x00693d12, 0x00683c11, 0x00643912, 0x00643914, 0x00633814, 0x00613514, 0x005d3411, 0x00583311, 0x00552f10, 0x00512c0f, 0x00502b0d, 0x004d280c, 0x004b250a, 0x004b270c, 0x00462108, 0x004c240f, 0x00371504, 0x00291001, 0x00241203, 0x00201104, 0x00201309, 0x00221810, 0x001c130b, 0x00241c12, 0x00262014, 0x00202018, 0x00101714, 0x00060f0c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00070f0a, 0x00050d08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0036370c, 0x00393b0d, 0x003c3e0c, 0x0041420e, 0x0044450d, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00525310, 0x00535410, 0x00555611, 0x00585810, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00636413, 0x00636414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00696614, 0x00c6a218, 0x00cca619, 0x007a7014, 0x00646414, 0x00646414, 0x00636414, 0x00616112, 0x00616112, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00021008, 0x00021008, 0x00021008, 0x00021008, 0x00021009, 0x00021009, 0x00021009, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120d, 0x0008130d, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006110b, 0x0007110a, 0x0008110b, 0x0008120c, 0x0008120c, 0x0007110c, 0x0006100b, 0x0007110c, 0x0007110c, 0x00061009, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00051008, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e08, 0x00041006, 0x00041007, 0x00060e08, 0x00101208, 0x00393120, 0x0056432d, 0x005e4433, 0x0064412e, 0x005f3d28, 0x00503b2c, 0x00443933, 0x004a4440, 0x00544e4c, 0x005c5252, 0x00605354, 0x00655555, 0x00675757, 0x00675452, 0x0067514c, 0x00685148, 0x006f5042, 0x00714f3e, 0x00724c38, 0x00744b34, 0x00744c31, 0x00764c2d, 0x007a4c28, 0x007b4924, 0x0079471b, 0x00784416, 0x00744113, 0x006f3c0e, 0x006a3a0c, 0x00643808, 0x005c3308, 0x00562d08, 0x00542c09, 0x005b340f, 0x00603912, 0x00673d17, 0x00673c18, 0x006a3c1f, 0x006f4328, 0x00754c34, 0x00734b36, 0x00714a34, 0x00744e35, 0x00785138, 0x00785138, 0x007c533c, 0x007e5136, 0x00804f28, 0x00844a19, 0x00844710, 0x0086470f, 0x0088480f, 0x008a480f, 0x0087480e, 0x0080460c, 0x007b430c, 0x0074400c, 0x006e3c0c, 0x006c3c0e, 0x006c3e13, 0x00693912, 0x00623010, 0x005a290c, 0x00542405, 0x005c2c0a, 0x00683611, 0x00703c13, 0x00703c12, 0x00713c14, 0x00703b13, 0x006c3810, 0x0064340b, 0x00582c04, 0x00542903, 0x00572f08, 0x005b320c, 0x00603710, 0x0064380f, 0x0068390e, 0x00693b0c, 0x006a3c0e, 0x006a3c0d, 0x006a3c0e, 0x00693b11, 0x00683c13, 0x00673c13, 0x00643b12, 0x00613810, 0x00623812, 0x00613614, 0x00603412, 0x005b3210, 0x0056300f, 0x00583113, 0x00532e10, 0x004c280c, 0x004d280c, 0x004b250c, 0x0048240a, 0x00422007, 0x00452310, 0x002c1404, 0x00120700, 0x00121002, 0x00151105, 0x001a150c, 0x001b1911, 0x00181710, 0x0019170f, 0x001c1b14, 0x00191c18, 0x000f1314, 0x00070f0d, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00050d09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040d07, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00050c08, 0x00050c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0024250b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x004f5010, 0x00525310, 0x00555611, 0x00565710, 0x00585911, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00696614, 0x00c6a218, 0x00cca619, 0x007a7014, 0x00646514, 0x00646414, 0x00636414, 0x00626312, 0x00606012, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x00494a10, 0x0045470e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006110c, 0x0005110b, 0x0006120c, 0x0007130d, 0x0006100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00040f08, 0x00040f08, 0x00060e08, 0x000b1008, 0x000c0d03, 0x001f1c0f, 0x00302c1c, 0x00413224, 0x00463426, 0x003d2f24, 0x00403630, 0x00423b38, 0x004e4845, 0x00584f4d, 0x00605452, 0x00645454, 0x00645454, 0x00675653, 0x0064504b, 0x00665048, 0x006c4f40, 0x00704f3e, 0x00704c37, 0x00704932, 0x00714a2f, 0x00714828, 0x00704320, 0x0070421c, 0x00734216, 0x00714012, 0x006f4013, 0x00683c10, 0x0062370c, 0x005b320a, 0x00562d07, 0x00562b07, 0x005d310f, 0x00653913, 0x00693d14, 0x006c3e10, 0x006d3c0f, 0x00683714, 0x00603414, 0x0060381f, 0x005c3822, 0x005b3724, 0x00603c29, 0x00684430, 0x00714d36, 0x00754f38, 0x00774c34, 0x00784829, 0x006e3c14, 0x00764012, 0x00773f0e, 0x00783f0e, 0x00793f0d, 0x00783f0d, 0x00753e0c, 0x006e3b0e, 0x00683b13, 0x00613814, 0x00572f10, 0x004c2507, 0x00471f03, 0x00411900, 0x004a2006, 0x00582a0e, 0x00683715, 0x006e3b14, 0x00733e12, 0x00744010, 0x00753f13, 0x00763f13, 0x00713c0d, 0x006b3808, 0x0065360b, 0x005b2e09, 0x00562c0b, 0x00592f10, 0x005d3412, 0x00603511, 0x00613710, 0x0061380d, 0x0061380c, 0x00643b0c, 0x00653c0d, 0x00663c12, 0x00663b14, 0x00653a14, 0x00633913, 0x00613811, 0x00613812, 0x00613814, 0x005c3210, 0x00582f0e, 0x00583112, 0x00583114, 0x00522b0f, 0x004e260d, 0x004c260c, 0x0048240a, 0x0047230a, 0x0044230c, 0x00402414, 0x00241405, 0x00100e00, 0x000e1406, 0x0015170a, 0x001c180e, 0x001c180e, 0x0018160e, 0x0013140f, 0x00131513, 0x00151914, 0x000d120c, 0x00081009, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d0a, 0x00080d09, 0x00080d09, 0x00080d08, 0x00080d0a, 0x00080c09, 0x00080c07, 0x00080c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c09, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x00292b0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a10, 0x004d4e0f, 0x00515110, 0x00525310, 0x00565610, 0x00595a11, 0x005b5b12, 0x005c5c12, 0x005e5f11, 0x00605f11, 0x00616012, 0x00626113, 0x00626113, 0x00636213, 0x00646313, 0x00646212, 0x00646313, 0x00646413, 0x00646413, 0x00656413, 0x00666412, 0x00666412, 0x00686513, 0x00686513, 0x00686613, 0x00696614, 0x00696614, 0x006b6814, 0x006b6814, 0x006c6814, 0x006c6914, 0x006c6914, 0x006d6a14, 0x006e6b14, 0x00938115, 0x00c9a419, 0x00cca619, 0x00797014, 0x00646414, 0x00646414, 0x00636414, 0x00626312, 0x00616112, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130c, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006110c, 0x0005110b, 0x0006120c, 0x0007130d, 0x0007100c, 0x0009110d, 0x0009110d, 0x0008100c, 0x0008100c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e06, 0x00080e05, 0x000c0f05, 0x00100f04, 0x00201a10, 0x002d251a, 0x002f261e, 0x002e2823, 0x00433e38, 0x0048413c, 0x00514744, 0x00615454, 0x00605251, 0x00615050, 0x00655451, 0x00624e49, 0x00644e45, 0x00684d40, 0x006d4d3f, 0x006f4c38, 0x006e4833, 0x006f472d, 0x006d4427, 0x006c401e, 0x006c4018, 0x006d3d13, 0x006b3b0f, 0x00683a10, 0x0061350e, 0x005b330c, 0x00573009, 0x00542b06, 0x00572c07, 0x00643710, 0x006b3c14, 0x006f3f13, 0x00724010, 0x00724010, 0x00703c15, 0x00683914, 0x0054290c, 0x0048240c, 0x0042200c, 0x003f1d08, 0x003f1f0c, 0x00543420, 0x00684631, 0x006f4832, 0x006c4229, 0x00653919, 0x0064340d, 0x0066350c, 0x0068340c, 0x0068350d, 0x0068350d, 0x0064340c, 0x005f310c, 0x00593010, 0x00482206, 0x00381600, 0x00351400, 0x003c1902, 0x00432009, 0x00512a0f, 0x00603414, 0x006c3a17, 0x00733e14, 0x00774111, 0x00784310, 0x007b4413, 0x007c4212, 0x0079420e, 0x00723f0a, 0x006e3b0d, 0x00663610, 0x005b2d0b, 0x00582e0c, 0x005b310f, 0x005c330f, 0x005d340f, 0x005e350d, 0x005e350c, 0x0060370c, 0x0060380c, 0x00623910, 0x00623812, 0x00623811, 0x00603710, 0x00603710, 0x00603711, 0x005e3411, 0x00592f0d, 0x0058300f, 0x00593112, 0x00593114, 0x0052280e, 0x004d240c, 0x004c240d, 0x0047220a, 0x0046230a, 0x0044240d, 0x003b2213, 0x001f1007, 0x00100d04, 0x000d1506, 0x00121306, 0x0021180f, 0x00241a10, 0x001c180d, 0x00151510, 0x00111310, 0x00101410, 0x000b1009, 0x0009100a, 0x0005100a, 0x00040f09, 0x0005100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070c0b, 0x00070d09, 0x00070d09, 0x00070d08, 0x00080e0a, 0x00070d09, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004d4e10, 0x00706411, 0x00b79414, 0x00bd9815, 0x00be9a16, 0x00be9a16, 0x00be9b16, 0x00be9b17, 0x00bf9b18, 0x00bf9b18, 0x00bf9b18, 0x00bf9b18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00c09d18, 0x00c09d18, 0x00c09d18, 0x00c09d18, 0x00c09d18, 0x00c09d18, 0x00c09e18, 0x00c09e18, 0x00c09e18, 0x00c09e18, 0x00c09f18, 0x00c8a418, 0x00cca619, 0x00c09e18, 0x00716c14, 0x00646514, 0x00646414, 0x00636414, 0x00626313, 0x00606013, 0x00606013, 0x005d5d12, 0x00a38814, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x00484910, 0x0044450e, 0x0040400d, 0x003b3c0c, 0x0038380c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040f09, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006110c, 0x0005110b, 0x0005110b, 0x0007130c, 0x000a140f, 0x000c140f, 0x000c140f, 0x0009110d, 0x0008100b, 0x0008120d, 0x0008120d, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00060e06, 0x00080d06, 0x00090c06, 0x000d0e09, 0x0022211c, 0x00282620, 0x00282620, 0x003c3833, 0x00443c38, 0x00544948, 0x005c504f, 0x005f5050, 0x00605050, 0x0062514e, 0x00624f49, 0x00604c43, 0x0062493d, 0x0066473a, 0x006c4a39, 0x006c4733, 0x006c452d, 0x006a4326, 0x00683f1d, 0x00683d18, 0x006a3c14, 0x0066380e, 0x0061340c, 0x005c320c, 0x0058300c, 0x00542c09, 0x00562c08, 0x00603510, 0x00683b11, 0x006c3d10, 0x00714010, 0x00733f10, 0x00743f10, 0x00764014, 0x006f3d15, 0x005f3211, 0x004f290a, 0x00442108, 0x003d1f07, 0x003c200b, 0x003a1d0b, 0x00432614, 0x00533421, 0x005b3924, 0x005c381e, 0x00593114, 0x005a2e10, 0x0054290a, 0x00582f10, 0x00593010, 0x00593013, 0x004c250a, 0x003e1a00, 0x00371700, 0x00361a09, 0x00391c0a, 0x003e1e09, 0x0048240c, 0x00542c0f, 0x00643715, 0x00703e17, 0x00744014, 0x00784210, 0x0079440f, 0x007c4410, 0x007e4410, 0x007c4410, 0x0077400e, 0x00703c0d, 0x006b3910, 0x0063340d, 0x00582e0a, 0x00582c09, 0x00582e0c, 0x005a300f, 0x005c3210, 0x005e3410, 0x005d340e, 0x005d340d, 0x00603610, 0x00623912, 0x00613811, 0x005e350e, 0x005c320c, 0x005d3410, 0x00603514, 0x005b3010, 0x00572d0f, 0x00593014, 0x00583014, 0x00582f15, 0x004f260f, 0x004f2611, 0x004f2a13, 0x0043200b, 0x003c1d08, 0x002e180b, 0x00180803, 0x00130e08, 0x00111409, 0x00161305, 0x0024180e, 0x00281c10, 0x00211a0d, 0x0018150e, 0x0012120f, 0x000e120e, 0x0009100c, 0x0008100c, 0x0005100a, 0x00040f09, 0x0005100a, 0x00050f0a, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070c0b, 0x00070d09, 0x00070d09, 0x00070d08, 0x00080e0a, 0x00070d09, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x00615910, 0x00bc9815, 0x00cca316, 0x00cca316, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00c2a018, 0x008b7c14, 0x00656614, 0x00646514, 0x00646514, 0x00636414, 0x00626313, 0x00616112, 0x00606012, 0x00605f12, 0x00ac8f15, 0x00cca417, 0x00b09014, 0x004f5010, 0x00505010, 0x004c4d0f, 0x00484910, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0036370c, 0x0034350c, 0x002d2f0b, 0x00292b0a, 0x0026280b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00040e09, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006110c, 0x0005110b, 0x0006120c, 0x0008140e, 0x0008120d, 0x0009110d, 0x0009110d, 0x0008100c, 0x0009110d, 0x0008120d, 0x0008110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00031006, 0x00031008, 0x00060e08, 0x00070c0a, 0x00070c0b, 0x00101512, 0x001c201a, 0x001e1e17, 0x00343129, 0x003e3832, 0x00504542, 0x00584c4b, 0x005a4c4b, 0x005c4d4c, 0x0062504e, 0x00604d48, 0x005d4c42, 0x0060493e, 0x0064483b, 0x00694b3b, 0x00694834, 0x0066442c, 0x00664024, 0x00663e1e, 0x00673d19, 0x00663b13, 0x0061350c, 0x005c330b, 0x0058300c, 0x00542d0c, 0x00542c0d, 0x005d3410, 0x00653a12, 0x006c3e12, 0x00703e0d, 0x0074400f, 0x00774010, 0x00784010, 0x00774011, 0x00713d12, 0x00653811, 0x00562f0c, 0x0048270a, 0x00402409, 0x003b1f0a, 0x00351b0a, 0x00341c0b, 0x00361e0c, 0x00412614, 0x0050311f, 0x00502f1a, 0x00502c17, 0x004c2511, 0x004e2915, 0x00492611, 0x0040200a, 0x00361702, 0x00341400, 0x00341801, 0x00381e0c, 0x003f220c, 0x004a260f, 0x00542c10, 0x005d3311, 0x00663813, 0x006f3d12, 0x00723e0f, 0x00744009, 0x0076400a, 0x0079410c, 0x007b420c, 0x007b420e, 0x0078400d, 0x00733d0c, 0x006c3a0c, 0x0067380c, 0x005e340e, 0x00582c09, 0x00542a09, 0x00552b0c, 0x00582e0f, 0x005b3010, 0x005c3210, 0x005d3410, 0x005e350e, 0x005d340d, 0x005d340d, 0x005c330c, 0x005b320b, 0x005e3410, 0x00582d0c, 0x005c3111, 0x00542a0d, 0x00542c10, 0x00532a0f, 0x00542c11, 0x0050260f, 0x004c250e, 0x004a240e, 0x00421f0a, 0x003c1c0a, 0x00281408, 0x00140703, 0x00130d09, 0x00131308, 0x00191404, 0x0025180c, 0x002f2014, 0x002a2011, 0x001e170e, 0x00181410, 0x00101410, 0x00081210, 0x0007120d, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x006e6011, 0x00cca215, 0x00c8a016, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48815, 0x00a48915, 0x00a48915, 0x00a48916, 0x00a48916, 0x00a48916, 0x00a48916, 0x00a38a15, 0x00a38a15, 0x00a38915, 0x00a38915, 0x00a28915, 0x00a28915, 0x00a28916, 0x00a28916, 0x00a18817, 0x00a18816, 0x00a18915, 0x00a18915, 0x00a18816, 0x00a18916, 0x00a08916, 0x00a08916, 0x00a08916, 0x00a08916, 0x00a08916, 0x00a08916, 0x00988416, 0x00787114, 0x00656614, 0x00656614, 0x00656614, 0x00646514, 0x00646414, 0x00626313, 0x00626312, 0x00606012, 0x00616012, 0x00bc9916, 0x00cca417, 0x00aa8b14, 0x004f5010, 0x00505010, 0x004c4d0f, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040f0a, 0x00040f09, 0x00040e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040f09, 0x0008110c, 0x0005100a, 0x00040d08, 0x00040d08, 0x0007110c, 0x0007110c, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0007110c, 0x0005100a, 0x0008120c, 0x0008120d, 0x0007120c, 0x0006120c, 0x0007130c, 0x0008140e, 0x0007130d, 0x0007110c, 0x0009120d, 0x0008120d, 0x0007110c, 0x0009130e, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x00061009, 0x00061009, 0x00040f08, 0x00051008, 0x0007100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040e05, 0x00040e05, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00031006, 0x00060e09, 0x00060e09, 0x0006100c, 0x000c120f, 0x00161a14, 0x0021211a, 0x002e2c22, 0x00352f28, 0x00493f3b, 0x00544845, 0x005a4d4c, 0x00544644, 0x00584945, 0x005c4a45, 0x005c4a43, 0x0060483d, 0x00604538, 0x0065483a, 0x00664838, 0x0067442f, 0x00644026, 0x00633d1f, 0x00633b18, 0x00633815, 0x005e3410, 0x0058320d, 0x0054300c, 0x00542f0e, 0x005c3014, 0x00633513, 0x006b3c12, 0x00724113, 0x0076400e, 0x0077410e, 0x007a4312, 0x00793f10, 0x00783e10, 0x00713c0f, 0x00693b11, 0x00603810, 0x00523111, 0x00482a0e, 0x0040240b, 0x003f250f, 0x003a2410, 0x0035210d, 0x00331e0a, 0x0038200c, 0x00422715, 0x00442818, 0x00452617, 0x00432414, 0x003d1f10, 0x00341605, 0x00351804, 0x003c1e0a, 0x00432510, 0x00482914, 0x004d2c14, 0x00522c11, 0x00582e11, 0x00643815, 0x00683b11, 0x006d3c10, 0x00703c0c, 0x00703c09, 0x00703c08, 0x00733c09, 0x0078400c, 0x00733d0c, 0x006c3808, 0x006c390b, 0x0068360a, 0x0066360e, 0x0061340e, 0x005b2f0d, 0x00562b0e, 0x00542b10, 0x00582f14, 0x00572c10, 0x005b3011, 0x005b3010, 0x005b320c, 0x005b310c, 0x005d3410, 0x005d3410, 0x005d3410, 0x005c3411, 0x00582f0e, 0x00582f10, 0x00542b0e, 0x00532c10, 0x0050280d, 0x00512a10, 0x00502910, 0x004b250c, 0x004c2610, 0x0044200b, 0x00381c0a, 0x00231206, 0x00120902, 0x00110f07, 0x00171408, 0x001f1708, 0x002c1c0f, 0x00342412, 0x0030220d, 0x00281c0f, 0x001f1810, 0x0012140f, 0x00091110, 0x00071310, 0x0006120c, 0x0004100a, 0x00030f09, 0x00040e08, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00060d09, 0x00080c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070e08, 0x00070e08, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c07, 0x00050d07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x00494a0f, 0x004d4e0f, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005b5811, 0x00595a12, 0x005b5b11, 0x005c5d12, 0x005d5e13, 0x005e5f13, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00616113, 0x00616113, 0x00616114, 0x00616114, 0x00616114, 0x00616114, 0x00626314, 0x00626314, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00646513, 0x00656614, 0x00656614, 0x00656613, 0x00666713, 0x00666713, 0x00666713, 0x00656614, 0x00646513, 0x00646414, 0x00636414, 0x00616112, 0x00606013, 0x00786c14, 0x00c8a116, 0x00cca417, 0x00927b13, 0x00515110, 0x00505010, 0x004c4d0f, 0x0047480e, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0038380c, 0x0030310c, 0x002d2f0a, 0x0026280a, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f09, 0x00040d08, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x0006100b, 0x00040f09, 0x00040d08, 0x00040d08, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0007110c, 0x0005100a, 0x0008120c, 0x0008120d, 0x0008120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0007110c, 0x0009130e, 0x0007110c, 0x0008120d, 0x0009130e, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x00061009, 0x00061009, 0x0008110b, 0x00040f08, 0x00040c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040e05, 0x00040e05, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00050f08, 0x00040e09, 0x00080f0b, 0x000e140f, 0x001b1c16, 0x0026251c, 0x00353028, 0x0048403a, 0x004e443e, 0x00524641, 0x00544743, 0x00584945, 0x00574640, 0x0056463d, 0x005e473c, 0x0062473b, 0x005e4334, 0x00604232, 0x0063412d, 0x00633f26, 0x00633c20, 0x00623b18, 0x005e3614, 0x005a3210, 0x0058300e, 0x0057310f, 0x00593110, 0x00613416, 0x00683914, 0x006c3d12, 0x00734011, 0x00794311, 0x00784311, 0x00784110, 0x00794110, 0x00763e10, 0x00703c10, 0x006b3c12, 0x00613810, 0x00573311, 0x00502d10, 0x00462508, 0x0047290f, 0x00402710, 0x003b240f, 0x0037200b, 0x00351e0a, 0x00341c08, 0x00341b0b, 0x00361b0c, 0x00391c0c, 0x003b1c0d, 0x00371908, 0x00391c09, 0x0040210c, 0x00482812, 0x004c2b12, 0x00502c13, 0x00542c11, 0x005b2e12, 0x00653514, 0x00683811, 0x006c380d, 0x006c3a0b, 0x006d3b0a, 0x006e3c0b, 0x006f390c, 0x00733c0e, 0x006e3a0b, 0x006c3b0c, 0x0068360b, 0x00613109, 0x005d2f08, 0x005d2e0b, 0x00582c0b, 0x00572a0f, 0x00552c12, 0x00562d13, 0x00592f13, 0x005a3012, 0x005b3010, 0x005a300c, 0x00582f0c, 0x005c3310, 0x005c3311, 0x005c3412, 0x005b3311, 0x0058300f, 0x00542c0d, 0x0050280b, 0x00532c10, 0x004f280c, 0x004e260c, 0x004d250b, 0x004a260b, 0x004d2810, 0x0044200c, 0x00361c0a, 0x001a0d00, 0x00100c04, 0x000d0d04, 0x00151306, 0x0023180b, 0x002f1d11, 0x003a2412, 0x0038240c, 0x002d1d0d, 0x0022180f, 0x0015140e, 0x000c1110, 0x00081310, 0x0006120c, 0x0004100a, 0x00030f09, 0x00020e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00060d09, 0x00080c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070e08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c07, 0x00050e08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x00202309, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606012, 0x00606012, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666713, 0x00666713, 0x00666714, 0x00666714, 0x00666714, 0x00666714, 0x00666713, 0x00666713, 0x00656614, 0x00646514, 0x00636414, 0x00626312, 0x00616113, 0x00a18815, 0x00cca417, 0x00c59f16, 0x006e6412, 0x00535410, 0x00505010, 0x004c4d0f, 0x0048490e, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130e, 0x000f130f, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f0a, 0x0005100a, 0x00040f09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x0008110c, 0x0008120d, 0x0008120d, 0x0007130c, 0x0007130d, 0x0007130d, 0x0005110b, 0x0008120c, 0x0008120d, 0x0008120c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120c, 0x0008120c, 0x0008120c, 0x0008120c, 0x0008120c, 0x0007110c, 0x00061009, 0x00061009, 0x00061009, 0x00040f08, 0x00060f09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00060e08, 0x00040e07, 0x00040f08, 0x00050e08, 0x00090e09, 0x0010120e, 0x001c1c17, 0x0034322b, 0x0048433b, 0x004b423c, 0x004c413a, 0x0050443c, 0x0050413a, 0x0053423a, 0x00534439, 0x005b463a, 0x0060483a, 0x005d4434, 0x005c412f, 0x005e3e2b, 0x00603c25, 0x005f391e, 0x005e3718, 0x005a3312, 0x0058300e, 0x00572f0d, 0x0059300f, 0x005c3010, 0x00633814, 0x00693a14, 0x006a3a0e, 0x006e3c0e, 0x00744012, 0x00733e10, 0x00733e10, 0x00794416, 0x00764113, 0x006d3c0f, 0x006a3a10, 0x00643611, 0x005c3010, 0x005c3417, 0x0050290f, 0x00522c13, 0x004b2b12, 0x00482b14, 0x003f230c, 0x003c1f09, 0x003b1e0a, 0x003b1e0b, 0x00381b08, 0x003a1c0c, 0x003f200e, 0x0040210d, 0x0040200a, 0x0045250c, 0x004d2c12, 0x004f2b11, 0x00542c11, 0x00562b0e, 0x005e3010, 0x00643413, 0x00693813, 0x006c3c12, 0x006f3c11, 0x006d3c0e, 0x006c3b0d, 0x006b370c, 0x006c380d, 0x00643306, 0x00633307, 0x00613308, 0x00643811, 0x005d300b, 0x00562908, 0x00582c0c, 0x0054290b, 0x00552c10, 0x00562c10, 0x00562b10, 0x005b3012, 0x005b3010, 0x00582f0c, 0x00572d0a, 0x005a300d, 0x00582f0d, 0x0059300f, 0x0058300f, 0x00552d0e, 0x00512a0c, 0x0050280c, 0x00502a10, 0x004d280d, 0x004f290f, 0x00502b10, 0x004a270b, 0x004a240c, 0x00411e0b, 0x00331909, 0x00140c01, 0x000e0e07, 0x000c0c06, 0x00141106, 0x0024170c, 0x00321c11, 0x003d2413, 0x003d260f, 0x00311e0e, 0x0026180e, 0x0019140e, 0x0010110e, 0x000a120e, 0x0005110c, 0x0004100a, 0x0004100a, 0x00040f09, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00060d09, 0x00080c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070e08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c07, 0x00050e08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005d5b12, 0x005c5d11, 0x005c5d11, 0x00606013, 0x00606012, 0x00606012, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00666714, 0x00656614, 0x00656614, 0x00646414, 0x00626313, 0x00756c14, 0x00c49f18, 0x00cca417, 0x00a68914, 0x00585811, 0x00535410, 0x00505010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f09, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x0005100a, 0x00040e08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x0007110c, 0x0008110c, 0x0007110c, 0x0005110b, 0x0006120c, 0x0008140e, 0x0008140e, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007110c, 0x00061009, 0x00061009, 0x0007110a, 0x00040f08, 0x00040e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00050e08, 0x00040e06, 0x00040f06, 0x00050f06, 0x00060e08, 0x00080c09, 0x000e100c, 0x00282721, 0x003c3932, 0x0048433a, 0x004b4338, 0x004e4439, 0x00504238, 0x0055443c, 0x00504136, 0x00584538, 0x005c4537, 0x00594030, 0x00583e2b, 0x00593c2a, 0x005c3c28, 0x005c3920, 0x005a3618, 0x00583212, 0x0055300e, 0x00572f0d, 0x005b300e, 0x005b310c, 0x0061360d, 0x00673810, 0x006b3b10, 0x006c3c10, 0x00703d11, 0x006c390d, 0x00703f13, 0x00734114, 0x00703f11, 0x006c3b0f, 0x006b3a11, 0x006b3b17, 0x006b3c1a, 0x00653818, 0x005b3012, 0x005c3416, 0x00543016, 0x004d2c14, 0x00492811, 0x0043220c, 0x0040210b, 0x003d200b, 0x003d1f0b, 0x003e1e0b, 0x003f1e0b, 0x0041200c, 0x0044220c, 0x0048260c, 0x004f2c10, 0x00532d10, 0x00552c0f, 0x005a2d0c, 0x0060300f, 0x00683717, 0x00683614, 0x00683810, 0x006c3c12, 0x0068380d, 0x0069380d, 0x0068370e, 0x0069370e, 0x005f3007, 0x005c2f06, 0x0060320c, 0x005f3310, 0x00542806, 0x00522407, 0x0053270a, 0x0054280b, 0x00542c0e, 0x00542b0f, 0x00552a0f, 0x00592f10, 0x005c3110, 0x005c320f, 0x00592f0d, 0x005a300e, 0x00592f0e, 0x00582f0d, 0x00542c0c, 0x00542c0c, 0x00502a0c, 0x0050280e, 0x004f2810, 0x004c260c, 0x004a240b, 0x00482208, 0x00482408, 0x00462009, 0x00401b0a, 0x002b1204, 0x000f0c02, 0x00090d07, 0x000c0e08, 0x00151009, 0x0025170c, 0x00341c12, 0x003e2212, 0x00402610, 0x00372311, 0x002a1c10, 0x001e160d, 0x0014140d, 0x000b120e, 0x0006120c, 0x0004100a, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00060d09, 0x00080c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070e08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c07, 0x00050e08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005d5b12, 0x005c5c11, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00626313, 0x00636413, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00666713, 0x00656614, 0x00646414, 0x00686413, 0x00b09317, 0x00cca418, 0x00c39e17, 0x00706612, 0x00565711, 0x00535410, 0x00505010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d08, 0x00070f0a, 0x00040d08, 0x00050e09, 0x00050e09, 0x00040f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050e08, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f0a, 0x00060f0a, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050f09, 0x00050e09, 0x00060d09, 0x00070e09, 0x00060d08, 0x00050c08, 0x00040c08, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100b, 0x0005100b, 0x0005100a, 0x0006100b, 0x0007120c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008110c, 0x0008110c, 0x0008110c, 0x0008110c, 0x0008120d, 0x0008110c, 0x0007110c, 0x0007100c, 0x0006100b, 0x0006110b, 0x00051009, 0x00051009, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00040e07, 0x00040f06, 0x00050e06, 0x00070e08, 0x00060c08, 0x00080d09, 0x001f1f1b, 0x0038352f, 0x00474339, 0x00484136, 0x004c4238, 0x0051433a, 0x0058483f, 0x00504034, 0x00564438, 0x00594334, 0x00543c2c, 0x004f3623, 0x00573d29, 0x005b3f2a, 0x00593b21, 0x0058361a, 0x00543313, 0x0054300e, 0x00542d0a, 0x005c330f, 0x005c320b, 0x0060360c, 0x0063360d, 0x0064350c, 0x00693a11, 0x00683910, 0x0066380e, 0x006c3b12, 0x006e3c14, 0x006b3b10, 0x006b3b10, 0x0067380f, 0x00683812, 0x006d3f1a, 0x00633611, 0x005f330f, 0x00603514, 0x005a3315, 0x00522c11, 0x00512a14, 0x0048240e, 0x0043200b, 0x0043230c, 0x0042230c, 0x0043210b, 0x00401e08, 0x00401e06, 0x0047250c, 0x004b270c, 0x004f2a0c, 0x00552f0d, 0x00572d0b, 0x00603410, 0x005e300f, 0x00683818, 0x00673715, 0x00643410, 0x00683911, 0x0064350d, 0x00643510, 0x00663611, 0x00643410, 0x005c2f0a, 0x005a2e08, 0x00592d0a, 0x00572c0c, 0x0054290b, 0x0055290d, 0x00502408, 0x0052280b, 0x0053280c, 0x0051280c, 0x00562c0f, 0x00592f0f, 0x005c3110, 0x005c3310, 0x005b3110, 0x005a3010, 0x0059300e, 0x00552e0c, 0x00542c0c, 0x00542c0d, 0x00542d10, 0x0050280f, 0x004f2910, 0x004d280f, 0x0049240b, 0x00462208, 0x00442308, 0x00421f0a, 0x00391c0b, 0x00200e00, 0x000d0d04, 0x00080e07, 0x000c0f09, 0x0016100a, 0x0024160c, 0x00311d10, 0x00392210, 0x003c2711, 0x00362313, 0x002c1d11, 0x00221a10, 0x0018150e, 0x0010140d, 0x000a130d, 0x0008100b, 0x00061009, 0x00050f09, 0x00040e0a, 0x00040e0a, 0x00040e0a, 0x00040e0a, 0x00050e09, 0x00050e09, 0x00070f09, 0x00060e09, 0x00060d09, 0x00060d09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00070e09, 0x00060d08, 0x00050c08, 0x00060c08, 0x00070c08, 0x00070c08, 0x00080c08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00080c09, 0x00080d09, 0x00060d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00060f09, 0x00070f09, 0x00060d08, 0x00060d08, 0x00070c08, 0x00080c08, 0x00080c08, 0x00070c08, 0x00050e08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00050d09, 0x00050d09, 0x00050d09, 0x00040c08, 0x00040c07, 0x00050d07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00050d08, 0x00050d09, 0x00050d0a, 0x00060e0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00050f08, 0x00050f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00050e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050f08, 0x00050f08, 0x00070e09, 0x00060e08, 0x00050e08, 0x00050e07, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00050c08, 0x00070c08, 0x00080c09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x001d200a, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005d5e11, 0x005e5f13, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00686614, 0x00a28916, 0x00cba418, 0x00caa418, 0x00907c14, 0x00595a11, 0x00585810, 0x00535410, 0x00505010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f07, 0x00040f07, 0x00040f07, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00050c08, 0x00050c08, 0x00050c08, 0x00040d08, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008120d, 0x0007110c, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x00050f0a, 0x0007100b, 0x00070f0a, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f07, 0x00050e07, 0x00070f09, 0x00040c08, 0x00090f0a, 0x0013140e, 0x002e2b24, 0x003b372d, 0x00463f34, 0x004d4339, 0x0051433a, 0x005a4941, 0x0058463c, 0x005a4539, 0x00573f30, 0x00543c2b, 0x004c321f, 0x00593f2b, 0x005e432d, 0x005a3c22, 0x0058361a, 0x00543213, 0x0054300d, 0x00532c09, 0x0058300c, 0x00502702, 0x005c320c, 0x005c310c, 0x005c300b, 0x00643814, 0x00623610, 0x00643712, 0x00683915, 0x006b3c18, 0x006a3c15, 0x006a3c14, 0x00693c15, 0x00693c15, 0x006c3e18, 0x00643811, 0x0060340d, 0x00603512, 0x005e3312, 0x005b3214, 0x00552c11, 0x00512811, 0x0049230b, 0x004c280f, 0x0047240b, 0x0048230a, 0x0049250c, 0x00452107, 0x00482408, 0x00502a0d, 0x00542d0c, 0x0059310c, 0x005b300c, 0x0060340f, 0x00603310, 0x00643413, 0x00643512, 0x0062340f, 0x0064350f, 0x0062340f, 0x00603210, 0x00603210, 0x005b2e0c, 0x00582c0b, 0x00562b0b, 0x0054290a, 0x0051280b, 0x00502609, 0x0051280c, 0x0053280c, 0x0054290f, 0x00542b10, 0x0053280c, 0x00582d10, 0x005b3010, 0x005b300f, 0x005a330f, 0x005a3210, 0x0056300d, 0x00542e0c, 0x00512c09, 0x00522c0b, 0x0050290a, 0x0050280c, 0x004b240b, 0x004c270e, 0x004b250d, 0x00441e07, 0x00462209, 0x003f2009, 0x003b1d0b, 0x00301a0c, 0x001a0e01, 0x000c0e04, 0x00090e06, 0x000c0f08, 0x0016100a, 0x00211608, 0x00281c0c, 0x002d1e0c, 0x0034210f, 0x00312113, 0x002a1c12, 0x00241a12, 0x001a170f, 0x0013140d, 0x000e130d, 0x000a100b, 0x00081009, 0x00060e09, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00050d09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060d0b, 0x00060d0b, 0x00060e08, 0x00060e08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050d09, 0x00050d09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e06, 0x00060e06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c08, 0x00070c08, 0x00080c09, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x00494a0f, 0x004f500f, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005c5c11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00616112, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646514, 0x00646513, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x006c6914, 0x00a48c17, 0x00caa419, 0x00cba418, 0x00a58b16, 0x00616012, 0x00595a11, 0x00585810, 0x00535410, 0x00505010, 0x004c4d0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00050d08, 0x00040c08, 0x0008100b, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00041004, 0x00041004, 0x00041004, 0x00041004, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d09, 0x00050f0a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x00040f09, 0x00040f09, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0008120c, 0x0008120c, 0x0008120c, 0x0008120c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x00040e09, 0x00050e09, 0x00070f0a, 0x00070f0a, 0x00060f09, 0x00050d08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060f08, 0x00040d07, 0x00080e08, 0x0010110b, 0x0027241e, 0x0038342a, 0x004b433a, 0x004c4238, 0x0051433c, 0x0057463f, 0x00544239, 0x00554035, 0x00553e30, 0x00543929, 0x004c321e, 0x005b412d, 0x005e432d, 0x005c3e24, 0x0058381b, 0x00543011, 0x00542e0e, 0x00542d0d, 0x00583010, 0x00522a0b, 0x005e3414, 0x005c3311, 0x00582d0e, 0x005d3212, 0x005c3010, 0x00643817, 0x00613514, 0x00653817, 0x00683b18, 0x006a3d19, 0x00683c17, 0x00693d18, 0x006a4019, 0x00643913, 0x00613610, 0x00613611, 0x005f340e, 0x005e3210, 0x005c2f10, 0x00582d10, 0x00542b0e, 0x00542c0f, 0x0050290c, 0x004e2708, 0x00522b0d, 0x0050280b, 0x00532c0c, 0x00572f0c, 0x00582f09, 0x0060360f, 0x0060330d, 0x005f310b, 0x00643710, 0x00633410, 0x0062340e, 0x005e300c, 0x00603210, 0x005f320f, 0x005d300f, 0x005a2f0e, 0x00572b0c, 0x00542a0b, 0x0051280b, 0x004f2709, 0x004c240a, 0x004a2108, 0x004b2309, 0x004d240b, 0x004f260c, 0x004f260c, 0x00542b10, 0x00592f11, 0x005a3010, 0x005c310f, 0x005b3410, 0x005b3310, 0x00552f0c, 0x00512b08, 0x00512c08, 0x00512b0a, 0x0050290a, 0x00522c10, 0x004b240c, 0x004b250d, 0x004b250f, 0x00462009, 0x0044220c, 0x003a1f0a, 0x00361b0c, 0x00291409, 0x00180d05, 0x000d0e04, 0x00090e05, 0x000d1007, 0x0016100a, 0x00201709, 0x0024190a, 0x00251708, 0x002a190c, 0x002c1e14, 0x00281c14, 0x00211b14, 0x00191710, 0x00141410, 0x000e140e, 0x000a110c, 0x00081009, 0x00060e0a, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00050d09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060d0b, 0x00060d0b, 0x00060e08, 0x00060e08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e06, 0x00060e06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c08, 0x00060c08, 0x00070d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x006e6011, 0x00cca215, 0x00c29c15, 0x005c5911, 0x00595a12, 0x005b5b12, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646514, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00686814, 0x00847815, 0x00b59718, 0x00cba519, 0x00cba419, 0x00ac9016, 0x00686413, 0x005d5e12, 0x005b5b12, 0x00585810, 0x00545511, 0x00505010, 0x004c4d0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00051008, 0x00051007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0006100b, 0x00050e09, 0x00070f0a, 0x0008100b, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00040e07, 0x00080e08, 0x000c0d07, 0x001c1812, 0x00332e26, 0x00463e36, 0x004d4239, 0x0053443d, 0x0056453e, 0x00534239, 0x0058443a, 0x005a4234, 0x004f3422, 0x004e3420, 0x005c422e, 0x005d412c, 0x005e4025, 0x005a381b, 0x00563010, 0x00542d0d, 0x00572f13, 0x00572e14, 0x00532c11, 0x00563013, 0x00552f13, 0x00563014, 0x00542d0f, 0x00583012, 0x00603818, 0x005a3112, 0x005e3414, 0x00623817, 0x00663c1b, 0x00623816, 0x00623815, 0x00653b16, 0x00643a14, 0x00663c15, 0x00653a14, 0x0060350d, 0x0060340c, 0x0060320d, 0x00603210, 0x005f3310, 0x005c320f, 0x00562e0a, 0x00572f0b, 0x0058300c, 0x005b320f, 0x005f3610, 0x00623810, 0x0063380e, 0x006b3d14, 0x006a3c13, 0x00673810, 0x00683910, 0x0064360d, 0x0062340e, 0x005f310d, 0x005e3110, 0x005a2e0e, 0x00582c0e, 0x00542b0d, 0x0051280c, 0x0050270b, 0x004d250c, 0x004b240a, 0x0048210a, 0x00441e08, 0x00441e06, 0x00482209, 0x00502812, 0x00532b13, 0x00582f13, 0x00542c0d, 0x00592f0e, 0x005c3310, 0x005d3511, 0x005d3511, 0x0057310c, 0x00512c06, 0x00502a07, 0x004f2809, 0x00512b10, 0x004f2a10, 0x0049240c, 0x004c2810, 0x004c2a14, 0x00482510, 0x00452510, 0x00381f0c, 0x00341b0e, 0x00241108, 0x00140c04, 0x000d0f07, 0x00080f05, 0x000c1008, 0x0016110a, 0x001f1809, 0x00261c0d, 0x00281c10, 0x0024150c, 0x0022140d, 0x001e1610, 0x001b1511, 0x00151511, 0x00121510, 0x000f140e, 0x000b120c, 0x0008110a, 0x00070f0a, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00070f0a, 0x0008100b, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060d0b, 0x00060d0b, 0x00060e08, 0x00060e08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e06, 0x00060e06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c08, 0x00050c08, 0x00060d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003c3e0d, 0x0041420d, 0x0044450e, 0x0048490f, 0x004c4d0f, 0x006d6011, 0x00cca215, 0x00c29c15, 0x005c5911, 0x005b5910, 0x005c5c11, 0x005e5d12, 0x00605e12, 0x00605e12, 0x00605f12, 0x00616012, 0x00616012, 0x00616012, 0x00626113, 0x00626113, 0x00626113, 0x00626113, 0x00626113, 0x00626113, 0x00626113, 0x00636213, 0x00636213, 0x00646413, 0x00646412, 0x00646412, 0x00656514, 0x00666614, 0x00666614, 0x00686714, 0x00686814, 0x00696814, 0x006a6914, 0x006b6a14, 0x006c6b14, 0x00706d14, 0x007b7315, 0x008f7f16, 0x00af9418, 0x00c6a319, 0x00cca61a, 0x00caa519, 0x00a88d17, 0x006a6713, 0x00606013, 0x005d5e12, 0x005b5b12, 0x00585810, 0x00545511, 0x00505010, 0x004c4d10, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040e07, 0x00040e06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0004100a, 0x0004100a, 0x0005100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100b, 0x0005100b, 0x0005100b, 0x0005100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00060f09, 0x00070f0a, 0x0008100b, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070e08, 0x000c0c07, 0x0012100a, 0x002e2921, 0x003a332a, 0x00453b32, 0x004c3e36, 0x0057453f, 0x00524238, 0x00544134, 0x00553e2f, 0x004c321f, 0x004f3520, 0x005d442f, 0x00644830, 0x005c3f25, 0x0059381a, 0x00583212, 0x00532c0f, 0x00522b10, 0x00502910, 0x004a250c, 0x004c280e, 0x004c280d, 0x004f2c11, 0x004f2c10, 0x004f2a0e, 0x00522e10, 0x00573012, 0x00603a1c, 0x005d3718, 0x00603a19, 0x00623919, 0x00613918, 0x00633916, 0x00633a15, 0x00683e18, 0x00683c14, 0x00673b11, 0x00683a10, 0x00673810, 0x00673811, 0x00653812, 0x00633811, 0x00603610, 0x005f350f, 0x005f350f, 0x00623811, 0x00653c14, 0x00673d13, 0x00693d12, 0x006c3f14, 0x006c3c13, 0x006c3c13, 0x0068380f, 0x0063340c, 0x0061330d, 0x0060330f, 0x005c2f0f, 0x00542a0c, 0x0051280c, 0x0050270b, 0x004e270c, 0x004e270c, 0x004b230a, 0x00492108, 0x004a220b, 0x00461e07, 0x00461d06, 0x00482109, 0x0049230c, 0x00512a13, 0x00532a0f, 0x00522809, 0x00592f0d, 0x005c330f, 0x005e370f, 0x005d360e, 0x0059320c, 0x00542d08, 0x00502908, 0x004c2406, 0x004c280c, 0x0048240a, 0x0049260c, 0x0044230c, 0x0043220c, 0x0040200c, 0x003c1c0a, 0x00361e0c, 0x00301b10, 0x001e1007, 0x00100c04, 0x000c1008, 0x00091007, 0x000c1006, 0x00141309, 0x001d1809, 0x00261c10, 0x002c2015, 0x002a1c14, 0x0020140f, 0x001c140f, 0x00181410, 0x00131510, 0x00111410, 0x000e140e, 0x000b120c, 0x0008110a, 0x00070f09, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080d09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050c0a, 0x00050d09, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c09, 0x00040c0a, 0x00060d0b, 0x00060e0a, 0x00060e08, 0x00060e08, 0x00040f08, 0x00031008, 0x00031008, 0x00031008, 0x00040f08, 0x00050e08, 0x00060e08, 0x00060e09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e07, 0x00060e06, 0x00040f06, 0x00031006, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a0f, 0x006c5f10, 0x00cca215, 0x00c9a016, 0x00ba9615, 0x00ba9615, 0x00ba9715, 0x00ba9716, 0x00ba9716, 0x00ba9716, 0x00ba9816, 0x00ba9815, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00bb9818, 0x00bb9818, 0x00bb9818, 0x00bb9818, 0x00bb9817, 0x00bb9917, 0x00bb9917, 0x00bb9a18, 0x00bb9a18, 0x00bb9b18, 0x00bb9b18, 0x00bb9b18, 0x00bc9b18, 0x00bc9c19, 0x00bc9c19, 0x00bd9d18, 0x00c4a119, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00c3a119, 0x00978415, 0x00686714, 0x00636414, 0x00616112, 0x005e5f12, 0x005b5b11, 0x00585910, 0x00545511, 0x00515110, 0x004c4d10, 0x0048490e, 0x0044450e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050c07, 0x00080c08, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x0008100b, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050f08, 0x00051008, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x0004100a, 0x00041009, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f0b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060f09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00070e08, 0x00090e08, 0x000e0e08, 0x0027241c, 0x00322c24, 0x003e342d, 0x004a3d36, 0x00504038, 0x0049392f, 0x004e3c2f, 0x004c3726, 0x004b301d, 0x00493019, 0x0058412a, 0x00614830, 0x005d4026, 0x005a381b, 0x00553111, 0x00542f10, 0x00552f13, 0x00502a11, 0x0046230a, 0x0044220b, 0x0044220b, 0x0045230a, 0x00462409, 0x0049280b, 0x00502d11, 0x00583416, 0x005c381b, 0x005b3617, 0x005c3618, 0x005d3618, 0x00603818, 0x00613818, 0x00633918, 0x00643915, 0x00653813, 0x00663910, 0x00673a10, 0x00673810, 0x00673811, 0x00673912, 0x00673a15, 0x00683c17, 0x00663b17, 0x00633813, 0x00603510, 0x0060340f, 0x00603410, 0x00603410, 0x00623510, 0x00633411, 0x0060310e, 0x005c2c0b, 0x00582806, 0x00582806, 0x00502301, 0x004c2000, 0x004b2003, 0x00461d01, 0x00451c00, 0x004b2102, 0x00512708, 0x00582d0f, 0x00592f13, 0x005c3115, 0x00562b0e, 0x0052280a, 0x004f250b, 0x0048220a, 0x004c240c, 0x00502708, 0x00542909, 0x0059300c, 0x005c340c, 0x0060370c, 0x005d340a, 0x00583008, 0x00562c08, 0x0050280b, 0x004c270a, 0x004a260b, 0x00462408, 0x0045230b, 0x0042220b, 0x0040210c, 0x003d200d, 0x00351c0b, 0x00321b0d, 0x0026150a, 0x00130a03, 0x00100e07, 0x000b1208, 0x000a1008, 0x000c1005, 0x00141409, 0x00191409, 0x00251910, 0x002d1c15, 0x002f2018, 0x00251910, 0x001c140b, 0x0018140c, 0x0012140c, 0x000f130e, 0x000e140e, 0x000c140e, 0x0009110b, 0x00070f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070e0c, 0x00070f0a, 0x00060e09, 0x00060e08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280c, 0x002c2d0b, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0044450d, 0x0048490f, 0x00565210, 0x00b08d14, 0x00cca215, 0x00cca216, 0x00cca316, 0x00cca316, 0x00cca316, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca518, 0x00cca518, 0x00cca519, 0x00cca519, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00caa61a, 0x00c3a119, 0x00a99017, 0x007c7315, 0x00656614, 0x00646514, 0x00636414, 0x00616112, 0x005e5f12, 0x005c5c11, 0x00585910, 0x00555610, 0x00515110, 0x004c4d10, 0x0048490f, 0x0044450e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050c07, 0x00060c08, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x0004100a, 0x00041009, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f0b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110c, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060f0a, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f08, 0x00080e08, 0x000c0f08, 0x001c1a14, 0x002a251e, 0x003c342d, 0x004b4038, 0x004e4038, 0x00473a30, 0x00534435, 0x00543d2c, 0x00543a27, 0x00503721, 0x005c432c, 0x00644b33, 0x00604328, 0x005c3c1d, 0x00563211, 0x00573211, 0x00583414, 0x00502a0f, 0x00482409, 0x0049250c, 0x004a240b, 0x00472108, 0x00441e03, 0x00482406, 0x00502b0c, 0x00522d0e, 0x00512c0e, 0x00532e10, 0x00542f10, 0x00542d0f, 0x00552d10, 0x00552c0f, 0x00572c0f, 0x00582e0d, 0x00582e09, 0x00582e07, 0x00582d07, 0x00582c07, 0x005a2c09, 0x005a2d0a, 0x005b2e0c, 0x005c2f0e, 0x005a2e0f, 0x00572b0c, 0x00512507, 0x00502406, 0x004f2304, 0x00502407, 0x00532408, 0x00542508, 0x00522204, 0x004e1d00, 0x004c1c00, 0x004c1d00, 0x004c1c00, 0x004f1f01, 0x00502104, 0x004f2304, 0x00542706, 0x00603210, 0x00683b15, 0x006c3f19, 0x0070421c, 0x0070411c, 0x00693b16, 0x00623410, 0x00582e0c, 0x004e2508, 0x004c240b, 0x00522a0b, 0x00572d0b, 0x005c340f, 0x00603610, 0x005d340c, 0x00582f07, 0x00562c08, 0x00532908, 0x0052280c, 0x00522c10, 0x00472208, 0x00412006, 0x0044240c, 0x0041220c, 0x003f210c, 0x003c200d, 0x00341c0b, 0x002d170a, 0x00211409, 0x00130c04, 0x000e0e07, 0x000c1108, 0x000c100a, 0x000e0f07, 0x00151409, 0x001d150b, 0x0023140a, 0x0029170d, 0x00312014, 0x00302416, 0x00281f14, 0x00211c13, 0x001c1b14, 0x00151711, 0x000d120c, 0x00091009, 0x00070f08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c0a, 0x00040c08, 0x00060e09, 0x00060e08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x0014180f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0045470e, 0x00494a10, 0x00605810, 0x00a08212, 0x00a48613, 0x00a58814, 0x00a58814, 0x00a58814, 0x00a58814, 0x00a58814, 0x00a48814, 0x00a58814, 0x00a48914, 0x00a58914, 0x00a48914, 0x00a48914, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48915, 0x00a48815, 0x00a48815, 0x00a48915, 0x00a48916, 0x00a48a15, 0x00a48b15, 0x00a48b16, 0x00a48b16, 0x00a48b16, 0x00a48c16, 0x00a48c18, 0x00a48c18, 0x00a48c18, 0x009e8917, 0x00908016, 0x00777114, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00646414, 0x00626312, 0x005e5f13, 0x005c5c11, 0x00585911, 0x00555610, 0x00515110, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d08, 0x00060c08, 0x00060d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00020e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x0004100a, 0x00041009, 0x00040d08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060f09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e0b, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00061009, 0x00061009, 0x00061009, 0x00061009, 0x00070f08, 0x00070f08, 0x00081009, 0x00060f08, 0x00040d05, 0x00071007, 0x00071007, 0x00071007, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00051009, 0x00051008, 0x00061009, 0x00070f0a, 0x00070f0a, 0x0007100b, 0x000a100a, 0x00191c16, 0x0025241e, 0x00342e28, 0x00433932, 0x00493e34, 0x0044382d, 0x004c3c2f, 0x00553f30, 0x00503724, 0x00503420, 0x00573d27, 0x00634932, 0x00604429, 0x005c3b1d, 0x005c3815, 0x0058330f, 0x00532d0c, 0x004f280a, 0x004b2607, 0x004b2406, 0x00522c0d, 0x00542e0f, 0x00532b0c, 0x00542c0c, 0x00572f0d, 0x00512908, 0x004d2605, 0x004c2507, 0x004c2506, 0x004d2406, 0x004e2508, 0x0051260b, 0x0050250a, 0x00502408, 0x004f2504, 0x004f2504, 0x004e2403, 0x004c2102, 0x004c2000, 0x004b1e00, 0x004c1f02, 0x004b1c00, 0x00481c00, 0x00481c01, 0x00471b00, 0x00451800, 0x00421600, 0x00431800, 0x00461900, 0x004b1c01, 0x004c1d01, 0x00542408, 0x005c2c10, 0x005d2c10, 0x005e2c0f, 0x00643114, 0x00643011, 0x00653311, 0x006b3814, 0x00744018, 0x00713e13, 0x00744214, 0x00764416, 0x00744013, 0x00703d10, 0x0065360a, 0x005d3008, 0x00582c0c, 0x00542b0f, 0x00542c0b, 0x005c3210, 0x005e3510, 0x005e350e, 0x005c330c, 0x00572d08, 0x00512806, 0x004f2407, 0x0051280d, 0x004e280f, 0x0048240c, 0x00401f06, 0x0040220b, 0x003e200a, 0x003c1f0c, 0x003e2210, 0x00321a0a, 0x002a160a, 0x001c1006, 0x00130f08, 0x000e100a, 0x000e100a, 0x000f100a, 0x00141009, 0x0019150c, 0x0021170d, 0x0028160d, 0x002a1408, 0x002e1b0a, 0x00312211, 0x002d2012, 0x00271e14, 0x001e1a13, 0x0013140f, 0x000c110c, 0x0009100a, 0x00081009, 0x00060e08, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060d0b, 0x00060e09, 0x00070f0a, 0x00070f09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00050e08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250b, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x003c3e0c, 0x0040400d, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4c0f, 0x004d4d10, 0x00505010, 0x00515110, 0x00535410, 0x00545411, 0x00555511, 0x00555511, 0x00565711, 0x00565710, 0x00585810, 0x00585810, 0x00585810, 0x00585810, 0x00585810, 0x00585811, 0x00585811, 0x00585811, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x005c5c12, 0x005d5d12, 0x005e5f13, 0x00606013, 0x00606013, 0x00626213, 0x00636314, 0x00646414, 0x00656514, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00686814, 0x00686814, 0x00646513, 0x00646414, 0x00616112, 0x005e5f13, 0x005c5c11, 0x00595a11, 0x00555610, 0x00515110, 0x004d4e0f, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0005100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x0004100a, 0x00041009, 0x00040d08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060f09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060d08, 0x00070d09, 0x00060e0b, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110c, 0x0009110d, 0x00070f0b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x00061009, 0x00061009, 0x00061009, 0x00061009, 0x00071007, 0x00071007, 0x0009120a, 0x00081008, 0x00040d05, 0x00071007, 0x00071007, 0x00071007, 0x0007110a, 0x0007110c, 0x0005100a, 0x0005100a, 0x00051009, 0x00051008, 0x00061009, 0x00070f0a, 0x00070f0a, 0x0006100b, 0x0009110b, 0x00161b15, 0x00282923, 0x002c2c25, 0x00353129, 0x00443c33, 0x00443c30, 0x00554538, 0x00554030, 0x00543928, 0x004c301c, 0x00573d29, 0x005e442e, 0x005e4227, 0x005a3b1c, 0x00573410, 0x0058340e, 0x00583210, 0x00542e0d, 0x00552d0d, 0x00532b09, 0x005b3210, 0x00633917, 0x00653c18, 0x00683e1c, 0x006c421f, 0x00683f1e, 0x00623818, 0x005e3618, 0x005e3618, 0x005e3519, 0x005d3519, 0x005e3418, 0x005c3015, 0x005c3010, 0x0054290a, 0x00532707, 0x00522507, 0x00502206, 0x00502004, 0x004d1d01, 0x004c1c00, 0x004c1d00, 0x004c1d00, 0x004d1e00, 0x00512103, 0x00542507, 0x00552809, 0x005c2f10, 0x005e3011, 0x00623414, 0x00663818, 0x00653617, 0x00673717, 0x00683616, 0x00693616, 0x006a3514, 0x006a3411, 0x006d3812, 0x00713a12, 0x00743f12, 0x00723c0c, 0x0076410c, 0x0078430e, 0x00753f0a, 0x00703d08, 0x006a3a08, 0x00633308, 0x005c2f0c, 0x005a2e10, 0x00572d0c, 0x005c3310, 0x005c340e, 0x005c340c, 0x005b320b, 0x00542a05, 0x00512806, 0x004e2508, 0x004e240a, 0x0048220a, 0x00431f08, 0x00412109, 0x0040210c, 0x003d1e09, 0x003b1d0b, 0x00361808, 0x00341c0c, 0x0028180c, 0x00170e04, 0x00121108, 0x000e110b, 0x000f100a, 0x00100f09, 0x0017130b, 0x001e170e, 0x00251810, 0x0028180d, 0x002a1609, 0x002e1c0b, 0x0030210f, 0x002b1e0e, 0x00261c10, 0x001d1810, 0x0013140f, 0x000c140d, 0x0009130c, 0x0007110a, 0x00061009, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e07, 0x00050e06, 0x00050e06, 0x00050e06, 0x00060e08, 0x00060e09, 0x00050d09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0a, 0x002c2d0a, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x004f5010, 0x00505010, 0x00515110, 0x00525310, 0x00535410, 0x00545510, 0x00545510, 0x00555611, 0x00545511, 0x00555611, 0x00565711, 0x00555610, 0x00555611, 0x00565710, 0x00565710, 0x00565710, 0x00585910, 0x00585911, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005d5e11, 0x005e5f12, 0x00606013, 0x00616112, 0x00626313, 0x00646414, 0x00646514, 0x00666714, 0x00686815, 0x006b6a14, 0x008a7c15, 0x008d7e15, 0x008d7e15, 0x008d7e15, 0x008c7d15, 0x008c7d16, 0x008c7c14, 0x008b7b14, 0x008b7a14, 0x00897814, 0x007c6f13, 0x005b5a11, 0x00555610, 0x00525310, 0x004d4e0f, 0x0048490f, 0x0045470e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00080d09, 0x00080c09, 0x00080d09, 0x00050e09, 0x00040e09, 0x00030d08, 0x00010d08, 0x00030f09, 0x00030f09, 0x0004100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x00090f0b, 0x00090f0b, 0x000a100c, 0x000a100c, 0x00081009, 0x00081009, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110a, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x0008110a, 0x0008110a, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x0008100b, 0x000c130f, 0x00131913, 0x002a2e29, 0x002e2f2a, 0x00323029, 0x00383329, 0x00403a2d, 0x00504434, 0x00534030, 0x0058402e, 0x00503422, 0x00533824, 0x00543924, 0x005c4025, 0x00563819, 0x0052310e, 0x005c3814, 0x005a3310, 0x0058300d, 0x005b3110, 0x005d330e, 0x00613610, 0x00673c14, 0x00683e14, 0x006c4219, 0x00744822, 0x00764a28, 0x00744728, 0x00714729, 0x006e4428, 0x006a4125, 0x00673d23, 0x006b401b, 0x0070431b, 0x00744218, 0x00764017, 0x00754018, 0x00743e19, 0x00743d1b, 0x00733d18, 0x00703d15, 0x006f3c14, 0x006c3910, 0x006c3910, 0x006c3a10, 0x006f3c13, 0x00703e15, 0x00703d16, 0x00703c15, 0x006d3b14, 0x006c3a13, 0x00693810, 0x00673610, 0x0067350f, 0x0068350f, 0x006a350f, 0x006a3510, 0x006c370f, 0x006c370c, 0x006e370a, 0x00703809, 0x00723a0a, 0x00743c0c, 0x00773f0d, 0x00753d0c, 0x00713b0c, 0x006d3c11, 0x0066360d, 0x005c2f09, 0x00592e0a, 0x005b320e, 0x005b330f, 0x005a330d, 0x005c320d, 0x005b320c, 0x00502804, 0x004e2805, 0x004f2809, 0x004c240b, 0x0048220a, 0x00411f07, 0x0040230c, 0x003e210c, 0x003c1f0a, 0x003c200e, 0x00351709, 0x0032180c, 0x001c1003, 0x00161004, 0x00111208, 0x0010140b, 0x0012110a, 0x00161008, 0x001e140b, 0x0024180d, 0x002a1a11, 0x002d1b11, 0x0028170a, 0x002a1908, 0x00302110, 0x002d2011, 0x00271d10, 0x00201710, 0x00151510, 0x000e150f, 0x000b130c, 0x0008120b, 0x0007110a, 0x0006100b, 0x0006100b, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0009120c, 0x0009120c, 0x0009130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a120c, 0x0009110c, 0x0009110c, 0x000a120e, 0x000a120e, 0x0009110d, 0x0008100c, 0x0008100c, 0x0008100c, 0x0009120b, 0x000a130c, 0x000a130c, 0x000a130c, 0x00081109, 0x00081109, 0x00081108, 0x00081008, 0x0009100b, 0x00080f0a, 0x00060e09, 0x00060f0a, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d09, 0x00040d09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00080f0a, 0x00081009, 0x00060e08, 0x00040d07, 0x00040e07, 0x00030e07, 0x00030e07, 0x00041008, 0x00041008, 0x0004100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060b07, 0x00050b05, 0x00070c06, 0x00070d06, 0x00060f08, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040e07, 0x00020e07, 0x00020e07, 0x00031008, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280a, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004b4c0f, 0x004c4d0f, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00525310, 0x00535410, 0x00535410, 0x00535410, 0x00545510, 0x00535410, 0x00545510, 0x00555611, 0x00545510, 0x00565711, 0x00565711, 0x00585810, 0x00585911, 0x00595a12, 0x005c5c11, 0x005d5e11, 0x005e5f13, 0x00606013, 0x00616112, 0x00636414, 0x00646514, 0x00666713, 0x00686714, 0x00a48c17, 0x00c8a519, 0x00caa51a, 0x00caa51a, 0x00caa51a, 0x00caa51a, 0x00caa41a, 0x00c9a419, 0x00c9a419, 0x00c9a418, 0x00c9a318, 0x00c7a017, 0x008e7a13, 0x00545511, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0040400d, 0x003c3e0d, 0x0036370c, 0x0032330c, 0x002d2f0a, 0x0026280a, 0x0026280c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00080d09, 0x00080c09, 0x00080c09, 0x00050e09, 0x00040e09, 0x00030d08, 0x00010d08, 0x00030f09, 0x00030f09, 0x0004100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x00081009, 0x00081009, 0x0008110b, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120b, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x0008110a, 0x0008110a, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0009100b, 0x00080f0a, 0x000b100c, 0x000e1310, 0x001a1e1b, 0x00303532, 0x0031322e, 0x002e2c26, 0x002d2920, 0x003d372a, 0x00473c2c, 0x00483928, 0x00503b28, 0x00533826, 0x0049301a, 0x0050351f, 0x00583c23, 0x0056381b, 0x00523211, 0x005b3716, 0x00593412, 0x005a310e, 0x005c320e, 0x00623711, 0x00693c14, 0x00683c12, 0x006e4218, 0x0070441a, 0x00784b24, 0x00764a28, 0x00754829, 0x0075482b, 0x0072462b, 0x006e4428, 0x006b4124, 0x006b411c, 0x006d4018, 0x00704015, 0x00743f14, 0x00763d13, 0x00783c13, 0x00783c13, 0x00783d13, 0x007c4217, 0x007c4317, 0x00774012, 0x00753d11, 0x00743c10, 0x00743c10, 0x00743c10, 0x00743c11, 0x00723a10, 0x006e350c, 0x006c360b, 0x0069340b, 0x0068350b, 0x0066360c, 0x0066370c, 0x0067370f, 0x0067370f, 0x0067360d, 0x0068360a, 0x006a3709, 0x006f3909, 0x00703a09, 0x00713b0a, 0x00743e0c, 0x00733d0c, 0x006f3a0b, 0x006d3c11, 0x0066360e, 0x005a2c06, 0x005c310c, 0x005e3511, 0x005c3511, 0x0058310c, 0x0058310c, 0x00552f09, 0x00512b06, 0x00492604, 0x00492708, 0x004a260c, 0x00432008, 0x003c1c05, 0x0040220c, 0x003d200c, 0x003c1f0b, 0x003c200e, 0x00371b0d, 0x002c170a, 0x00140c00, 0x00141006, 0x00141309, 0x0014140c, 0x0018140b, 0x001c1209, 0x0024170d, 0x00291b11, 0x002d1c12, 0x002d1d11, 0x002b1b0e, 0x0029190b, 0x002b1c0e, 0x002a1c10, 0x00271d12, 0x00211811, 0x00161610, 0x000f150e, 0x000c140e, 0x000b150e, 0x000a140d, 0x0009130e, 0x0009130e, 0x0008120c, 0x0008120c, 0x0008120d, 0x0008120d, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x0009110d, 0x0009110d, 0x000a120e, 0x000a120e, 0x000a120e, 0x000a120e, 0x000a120e, 0x000a120e, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x00081109, 0x00081108, 0x0009120a, 0x000a130b, 0x000b120d, 0x0009100c, 0x00070f0a, 0x00060f0a, 0x0006100b, 0x0006100b, 0x00050f0a, 0x0006100b, 0x0006100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00080f0a, 0x00091009, 0x00060e08, 0x00040d07, 0x00040e07, 0x00020e07, 0x00020e07, 0x00041008, 0x00041008, 0x0004100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00080c09, 0x00080c08, 0x00070d08, 0x00070e06, 0x00050f08, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040e07, 0x00020e07, 0x00020e07, 0x00031008, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0c, 0x00191c09, 0x001d2009, 0x00202308, 0x0020230a, 0x0026280b, 0x00292b0a, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003c3e0c, 0x0040400d, 0x0041420e, 0x0044450d, 0x0047480e, 0x0048490f, 0x00494a0f, 0x004b4c0f, 0x004c4d0f, 0x004f5010, 0x004f5010, 0x00505010, 0x004f5010, 0x00515110, 0x00505010, 0x00505010, 0x00515110, 0x00515110, 0x00525310, 0x00535410, 0x00535410, 0x00545510, 0x00545511, 0x00555611, 0x00565710, 0x00585911, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00626313, 0x00646414, 0x00656614, 0x006a6714, 0x00c5a219, 0x00cca71a, 0x00c4a019, 0x00c1a019, 0x00c1a019, 0x00c1a018, 0x00c19f18, 0x00c19f18, 0x00c19f18, 0x00c19f18, 0x00c6a018, 0x00cca418, 0x00b09014, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003b3c0c, 0x0036370b, 0x0034350c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00080d09, 0x00080c09, 0x00080c09, 0x00050e09, 0x00040e09, 0x00030d08, 0x00010d08, 0x00030f09, 0x0004100a, 0x0004100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x0008110a, 0x0008110a, 0x0009110d, 0x0009110d, 0x000a120e, 0x000a120e, 0x000a130c, 0x000a130c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009140b, 0x0009140b, 0x0009130b, 0x0009140b, 0x000b130c, 0x000b130c, 0x000b130c, 0x000b140b, 0x0009120c, 0x0009120c, 0x0009130c, 0x0009130c, 0x0009130c, 0x0009130c, 0x000b130e, 0x000b130f, 0x000b130e, 0x000b130e, 0x000b110e, 0x00101412, 0x00151918, 0x001c201e, 0x00222624, 0x00303230, 0x00343734, 0x00363733, 0x002d2b26, 0x0029251c, 0x00353024, 0x0041392a, 0x00403322, 0x00493523, 0x004c3521, 0x004b311a, 0x00523720, 0x00553b23, 0x0053351c, 0x00563519, 0x00573416, 0x005a3312, 0x005c320d, 0x005b310a, 0x005e340b, 0x00643a0f, 0x00693d10, 0x006c4013, 0x0070441b, 0x00754822, 0x00754925, 0x00714624, 0x00744728, 0x00744728, 0x00764c2c, 0x00734928, 0x006c4320, 0x006a3f19, 0x006c3e16, 0x00703d13, 0x00713b10, 0x0074390d, 0x0074390d, 0x0074390c, 0x00743a0d, 0x00743c0e, 0x00743c10, 0x00733b0f, 0x0070380c, 0x0070380c, 0x0070390c, 0x0070380e, 0x006d350c, 0x006a3208, 0x00693308, 0x00683309, 0x00663409, 0x0062360b, 0x0062370b, 0x0061370c, 0x0062370d, 0x0062360b, 0x0064380a, 0x006b3c0c, 0x006e3d0c, 0x006f3c0a, 0x00703d0b, 0x00713e0c, 0x006e3b09, 0x006b3808, 0x0068370d, 0x0062320a, 0x00582c05, 0x00582d08, 0x00562e08, 0x0058310c, 0x0059320c, 0x00562f09, 0x00522c09, 0x004c2907, 0x00462505, 0x00442608, 0x003c1d04, 0x003c1f07, 0x003c2008, 0x003a1e08, 0x003b1d09, 0x003e210f, 0x00371d0e, 0x00291405, 0x00201104, 0x00100c00, 0x000f0c02, 0x0015120c, 0x001a150e, 0x00241c12, 0x002a1d14, 0x002c1c11, 0x002d1c11, 0x002d1d11, 0x002e1e11, 0x002e1e10, 0x002f1f10, 0x002c1e11, 0x002a1d12, 0x00281e15, 0x00231914, 0x001a1812, 0x00131610, 0x000e140e, 0x000d140e, 0x000c140d, 0x000a120e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0008120c, 0x0008120d, 0x0009110c, 0x0009110d, 0x000a120e, 0x000a120e, 0x000c140d, 0x000c140d, 0x000c140e, 0x000c140d, 0x000c140d, 0x000c140e, 0x000d150f, 0x000d150f, 0x000c140f, 0x000c1410, 0x000c1410, 0x000d1510, 0x000d1510, 0x000d1510, 0x000d1510, 0x000c140f, 0x000a120e, 0x0009120c, 0x0009120c, 0x000c140d, 0x000c140d, 0x000a120b, 0x000c140c, 0x000a130b, 0x000a130b, 0x000b120d, 0x000b120e, 0x0009110d, 0x0008110c, 0x0008120c, 0x0009130e, 0x0009130e, 0x0008120c, 0x0008110c, 0x0009100c, 0x0009110c, 0x0008100c, 0x00070f0a, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f09, 0x00080e08, 0x00070f08, 0x00070f08, 0x00051008, 0x00031008, 0x00041008, 0x00041008, 0x00041008, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00090e0b, 0x00091009, 0x00080f08, 0x00061008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040e07, 0x00020e07, 0x00020e07, 0x00031008, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280a, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0040400d, 0x0043440e, 0x0044450d, 0x0045470e, 0x0047480f, 0x0048490f, 0x00494a0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004c4d0f, 0x004f5010, 0x004f5010, 0x004d4e10, 0x00505010, 0x00505010, 0x00505010, 0x00515110, 0x00515110, 0x00525310, 0x00535410, 0x00545511, 0x00555611, 0x00565710, 0x00585911, 0x005b5b12, 0x005c5d11, 0x005d5e12, 0x00606012, 0x00616112, 0x00626314, 0x00646414, 0x006a6714, 0x00c6a219, 0x00cca61a, 0x00847715, 0x00736e14, 0x00736e14, 0x00736e14, 0x00726d14, 0x00716c14, 0x00706a14, 0x006e6814, 0x009f8615, 0x00cca418, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x0030310c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00080d09, 0x00080c09, 0x00080c09, 0x00050e09, 0x00040e09, 0x00030d08, 0x00010d08, 0x00030f09, 0x0004100a, 0x0006120c, 0x0007120c, 0x00070f08, 0x00070f08, 0x0008110a, 0x0008110a, 0x0008120d, 0x0008120d, 0x0009130e, 0x0009130e, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x0009120c, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x0008140b, 0x0008140b, 0x0009150c, 0x000a150c, 0x000c150c, 0x000c150c, 0x000c150c, 0x000c150c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c1410, 0x000c1410, 0x000c1411, 0x000d1412, 0x000e1411, 0x00141816, 0x001b1f1c, 0x00282c29, 0x00353837, 0x00393b3b, 0x00363837, 0x00343434, 0x002d2c28, 0x0026241b, 0x002a281b, 0x00383324, 0x00423827, 0x00493826, 0x0049341f, 0x004d341c, 0x0050341c, 0x00563b24, 0x0052351f, 0x00573820, 0x005a381c, 0x005c3614, 0x005b330c, 0x005e340a, 0x0063380e, 0x0064390c, 0x006a3f10, 0x006d4213, 0x0074471d, 0x00794b24, 0x00754824, 0x00744624, 0x00704422, 0x00704423, 0x00734928, 0x00704724, 0x006b441f, 0x00693f1a, 0x006c3f19, 0x00693a11, 0x0068380b, 0x006c380b, 0x006c380c, 0x006c380c, 0x006b370c, 0x006a370c, 0x006a380d, 0x0069370d, 0x0066340b, 0x0067340b, 0x0067350c, 0x0068350c, 0x0064320a, 0x00633008, 0x00613108, 0x00613108, 0x005f3208, 0x005d3409, 0x005c3409, 0x0060370c, 0x0060380c, 0x0061380c, 0x00643b0c, 0x006a3e0d, 0x006c3e0d, 0x006d3c0b, 0x00703e0c, 0x00713f0c, 0x006c3c09, 0x00693808, 0x0065340a, 0x005e2e06, 0x00582c05, 0x00562c08, 0x00522c07, 0x00542f08, 0x004e2904, 0x00512c08, 0x004c2907, 0x00482506, 0x00442608, 0x0042260a, 0x003a1e05, 0x003b2007, 0x00391e08, 0x00381b07, 0x003c1d0c, 0x00371b0a, 0x00321b0c, 0x00241204, 0x00150c00, 0x000e0d00, 0x000e0c03, 0x0018140d, 0x00201811, 0x002a1f14, 0x002f2015, 0x00302014, 0x00312014, 0x00312014, 0x00322214, 0x00322214, 0x00322213, 0x00302114, 0x002d2016, 0x002a2018, 0x00241b16, 0x001b1813, 0x00141510, 0x0010140f, 0x000f140e, 0x000c120c, 0x000a140f, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x000b1410, 0x000b1510, 0x000c140f, 0x000c140f, 0x000b130e, 0x000a120e, 0x000c140d, 0x000c140e, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000c1410, 0x000c1410, 0x000d1510, 0x000d1510, 0x000d1510, 0x000d1510, 0x000d1510, 0x000c140f, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140c, 0x000d160e, 0x000b130c, 0x000a130c, 0x000b120d, 0x000b120e, 0x000a120e, 0x000b130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0009110d, 0x0009110d, 0x0009100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f09, 0x00080e08, 0x00070f08, 0x00070f08, 0x00051008, 0x00041008, 0x00051009, 0x00041008, 0x00041008, 0x00040f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00080f0b, 0x0008100a, 0x00070f08, 0x00061008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040e07, 0x00030e07, 0x00030e07, 0x00041008, 0x00041008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250c, 0x0026280b, 0x002c2d0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003b3c0c, 0x003e400c, 0x0040400d, 0x0043440e, 0x0044450d, 0x0045470d, 0x0047480e, 0x0048490f, 0x00494a10, 0x004b4c10, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e10, 0x004f5010, 0x00505010, 0x00515110, 0x00515110, 0x00525310, 0x00545510, 0x00555611, 0x00585810, 0x00585911, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00626313, 0x00646414, 0x00696614, 0x00c6a218, 0x00cca61a, 0x007c7315, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00646514, 0x00646414, 0x00616112, 0x009b8415, 0x00cca418, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e09, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e07, 0x00060e08, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e09, 0x00080c09, 0x00080c0a, 0x00070c0b, 0x00060e0b, 0x0005100a, 0x0004100a, 0x0007110d, 0x0008120d, 0x0008110b, 0x0008120a, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0008120c, 0x0008120c, 0x0009140c, 0x0009140c, 0x000c140d, 0x000c140d, 0x000b140d, 0x000b140d, 0x000b140d, 0x000b140d, 0x000c140d, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d160d, 0x000d160d, 0x000c150c, 0x000c150c, 0x000d140c, 0x000d140c, 0x000e140c, 0x000e140c, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c1510, 0x000b1410, 0x000f1614, 0x00151b18, 0x00171b17, 0x0020231e, 0x00292c27, 0x00343632, 0x00363636, 0x00323234, 0x002f2f2f, 0x0023231f, 0x001b1a11, 0x00242418, 0x002a2819, 0x00373020, 0x00403220, 0x0046341e, 0x00483018, 0x004f341c, 0x00593e28, 0x00543624, 0x00573723, 0x005b381f, 0x005c3718, 0x005b340e, 0x005c340c, 0x00603810, 0x00643a10, 0x006a3e14, 0x006e4016, 0x00774820, 0x00754720, 0x00754823, 0x00744823, 0x00704520, 0x00704520, 0x006d441f, 0x0069401b, 0x00673d18, 0x00633a13, 0x00613810, 0x0062360d, 0x0062360a, 0x00603508, 0x0060340a, 0x0060340c, 0x0060340c, 0x005f330a, 0x005b3108, 0x00582f06, 0x00593008, 0x005a3008, 0x00593008, 0x00593008, 0x005c320c, 0x005b310b, 0x00582d08, 0x005d2f08, 0x005f3108, 0x00603308, 0x00613409, 0x0064350b, 0x0063360b, 0x0064380c, 0x00683c0f, 0x006b3c0e, 0x006c3c0c, 0x00703d0b, 0x006e3c09, 0x006c3a08, 0x006b3a09, 0x00653808, 0x005a2f04, 0x00562c02, 0x0058310a, 0x0058310a, 0x00542e08, 0x00502c08, 0x004a2804, 0x004c2c08, 0x00402000, 0x00402104, 0x0043240b, 0x00371a02, 0x00381d06, 0x00391c07, 0x00381c08, 0x00381c08, 0x003b1d0b, 0x00351a09, 0x002c1708, 0x00201207, 0x00100c01, 0x000c0f06, 0x000e0d05, 0x00171208, 0x0022170c, 0x002e2013, 0x00342519, 0x002c1f14, 0x002a1e14, 0x00302118, 0x00332518, 0x00332517, 0x00302212, 0x002d2012, 0x002c2115, 0x002b221a, 0x00221c16, 0x001a1812, 0x00171511, 0x00121410, 0x0011140f, 0x000f140f, 0x000a140f, 0x000a140f, 0x000a140f, 0x000a140f, 0x000b150e, 0x000b150e, 0x000b150e, 0x000b150e, 0x000d150f, 0x000e1610, 0x000d150f, 0x000d150f, 0x000e1610, 0x000e1710, 0x000f1710, 0x000d150f, 0x000e1710, 0x000f1811, 0x000f1811, 0x000e1710, 0x000e1710, 0x000e1612, 0x000e1612, 0x000e1612, 0x000f1713, 0x000e1612, 0x000e1612, 0x000e1612, 0x000e1612, 0x000e1710, 0x000f1610, 0x000e150f, 0x000e150f, 0x000e1510, 0x000e1510, 0x000e1510, 0x000e1510, 0x000e140f, 0x000d130d, 0x000c120c, 0x000c130d, 0x000c140e, 0x000c140d, 0x000b130c, 0x0009120c, 0x0009120c, 0x0009130e, 0x0009130e, 0x0008120c, 0x0008110c, 0x0007110c, 0x0006100b, 0x0007110c, 0x0007110c, 0x0008120d, 0x0007130d, 0x0006120c, 0x0005100b, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x0005100a, 0x00040d08, 0x00040e09, 0x00040e09, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060f0a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100d, 0x0008100c, 0x0008100b, 0x00090f0b, 0x00080f0a, 0x00070f0a, 0x00060e0a, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040c06, 0x00040c08, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100a, 0x00051008, 0x00040f08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x0038380c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0047480e, 0x0047480f, 0x00484910, 0x00484910, 0x00494a10, 0x004b4c10, 0x004b4c0f, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00525310, 0x00525310, 0x00545510, 0x00555611, 0x00585810, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00626312, 0x00636414, 0x00686514, 0x00c6a219, 0x00cca619, 0x007c7215, 0x00686814, 0x00686814, 0x00666714, 0x00656613, 0x00656614, 0x00636414, 0x00626312, 0x009b8415, 0x00cca418, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x004b4c10, 0x0047480e, 0x0041420e, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e0a, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0006100b, 0x0006100b, 0x0005100b, 0x0005100a, 0x00050f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00060e06, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080f0b, 0x000a0f0b, 0x000a0f0c, 0x00090f0c, 0x00080f0b, 0x00070f08, 0x00051009, 0x0007110c, 0x0008120c, 0x0008130a, 0x0008130a, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c140e, 0x000c140e, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e170e, 0x000e170e, 0x000f1810, 0x000f1810, 0x0010160e, 0x0010160e, 0x0010160e, 0x0010160e, 0x000f1610, 0x000e1610, 0x000e1610, 0x000d1711, 0x000c1612, 0x00111815, 0x00151a17, 0x00181c16, 0x00272921, 0x00303028, 0x0034342e, 0x00323230, 0x002e2e2e, 0x00282828, 0x001b1c18, 0x0011130a, 0x001f2015, 0x0028281c, 0x00363024, 0x003b301f, 0x0042311c, 0x00432c15, 0x00472d16, 0x00523822, 0x00523625, 0x00563924, 0x0058391e, 0x00583616, 0x005b3713, 0x0059340e, 0x005c350f, 0x00613911, 0x006b3f17, 0x006e4218, 0x00754720, 0x00784a23, 0x00754823, 0x00744823, 0x00714620, 0x0070441e, 0x0069401c, 0x00673d18, 0x00643b14, 0x00603710, 0x005d340d, 0x005c340c, 0x005c3409, 0x005b3208, 0x00583107, 0x00562f08, 0x00562f0b, 0x00542e0a, 0x00502b09, 0x004e2807, 0x004f2908, 0x00502a08, 0x00502a08, 0x00502b08, 0x00522f0c, 0x0054300c, 0x00522c05, 0x005b300a, 0x0060340b, 0x0062340a, 0x0066360c, 0x0067380d, 0x0067380d, 0x0069390d, 0x006d3c10, 0x006f3c0e, 0x00703b0c, 0x00703c0c, 0x006f3c0a, 0x006b3909, 0x0068390a, 0x00603306, 0x005b3006, 0x005b320c, 0x0057310c, 0x0057310c, 0x00532f0a, 0x00502c09, 0x00492807, 0x004b2c0c, 0x00391c00, 0x003b1d01, 0x003d2008, 0x00381c06, 0x003b1d08, 0x00391c07, 0x00381c08, 0x00381c0b, 0x003a1d0c, 0x00341b0b, 0x00281708, 0x001c1106, 0x00110f07, 0x000b0f06, 0x000c0e06, 0x00171208, 0x0021170b, 0x002e2013, 0x00342619, 0x00281c12, 0x00241b13, 0x002a1f16, 0x002e2318, 0x00312518, 0x002e2213, 0x002e2416, 0x00292015, 0x00221c13, 0x001e1a14, 0x001a1813, 0x00161512, 0x00121410, 0x0011140f, 0x0010140f, 0x000c1410, 0x000c1410, 0x000d1510, 0x000d1510, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x00101711, 0x00101711, 0x000f150f, 0x000f150f, 0x000f1610, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1710, 0x000f1811, 0x000f1811, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x000f1811, 0x000f1811, 0x00101812, 0x00101812, 0x00121812, 0x00131712, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00101610, 0x000f150f, 0x000e150f, 0x000d150f, 0x000d150f, 0x000c140e, 0x000b130c, 0x000a130c, 0x000a140f, 0x000a140f, 0x000a140f, 0x000a140f, 0x0009130e, 0x0009130e, 0x0008120c, 0x0007110c, 0x0007130d, 0x0007130d, 0x0007130d, 0x0007130d, 0x0006110c, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040f09, 0x0005100a, 0x00040d08, 0x00040e09, 0x00040f09, 0x0008100b, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00060e09, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005100e, 0x0006100c, 0x0008100b, 0x00090f0b, 0x00080f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040c06, 0x00040c08, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100a, 0x00051008, 0x00040f08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x00191c08, 0x00202308, 0x0024250a, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0030310c, 0x0034350c, 0x0038380c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0040400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0047480d, 0x0047480e, 0x00484910, 0x00484910, 0x00494a10, 0x00494a10, 0x00494a10, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00515110, 0x00525310, 0x00535410, 0x00555611, 0x00585810, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00606013, 0x00636413, 0x00686414, 0x00c6a219, 0x00cca619, 0x007c7114, 0x00666714, 0x00666714, 0x00666713, 0x00656614, 0x00646414, 0x00646414, 0x00616112, 0x009b8415, 0x00cca417, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0047480f, 0x0041420e, 0x003e400d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250b, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f09, 0x0008110a, 0x00081009, 0x00070f08, 0x00070f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060f0b, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x0008100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0005100a, 0x00050f0a, 0x00060e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00060e06, 0x00081009, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f08, 0x00070f08, 0x00081009, 0x000a0f09, 0x000b0f0b, 0x000b0f0c, 0x000a100a, 0x000a100a, 0x0009120b, 0x0009120c, 0x000a130c, 0x000a130b, 0x000b140b, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000f150f, 0x00101610, 0x00101610, 0x00101710, 0x00101711, 0x00101711, 0x00111812, 0x00101711, 0x000f1510, 0x00111812, 0x00111812, 0x00121813, 0x00121813, 0x00121911, 0x00121911, 0x00131a12, 0x00131a12, 0x00141811, 0x00111610, 0x0010150e, 0x0010150e, 0x00101711, 0x00101711, 0x00101711, 0x00121913, 0x00101814, 0x00131a16, 0x00161914, 0x001c1d14, 0x0025251b, 0x002f2c24, 0x002f2d26, 0x00302d2a, 0x002e2c2b, 0x00252422, 0x00242420, 0x00181a14, 0x0013140c, 0x0024241a, 0x002e2b20, 0x0031281a, 0x003f301d, 0x0048351d, 0x003f2710, 0x00442c18, 0x004c3321, 0x00543924, 0x0055381c, 0x00543518, 0x00563416, 0x00573313, 0x005b3613, 0x00603b14, 0x00683f18, 0x00693f17, 0x006f421b, 0x00754923, 0x00744824, 0x00734823, 0x006e4520, 0x006b421d, 0x00683f1a, 0x00693e19, 0x00663c16, 0x00623912, 0x005f3710, 0x005d360e, 0x005d360c, 0x00583108, 0x00512a04, 0x00522c08, 0x00522c0c, 0x00502b0b, 0x00502a0c, 0x004e280b, 0x004e290c, 0x004d280b, 0x004d280b, 0x00542e10, 0x0053300f, 0x0054300c, 0x00552f09, 0x005e340d, 0x0064380e, 0x0065370c, 0x0067380d, 0x0067380d, 0x0068380e, 0x006b3a0f, 0x006f3d10, 0x00703c0e, 0x006f3b0b, 0x006e3a09, 0x006c3b0b, 0x0068390a, 0x00633508, 0x0062360b, 0x00603610, 0x005a300c, 0x005c3410, 0x0058300e, 0x00522c0b, 0x00502d0c, 0x00482709, 0x0047280b, 0x003a1d04, 0x003a1d04, 0x003c200b, 0x003a1e0a, 0x00381c0b, 0x00381c0b, 0x00381c0a, 0x00361a08, 0x00381c0b, 0x00311909, 0x00241507, 0x00181006, 0x00131209, 0x000c1107, 0x000d0f05, 0x00161107, 0x0020160b, 0x002b1e12, 0x00312418, 0x00271c11, 0x00231912, 0x00251d15, 0x002a2018, 0x002d2519, 0x0030271a, 0x002f261a, 0x00272116, 0x001f1c13, 0x001d1d15, 0x001a1b16, 0x00141813, 0x00141713, 0x00141612, 0x00131712, 0x00111814, 0x00101713, 0x00101512, 0x00101511, 0x00101711, 0x00111812, 0x00111812, 0x00111812, 0x00111611, 0x00111611, 0x00131712, 0x00131712, 0x00121812, 0x00111812, 0x00111812, 0x00101711, 0x00111812, 0x00111813, 0x00121813, 0x00121813, 0x00121813, 0x00111812, 0x00111812, 0x00101812, 0x00101812, 0x00101811, 0x00101811, 0x00111812, 0x00111812, 0x00131714, 0x00141614, 0x00131513, 0x00131513, 0x00131513, 0x00131513, 0x00131513, 0x00131513, 0x00121612, 0x00111711, 0x00101710, 0x00101610, 0x000e1610, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000b1510, 0x000b1510, 0x0008140f, 0x0007130d, 0x0008140d, 0x0008140e, 0x0008120c, 0x0006100b, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00050d09, 0x00040c08, 0x00040f09, 0x0005100a, 0x0004100a, 0x0003100d, 0x0004100c, 0x0006100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x00060e08, 0x00030d06, 0x00040d09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x0006100a, 0x00051008, 0x00040f08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180a, 0x00191c09, 0x00191c08, 0x001d2008, 0x00202308, 0x0026280c, 0x00292b0b, 0x00292b0a, 0x0030310b, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003b3c0d, 0x003e400c, 0x003e400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0045470e, 0x0047480d, 0x0047480e, 0x00484910, 0x00484910, 0x00494a10, 0x00494a10, 0x00494a10, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545511, 0x00565711, 0x00585911, 0x00595a12, 0x005c5c11, 0x005e5f13, 0x00606012, 0x00616112, 0x00686414, 0x00c6a219, 0x00cca619, 0x007b7014, 0x00666713, 0x00666713, 0x00656614, 0x00646514, 0x00646414, 0x00626313, 0x00606013, 0x009b8415, 0x00cca417, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0047480f, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e0a, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0007100b, 0x00060e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e06, 0x00081008, 0x00081008, 0x00070f08, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00081009, 0x00071009, 0x0008100a, 0x000a100a, 0x000b100a, 0x000c0f0a, 0x000b100a, 0x000d130c, 0x000d140c, 0x000c140c, 0x000d140c, 0x000d140b, 0x000d140b, 0x000f140d, 0x000f140e, 0x0010140f, 0x0010140f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x00101711, 0x00111812, 0x00111812, 0x00121813, 0x00121813, 0x00121813, 0x00121813, 0x00131914, 0x00141a14, 0x00141914, 0x00141914, 0x00151a14, 0x00151a14, 0x00151a13, 0x00151a13, 0x00141912, 0x00141912, 0x00161812, 0x00161812, 0x00171913, 0x00171913, 0x00141914, 0x00141914, 0x00141914, 0x00141a14, 0x00141a14, 0x00161a14, 0x00181a14, 0x001d1c13, 0x00211f14, 0x0028241a, 0x002a251e, 0x002d2923, 0x002f2b28, 0x00282724, 0x002c2b26, 0x00181914, 0x0011140d, 0x0023251e, 0x0026251c, 0x002e281c, 0x003c3122, 0x0046351f, 0x00402d15, 0x0048321c, 0x00493320, 0x004f361e, 0x0050351a, 0x00503318, 0x0053341a, 0x00513115, 0x00502e0c, 0x0058340f, 0x00633b15, 0x00684018, 0x00684017, 0x006c441c, 0x00744a25, 0x00704822, 0x006c4520, 0x006b411c, 0x00673d18, 0x00683c18, 0x00673e17, 0x00643b14, 0x00603710, 0x00613710, 0x0060380f, 0x005c330b, 0x00562c08, 0x00572c0c, 0x00572e0e, 0x00542c0c, 0x00542c0e, 0x00542b0d, 0x00542b0d, 0x0050280a, 0x00502809, 0x00522a0b, 0x00573010, 0x005a3310, 0x005c320e, 0x0060330c, 0x0064360d, 0x0066360c, 0x0067380d, 0x0067380d, 0x0067390e, 0x0067390b, 0x006b3c0c, 0x006b3c0a, 0x006c3a08, 0x006b3a08, 0x006a390b, 0x0068390d, 0x00623409, 0x0061340c, 0x00592e09, 0x00572d0a, 0x00583010, 0x00593111, 0x004f2809, 0x004d290c, 0x00452408, 0x003d2005, 0x003a1f06, 0x00381e08, 0x00381e09, 0x00361c0b, 0x00371c0a, 0x00381c0b, 0x00381c0c, 0x00341908, 0x00341b09, 0x002d1907, 0x00251809, 0x00161104, 0x00121408, 0x000c1107, 0x000d0f05, 0x00161008, 0x001f170b, 0x00281c0f, 0x002d2014, 0x00281d13, 0x00241a13, 0x00201813, 0x001f1912, 0x00241f15, 0x00282318, 0x00282418, 0x00242318, 0x00201f16, 0x001c1d14, 0x001b1c17, 0x00181a16, 0x00161814, 0x00161814, 0x00161814, 0x00141815, 0x00141815, 0x00141814, 0x00131714, 0x00141813, 0x00141914, 0x00141814, 0x00141813, 0x00141813, 0x00141813, 0x00141813, 0x00141612, 0x00141814, 0x00141914, 0x00141914, 0x00141813, 0x00141813, 0x00141914, 0x00141914, 0x00151a14, 0x00151a14, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00141913, 0x00141914, 0x00141914, 0x00141813, 0x00141813, 0x00141814, 0x00141814, 0x00141814, 0x00141814, 0x00141814, 0x00131813, 0x00121813, 0x00101812, 0x00101812, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000e1813, 0x000d1712, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000b1510, 0x000b1510, 0x000b1710, 0x0008140f, 0x0008140e, 0x0008140e, 0x0008130d, 0x0008110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00060e09, 0x00050d09, 0x00060e09, 0x00060e09, 0x0005100a, 0x0005100a, 0x0004100a, 0x0003100d, 0x0003100c, 0x00040f0a, 0x00040e09, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040e07, 0x00040d09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x0005100a, 0x00051009, 0x00051008, 0x00040f08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180a, 0x00191c09, 0x00191c08, 0x001d2008, 0x00202308, 0x0026280c, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0c, 0x003b3c0d, 0x003e400c, 0x003e400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0045470d, 0x0047480d, 0x0047480e, 0x00484910, 0x00484910, 0x00494a10, 0x00494a10, 0x00494a10, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00525310, 0x00535410, 0x00545511, 0x00565710, 0x00585911, 0x00595a12, 0x005c5c11, 0x005e5f13, 0x00606013, 0x00616112, 0x00666413, 0x00c6a219, 0x00cca619, 0x007b7014, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00636413, 0x00606013, 0x009a8215, 0x00cca417, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0047480f, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050d07, 0x00050e08, 0x00081008, 0x00071007, 0x00071007, 0x00060e08, 0x00040c07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x00050d07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060f08, 0x00060e0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050e09, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060e08, 0x00071007, 0x00071007, 0x00070f08, 0x00070f08, 0x00081009, 0x00061009, 0x0007110a, 0x0007110a, 0x0008120b, 0x0008120c, 0x000a110c, 0x000b110c, 0x000b110c, 0x000c120c, 0x000c130c, 0x000e120d, 0x000e120d, 0x000e130c, 0x000f140c, 0x00101610, 0x00101610, 0x00101610, 0x00101610, 0x00101510, 0x00111611, 0x00121712, 0x00131812, 0x00111812, 0x00121813, 0x00121813, 0x00131914, 0x00131913, 0x00131a12, 0x00131a13, 0x00121912, 0x00151c14, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161b14, 0x00181a14, 0x00181a15, 0x00181a15, 0x00181a15, 0x00171914, 0x00181a15, 0x00191c17, 0x00191c16, 0x00181c15, 0x00181a14, 0x00181a14, 0x00181b15, 0x00171914, 0x00181a14, 0x001e1c15, 0x00211e14, 0x00211c12, 0x00241d13, 0x00252016, 0x0027211a, 0x0028241e, 0x0026241f, 0x00292924, 0x0012140e, 0x00191d17, 0x0032342e, 0x0025241c, 0x00353127, 0x003b3226, 0x003d301e, 0x0040311c, 0x0045331c, 0x00432e17, 0x00473017, 0x004b3219, 0x004f361d, 0x004f341e, 0x004d3016, 0x004c2d0c, 0x00543210, 0x0054300c, 0x00623d17, 0x00643e18, 0x0069411c, 0x006b441e, 0x006b4420, 0x006b431f, 0x0069401d, 0x00673d1a, 0x00683c18, 0x00683d17, 0x00653b12, 0x00623810, 0x0060380f, 0x005e350c, 0x00593008, 0x00542b07, 0x00512707, 0x00582e0f, 0x00572d11, 0x00562f10, 0x00593111, 0x0058300d, 0x00512808, 0x00502708, 0x00532808, 0x005a2e10, 0x005e3210, 0x005e330d, 0x0060340c, 0x0064360c, 0x0066360e, 0x0066370c, 0x0068380c, 0x0068380c, 0x0069390c, 0x006a390a, 0x006a390b, 0x0069380c, 0x0069380c, 0x0067380d, 0x0064340c, 0x0061330a, 0x0060340c, 0x00562b07, 0x005d320f, 0x00582d0c, 0x00572d0e, 0x00542c0d, 0x00522e11, 0x00442408, 0x003c2005, 0x00391e08, 0x003b1f0b, 0x00371c08, 0x00371b09, 0x00371b09, 0x00381c0a, 0x00361c0b, 0x00321908, 0x00301807, 0x002c1a08, 0x00271a09, 0x00161002, 0x000c0d00, 0x00080c02, 0x00111309, 0x00171309, 0x001c1408, 0x0024180e, 0x002d2014, 0x00281d14, 0x00241b13, 0x001f1a13, 0x001f1c15, 0x001e1c14, 0x001f1c14, 0x00202014, 0x00212318, 0x00202219, 0x001d2019, 0x001c1e18, 0x00191c16, 0x00171a14, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00151a14, 0x00151a14, 0x00141914, 0x00151a14, 0x00141914, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00151a14, 0x00151b15, 0x00151c15, 0x00141a14, 0x00141914, 0x00171914, 0x00171914, 0x00181a15, 0x00161b15, 0x00151c14, 0x00151c14, 0x00141b13, 0x00121810, 0x00141912, 0x00141912, 0x00161b14, 0x00161b14, 0x00131815, 0x00131816, 0x00131917, 0x00131917, 0x00141a16, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141813, 0x00111812, 0x000f1912, 0x000f1912, 0x000d1710, 0x000c160f, 0x000c1712, 0x000e1814, 0x000c1713, 0x000c1713, 0x000c1610, 0x000d1510, 0x000c1410, 0x000c140f, 0x000a140f, 0x0008120d, 0x0007110c, 0x0007110c, 0x0007100c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x000a100c, 0x00070f0a, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100a, 0x0008110b, 0x0008120b, 0x00061009, 0x0006100b, 0x0007100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e08, 0x00040e09, 0x00040e09, 0x00040c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060f09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x00141810, 0x0014180b, 0x0014180a, 0x00191c09, 0x00191c08, 0x00202308, 0x0024250b, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0034350c, 0x0038380c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0040400d, 0x0043440f, 0x0043440e, 0x0045470e, 0x0045470e, 0x0047480d, 0x0047480e, 0x00484910, 0x00494a10, 0x00494a10, 0x00494a10, 0x00494a0f, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00525310, 0x00545510, 0x00555611, 0x00565711, 0x00585911, 0x00595a12, 0x005c5c11, 0x005e5f13, 0x00606013, 0x00606013, 0x00666413, 0x00c6a218, 0x00cca519, 0x007a7014, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00636414, 0x00616112, 0x00606013, 0x009a8215, 0x00cca417, 0x00b09015, 0x00515111, 0x00525310, 0x004f5010, 0x00494a0f, 0x0047480f, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00050e07, 0x00060e06, 0x00060e06, 0x00040c06, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x00040d07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00070f09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e07, 0x00060e09, 0x00040e09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060e08, 0x00071007, 0x00071007, 0x00060e08, 0x00060e08, 0x0008110b, 0x0008120b, 0x0008130c, 0x0008130c, 0x0009140c, 0x000a140d, 0x000c130d, 0x000c130d, 0x000c130d, 0x000d140e, 0x000d140e, 0x000f140e, 0x000f140e, 0x0010140f, 0x0010140f, 0x00101510, 0x00101510, 0x00111611, 0x00111611, 0x00111611, 0x00131712, 0x00141813, 0x00141813, 0x00121813, 0x00131914, 0x00131914, 0x00141a14, 0x00141a14, 0x00141b13, 0x00141b13, 0x00121911, 0x00151c14, 0x00161b15, 0x00161b14, 0x00181c14, 0x00181d14, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c17, 0x00181a16, 0x00181b17, 0x00191c16, 0x00191c16, 0x001b1c14, 0x001b1c14, 0x001c1d16, 0x001c1c15, 0x001a1b14, 0x001c1c15, 0x00201d17, 0x00231f15, 0x00241e14, 0x00272018, 0x0028201a, 0x0028211b, 0x00272219, 0x0025231b, 0x0022231c, 0x0010120c, 0x001c211a, 0x00383b34, 0x002c2c24, 0x002d2920, 0x00362e24, 0x002f2417, 0x00372917, 0x0041321a, 0x00412e15, 0x0048341a, 0x00503820, 0x00513822, 0x004b311a, 0x004a2f14, 0x00523414, 0x00593818, 0x0054320f, 0x00623e19, 0x00623c18, 0x0066401a, 0x0067411b, 0x0067411c, 0x0068401c, 0x0068401c, 0x00693d1b, 0x00683d19, 0x00683d17, 0x00663c13, 0x00623810, 0x0061380e, 0x0061380e, 0x005d340c, 0x00562d09, 0x00502706, 0x00552d0f, 0x00542c12, 0x00573013, 0x005b3314, 0x00582f0f, 0x00502608, 0x0054290c, 0x00562a0d, 0x005d3013, 0x005f330f, 0x005f320c, 0x0062350d, 0x0064370f, 0x0065370e, 0x0066380d, 0x0067390c, 0x00683a0d, 0x00693a0c, 0x006a390c, 0x0069380d, 0x0068380f, 0x0068370f, 0x0063340c, 0x00613209, 0x00603209, 0x005f330b, 0x005c2f09, 0x00592e0b, 0x00542b09, 0x005c3112, 0x00552c0e, 0x00502b0e, 0x00402004, 0x00391d03, 0x00371c05, 0x003a1e0a, 0x00371b08, 0x00371b09, 0x00371c0a, 0x00371c0a, 0x00331c09, 0x002e1707, 0x002d1708, 0x002c190a, 0x00271a09, 0x00161000, 0x000c0c00, 0x00090d03, 0x00101008, 0x0018140b, 0x001b1408, 0x0022160c, 0x002b1e14, 0x00291e14, 0x00241c14, 0x00201c14, 0x001d1c14, 0x001b1b12, 0x00181911, 0x00181a11, 0x001b1d14, 0x001b1d17, 0x001c1e18, 0x001c1e18, 0x00191c16, 0x00181c15, 0x00171c17, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161b15, 0x00161b15, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a13, 0x00151a13, 0x00161b14, 0x00161b14, 0x00161c16, 0x00171d18, 0x00171d18, 0x00161c17, 0x00171b16, 0x00181b17, 0x00181b16, 0x00181a15, 0x00181a15, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00171c15, 0x00171c15, 0x00161b14, 0x00161b14, 0x00141b17, 0x00141b17, 0x00151b17, 0x00151b17, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00131914, 0x00121b12, 0x00111b12, 0x00101810, 0x000e1710, 0x00101814, 0x00101814, 0x000f1713, 0x000f1713, 0x000f1713, 0x000d1510, 0x000e1611, 0x000c1410, 0x000b1410, 0x0009130e, 0x0007110c, 0x0007110c, 0x0007100c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00080f0b, 0x0008100c, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040f08, 0x00061009, 0x0007110a, 0x00061009, 0x0006100c, 0x0007110d, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x0020230a, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x003c3e0c, 0x0040400c, 0x0041420e, 0x0043440e, 0x0045470e, 0x0047480e, 0x0047480e, 0x00484910, 0x00484910, 0x00494a0f, 0x00494a0f, 0x004b4c0f, 0x004c4d0f, 0x004b4c0f, 0x004c4d0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00515110, 0x00525310, 0x00545510, 0x00565711, 0x00585810, 0x00585911, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00616112, 0x00666413, 0x00c6a218, 0x00cca519, 0x007a7014, 0x00646514, 0x00646514, 0x00646514, 0x00646414, 0x00626313, 0x00616112, 0x00606013, 0x009a8214, 0x00cca417, 0x00b09015, 0x00515110, 0x00525310, 0x004f5010, 0x004b4c10, 0x0047480f, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e07, 0x00050d07, 0x00040d06, 0x00040d05, 0x00071007, 0x00070f08, 0x00081009, 0x00081009, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050d07, 0x00070f08, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e07, 0x00060e09, 0x00040e09, 0x00080c09, 0x00080c09, 0x00070c08, 0x00050d08, 0x00040d08, 0x00070f0a, 0x00070f0a, 0x00050e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e06, 0x00070f08, 0x00070f08, 0x00081008, 0x00071007, 0x00060e07, 0x00050d07, 0x0009120c, 0x0009120c, 0x000a130c, 0x000b120c, 0x000c130c, 0x000c140c, 0x000c140d, 0x000d140e, 0x000e140e, 0x000f150f, 0x000f150f, 0x0010140f, 0x0010140f, 0x00101510, 0x00101510, 0x00131611, 0x00131611, 0x00141813, 0x00141712, 0x00141813, 0x00141813, 0x00141813, 0x00151814, 0x00151814, 0x00161914, 0x00161914, 0x00171914, 0x00171a14, 0x00171a14, 0x00181b14, 0x00181b14, 0x00181c15, 0x00181c16, 0x001a1d15, 0x001a1e14, 0x001a1d15, 0x001c1d18, 0x001c1d18, 0x001c1d18, 0x001c1d18, 0x001b1c18, 0x001b1c16, 0x001c1d17, 0x001c1d16, 0x001d1c15, 0x001c1c15, 0x001c1c15, 0x001e1d16, 0x001c1d17, 0x001d1d17, 0x00201d16, 0x00231e14, 0x00241d14, 0x00272017, 0x002a221c, 0x0028201a, 0x00241f15, 0x001c1a11, 0x00151610, 0x0010140e, 0x00242621, 0x003c3d38, 0x0036352e, 0x0027231b, 0x00282218, 0x0030261a, 0x003b3020, 0x00423420, 0x0044341b, 0x00432f16, 0x0047331a, 0x004f3820, 0x0048321a, 0x00452d13, 0x004f3014, 0x00543314, 0x00583616, 0x005c3815, 0x005f3915, 0x00633d18, 0x0065401b, 0x0066401c, 0x0067401c, 0x0068401c, 0x00693d1c, 0x00683c18, 0x00663b15, 0x00663c13, 0x00643a11, 0x00643a10, 0x0062380e, 0x005c340c, 0x0058300c, 0x00562e0a, 0x00572f0f, 0x00582e10, 0x005c3213, 0x005c3110, 0x005c300d, 0x005c2f0e, 0x005d3010, 0x005a2c0c, 0x00603210, 0x0060340c, 0x0061340d, 0x0063360f, 0x00643710, 0x0064380f, 0x0065380d, 0x00653a0c, 0x00663a0d, 0x00673b0c, 0x0067380c, 0x0066380e, 0x00673810, 0x0064370e, 0x0060340a, 0x005f3309, 0x005f340a, 0x005f340c, 0x005e320c, 0x005a2f0c, 0x00572b0b, 0x005d3213, 0x00562d0f, 0x004f290c, 0x00432207, 0x003d2107, 0x00351904, 0x00371b07, 0x003a1e0a, 0x00371c0a, 0x00351c09, 0x00341c0a, 0x002c1807, 0x002a1707, 0x002c1809, 0x002c190b, 0x0025180b, 0x00170e02, 0x000e0b00, 0x000c0f04, 0x000f0f04, 0x0018150c, 0x001b140a, 0x001f140b, 0x00251a10, 0x00271d14, 0x00272018, 0x00221d14, 0x001f1b14, 0x001d1b13, 0x001d1c15, 0x001b1c13, 0x00191c14, 0x00191c16, 0x00191c16, 0x00191d16, 0x00181d16, 0x00171c16, 0x00171c17, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00171c17, 0x00171c17, 0x00171c14, 0x00171c15, 0x00171c15, 0x00171c15, 0x00161c16, 0x00161c16, 0x00171d16, 0x00181f18, 0x001b1f18, 0x00191c17, 0x00181c15, 0x00181c16, 0x00181c16, 0x00181c14, 0x00171b13, 0x00171b13, 0x00171b13, 0x00161c13, 0x00161c13, 0x00171c14, 0x00171c14, 0x00161c16, 0x00151b15, 0x00151c16, 0x00151c16, 0x00151c15, 0x00141b15, 0x00141a14, 0x00141b15, 0x00161c17, 0x00151c16, 0x00151c16, 0x00151c16, 0x00151c16, 0x00161b15, 0x00161b15, 0x00151a14, 0x00141914, 0x00141b13, 0x00141b13, 0x00131b13, 0x00111912, 0x00121815, 0x00121814, 0x00121814, 0x00101814, 0x00101814, 0x00101813, 0x000e1611, 0x000e1611, 0x000c1510, 0x000a140f, 0x0008120d, 0x0008120c, 0x0007100b, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00070d09, 0x0008100c, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040e08, 0x00040f08, 0x00051008, 0x00061009, 0x0006100c, 0x0007110d, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x0038380c, 0x00393b0d, 0x003c3e0c, 0x003e400c, 0x0041420e, 0x0044450e, 0x0045470e, 0x0047480e, 0x0048490f, 0x00494a10, 0x004b4c10, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004d4e0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004d4e10, 0x004f5010, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00545511, 0x00555611, 0x00565711, 0x00585910, 0x00595a12, 0x005c5c12, 0x005c5d11, 0x005d5e12, 0x00606013, 0x00606013, 0x00666413, 0x00c6a218, 0x00cca519, 0x00796f14, 0x00646514, 0x00646514, 0x00646414, 0x00636414, 0x00626313, 0x00606013, 0x005e5f13, 0x009a8214, 0x00cca417, 0x00b09015, 0x00515110, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e06, 0x00050e06, 0x00060e08, 0x00060e08, 0x00050e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00070f08, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e07, 0x00060e09, 0x00040e09, 0x00080c09, 0x00080c09, 0x00070c08, 0x00040c08, 0x00050d08, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e06, 0x00070f08, 0x00081009, 0x00081108, 0x00081008, 0x00081008, 0x00081009, 0x000b130c, 0x000c140d, 0x000d140c, 0x000e140c, 0x000f140d, 0x000f140d, 0x000f140e, 0x000e140f, 0x000f150f, 0x00101610, 0x00101610, 0x00101510, 0x00101510, 0x00111611, 0x00111611, 0x00151814, 0x00151814, 0x00171914, 0x00171914, 0x00171814, 0x00171814, 0x00171814, 0x00171814, 0x00181915, 0x00181915, 0x00181914, 0x00181814, 0x00181914, 0x00181a14, 0x00181a14, 0x00191b15, 0x00191b15, 0x001a1c15, 0x001c1e15, 0x001b1d14, 0x001c1d14, 0x001d1d17, 0x001d1d17, 0x001d1d17, 0x001d1d17, 0x001c1c18, 0x001c1c17, 0x001d1d17, 0x001d1d16, 0x001f1e16, 0x001e1c14, 0x001e1c14, 0x001e1c15, 0x001e1d17, 0x001f1c16, 0x00201c15, 0x00201c12, 0x00211b13, 0x00231c14, 0x00241c16, 0x00231c15, 0x001f1910, 0x0019170e, 0x0014130c, 0x0012140e, 0x0020241e, 0x00373831, 0x00383730, 0x002b271f, 0x001f1a10, 0x002c261c, 0x00393023, 0x003c311f, 0x0041341d, 0x0045341c, 0x00453218, 0x0047331a, 0x0049351c, 0x00452c14, 0x00482910, 0x00543118, 0x005c381c, 0x005c3716, 0x00603917, 0x00603b18, 0x00613c18, 0x00643d1b, 0x00643e1a, 0x00653d1b, 0x00673d1a, 0x006a3c19, 0x00663b15, 0x00663c13, 0x00653b12, 0x00653b10, 0x00633a10, 0x0060370c, 0x005c340d, 0x005e3412, 0x005d3410, 0x005e340e, 0x0063370f, 0x0067390f, 0x00673a0f, 0x006a3b12, 0x006a3b12, 0x0064350c, 0x0067380f, 0x0064350b, 0x0065380e, 0x0063350e, 0x00643711, 0x0063360f, 0x0062380c, 0x0062380b, 0x0062380b, 0x0062370a, 0x0061370c, 0x0062370e, 0x0061360d, 0x0060350c, 0x005d3409, 0x005c3208, 0x005f340a, 0x005e340b, 0x005b310b, 0x005b300d, 0x005c3110, 0x00582e0f, 0x00552c0d, 0x004c280c, 0x00442408, 0x003e2208, 0x00351904, 0x00361a06, 0x003a1e0b, 0x00381c0a, 0x00331b09, 0x00301b08, 0x00281704, 0x00281808, 0x002a1809, 0x0028170b, 0x00221509, 0x00160d04, 0x000e0a00, 0x000c0e02, 0x00121207, 0x0019150c, 0x001b150b, 0x0021170c, 0x00251c12, 0x00241d13, 0x00241d15, 0x00231c14, 0x001f1a13, 0x001d1b13, 0x001c1c14, 0x001a1b14, 0x00181c14, 0x00191c15, 0x00191c16, 0x00191c16, 0x00181d16, 0x00181c16, 0x00181c18, 0x00181c18, 0x00181c18, 0x00181c18, 0x00171c16, 0x00171c16, 0x00161b14, 0x00161b14, 0x00171c17, 0x00171c17, 0x00171c15, 0x00171c14, 0x00171c14, 0x00171c14, 0x00161c14, 0x00161d14, 0x00171d14, 0x00171e15, 0x00181c15, 0x00191c15, 0x00191c15, 0x00191c15, 0x00191c15, 0x00191d14, 0x00191c13, 0x00191c13, 0x00191c13, 0x00181d13, 0x00181d13, 0x00181d13, 0x00181d14, 0x00181f16, 0x00161d14, 0x00151c13, 0x00151c13, 0x00151c15, 0x00151c15, 0x00141b14, 0x00151c16, 0x00161c17, 0x00161c17, 0x00171d18, 0x00181e18, 0x00181d18, 0x00181c18, 0x00181c18, 0x00171c16, 0x00161b15, 0x00141c14, 0x00141c14, 0x00141b13, 0x00141b13, 0x00151c15, 0x00151c16, 0x00151b16, 0x00131914, 0x00101814, 0x00101814, 0x00101814, 0x000e1611, 0x000c1610, 0x000c1610, 0x000b1510, 0x000a140f, 0x0008110c, 0x0009110c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00050d09, 0x00080f0b, 0x0008100b, 0x0008100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00061009, 0x0006100c, 0x0007110d, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0005100a, 0x0005100a, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00050d09, 0x00060d09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x00191c08, 0x00202308, 0x0020230a, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0045470e, 0x0048490f, 0x00494a10, 0x004b4c10, 0x004b4c0f, 0x004d4e0f, 0x004d4e10, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x004f5010, 0x00505010, 0x00515110, 0x00515110, 0x00505010, 0x00525310, 0x00515110, 0x00525310, 0x00535410, 0x00545510, 0x00555611, 0x00565711, 0x00585810, 0x00595a11, 0x005b5b12, 0x005c5c11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00616112, 0x00666413, 0x00c6a218, 0x00cca519, 0x00796f14, 0x00646414, 0x00646414, 0x00646414, 0x00636414, 0x00616112, 0x00616112, 0x005e5f13, 0x009a8214, 0x00cca417, 0x00b09015, 0x00515110, 0x00515110, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00050e07, 0x00060e07, 0x00050e08, 0x00050e08, 0x00040d07, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x0008100b, 0x00070f09, 0x00070f09, 0x00040d08, 0x00050d08, 0x00050e08, 0x0008100b, 0x00060e09, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e07, 0x00060e09, 0x00050e09, 0x00080d09, 0x00080d09, 0x00070d09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070e0b, 0x00070f09, 0x00070f09, 0x00070f08, 0x0008100a, 0x0008100a, 0x0009120b, 0x000a130c, 0x000b130b, 0x000c140c, 0x000c140d, 0x000c140d, 0x000f140e, 0x0010140e, 0x0011140f, 0x0013140f, 0x00111510, 0x00111510, 0x00111510, 0x00121510, 0x00121510, 0x00141510, 0x00141610, 0x00141611, 0x00141611, 0x00181914, 0x00181914, 0x00191b15, 0x00181a14, 0x00181814, 0x00181814, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181914, 0x00181914, 0x00181a14, 0x00181a14, 0x00181a14, 0x00191a14, 0x00191b14, 0x001b1c16, 0x001c1e18, 0x001c1c14, 0x001c1c14, 0x001c1c15, 0x001d1e16, 0x001e1d15, 0x001f1e15, 0x00201d17, 0x00201d17, 0x00201e16, 0x00201e15, 0x00201e14, 0x00201e14, 0x00201e14, 0x00201e14, 0x001f1e16, 0x00201d15, 0x00201c14, 0x00201b13, 0x00201b13, 0x00211b14, 0x00221c14, 0x00221c15, 0x001b180f, 0x0018150d, 0x0014140c, 0x0012140c, 0x001c1d17, 0x0034342c, 0x0036342c, 0x002c2920, 0x00201c12, 0x00241e16, 0x002e271c, 0x00352c1b, 0x003c301a, 0x00483820, 0x0048361c, 0x00443015, 0x00473018, 0x0049301b, 0x004a2c17, 0x004c2c16, 0x004c2a13, 0x00502c10, 0x00603a1b, 0x005f3918, 0x005f3815, 0x00603a16, 0x00623b17, 0x00633b17, 0x00643b17, 0x00673c18, 0x00643c14, 0x00653b12, 0x00663b11, 0x00663a10, 0x00663a10, 0x00643a10, 0x0063380f, 0x00643910, 0x00673910, 0x00693b10, 0x006f4013, 0x00734012, 0x00724010, 0x00734111, 0x00754313, 0x00723f10, 0x00713d0e, 0x006d390b, 0x006b380c, 0x0068350c, 0x0068370f, 0x0064370c, 0x0063360a, 0x00623508, 0x00613608, 0x005f3408, 0x0060340b, 0x00623710, 0x0060360e, 0x005e340c, 0x005d330a, 0x005d330a, 0x0061360d, 0x005c3109, 0x00572e07, 0x00582f09, 0x005c3311, 0x00542b0b, 0x00522c0c, 0x00492608, 0x00412106, 0x003c2007, 0x00381904, 0x00351804, 0x00381c0a, 0x00341c0b, 0x002f1b08, 0x00281704, 0x00241504, 0x00241504, 0x00271709, 0x0026170b, 0x0020140a, 0x00150c03, 0x000e0901, 0x000d0c04, 0x0014130c, 0x0018140f, 0x0019140e, 0x00211a0f, 0x00241d13, 0x00241d13, 0x00211c13, 0x00201c14, 0x00201b14, 0x001e1b14, 0x001c1b15, 0x001b1c15, 0x00191c15, 0x00191c16, 0x00191c16, 0x00191c17, 0x00181c17, 0x00191d18, 0x00181c18, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161c16, 0x00161c16, 0x00151c14, 0x00151b14, 0x00181e16, 0x00181e16, 0x00181e15, 0x00181e15, 0x00171d14, 0x00161d14, 0x00161d14, 0x00161d14, 0x00171e14, 0x00161d14, 0x00171c13, 0x00181c14, 0x00191c14, 0x00181c14, 0x00191c14, 0x00191c14, 0x00191c14, 0x00191c14, 0x00191c14, 0x00181c14, 0x00181c14, 0x00191c14, 0x00181d14, 0x00181f15, 0x00182016, 0x00171d14, 0x00171d14, 0x00181d16, 0x00181c16, 0x00181c15, 0x00181c16, 0x00181d17, 0x00181d16, 0x00181d17, 0x00181e18, 0x00181d18, 0x00191d18, 0x00191e18, 0x00191d18, 0x00171c15, 0x00181c16, 0x00181d17, 0x00181c17, 0x00171c16, 0x00161c17, 0x00151d17, 0x00141c16, 0x00131a14, 0x00101813, 0x00101813, 0x00101813, 0x00101813, 0x000e1711, 0x000d1610, 0x000d1710, 0x000d1610, 0x000a130d, 0x000a130d, 0x000a120d, 0x0009110c, 0x0009110c, 0x0009110c, 0x0008100b, 0x0008100b, 0x00060f0a, 0x00090f0b, 0x00080f0b, 0x00070f0a, 0x0005100a, 0x00060f0a, 0x00060f0a, 0x00060f0a, 0x00060f0a, 0x00050e08, 0x00050e08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f0b, 0x00040e0a, 0x00040e0a, 0x00040f0a, 0x0005100a, 0x00060f0a, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x0006100a, 0x00050e09, 0x00030c08, 0x00040e09, 0x0008100b, 0x0008100b, 0x0008100b, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x00141810, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x00393b0c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x0048490f, 0x004b4c10, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00515110, 0x00515110, 0x00525310, 0x00525310, 0x00525310, 0x00525310, 0x00535410, 0x00535410, 0x00535410, 0x00545510, 0x00555611, 0x00555611, 0x00565710, 0x00585910, 0x00585911, 0x00595a12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x00606013, 0x00606013, 0x00616112, 0x00666413, 0x00c6a218, 0x00cca519, 0x00796f14, 0x00646414, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x009a8114, 0x00cca417, 0x00b09015, 0x004f5010, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0c, 0x00393b0c, 0x0034350c, 0x0030310c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00070f0a, 0x0008100c, 0x00050d09, 0x00040c08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00070f0a, 0x0008100b, 0x00081009, 0x0008110b, 0x0009120c, 0x000a130c, 0x000c140d, 0x000c140c, 0x000c150c, 0x000e150d, 0x000e150d, 0x0011140f, 0x0013130f, 0x00131410, 0x00141410, 0x00141511, 0x00141712, 0x00141712, 0x00141712, 0x00141712, 0x00171812, 0x00171812, 0x00171812, 0x00171812, 0x00181813, 0x00181a14, 0x001a1b15, 0x00181914, 0x00181813, 0x00181813, 0x00181a14, 0x00181a14, 0x00191a14, 0x00191a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00191c18, 0x001c1d18, 0x001c1c17, 0x001c1c14, 0x001c1c15, 0x00201e17, 0x00201e15, 0x00221e15, 0x00231e18, 0x00231e17, 0x00231e16, 0x00231e14, 0x00201e14, 0x00201e14, 0x00201e14, 0x00201e14, 0x00201d14, 0x00201d14, 0x00201d14, 0x00211c14, 0x00221c14, 0x00211c14, 0x00211c14, 0x00201c14, 0x0018160e, 0x0016140c, 0x0014140b, 0x0012130a, 0x00181810, 0x002a2a22, 0x00302e25, 0x0029281f, 0x0026231a, 0x00201b13, 0x00221b10, 0x00342c1d, 0x003a2f1d, 0x00453722, 0x004a3821, 0x00453117, 0x0047301a, 0x0049301c, 0x004c301d, 0x004d311c, 0x0053341d, 0x0056351a, 0x005e3b1c, 0x005e3818, 0x005f3715, 0x00623815, 0x00633b16, 0x00643c18, 0x00653c18, 0x00643c17, 0x00633b14, 0x00643911, 0x00673a10, 0x00673a10, 0x00683b10, 0x006b3e14, 0x006c3e11, 0x00704010, 0x00724312, 0x00774416, 0x007c4a19, 0x00814c18, 0x0078440e, 0x007d4813, 0x00804914, 0x007e4712, 0x007f4712, 0x007b4310, 0x0078400f, 0x00733c0e, 0x006f3a0d, 0x006c380a, 0x00683808, 0x00663608, 0x00643508, 0x0060340a, 0x0060330c, 0x0061340e, 0x0060350f, 0x0061360f, 0x0062370f, 0x0062370f, 0x00643810, 0x005a3007, 0x00542c05, 0x00562e08, 0x0059300e, 0x00522a0a, 0x004d280a, 0x00442005, 0x003d1d04, 0x003e2008, 0x003b1c08, 0x00361806, 0x00361c0c, 0x002d1809, 0x00271607, 0x00221404, 0x00231404, 0x00231404, 0x00241508, 0x00241508, 0x001e1409, 0x00150c04, 0x00130c06, 0x0015100c, 0x00181310, 0x00181310, 0x0018140f, 0x001d180f, 0x001f1b10, 0x001f1c11, 0x001e1b12, 0x001e1a13, 0x001d1b14, 0x001c1b14, 0x001c1b16, 0x001b1c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c17, 0x00181c18, 0x00191d18, 0x00181d18, 0x00161b15, 0x00161c17, 0x00161c17, 0x00161c15, 0x00161c15, 0x00161c15, 0x00171d16, 0x00171e14, 0x00171e14, 0x00181f15, 0x00171e14, 0x00171e14, 0x00161d14, 0x00161d14, 0x00161d14, 0x00161d14, 0x00161d14, 0x00161c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00171e15, 0x00171e15, 0x00181e15, 0x00181e15, 0x001c1e18, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d15, 0x00181d14, 0x001a1f16, 0x001a1f15, 0x00191e16, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00161d18, 0x00151e18, 0x00141d17, 0x00131b14, 0x00121a14, 0x00111913, 0x00111913, 0x00111913, 0x00101811, 0x000e170e, 0x000e1710, 0x000e1710, 0x000c140d, 0x000c140d, 0x000c140e, 0x000c140f, 0x000c140f, 0x000a120e, 0x0008100b, 0x0008100b, 0x0008100b, 0x00090f0b, 0x00080f0b, 0x00070f0a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x0005100a, 0x00070f0a, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060f0a, 0x00050f0a, 0x0005100a, 0x00040e09, 0x00040d08, 0x0007100b, 0x00070f0a, 0x00070f0a, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00515110, 0x00515110, 0x00525310, 0x00535410, 0x00535410, 0x00545510, 0x00545511, 0x00545510, 0x00545510, 0x00545510, 0x00545510, 0x00555611, 0x00555611, 0x00555611, 0x00565711, 0x00585810, 0x00585810, 0x00585911, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00616112, 0x00626312, 0x00666414, 0x00c6a219, 0x00cca519, 0x00796f14, 0x00646414, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005d5e12, 0x009a8114, 0x00cca417, 0x00b09014, 0x00505010, 0x00515110, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040c06, 0x00050e08, 0x00050d07, 0x00050e08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00050d08, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e0a, 0x00070f0a, 0x00050d09, 0x00050d09, 0x00040c08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00070e0c, 0x0008100b, 0x0008100c, 0x0008100a, 0x0009120c, 0x000a130c, 0x000c130d, 0x000c140d, 0x000d140c, 0x000e150d, 0x0010150d, 0x0010150e, 0x00121510, 0x00131410, 0x00141511, 0x00151512, 0x00151713, 0x00161814, 0x00161814, 0x00161814, 0x00171814, 0x00171812, 0x00171812, 0x00181a14, 0x00181a14, 0x00181813, 0x00181a14, 0x00191b14, 0x00181a14, 0x00181813, 0x00181813, 0x00181914, 0x00181914, 0x00181a14, 0x00181a14, 0x00181914, 0x00181914, 0x00191a14, 0x001a1b15, 0x00191a14, 0x00181914, 0x00181a14, 0x00191c17, 0x001b1c16, 0x001c1b16, 0x001c1b14, 0x00201c17, 0x00241e18, 0x00241d16, 0x00241e14, 0x00241d16, 0x00241d16, 0x00241e14, 0x00241e13, 0x00221e14, 0x00201f14, 0x00201e14, 0x00201e14, 0x00211e14, 0x00211e14, 0x00201e14, 0x00221d14, 0x00231c14, 0x00221c14, 0x00211c14, 0x001e1a13, 0x0017150c, 0x0017140c, 0x0014140a, 0x00141209, 0x0015150b, 0x001f1e15, 0x0029271f, 0x0026241c, 0x00201e15, 0x00201d14, 0x001a180e, 0x00231c11, 0x0032281c, 0x003a2d1d, 0x0041321c, 0x00402e16, 0x0046301b, 0x004b3321, 0x004d3423, 0x004f3420, 0x0051341d, 0x0055351c, 0x005c3a1c, 0x005d3818, 0x005e3614, 0x00603614, 0x00643c16, 0x00663f19, 0x00643d18, 0x00643c17, 0x00623b14, 0x00643911, 0x00663910, 0x00683a10, 0x006b3c11, 0x00714114, 0x00754415, 0x00794715, 0x007b4814, 0x007d4914, 0x00814d17, 0x00824b11, 0x007c450b, 0x007e450c, 0x007f460c, 0x0081470e, 0x00854a11, 0x00834811, 0x007f4610, 0x007c4410, 0x00753f0d, 0x00703c0a, 0x006d3b08, 0x006c380a, 0x0069370b, 0x0064340c, 0x0063340c, 0x0064370f, 0x0062350d, 0x005f330b, 0x0060340c, 0x0060340c, 0x0062350e, 0x005b300a, 0x00562e09, 0x00522a07, 0x00542c0c, 0x0051280b, 0x004e280c, 0x00452209, 0x0041200b, 0x003e200b, 0x003c1e0c, 0x00381c0c, 0x00341d0d, 0x00281608, 0x00221408, 0x00201306, 0x00211407, 0x00211407, 0x00221407, 0x00201407, 0x001d1208, 0x001a1008, 0x0018110a, 0x0017130c, 0x0018130e, 0x0018130f, 0x0019140f, 0x001b170f, 0x001d1a11, 0x001c1912, 0x001c1911, 0x001a1811, 0x001b1812, 0x001b1a15, 0x001b1b16, 0x001b1c16, 0x001a1c16, 0x00191c16, 0x00181c15, 0x00181c16, 0x00181c18, 0x00181c18, 0x00181c18, 0x00161c16, 0x00161c17, 0x00161c17, 0x00161c16, 0x00171e17, 0x00171d17, 0x00181e17, 0x00151c14, 0x00151c14, 0x00161c16, 0x00161c16, 0x00151c14, 0x00151c14, 0x00151c15, 0x00151c15, 0x00151c16, 0x00151c15, 0x00161c15, 0x00171c15, 0x00171c15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00171c15, 0x00171c15, 0x00161c16, 0x00171d17, 0x00171d17, 0x00171d16, 0x001b1d17, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d15, 0x00181d14, 0x001a1f16, 0x001a1f16, 0x001a1f17, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00171e18, 0x00161e18, 0x00151d17, 0x00141c15, 0x00141c15, 0x00131b14, 0x00141c15, 0x00121a14, 0x00111a12, 0x00101810, 0x000f1810, 0x000f1811, 0x000c140e, 0x000c140e, 0x000c140f, 0x000c1410, 0x000c1410, 0x000b130f, 0x0008100c, 0x0008100c, 0x0008100c, 0x0009100c, 0x0008100b, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00050d07, 0x00040d07, 0x00050d08, 0x00050d08, 0x00050d09, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x00070f0a, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070f0a, 0x0005100a, 0x00040f09, 0x0006100b, 0x0006100b, 0x00050f0a, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a0f, 0x004c4d0f, 0x004f5010, 0x00505010, 0x00525310, 0x00535410, 0x00545510, 0x00555611, 0x00555611, 0x00565711, 0x00565710, 0x00565710, 0x00585810, 0x00585810, 0x00585810, 0x00585810, 0x00565710, 0x00585810, 0x00585911, 0x00585910, 0x00595a11, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00616112, 0x00626312, 0x00626313, 0x00666414, 0x00c6a219, 0x00cca519, 0x00796f14, 0x00646414, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606012, 0x005d5e12, 0x009a8114, 0x00cca417, 0x00b09014, 0x00505010, 0x00515110, 0x004d4e0f, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040c06, 0x00040d07, 0x00040d07, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00050e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00070f0a, 0x00070f0b, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100c, 0x0009110d, 0x000b130e, 0x000b130c, 0x000a130c, 0x000c140e, 0x000f150f, 0x000f150f, 0x0010160f, 0x00111710, 0x00131610, 0x00141710, 0x00151813, 0x00151813, 0x00171814, 0x00171814, 0x00171814, 0x00181a15, 0x00181a15, 0x00181a15, 0x00181a15, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181813, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181913, 0x00181914, 0x00181913, 0x00181813, 0x00181914, 0x00181b16, 0x001a1b15, 0x001b1a15, 0x001b1a14, 0x00201c16, 0x00231e18, 0x00241c16, 0x00241d14, 0x00241d16, 0x00241d14, 0x00241d13, 0x00241d12, 0x00241f13, 0x00242013, 0x00231f13, 0x00231f12, 0x00231f12, 0x00231f12, 0x00221e12, 0x00221d14, 0x00231c14, 0x00231c14, 0x00231c14, 0x001d1912, 0x001a1810, 0x0018150d, 0x0015130a, 0x00141208, 0x00131308, 0x0017150d, 0x001f1c14, 0x00211f17, 0x001d1c13, 0x001c1c13, 0x001c1b13, 0x0017130c, 0x00241c14, 0x0032281b, 0x003b2f19, 0x003c2e16, 0x0044311c, 0x00452f1e, 0x0048321d, 0x004a321c, 0x0051371f, 0x0055371d, 0x005d3a1e, 0x005e3818, 0x005e3614, 0x005e3411, 0x00633914, 0x00643d18, 0x00663e18, 0x00643c17, 0x00653c18, 0x00663c16, 0x00693d14, 0x006d4014, 0x00714014, 0x00784518, 0x007d4918, 0x007c4714, 0x007b4511, 0x0078420d, 0x007c4510, 0x00854d14, 0x00844910, 0x007c420a, 0x007c4109, 0x007e420a, 0x0081450c, 0x00854a10, 0x0081470e, 0x007c440c, 0x007c440e, 0x0078420c, 0x00733f09, 0x00703c0c, 0x006e3b0c, 0x006a380e, 0x0066360e, 0x0064360d, 0x0063340c, 0x0060340b, 0x0060340c, 0x0060340b, 0x005d3009, 0x005c310d, 0x005c3311, 0x00582f0f, 0x0052290d, 0x004c2409, 0x00462008, 0x0044200a, 0x0041200d, 0x003a1c0a, 0x003a1c0d, 0x00351c0e, 0x002a170a, 0x00241408, 0x001e1307, 0x001c1106, 0x001d1308, 0x001f1408, 0x00201408, 0x001f1408, 0x001e1409, 0x001c1209, 0x0019140b, 0x0017140b, 0x0016120a, 0x0016120a, 0x0018140d, 0x0019180f, 0x001c1a13, 0x001c1a14, 0x001c1a14, 0x001a1913, 0x00191913, 0x001a1a14, 0x001a1b15, 0x001b1c16, 0x001a1c16, 0x00181c15, 0x00181a14, 0x00181b15, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161c16, 0x00151c15, 0x00161c17, 0x00161c17, 0x00161c16, 0x00161c17, 0x00151c16, 0x00141b15, 0x00141b15, 0x00151c17, 0x00151c16, 0x00141b15, 0x00141a15, 0x00141c15, 0x00141c15, 0x00141c15, 0x00131b14, 0x00131a14, 0x00141a14, 0x00151a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00151b15, 0x00151b15, 0x00161c16, 0x00161c17, 0x00161c16, 0x00151b15, 0x00181b14, 0x00181b14, 0x00181b14, 0x00181b14, 0x00181c15, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d15, 0x00181d14, 0x001a1f16, 0x001b2017, 0x001a1f18, 0x00191d18, 0x00191d18, 0x001a1f19, 0x00191e18, 0x00181e18, 0x00171f18, 0x00171f18, 0x00171f18, 0x00161e18, 0x00161e18, 0x00161e18, 0x00131b14, 0x00121a12, 0x00121b12, 0x00111a12, 0x000f1811, 0x000e1710, 0x000e1710, 0x000e1610, 0x000d1510, 0x000d1510, 0x000c1410, 0x000b130f, 0x000a120e, 0x000a120e, 0x0009120e, 0x0008120d, 0x0005110b, 0x0005110b, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f09, 0x00070f08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060e09, 0x00070f0a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x00070f0a, 0x00080e0a, 0x00070d09, 0x00070d09, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0007110c, 0x00040c08, 0x00050d08, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a0f, 0x004c4d0f, 0x004b4c10, 0x004d4e10, 0x00505010, 0x00525311, 0x00535411, 0x00545510, 0x00555610, 0x00565711, 0x00585812, 0x00585811, 0x00585912, 0x00585912, 0x00585911, 0x00585911, 0x00585912, 0x00595a11, 0x00595a11, 0x00595a12, 0x00595a12, 0x005c5c12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005d5d11, 0x00606012, 0x00606013, 0x00616113, 0x00626213, 0x00636312, 0x00646412, 0x00646414, 0x00847714, 0x00c8a318, 0x00cca519, 0x00797014, 0x00646414, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606012, 0x005d5e12, 0x009a8114, 0x00cca417, 0x00b09014, 0x00505010, 0x00515110, 0x004c4d10, 0x00494a10, 0x0045470e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0020230a, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00070f08, 0x00040d07, 0x00040c07, 0x00040d08, 0x00040d08, 0x00070f0a, 0x00060e0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x0008100b, 0x0008100c, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060f08, 0x00060f08, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050e08, 0x00060d08, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0009110c, 0x000c140e, 0x000c140f, 0x000c140e, 0x000c140e, 0x000d150f, 0x00101711, 0x00101711, 0x00131811, 0x00141811, 0x00141811, 0x00151812, 0x00181814, 0x00181814, 0x00181914, 0x00181915, 0x00181a15, 0x00181a15, 0x00181a15, 0x00181a15, 0x00181a14, 0x00181a13, 0x00181a13, 0x00181a13, 0x00181a13, 0x00181913, 0x00181a14, 0x00181a14, 0x00181a13, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00171813, 0x00171812, 0x00171813, 0x00181813, 0x00181813, 0x00181a14, 0x001a1b15, 0x001b1a15, 0x001a1a15, 0x001c1c15, 0x001f1d16, 0x00201c14, 0x00211c13, 0x00241e14, 0x00241e13, 0x00241e13, 0x00241e11, 0x00241f12, 0x00261f12, 0x00251e11, 0x00251d11, 0x00241e11, 0x00241e11, 0x00241e11, 0x00241e11, 0x00241d13, 0x00231c15, 0x00231c14, 0x001f1a13, 0x001c1810, 0x0018160d, 0x0015140a, 0x00131308, 0x00141408, 0x0014130a, 0x0017150d, 0x001a1910, 0x001b1b12, 0x001b1b12, 0x001b1a13, 0x0015140d, 0x0016120c, 0x0020190f, 0x00352c1c, 0x00372b18, 0x0040311e, 0x0040301c, 0x0043301c, 0x0046321b, 0x0050381f, 0x0051361b, 0x00583418, 0x005b3616, 0x005d3612, 0x00603611, 0x00633914, 0x00653d18, 0x00673d18, 0x00673c18, 0x00683d19, 0x00683d17, 0x006f4319, 0x00714419, 0x00774418, 0x007c4718, 0x00804919, 0x007c4614, 0x007a4411, 0x00753d0b, 0x00743c09, 0x007d440f, 0x007c410c, 0x007e420d, 0x007e420d, 0x007c400c, 0x007d430c, 0x00834b10, 0x007f480f, 0x007c450e, 0x007a440d, 0x0078440d, 0x00743f08, 0x00703c08, 0x006e3a0a, 0x006c380e, 0x0069370f, 0x0066360e, 0x0067370f, 0x0063340b, 0x0061340b, 0x0060340b, 0x005c300a, 0x005c2f0c, 0x00582f0d, 0x00542c0e, 0x0050270b, 0x00482006, 0x00411c04, 0x00411f09, 0x003b1c0a, 0x00341908, 0x00361c10, 0x002c150c, 0x00201005, 0x001e1107, 0x001c1108, 0x001a1007, 0x001b1208, 0x001c1308, 0x001e1309, 0x001f1409, 0x001e1409, 0x001b1309, 0x0019140b, 0x0018140b, 0x0017140a, 0x0017130b, 0x0018160e, 0x0019170f, 0x001c1913, 0x001b1a15, 0x001a1b15, 0x001a1914, 0x00181a14, 0x00181a14, 0x00181c14, 0x00181c16, 0x00191c16, 0x001a1c16, 0x00191a14, 0x00181b15, 0x00171c17, 0x00161c17, 0x00151c16, 0x00141c15, 0x00131b14, 0x00141a14, 0x00151c15, 0x00151a14, 0x00151b16, 0x00141a16, 0x00141a15, 0x00141915, 0x00131915, 0x00131915, 0x00141a16, 0x00141a16, 0x00141c15, 0x00141c15, 0x00141c15, 0x00121a14, 0x00121913, 0x00131813, 0x00131813, 0x00121813, 0x00131813, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00141814, 0x00141814, 0x00141814, 0x00141914, 0x00141a14, 0x00141a14, 0x00141a14, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a14, 0x00161b14, 0x00171c15, 0x00181d16, 0x00181c16, 0x00181d16, 0x001a1e18, 0x00191d17, 0x00181d16, 0x00181d18, 0x00191d18, 0x001b201a, 0x001b201a, 0x00181e18, 0x00181e18, 0x00181e18, 0x00181e18, 0x00171f18, 0x00171f18, 0x00161e18, 0x00141c16, 0x00131b14, 0x00141c15, 0x00141b15, 0x00101812, 0x00101812, 0x00111812, 0x00101610, 0x000f1410, 0x000f1410, 0x000e1510, 0x000d1410, 0x000b120e, 0x000a120e, 0x0009130e, 0x0009130e, 0x0006100b, 0x0005110b, 0x0006100a, 0x00070f0b, 0x00070f0b, 0x00070f0b, 0x0008100b, 0x00081009, 0x00081009, 0x00070f09, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x00060f0a, 0x00070e0a, 0x00070d09, 0x00070e09, 0x0007100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040c08, 0x00060e09, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x003e400d, 0x0043440e, 0x0045470e, 0x00494a0f, 0x004c4d0f, 0x00685e10, 0x00aa8b14, 0x00af8e14, 0x00af8f14, 0x00b09014, 0x00b09014, 0x00b09014, 0x00b09115, 0x00b09115, 0x00b09115, 0x00b09115, 0x00b19315, 0x00b19215, 0x00b19215, 0x00b19215, 0x00b19216, 0x00b29316, 0x00b29316, 0x00b29316, 0x00b29316, 0x00b39316, 0x00b39317, 0x00b39317, 0x00b39417, 0x00b49417, 0x00b49417, 0x00b49417, 0x00b49417, 0x00b49517, 0x00b49518, 0x00b49518, 0x00b59518, 0x00c4a119, 0x00cca519, 0x00c4a019, 0x00746c14, 0x00646514, 0x00646414, 0x00636414, 0x00636413, 0x00616112, 0x00606012, 0x005d5e12, 0x009b8314, 0x00cca417, 0x00b09014, 0x00505010, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450d, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x0008110a, 0x0008110a, 0x000a130c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000e1610, 0x000e1610, 0x000f1811, 0x00101812, 0x00141813, 0x00141811, 0x00141912, 0x00141910, 0x00181813, 0x00181813, 0x00181914, 0x00181a14, 0x00191b14, 0x001a1b14, 0x00191b14, 0x00181a12, 0x00181a12, 0x00181910, 0x0017180f, 0x00181910, 0x00181910, 0x00181b12, 0x00181b12, 0x00181a12, 0x00161811, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00181814, 0x00181814, 0x00181813, 0x00181a14, 0x00181a14, 0x001a1815, 0x00181a14, 0x001b1c15, 0x001f1e14, 0x00211c13, 0x00221c11, 0x00251d11, 0x00261d11, 0x00261d11, 0x00261d11, 0x00271e10, 0x00271e10, 0x00271f0f, 0x00271e10, 0x00271e10, 0x00271e10, 0x00261d10, 0x00241c10, 0x00241c12, 0x00241c12, 0x00241e14, 0x00231c14, 0x001f1910, 0x001b180e, 0x0018170c, 0x0015150a, 0x00141408, 0x00141408, 0x00141408, 0x00191810, 0x00181810, 0x00181810, 0x00181710, 0x00161510, 0x00161410, 0x0016120a, 0x00282217, 0x00372d1f, 0x003f3320, 0x00453823, 0x0043321d, 0x0043301a, 0x004e3820, 0x004d341b, 0x0055341a, 0x005d3b1c, 0x005e3815, 0x005e3812, 0x00623a13, 0x00663c16, 0x00673c16, 0x00693c18, 0x00683c18, 0x00683c16, 0x0070441c, 0x006f4117, 0x0079481b, 0x00804a1e, 0x007c4619, 0x00763e11, 0x00733c0c, 0x00743c0d, 0x00703808, 0x00743b0b, 0x00773d0d, 0x00733909, 0x00753c0a, 0x00773e0c, 0x00743e0a, 0x00744009, 0x0074410c, 0x00764310, 0x0074410d, 0x00703d09, 0x006d3905, 0x006c3907, 0x006c3908, 0x006c390d, 0x0068360d, 0x0068370e, 0x00683810, 0x00603108, 0x00603208, 0x005c2f08, 0x005a2d08, 0x00592d0b, 0x00562c0c, 0x00542c0d, 0x004c2409, 0x00421d03, 0x00432007, 0x003c1e08, 0x00351c0a, 0x0030190c, 0x0025130c, 0x001e0d06, 0x001c1007, 0x001b1108, 0x00191108, 0x00191208, 0x00191208, 0x001c1309, 0x001c1309, 0x001c1208, 0x001c1307, 0x001a130b, 0x0019140b, 0x0018140b, 0x00171409, 0x0018140c, 0x001b170f, 0x001c1810, 0x001c1914, 0x001b1a17, 0x00181915, 0x00181915, 0x00181915, 0x00181a15, 0x00141a14, 0x00141c14, 0x00161b14, 0x00171a14, 0x00181712, 0x00161811, 0x00141812, 0x00111812, 0x00131915, 0x00131b16, 0x00121a15, 0x00131914, 0x00141914, 0x00151a14, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00131914, 0x00131914, 0x00131914, 0x00131914, 0x00121a14, 0x00121a14, 0x00111913, 0x00101812, 0x00121812, 0x00131712, 0x00121712, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00121511, 0x00131511, 0x00131511, 0x00131511, 0x00131511, 0x00141612, 0x00141813, 0x00131914, 0x00131b14, 0x00131b14, 0x00131b14, 0x00131b14, 0x00131a14, 0x00141a14, 0x00141b14, 0x00151c15, 0x00161c15, 0x00181b17, 0x00191c18, 0x00191c18, 0x00181b17, 0x00171c17, 0x00191e19, 0x001a1f18, 0x001a1f16, 0x001a1f16, 0x001a1f18, 0x001a201a, 0x001a1f19, 0x00181f17, 0x00181f17, 0x00181f17, 0x00161c15, 0x00151c14, 0x00151b17, 0x00151b17, 0x00141a16, 0x00141914, 0x00141914, 0x00131712, 0x00101510, 0x0010140f, 0x0010140f, 0x000e140e, 0x000c130d, 0x000c140d, 0x000b140d, 0x000a130c, 0x0008110a, 0x00081009, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x0005100a, 0x00040d08, 0x00040d08, 0x00040d08, 0x0006100b, 0x00040d08, 0x0005100a, 0x00040d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003c3e0d, 0x0041420e, 0x0044450d, 0x0048490f, 0x004c4d0f, 0x005c5710, 0x00b69314, 0x00cca316, 0x00cca316, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca619, 0x00cca619, 0x00c8a418, 0x00978315, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00626313, 0x00626312, 0x00606012, 0x005e5f12, 0x00a48914, 0x00cca417, 0x00b09014, 0x004f5010, 0x00505010, 0x004c4d10, 0x00484910, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0036370b, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x00081009, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f0a, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00060e08, 0x00070f08, 0x00081009, 0x00081009, 0x00081009, 0x0009120b, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c140d, 0x000e1610, 0x000e1610, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00141813, 0x00141811, 0x00141912, 0x00141910, 0x00181813, 0x00181813, 0x00181914, 0x00181a14, 0x001a1b14, 0x001c1c15, 0x001b1c14, 0x00181a12, 0x00181a12, 0x00181910, 0x0017180f, 0x00181910, 0x00181910, 0x00181a14, 0x00181a14, 0x00171914, 0x00161812, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00141813, 0x00131712, 0x00141612, 0x00151612, 0x00161713, 0x00161712, 0x00171812, 0x00191813, 0x001a1b12, 0x001c1c12, 0x001f1e12, 0x00221c10, 0x00241c10, 0x00281c11, 0x00291c12, 0x00291c12, 0x00291c10, 0x00291d10, 0x002a1e10, 0x002a1e11, 0x002a1e11, 0x002a1d13, 0x00291c11, 0x00281c13, 0x00281c13, 0x00281c13, 0x00251c10, 0x00261d11, 0x00241d11, 0x00221b0f, 0x001d190c, 0x001b190b, 0x0018180b, 0x00141508, 0x00121205, 0x00121206, 0x0018170c, 0x0017160d, 0x0016160d, 0x0014140c, 0x0014140b, 0x0014140c, 0x0016140b, 0x00151107, 0x00282315, 0x00352d1d, 0x003c3220, 0x00423421, 0x0044331f, 0x004c3823, 0x004c341d, 0x0055361e, 0x005c3c20, 0x005a3817, 0x005c3814, 0x005f3a15, 0x00633c18, 0x00653b18, 0x00683c1a, 0x00673c18, 0x00683c16, 0x006e411a, 0x006d3f16, 0x0078461c, 0x00764218, 0x006f3c11, 0x006e380f, 0x006f3a0e, 0x006e380c, 0x006b360a, 0x006e390b, 0x00703a0c, 0x006a3508, 0x006c3708, 0x00713c0c, 0x006c3808, 0x006c3b0a, 0x006d3c0c, 0x006d3c0d, 0x006d3c0d, 0x00693809, 0x00683808, 0x00683609, 0x0068370c, 0x0069380c, 0x0068380c, 0x0069390f, 0x0068380f, 0x005f3006, 0x00603209, 0x00582c06, 0x005a2d09, 0x00572c09, 0x0053280a, 0x0050290c, 0x00462107, 0x00401d04, 0x00402208, 0x00391f0b, 0x00311d0c, 0x00241408, 0x001d1108, 0x001c1009, 0x001a0f08, 0x00191008, 0x00181006, 0x00191107, 0x00191208, 0x001a1208, 0x001a1108, 0x00191006, 0x00181205, 0x00181408, 0x00181408, 0x00181408, 0x00181408, 0x001a160b, 0x001c180c, 0x001f190f, 0x001e1913, 0x001b1814, 0x00191816, 0x00181917, 0x00181917, 0x00191816, 0x00171814, 0x00161814, 0x00141811, 0x0013150f, 0x0010120c, 0x0010120a, 0x0010140b, 0x000d120b, 0x00101610, 0x00121914, 0x00111913, 0x00121813, 0x00131712, 0x00121812, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00131914, 0x00131914, 0x00131914, 0x00131914, 0x00131914, 0x00131914, 0x00111813, 0x00101711, 0x00121712, 0x00131712, 0x00121712, 0x00111611, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00121611, 0x00131712, 0x00111812, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00111813, 0x00131914, 0x00141b14, 0x00151c15, 0x00151c15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00141a14, 0x00171d18, 0x00181f17, 0x00181f15, 0x00181f15, 0x00181f17, 0x00181e18, 0x00181f19, 0x00181f17, 0x00181f17, 0x00181f17, 0x00171e16, 0x00161c16, 0x00161c17, 0x00161c17, 0x00141b15, 0x00141a14, 0x00141914, 0x00131712, 0x00111611, 0x0010140f, 0x0010140f, 0x000e140e, 0x000c130d, 0x000c140d, 0x000c140d, 0x000b140d, 0x0008110a, 0x0008100a, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x0006100b, 0x00040e09, 0x0005100a, 0x00040e09, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x00202309, 0x00202309, 0x0026280c, 0x00292b0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00706211, 0x00cca316, 0x00caa216, 0x00b59414, 0x00b39315, 0x00b39316, 0x00b39416, 0x00b39417, 0x00b39417, 0x00b39417, 0x00b39417, 0x00b39417, 0x00b29317, 0x00b29317, 0x00b19217, 0x00b19317, 0x00b19316, 0x00b19316, 0x00b09216, 0x00b09216, 0x00b09216, 0x00b09117, 0x00b09117, 0x00b09116, 0x00b09116, 0x00b09216, 0x00b09217, 0x00b09217, 0x00b09218, 0x00b09218, 0x00b09218, 0x00b09217, 0x00af9318, 0x00a88e17, 0x00857814, 0x00666713, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00636414, 0x00616112, 0x00606013, 0x00605e12, 0x00b49416, 0x00cca417, 0x00ac8c15, 0x004f5010, 0x00505010, 0x004c4d10, 0x00484910, 0x0045470e, 0x0040400d, 0x003c3e0d, 0x0036370c, 0x0034350c, 0x002d2f0a, 0x00292b0b, 0x0026280b, 0x00202309, 0x001d2008, 0x001d2009, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00050d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00050d05, 0x00060e06, 0x00060e06, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x0008100a, 0x000a130c, 0x000c140e, 0x000d140e, 0x00101610, 0x00101610, 0x00101610, 0x00101610, 0x00101610, 0x00121812, 0x00131914, 0x00141a14, 0x00161b15, 0x00161b14, 0x00171c15, 0x00171c14, 0x00181a14, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x001a1b14, 0x001a1b14, 0x00191b13, 0x00181a12, 0x00181a12, 0x00181a10, 0x00181a10, 0x0017180f, 0x00161810, 0x00141913, 0x00141914, 0x00141813, 0x00111611, 0x00131712, 0x00111611, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101610, 0x00101610, 0x00111510, 0x00141712, 0x00161814, 0x00161815, 0x00181613, 0x00191710, 0x001c1b0f, 0x001e1c0f, 0x00221d10, 0x00251c0e, 0x00281d0d, 0x002b1d0c, 0x002d1d0d, 0x002c1c0c, 0x002d1e0e, 0x002f200d, 0x0030210f, 0x00322310, 0x00332411, 0x00322312, 0x00302010, 0x002e1e0f, 0x002c1f10, 0x002c1f10, 0x002a1e0f, 0x00281c0d, 0x00281e0f, 0x00231a0c, 0x001f180a, 0x001d1a0a, 0x001b190a, 0x00171708, 0x00171408, 0x00141208, 0x0016140a, 0x001a180e, 0x001a180e, 0x0016150b, 0x00141408, 0x00141408, 0x00131308, 0x00141207, 0x00141105, 0x00241e13, 0x00342b1d, 0x00413424, 0x00403020, 0x0043301e, 0x004f3824, 0x00523520, 0x0054351c, 0x00573718, 0x00553412, 0x00573413, 0x005d3a18, 0x00623c18, 0x00643c1a, 0x00663b18, 0x00693c18, 0x006b3c17, 0x006c3d14, 0x00704118, 0x006f3f15, 0x006c3b11, 0x006d3b12, 0x006d3c12, 0x0066360d, 0x00623208, 0x00643409, 0x00613107, 0x00633308, 0x0064340a, 0x006a3b0e, 0x0066370a, 0x00643508, 0x0067380b, 0x006a3a10, 0x00633308, 0x0067380d, 0x0067380c, 0x0065350c, 0x0065350d, 0x0066360c, 0x0067390c, 0x0067390d, 0x00623709, 0x005c3005, 0x00582c04, 0x00542904, 0x00542908, 0x00532909, 0x004c2306, 0x004b2509, 0x00462309, 0x003f1f06, 0x003a210a, 0x00311e0a, 0x00221404, 0x00180f04, 0x00150f07, 0x00150f06, 0x00180e07, 0x00180e07, 0x00180f05, 0x00191108, 0x001a1208, 0x00191208, 0x00191208, 0x00181207, 0x00161307, 0x00161408, 0x00161408, 0x00171507, 0x001a1709, 0x001c170a, 0x001d170b, 0x00221b0e, 0x00221b12, 0x001e1913, 0x001c1812, 0x001a1913, 0x001b1812, 0x001b1711, 0x001d1810, 0x001d1912, 0x001c180f, 0x001c1b10, 0x0018190f, 0x00121408, 0x00101408, 0x000d1008, 0x000c100b, 0x000c130d, 0x00101610, 0x00101610, 0x00101610, 0x000e1611, 0x000c1710, 0x000c1710, 0x000c1710, 0x000c1710, 0x00101812, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000e1710, 0x000e1610, 0x000f1610, 0x00101610, 0x00101610, 0x000f150f, 0x000f150f, 0x0010140f, 0x0010140f, 0x0010140f, 0x0010140f, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101711, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x00101913, 0x00121a14, 0x00131b14, 0x00141c15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00151a14, 0x00141a14, 0x00161c16, 0x00171d16, 0x00171e14, 0x00171e14, 0x00171d16, 0x00171d18, 0x00171d18, 0x00181f17, 0x00181f17, 0x00182018, 0x00182018, 0x00171e18, 0x00171d18, 0x00171d18, 0x00161c17, 0x00151c15, 0x00151a14, 0x00141914, 0x00141813, 0x00111611, 0x00111611, 0x00101610, 0x000f150f, 0x000d150f, 0x000e1610, 0x000c140e, 0x000a130c, 0x000a130c, 0x000a1210, 0x0009110f, 0x0008100d, 0x0008100d, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0006100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x0005100a, 0x0006100b, 0x00040e09, 0x0006100b, 0x00060c07, 0x000f130f, 0x000f130f, 0x0014180f, 0x0014180b, 0x00191c0a, 0x001d200a, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004f5010, 0x00515110, 0x00706411, 0x00cca316, 0x00c7a016, 0x006d6612, 0x00605f12, 0x00626013, 0x00636212, 0x00646413, 0x00646413, 0x00656414, 0x00656414, 0x00656414, 0x00656414, 0x00656414, 0x00646413, 0x00646413, 0x00646413, 0x00646313, 0x00646312, 0x00646313, 0x00646313, 0x00646313, 0x00646313, 0x00646313, 0x00646413, 0x00646413, 0x00646414, 0x00656414, 0x00656414, 0x00656414, 0x00666514, 0x00666513, 0x00686714, 0x00686813, 0x00666713, 0x00666713, 0x00656614, 0x00656614, 0x00656614, 0x00646514, 0x00636414, 0x00626313, 0x00616112, 0x006c6613, 0x00c4a017, 0x00cca417, 0x00988014, 0x00515110, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x0008100b, 0x0008100b, 0x00050d08, 0x00050d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00060e06, 0x00060e06, 0x00050d05, 0x00060e08, 0x00060e08, 0x00081009, 0x00070f08, 0x00070f08, 0x0009110b, 0x0008100a, 0x0008100a, 0x0008110a, 0x0008110b, 0x000a130c, 0x000c140e, 0x000d140e, 0x00101510, 0x00101510, 0x00131712, 0x00131712, 0x00131712, 0x00141914, 0x00151a14, 0x00151a14, 0x00161b15, 0x00181a14, 0x00181c15, 0x00181c14, 0x00181813, 0x001a1c15, 0x001c1d18, 0x001b1c16, 0x001a1b14, 0x001a1b14, 0x00191a13, 0x00181911, 0x00181911, 0x00171810, 0x00171810, 0x00161710, 0x00141810, 0x00131812, 0x00121813, 0x00111812, 0x00101610, 0x00101711, 0x00101610, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x00101510, 0x00131713, 0x00161815, 0x00161815, 0x00181712, 0x001a1810, 0x001e1b10, 0x00201c0f, 0x00241d10, 0x00281c0c, 0x002b1c0a, 0x002f1c05, 0x00311f05, 0x00322004, 0x00312005, 0x0038260a, 0x0038270b, 0x00362509, 0x00352408, 0x00352408, 0x00352408, 0x00342408, 0x00342409, 0x0033230b, 0x0030220a, 0x002d200a, 0x002b1e09, 0x00261b08, 0x00241b0a, 0x00211c0a, 0x00201c0b, 0x001c1908, 0x0018170c, 0x0017140a, 0x0017140b, 0x0017140a, 0x0019180c, 0x0017170a, 0x00141408, 0x00131408, 0x00111408, 0x00111308, 0x00131208, 0x00141008, 0x00221c10, 0x00393021, 0x00423525, 0x003f2f1f, 0x0044311e, 0x004a321f, 0x004c311a, 0x0055371d, 0x00543415, 0x00553515, 0x00563414, 0x00603a1a, 0x00633c1c, 0x00643a18, 0x00673c18, 0x00683b15, 0x00673b12, 0x00693c13, 0x006c3d14, 0x006b3c14, 0x00683a11, 0x0064360f, 0x005e300a, 0x00582c05, 0x00572b04, 0x00542803, 0x00572b06, 0x005f320c, 0x0062340c, 0x0062350c, 0x005f3109, 0x005f310a, 0x0061340d, 0x005d300a, 0x005c2f08, 0x005d3009, 0x005f320c, 0x005f320c, 0x0061340c, 0x0064380e, 0x0064380e, 0x005d3308, 0x00592e05, 0x00572c06, 0x00542a08, 0x00542c0c, 0x00542c0d, 0x00492308, 0x00431f05, 0x003e1c06, 0x00381b06, 0x00341f0b, 0x00201200, 0x00181002, 0x00141004, 0x00141008, 0x00151007, 0x00160e06, 0x00170e04, 0x00171005, 0x00181208, 0x00191308, 0x00181308, 0x00181308, 0x00161307, 0x00141407, 0x00141506, 0x00161408, 0x00191709, 0x001c1809, 0x001d1707, 0x001e1607, 0x00251c0d, 0x00281d10, 0x00231a0f, 0x001e180c, 0x001c190c, 0x001d190b, 0x001d1609, 0x00261c0c, 0x002c200f, 0x002e2411, 0x00322a18, 0x002a2514, 0x00181606, 0x00131307, 0x00101308, 0x000f1009, 0x000e1109, 0x0010150e, 0x00101510, 0x00101610, 0x000e1611, 0x000c1810, 0x000c1810, 0x000c1810, 0x000c1810, 0x000e1811, 0x000c160f, 0x000c160f, 0x000c160f, 0x000c160f, 0x000c1710, 0x000c1710, 0x000d1810, 0x000d1610, 0x000c140e, 0x000c140e, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000e150f, 0x000d150f, 0x000c160f, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000e1811, 0x000e1811, 0x000f1912, 0x000f1912, 0x00101912, 0x00111812, 0x00111812, 0x00111812, 0x00101812, 0x00131b14, 0x00141c15, 0x00131c13, 0x00131c13, 0x00131c13, 0x00131c13, 0x00151e18, 0x00151e18, 0x00181f17, 0x00181f17, 0x00182018, 0x00182018, 0x00181e17, 0x00171d16, 0x00181e17, 0x00182018, 0x00181f18, 0x00161b15, 0x00151a14, 0x00141914, 0x00131712, 0x00131712, 0x00111711, 0x00101610, 0x000e1610, 0x000f1710, 0x000c140e, 0x000c140e, 0x000c140e, 0x000a120f, 0x0009110f, 0x0008100d, 0x0008100d, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0007100b, 0x0006100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x00040e09, 0x0008110c, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003e400c, 0x0043440e, 0x0047480e, 0x004c4d10, 0x004f5010, 0x00535410, 0x00716512, 0x00cca417, 0x00c7a116, 0x006c6713, 0x00606013, 0x00626313, 0x00646414, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666713, 0x00656614, 0x00646514, 0x00656614, 0x00646414, 0x00646514, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646514, 0x00646514, 0x00646513, 0x00656614, 0x00666714, 0x00666713, 0x00666714, 0x00666714, 0x00666714, 0x00666714, 0x00666713, 0x00656614, 0x00646513, 0x00646414, 0x00626313, 0x00606013, 0x00947f14, 0x00caa317, 0x00c8a117, 0x00746811, 0x00535410, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x0026280a, 0x0026280c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00081009, 0x00060e08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d07, 0x00070f08, 0x00070f08, 0x00081009, 0x0008100b, 0x0008100c, 0x000b130e, 0x000c1410, 0x000c140f, 0x000e140e, 0x000f150f, 0x000f150f, 0x00101510, 0x00121611, 0x00121711, 0x00141814, 0x00151a14, 0x00151a13, 0x00161b14, 0x00171c15, 0x00171c15, 0x001a1b15, 0x001a1b15, 0x001b1c16, 0x001b1c16, 0x001c1c18, 0x001b1c16, 0x00191b14, 0x001a1b14, 0x00171811, 0x00171812, 0x00161711, 0x00151610, 0x00151610, 0x00131611, 0x00131611, 0x00131510, 0x00131510, 0x00101510, 0x00101510, 0x00111611, 0x00101610, 0x000d1510, 0x000d1510, 0x000c1410, 0x000c1410, 0x000f150f, 0x000f150f, 0x000f150f, 0x000e140e, 0x000c140d, 0x000e150f, 0x00101610, 0x00101510, 0x00131714, 0x00161814, 0x00191711, 0x001c180f, 0x001e190e, 0x00241b10, 0x002c1c10, 0x00321b0d, 0x003c200d, 0x004f3414, 0x00583d1a, 0x004f340e, 0x00482f08, 0x00503812, 0x00503814, 0x004a330f, 0x00442c08, 0x00442b09, 0x00482d0c, 0x00462f0c, 0x0045300c, 0x00422f0c, 0x00382805, 0x00342404, 0x002f2104, 0x002a1e03, 0x00261b08, 0x00251c09, 0x00251d0b, 0x00231c0a, 0x001b190b, 0x00181609, 0x00181709, 0x00161407, 0x0019180a, 0x0019180c, 0x00141408, 0x00111406, 0x00101407, 0x000f1307, 0x00101207, 0x00101107, 0x00131107, 0x00211b10, 0x0033291c, 0x003a2d1f, 0x00483828, 0x0046311f, 0x00442e18, 0x00563d24, 0x00553920, 0x0058391c, 0x00553517, 0x005d391a, 0x005f3818, 0x00603718, 0x00653a18, 0x00623712, 0x00643911, 0x0064380f, 0x0064380f, 0x00653910, 0x005e320a, 0x00592c07, 0x00592c0b, 0x00582c0d, 0x00542b0c, 0x004d2408, 0x0051280c, 0x00552a0c, 0x00582d0e, 0x005c310c, 0x005d320c, 0x005b300b, 0x00582d09, 0x005c300c, 0x00542804, 0x005a2f0b, 0x005d320e, 0x005a2f09, 0x005f340e, 0x00623810, 0x0061370e, 0x005c3008, 0x00542a03, 0x00562b07, 0x00542c0a, 0x00542c0d, 0x004b2608, 0x004b260c, 0x0041210a, 0x00361c09, 0x002e1808, 0x00200e01, 0x00190e04, 0x00141005, 0x00121008, 0x00131008, 0x00151008, 0x00161007, 0x00171106, 0x00171207, 0x00181308, 0x00171408, 0x00151408, 0x00151408, 0x00141408, 0x00161408, 0x00181408, 0x0019140b, 0x001d160c, 0x001f170a, 0x00201806, 0x00261b09, 0x002d200e, 0x00342511, 0x00311f08, 0x002a1901, 0x002b1c05, 0x002e2007, 0x00302003, 0x003d2a08, 0x00463413, 0x00433415, 0x0040321a, 0x002f2410, 0x00181104, 0x00110f05, 0x00121006, 0x00110f05, 0x000f0d04, 0x000f100b, 0x0010140f, 0x000f1410, 0x000d1510, 0x000c1710, 0x000b1710, 0x000b1710, 0x000b1710, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000b1510, 0x000b1510, 0x000a140f, 0x0009130e, 0x000a140f, 0x000a140d, 0x000a140d, 0x000a140d, 0x000a140d, 0x0009140b, 0x0008130a, 0x0009140b, 0x0009140b, 0x000c140c, 0x000c140c, 0x000c140c, 0x000c140c, 0x000a140d, 0x000b150e, 0x000b150e, 0x000b150e, 0x000c1410, 0x000c1410, 0x000d1510, 0x000d1510, 0x000c1610, 0x000b170f, 0x000c1810, 0x000c1810, 0x000c1811, 0x000d1712, 0x000d1711, 0x000e1813, 0x000f1812, 0x00111913, 0x00131b14, 0x00131b14, 0x00131b14, 0x00131b15, 0x00131b14, 0x00141c15, 0x00141c14, 0x00161c16, 0x00181c18, 0x00191d18, 0x00191e18, 0x00191d18, 0x00181c18, 0x00181c17, 0x00181d15, 0x00181c15, 0x00171c17, 0x00171c17, 0x00161b15, 0x00141914, 0x00141612, 0x00131712, 0x00101812, 0x000e1710, 0x00101610, 0x00101610, 0x000c140e, 0x000b140d, 0x000a140d, 0x0009140d, 0x0008120c, 0x0008120c, 0x0009110c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0007100b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0004100a, 0x0004100a, 0x00030f09, 0x00030f09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0044450d, 0x00494a0f, 0x004d4e0f, 0x00515110, 0x00555610, 0x00726612, 0x00cca417, 0x00c7a118, 0x006f6913, 0x00636413, 0x00646514, 0x00656614, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00686814, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00656614, 0x00646514, 0x00636414, 0x006b6613, 0x00bc9917, 0x00cca418, 0x00ad8e15, 0x005b5911, 0x00545510, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0038380c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00081009, 0x00060e08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d07, 0x00070f08, 0x0009110b, 0x0009120b, 0x0008100c, 0x0008100c, 0x000b130e, 0x000c1410, 0x000e1510, 0x000f150f, 0x00101610, 0x00101710, 0x00111711, 0x00141814, 0x00141814, 0x00151a14, 0x00161a14, 0x00181a14, 0x00181a14, 0x00181c15, 0x00181c15, 0x001a1b15, 0x001a1b15, 0x001b1c16, 0x001b1c16, 0x001a1b17, 0x00181914, 0x00181913, 0x001a1b14, 0x00191b14, 0x00181813, 0x00161711, 0x00151610, 0x00141610, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x000f150f, 0x000f150f, 0x000e140e, 0x000e140e, 0x000c140d, 0x000c140d, 0x000b130c, 0x000b130c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140e, 0x000f1610, 0x00101510, 0x00121814, 0x00141711, 0x001a1811, 0x001e1910, 0x0020190c, 0x00281b0e, 0x00301c0a, 0x00402508, 0x005c3c16, 0x00755324, 0x0074501d, 0x0066440e, 0x00603f07, 0x00684811, 0x00684814, 0x0064430f, 0x005f3c08, 0x005c3a08, 0x005e3b0b, 0x005c3a0c, 0x005a3a0f, 0x00573a10, 0x00483008, 0x003b2704, 0x00332204, 0x002d1f05, 0x002b1d09, 0x00291d0a, 0x00281e09, 0x00241c08, 0x001e1c0b, 0x001b1909, 0x001b1a0a, 0x001c1c0c, 0x001b1a0a, 0x00191809, 0x00181809, 0x00101404, 0x000d1204, 0x000e1205, 0x000e1207, 0x000e1107, 0x00121308, 0x00151206, 0x001a1408, 0x002d2416, 0x003e3121, 0x00443220, 0x0045301d, 0x00523a25, 0x00583c27, 0x00563a1f, 0x00543518, 0x005a3818, 0x005a3415, 0x005d3415, 0x00613816, 0x005f3511, 0x00663c15, 0x0060370e, 0x0060340c, 0x005c320b, 0x005c320b, 0x00572b06, 0x0057290b, 0x0056290c, 0x00542a10, 0x004c250b, 0x004e250c, 0x004e250a, 0x00532a0c, 0x005a3110, 0x005c3310, 0x005a300d, 0x00562c09, 0x00552b08, 0x00562c09, 0x005c3310, 0x00603613, 0x005a310d, 0x005b310c, 0x00603611, 0x005f350f, 0x005c330c, 0x00552c07, 0x00542c09, 0x00532c0b, 0x00492607, 0x00411f04, 0x0042230c, 0x0039200b, 0x00291505, 0x001c0d01, 0x00160b00, 0x00160e06, 0x00140f09, 0x00120f0a, 0x00141009, 0x00161109, 0x00161208, 0x00171407, 0x00171408, 0x00171408, 0x00161408, 0x00161408, 0x00161407, 0x00151406, 0x00171406, 0x001a1408, 0x001b1308, 0x001e150c, 0x0021170a, 0x00281b08, 0x002b1d08, 0x00362410, 0x003f2a0f, 0x00432b08, 0x00462d03, 0x004e3407, 0x005a4010, 0x00563e0b, 0x0058400f, 0x00543d13, 0x0044300d, 0x0032230a, 0x00241707, 0x00170f04, 0x00110f05, 0x00121006, 0x00111005, 0x000f0d04, 0x00101009, 0x0011140e, 0x000f1410, 0x000d1410, 0x00091410, 0x00091410, 0x00091410, 0x00091410, 0x000a1410, 0x000a1410, 0x000a1410, 0x000a1410, 0x000a1410, 0x00091310, 0x00091310, 0x0008120f, 0x0009130f, 0x0009130e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0008120c, 0x0008120c, 0x0009140c, 0x0009140c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000a140d, 0x000b150e, 0x000a140d, 0x000a140d, 0x000c140f, 0x000c140f, 0x000c1410, 0x000c1410, 0x000b150f, 0x000a160e, 0x000b170f, 0x000c1810, 0x000c1811, 0x000c1713, 0x000c1711, 0x000c1711, 0x000d1710, 0x00101812, 0x00111913, 0x00131b14, 0x00131b14, 0x00141a16, 0x00141a14, 0x00151c15, 0x00151c14, 0x00161b15, 0x00161b15, 0x00171c17, 0x00181c17, 0x00181c18, 0x00181d17, 0x00181d15, 0x00181d14, 0x00181c14, 0x00171c17, 0x00171c17, 0x00161b15, 0x00141914, 0x00141813, 0x00121712, 0x00101812, 0x000e1710, 0x00101610, 0x00101610, 0x000e1710, 0x000c140e, 0x000a140d, 0x0009140c, 0x0008120c, 0x0008120c, 0x0009110c, 0x0009110d, 0x0008100b, 0x0008100b, 0x0007100b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0004100a, 0x0004100a, 0x00030f09, 0x00030f09, 0x00040e09, 0x0005100a, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0026280c, 0x00292b0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x004b4c0f, 0x00505010, 0x00535410, 0x00565711, 0x00746812, 0x00cca418, 0x00c7a118, 0x00706b14, 0x00646414, 0x00656614, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00666713, 0x00656614, 0x00646513, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00646514, 0x00646414, 0x00a28915, 0x00cba418, 0x00c6a118, 0x00786c13, 0x00565711, 0x00545511, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00081009, 0x00060e08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060e06, 0x00071007, 0x00060e06, 0x00060e06, 0x00081009, 0x00081009, 0x0009120c, 0x0009120c, 0x000a120e, 0x000b130e, 0x000c1410, 0x000d1510, 0x000e1510, 0x00101610, 0x00101711, 0x00111812, 0x00131812, 0x00161812, 0x00161812, 0x00181c15, 0x00191c15, 0x001a1b14, 0x001a1b14, 0x001a1b14, 0x001a1b14, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x001a1b17, 0x00181914, 0x00181813, 0x00181912, 0x00161810, 0x00141710, 0x00131610, 0x0012150f, 0x0011150f, 0x0010150f, 0x000f150f, 0x000e140f, 0x000c130d, 0x000c140d, 0x000c140e, 0x000a130c, 0x000a130c, 0x000a130c, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008130c, 0x0008130c, 0x0008120c, 0x0008120c, 0x0009130c, 0x000b140d, 0x000e150f, 0x00101510, 0x00111613, 0x00141510, 0x001b1811, 0x00201810, 0x0023190d, 0x002e1e0f, 0x003c2408, 0x00634414, 0x007f581b, 0x0091651c, 0x008e6212, 0x008c600f, 0x00895f0b, 0x00916814, 0x00916815, 0x008c6410, 0x008a600d, 0x008a600c, 0x00895e0c, 0x00855a11, 0x007e5514, 0x00684209, 0x00513302, 0x00432b02, 0x00372405, 0x002e1e06, 0x002e1e09, 0x002d1e0a, 0x002b1f09, 0x0029200b, 0x00221e0b, 0x001f1c0a, 0x00201c0b, 0x00201d0b, 0x001e1c09, 0x001a1908, 0x001a1b09, 0x00161a09, 0x000c1002, 0x000c1004, 0x000c1005, 0x000c1006, 0x000e1006, 0x00121108, 0x00151208, 0x00181307, 0x00292012, 0x003f3020, 0x00402e1e, 0x004b3623, 0x00503824, 0x0050351d, 0x00503419, 0x00563719, 0x00563417, 0x005d3417, 0x005f3414, 0x00623816, 0x00643c16, 0x005d350e, 0x005b330c, 0x00572f0a, 0x005b330d, 0x005b300e, 0x00582b0e, 0x0054280e, 0x0050270c, 0x004c240c, 0x004c240d, 0x004b250a, 0x00532c0e, 0x00532c0c, 0x00502808, 0x00512908, 0x00572c0c, 0x00562c0c, 0x00512807, 0x00572d0c, 0x005d3313, 0x005c3210, 0x00572d0a, 0x00582e0a, 0x0059300c, 0x00582f0a, 0x00512806, 0x004e2809, 0x00502c10, 0x0049270d, 0x003c1f08, 0x00331c0b, 0x00281608, 0x00190c02, 0x00140c04, 0x00120d05, 0x00110d08, 0x00120e0c, 0x00100f0c, 0x00120f0b, 0x00131009, 0x00141208, 0x00151406, 0x00161407, 0x00161408, 0x00161408, 0x00161407, 0x00181508, 0x00191507, 0x001b1406, 0x001d1408, 0x0020160b, 0x0024180c, 0x00281a0c, 0x002e1f0a, 0x00312008, 0x003f280d, 0x00503510, 0x006e4e1b, 0x008d682a, 0x009d7128, 0x00a0762a, 0x008e6b24, 0x006e4e16, 0x004d340a, 0x00352103, 0x00211400, 0x00180f02, 0x00131006, 0x00111005, 0x00100f04, 0x00111005, 0x00100e05, 0x000e0f08, 0x000e110b, 0x000e130e, 0x000c1410, 0x00081311, 0x00081312, 0x00081312, 0x00081312, 0x00091312, 0x00091312, 0x00091312, 0x00091312, 0x00091211, 0x00091111, 0x00091211, 0x00091211, 0x00091310, 0x00091310, 0x00091310, 0x0008120f, 0x0008120f, 0x0009130e, 0x0008120c, 0x0008110c, 0x0008110c, 0x0009110e, 0x0009110e, 0x0009110e, 0x0009110e, 0x0008130c, 0x0009140c, 0x0009140c, 0x0009140c, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009140e, 0x0009160e, 0x000a160e, 0x000b160e, 0x000b1610, 0x000c1511, 0x000c1610, 0x000c1610, 0x000c160f, 0x000d150f, 0x000f1710, 0x000f1811, 0x00111913, 0x00141815, 0x00151a14, 0x00141914, 0x00151a13, 0x00161a14, 0x00161a15, 0x00171c17, 0x00181c17, 0x00171c16, 0x00171c14, 0x00171c14, 0x00171c13, 0x00171c14, 0x00171c17, 0x00171c17, 0x00171c17, 0x00151a14, 0x00161b15, 0x00141a14, 0x00131914, 0x00101812, 0x00101610, 0x00101710, 0x000e1610, 0x000e1610, 0x000c1610, 0x000b150e, 0x000a140d, 0x0008120c, 0x0009110c, 0x0009110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110b, 0x0005110b, 0x0006120c, 0x0004100a, 0x0004100a, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00141809, 0x00191c09, 0x00202309, 0x00202309, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003e400d, 0x0043440e, 0x0048490e, 0x004c4d0f, 0x00505010, 0x00545510, 0x00585911, 0x00756a13, 0x00cca418, 0x00c7a218, 0x00716c14, 0x00656614, 0x00686814, 0x00696914, 0x006a6a14, 0x006b6b14, 0x006b6b14, 0x006b6b14, 0x006b6b14, 0x006b6b14, 0x006a6a14, 0x006a6a14, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00686814, 0x00686814, 0x00686814, 0x00656614, 0x00907e15, 0x00c8a418, 0x00cba418, 0x009c8415, 0x005c5c12, 0x00585810, 0x00545511, 0x00515110, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00081009, 0x00060e08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060e06, 0x00071007, 0x00081108, 0x00081108, 0x00081009, 0x00081009, 0x0009120c, 0x000a130c, 0x000c1410, 0x000d1510, 0x000d1510, 0x000e1610, 0x000f1610, 0x00101610, 0x00111812, 0x00141914, 0x00151a14, 0x00191a13, 0x00191a13, 0x001a1b14, 0x001a1b14, 0x001b1a14, 0x001b1a14, 0x001b1a14, 0x001b1a14, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x00181915, 0x00171813, 0x00161712, 0x00161710, 0x00141610, 0x00111610, 0x0011160f, 0x0010150e, 0x0010150e, 0x000d150f, 0x000d150f, 0x000c140e, 0x000c140d, 0x0009140c, 0x0009140c, 0x0009140c, 0x0009140c, 0x0009120a, 0x00081108, 0x00081108, 0x00081108, 0x0007110a, 0x0006120a, 0x0007120b, 0x0008130c, 0x0008130c, 0x000a150d, 0x000d1510, 0x000f1510, 0x00111613, 0x00141510, 0x001c1711, 0x00201810, 0x00261c0e, 0x0031200c, 0x00462a08, 0x007c571b, 0x00a97e2c, 0x00be8c28, 0x00c08e24, 0x00c09023, 0x00bd8e1d, 0x00c29422, 0x00c39523, 0x00c29423, 0x00c19421, 0x00c0931b, 0x00bd9018, 0x00bc8e22, 0x00b08223, 0x007c5003, 0x00583400, 0x004a2e00, 0x003c2707, 0x00322109, 0x00311f0a, 0x0030200a, 0x002d1f08, 0x002b1f08, 0x0024210c, 0x00222009, 0x00201d08, 0x00201d08, 0x00221e09, 0x001e1c09, 0x001a1b06, 0x00141803, 0x00151909, 0x000f1208, 0x000c0f04, 0x000c1007, 0x000c0f08, 0x000e0e07, 0x00100e06, 0x00141108, 0x00171004, 0x002c2314, 0x00382c1c, 0x0040301e, 0x003f2c17, 0x004f3720, 0x004d321b, 0x0055371d, 0x00553418, 0x005c3416, 0x005b3213, 0x00613916, 0x00603914, 0x005f3810, 0x00573009, 0x005c3410, 0x00572f0b, 0x005c3312, 0x00582b10, 0x0054280f, 0x0050270c, 0x004c240d, 0x0049240d, 0x004a250c, 0x00522b11, 0x00522b0e, 0x004f280a, 0x00572f10, 0x0053280c, 0x00572c0f, 0x00582e10, 0x00592e11, 0x00572e0e, 0x0059300f, 0x00572c0c, 0x00582e0c, 0x00562c0c, 0x00512808, 0x00492104, 0x00472008, 0x0048250f, 0x003d1e0a, 0x00311705, 0x00201004, 0x00170c04, 0x00130c07, 0x0013110b, 0x000f0e08, 0x000f0e08, 0x000f0e0b, 0x00110d0d, 0x0010100c, 0x00121109, 0x00141408, 0x00141407, 0x00161408, 0x00161408, 0x00151407, 0x0019170a, 0x001c190a, 0x001d1807, 0x001e1707, 0x00201608, 0x0024180a, 0x00281b0c, 0x002b1c0a, 0x00312109, 0x00352308, 0x00442c0c, 0x0055370a, 0x008c6528, 0x00b98c40, 0x00be862c, 0x00af7a1d, 0x008d6016, 0x005d3504, 0x00351a00, 0x00221200, 0x001a1103, 0x00131206, 0x00101108, 0x00110f05, 0x000e0c02, 0x000e0c02, 0x00101007, 0x0011130b, 0x000e110b, 0x000e120d, 0x000c1310, 0x00081110, 0x00071210, 0x00071210, 0x00071210, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0007100f, 0x00081110, 0x00081110, 0x00081210, 0x0008120f, 0x0008120e, 0x0007110d, 0x0007110d, 0x0008120d, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110b, 0x0008120c, 0x0009140d, 0x0009140d, 0x0008140e, 0x0008140e, 0x0007130d, 0x0007130d, 0x0008140d, 0x0008140d, 0x0008140d, 0x0008150e, 0x0008140f, 0x000a1410, 0x000b1410, 0x000c1610, 0x000c160f, 0x000d150f, 0x000d150f, 0x000d140e, 0x000e1610, 0x00121613, 0x00141813, 0x00121712, 0x00141811, 0x00141914, 0x00141914, 0x00151a14, 0x00161b16, 0x00171c15, 0x00171c14, 0x00171c13, 0x00161c12, 0x00161c13, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161b15, 0x00161c16, 0x00161c15, 0x00151b15, 0x00141914, 0x00131712, 0x00111813, 0x000f1610, 0x000f1610, 0x000d1710, 0x000c1710, 0x000c160f, 0x000a140d, 0x0009120c, 0x0008100c, 0x0008100b, 0x0008100c, 0x0007100c, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110b, 0x0005110b, 0x0006120c, 0x0004100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0020230a, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003e400c, 0x0043440e, 0x0048490f, 0x004c4d10, 0x00515110, 0x00555610, 0x00595a11, 0x00756a13, 0x00cca418, 0x00c7a218, 0x00726d14, 0x00686814, 0x00696914, 0x006b6b14, 0x006c6c14, 0x006c6c15, 0x006c6c15, 0x006c6c15, 0x006c6c15, 0x006c6c15, 0x006b6b14, 0x006a6a14, 0x006a6a14, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x006a6a14, 0x00696914, 0x00696914, 0x00686814, 0x00686814, 0x00938115, 0x00c6a219, 0x00cca518, 0x00b09217, 0x00646212, 0x005b5b11, 0x00585910, 0x00545510, 0x00515110, 0x004c4d10, 0x00484910, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00080f0a, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00081009, 0x0008110a, 0x00081009, 0x00060e08, 0x00040f08, 0x00081009, 0x000c120c, 0x000c130d, 0x000c130d, 0x000f150f, 0x00101610, 0x0010170f, 0x00121911, 0x00141912, 0x00151812, 0x00171910, 0x00181b12, 0x001a1b14, 0x001a1b14, 0x001b1c14, 0x001b1c14, 0x001a1b14, 0x001a1b14, 0x001b1c14, 0x001b1c14, 0x00181c15, 0x00181c15, 0x00171a14, 0x00161913, 0x00141813, 0x00141714, 0x00141714, 0x00121510, 0x00101510, 0x00101510, 0x0010140f, 0x0010140f, 0x000f140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000c130d, 0x0008120b, 0x0008120b, 0x0007110a, 0x0007110a, 0x00061009, 0x0007110a, 0x0007110a, 0x0007110a, 0x00061008, 0x00070f08, 0x00081009, 0x0009120b, 0x000b140e, 0x000c140f, 0x000c1210, 0x000d1211, 0x00101412, 0x00141510, 0x001b1610, 0x00201810, 0x00271c0c, 0x00351f0a, 0x004c2d0f, 0x00856021, 0x00c49936, 0x00c9a124, 0x00cca622, 0x00cca81d, 0x00cca819, 0x00cba817, 0x00cba817, 0x00cba918, 0x00c9a818, 0x00c8a914, 0x00c9a90e, 0x00cba615, 0x00c3981d, 0x00906208, 0x00633b01, 0x00523108, 0x00442c0c, 0x0038260f, 0x0034230b, 0x0034230b, 0x0033230b, 0x00302108, 0x002a2108, 0x00272008, 0x00241d08, 0x00241d09, 0x00241f0b, 0x00221e09, 0x001a1a08, 0x00151a08, 0x00141809, 0x000e1106, 0x000b0e04, 0x000c0f07, 0x000c0f08, 0x000d0f07, 0x00100f08, 0x00100f08, 0x00131007, 0x00151004, 0x00211a0c, 0x00322817, 0x003b2c18, 0x003f2c18, 0x0049311c, 0x0051341d, 0x00543419, 0x00563214, 0x00583312, 0x00583410, 0x0056310b, 0x0059340c, 0x0059340e, 0x0058320f, 0x0055300d, 0x00532c0c, 0x0052280c, 0x004d2408, 0x004f260c, 0x00502a10, 0x0048240b, 0x00442006, 0x00512c12, 0x00512c0f, 0x004c2508, 0x0050290a, 0x00542e0f, 0x00522a0c, 0x00532b0f, 0x00572f10, 0x00512c0b, 0x00532d0a, 0x00542d09, 0x00502907, 0x004e2708, 0x004b240c, 0x0046220b, 0x003e1e08, 0x00341c08, 0x00271703, 0x001a1000, 0x00171009, 0x00140e09, 0x00100d07, 0x00100e08, 0x00100e08, 0x00100d07, 0x000f0e06, 0x00101008, 0x00131009, 0x00131008, 0x00161309, 0x0018140b, 0x0018140a, 0x00181409, 0x001b170b, 0x00201c0c, 0x00201c0a, 0x00201807, 0x00221708, 0x00251809, 0x00281b09, 0x002d1f05, 0x002f2008, 0x0033240b, 0x003b2a0d, 0x00432b0a, 0x0055390c, 0x00805c20, 0x00a77b33, 0x00a77420, 0x0084540c, 0x00623604, 0x003d1800, 0x00291103, 0x00201004, 0x00181107, 0x00121208, 0x00111108, 0x000f0e05, 0x000b0b01, 0x00121108, 0x00101008, 0x00101109, 0x000e110b, 0x000d110c, 0x000c120d, 0x0009110e, 0x0009120f, 0x00081010, 0x00061110, 0x00091211, 0x00081110, 0x0007100f, 0x0007100f, 0x00091310, 0x0007110d, 0x0006100c, 0x0006100c, 0x0007100d, 0x0008120e, 0x0008110e, 0x0006110d, 0x0007110d, 0x0007110c, 0x00040e09, 0x00040f09, 0x0005100a, 0x0008120c, 0x0006100b, 0x0008110c, 0x0009130e, 0x0008120e, 0x0008120f, 0x0007110d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0008120e, 0x0008120e, 0x0008120f, 0x0007130f, 0x0007130f, 0x0007130f, 0x0007130f, 0x0008120f, 0x000b1411, 0x000a1410, 0x000a1410, 0x000b1510, 0x000c1610, 0x000c1610, 0x000c1610, 0x000e1410, 0x00101512, 0x00111611, 0x00111610, 0x00121911, 0x00131a12, 0x00131a12, 0x00131a12, 0x00141a13, 0x00151a13, 0x00161b14, 0x00161b14, 0x00161c15, 0x00181e18, 0x00181e18, 0x00171d16, 0x00181d15, 0x00191c16, 0x00181c15, 0x00181b14, 0x00161913, 0x00141914, 0x00141813, 0x00111611, 0x0010140f, 0x000f1410, 0x000e1610, 0x000c160f, 0x000a140c, 0x000a130d, 0x000b120e, 0x0009110d, 0x0009110d, 0x0008120c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x0005100a, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250c, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x003b3c0d, 0x0040400d, 0x0044450e, 0x00494a0f, 0x004d4e0f, 0x00525310, 0x00565711, 0x005c5c12, 0x00776c14, 0x00cca518, 0x00c7a218, 0x00736e14, 0x00696914, 0x006b6b14, 0x006c6c15, 0x006d6d15, 0x006d6d15, 0x006e6e15, 0x006d6d15, 0x006d6d15, 0x006c6c15, 0x006c6c15, 0x006b6b14, 0x006b6b14, 0x00696914, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x006a6a14, 0x006a6a14, 0x006a6a14, 0x00686814, 0x00757014, 0x00a58d17, 0x00c8a419, 0x00cca619, 0x00b79817, 0x006f6813, 0x005e5f12, 0x005c5c12, 0x00585910, 0x00555610, 0x00515110, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040c08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00050d09, 0x00040c08, 0x0008100a, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00070f08, 0x00081009, 0x00070f08, 0x00081009, 0x00051008, 0x0008110b, 0x000d140e, 0x000d140e, 0x000d140e, 0x00101610, 0x00101710, 0x00111810, 0x00131810, 0x00151812, 0x00171812, 0x00191b12, 0x001b1c13, 0x001a1b14, 0x001a1b14, 0x001b1c14, 0x001b1c14, 0x001a1b15, 0x001a1b15, 0x001b1c16, 0x001b1c16, 0x00181c15, 0x00171c15, 0x00151a13, 0x00141811, 0x00111613, 0x00111613, 0x00121714, 0x00101512, 0x00101510, 0x000f150f, 0x000f150f, 0x000d140e, 0x000d140e, 0x000c120c, 0x000c120c, 0x000c120c, 0x000a110c, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00040f08, 0x00051008, 0x00051008, 0x00051008, 0x00070f08, 0x00070f08, 0x00081009, 0x0009120b, 0x000a130c, 0x000a120e, 0x000b1110, 0x000d1211, 0x00101412, 0x00141510, 0x001b1610, 0x00201810, 0x00271c0c, 0x0035200b, 0x004c2c0e, 0x00876123, 0x00c39c33, 0x00cbab24, 0x00ccb020, 0x00ccb219, 0x00ccb414, 0x00ccb412, 0x00ccb412, 0x00ccb411, 0x00cbb410, 0x00cbb40e, 0x00cbb30b, 0x00ccb011, 0x00c09b18, 0x008a6102, 0x00684006, 0x0058360c, 0x0048300e, 0x003c2b10, 0x0037250a, 0x0037250a, 0x0038260b, 0x00342408, 0x00302407, 0x002d2207, 0x002b1f08, 0x002a1f09, 0x00281f09, 0x00241d09, 0x0020200d, 0x00191c0b, 0x00151a09, 0x00111508, 0x000c1004, 0x000b0e05, 0x000c0f07, 0x000d0f07, 0x000f1008, 0x000f1008, 0x00111109, 0x00141006, 0x00151105, 0x001b1404, 0x00261d0c, 0x00362915, 0x00422f1c, 0x004f3520, 0x0051341c, 0x00533417, 0x00543414, 0x00543110, 0x00502d08, 0x0058350f, 0x0056330d, 0x00502c0a, 0x004c2808, 0x004c280a, 0x004d270a, 0x004a2306, 0x00482406, 0x004d280c, 0x00482408, 0x004a260a, 0x004f2c10, 0x00502c0e, 0x004b2508, 0x004d2809, 0x004f2b0b, 0x004c2808, 0x004c2808, 0x00502c0c, 0x004c2a06, 0x004e2d08, 0x004d2a04, 0x00492602, 0x00472505, 0x00432409, 0x0040220c, 0x00301804, 0x00231000, 0x001b1000, 0x00160f02, 0x00131009, 0x00121009, 0x00110f08, 0x00100d07, 0x000f0f05, 0x000f0f05, 0x000e0e04, 0x00111008, 0x00131107, 0x00131107, 0x0018140b, 0x001a160c, 0x001b150d, 0x001c160d, 0x001e180c, 0x00221c0c, 0x00241c0c, 0x00251b09, 0x00271b08, 0x002b1c08, 0x002e1f0a, 0x00302209, 0x0032240a, 0x0038290f, 0x0038290d, 0x00392409, 0x00412704, 0x00543308, 0x00633d0b, 0x005d3504, 0x00482200, 0x00381800, 0x002c1104, 0x0025120d, 0x001d100d, 0x0018100b, 0x00141108, 0x00121107, 0x00111007, 0x00101007, 0x00131209, 0x000f0f05, 0x000d0f07, 0x000c1009, 0x000c100c, 0x000c120c, 0x0008100a, 0x000b1310, 0x00091310, 0x00081311, 0x00091310, 0x0008120f, 0x0007110d, 0x0007110d, 0x00091310, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110d, 0x0006110d, 0x0006100b, 0x0005100a, 0x0006100b, 0x0006100b, 0x0007110c, 0x0006100b, 0x0005100a, 0x0008110c, 0x0007100d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0007110e, 0x0007130f, 0x0007130f, 0x0007130f, 0x0007130f, 0x0008110d, 0x000a1410, 0x00091310, 0x00091310, 0x0009130e, 0x000a140f, 0x000b1510, 0x000b1410, 0x000c130f, 0x000f1410, 0x00101610, 0x0010160e, 0x00121911, 0x00121911, 0x00111810, 0x00111810, 0x00131812, 0x00141813, 0x00141913, 0x00141913, 0x00151b15, 0x00161c17, 0x00161c16, 0x00171d16, 0x00181d14, 0x00191c16, 0x00181c15, 0x001a1d17, 0x00181b14, 0x00161b16, 0x00151a14, 0x00141813, 0x00111611, 0x00101411, 0x0010150f, 0x000e150f, 0x000c150d, 0x000c130e, 0x000b120e, 0x0009110d, 0x0009110d, 0x0008120c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008110c, 0x0008110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0b, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x0040400e, 0x0045470e, 0x004b4c0f, 0x004f5010, 0x00535410, 0x00585811, 0x005c5d12, 0x00786c14, 0x00cca518, 0x00c7a318, 0x00746f14, 0x006a6a14, 0x006c6c14, 0x006d6d15, 0x006e6e15, 0x006f6f14, 0x006f6f14, 0x006f6f14, 0x006e6e15, 0x006d6d15, 0x006c6c15, 0x006c6c14, 0x006b6b14, 0x006a6a14, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x006a6a14, 0x006c6b14, 0x00716e14, 0x007d7414, 0x009f8a16, 0x00c09e19, 0x00cca71a, 0x00cba51a, 0x00b49618, 0x00716c14, 0x00626313, 0x005e5f13, 0x005c5c11, 0x00585911, 0x00555610, 0x00515110, 0x004d4e0f, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x000f130b, 0x000f130f, 0x000f130f, 0x0008100b, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040f09, 0x0005100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00070f08, 0x00081009, 0x00060e08, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d05, 0x00040c08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00060e08, 0x0008110b, 0x0008110a, 0x0008110b, 0x00061009, 0x000a130c, 0x000f150f, 0x000f150f, 0x00101510, 0x00121712, 0x00141812, 0x00141810, 0x00161912, 0x00181913, 0x00181913, 0x001a1a12, 0x001c1c14, 0x001b1c14, 0x001b1c14, 0x001a1b14, 0x001a1b14, 0x001b1c16, 0x001b1c16, 0x001a1b15, 0x001a1b15, 0x00171913, 0x00151a13, 0x00141811, 0x00111610, 0x00101411, 0x00101411, 0x00121613, 0x00101512, 0x000e140f, 0x000d140e, 0x000d140e, 0x000c120c, 0x000b110c, 0x0009120c, 0x00081009, 0x0008110a, 0x00070f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x0008110a, 0x0009120c, 0x000a110d, 0x000d1210, 0x00101410, 0x0015140e, 0x001c1510, 0x0020170f, 0x00271b0a, 0x00311f08, 0x0044280c, 0x006f4c14, 0x00aa8628, 0x00c5a524, 0x00cbae20, 0x00ccb017, 0x00cbb310, 0x00ccb410, 0x00ccb410, 0x00cbb50c, 0x00cab408, 0x00cbb508, 0x00cbb508, 0x00ccb112, 0x00b99513, 0x00845b00, 0x00683e04, 0x005a380c, 0x004a310c, 0x00402e0c, 0x003b2a09, 0x003b2a09, 0x003c2b0a, 0x00392808, 0x00372808, 0x00342508, 0x00332307, 0x0033220a, 0x002f220b, 0x00261e08, 0x00201e08, 0x001e1f0b, 0x001b1f0c, 0x00141807, 0x000c1002, 0x000b0d04, 0x000a0d04, 0x000c0e06, 0x000d0f07, 0x000d0f07, 0x00101009, 0x00101008, 0x00141208, 0x00161105, 0x00181203, 0x00221908, 0x00372817, 0x00483421, 0x004c331c, 0x00503218, 0x00543417, 0x00583718, 0x00533310, 0x0050300c, 0x004c2c09, 0x004b2809, 0x004a270b, 0x00482509, 0x004a260a, 0x00492608, 0x004a2709, 0x004c280a, 0x004e290b, 0x004e290c, 0x004d280a, 0x004c2808, 0x00482606, 0x00482505, 0x004b2908, 0x004e2d0b, 0x00502f0c, 0x004c2c08, 0x004b2b08, 0x004d2f0a, 0x0051310f, 0x00492a0b, 0x00402408, 0x003d230c, 0x002d1704, 0x00211000, 0x001c0f04, 0x00191005, 0x00151108, 0x0013120b, 0x00101009, 0x00101008, 0x000e0e06, 0x000e0d04, 0x000e0d04, 0x00100e06, 0x00121207, 0x00161409, 0x00171408, 0x001a160b, 0x001b150b, 0x001c150b, 0x001f170b, 0x00251c0d, 0x0028200d, 0x00281e0a, 0x002c200a, 0x0030220b, 0x00312109, 0x00312109, 0x00302108, 0x00302308, 0x00302206, 0x002d1e04, 0x002d1a03, 0x00321902, 0x00381a01, 0x00381600, 0x00331804, 0x002c1605, 0x00241106, 0x001d0e08, 0x001a0e0c, 0x001a100d, 0x0018100b, 0x00161008, 0x00141108, 0x00131108, 0x00121008, 0x00111108, 0x000e0e05, 0x000d0f07, 0x000c1008, 0x000a0f08, 0x000c120b, 0x000c140d, 0x0008110b, 0x0009130f, 0x00081410, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x00091310, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0004100c, 0x0005100c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100c, 0x0006100c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0007100d, 0x00050f0c, 0x0005100c, 0x0006110d, 0x0006110d, 0x0006110d, 0x0006110d, 0x0007110d, 0x0007110d, 0x00091310, 0x00091310, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x000b130e, 0x000c1410, 0x000d150f, 0x000d160d, 0x00101710, 0x00111810, 0x00111810, 0x00101710, 0x00121711, 0x00131712, 0x00141813, 0x00141914, 0x00141a14, 0x00151c15, 0x00151c15, 0x00161c15, 0x00171c14, 0x00181c15, 0x00181c15, 0x001a1d17, 0x00181c15, 0x00171c17, 0x00161b15, 0x00151a14, 0x00141813, 0x00141614, 0x00111611, 0x00101610, 0x000e160e, 0x000d1410, 0x000c1410, 0x000c140f, 0x000a120e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120c, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120d, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f1612, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x0014180a, 0x001d2009, 0x001d2008, 0x0024250b, 0x00292b0b, 0x002d2f0b, 0x0030310c, 0x0036370c, 0x003b3c0d, 0x0040400d, 0x0045470e, 0x004b4c0f, 0x00505010, 0x00545510, 0x00585911, 0x005c5d12, 0x00786c14, 0x00cca518, 0x00caa419, 0x00b19518, 0x00af9418, 0x00b09418, 0x00b09418, 0x00b09518, 0x00b09518, 0x00b09518, 0x00b09518, 0x00b09518, 0x00b09518, 0x00b09418, 0x00b09418, 0x00af9418, 0x00af9318, 0x00af9318, 0x00af9318, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00ae9117, 0x00ae9117, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00af9218, 0x00af9318, 0x00af9318, 0x00af9418, 0x00b39618, 0x00bc9c18, 0x00c8a519, 0x00cca71a, 0x00cca71a, 0x00c8a419, 0x00a48c17, 0x006d6a14, 0x00646514, 0x00626314, 0x00606013, 0x005c5d11, 0x00595a11, 0x00555610, 0x00525310, 0x004d4e0f, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x0006100b, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00081009, 0x00081009, 0x00060e08, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d06, 0x00040c08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00060e08, 0x0009120b, 0x0008110a, 0x0008110b, 0x0009130c, 0x000c140d, 0x00101711, 0x00101711, 0x00101510, 0x00141612, 0x00141812, 0x00151811, 0x00181a12, 0x00181a14, 0x00191a13, 0x001a1a12, 0x001d1c14, 0x001c1c14, 0x001b1c14, 0x001a1b14, 0x001a1b14, 0x001b1c16, 0x001b1c16, 0x001a1b15, 0x001a1b15, 0x00161913, 0x00151a13, 0x00141811, 0x00111610, 0x00101411, 0x00101411, 0x00101411, 0x000f1310, 0x000d120e, 0x000a130c, 0x000a130c, 0x0008110a, 0x0008110a, 0x00061009, 0x00040f08, 0x00051008, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x00081109, 0x0009120a, 0x000a120c, 0x000d130f, 0x0012140f, 0x0015140e, 0x001c160f, 0x0020160c, 0x00261b08, 0x002d1c04, 0x003c2109, 0x00542f06, 0x00734d04, 0x0099710d, 0x00b68f1d, 0x00be981a, 0x00c5a318, 0x00caaa14, 0x00ccb013, 0x00ccb10e, 0x00ccb208, 0x00ccb208, 0x00ccb00b, 0x00caaa12, 0x00ac8208, 0x00805100, 0x00683e04, 0x0058380b, 0x004a3308, 0x00403008, 0x003f2f09, 0x003f2f0a, 0x00402f0a, 0x003e2c08, 0x003c2b07, 0x003b2807, 0x00382508, 0x00382409, 0x0034250c, 0x002b2109, 0x00241e08, 0x00201f09, 0x001c1f0b, 0x00161b08, 0x00111405, 0x000c0f03, 0x000c0e04, 0x000c0e06, 0x000d0f07, 0x000d0f07, 0x000e1109, 0x000f1009, 0x0012120a, 0x00141208, 0x00151306, 0x00171402, 0x00181100, 0x002d210e, 0x0044301c, 0x004f341c, 0x00523418, 0x00503415, 0x004f3210, 0x004f310e, 0x004b2c0b, 0x0048280a, 0x004c2a0d, 0x004b290c, 0x00472507, 0x00482707, 0x004c2a0a, 0x004b2a09, 0x004b2808, 0x004a2808, 0x00492706, 0x00492805, 0x00472605, 0x00462605, 0x00492b09, 0x004d2f0b, 0x0050320c, 0x004d3009, 0x004b2e0b, 0x004d300e, 0x004b2f10, 0x0041280e, 0x00371e0c, 0x00281102, 0x001e0d00, 0x001a1004, 0x00181106, 0x00181108, 0x0016140b, 0x0012140c, 0x0010120a, 0x00101009, 0x000d0f07, 0x000c0e04, 0x000e0d04, 0x00100e06, 0x00121207, 0x00161406, 0x00161406, 0x00181609, 0x00181808, 0x00201705, 0x00251a05, 0x002c2008, 0x002e2408, 0x002f2207, 0x00332308, 0x0036240b, 0x00352108, 0x00332107, 0x00302005, 0x002f2105, 0x002f2105, 0x002d1e04, 0x002c1b03, 0x002f1905, 0x00301808, 0x002e1408, 0x00271809, 0x00231707, 0x00201609, 0x001c1408, 0x00181105, 0x00171106, 0x00171008, 0x00171009, 0x00141008, 0x00131008, 0x00121008, 0x000f0f05, 0x000e0e04, 0x000c0d05, 0x000b0e05, 0x000a0f08, 0x000c120b, 0x000b130b, 0x0009120b, 0x0009130c, 0x0007120c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008120f, 0x0007100d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100c, 0x0005100c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100c, 0x0006100c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x00040f0c, 0x00050f0c, 0x0006100d, 0x0006110d, 0x0006110d, 0x0005100c, 0x0005100c, 0x0007110d, 0x0007110d, 0x00091310, 0x00091310, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009110c, 0x000a120e, 0x000c140e, 0x000d160d, 0x000f150d, 0x0010160e, 0x0010170f, 0x00101710, 0x00121711, 0x00141813, 0x00141813, 0x00141813, 0x00141a14, 0x00151c15, 0x00151c15, 0x00161c15, 0x00171c14, 0x00181c15, 0x00181c15, 0x001a1d17, 0x00181c15, 0x00171c17, 0x00161b15, 0x00151a14, 0x00151a14, 0x00161815, 0x00141813, 0x00131712, 0x00101710, 0x00101510, 0x000e1510, 0x000d1510, 0x000b130f, 0x0009130e, 0x0008120d, 0x0008120d, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0041420d, 0x0045470e, 0x004b4c0f, 0x00505010, 0x00545511, 0x00585911, 0x005d5e12, 0x006d6813, 0x00bd9c18, 0x00cca61a, 0x00cca71a, 0x00cca71a, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca71a, 0x00cca71a, 0x00cca61a, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca61a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cba61a, 0x00c9a41a, 0x00b59818, 0x00887a16, 0x00686814, 0x00686814, 0x00646514, 0x00626313, 0x00606013, 0x005c5d11, 0x00595a11, 0x00555611, 0x00525310, 0x004d4e0f, 0x00494a10, 0x0045470e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070e0c, 0x00070f0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x00081009, 0x00081009, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00050e08, 0x00091009, 0x0009120c, 0x000b130c, 0x000b150e, 0x000c140e, 0x000c140e, 0x00101610, 0x00131813, 0x00161814, 0x00181814, 0x00181814, 0x00191a14, 0x001b1b14, 0x001d1b14, 0x001c1b14, 0x001b1a14, 0x001e1d16, 0x001e1e18, 0x001c1b16, 0x001a1b15, 0x001a1b15, 0x00181c15, 0x00181c15, 0x00171812, 0x00171812, 0x00111711, 0x00111711, 0x00101610, 0x000e140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000d110d, 0x000b110c, 0x0009120a, 0x00081108, 0x00081008, 0x00081009, 0x0006100a, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00071008, 0x00071007, 0x00071007, 0x00081008, 0x0008110a, 0x000a110b, 0x000d130d, 0x0012140f, 0x0015140e, 0x001b150e, 0x001e140b, 0x00241809, 0x002a1a08, 0x00371d09, 0x00442203, 0x00552e00, 0x00683d00, 0x00764a01, 0x00845801, 0x00946806, 0x00aa800b, 0x00b8910f, 0x00c39e12, 0x00c9a510, 0x00cba814, 0x00cca81a, 0x00bd9410, 0x00946800, 0x00784c02, 0x0064400c, 0x00573a0b, 0x004a3408, 0x00433309, 0x00413209, 0x00413209, 0x00413209, 0x00413208, 0x00423007, 0x003d2d06, 0x003b2b06, 0x00392b08, 0x00352808, 0x002d2406, 0x00261f05, 0x00211e07, 0x00201e0a, 0x001e1d0c, 0x00181709, 0x000c1002, 0x000c0f04, 0x000d0f05, 0x000d0f05, 0x000c0e05, 0x000f1008, 0x000d1008, 0x00101008, 0x0016140b, 0x0017140c, 0x0018140b, 0x00191509, 0x00181002, 0x00241807, 0x00382610, 0x00432f14, 0x00442f13, 0x00472f11, 0x00482d0e, 0x004c2c0e, 0x00482809, 0x004c280b, 0x004d2b0c, 0x004b2b0c, 0x004a2a0b, 0x00462707, 0x00472808, 0x00472808, 0x00482809, 0x00482809, 0x00482809, 0x00482c0c, 0x00472c0c, 0x00482c0c, 0x004b2f0e, 0x004b300c, 0x00503414, 0x00493012, 0x0044290f, 0x003b230c, 0x002e1807, 0x00241204, 0x00201004, 0x001c1106, 0x00181105, 0x00171107, 0x00171008, 0x0014130a, 0x00131209, 0x00101007, 0x00101008, 0x000e0f08, 0x000d0f07, 0x000f0f05, 0x00131107, 0x00161409, 0x00181408, 0x00181407, 0x001a1507, 0x001d1707, 0x00261908, 0x002a1b08, 0x0030200a, 0x00403014, 0x003d2c0c, 0x003d2b09, 0x003e2b05, 0x00402a07, 0x00402a0c, 0x00392307, 0x00352006, 0x00321f06, 0x00301e04, 0x002e1c04, 0x002c1a06, 0x002b1908, 0x00271606, 0x00241705, 0x00221604, 0x00201605, 0x001b1302, 0x00181304, 0x00181106, 0x00181109, 0x0017100a, 0x0016100a, 0x00141109, 0x00121008, 0x00100e05, 0x00100f06, 0x000e0f05, 0x000c0f06, 0x000c1007, 0x000c1108, 0x000a1008, 0x000a1008, 0x0009120c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x00060e0b, 0x0008100c, 0x0008120d, 0x0007110c, 0x0005100b, 0x0007100c, 0x0008100c, 0x0005100b, 0x0006100b, 0x0005110b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f0a, 0x0008110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006110c, 0x0008100c, 0x00050d09, 0x00060f0a, 0x000a120e, 0x0009110d, 0x0008100c, 0x0009130e, 0x0005100b, 0x0008120c, 0x0007110a, 0x0009140c, 0x000a140b, 0x000c150c, 0x000d160d, 0x000f150d, 0x0010160e, 0x00101710, 0x00111812, 0x00131812, 0x00141914, 0x00141914, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161c12, 0x00171c14, 0x00171c14, 0x00171c14, 0x00171c14, 0x00171c17, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161b15, 0x00151a14, 0x00141813, 0x00131712, 0x00101510, 0x000f150f, 0x000e140f, 0x000c140e, 0x000a130c, 0x0009120c, 0x0009120c, 0x0008110a, 0x00070f08, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x0007100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0038380c, 0x003b3c0c, 0x0041420d, 0x0047480f, 0x004c4d0f, 0x00505010, 0x00545511, 0x00595a12, 0x005d5e12, 0x00606013, 0x007d7314, 0x00b09418, 0x00b29618, 0x00b39718, 0x00b39818, 0x00b49819, 0x00b49819, 0x00b49819, 0x00b49819, 0x00b49819, 0x00b49819, 0x00b39819, 0x00b39718, 0x00b39618, 0x00b29618, 0x00b29618, 0x00b19518, 0x00b19518, 0x00b19418, 0x00b19317, 0x00b19317, 0x00b19317, 0x00b09317, 0x00b09317, 0x00b19317, 0x00b19317, 0x00b19317, 0x00b19417, 0x00b19518, 0x00b19518, 0x00b19518, 0x00b29618, 0x00b29618, 0x00b19518, 0x00ad9218, 0x009f8a17, 0x00837815, 0x006c6b14, 0x00696914, 0x00686814, 0x00666714, 0x00656614, 0x00626313, 0x00606013, 0x005c5d11, 0x00595a11, 0x00565711, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070e0c, 0x00070f0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f08, 0x00081009, 0x00081009, 0x00081009, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x0008110a, 0x000a1009, 0x0009130c, 0x000b130c, 0x000b150e, 0x000d150f, 0x000d150f, 0x00101610, 0x00141813, 0x00181814, 0x00181814, 0x00181814, 0x00191b14, 0x001b1b14, 0x001c1c14, 0x001c1b14, 0x001c1b14, 0x001e1d16, 0x001d1e18, 0x001b1c16, 0x001a1b15, 0x001a1b15, 0x00181c15, 0x00181c15, 0x00161812, 0x00161812, 0x00111611, 0x00101711, 0x00101610, 0x000d140e, 0x000d130d, 0x000c130d, 0x000c120c, 0x000b100b, 0x0009110a, 0x00081108, 0x00081108, 0x00081008, 0x00081009, 0x0006100b, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100a, 0x00081009, 0x00081008, 0x00081007, 0x0008110a, 0x0009120c, 0x000a120c, 0x000c120c, 0x0011140f, 0x0015140e, 0x001b150c, 0x001c1409, 0x00221708, 0x0028180a, 0x00311a08, 0x00391c01, 0x00442201, 0x00502c05, 0x00583204, 0x005e3700, 0x00684000, 0x00714800, 0x007b5200, 0x00886001, 0x00966d07, 0x00a2780c, 0x00ab8013, 0x00996e09, 0x007d5200, 0x006c4406, 0x005d3d0d, 0x0054390a, 0x004c3609, 0x0048350a, 0x0048360b, 0x0048360b, 0x0048350a, 0x00483509, 0x00463408, 0x00413106, 0x003c2f06, 0x003b2f08, 0x00372c08, 0x00302705, 0x00272003, 0x00241e05, 0x00221d0a, 0x00201c0c, 0x0018180a, 0x000f1104, 0x000d1004, 0x000f1007, 0x000d0f05, 0x000c0e04, 0x000d0f05, 0x000c1005, 0x00101008, 0x00141109, 0x0017130b, 0x0016140c, 0x0018140b, 0x001c140a, 0x001d1407, 0x00241906, 0x00271803, 0x0033210a, 0x00402a13, 0x00432c10, 0x00472c12, 0x00492c10, 0x0049280b, 0x0048280a, 0x0047280c, 0x0046280c, 0x0045270b, 0x0045280c, 0x0047280c, 0x0048290d, 0x0047280c, 0x0047280c, 0x00442a0d, 0x00442a0e, 0x00432a0d, 0x00442b0e, 0x003c2308, 0x003d240c, 0x00381e09, 0x00311705, 0x002b1404, 0x00241003, 0x00201004, 0x00201408, 0x001d1408, 0x001a1508, 0x00181308, 0x00171008, 0x00151109, 0x00131008, 0x00100e05, 0x00110f07, 0x00100f08, 0x000f0e07, 0x00100e05, 0x00131107, 0x00181408, 0x00191408, 0x001b1407, 0x001e1508, 0x00221809, 0x002a1c0c, 0x002d1d0c, 0x00382411, 0x004b3519, 0x0049300e, 0x004e3209, 0x00533706, 0x00563808, 0x0058390a, 0x004f3305, 0x00452b04, 0x003c2406, 0x00362006, 0x00301d06, 0x002c1c07, 0x00291b08, 0x00261808, 0x00241506, 0x00241508, 0x00221608, 0x001c1404, 0x00191204, 0x00181107, 0x00181109, 0x0017100b, 0x0016100b, 0x0014100a, 0x00121008, 0x00110f07, 0x00110f07, 0x000f0f05, 0x000d0f05, 0x000c1007, 0x000b1007, 0x000b1007, 0x000b1008, 0x000a110b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0009110e, 0x0008100c, 0x0008100b, 0x00071009, 0x00061009, 0x00051109, 0x0008100b, 0x0008100c, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x0006100b, 0x00040f09, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0007100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x0007110c, 0x0006120c, 0x0008120c, 0x0007110a, 0x0008130a, 0x00081308, 0x000a130b, 0x000c150c, 0x000f150d, 0x000d140c, 0x000e150e, 0x00111812, 0x00121812, 0x00141813, 0x00141914, 0x00141914, 0x00161b15, 0x00161b14, 0x00161c12, 0x00161c12, 0x00161c12, 0x00171c14, 0x00171c14, 0x00171c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00161b15, 0x00151a14, 0x00141813, 0x00131712, 0x00101510, 0x000f150f, 0x000d140e, 0x000e150f, 0x000b140d, 0x000a130c, 0x0009120c, 0x0009120c, 0x00081009, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x003b3c0c, 0x0041420d, 0x0047480f, 0x004c4d0f, 0x00505010, 0x00555610, 0x00595a12, 0x005d5e12, 0x00606013, 0x00646314, 0x00686614, 0x006c6914, 0x006d6b14, 0x00706d15, 0x00706e15, 0x00716f16, 0x00716f16, 0x00716f16, 0x00716f15, 0x00706e15, 0x006f6c15, 0x006f6d15, 0x006e6c15, 0x006c6b14, 0x006c6a14, 0x006a6814, 0x00686714, 0x00686614, 0x00656414, 0x00656413, 0x00646312, 0x00646313, 0x00646313, 0x00646312, 0x00646313, 0x00656414, 0x00666514, 0x00686714, 0x00696813, 0x006a6814, 0x006c6a14, 0x006c6a14, 0x00706d14, 0x00706d14, 0x006f6d14, 0x006f6d14, 0x006f6d14, 0x006e6c14, 0x006d6c14, 0x006c6914, 0x006a6814, 0x00686713, 0x00656413, 0x00626011, 0x005e5d11, 0x00565711, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0040400d, 0x003b3c0c, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00031008, 0x00041008, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f0a, 0x00070f0a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x00081009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x0009120c, 0x000a120c, 0x000b140d, 0x000c140e, 0x000c1710, 0x000e1610, 0x000f160f, 0x00111610, 0x00151812, 0x00181914, 0x00181a14, 0x00191a14, 0x001a1b14, 0x001c1c15, 0x001c1d16, 0x001c1d15, 0x001c1d15, 0x001c1c15, 0x001b1c16, 0x001a1b15, 0x00181a14, 0x00181a14, 0x00171913, 0x00161913, 0x00141811, 0x00141811, 0x00101510, 0x000f1510, 0x000e150f, 0x000c140d, 0x000b130c, 0x000a130c, 0x000a120c, 0x00081009, 0x00071008, 0x00081008, 0x00081008, 0x00071007, 0x00071009, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100a, 0x00081008, 0x0008110a, 0x0009120c, 0x000a120c, 0x000c110c, 0x0011130e, 0x0015140d, 0x001a140c, 0x001c1308, 0x001f1408, 0x00241608, 0x002a1809, 0x00311a05, 0x00371c04, 0x003b2108, 0x00402408, 0x00482907, 0x004f2e04, 0x00583405, 0x005a3602, 0x005f3900, 0x00633f00, 0x00694400, 0x00704700, 0x00694200, 0x005c3700, 0x00543201, 0x004e3406, 0x004b3204, 0x004b3104, 0x004c3509, 0x004c3508, 0x004a3407, 0x00483306, 0x00493407, 0x00463408, 0x0047370c, 0x0041340c, 0x0040340c, 0x003c310a, 0x00382b08, 0x002c2204, 0x00281f04, 0x0026200c, 0x00221f0c, 0x001b1b0a, 0x00141508, 0x00101104, 0x000d0f04, 0x000c0d04, 0x000c1005, 0x000c1007, 0x000d1008, 0x00101008, 0x00131008, 0x00141008, 0x0014130a, 0x0018140b, 0x001d160b, 0x0021180b, 0x0023180a, 0x00241505, 0x00241302, 0x00281403, 0x00291701, 0x0034210a, 0x003f2811, 0x0040280d, 0x0041270c, 0x0043280e, 0x0045280f, 0x00462810, 0x00462810, 0x0045280f, 0x0044260d, 0x0041240c, 0x003f2309, 0x003c250c, 0x003a2209, 0x00351d04, 0x00351d04, 0x00301802, 0x002c1401, 0x002c1303, 0x002c1408, 0x002a150a, 0x0027160c, 0x00211408, 0x001f1406, 0x001c1708, 0x001b1608, 0x00191408, 0x00171108, 0x0016120a, 0x00141008, 0x00100e05, 0x00110f07, 0x00100f08, 0x00100f08, 0x00110f06, 0x00151108, 0x00191408, 0x001b1408, 0x001c1307, 0x00201507, 0x00251808, 0x002b1d0b, 0x0032220e, 0x003d2910, 0x004c3410, 0x00593b0b, 0x006c480c, 0x007c5810, 0x00896616, 0x00947020, 0x007e5b0f, 0x00583600, 0x004c2e04, 0x0041280c, 0x00342008, 0x002f1d09, 0x002a1c09, 0x0029190b, 0x00241608, 0x00241409, 0x00211408, 0x001c1305, 0x00191105, 0x00181108, 0x0018110b, 0x0017100b, 0x0016100b, 0x0014100a, 0x00141008, 0x00121008, 0x00110f07, 0x000e0e04, 0x000d0f05, 0x000c1007, 0x000c1108, 0x000c1007, 0x000c0f08, 0x000a0f09, 0x0009100a, 0x0008100c, 0x0008100c, 0x0009110c, 0x000a120e, 0x0008110a, 0x0007100a, 0x00061009, 0x00051109, 0x0008100c, 0x0008100c, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x0006100b, 0x00040e09, 0x0005100a, 0x0007110c, 0x0006110c, 0x0005110b, 0x0006120c, 0x0006120c, 0x0006100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100b, 0x00070f0a, 0x0007110c, 0x0003100a, 0x00061009, 0x00051008, 0x00071208, 0x00081308, 0x0009120a, 0x000a120a, 0x000c130b, 0x000c140c, 0x000c130c, 0x00101610, 0x00111711, 0x00111611, 0x00121712, 0x00131812, 0x00141813, 0x00141912, 0x00151a11, 0x00161c12, 0x00161c12, 0x00171c13, 0x00171c14, 0x00181d16, 0x00181d16, 0x00171c15, 0x00171c15, 0x00171c16, 0x00151a14, 0x00141914, 0x00131712, 0x00111611, 0x00101510, 0x000f150f, 0x000e150f, 0x000c140e, 0x000b140d, 0x000a130c, 0x0009120c, 0x00081009, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x003b3c0c, 0x0041420d, 0x0047480f, 0x004c4d0f, 0x00505010, 0x00545511, 0x00595a12, 0x005d5e12, 0x00756c14, 0x00c29f18, 0x00c2a019, 0x00c2a119, 0x00c2a11a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x009e8918, 0x006a6a14, 0x00686814, 0x00686814, 0x00656614, 0x00646514, 0x00636413, 0x00616112, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00626312, 0x00636413, 0x00646414, 0x00646514, 0x00656614, 0x00686814, 0x006b6914, 0x00bc9c18, 0x00c4a119, 0x00c4a119, 0x00c4a119, 0x00c4a119, 0x00c4a119, 0x00c4a019, 0x00c4a019, 0x00c4a019, 0x00c39f18, 0x00c39e18, 0x00c39e18, 0x00aa8c14, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003b3c0c, 0x0036370c, 0x0032330c, 0x002d2f0a, 0x0026280a, 0x0026280c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00031008, 0x00041008, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x0006100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00050f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x00081009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00081009, 0x0009120c, 0x000b130c, 0x000c140d, 0x000c160f, 0x000c1710, 0x000e1610, 0x00111810, 0x00141911, 0x00181b14, 0x001b1c16, 0x001b1c16, 0x001c1c17, 0x001c1d17, 0x001c1e16, 0x001c1e16, 0x001c1e16, 0x001c1c15, 0x001a1b14, 0x001b1a15, 0x001b1a15, 0x00181913, 0x00171812, 0x00151812, 0x00141710, 0x00141710, 0x00131610, 0x0010140f, 0x000f150f, 0x000c140e, 0x000b130c, 0x0009120c, 0x0008120c, 0x0008120c, 0x00071009, 0x00060f08, 0x00081008, 0x00081008, 0x00071007, 0x00070f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100d, 0x0008100c, 0x0008100c, 0x0008100a, 0x0008110a, 0x0009120c, 0x000a120c, 0x000c110c, 0x0011130e, 0x0014140c, 0x0019140b, 0x001c1208, 0x001e1407, 0x0021140a, 0x0026170c, 0x00291808, 0x002e1b08, 0x00331d0a, 0x00371e0a, 0x003c2008, 0x00412406, 0x00492a07, 0x004a2b05, 0x004c2d04, 0x00513105, 0x00543103, 0x00543004, 0x00543005, 0x00503008, 0x004a2f06, 0x00483306, 0x004f3809, 0x005b3d10, 0x005e4012, 0x005b3e10, 0x00573c0d, 0x004e3304, 0x004c3103, 0x00443104, 0x003f3004, 0x003d3004, 0x0040340b, 0x0041340d, 0x003c2f0b, 0x00332708, 0x002c2004, 0x00282008, 0x0024200c, 0x00201f0c, 0x00181909, 0x00101104, 0x000c0e03, 0x000b0c03, 0x000c1005, 0x000c1007, 0x000d1008, 0x00101007, 0x00131008, 0x00151109, 0x00141109, 0x0018140b, 0x001c150b, 0x0020180c, 0x0023190d, 0x0024190e, 0x0028180e, 0x0029190c, 0x00251708, 0x00231704, 0x00281905, 0x002a1801, 0x002c1700, 0x00361c05, 0x003c230c, 0x003e240e, 0x003f250e, 0x003c230c, 0x003b200a, 0x00381f08, 0x00351c05, 0x00301b04, 0x00311b04, 0x002f1902, 0x002d1800, 0x002c1600, 0x002d1804, 0x002c1807, 0x00291406, 0x002b180f, 0x0027180f, 0x00211608, 0x001f1506, 0x001d1707, 0x001a1508, 0x00181308, 0x00181108, 0x0016120a, 0x00141008, 0x00100e05, 0x00110f07, 0x00100f08, 0x00111009, 0x00140f07, 0x00181207, 0x00191408, 0x001b1406, 0x001f1406, 0x00221706, 0x00261808, 0x002d2008, 0x0037280a, 0x0046300c, 0x00583c0c, 0x008a6825, 0x00aa872d, 0x00b9982b, 0x00c6a62c, 0x00c8a62d, 0x00b48b21, 0x00785001, 0x00553400, 0x00462908, 0x0038240c, 0x00311f09, 0x002c1c09, 0x002a1b0a, 0x00261808, 0x00241507, 0x00201404, 0x001b1302, 0x00181204, 0x00181106, 0x0018110b, 0x0017100c, 0x0016100b, 0x00151009, 0x00141008, 0x00121008, 0x00111008, 0x00101007, 0x000f1007, 0x000d1008, 0x000c1108, 0x000c1007, 0x000c0f08, 0x000b0e09, 0x000a0f09, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100c, 0x0008110b, 0x0007110a, 0x00061009, 0x00051109, 0x0008110c, 0x0008100c, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x0006100b, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0005110b, 0x0006120c, 0x0007130c, 0x0006100a, 0x00060e09, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00060e09, 0x0006100b, 0x00030f09, 0x00051008, 0x00051008, 0x00061108, 0x00061106, 0x00081008, 0x00081108, 0x000b110a, 0x000c120b, 0x000c120c, 0x00101610, 0x00101610, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00121710, 0x00141810, 0x00161c12, 0x00161c12, 0x00161c12, 0x00171c13, 0x00181d15, 0x00181d15, 0x00181d15, 0x00171c14, 0x00171c17, 0x00161b15, 0x00151a14, 0x00141813, 0x00131712, 0x00101711, 0x00101610, 0x000f1610, 0x000e1610, 0x000c140d, 0x000a130c, 0x0009120c, 0x00081009, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x003b3c0c, 0x0041420d, 0x0047480f, 0x004c4d0f, 0x00505010, 0x00545511, 0x00585911, 0x005d5e12, 0x00786d14, 0x00cca519, 0x00cca619, 0x00cca71a, 0x00cca71a, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00a48c18, 0x00696914, 0x00686814, 0x00666714, 0x00646514, 0x00636413, 0x00616112, 0x00606013, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00616112, 0x00636413, 0x00646414, 0x00646514, 0x00656614, 0x006b6814, 0x00c4a119, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca61a, 0x00cca619, 0x00cca619, 0x00cca519, 0x00cca418, 0x00cca418, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003b3c0c, 0x0036370b, 0x0034350c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00041008, 0x00041008, 0x00051009, 0x00051009, 0x00051009, 0x00051009, 0x0006100a, 0x0006100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00070f09, 0x00070f09, 0x0008100a, 0x0008100a, 0x00081009, 0x00071008, 0x00071008, 0x00071008, 0x00070f08, 0x00070f08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00070f08, 0x0008110b, 0x0009130c, 0x000c140d, 0x000c150e, 0x000c1710, 0x000c180f, 0x00101912, 0x00131a12, 0x00161b14, 0x00181c15, 0x001c1c17, 0x001d1c17, 0x001d1d17, 0x001d1d16, 0x001d1d16, 0x001d1d16, 0x001d1d16, 0x001c1c15, 0x001a1a13, 0x001b1a15, 0x001b1a15, 0x00181813, 0x00151811, 0x00141711, 0x00131611, 0x00111510, 0x0010140f, 0x000f150f, 0x000d140e, 0x000b130c, 0x000a120c, 0x0008110b, 0x0008110b, 0x0008110a, 0x00071009, 0x00060f08, 0x0006100a, 0x0007100a, 0x0006100a, 0x0006100a, 0x0005100a, 0x00051009, 0x00040f08, 0x00040f08, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0007100b, 0x0007100c, 0x0007100b, 0x0007100b, 0x0007100a, 0x0008110b, 0x000a120c, 0x000c110b, 0x0010130c, 0x0013140b, 0x0017140a, 0x00191408, 0x001b1408, 0x0020150c, 0x0023160c, 0x0026180c, 0x002a190b, 0x002d1a0a, 0x00301b09, 0x00341c07, 0x00371e04, 0x003d2207, 0x00402308, 0x0044270b, 0x00472b0c, 0x00482c0b, 0x00482c0b, 0x00482e0c, 0x004b320e, 0x004d3410, 0x0052370f, 0x00644612, 0x006e4c0c, 0x006b4805, 0x006c480c, 0x00644308, 0x005f3f08, 0x00543404, 0x00443000, 0x003c2c00, 0x00392b00, 0x003c2e07, 0x00433611, 0x003f300d, 0x00382a09, 0x002f2303, 0x00292005, 0x0025210a, 0x0024220e, 0x001c1c0a, 0x00121404, 0x000c0f02, 0x000b0d04, 0x000c0f05, 0x000b0f06, 0x000c1008, 0x00101008, 0x0013100a, 0x0016110b, 0x0014110a, 0x0018140c, 0x001c140b, 0x0020180c, 0x00231a0f, 0x00241a0e, 0x00281c0f, 0x002b1d0f, 0x002b1c0c, 0x002d1f0c, 0x002c1e0a, 0x002c1d07, 0x002f1a04, 0x00301701, 0x00321903, 0x00321a04, 0x00341c05, 0x00341b05, 0x00301803, 0x00331c06, 0x00341d07, 0x00301905, 0x00321b07, 0x00341c08, 0x00331b06, 0x00301b04, 0x00301b07, 0x002c1807, 0x002c1808, 0x002c190e, 0x0028180e, 0x00241709, 0x00201607, 0x001e1607, 0x001b1407, 0x00191308, 0x00181008, 0x00141008, 0x00141008, 0x00121008, 0x00121008, 0x00111008, 0x00121008, 0x00141007, 0x00181207, 0x001a1407, 0x001b1204, 0x00201704, 0x00241a07, 0x00281c08, 0x00322309, 0x003d2b09, 0x0050360a, 0x00715114, 0x00b7983a, 0x00c9ae30, 0x00ccb321, 0x00ccb41b, 0x00ccb11b, 0x00c3a01f, 0x00876002, 0x005c3500, 0x004e2f0b, 0x003e280b, 0x0035220b, 0x002c1c06, 0x002a1b09, 0x00251705, 0x00241604, 0x00201404, 0x001b1202, 0x00191104, 0x00181106, 0x00181109, 0x0017100a, 0x00151009, 0x00141008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00101008, 0x000f1008, 0x000d1008, 0x000c0d07, 0x000c0e08, 0x000c0f08, 0x000a100a, 0x0008100b, 0x0007100b, 0x0006100b, 0x0007100c, 0x0008100a, 0x00081009, 0x00071009, 0x00061009, 0x0007100b, 0x0007100b, 0x0006100b, 0x0007100c, 0x0007100b, 0x00060f0a, 0x0007100b, 0x0007100b, 0x0007100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0007110c, 0x0006100c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100b, 0x0007110c, 0x0007120c, 0x0005100a, 0x00060f0a, 0x0006100b, 0x0006100b, 0x0006100b, 0x00050f0a, 0x00040d08, 0x0005100a, 0x0005100a, 0x0006100a, 0x0006100a, 0x0007110a, 0x00071109, 0x00071008, 0x00071008, 0x0008120b, 0x000a120b, 0x000a120c, 0x000e150f, 0x000f1610, 0x00101610, 0x00101610, 0x00111410, 0x00111410, 0x00121510, 0x00121510, 0x00141812, 0x00151a14, 0x00151a14, 0x00151b14, 0x00181c14, 0x00191d15, 0x00191c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00171b15, 0x00161913, 0x00141812, 0x00131711, 0x00121610, 0x00101610, 0x000f160f, 0x000d140e, 0x000c140d, 0x000b130c, 0x0008110b, 0x0009110c, 0x0009110c, 0x0008110b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008110c, 0x0008110c, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0007100b, 0x0007100b, 0x0007100c, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x004b4c0f, 0x00505010, 0x00545511, 0x00585910, 0x005c5d12, 0x00786c14, 0x00cca518, 0x00c8a418, 0x008b7c16, 0x00897c16, 0x00897c17, 0x00887c16, 0x00887c16, 0x00887c16, 0x00887c17, 0x00867b16, 0x00b19618, 0x00cca71a, 0x00a48c17, 0x00686814, 0x00666714, 0x00646514, 0x00636413, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005c5d11, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00616112, 0x00636413, 0x00646414, 0x00656614, 0x006a6814, 0x00c4a019, 0x00cca71a, 0x00958316, 0x00887c15, 0x00887a16, 0x00867915, 0x00857816, 0x00847714, 0x00827514, 0x00807414, 0x00998315, 0x00c9a218, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x00292b0b, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x00071007, 0x00071007, 0x00071007, 0x00071008, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x0009120c, 0x000a140c, 0x000c140e, 0x000c1710, 0x000c1710, 0x000d180f, 0x00131b12, 0x00131a13, 0x00171c15, 0x00191c16, 0x001c1b16, 0x001c1c17, 0x001e1c16, 0x001e1d16, 0x001e1d16, 0x001d1d16, 0x001d1d16, 0x001c1c14, 0x001b1912, 0x001b1a15, 0x001b1a15, 0x00171813, 0x00141810, 0x00101610, 0x00101610, 0x000f1610, 0x000c140e, 0x000c140e, 0x000b130c, 0x0009120b, 0x0008100a, 0x00080f09, 0x00080f09, 0x00071008, 0x00070f08, 0x00060f09, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00061009, 0x00040f08, 0x00040f07, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x00061009, 0x0009120b, 0x000b130c, 0x000b1109, 0x000e1109, 0x00101208, 0x00131208, 0x00151308, 0x00181408, 0x001e150c, 0x001f1409, 0x0024180b, 0x0027180b, 0x002a180a, 0x002c1909, 0x00301c09, 0x00301c06, 0x00371f08, 0x003b200a, 0x003d2309, 0x003e260b, 0x003f280c, 0x0040290d, 0x00432c0c, 0x0048340e, 0x00503612, 0x00624115, 0x008d6d2c, 0x00a4842c, 0x00a07e1d, 0x008f6a13, 0x00815d08, 0x00745004, 0x00654204, 0x00573d03, 0x00483404, 0x003d2c01, 0x00342603, 0x003c300d, 0x003f3010, 0x00392b09, 0x00342604, 0x002b2105, 0x00282108, 0x0027230c, 0x00201e0a, 0x00151605, 0x000c1002, 0x000b0e04, 0x000c0f06, 0x000a0f06, 0x000c1007, 0x000f0f08, 0x0014100b, 0x0018120c, 0x0014110b, 0x0018140c, 0x001a130a, 0x001e170c, 0x0022190e, 0x00241a0d, 0x00281c0c, 0x002c1e0d, 0x002c1c0a, 0x002e1d0c, 0x00301f0c, 0x0032200a, 0x00331f08, 0x00372008, 0x0038210a, 0x0039230c, 0x003c260e, 0x003c260f, 0x0038240c, 0x003a230d, 0x0038220c, 0x0038200b, 0x0038200c, 0x0039200c, 0x00341a07, 0x00341c08, 0x00311b07, 0x002c1706, 0x00291808, 0x002a180c, 0x0028170b, 0x00251709, 0x00221508, 0x001f1407, 0x001c1407, 0x001a1308, 0x00181008, 0x00140e08, 0x00131008, 0x00131008, 0x00121008, 0x00131008, 0x00121008, 0x00151108, 0x00181308, 0x001b1407, 0x001d1606, 0x00221c08, 0x00241c06, 0x00281e06, 0x0035260c, 0x00442f0c, 0x00583c0c, 0x007c5a15, 0x00bfa034, 0x00cbb424, 0x00ccb713, 0x00cab810, 0x00cab714, 0x00c4ab1b, 0x00906a01, 0x00643c00, 0x00503208, 0x00422d08, 0x0039260a, 0x00301f04, 0x002b1c08, 0x00271805, 0x00241605, 0x00201406, 0x001c1104, 0x001a1105, 0x00181108, 0x00181009, 0x00171009, 0x00141109, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00111108, 0x000e1008, 0x000e0f08, 0x000f100a, 0x000f100a, 0x000c1009, 0x000a100a, 0x0007100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0009100a, 0x00081009, 0x00081009, 0x00071009, 0x0006100a, 0x0006100b, 0x0007100b, 0x0008100c, 0x0007100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100b, 0x0007110c, 0x0007110c, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x00061009, 0x00061009, 0x00061108, 0x00081109, 0x000c140d, 0x000c140e, 0x000c140e, 0x000f140f, 0x0010140f, 0x0010140f, 0x00121511, 0x00121611, 0x00131712, 0x00151a14, 0x00151a14, 0x00151a14, 0x00181a14, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181c15, 0x00181c15, 0x00181c15, 0x00171913, 0x00171812, 0x00161812, 0x00141811, 0x0012160f, 0x0010140e, 0x000d140e, 0x000d140e, 0x000c140d, 0x0008120c, 0x0009120c, 0x0009120c, 0x0008110a, 0x0008100b, 0x0008100d, 0x0008100d, 0x0007110d, 0x0006110d, 0x0008120d, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x0041420d, 0x0045470e, 0x004b4c0f, 0x004f5010, 0x00545510, 0x00585811, 0x005c5c12, 0x00776c14, 0x00cca518, 0x00c6a219, 0x006b6814, 0x006a6a14, 0x006b6b14, 0x006c6c15, 0x006c6c15, 0x006d6d15, 0x006c6c15, 0x006a6a14, 0x00a99018, 0x00cca71a, 0x00a38b18, 0x00666714, 0x00656614, 0x00636414, 0x00616112, 0x00606013, 0x005d5e12, 0x005c5d11, 0x005c5c11, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x00606013, 0x00616112, 0x00636413, 0x00646414, 0x00686614, 0x00c4a019, 0x00cca61a, 0x007c7315, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00646414, 0x00626313, 0x00887814, 0x00c8a218, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00050f08, 0x00050f08, 0x00050f08, 0x00051008, 0x00051008, 0x00051008, 0x00050f09, 0x00050f0a, 0x00040f0a, 0x0004100a, 0x0004100a, 0x0004100a, 0x00050f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081008, 0x00071007, 0x00071007, 0x00071008, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00071009, 0x0008110a, 0x000a130c, 0x000c140e, 0x000e150f, 0x000f1610, 0x000f1610, 0x00111911, 0x00141b13, 0x00141b12, 0x00181c14, 0x001b1d16, 0x001c1c16, 0x001d1c16, 0x001e1c16, 0x001e1d16, 0x001d1d16, 0x001c1e16, 0x001c1d16, 0x001a1b14, 0x00181912, 0x00191914, 0x00191a14, 0x00151812, 0x00111610, 0x000f1610, 0x000f150f, 0x000d150f, 0x000c140d, 0x0008120c, 0x0008120b, 0x00071009, 0x00071008, 0x00060f08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060f09, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00061009, 0x00040f08, 0x00040f07, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100a, 0x000a130c, 0x000c140d, 0x000c110a, 0x000d1008, 0x000f1007, 0x00111006, 0x00131107, 0x00161307, 0x001b1208, 0x001c1307, 0x00211609, 0x00231608, 0x00251708, 0x0028180a, 0x002c1c0a, 0x002e1e08, 0x00311c06, 0x00341d07, 0x00361f08, 0x00382209, 0x003b250c, 0x003d270c, 0x00432c0d, 0x0048330b, 0x00543b0e, 0x00705118, 0x00b0923d, 0x00caae3d, 0x00c8ac2b, 0x00c4a528, 0x00b8981f, 0x00ac881a, 0x0094700f, 0x006d4e00, 0x00543901, 0x00443004, 0x00382806, 0x00342504, 0x003c2e0d, 0x003b2c0b, 0x00362807, 0x002d2203, 0x002a2006, 0x002a230b, 0x00242009, 0x00181806, 0x000d1002, 0x000c0f04, 0x000b0f06, 0x000a0f07, 0x000c1008, 0x000e0e07, 0x00141009, 0x0018110c, 0x0014110b, 0x0018130c, 0x00191209, 0x001c150b, 0x0021180c, 0x0024180c, 0x00281c0c, 0x002b1e0d, 0x002d1c0b, 0x002e1d0c, 0x002e1d0a, 0x002e1d06, 0x00321c06, 0x00382008, 0x0039210b, 0x00382008, 0x003a230b, 0x003d250c, 0x00392108, 0x003c240c, 0x003c240c, 0x003a220b, 0x0039200a, 0x003a210a, 0x00381e09, 0x00341c08, 0x00321b07, 0x002e1908, 0x002a1707, 0x00281508, 0x00271509, 0x00251609, 0x00221407, 0x00201406, 0x001c1406, 0x001a1208, 0x00171008, 0x00140f08, 0x00131008, 0x00131008, 0x00121008, 0x00131008, 0x00131008, 0x00171108, 0x001a1408, 0x001c1408, 0x00221a0a, 0x0028200d, 0x00271e08, 0x00281e06, 0x0038280d, 0x0048320d, 0x005c3e0d, 0x00836018, 0x00c3a236, 0x00ccb421, 0x00cbb710, 0x00cab80c, 0x00cab80f, 0x00c7ae18, 0x00987303, 0x00684000, 0x00543707, 0x00443006, 0x003b2608, 0x00342304, 0x002d1c05, 0x002b1c08, 0x00241806, 0x00201406, 0x001c1104, 0x001a1105, 0x00181108, 0x00181009, 0x00181009, 0x00141008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00141008, 0x0014130a, 0x000e0f08, 0x000f1008, 0x0010100b, 0x0010100b, 0x000c0f08, 0x000b1009, 0x0007100a, 0x0006100a, 0x0006100a, 0x0008110c, 0x0009100a, 0x00081009, 0x00080f09, 0x00061009, 0x0006100a, 0x0006100b, 0x0007100b, 0x0008100b, 0x0006100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0006100b, 0x0006100b, 0x00050f0a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x00061009, 0x00061009, 0x00061008, 0x00071008, 0x000a120c, 0x000b140d, 0x000c140e, 0x000c140e, 0x000f140f, 0x0010150f, 0x00101610, 0x00101610, 0x00121712, 0x00141914, 0x00151a14, 0x00151a14, 0x00181a14, 0x00181c15, 0x00191c16, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181a14, 0x00171813, 0x00171813, 0x00151811, 0x0012160f, 0x0010140e, 0x000e140f, 0x000e140f, 0x000c140e, 0x0009130c, 0x0009120c, 0x0009120c, 0x0008110a, 0x0008100b, 0x0008100d, 0x0008100d, 0x0007100d, 0x0006110d, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002d2f0b, 0x0030310c, 0x0036370c, 0x003b3c0d, 0x0040400d, 0x0045470e, 0x00494a0f, 0x004f5010, 0x00535410, 0x00585811, 0x005c5c12, 0x00776c14, 0x00cca518, 0x00c6a118, 0x006a6714, 0x00696914, 0x006a6a14, 0x006b6b14, 0x006c6c15, 0x006c6c15, 0x006c6c14, 0x00686814, 0x00a99017, 0x00cca71a, 0x00a38b17, 0x00646514, 0x00646414, 0x00616113, 0x00606013, 0x005d5e12, 0x005c5c11, 0x005b5b12, 0x00595a12, 0x00585911, 0x00585911, 0x00585911, 0x00585911, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00616112, 0x00636413, 0x00686514, 0x00c3a018, 0x00cca619, 0x007c7114, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00646514, 0x00646414, 0x00616112, 0x00887814, 0x00c8a217, 0x00b09015, 0x00525311, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e06, 0x00060e06, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00070f0a, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081008, 0x00081008, 0x00081008, 0x00081008, 0x00081009, 0x00081009, 0x00081009, 0x0008110a, 0x0009120b, 0x000a130c, 0x000c140d, 0x000d140e, 0x00101510, 0x00111610, 0x00121812, 0x00141a13, 0x00151a13, 0x00171a11, 0x00191c14, 0x001d1f17, 0x001e1c15, 0x001d1c15, 0x001e1d16, 0x001d1d17, 0x001c1d17, 0x001b1e16, 0x001b1e15, 0x00181c14, 0x00171810, 0x00161812, 0x00151812, 0x00111610, 0x0010160e, 0x000c150f, 0x000c140d, 0x000b140d, 0x0008110b, 0x0007110a, 0x0007110a, 0x00061009, 0x00061009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060f09, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00061009, 0x00040f08, 0x00040f07, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110c, 0x0009110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007100a, 0x0009110b, 0x000a120c, 0x000b1109, 0x000c1006, 0x000e0f05, 0x00121107, 0x00131107, 0x00151307, 0x00191208, 0x001b1307, 0x001f1508, 0x001e1404, 0x00201408, 0x0024180b, 0x00271908, 0x002b1c08, 0x002f1c07, 0x00311e08, 0x00321f08, 0x0034210b, 0x003a250e, 0x003c260c, 0x00432d0c, 0x004a350b, 0x00583e0a, 0x00795c13, 0x00bba038, 0x00ccb42a, 0x00ccb818, 0x00ccb612, 0x00c8b111, 0x00cbb01b, 0x00c4a41e, 0x0099750e, 0x00674700, 0x004c3400, 0x003d2c05, 0x00342504, 0x00302100, 0x003c2d0c, 0x003a2c0a, 0x00302403, 0x002e2406, 0x002c2309, 0x00272008, 0x001e1b07, 0x00101406, 0x000d1007, 0x000a0f06, 0x000a0f08, 0x000c1008, 0x000d0f07, 0x00100f08, 0x0016100b, 0x0014100b, 0x00161109, 0x001a120a, 0x001c140a, 0x0020170c, 0x0021170a, 0x00261b0b, 0x00291c0b, 0x002e1d0c, 0x002f1e0c, 0x002e1d0b, 0x00301f08, 0x00342009, 0x003a230c, 0x003b230c, 0x003a230a, 0x003c240c, 0x003e250c, 0x003c230a, 0x003d2409, 0x003f250b, 0x003a2109, 0x00381f07, 0x00381f06, 0x00371d05, 0x00341c05, 0x00301a06, 0x002f1a08, 0x002c1909, 0x00281608, 0x00261508, 0x00241608, 0x00211406, 0x001f1306, 0x001b1305, 0x00181108, 0x00170f07, 0x00151008, 0x00131008, 0x00131008, 0x00121008, 0x00121008, 0x00141109, 0x00181309, 0x001c1408, 0x001c1608, 0x00241c0a, 0x002f2711, 0x00291f08, 0x002a1d05, 0x0039290c, 0x0048330a, 0x005d400b, 0x00836017, 0x00c0a030, 0x00ccb420, 0x00cbb80e, 0x00cab80b, 0x00cab80c, 0x00cab215, 0x00a17d05, 0x006e4700, 0x00563804, 0x00483104, 0x003c2704, 0x00372402, 0x002f1d04, 0x002c1c08, 0x00261808, 0x00211406, 0x001d1204, 0x001a1105, 0x00181108, 0x00181009, 0x00161008, 0x00141008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00141008, 0x00141109, 0x00100f08, 0x000f1008, 0x000f100a, 0x000f100a, 0x000d1009, 0x00090f08, 0x00060f08, 0x00070f08, 0x00061009, 0x0008120c, 0x000a100a, 0x00080f08, 0x00070f08, 0x00061008, 0x00051009, 0x0005100a, 0x0006100a, 0x0007100b, 0x0006100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040f09, 0x00040f09, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00040e09, 0x00040f08, 0x00051008, 0x00051008, 0x00071008, 0x0008110b, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c130d, 0x000d140e, 0x00101610, 0x00101610, 0x00111611, 0x00131712, 0x00141814, 0x00141814, 0x00171913, 0x00171913, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181b14, 0x00181a14, 0x00181913, 0x00151811, 0x00121610, 0x0010150e, 0x00101610, 0x00101610, 0x000d150f, 0x000a140d, 0x000a130c, 0x000a130c, 0x0008110b, 0x0008100a, 0x0008100d, 0x0008100d, 0x0006100c, 0x0005100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0006100b, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x0024250b, 0x00292b0b, 0x002d2f0b, 0x0030310c, 0x0036370c, 0x003b3c0d, 0x0040400e, 0x0045470e, 0x00494a10, 0x004d4e0f, 0x00525310, 0x00565711, 0x005b5b12, 0x00766a13, 0x00cca418, 0x00c6a118, 0x00696614, 0x00686814, 0x00696914, 0x006a6a14, 0x006a6a14, 0x006a6a14, 0x006a6a14, 0x00686814, 0x00a99017, 0x00cca61a, 0x00a28a16, 0x00636414, 0x00626313, 0x00606013, 0x005d5e12, 0x005c5c11, 0x00595a12, 0x00585911, 0x00585810, 0x00565710, 0x00565710, 0x00565710, 0x00565710, 0x00585810, 0x00585911, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00616112, 0x00656314, 0x00c3a018, 0x00cca619, 0x007a7014, 0x00656613, 0x00656613, 0x00656614, 0x00656614, 0x00646514, 0x00626313, 0x00606012, 0x00887814, 0x00c8a217, 0x00b09015, 0x00515110, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e06, 0x00060e06, 0x00060e08, 0x00040f08, 0x00040f08, 0x00030f08, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00080f0a, 0x0008100b, 0x0008100b, 0x00060e0a, 0x00040d08, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x0008100a, 0x000c140e, 0x000d140e, 0x000f140f, 0x0010150f, 0x00111610, 0x00131812, 0x00151813, 0x00171913, 0x00161b14, 0x00181b13, 0x001c1c15, 0x001f1e16, 0x001e1c15, 0x001e1c15, 0x001e1d16, 0x001c1d17, 0x001c1d17, 0x00191e16, 0x00181d15, 0x00161c13, 0x00141811, 0x00111610, 0x00101610, 0x000e170e, 0x000c170e, 0x000a140d, 0x0009140c, 0x0008110b, 0x00061009, 0x00061009, 0x0007110a, 0x00061009, 0x00061009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060f09, 0x0006100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00061009, 0x00050f08, 0x00050f08, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0007100a, 0x0008100a, 0x0009110a, 0x000b1008, 0x000b0f06, 0x000d1006, 0x00111108, 0x00121107, 0x00141207, 0x00181207, 0x00191306, 0x001b1306, 0x001b1104, 0x001d1308, 0x00201508, 0x00231808, 0x00261907, 0x00281806, 0x002c1b06, 0x002f1d06, 0x00332009, 0x0038250c, 0x003b270b, 0x0044300c, 0x004d380b, 0x005d440c, 0x00836618, 0x00baa12e, 0x00ccb720, 0x00cbba09, 0x00cbbb05, 0x00cbbb07, 0x00ccb80c, 0x00ccb518, 0x00b79618, 0x00755400, 0x00543a00, 0x00443203, 0x00382a04, 0x002c1c00, 0x00392b0a, 0x003d300c, 0x00372b08, 0x00312807, 0x002f2608, 0x00282006, 0x0024200b, 0x00171608, 0x00101106, 0x000c0f06, 0x000a0f08, 0x000c1007, 0x000d1007, 0x00100f08, 0x00141009, 0x0014110b, 0x00161109, 0x00191209, 0x001c140a, 0x001f150a, 0x00201608, 0x00251909, 0x00281a0b, 0x002c1c0c, 0x002f1d0c, 0x002e1d0b, 0x0032200a, 0x0038240c, 0x003a220c, 0x003a220c, 0x003b230b, 0x003d240c, 0x003e250c, 0x003e250b, 0x003d2309, 0x003d2309, 0x00392008, 0x00371e06, 0x00381f08, 0x00371e08, 0x00341b06, 0x00301805, 0x002d1806, 0x002e1b09, 0x002b180a, 0x00261607, 0x00251608, 0x00211406, 0x00201406, 0x001c1306, 0x00191108, 0x00170f08, 0x00151008, 0x00141008, 0x00131008, 0x00121008, 0x00121008, 0x00141008, 0x0019140a, 0x001e170a, 0x001f1807, 0x0028200c, 0x00352c14, 0x00291e05, 0x002b1d03, 0x0039290a, 0x00483309, 0x005c3f0b, 0x00805d13, 0x00bc9c2c, 0x00cab41d, 0x00cbb80c, 0x00cab908, 0x00cab80a, 0x00cab314, 0x00a88408, 0x00754e00, 0x00573a00, 0x00483303, 0x003e2804, 0x00372401, 0x00301e03, 0x002c1c08, 0x00261808, 0x00221608, 0x001e1407, 0x001a1105, 0x00171208, 0x00161008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00140f08, 0x00110f06, 0x00100f08, 0x000f1008, 0x000f100a, 0x000f1009, 0x000f120b, 0x00080d06, 0x00080f08, 0x00070f08, 0x00071009, 0x0008120b, 0x0008110a, 0x00080f08, 0x00060f08, 0x00061008, 0x00051009, 0x0006100a, 0x0006100a, 0x0008100c, 0x0009120d, 0x0009110c, 0x0009110c, 0x0009110c, 0x0009110c, 0x0009110c, 0x0009110c, 0x0008100b, 0x0008100b, 0x0005100c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0007100c, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040d08, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00040f08, 0x00051008, 0x00051007, 0x00061008, 0x0008100a, 0x0009120c, 0x0009120c, 0x000a130c, 0x000c130d, 0x000c130d, 0x000e150f, 0x00101610, 0x00101510, 0x00121712, 0x00141812, 0x00141812, 0x00161913, 0x00171913, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181b14, 0x00171a14, 0x00141812, 0x00131710, 0x00111610, 0x00101610, 0x00101610, 0x000e150f, 0x000c140e, 0x000b140d, 0x000a130c, 0x0009120b, 0x00081009, 0x0008100c, 0x0008100c, 0x0006100c, 0x0005100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x0040400d, 0x0044450e, 0x00494a10, 0x004d4e0f, 0x00515110, 0x00555610, 0x00595a11, 0x00756a13, 0x00cca418, 0x00c6a118, 0x00686514, 0x00666714, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00656614, 0x00a88f17, 0x00cca619, 0x00a28917, 0x00616113, 0x00606013, 0x005e5f13, 0x005c5c11, 0x00595a12, 0x00585810, 0x00585810, 0x00555610, 0x00545511, 0x00545511, 0x00545511, 0x00545511, 0x00555611, 0x00565710, 0x00585911, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00646113, 0x00c3a018, 0x00cca519, 0x007a7014, 0x00646514, 0x00656614, 0x00646514, 0x00646514, 0x00636414, 0x00626312, 0x00606013, 0x00887714, 0x00c8a117, 0x00b09015, 0x00515110, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040e07, 0x00020e07, 0x00020e07, 0x00020e08, 0x00020e08, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081009, 0x00081009, 0x0008110a, 0x0008110a, 0x000c130d, 0x000f150f, 0x0010140f, 0x00111510, 0x00141810, 0x00151912, 0x00181813, 0x00181913, 0x00181c13, 0x001a1d14, 0x001d1c15, 0x00201c14, 0x001f1c14, 0x001f1c14, 0x001e1c17, 0x001c1c17, 0x001a1d17, 0x00171b14, 0x00151812, 0x00141912, 0x00121911, 0x00101811, 0x000e1610, 0x000c160f, 0x0008150d, 0x0009140c, 0x0008120b, 0x00051008, 0x00051008, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00081009, 0x00081009, 0x00081009, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0006100b, 0x0007100c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0009100b, 0x000a100a, 0x000a1009, 0x00091007, 0x00091006, 0x000b1007, 0x000e1108, 0x00101108, 0x00121006, 0x00151005, 0x00161006, 0x00181105, 0x001a1307, 0x001c1408, 0x001c1408, 0x00201608, 0x00241809, 0x00261809, 0x00291b08, 0x002c1d07, 0x00312006, 0x00382508, 0x003c2809, 0x0046300b, 0x00503a0a, 0x005f460c, 0x00846819, 0x00bda432, 0x00ccb81e, 0x00ccbc09, 0x00cbbc09, 0x00cbbc0a, 0x00caba0c, 0x00cbb910, 0x00b79c0f, 0x00795800, 0x00573c00, 0x00453400, 0x00392c02, 0x002e2000, 0x00382908, 0x003f330d, 0x003b3009, 0x00352c08, 0x00302808, 0x002c2409, 0x00271e08, 0x001f1705, 0x00141104, 0x000d0f07, 0x000b1008, 0x000c1007, 0x000d1007, 0x00101008, 0x00101008, 0x0014110b, 0x00161109, 0x00181108, 0x001b1308, 0x001e1409, 0x00201608, 0x00231809, 0x0028180a, 0x002b1a0a, 0x002e1c0c, 0x00311e0c, 0x00321f09, 0x00341d07, 0x00372008, 0x0039210a, 0x003a220c, 0x003c250e, 0x003e240c, 0x003f250d, 0x003c240a, 0x003c2309, 0x00382008, 0x0038200a, 0x00371f0c, 0x00361e0e, 0x00371c0c, 0x00331a08, 0x00301a08, 0x002e1b08, 0x002c1a08, 0x00281706, 0x00261808, 0x00231507, 0x00201407, 0x001d1407, 0x001b1108, 0x00181008, 0x00171009, 0x00141109, 0x00141109, 0x00131008, 0x00121009, 0x00141008, 0x001a150b, 0x001e1809, 0x00201806, 0x002b210c, 0x00382d14, 0x00281c02, 0x002f2004, 0x003a2808, 0x0048330a, 0x005a3c09, 0x007e5b13, 0x00bc9c2c, 0x00c9b21c, 0x00cbb80c, 0x00cab908, 0x00cab808, 0x00cbb314, 0x00ae880b, 0x00775100, 0x00583b00, 0x004a3401, 0x003f2a04, 0x00382401, 0x00301f04, 0x002d1c08, 0x00271807, 0x00241506, 0x00201307, 0x00181105, 0x00171208, 0x00171109, 0x00141008, 0x00141009, 0x00151109, 0x00151109, 0x00151109, 0x00151109, 0x00141008, 0x00131008, 0x00101009, 0x00101009, 0x00100f08, 0x00100f08, 0x000f1009, 0x000a0f06, 0x000a0f08, 0x00091008, 0x00081008, 0x00071208, 0x0008110a, 0x00061008, 0x00061009, 0x00051109, 0x0008100b, 0x0008100c, 0x0006100a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0009100c, 0x0007110c, 0x0005100a, 0x0007110c, 0x0007110c, 0x0006100b, 0x0008120d, 0x0005100a, 0x0005100a, 0x0005100b, 0x0006100b, 0x0005100b, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00040f09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051008, 0x00051008, 0x00040e06, 0x00050e07, 0x00070f08, 0x0008110a, 0x0008110a, 0x0008110b, 0x000a120c, 0x000c140e, 0x000c140e, 0x000d150f, 0x000f140f, 0x00101610, 0x00121710, 0x00131810, 0x00131712, 0x00151a14, 0x00161b15, 0x00161b15, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181c17, 0x00151a14, 0x00151a14, 0x00141814, 0x00131712, 0x00131712, 0x00101510, 0x00101510, 0x00101510, 0x000d150f, 0x000a120c, 0x0008110b, 0x0008110a, 0x00081009, 0x0008100a, 0x0007110a, 0x00051109, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008110c, 0x0008110c, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003e400c, 0x0044450e, 0x0048490f, 0x004c4d10, 0x00515110, 0x00555611, 0x00585911, 0x00746913, 0x00cca418, 0x00c6a118, 0x00666414, 0x00646514, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00646514, 0x00a88e16, 0x00cca519, 0x00a18816, 0x00606012, 0x005e5f13, 0x005c5d11, 0x005b5b12, 0x00585910, 0x00565710, 0x00555611, 0x00535410, 0x00525310, 0x00525310, 0x00525310, 0x00535410, 0x00545510, 0x00555611, 0x00565710, 0x00585911, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00636013, 0x00c39f18, 0x00cca518, 0x00786e14, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00626313, 0x00616112, 0x00606013, 0x00887614, 0x00c8a117, 0x00b09015, 0x00505010, 0x00515110, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040e07, 0x00020e07, 0x00020e07, 0x00020e08, 0x00020e08, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081009, 0x00081009, 0x0008110a, 0x0009110a, 0x000c130d, 0x00101610, 0x00111610, 0x00121712, 0x00141812, 0x00161913, 0x00181913, 0x00181a14, 0x001a1c14, 0x001c1e16, 0x001e1d16, 0x00201c14, 0x00201c14, 0x001f1c14, 0x001d1c16, 0x001a1c16, 0x00191c16, 0x00181b14, 0x00151812, 0x00131811, 0x00111810, 0x00101711, 0x000e1610, 0x0009140c, 0x0008140d, 0x0009140c, 0x0007110a, 0x00040f08, 0x00040e07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00081009, 0x00081009, 0x00081008, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0006100b, 0x0006100b, 0x00040e09, 0x0007110c, 0x000a140f, 0x0008120d, 0x0007110c, 0x0007110c, 0x0009100b, 0x000a100a, 0x000a1009, 0x00091008, 0x00091006, 0x000a0f06, 0x000d1007, 0x00101108, 0x00121006, 0x00141007, 0x00151008, 0x00151006, 0x00181207, 0x00191409, 0x001a140a, 0x001f1509, 0x0022170a, 0x0025180b, 0x00281c0a, 0x002c1d08, 0x00302008, 0x00352508, 0x003b2908, 0x0044310a, 0x00503a09, 0x0062470c, 0x00886b1a, 0x00c0a835, 0x00ccb820, 0x00ccbb0c, 0x00cbbc09, 0x00cabb0b, 0x00caba0d, 0x00cbb910, 0x00b6980b, 0x007c5900, 0x005c3e00, 0x004a3802, 0x003d3004, 0x00322400, 0x003a2c0a, 0x00413410, 0x003f340a, 0x003b3008, 0x00352b0a, 0x0031250a, 0x002c230b, 0x00211a07, 0x00181404, 0x000f0f05, 0x000c1007, 0x000c1005, 0x000e1208, 0x00101108, 0x00101008, 0x0014110b, 0x00161009, 0x00181108, 0x001b1308, 0x001e1409, 0x001f1406, 0x00221608, 0x00281809, 0x002b190a, 0x002e1c0c, 0x00301d0c, 0x00321f09, 0x00341d08, 0x00371f08, 0x0039210a, 0x003a220c, 0x003c240d, 0x003e240c, 0x003e240d, 0x003c230b, 0x003c230a, 0x003a230a, 0x00382108, 0x00371f0b, 0x00371f0c, 0x00371c0c, 0x00331a08, 0x00301a08, 0x002f1a08, 0x002c1a08, 0x00281706, 0x00261807, 0x00231607, 0x00201407, 0x001d1407, 0x001b1108, 0x00181008, 0x00171009, 0x00141109, 0x00141109, 0x00131008, 0x00131009, 0x00141109, 0x001c170d, 0x001f1809, 0x00201805, 0x00302610, 0x00382c14, 0x002b1d01, 0x00332205, 0x003c2a08, 0x0048340b, 0x005a3d0d, 0x007b5812, 0x00b7972b, 0x00c9b21e, 0x00ccb80c, 0x00cab908, 0x00cbb808, 0x00cbb516, 0x00b08b0c, 0x00785000, 0x005a3b00, 0x004c3501, 0x00412c04, 0x00382401, 0x00301f04, 0x002d1c07, 0x00281806, 0x00241506, 0x00201305, 0x00181105, 0x00171208, 0x00171109, 0x00151008, 0x00141009, 0x00151109, 0x00151109, 0x00151109, 0x00151109, 0x00141008, 0x00131008, 0x00111009, 0x00101009, 0x00100f08, 0x00100f08, 0x000f1009, 0x000c0f05, 0x000a0f06, 0x00091008, 0x000a1008, 0x00081108, 0x0008110a, 0x00061008, 0x00061009, 0x00051109, 0x0008100b, 0x0008100b, 0x0006100a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0007110c, 0x0005100a, 0x0007110c, 0x0007110c, 0x0006100b, 0x0008120d, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040f09, 0x0006100b, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00040f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051008, 0x00051008, 0x00040e06, 0x00050e07, 0x00070f08, 0x0008110a, 0x0008110a, 0x0008110a, 0x0009120c, 0x000c140e, 0x000c140d, 0x000c140e, 0x000d140e, 0x00101610, 0x0010170f, 0x00111810, 0x00131712, 0x00131712, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161b14, 0x00181c15, 0x00181d16, 0x00181c17, 0x00151a14, 0x00151a14, 0x00141814, 0x00131712, 0x00131712, 0x00101510, 0x00101510, 0x00101510, 0x000c140e, 0x0009120b, 0x0008110a, 0x0008110a, 0x0009120c, 0x0009120c, 0x0008130c, 0x00051109, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008110c, 0x0008110c, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250c, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003e400c, 0x0043440e, 0x0048490e, 0x004c4d0f, 0x00505010, 0x00545511, 0x00585810, 0x00746813, 0x00cca418, 0x00c6a018, 0x00656313, 0x00646414, 0x00646514, 0x00666713, 0x00656613, 0x00666713, 0x00666714, 0x00636414, 0x00a88e16, 0x00cca519, 0x00a18815, 0x005e5f13, 0x005c5d11, 0x005b5b12, 0x00585911, 0x00585810, 0x00555611, 0x00535410, 0x00525310, 0x00515110, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00545510, 0x00555611, 0x00565710, 0x00585911, 0x005b5b12, 0x005c5d11, 0x00626013, 0x00c39e18, 0x00cca518, 0x00786e14, 0x00636414, 0x00636414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x00887614, 0x00c8a117, 0x00b09015, 0x00505010, 0x00515110, 0x004d4e0f, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e06, 0x00060e06, 0x00070d08, 0x00050e08, 0x00040f08, 0x00031008, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008110a, 0x0008110a, 0x0009120c, 0x0009120c, 0x000d140e, 0x00101610, 0x00111611, 0x00121712, 0x00171912, 0x00171913, 0x00181a14, 0x001b1c16, 0x001c1e16, 0x001c1e16, 0x001f1c16, 0x00201c14, 0x00201c14, 0x00201c14, 0x001c1b14, 0x00191b16, 0x00181a15, 0x00151811, 0x0012160f, 0x0010150e, 0x0010160e, 0x000f150f, 0x000b140d, 0x0009140c, 0x0008140c, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x0008100a, 0x00070f0a, 0x00060f0a, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008110a, 0x00081009, 0x00070f08, 0x0008100b, 0x0008100b, 0x00060e09, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008120d, 0x0008120d, 0x0007110c, 0x0007100a, 0x00081009, 0x00091008, 0x000a0f08, 0x000a0f08, 0x000b1008, 0x00090e05, 0x000a0f06, 0x000c0f04, 0x000f1007, 0x00101005, 0x00141008, 0x00141008, 0x00141006, 0x00171008, 0x0019140b, 0x0019140b, 0x001c1308, 0x00201508, 0x00231809, 0x00271b0b, 0x002b1c08, 0x00302008, 0x00342408, 0x003c2a08, 0x00443109, 0x0051390b, 0x0063470c, 0x00896c18, 0x00c0a835, 0x00ccb721, 0x00cbba0d, 0x00cbba08, 0x00cab90a, 0x00cbb90d, 0x00ccb811, 0x00b6950b, 0x007d5700, 0x00603e00, 0x004b3702, 0x00403006, 0x00342502, 0x003c2e0b, 0x00443610, 0x0040340a, 0x003e3208, 0x00382c08, 0x00342709, 0x0030240a, 0x00271e08, 0x001a1505, 0x00100e04, 0x000c0e06, 0x000c1005, 0x000e1208, 0x00101208, 0x00121108, 0x00131008, 0x00141008, 0x00170f07, 0x00181108, 0x001e1409, 0x001f1406, 0x00211507, 0x00271809, 0x002b1a0b, 0x002e1b0a, 0x00301c0b, 0x00331e09, 0x0037200a, 0x00382009, 0x0039210a, 0x0039220a, 0x003b240b, 0x003c230b, 0x003f260d, 0x003c220a, 0x00392006, 0x00392207, 0x00372005, 0x00372008, 0x00361e09, 0x00361c0a, 0x00331a08, 0x00301a08, 0x002f1a08, 0x002d1a08, 0x00281808, 0x00261807, 0x00241607, 0x00231709, 0x001f1408, 0x001a1108, 0x00181008, 0x00170f08, 0x00151109, 0x00151109, 0x00141008, 0x0015100b, 0x0016130b, 0x001c170d, 0x001e180a, 0x00221a06, 0x00342811, 0x003c2e14, 0x002e1f03, 0x00342206, 0x003c2b08, 0x0048340b, 0x005a3e0d, 0x00785712, 0x00b49529, 0x00ccb220, 0x00ccb80f, 0x00cab809, 0x00cab808, 0x00cbb416, 0x00b18a0c, 0x007b5000, 0x005d3b00, 0x004e3403, 0x00432c04, 0x00382401, 0x00311f04, 0x002d1d05, 0x00291a06, 0x00261808, 0x00201406, 0x00181204, 0x00171208, 0x00171109, 0x00161109, 0x00141209, 0x0014130a, 0x0014120a, 0x00141109, 0x00141109, 0x00141008, 0x00141008, 0x00121009, 0x00101009, 0x00110f08, 0x00111009, 0x00101009, 0x000d0f05, 0x000c1006, 0x000a0f06, 0x000a1008, 0x00081108, 0x00081009, 0x00061009, 0x0007110a, 0x00061009, 0x0007100a, 0x0007100b, 0x0006100a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0008120d, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007110c, 0x0006100b, 0x0006100b, 0x00051008, 0x00051008, 0x00061008, 0x00071008, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x0008100a, 0x000a130c, 0x000a130c, 0x000c140e, 0x000d140e, 0x00101610, 0x00101610, 0x00111810, 0x00131712, 0x00131712, 0x00141914, 0x00141914, 0x00151a13, 0x00151a13, 0x00171c15, 0x00171c15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00141914, 0x00141814, 0x00121711, 0x00101510, 0x00101510, 0x000d150f, 0x000d150f, 0x000b130c, 0x0009120c, 0x00081009, 0x00081009, 0x0008120b, 0x00051109, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250c, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x00535410, 0x00565710, 0x00736812, 0x00cca418, 0x00c6a018, 0x00646212, 0x00626313, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00616114, 0x00a88d16, 0x00cca518, 0x00a08716, 0x005d5e12, 0x005c5c11, 0x00595a11, 0x00585810, 0x00555611, 0x00535410, 0x00525310, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00545510, 0x00555610, 0x00585810, 0x00595a12, 0x005c5c11, 0x00615f12, 0x00c39e17, 0x00cca418, 0x00786c14, 0x00616112, 0x00616112, 0x00626312, 0x00616112, 0x00606013, 0x00606013, 0x005e5f12, 0x00877514, 0x00c8a117, 0x00b09014, 0x00505010, 0x00515110, 0x004d4e0f, 0x00494a10, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e06, 0x00060e07, 0x00070d08, 0x00060e08, 0x00040f08, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008110b, 0x0009120c, 0x0009120c, 0x0009120c, 0x000d140e, 0x00101610, 0x00131712, 0x00141813, 0x00171913, 0x00171913, 0x001a1b15, 0x001c1c17, 0x001c1e16, 0x001c1e16, 0x001f1c16, 0x001f1c14, 0x00201c14, 0x001f1c14, 0x001c1b14, 0x001a1b14, 0x00181a14, 0x00151811, 0x0012160f, 0x0010150e, 0x000f150f, 0x000b130e, 0x000a120e, 0x0009130e, 0x0008140d, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060f09, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008110a, 0x00081009, 0x00070f08, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110d, 0x0006100b, 0x0006100b, 0x0009130d, 0x0006100b, 0x0006100b, 0x0008110c, 0x0008100b, 0x00081009, 0x000a0f08, 0x000a0f08, 0x000a0f08, 0x000b1008, 0x00090e05, 0x000b0e05, 0x000c0f06, 0x000f1007, 0x00101007, 0x00131008, 0x00131008, 0x00141006, 0x00151108, 0x00171309, 0x00171309, 0x00191308, 0x001d1509, 0x00201808, 0x00241b0a, 0x00291c08, 0x002e2008, 0x00342508, 0x003c2a09, 0x0045320a, 0x0051390b, 0x0064480b, 0x00896c16, 0x00c0a834, 0x00ccb721, 0x00cbb90e, 0x00cbba0a, 0x00cab909, 0x00cbb90d, 0x00ccb810, 0x00b5950b, 0x007e5800, 0x00603f00, 0x004d3703, 0x00403005, 0x00342601, 0x003e300c, 0x00473913, 0x0043360c, 0x00403309, 0x003c2e09, 0x00362808, 0x00312709, 0x00292008, 0x001c1705, 0x00111002, 0x000d0f05, 0x000c1005, 0x000f1308, 0x00101208, 0x00121108, 0x00131008, 0x00161109, 0x00181008, 0x00181108, 0x001c1408, 0x001e1407, 0x00201507, 0x00251709, 0x002b1a0c, 0x002d1a0a, 0x002f1c09, 0x00321d08, 0x0037200b, 0x003a220c, 0x003b240c, 0x003b240c, 0x003b230a, 0x003c230b, 0x00392008, 0x003c220a, 0x00392007, 0x00392104, 0x00382004, 0x00381f08, 0x00381e09, 0x00371c08, 0x00331a08, 0x00301a08, 0x002f1a08, 0x002d1a08, 0x00281808, 0x00271708, 0x00241608, 0x00221708, 0x001f1408, 0x001a1108, 0x00181008, 0x00161008, 0x00151109, 0x00151109, 0x00141008, 0x0016110c, 0x0016130b, 0x001d180e, 0x001d1709, 0x00221a06, 0x00342910, 0x003c2f14, 0x002f2004, 0x00342206, 0x003c2c0a, 0x0049350c, 0x005c3f0f, 0x00785712, 0x00b4942a, 0x00ccb320, 0x00ccb70e, 0x00ccb80a, 0x00ccb809, 0x00cbb415, 0x00b18a0c, 0x007b5000, 0x005e3c00, 0x004f3404, 0x00442c05, 0x00382501, 0x00312004, 0x002d1d05, 0x00291a06, 0x00261808, 0x00201504, 0x00191104, 0x00171307, 0x00161209, 0x00151109, 0x00141109, 0x0014130a, 0x0014120a, 0x00141109, 0x00141109, 0x00141008, 0x00141008, 0x00121009, 0x00101009, 0x00110f08, 0x00121009, 0x00101009, 0x000f0f06, 0x000c0f05, 0x000c1007, 0x000b1008, 0x00081108, 0x00081009, 0x00061009, 0x0007110a, 0x0006100a, 0x0007100a, 0x0007100b, 0x0007100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0007110c, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008110c, 0x0007110c, 0x0006100b, 0x00061009, 0x00061009, 0x00061009, 0x00061008, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00081009, 0x0009120c, 0x0008110a, 0x000a130c, 0x000c140d, 0x000d150f, 0x000e1710, 0x00101810, 0x00111711, 0x00121711, 0x00141914, 0x00141914, 0x00151a14, 0x00151a13, 0x00171c15, 0x00171c15, 0x00161b14, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00151a14, 0x00131712, 0x00101510, 0x00101510, 0x000d150f, 0x000d150f, 0x000b130c, 0x0009120c, 0x0008100a, 0x0008100b, 0x0008120c, 0x0005110b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f1612, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003e400d, 0x0041420e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x00525310, 0x00565711, 0x00736812, 0x00cca417, 0x00c6a018, 0x00646113, 0x00616112, 0x00626313, 0x00646414, 0x00646414, 0x00646414, 0x00636414, 0x00606013, 0x00a78c16, 0x00cca418, 0x00a08715, 0x005c5d11, 0x005b5b12, 0x00585910, 0x00565711, 0x00545510, 0x00525310, 0x00515110, 0x004f5010, 0x004f5010, 0x004d4e0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545511, 0x00565711, 0x00585810, 0x00595a12, 0x00605d11, 0x00c39e17, 0x00cca418, 0x00776c14, 0x00616112, 0x00606012, 0x00616112, 0x00606013, 0x00606013, 0x005e5f13, 0x005c5d11, 0x00877514, 0x00c8a117, 0x00b09014, 0x004f5010, 0x00505010, 0x004d4e10, 0x0048490f, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e0b, 0x00050e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00041007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x0009120c, 0x000a130c, 0x000c120c, 0x000d140d, 0x000f150d, 0x00101710, 0x00141811, 0x00151a13, 0x00181c15, 0x00181c15, 0x001b1c14, 0x001e1d14, 0x00201e15, 0x00201e15, 0x001f1c14, 0x001e1d14, 0x001e1d14, 0x001c1c14, 0x00191812, 0x00181810, 0x00171812, 0x00141611, 0x0011140f, 0x0010140f, 0x000b130e, 0x000a1410, 0x000a1410, 0x0008120f, 0x0007100c, 0x00051009, 0x00040f08, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051008, 0x00061009, 0x00061009, 0x00061009, 0x00061009, 0x0008110b, 0x00081009, 0x00081009, 0x0006100b, 0x0007110c, 0x0007110c, 0x0008100a, 0x00081008, 0x000a0f08, 0x000a0f08, 0x000a0f07, 0x000a0f06, 0x000c0f06, 0x000c0d08, 0x000c0d08, 0x000c0f08, 0x000c0f08, 0x000f1008, 0x000f1007, 0x00111008, 0x00141208, 0x00161409, 0x00161409, 0x00171308, 0x001a1508, 0x001f180a, 0x00241b0a, 0x00271c07, 0x002e1f08, 0x0034240a, 0x003b2b0a, 0x0045330b, 0x00513b0c, 0x0064480b, 0x00886b14, 0x00c0a730, 0x00cbb620, 0x00cbba0c, 0x00cbba0a, 0x00cbba0a, 0x00cbb90c, 0x00ccb810, 0x00b2930a, 0x00805a00, 0x00604000, 0x004c3803, 0x00403006, 0x00342701, 0x003e300b, 0x00483913, 0x0046370e, 0x0043340c, 0x003f300c, 0x00322503, 0x00342a0a, 0x002d250b, 0x00201c06, 0x00111000, 0x000d1004, 0x000c1005, 0x000f1308, 0x00101208, 0x00111008, 0x00131008, 0x00161108, 0x00181009, 0x00191209, 0x001c1208, 0x001e1407, 0x00211509, 0x00241609, 0x00241607, 0x002b190a, 0x002f1b0a, 0x00321d0a, 0x00371f0b, 0x003a200b, 0x003d240c, 0x003c230b, 0x003c230b, 0x0040240e, 0x003d220b, 0x003c210a, 0x003c2208, 0x003b2007, 0x003c2009, 0x003b1f09, 0x003a1e0a, 0x00381f08, 0x00341c08, 0x00311a06, 0x002f1a08, 0x002d190a, 0x002a180b, 0x00261509, 0x00231409, 0x00201408, 0x001d1508, 0x001a1308, 0x00181108, 0x0018120b, 0x0018110a, 0x00140e07, 0x00161009, 0x0016120a, 0x0018140b, 0x001c170c, 0x001c1408, 0x00241b07, 0x00362c10, 0x003f3214, 0x002f2004, 0x00342208, 0x003c2b0a, 0x0049350d, 0x005c400f, 0x00785614, 0x00b4942a, 0x00ccb321, 0x00ccb60d, 0x00ccb80a, 0x00ccb809, 0x00cbb414, 0x00ab8305, 0x007b5000, 0x005f3c00, 0x004f3404, 0x00452c08, 0x00382600, 0x00312004, 0x002d1d05, 0x00291a06, 0x00251908, 0x001e1506, 0x00191306, 0x00181207, 0x00171208, 0x00141209, 0x00141109, 0x00141109, 0x00141109, 0x00131008, 0x00131008, 0x00140f09, 0x00121009, 0x00121009, 0x00120f0b, 0x00120f0b, 0x00120f0b, 0x00110f08, 0x00121108, 0x00141008, 0x000f1007, 0x000c1108, 0x00091008, 0x00081009, 0x00081009, 0x0009110c, 0x0008110c, 0x0007100b, 0x0008100b, 0x0008100c, 0x0008100d, 0x00070e0c, 0x0008100c, 0x0008100d, 0x0008100d, 0x0008100d, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00060f0b, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0007110d, 0x0006100c, 0x00050f0c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110b, 0x0005110b, 0x00030f09, 0x00030f09, 0x0004100a, 0x0005100b, 0x00040f09, 0x0004100a, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008100b, 0x000a120e, 0x0009110d, 0x000c140f, 0x000f150f, 0x00101610, 0x00101811, 0x00101811, 0x00101812, 0x00121a14, 0x00141814, 0x00151a14, 0x00171c17, 0x00171c15, 0x00181e15, 0x00181f16, 0x00171e15, 0x00161d14, 0x00171c14, 0x00171913, 0x00141813, 0x00141614, 0x00131714, 0x000e1811, 0x000e1811, 0x000a140d, 0x0009140d, 0x00091310, 0x0008120e, 0x0008120f, 0x0008120f, 0x0008100b, 0x0008100b, 0x0008100b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280b, 0x00292b0a, 0x002d2f0c, 0x0032330c, 0x00393b0c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x00525310, 0x00555611, 0x00726612, 0x00cca417, 0x00c6a017, 0x00636013, 0x00606013, 0x00616112, 0x00626313, 0x00636413, 0x00636413, 0x00626313, 0x00606012, 0x00a78c15, 0x00cca418, 0x00a08615, 0x005b5b12, 0x00595a12, 0x00585810, 0x00555611, 0x00535410, 0x00515110, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004c4d0e, 0x004d4e0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00525310, 0x00545510, 0x00565711, 0x00585910, 0x00595a12, 0x00605c12, 0x00c39e17, 0x00cca418, 0x00766c14, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005e5f12, 0x005c5d11, 0x00867414, 0x00c8a116, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d0f, 0x00484910, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00060d0b, 0x00060d0b, 0x00060e0a, 0x00050f08, 0x00040f08, 0x00040f08, 0x00041007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x0009120c, 0x000c130d, 0x000e140e, 0x000f150f, 0x0010170f, 0x00121911, 0x00141912, 0x00161b14, 0x00181c15, 0x00181c15, 0x001c1d15, 0x001e1d14, 0x00201e15, 0x00201e15, 0x001e1d14, 0x001d1e14, 0x001c1c14, 0x001a1b14, 0x00181913, 0x00171812, 0x00161812, 0x00131610, 0x0010140e, 0x000e150f, 0x000a120e, 0x0008120f, 0x0008120f, 0x0007100d, 0x0006100c, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051009, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100c, 0x0008100b, 0x0008100b, 0x0006100b, 0x0007110d, 0x0007110c, 0x0008100a, 0x00091008, 0x000a0f08, 0x000a0f08, 0x000a0f07, 0x000a0f06, 0x000c0f06, 0x000c0e06, 0x000c0e06, 0x000c1007, 0x000c1007, 0x000f1008, 0x000f1007, 0x00111108, 0x00141208, 0x00141308, 0x00141308, 0x00151208, 0x00191408, 0x001d1809, 0x00221a09, 0x00271c07, 0x002e1e08, 0x0035250b, 0x003b2c0b, 0x0045340c, 0x00523b0c, 0x0064480b, 0x00886a15, 0x00c0a730, 0x00cbb61f, 0x00cbba0b, 0x00cbba0a, 0x00cbba0a, 0x00cbba0c, 0x00ccb910, 0x00af9008, 0x007c5800, 0x00604100, 0x004c3903, 0x003e2f04, 0x00342701, 0x003e300b, 0x00483912, 0x0047380f, 0x0044350e, 0x0040300c, 0x00322602, 0x00352b0b, 0x0031280d, 0x00231e08, 0x00121101, 0x00101005, 0x000c1005, 0x000e1208, 0x00101208, 0x00111008, 0x00131008, 0x00171208, 0x0018100a, 0x00191209, 0x001b1108, 0x001d1205, 0x00211408, 0x00241508, 0x00251608, 0x002a1909, 0x002e1909, 0x00301c08, 0x00351c09, 0x00381d08, 0x00392009, 0x003c220a, 0x003e250c, 0x0040240e, 0x003d220b, 0x003c210a, 0x003c2208, 0x003c210a, 0x003b2008, 0x003b1f09, 0x003a1e0a, 0x00381f08, 0x00341c08, 0x00301a06, 0x002f1a08, 0x002c1909, 0x00281609, 0x00261509, 0x00241409, 0x00201408, 0x001c1407, 0x00191208, 0x00181108, 0x00171009, 0x00161009, 0x00161009, 0x00161009, 0x0018130c, 0x0019160c, 0x001c160d, 0x001f180b, 0x00271f0a, 0x00382e10, 0x00423414, 0x00312204, 0x00342206, 0x003c2b0a, 0x0049350c, 0x005c4010, 0x00785614, 0x00b4942b, 0x00ccb322, 0x00cbb50d, 0x00ccb90c, 0x00ccb80a, 0x00cbb414, 0x00aa8305, 0x007b5000, 0x00603c00, 0x004e3404, 0x00462d08, 0x00392701, 0x00332104, 0x002d1d04, 0x00291a06, 0x00251908, 0x001e1506, 0x001b1407, 0x00181207, 0x00171208, 0x00141309, 0x00141009, 0x00131008, 0x00131008, 0x00121008, 0x00121008, 0x00140f09, 0x00121009, 0x00121009, 0x00120f0b, 0x00120f0b, 0x00120f0b, 0x00121008, 0x00141209, 0x00141108, 0x00101008, 0x000a0d05, 0x000a1109, 0x0008110a, 0x00081009, 0x000a130c, 0x0009130c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x00060e09, 0x0008100b, 0x0009110d, 0x0008100c, 0x0008100c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0007100d, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x0007100b, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0004100a, 0x00040f09, 0x0004100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0008100b, 0x0009110d, 0x0008100c, 0x0009110d, 0x000c130d, 0x000d140e, 0x000d150f, 0x000e1710, 0x000f1811, 0x00101812, 0x00141815, 0x00141914, 0x00161b15, 0x00161b14, 0x00171d14, 0x00171e14, 0x00171e14, 0x00161d14, 0x00171c13, 0x00171912, 0x00141812, 0x00141612, 0x00131714, 0x000e1811, 0x000e1811, 0x000a140d, 0x0009130d, 0x00091310, 0x0008120e, 0x0008120f, 0x0008120f, 0x0008100b, 0x0008100b, 0x0008100b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x00494a10, 0x004d4e0f, 0x00515110, 0x00545510, 0x00726612, 0x00cca417, 0x00c6a016, 0x00615f12, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x005e5f13, 0x00a78b15, 0x00cca418, 0x00a08614, 0x00595a12, 0x00585910, 0x00565711, 0x00545510, 0x00525310, 0x00515110, 0x004f5010, 0x004d4e0f, 0x004c4d0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545511, 0x00565710, 0x00585911, 0x005e5c12, 0x00c39e17, 0x00cca418, 0x00766b14, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005c5c11, 0x00867414, 0x00c8a116, 0x00b09014, 0x004f5010, 0x00505010, 0x004c4d0f, 0x0048490f, 0x0044450e, 0x0040400d, 0x003b3c0c, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0020230a, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00041007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00060e09, 0x0008100b, 0x00060e09, 0x00050d09, 0x00070f0a, 0x0008100c, 0x000a120e, 0x000a120d, 0x000c140d, 0x000d140f, 0x00101610, 0x0010160f, 0x00101710, 0x00111810, 0x00151a13, 0x00171c15, 0x00191c16, 0x001b1d18, 0x001c1e16, 0x001e1d14, 0x001f1c14, 0x001e1d14, 0x001d1e16, 0x001b1c15, 0x00181c13, 0x00181b12, 0x00141810, 0x00131610, 0x00131612, 0x00101411, 0x000c140f, 0x000c140f, 0x0008110c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110e, 0x0009110e, 0x0008100c, 0x0007100d, 0x0006100d, 0x0007110c, 0x0008100a, 0x000a0f07, 0x000b0f06, 0x000c0f06, 0x000c0f06, 0x000c0f06, 0x000c0f06, 0x000c0e06, 0x000c0e06, 0x000c1007, 0x000c1007, 0x000f1008, 0x000f1007, 0x00101008, 0x00131107, 0x00141208, 0x0014130a, 0x00151108, 0x00191408, 0x001e1809, 0x00221a09, 0x00271c07, 0x002d1f08, 0x0034240a, 0x003b2d0b, 0x0044340c, 0x00523b0c, 0x0066480c, 0x00876814, 0x00c2a732, 0x00ccb61f, 0x00ccb90c, 0x00ccb90a, 0x00ccb90c, 0x00ccb90c, 0x00ccb810, 0x00af9009, 0x007c5800, 0x00604200, 0x004c3903, 0x003f3005, 0x00352801, 0x0042340d, 0x00483811, 0x0044350c, 0x0043340c, 0x0040310d, 0x00342805, 0x00322809, 0x00342a10, 0x0027210c, 0x00191707, 0x00101105, 0x000d0f05, 0x000d1107, 0x00101208, 0x00131209, 0x00121006, 0x00161108, 0x0018100a, 0x0019110b, 0x001b1108, 0x001d1205, 0x00221609, 0x00241609, 0x00251608, 0x00281808, 0x002e1a0a, 0x00311b08, 0x00341b07, 0x00381d09, 0x0039200a, 0x003a2108, 0x003b2209, 0x003e230d, 0x003c2109, 0x00391e07, 0x003c2007, 0x00391e06, 0x00391e06, 0x00381c07, 0x00381c08, 0x00371d07, 0x00341c06, 0x00311b07, 0x002f1907, 0x002c1808, 0x00281408, 0x00241408, 0x00221207, 0x001f1307, 0x001c1306, 0x00181108, 0x00181108, 0x0018110a, 0x00181009, 0x00170f08, 0x00170f08, 0x0018120b, 0x001a150c, 0x001c140c, 0x0021180c, 0x0029200b, 0x00382f0e, 0x00443815, 0x00322402, 0x00352304, 0x003c2c09, 0x00483409, 0x005b3f0f, 0x00785514, 0x00b4922b, 0x00ccb122, 0x00cbb40e, 0x00ccb80b, 0x00ccb80a, 0x00cbb214, 0x00ab8205, 0x007a4e00, 0x00603b00, 0x004e3104, 0x00472d0b, 0x00392602, 0x00322104, 0x002d1d04, 0x00291a06, 0x00251908, 0x001e1506, 0x001b1407, 0x00181207, 0x00171208, 0x00141309, 0x00131109, 0x00121108, 0x00111108, 0x00101008, 0x00111008, 0x00121009, 0x00121009, 0x00121009, 0x00120f0b, 0x00120d0a, 0x00120d0a, 0x00130f08, 0x00141109, 0x00151208, 0x00101008, 0x000c0e06, 0x000c1009, 0x000b130c, 0x0008110b, 0x0008110b, 0x000c140e, 0x0008110b, 0x0008110a, 0x0008110b, 0x0009120b, 0x0009120c, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110b, 0x0007110c, 0x0006100b, 0x0006100b, 0x0008120c, 0x0009120c, 0x00081009, 0x00081009, 0x00081009, 0x00061009, 0x00061009, 0x00061009, 0x00061009, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00060f0a, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x0006100c, 0x0007130d, 0x0007130d, 0x0006120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0005110b, 0x0005110b, 0x0006100b, 0x0006100b, 0x00050d09, 0x0008100c, 0x0009110c, 0x000a120e, 0x000c120e, 0x000d1410, 0x000c140e, 0x000c140e, 0x000d150f, 0x000f1811, 0x00141815, 0x00141914, 0x00151a14, 0x00161b14, 0x00171d14, 0x00171e14, 0x00171e14, 0x00161c13, 0x00171c11, 0x00181b11, 0x00161811, 0x00141711, 0x00131712, 0x000e1811, 0x000e1811, 0x000b150e, 0x000a140e, 0x000a1410, 0x00091310, 0x0008120f, 0x0008120f, 0x0008100c, 0x0008100c, 0x0008100c, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0c, 0x0040400d, 0x0044450d, 0x0048490f, 0x004c4d10, 0x00505010, 0x00545510, 0x00716512, 0x00cca417, 0x00c6a016, 0x00605d11, 0x005e5f13, 0x00606013, 0x00606013, 0x00606012, 0x00606012, 0x00606013, 0x005d5e13, 0x00a78b15, 0x00cca418, 0x00a08614, 0x00595a12, 0x00585810, 0x00555610, 0x00535410, 0x00525310, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004c4d0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00525310, 0x00545510, 0x00565710, 0x00595a11, 0x005e5c13, 0x00c39e17, 0x00cca418, 0x00756a13, 0x005e5f13, 0x00606013, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005c5d11, 0x005b5b11, 0x00867414, 0x00c8a116, 0x00b09014, 0x004d4e10, 0x004f5010, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0036370c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00050e08, 0x00040f08, 0x00040f08, 0x00041007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00060e09, 0x0008100b, 0x00060e09, 0x00070f0a, 0x0009110c, 0x0009110c, 0x0009110e, 0x000c140e, 0x000c140e, 0x000f1610, 0x00101710, 0x00101711, 0x00111810, 0x00131a12, 0x00161b14, 0x00171c15, 0x001a1c17, 0x001c1e18, 0x001c1e16, 0x001e1d14, 0x001e1d14, 0x001d1e14, 0x001b1c14, 0x00181c13, 0x00181a13, 0x00171913, 0x00141611, 0x00131410, 0x00101410, 0x000e1410, 0x000b130f, 0x000a130e, 0x0006100b, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x00040f09, 0x00040e08, 0x00051009, 0x00051009, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x000b1310, 0x000b1310, 0x000b1310, 0x00091310, 0x0008120f, 0x0007110c, 0x0009100a, 0x000a0f08, 0x000b0f07, 0x000c0f06, 0x000c0f06, 0x000c0f05, 0x000c0f04, 0x000c0e04, 0x000c0f04, 0x000c1005, 0x000c1005, 0x000f1008, 0x000f1007, 0x00101008, 0x00131107, 0x00131308, 0x0014130a, 0x00141208, 0x00181408, 0x001e1809, 0x00221a09, 0x00271c07, 0x002d1f08, 0x00342509, 0x003c2d0c, 0x0044340c, 0x00523b0c, 0x0068480c, 0x00876813, 0x00c2a732, 0x00ccb61e, 0x00ccb90c, 0x00ccb90a, 0x00ccb90c, 0x00cbbb0c, 0x00ccb910, 0x00af9009, 0x007d5800, 0x00604400, 0x004c3a04, 0x00413208, 0x00382b04, 0x0044370f, 0x0047380f, 0x0044340b, 0x0042340c, 0x00413410, 0x00342806, 0x002e2304, 0x00342a11, 0x002b2510, 0x00191605, 0x00111104, 0x000e1006, 0x000d1007, 0x00101208, 0x00111208, 0x00121006, 0x00161108, 0x0018100a, 0x0019110a, 0x001b1108, 0x001d1205, 0x00221609, 0x00241608, 0x00251608, 0x00281808, 0x002d1a09, 0x00301a08, 0x00331a06, 0x00351c08, 0x00381f09, 0x00381f08, 0x00392008, 0x003c210b, 0x003b2008, 0x003c2008, 0x003a1f06, 0x00371c04, 0x00381c05, 0x00371c06, 0x00371b08, 0x00371c08, 0x00341c06, 0x00321b07, 0x002f1907, 0x002c1809, 0x00281408, 0x00241408, 0x00221207, 0x001f1306, 0x001b1305, 0x00181107, 0x00181108, 0x0018110a, 0x00181009, 0x00170f08, 0x00170f08, 0x0018120b, 0x001a150c, 0x001c140c, 0x0021180c, 0x0029200a, 0x00382f0c, 0x00443813, 0x00342502, 0x00352401, 0x003e2d09, 0x0048340a, 0x005c3f0e, 0x00785514, 0x00b3932b, 0x00ccb222, 0x00cab40e, 0x00ccb80c, 0x00ccb80a, 0x00cbb214, 0x00ab8205, 0x007a4f00, 0x00603b00, 0x004d3003, 0x00472d0b, 0x003a2802, 0x00322104, 0x002d1d04, 0x00291a06, 0x00251908, 0x001e1506, 0x001b1407, 0x00181207, 0x00171208, 0x00141309, 0x00131109, 0x00121108, 0x00111108, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00121009, 0x00120f0b, 0x00140f0b, 0x00130e0a, 0x00140f08, 0x0015110a, 0x00151208, 0x00111008, 0x000d0f07, 0x00080e06, 0x000a120c, 0x000c140e, 0x000d140f, 0x00101711, 0x000d150e, 0x000e150e, 0x000c140c, 0x000a110a, 0x00091109, 0x00091008, 0x00091008, 0x00091008, 0x00081109, 0x0007110a, 0x00061009, 0x00061009, 0x0008130c, 0x0009120c, 0x00081009, 0x00081009, 0x00081008, 0x00061008, 0x00061108, 0x00061009, 0x0006100a, 0x0008110a, 0x0008110a, 0x0008100b, 0x0008100c, 0x0008100c, 0x0006100d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x0006100c, 0x0008120d, 0x0007130d, 0x0006120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0007120c, 0x0007120c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100c, 0x0009110d, 0x0009110d, 0x000a120e, 0x000a120e, 0x000c1410, 0x000c140f, 0x000c140f, 0x000d1510, 0x000f1812, 0x00141815, 0x00141914, 0x00151a14, 0x00161b14, 0x00171c14, 0x00171e14, 0x00171e14, 0x00161c13, 0x00161c12, 0x00181b11, 0x00161810, 0x00141710, 0x00131810, 0x000f1811, 0x000e1811, 0x000c150e, 0x000a140e, 0x000a1410, 0x00091310, 0x0008120f, 0x0008120f, 0x0008100c, 0x0008100c, 0x0008100c, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00141809, 0x00191c09, 0x00202309, 0x00202309, 0x0026280c, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0040400e, 0x0044450e, 0x0048490f, 0x004c4d0f, 0x00505010, 0x00535410, 0x00716412, 0x00cca316, 0x00c5a016, 0x00605d11, 0x005d5e12, 0x00606013, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x005c5d13, 0x00a68b15, 0x00cca418, 0x00a08514, 0x00585912, 0x00585910, 0x00555610, 0x00535410, 0x00525310, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004d4e0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545510, 0x00565710, 0x00585910, 0x005e5c12, 0x00c39e17, 0x00cca418, 0x00756a13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005b5b12, 0x00867414, 0x00c8a016, 0x00b09014, 0x004c4d10, 0x004f5010, 0x004c4d0f, 0x0048490e, 0x0044450e, 0x0040400e, 0x003c3e0d, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x00060e08, 0x00060e08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00080f0b, 0x00080f0a, 0x00060e08, 0x00050e07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f07, 0x00040f07, 0x00051008, 0x00051008, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00081009, 0x00081009, 0x00060e08, 0x00060e08, 0x00081009, 0x00081009, 0x00081009, 0x0008110a, 0x000b130c, 0x000e140e, 0x00101610, 0x00111812, 0x00121813, 0x00151a13, 0x00151a13, 0x00161b14, 0x00191c16, 0x001d1c18, 0x001e1c18, 0x001e1d16, 0x001e1d14, 0x001e1d16, 0x001c1e16, 0x001b1c14, 0x00181b12, 0x00151a13, 0x00141811, 0x00121710, 0x0010150f, 0x000e1410, 0x000c1410, 0x000c140f, 0x000a140f, 0x0008130e, 0x0006110d, 0x0006110d, 0x0005100c, 0x0005100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00040e0b, 0x0006100b, 0x00061009, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0006110b, 0x0006120c, 0x0005120c, 0x0005110b, 0x0005110b, 0x0005120c, 0x0006120c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0006110c, 0x0006120c, 0x0008130d, 0x0008120d, 0x0007100c, 0x0009120e, 0x000a120e, 0x000a120e, 0x000a1210, 0x0008100c, 0x00091009, 0x000a0f08, 0x000a0f08, 0x000a0f07, 0x000b0f05, 0x000c0f04, 0x000c0f04, 0x000b0f04, 0x000a1004, 0x000b1005, 0x000b1005, 0x000c1007, 0x000c1005, 0x000d0f05, 0x00101108, 0x00131209, 0x00131209, 0x00141208, 0x00181408, 0x001c1709, 0x00211808, 0x00271c08, 0x002c1f08, 0x00322408, 0x003a2e0b, 0x0044340c, 0x00523b0c, 0x0066480c, 0x00856611, 0x00c0a630, 0x00cbb61f, 0x00cbba0b, 0x00cbba0c, 0x00ccbb0c, 0x00ccba0e, 0x00cbb80e, 0x00ac8d09, 0x007c5700, 0x00614400, 0x004d3c04, 0x00413209, 0x00382b04, 0x0044370e, 0x0045380e, 0x0045380c, 0x00413409, 0x003f320c, 0x003a2f0d, 0x00281d01, 0x0033280f, 0x002a240f, 0x001c1a08, 0x00121204, 0x000f1007, 0x000e1006, 0x000e1208, 0x00101108, 0x00131107, 0x00151007, 0x00181009, 0x00181009, 0x001c1208, 0x001d1205, 0x00211509, 0x00241609, 0x00241608, 0x0028180a, 0x002c1a0a, 0x002f1a08, 0x00311807, 0x00351806, 0x00371b08, 0x00371b08, 0x00351c08, 0x00381f08, 0x00381f08, 0x00371e08, 0x00371e07, 0x00381e06, 0x00361c07, 0x00351c07, 0x00341907, 0x00351807, 0x00341907, 0x00311908, 0x002e1708, 0x002b1709, 0x0028140a, 0x0024130a, 0x00221209, 0x001d1107, 0x001c1106, 0x00191007, 0x00181108, 0x0018100a, 0x00171009, 0x00151008, 0x00151008, 0x0018120b, 0x00191409, 0x001b130a, 0x0020180a, 0x00281f08, 0x003c330f, 0x00453914, 0x00342603, 0x00362404, 0x003e2d09, 0x00483409, 0x005c400d, 0x00785514, 0x00b3932b, 0x00ccb222, 0x00cbb40e, 0x00ccb80c, 0x00ccb80a, 0x00cbb213, 0x00ab8204, 0x007b4f00, 0x00603c00, 0x00513408, 0x00462c0a, 0x003b2804, 0x002e1d01, 0x002d1d05, 0x00291a06, 0x00251908, 0x001e1504, 0x001a1305, 0x00181308, 0x0018130a, 0x00141209, 0x00121008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00121009, 0x00121009, 0x00140f09, 0x00140f09, 0x00140f09, 0x00151009, 0x00140f08, 0x00121008, 0x000d0e06, 0x000c0d08, 0x000e120b, 0x0010140e, 0x00151712, 0x00171712, 0x00181711, 0x00171710, 0x00171710, 0x0016160f, 0x0015150e, 0x0014140c, 0x0012140c, 0x0010140b, 0x000c1209, 0x000a140a, 0x000b140d, 0x000a140c, 0x0008120c, 0x0008120c, 0x0007110c, 0x0007110c, 0x0007110d, 0x0006110e, 0x0006110e, 0x0007110d, 0x0007100d, 0x0006100a, 0x00061009, 0x00061009, 0x00071008, 0x0008100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0008120c, 0x000c140f, 0x000c140f, 0x000c1511, 0x000c1512, 0x000c1713, 0x000e1814, 0x00121816, 0x00141815, 0x00151916, 0x00151a14, 0x00181c17, 0x00191d17, 0x00181d15, 0x00171c14, 0x00171c14, 0x00171c15, 0x00171c15, 0x00141912, 0x00141811, 0x00121812, 0x00111812, 0x000f150f, 0x000c140f, 0x000c1411, 0x000c1310, 0x00091310, 0x00081410, 0x0009110d, 0x0009110d, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002d2f0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x00525310, 0x00716412, 0x00cca316, 0x00c5a017, 0x00605c12, 0x005d5e11, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005c5c13, 0x00a68b15, 0x00cca417, 0x00a08514, 0x00585912, 0x00585810, 0x00565711, 0x00535410, 0x00525310, 0x00515110, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00525310, 0x00535410, 0x00555611, 0x00585810, 0x00585911, 0x005e5c13, 0x00c39d17, 0x00cca417, 0x00756a12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5c11, 0x005b5b12, 0x00867414, 0x00c8a016, 0x00b09014, 0x004c4d10, 0x004f5010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00070f08, 0x00070f08, 0x00080e08, 0x00070f08, 0x00070f08, 0x00051008, 0x00051008, 0x00051008, 0x00070d08, 0x00080f0b, 0x0008100a, 0x00050f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00051007, 0x00051008, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x0008100a, 0x000a130c, 0x000c140e, 0x000f150f, 0x00101711, 0x00111812, 0x00131813, 0x00151a13, 0x00151a13, 0x00171c14, 0x00191c16, 0x001d1c18, 0x001e1c18, 0x001e1d16, 0x001e1d14, 0x001e1d16, 0x001c1c14, 0x001b1c14, 0x00181b12, 0x00151a13, 0x00141811, 0x00131810, 0x0012160f, 0x000e150f, 0x000b1510, 0x000b1410, 0x0008120d, 0x0006100b, 0x0004100c, 0x0004100c, 0x0005100c, 0x0005100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00040e0b, 0x0006100b, 0x00061009, 0x0008110b, 0x0008110b, 0x0008110c, 0x0008110c, 0x0007110c, 0x0006100b, 0x0006100a, 0x00051109, 0x00061109, 0x0006120a, 0x0007110a, 0x000b110c, 0x000b110c, 0x000a100a, 0x0009100a, 0x000b130c, 0x000b130c, 0x000c140d, 0x000c140d, 0x000d140e, 0x00101610, 0x000e140e, 0x000e140e, 0x000c130f, 0x0009100b, 0x00090f08, 0x000a0f08, 0x000a0f06, 0x000a0f06, 0x000b0f05, 0x000c0f04, 0x000c0f04, 0x000a1004, 0x000a1004, 0x000b1005, 0x000b1005, 0x000b1007, 0x000c1005, 0x000d0f05, 0x00101108, 0x00111309, 0x00111309, 0x00131308, 0x00171509, 0x001c170a, 0x00231809, 0x00271c08, 0x002c2009, 0x00322408, 0x003a2e0b, 0x0044350c, 0x00523c0c, 0x0066480e, 0x00856611, 0x00c0a630, 0x00cbb61f, 0x00cab90a, 0x00cbba0c, 0x00cbba0c, 0x00cbbb0e, 0x00c9b810, 0x00ac8c08, 0x007c5700, 0x00624500, 0x004f3c05, 0x0044340c, 0x003b2d07, 0x0044380f, 0x0045380d, 0x0045390b, 0x00403408, 0x003e330c, 0x00392f0e, 0x00261c00, 0x002e240b, 0x002a240f, 0x00201e0b, 0x00111302, 0x000c0e04, 0x000c0e04, 0x000d1107, 0x00101208, 0x00121107, 0x00141007, 0x00181009, 0x00181009, 0x001c1208, 0x001d1205, 0x00211509, 0x00231709, 0x00231708, 0x0026180a, 0x002a1a0b, 0x002c1a08, 0x00301806, 0x00331906, 0x00351c08, 0x00351c09, 0x00351c09, 0x00361f08, 0x00361f08, 0x00361f08, 0x00361f08, 0x00381e08, 0x00361c08, 0x00351c08, 0x00341907, 0x00331806, 0x00321808, 0x00301808, 0x002e1808, 0x002c1709, 0x0027150a, 0x0024140a, 0x0021140a, 0x001e1208, 0x001c1307, 0x00181107, 0x00181108, 0x0017110a, 0x00151109, 0x00141008, 0x00151009, 0x0017130b, 0x00191409, 0x001b1308, 0x00201808, 0x00282008, 0x003d3210, 0x00453914, 0x00352804, 0x00362404, 0x003f2e08, 0x00493609, 0x005c400c, 0x00775512, 0x00b2932b, 0x00cab322, 0x00c9b50e, 0x00cab80c, 0x00ccb80a, 0x00cbb313, 0x00ac8406, 0x007c5000, 0x00603c00, 0x00513408, 0x00462c09, 0x003c2805, 0x002f1d02, 0x002d1d05, 0x00291a06, 0x00251908, 0x001e1504, 0x001a1304, 0x00181309, 0x0018130a, 0x00141209, 0x00121008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00121009, 0x00121009, 0x0013100a, 0x00121009, 0x00121009, 0x00141209, 0x00140f09, 0x00121008, 0x000e0d06, 0x000c0f06, 0x000e110a, 0x0012140e, 0x00151410, 0x0016140f, 0x0018140d, 0x0018130d, 0x0018130c, 0x0017120b, 0x0017120b, 0x0014130a, 0x0014130a, 0x0016180e, 0x0014180f, 0x0013180f, 0x0012170e, 0x0010150e, 0x000e140c, 0x000b110c, 0x000a110c, 0x0009100b, 0x0009100c, 0x0007110c, 0x0006110c, 0x0007110c, 0x0007110c, 0x0008120c, 0x0008120c, 0x0008100b, 0x00070f08, 0x00081009, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0006100b, 0x0007110c, 0x000a140f, 0x000a140f, 0x000b1411, 0x000b1411, 0x000c1713, 0x000c1713, 0x00101614, 0x00141814, 0x00141815, 0x00151914, 0x00161b17, 0x00171b18, 0x00171c16, 0x00171c14, 0x00171c14, 0x00171c15, 0x00171c15, 0x00161b14, 0x00141811, 0x00131712, 0x00111812, 0x000f150f, 0x000c140f, 0x000c1411, 0x000c1411, 0x00091310, 0x00081410, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x0040400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x00525310, 0x00706411, 0x00cca316, 0x00c5a017, 0x00605c12, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x005e5f13, 0x005e5f13, 0x005c5c13, 0x00a68a14, 0x00cca417, 0x00a08514, 0x00585912, 0x00585910, 0x00565711, 0x00545511, 0x00535410, 0x00515110, 0x00505010, 0x004f5010, 0x004f5010, 0x004d4e10, 0x004f5010, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545510, 0x00555611, 0x00565710, 0x00595a11, 0x005e5c13, 0x00c39e17, 0x00cca417, 0x00756a12, 0x005d5e12, 0x005e5f13, 0x005e5f12, 0x005d5e11, 0x005d5e11, 0x005c5c11, 0x00595a12, 0x00867413, 0x00c8a016, 0x00b09014, 0x004c4d10, 0x004d4e0f, 0x004b4c10, 0x0047480e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00080e08, 0x00080e08, 0x00080e08, 0x00070f08, 0x00070f08, 0x00051008, 0x00051008, 0x00051008, 0x0009100b, 0x0009100c, 0x0008110b, 0x00071008, 0x00051007, 0x00051007, 0x00051007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00061108, 0x00041008, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00081009, 0x00081009, 0x0009120c, 0x0008120c, 0x0008110b, 0x0008110a, 0x0008110a, 0x000a130c, 0x000c140e, 0x00101610, 0x00101711, 0x00131712, 0x00141813, 0x00181a14, 0x00181c15, 0x00191c16, 0x001a1d17, 0x001c1d18, 0x001c1d18, 0x001c1e16, 0x001c1e14, 0x001c1d15, 0x001a1b14, 0x001a1b14, 0x00171913, 0x00141813, 0x00131811, 0x00101610, 0x0010150e, 0x000c140e, 0x00091310, 0x0008120e, 0x0006100c, 0x0006100c, 0x00030f0b, 0x00030f0b, 0x0005100c, 0x0005100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100b, 0x00061009, 0x0007110a, 0x0007110a, 0x0007110c, 0x0007110c, 0x0007110b, 0x00061009, 0x00050f08, 0x00081009, 0x0009120b, 0x000a130b, 0x000b130b, 0x000c130c, 0x000c130c, 0x000f130c, 0x000e130c, 0x0010150e, 0x00111610, 0x0010150e, 0x0010150e, 0x00141811, 0x00161912, 0x0011160f, 0x0010140d, 0x000d120b, 0x00090e07, 0x00090e06, 0x00090f05, 0x000a1004, 0x000a1004, 0x000b1005, 0x000c0f06, 0x000c0f06, 0x000a1004, 0x000a1004, 0x000b1005, 0x000b1005, 0x000b1007, 0x000c1005, 0x000d0f05, 0x00101108, 0x00111309, 0x0013120b, 0x00141109, 0x0018140b, 0x001d160a, 0x00231809, 0x00271c08, 0x002c2009, 0x00322408, 0x003a2d0b, 0x0044350c, 0x00503c0d, 0x0065480d, 0x00846311, 0x00c0a430, 0x00ccb520, 0x00ccb80b, 0x00cab90a, 0x00cbb90c, 0x00cbb90d, 0x00cbb810, 0x00aa8a08, 0x007c5700, 0x00624500, 0x004f3c04, 0x0044350b, 0x003c2e07, 0x00483a11, 0x0045380d, 0x0044380a, 0x00403408, 0x00392e08, 0x003b3010, 0x002b2104, 0x00291f06, 0x0028220c, 0x00201e0b, 0x00141404, 0x000d0d02, 0x000c0e04, 0x000c1005, 0x00101109, 0x00131208, 0x00161108, 0x00181009, 0x00181009, 0x001c1208, 0x001d1205, 0x00211408, 0x00231708, 0x00241809, 0x00241809, 0x00281a0a, 0x002c1a08, 0x002e1906, 0x00311906, 0x00341b08, 0x00341b08, 0x00341b08, 0x00341c08, 0x00341c08, 0x00341c08, 0x00341c08, 0x00341b06, 0x00341b08, 0x00341a0a, 0x00341a0a, 0x00331806, 0x00311908, 0x00311a09, 0x002e1908, 0x002a1709, 0x00261509, 0x00231409, 0x00211409, 0x001c1308, 0x001a1308, 0x00181207, 0x00151108, 0x00141109, 0x00141109, 0x00131008, 0x00141109, 0x0017140c, 0x00181409, 0x001b1308, 0x00211709, 0x002a2008, 0x003c3110, 0x00443812, 0x00352804, 0x00382505, 0x00402f09, 0x0049370a, 0x005c400c, 0x00755410, 0x00af8f27, 0x00ccb323, 0x00cab40e, 0x00ccb80c, 0x00ccb80a, 0x00cbb412, 0x00ac8606, 0x007c5100, 0x00603c00, 0x004f3308, 0x00432b09, 0x003b2804, 0x002e1c01, 0x002d1d05, 0x00291a06, 0x00251908, 0x001e1504, 0x001a1304, 0x00181309, 0x0018130a, 0x00141209, 0x00121008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00121009, 0x00110f08, 0x00101009, 0x000f0e08, 0x00100f08, 0x00110f08, 0x00121009, 0x00100e08, 0x000e0d06, 0x000e1109, 0x000d1209, 0x0010140b, 0x0014140c, 0x0014130a, 0x0016110a, 0x00181309, 0x00181309, 0x00181309, 0x00181108, 0x00171309, 0x00161409, 0x00151409, 0x0014140a, 0x0015170d, 0x0016170f, 0x00171810, 0x0015170f, 0x0014160f, 0x00141610, 0x0014150f, 0x0010130e, 0x000c140d, 0x000c140d, 0x000c140d, 0x0009120b, 0x0008110a, 0x0008110a, 0x0009120b, 0x00081009, 0x00081009, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x00070f0a, 0x0008100c, 0x0006100b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0007100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0007110c, 0x0007110c, 0x0009130e, 0x0009130e, 0x00091310, 0x00091310, 0x000b1411, 0x000c1713, 0x00101614, 0x00111613, 0x00111613, 0x00141813, 0x00151916, 0x00151917, 0x00171b17, 0x00171c16, 0x00171c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00151a14, 0x00131712, 0x00111812, 0x00101710, 0x000d150f, 0x000d1510, 0x000d1510, 0x000a140f, 0x000a140f, 0x0009130e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0009110d, 0x0009110d, 0x0008100c, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x00515110, 0x00706412, 0x00cca316, 0x00c5a016, 0x005e5c12, 0x005c5c11, 0x005d5e11, 0x005e5f12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005b5b12, 0x00a68a14, 0x00cca417, 0x00a08514, 0x00585912, 0x00585810, 0x00565711, 0x00555611, 0x00535410, 0x00525310, 0x00515110, 0x00505010, 0x00505010, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00535410, 0x00545511, 0x00565711, 0x00585910, 0x00595a12, 0x005e5c12, 0x00c39e17, 0x00cca418, 0x00756a13, 0x005d5e12, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x005b5b12, 0x00867413, 0x00c8a016, 0x00b08f14, 0x004c4d10, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x0040400c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x0026280a, 0x0026280c, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x000a100a, 0x000a100a, 0x000a100a, 0x0008110a, 0x0008110a, 0x0007110a, 0x0007110a, 0x0007110a, 0x0009100b, 0x0009100c, 0x0008110b, 0x00081109, 0x00061108, 0x00071208, 0x00071208, 0x00061108, 0x00061108, 0x00061108, 0x00061108, 0x00071208, 0x00051008, 0x0008100b, 0x0008100b, 0x0009110c, 0x0008100c, 0x0008110a, 0x0008110a, 0x0009120c, 0x0009140c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000c140e, 0x000e1510, 0x00101711, 0x00131813, 0x00141914, 0x00151a14, 0x00181c15, 0x001a1d17, 0x001b1e18, 0x001c1f18, 0x001c1d18, 0x001c1d18, 0x001c1e16, 0x001c1d14, 0x001a1b14, 0x001a1b14, 0x00181813, 0x00141811, 0x00131712, 0x00101610, 0x000f150f, 0x000d140e, 0x000a120d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0004100c, 0x00030f0b, 0x0005100c, 0x0005100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100a, 0x00061009, 0x0007110a, 0x0007110a, 0x0009130d, 0x0009130e, 0x0009120c, 0x000a130c, 0x000d140d, 0x000f150e, 0x0010160f, 0x0011170e, 0x0012170e, 0x0014170f, 0x0013160e, 0x0013140c, 0x0012150c, 0x0012150c, 0x0013160d, 0x0012150c, 0x0012150c, 0x0014160d, 0x0016180e, 0x0013160c, 0x0011140c, 0x000e1209, 0x00090f05, 0x00080e04, 0x00070e03, 0x00090e02, 0x000b0e03, 0x000c0f05, 0x000c0f07, 0x000c0f06, 0x000a1004, 0x000a1004, 0x000b1005, 0x000b1005, 0x000b1007, 0x000c1005, 0x000d0f05, 0x00101108, 0x00111309, 0x0013120b, 0x00141109, 0x0018140b, 0x001d160a, 0x00231809, 0x00271c08, 0x002c2008, 0x00332408, 0x003a2d0b, 0x0044350c, 0x00523c0d, 0x0064460e, 0x00846210, 0x00c0a330, 0x00ccb420, 0x00ccb80c, 0x00cab90a, 0x00cab80c, 0x00cab80c, 0x00ccb811, 0x00a68606, 0x00795400, 0x00604300, 0x004c3a02, 0x00413208, 0x00382b04, 0x00463810, 0x0045380d, 0x00423509, 0x003f3307, 0x003b3008, 0x003a3010, 0x002e2407, 0x00281f07, 0x0028220c, 0x00201e0b, 0x00141404, 0x000e0e03, 0x000c0e04, 0x000c0f04, 0x0010120a, 0x00131208, 0x00161108, 0x00181009, 0x00181009, 0x001c1208, 0x001d1206, 0x00201408, 0x00221608, 0x00231809, 0x00231808, 0x00261909, 0x002b1b08, 0x002c1a06, 0x002e1a05, 0x00301c07, 0x00311c08, 0x00321c08, 0x00331a07, 0x00331a07, 0x00331a07, 0x00331a07, 0x00341b08, 0x00341b08, 0x00341a0a, 0x00341a0b, 0x00311906, 0x00311908, 0x00301808, 0x002c1707, 0x00281608, 0x00241409, 0x00211308, 0x001f1308, 0x001b1307, 0x00181208, 0x00161106, 0x00131107, 0x00121108, 0x00131008, 0x00111008, 0x00131209, 0x0017140c, 0x00181409, 0x001b1308, 0x00211709, 0x002b2008, 0x003c300f, 0x00433710, 0x00332400, 0x00342303, 0x003c2c07, 0x00473407, 0x005b3f0c, 0x0074520c, 0x00af8f26, 0x00ccb224, 0x00cbb510, 0x00ccb80b, 0x00ccb80a, 0x00ccb411, 0x00b08909, 0x007d5200, 0x00603c00, 0x004f3207, 0x00422a08, 0x003a2704, 0x00301d02, 0x002d1c05, 0x00291a06, 0x00251907, 0x001e1504, 0x001a1304, 0x00181308, 0x0018130a, 0x00141209, 0x00121008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00101009, 0x00100f08, 0x000f100a, 0x000d0f08, 0x000f100a, 0x000f1008, 0x00121009, 0x00100d07, 0x000e0d04, 0x00101108, 0x0010140a, 0x00101409, 0x00121308, 0x00141309, 0x0016140a, 0x00161409, 0x00161409, 0x00151408, 0x00161307, 0x00161408, 0x00161408, 0x00141408, 0x00141409, 0x00151409, 0x0017140a, 0x0017140c, 0x0018160d, 0x0018170e, 0x0018170e, 0x001b1b12, 0x00181810, 0x00171810, 0x00171810, 0x00171810, 0x0014150e, 0x0010140c, 0x000c140c, 0x000a130b, 0x0009120a, 0x0008100a, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x000a120e, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0009110c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0009110d, 0x0007110c, 0x0007110c, 0x0008120d, 0x0008120d, 0x00091310, 0x00091310, 0x000b1410, 0x000c1512, 0x00101614, 0x00111613, 0x00111613, 0x00141813, 0x00151917, 0x00161a18, 0x00171b18, 0x00171c18, 0x00171c16, 0x00171c15, 0x00171c15, 0x00181d16, 0x00171c15, 0x00141813, 0x00121813, 0x00111812, 0x000f1810, 0x000e1611, 0x000e1611, 0x000b1510, 0x000b1510, 0x0008140e, 0x0008140e, 0x0007130d, 0x0007130d, 0x0009110d, 0x0009110d, 0x0008100c, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x00393b0c, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x00515110, 0x00706311, 0x00cca316, 0x00c59f16, 0x005e5c12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005c5c12, 0x00a68a15, 0x00cca417, 0x00a48814, 0x005b5b12, 0x00585910, 0x00565710, 0x00555611, 0x00545511, 0x00535410, 0x00525310, 0x00515110, 0x00515110, 0x00515110, 0x00515110, 0x00515110, 0x00525310, 0x00535410, 0x00545510, 0x00555611, 0x00585810, 0x00585911, 0x00595a12, 0x00615e12, 0x00c5a017, 0x00cca418, 0x00756b13, 0x005e5f12, 0x005e5f13, 0x005d5e11, 0x005d5e11, 0x005c5d11, 0x005b5b12, 0x00595a12, 0x008c7813, 0x00caa116, 0x00af8f14, 0x004b4c10, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x0008110a, 0x0008110a, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x0009130c, 0x0009120a, 0x0009120a, 0x000a130b, 0x000a130b, 0x0009140b, 0x0009140b, 0x0008130a, 0x0008130a, 0x0009120c, 0x0009120c, 0x000a130c, 0x000c120c, 0x000a100a, 0x000a100a, 0x000a130c, 0x0009140c, 0x000b140d, 0x000d140e, 0x000f150f, 0x00101510, 0x00121611, 0x00141813, 0x00151a14, 0x00171914, 0x00181a15, 0x001a1d17, 0x001a1d17, 0x001d1e18, 0x001d1e18, 0x001c1e16, 0x001c1e16, 0x001c1e16, 0x001b1c14, 0x001a1b14, 0x00181a14, 0x00141811, 0x00111611, 0x00101511, 0x00101511, 0x000e1411, 0x000b120e, 0x0008120e, 0x0006120d, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005100a, 0x0006100b, 0x0008100c, 0x0008100c, 0x0009100c, 0x0009100c, 0x0008100c, 0x0009110c, 0x00081009, 0x0009120c, 0x000a140d, 0x000a140d, 0x000f140e, 0x00121410, 0x00131610, 0x00131710, 0x0012170e, 0x0011170e, 0x0012170e, 0x0013160c, 0x0013160c, 0x0015150c, 0x0014140c, 0x0014130a, 0x0014130a, 0x0013140b, 0x0012140b, 0x0013140c, 0x0013140c, 0x0012140a, 0x0013140b, 0x000f1308, 0x0011140a, 0x000c1208, 0x00090e04, 0x00070e03, 0x00070e03, 0x000a0e02, 0x000b0e03, 0x000c0e04, 0x000c0e06, 0x000c0e06, 0x000c1007, 0x000c1007, 0x000c0f08, 0x000c0f08, 0x000f100a, 0x000f1008, 0x000e0f08, 0x00101108, 0x00131209, 0x00131209, 0x0014130a, 0x0019150b, 0x001e1809, 0x00231909, 0x00271c08, 0x002c2008, 0x00342407, 0x003b2d0a, 0x0044350c, 0x00523c0f, 0x0064460d, 0x00846311, 0x00c0a430, 0x00ccb420, 0x00ccb80c, 0x00ccb80a, 0x00ccb80c, 0x00cab80c, 0x00c8b40d, 0x00a48404, 0x00785300, 0x005f4200, 0x004b3802, 0x003f3005, 0x003c2e05, 0x00473910, 0x0045370c, 0x00423408, 0x003e3108, 0x00392e09, 0x00342a0a, 0x002e2408, 0x00231b02, 0x002c2510, 0x00231e0c, 0x00171505, 0x000c0d02, 0x000b0e04, 0x000b0f05, 0x000d1209, 0x0014120c, 0x0016110c, 0x0018100b, 0x00181009, 0x001a1008, 0x001b1007, 0x001c1005, 0x001f1406, 0x00221708, 0x00231708, 0x00251708, 0x00271706, 0x00281805, 0x002c1906, 0x002e1b08, 0x002f1a08, 0x00301a06, 0x00311b08, 0x00331a08, 0x00341908, 0x00341908, 0x00331a07, 0x00331a07, 0x00341b08, 0x00341b08, 0x00341c08, 0x00301807, 0x002d1809, 0x002c180b, 0x00261509, 0x0024140b, 0x00201409, 0x001d1409, 0x001a1208, 0x00181107, 0x00161106, 0x00141007, 0x00121007, 0x00121008, 0x00121008, 0x0014120a, 0x0017140c, 0x0018140b, 0x001b120a, 0x0021180b, 0x002b210b, 0x003b3010, 0x00413510, 0x00342702, 0x00332000, 0x003a2905, 0x00463309, 0x00593d0c, 0x0074520d, 0x00ad8c24, 0x00ccb224, 0x00ccb610, 0x00ccb80a, 0x00ccb808, 0x00cbb411, 0x00b08b0a, 0x007c5300, 0x005f3b00, 0x004e3307, 0x00412b09, 0x00382603, 0x00311e03, 0x002f1d06, 0x002a1c05, 0x00241704, 0x00201604, 0x001b1405, 0x00171106, 0x00161309, 0x00131308, 0x00111007, 0x00101006, 0x00121107, 0x00101006, 0x000e0e05, 0x000f0d06, 0x000f0d07, 0x0010100b, 0x0010100c, 0x000f0f0c, 0x000f0f0c, 0x000d100c, 0x000d100c, 0x00100f08, 0x00101007, 0x000f0f06, 0x00131209, 0x00111309, 0x00101208, 0x00121108, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014140a, 0x00141408, 0x00141407, 0x00141308, 0x00141308, 0x00141408, 0x00141408, 0x0014130a, 0x0014130a, 0x00141308, 0x00141308, 0x00161408, 0x00161408, 0x00171509, 0x0019150c, 0x0019150c, 0x0019160c, 0x0018170c, 0x0018170e, 0x0018180f, 0x00181811, 0x00181810, 0x0016150f, 0x0011130d, 0x000d130e, 0x000c140d, 0x00081009, 0x0008100a, 0x0009120c, 0x00081009, 0x00061009, 0x0008120c, 0x0008120d, 0x0008120d, 0x0008110c, 0x0008120d, 0x0008120f, 0x0008120f, 0x0007110d, 0x0007110d, 0x0008110d, 0x0009110d, 0x0009110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x000a110f, 0x000b100f, 0x000c1110, 0x000d1411, 0x00101513, 0x00101513, 0x00111514, 0x00141716, 0x00141815, 0x00141a16, 0x00151c15, 0x00151c15, 0x00161b15, 0x00181a15, 0x00181b15, 0x00171c17, 0x00151a14, 0x00151a14, 0x00141914, 0x00111812, 0x00111812, 0x000f1713, 0x000f1713, 0x000c1410, 0x000b1510, 0x000c1410, 0x000c1310, 0x000a1410, 0x00091310, 0x000a1210, 0x000a1210, 0x000a1210, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003e400d, 0x0041420e, 0x0045470e, 0x0048490f, 0x004c4d10, 0x00515110, 0x006e6210, 0x00cba216, 0x00c69f15, 0x00646012, 0x005b5b12, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005c5c11, 0x00a08615, 0x00cca417, 0x00b09115, 0x005d5c12, 0x00585911, 0x00585810, 0x00565710, 0x00555611, 0x00545511, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00545511, 0x00555611, 0x00565710, 0x00585910, 0x00595a12, 0x005b5b12, 0x007b6e12, 0x00c8a116, 0x00c49f18, 0x006f6612, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x005c5c12, 0x00595a11, 0x009c8314, 0x00cca316, 0x00ab8c14, 0x004c4d10, 0x004c4d10, 0x00494a0f, 0x0045470e, 0x0041420e, 0x003c3e0c, 0x00393b0c, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130e, 0x000f130f, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000b140d, 0x000c140d, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x0009120a, 0x0009120a, 0x000a130b, 0x000a130b, 0x000a140c, 0x000a140c, 0x0009140b, 0x0009140b, 0x000a130c, 0x000a130c, 0x000a130c, 0x000c120c, 0x000c120c, 0x000b110c, 0x000c140d, 0x000a140d, 0x000c130d, 0x000d140e, 0x00101510, 0x00111611, 0x00121712, 0x00141914, 0x00151a14, 0x00171914, 0x00191c18, 0x001a1d17, 0x001b1e18, 0x001d1e18, 0x001c1d18, 0x001c1e16, 0x001c1e16, 0x001c1e16, 0x001b1c14, 0x001a1b14, 0x00181a14, 0x00141811, 0x00111611, 0x00101511, 0x00101512, 0x000e1411, 0x000a110e, 0x0008120d, 0x0008110c, 0x00051009, 0x00081009, 0x00081009, 0x00081009, 0x0008110a, 0x000a100a, 0x000b110c, 0x000d110c, 0x000e120d, 0x000e120d, 0x000e140e, 0x000d140d, 0x00101710, 0x00101710, 0x00101710, 0x00141610, 0x0016160f, 0x0016160f, 0x0015150e, 0x0014150c, 0x0013140b, 0x0012140a, 0x0014130a, 0x0014130a, 0x00141408, 0x00141408, 0x00141308, 0x00141308, 0x0014130a, 0x0013130a, 0x00121209, 0x00121108, 0x00111108, 0x00131209, 0x00101208, 0x0012140a, 0x00101409, 0x000c1005, 0x000b0e04, 0x00090d03, 0x000a0e03, 0x000b0e04, 0x000c0e04, 0x000c0e04, 0x000c0e05, 0x000c1007, 0x000c1007, 0x000c0f08, 0x000d0e0a, 0x00100f0a, 0x000f1008, 0x000e0f08, 0x00101108, 0x0014130a, 0x0014130a, 0x00161409, 0x001a160b, 0x001f180a, 0x00241b0a, 0x00271c07, 0x002c2008, 0x00342508, 0x003c2e0a, 0x0044340c, 0x00523c0f, 0x0064460d, 0x00846311, 0x00c0a430, 0x00ccb420, 0x00ccb80c, 0x00ccb80a, 0x00ccb80c, 0x00cab80c, 0x00c8b40d, 0x00a48404, 0x00785300, 0x00604300, 0x004c3903, 0x003f3005, 0x003c2e05, 0x00463810, 0x0044370c, 0x00413408, 0x003d3108, 0x00382d0a, 0x0033290a, 0x002c2509, 0x001f1a00, 0x0025200b, 0x00211e0c, 0x00191809, 0x000d1004, 0x00090e03, 0x00090f06, 0x000b1008, 0x0012120b, 0x0014130c, 0x0016100b, 0x00171009, 0x00181108, 0x00181107, 0x001a1105, 0x001d1408, 0x00211808, 0x00231708, 0x00251708, 0x00261807, 0x00271706, 0x00281808, 0x002c1808, 0x002d1806, 0x002d1806, 0x00301808, 0x00301808, 0x00311809, 0x00341909, 0x00321a07, 0x00311b07, 0x00311b07, 0x00311b07, 0x00311b08, 0x00301808, 0x002c1609, 0x002a160b, 0x00241408, 0x00201409, 0x001f1308, 0x001c1308, 0x00191208, 0x00181107, 0x00171106, 0x00141007, 0x00121006, 0x00120e07, 0x00120e07, 0x0015120a, 0x0017140c, 0x0018140b, 0x001b130a, 0x0020180b, 0x002b210b, 0x003a2f10, 0x0040340f, 0x00342702, 0x00332001, 0x00392808, 0x0048330d, 0x005a3d0f, 0x0073510e, 0x00ac8c23, 0x00ccb224, 0x00ccb610, 0x00ccb808, 0x00ccb806, 0x00cbb40f, 0x00b18c09, 0x007c5300, 0x005e3b00, 0x004c3306, 0x00412c09, 0x00372502, 0x00332004, 0x002f1d06, 0x002a1c05, 0x00241704, 0x00211504, 0x001c1505, 0x00181106, 0x00161308, 0x00141308, 0x00131207, 0x00111006, 0x000f0f04, 0x00101005, 0x00101008, 0x00121009, 0x00111009, 0x0010100b, 0x0010100c, 0x00100f0a, 0x00100f0a, 0x000f100a, 0x0010100b, 0x00100f08, 0x00101007, 0x00141109, 0x0014130a, 0x00131008, 0x00141109, 0x00141109, 0x00141109, 0x0014120a, 0x0016120b, 0x00161209, 0x00161208, 0x00161307, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x0016120a, 0x0016120a, 0x00161208, 0x00161208, 0x00171309, 0x00171309, 0x00181408, 0x00181408, 0x00181309, 0x00181309, 0x00161409, 0x0016150b, 0x0017160c, 0x0019170f, 0x00191710, 0x00181710, 0x00191811, 0x00181a14, 0x00171914, 0x00131811, 0x00121710, 0x000f140d, 0x000c110a, 0x000b1009, 0x000a1009, 0x000a100b, 0x000b110c, 0x000a100a, 0x000a100b, 0x000a100c, 0x000a100c, 0x0008100c, 0x0008100c, 0x0009110c, 0x0009110d, 0x0009110c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0009110f, 0x0009110f, 0x000a1210, 0x000c1411, 0x000e1613, 0x000e1613, 0x00101513, 0x00131615, 0x00131815, 0x00131914, 0x00141b14, 0x00151c15, 0x00151c15, 0x00161b15, 0x00161b15, 0x00171c17, 0x00161b15, 0x00151c15, 0x00141a14, 0x00121813, 0x00111812, 0x00101814, 0x00101814, 0x000d1510, 0x000c1711, 0x000f1412, 0x000c1210, 0x000c1411, 0x000a1310, 0x000a120f, 0x000a120e, 0x000a120e, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0044450e, 0x0048490f, 0x004c4d0f, 0x004f5010, 0x006b6010, 0x00c8a015, 0x00c8a015, 0x00736812, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f12, 0x005e5f13, 0x005c5d11, 0x008c7914, 0x00cba417, 0x00c49f17, 0x00696312, 0x00595a12, 0x00585910, 0x00585810, 0x00565710, 0x00555611, 0x00545511, 0x00545511, 0x00535410, 0x00535410, 0x00545510, 0x00545511, 0x00545511, 0x00555610, 0x00565710, 0x00585910, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x00a28814, 0x00cca418, 0x00b79617, 0x00646213, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005b5b12, 0x005b5911, 0x00b09015, 0x00cca316, 0x00a38613, 0x004b4c10, 0x004c4d0f, 0x0048490f, 0x0045470e, 0x0041420d, 0x003e400d, 0x0038380c, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x00292b0b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c130d, 0x000c130d, 0x000c140d, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140d, 0x000b140c, 0x000c140c, 0x000c140c, 0x000c140c, 0x000c140c, 0x000c140c, 0x000b140c, 0x000a130b, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c130d, 0x000c120c, 0x000c130d, 0x000c140d, 0x000b170f, 0x000d160f, 0x00101610, 0x00121812, 0x00141813, 0x00141813, 0x00141914, 0x00161b15, 0x00191a17, 0x001c1c18, 0x001c1c17, 0x001d1e18, 0x001d1e18, 0x001d1e18, 0x001c1e16, 0x001c1e16, 0x001c1e16, 0x001a1c15, 0x00181b12, 0x00171913, 0x00131712, 0x00101511, 0x00111611, 0x00101510, 0x000d1310, 0x000a100b, 0x000a100b, 0x000a1009, 0x00091008, 0x000b1008, 0x000b1009, 0x000f140c, 0x000f140c, 0x0010130c, 0x0010130d, 0x0012140e, 0x0012140e, 0x0013140f, 0x00141510, 0x00141610, 0x00161810, 0x0015160f, 0x0014150f, 0x0014120c, 0x0016140c, 0x0017140d, 0x0018140d, 0x0016140c, 0x0014120c, 0x0014120b, 0x0014120b, 0x0014120b, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x00151208, 0x00161208, 0x00171309, 0x00171309, 0x00141008, 0x00121007, 0x00131108, 0x00131308, 0x0014140a, 0x00101309, 0x000f1007, 0x000c0f04, 0x000c0e04, 0x000c0e04, 0x000c0e04, 0x000d0f05, 0x000d0f06, 0x000e1108, 0x000e1109, 0x000e100b, 0x000f100c, 0x0011100c, 0x0010110a, 0x000f1008, 0x00101208, 0x0014130a, 0x0014130a, 0x00171409, 0x001b150b, 0x001f180a, 0x00241b0a, 0x00271c07, 0x002c2008, 0x00342508, 0x003c2e09, 0x0045340c, 0x00503c10, 0x0064470e, 0x00866413, 0x00c0a432, 0x00ccb420, 0x00ccb80c, 0x00ccb80a, 0x00ccb80c, 0x00ccb80c, 0x00c8b40d, 0x00a48404, 0x00785200, 0x005f4100, 0x004c3803, 0x003d2f04, 0x003a2d05, 0x0044380f, 0x0041340a, 0x0042350c, 0x003c300a, 0x00342b0b, 0x0030280c, 0x002b240b, 0x001d1802, 0x001d1b08, 0x00211f0f, 0x001a190c, 0x00101208, 0x000a0e03, 0x00090e05, 0x000a0e07, 0x000f1009, 0x0013100c, 0x0014100c, 0x00150f0a, 0x0018100a, 0x00181108, 0x00181107, 0x001c1407, 0x00201708, 0x00211707, 0x00221606, 0x00261808, 0x00251605, 0x00281708, 0x00291808, 0x002b1807, 0x002b1807, 0x002d1809, 0x002e1709, 0x00301709, 0x00301809, 0x00301906, 0x00301905, 0x00301905, 0x00301905, 0x00301908, 0x002c1808, 0x002b1709, 0x0028150b, 0x0024140a, 0x00211409, 0x001f1308, 0x001c1308, 0x001a1108, 0x00191008, 0x00181008, 0x00141007, 0x00121008, 0x00120e07, 0x00120e07, 0x0016120a, 0x0017140c, 0x0018140b, 0x001b130a, 0x001f170a, 0x002b210c, 0x00382d11, 0x003f3210, 0x00342602, 0x00321f04, 0x00392809, 0x00453210, 0x00573c11, 0x00725110, 0x00ad8c25, 0x00ccb024, 0x00ccb510, 0x00ccb809, 0x00ccb806, 0x00cbb40f, 0x00b08e0a, 0x007c5400, 0x005e3b00, 0x004c3104, 0x00402c09, 0x00372502, 0x00342005, 0x002f1c05, 0x002b1c06, 0x00261805, 0x00221604, 0x001e1506, 0x00181104, 0x00171308, 0x00151207, 0x00141106, 0x00131107, 0x00121106, 0x00121106, 0x00131107, 0x00131008, 0x0013100a, 0x0012100a, 0x0012100a, 0x00110f09, 0x000f0c06, 0x00100d07, 0x00121008, 0x00121008, 0x00151309, 0x00161409, 0x00141308, 0x00141208, 0x00141208, 0x00141108, 0x00141008, 0x00151108, 0x00161208, 0x00171307, 0x00181206, 0x00181306, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00171408, 0x00171408, 0x00171408, 0x00171408, 0x00181208, 0x00161208, 0x00161309, 0x00151409, 0x0015140a, 0x0015140b, 0x0015140b, 0x0015140b, 0x0015140c, 0x0014140c, 0x0014140c, 0x0016160f, 0x00181710, 0x00181810, 0x00181811, 0x00151710, 0x0014150e, 0x0010110b, 0x0010110c, 0x0010110c, 0x000d100b, 0x000c0f09, 0x000c100c, 0x000c100c, 0x000a110c, 0x000b110c, 0x000a110c, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006120c, 0x0006120c, 0x0005110b, 0x0005110b, 0x0006120c, 0x0007110c, 0x0008110d, 0x0008110d, 0x0009120f, 0x000b1410, 0x000c1411, 0x000c1411, 0x000e1513, 0x00101614, 0x00111814, 0x00111913, 0x00131a14, 0x00141c15, 0x00151c15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151c15, 0x00151c15, 0x00141a14, 0x00111812, 0x00101812, 0x00101813, 0x000f1811, 0x000e1610, 0x00111414, 0x000f1311, 0x000f1412, 0x000c1411, 0x000c1410, 0x000c1410, 0x000c1410, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0048490e, 0x004b4c0f, 0x004f5010, 0x00635b10, 0x00c09b14, 0x00c9a116, 0x008a7613, 0x00595a12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e12, 0x005d5e11, 0x006d6612, 0x00c49f17, 0x00cba417, 0x00988114, 0x005b5b12, 0x00595a12, 0x00585910, 0x00585810, 0x00565710, 0x00565711, 0x00555611, 0x00565711, 0x00555611, 0x00555611, 0x00555611, 0x00565710, 0x00585810, 0x00585910, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x00756b13, 0x00c4a018, 0x00cca418, 0x009e8415, 0x005c5d13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x00605c11, 0x00c39c16, 0x00cca216, 0x00917912, 0x004d4e10, 0x004b4c0f, 0x0048490f, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x000f130b, 0x000f130f, 0x000f130f, 0x000b140d, 0x000b140d, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000e140e, 0x000e140e, 0x000d140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140d, 0x000c140c, 0x000c140c, 0x000c150c, 0x000c150c, 0x000c140c, 0x000c140c, 0x000c150c, 0x000c140c, 0x000c140e, 0x000c140e, 0x000c140d, 0x000c130d, 0x000c130d, 0x000e140f, 0x000c140e, 0x000c1710, 0x000e1610, 0x00101710, 0x00131813, 0x00141914, 0x00141914, 0x00151a14, 0x00181a16, 0x001b1c18, 0x001c1c18, 0x001e1c18, 0x001d1e18, 0x001e1e18, 0x001d1e18, 0x001c1e16, 0x001b1d15, 0x00191c14, 0x00181c14, 0x00181b12, 0x00171913, 0x00141711, 0x00121410, 0x00101410, 0x00111610, 0x00111610, 0x0010140e, 0x0010140d, 0x0010140c, 0x0010140c, 0x0012140c, 0x0014140e, 0x0014150e, 0x0014160f, 0x00141610, 0x00151610, 0x00181710, 0x00181710, 0x0014140c, 0x0016140f, 0x0017150e, 0x0018150e, 0x0018140d, 0x0018140d, 0x0016130b, 0x00181209, 0x0017130c, 0x0018140c, 0x0017140c, 0x0017130c, 0x0017130c, 0x0017140d, 0x0017140d, 0x0016140b, 0x0016140b, 0x00161309, 0x00161309, 0x00151308, 0x00141208, 0x00141007, 0x00151108, 0x00151108, 0x00151208, 0x00141308, 0x00141308, 0x0014140a, 0x00131209, 0x00101208, 0x000f1007, 0x000c0e04, 0x000c0e04, 0x000c0e04, 0x000d0f05, 0x000d1006, 0x000e1109, 0x000e1109, 0x000e110b, 0x0010100c, 0x0012100c, 0x0010120a, 0x00101109, 0x0012140a, 0x0014130a, 0x0015140b, 0x0018140b, 0x001c160c, 0x0021180b, 0x00241c0b, 0x00291f09, 0x002e2209, 0x00352708, 0x003d2f0a, 0x0044360c, 0x00503c0f, 0x0064480e, 0x00866414, 0x00c1a433, 0x00ccb421, 0x00ccb80c, 0x00ccb80a, 0x00ccb80c, 0x00cbb80c, 0x00c8b40d, 0x00a48404, 0x00765300, 0x005f4000, 0x004b3704, 0x003d2e04, 0x00392c04, 0x0044380e, 0x003d3007, 0x003c3008, 0x00342c08, 0x00302809, 0x002c250c, 0x0028220b, 0x001c1904, 0x001b1a08, 0x001e1d0f, 0x0017180c, 0x000f1108, 0x000a0f04, 0x00080e05, 0x00090e07, 0x000d0d08, 0x0011100a, 0x0014100b, 0x0014100a, 0x0018110a, 0x00181108, 0x00181107, 0x001a1304, 0x001e1506, 0x001e1505, 0x00201504, 0x00241807, 0x00221404, 0x00271608, 0x00281708, 0x00291807, 0x002a1706, 0x002b1808, 0x002c1708, 0x002d1708, 0x002f1708, 0x002e1805, 0x002d1804, 0x002d1804, 0x002d1804, 0x002e1808, 0x002c1608, 0x0029150a, 0x0027140b, 0x0023140a, 0x00201309, 0x001f1308, 0x001c1207, 0x001a1008, 0x00191008, 0x00170f07, 0x00141007, 0x00110f07, 0x00120e07, 0x00120e07, 0x0016120a, 0x0018140c, 0x0018140b, 0x001a1409, 0x001c1407, 0x00271e08, 0x00362c10, 0x003d3010, 0x00332404, 0x00311e03, 0x0038260a, 0x0044310f, 0x00553910, 0x00704f0f, 0x00ac8b28, 0x00ccaf2a, 0x00ccb416, 0x00ccb70e, 0x00ccb80a, 0x00cbb40d, 0x00b08e0a, 0x007b5400, 0x005e3b00, 0x004b3004, 0x00402b09, 0x00372502, 0x00342005, 0x002e1c05, 0x002b1c06, 0x00281b07, 0x00241806, 0x00201705, 0x001c1204, 0x00191408, 0x00181307, 0x00151308, 0x00141308, 0x00141308, 0x00141308, 0x00141308, 0x00141108, 0x00131008, 0x00131009, 0x00141109, 0x00141108, 0x00110e04, 0x00110e04, 0x00141007, 0x00141307, 0x00141207, 0x00161408, 0x00161408, 0x00141308, 0x00141307, 0x00151408, 0x00161408, 0x00181308, 0x001a1307, 0x001a1305, 0x00191305, 0x00191305, 0x00191306, 0x00191307, 0x00191307, 0x00191208, 0x00191208, 0x00191208, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x00171408, 0x00171408, 0x00181108, 0x00161208, 0x00141208, 0x00141308, 0x00141309, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x00141309, 0x00141309, 0x00141409, 0x00141409, 0x00161309, 0x00161309, 0x001a170d, 0x0018150c, 0x0018150e, 0x0018150e, 0x0018160e, 0x0014140c, 0x0014130c, 0x0012140c, 0x0012140e, 0x000f120c, 0x000a100a, 0x00080f08, 0x0007100a, 0x0006100b, 0x0007110c, 0x0006120c, 0x0006120c, 0x0005130c, 0x0005130c, 0x0004110b, 0x0004110b, 0x0005130c, 0x0005120c, 0x0006110d, 0x0006110d, 0x0006110d, 0x0008130f, 0x000a1511, 0x000a1511, 0x000c1512, 0x000f1714, 0x000f1714, 0x00101912, 0x00101a13, 0x00111b14, 0x00141c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00131914, 0x00111913, 0x00121a14, 0x000f1811, 0x00101812, 0x00111514, 0x00101211, 0x00101412, 0x000f1412, 0x000d1410, 0x000d150f, 0x000c140f, 0x00060c07, 0x000f130f, 0x000f130f, 0x0014180f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x002c2d0b, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c10, 0x004d4e0f, 0x00585510, 0x00b69314, 0x00cca316, 0x00a48814, 0x005b5a12, 0x005b5b12, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5d11, 0x009f8615, 0x00cca417, 0x00c49f17, 0x00736813, 0x00595a12, 0x00595a12, 0x00585910, 0x00585910, 0x00585810, 0x00585810, 0x00565711, 0x00565711, 0x00565710, 0x00585810, 0x00585810, 0x00585911, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x00646112, 0x00b19316, 0x00cca418, 0x00c7a118, 0x00766c14, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x007f7012, 0x00c8a016, 0x00cba216, 0x00786811, 0x004d4e10, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x0030310c, 0x00292b0a, 0x0026280b, 0x0024250b, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x000c140e, 0x000c140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000f150f, 0x000f150f, 0x000d150f, 0x000d150f, 0x000c140e, 0x000c140e, 0x000c140d, 0x000c140c, 0x000c140c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000d140d, 0x000d140d, 0x000e140e, 0x000f150f, 0x000f150f, 0x0010140f, 0x000f1410, 0x00101510, 0x00131713, 0x00141714, 0x00151814, 0x00171814, 0x00171814, 0x00181914, 0x00191a17, 0x001c1c18, 0x001d1c18, 0x001f1e18, 0x001d1e18, 0x001d1f18, 0x001b1d16, 0x001b1d15, 0x001a1d15, 0x00181c13, 0x00171a11, 0x00161910, 0x00161811, 0x00151711, 0x00141610, 0x0012140d, 0x0012160e, 0x00141810, 0x00141710, 0x0014160d, 0x0015150d, 0x0015150d, 0x0017150d, 0x0017150d, 0x0017150e, 0x0017150d, 0x0014130b, 0x0015140b, 0x0016130c, 0x0017140c, 0x0014130b, 0x0015130b, 0x0016140a, 0x0016140b, 0x0016140b, 0x0017140b, 0x0017140a, 0x00151308, 0x0017140b, 0x0018140c, 0x0018140b, 0x0018140b, 0x0018140b, 0x0018140c, 0x0018140c, 0x0017140b, 0x0017140a, 0x00161409, 0x00161409, 0x00151409, 0x00151409, 0x0017130a, 0x0017130a, 0x0017140b, 0x0017130a, 0x00151209, 0x0016130a, 0x0017130a, 0x0016130a, 0x00141208, 0x00111108, 0x000f1006, 0x000f0d04, 0x000f0d05, 0x00111008, 0x00101008, 0x00101209, 0x00101209, 0x0010120a, 0x0010110a, 0x00121109, 0x00121109, 0x00141209, 0x00151309, 0x00161309, 0x0018140a, 0x001a150a, 0x001e1809, 0x00231808, 0x00271a09, 0x002c1e08, 0x00302208, 0x00372708, 0x003e2f09, 0x0044370b, 0x004f3d0c, 0x0064480c, 0x00866414, 0x00bea130, 0x00ccb421, 0x00ccb80c, 0x00cbb80a, 0x00cbb80c, 0x00cbb90d, 0x00c9b60f, 0x00a48604, 0x00765200, 0x005f4000, 0x004a3604, 0x003c2f05, 0x00382c04, 0x0044370f, 0x003b2f06, 0x00352b04, 0x00342c08, 0x0030290c, 0x0029230b, 0x0024210c, 0x001c1a08, 0x00191808, 0x001a1b0c, 0x00131509, 0x000d1107, 0x00090f04, 0x00070e04, 0x00080e05, 0x000c0e07, 0x00100f08, 0x0013100b, 0x0014100a, 0x0016100a, 0x00181108, 0x00181207, 0x00181305, 0x001c1407, 0x001c1405, 0x001e1406, 0x00201508, 0x00211407, 0x00251709, 0x0028180a, 0x00281708, 0x00281708, 0x00281708, 0x00281708, 0x00291708, 0x002b1608, 0x002b1706, 0x002b1706, 0x002c1806, 0x002c1806, 0x002b1708, 0x00291509, 0x00261409, 0x0024130a, 0x0021140a, 0x001e1309, 0x001d1208, 0x001c110a, 0x001b1008, 0x00191008, 0x00170f07, 0x00141008, 0x00120e07, 0x00110f08, 0x00110f08, 0x00141109, 0x0016140a, 0x0018140b, 0x00191408, 0x001c1407, 0x00231b08, 0x00322711, 0x003b2e14, 0x00312408, 0x002f1e03, 0x00382809, 0x0044310c, 0x0052370c, 0x006d4b0c, 0x00ac8a28, 0x00ccb12b, 0x00ccb417, 0x00cbb50f, 0x00cbb60a, 0x00cbb60e, 0x00af8e0a, 0x007a5300, 0x005e3a00, 0x004c2f04, 0x00402b09, 0x00362602, 0x00342005, 0x002f1c07, 0x002c1c08, 0x00291b08, 0x00261808, 0x00221706, 0x00201408, 0x001c1508, 0x001a1407, 0x00181306, 0x00181208, 0x00181208, 0x00171107, 0x00151208, 0x00151208, 0x00141208, 0x00121108, 0x00141308, 0x00151408, 0x00181409, 0x00151206, 0x00151106, 0x00181208, 0x00161005, 0x00171207, 0x00181208, 0x00171208, 0x00181409, 0x00171408, 0x00181508, 0x001b1408, 0x001c1408, 0x001c1405, 0x001c1405, 0x001c1405, 0x001d1405, 0x001d1407, 0x001e1408, 0x001d1408, 0x001c1408, 0x001c1409, 0x001c1408, 0x001d1508, 0x001c1508, 0x001c1608, 0x00181307, 0x00171408, 0x00181108, 0x00171109, 0x00161109, 0x00141108, 0x00141209, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x00141309, 0x00141309, 0x00151008, 0x00171109, 0x00171109, 0x0018120a, 0x0019130b, 0x0019130b, 0x0017140c, 0x0017140c, 0x0019170f, 0x0018160e, 0x0017150f, 0x0017150f, 0x00181710, 0x00181710, 0x00141510, 0x00101510, 0x00101410, 0x000c120d, 0x000b110c, 0x0008100b, 0x0008110b, 0x0006130c, 0x0006130c, 0x0006110a, 0x0006110a, 0x0007110b, 0x0007110b, 0x0006110a, 0x0008120c, 0x0006120b, 0x0006130c, 0x0008140f, 0x000b1510, 0x000b1510, 0x000d1712, 0x000e1812, 0x000f1812, 0x00101a13, 0x00111c14, 0x00131c15, 0x00141c14, 0x00141c14, 0x00161c15, 0x00161c15, 0x00161c15, 0x00161c15, 0x00161c14, 0x00151a14, 0x00131a14, 0x00131914, 0x00101812, 0x00101812, 0x00131714, 0x00111412, 0x00101512, 0x00101411, 0x000d140f, 0x000d150f, 0x000c140e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004c4d0f, 0x004d4e10, 0x00a48714, 0x00cca316, 0x00be9915, 0x00615d12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x00696412, 0x00b99816, 0x00cca417, 0x00b49415, 0x00696312, 0x005b5b12, 0x00595a12, 0x00585911, 0x00585910, 0x00585910, 0x00585910, 0x00585910, 0x00585910, 0x00585911, 0x00595a12, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x00605e12, 0x00a38815, 0x00cca418, 0x00cca418, 0x00a48815, 0x00605f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5c11, 0x005b5b12, 0x00595a11, 0x00a08514, 0x00cca316, 0x00bf9915, 0x00615a10, 0x004d4e0f, 0x00494a0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0036370b, 0x0034350c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x000d150f, 0x000c150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x00101610, 0x00101610, 0x000e150f, 0x000d150f, 0x000d150f, 0x000e1610, 0x000d150f, 0x000d150f, 0x000d150f, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x0010160d, 0x0010160d, 0x00101710, 0x00101710, 0x00101610, 0x00101510, 0x00141613, 0x00151613, 0x00161714, 0x00171814, 0x00171814, 0x00181814, 0x00181814, 0x001a1a15, 0x001c1b17, 0x001e1c17, 0x001f1e18, 0x001f1e18, 0x001f1e18, 0x001e2018, 0x001c1e16, 0x00191c13, 0x00171a10, 0x0017190f, 0x0014170c, 0x0013150d, 0x0014150d, 0x0015150f, 0x0014140d, 0x0013140b, 0x0013140b, 0x0012140b, 0x0014140b, 0x0014140b, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0015130a, 0x0015130a, 0x0014130a, 0x0014130a, 0x00151108, 0x00151108, 0x00141108, 0x00151208, 0x00141308, 0x00161409, 0x00151409, 0x00151409, 0x00151408, 0x00171408, 0x00171409, 0x00181409, 0x00181409, 0x00181408, 0x001a1408, 0x001b1408, 0x00191408, 0x00181408, 0x00181408, 0x00181408, 0x00181409, 0x00181308, 0x00181309, 0x0018130a, 0x0018130a, 0x0018130a, 0x0018130a, 0x00181309, 0x00181109, 0x00181008, 0x00181007, 0x00161208, 0x00141207, 0x00141108, 0x00141108, 0x00141008, 0x00131007, 0x00131108, 0x00131409, 0x00121308, 0x00121308, 0x00131308, 0x00141208, 0x00151108, 0x00181308, 0x00191408, 0x001a1408, 0x001b1409, 0x001e1708, 0x00221808, 0x00261808, 0x002b1a08, 0x002f1e08, 0x00342208, 0x00382709, 0x003e2f09, 0x0044360b, 0x00503c0c, 0x0064480c, 0x00876414, 0x00bca02e, 0x00ccb421, 0x00ccb80c, 0x00cab90a, 0x00cbb90c, 0x00cbba0e, 0x00cab810, 0x00a48805, 0x00745100, 0x00604100, 0x004a3505, 0x003c2f07, 0x00382c04, 0x0042370f, 0x003b2f07, 0x00342803, 0x002e2605, 0x002b2509, 0x00262009, 0x00221f0c, 0x001b1809, 0x00161507, 0x0017180b, 0x00131509, 0x000e1208, 0x000a1006, 0x00070e04, 0x00070e04, 0x000c0e08, 0x00100f08, 0x00100e0a, 0x00101009, 0x00140f09, 0x00141008, 0x00171207, 0x00181205, 0x001a1407, 0x001b1407, 0x001d1408, 0x0020140a, 0x00201409, 0x00241809, 0x0026170a, 0x0027170a, 0x0027170a, 0x00241708, 0x00241708, 0x00261608, 0x00261508, 0x00261607, 0x00261607, 0x00281708, 0x00281809, 0x0028160a, 0x00251409, 0x0023140a, 0x0021140a, 0x0020140a, 0x001d140a, 0x001c120a, 0x001b1008, 0x001a1008, 0x00181008, 0x00161007, 0x00140e08, 0x00110f07, 0x00100f08, 0x00100f08, 0x00131109, 0x00141409, 0x0017140b, 0x00181408, 0x001c1507, 0x00221a0a, 0x002b2010, 0x00342713, 0x0030210a, 0x002f1d04, 0x00382708, 0x00422e0a, 0x0053350b, 0x006e4c0b, 0x00a98823, 0x00caac24, 0x00cbb10f, 0x00cab408, 0x00cbb406, 0x00ccb411, 0x00ae8c0b, 0x00785000, 0x005c3800, 0x004c3004, 0x00412c09, 0x00372703, 0x00342006, 0x00301c07, 0x002f1c08, 0x002c1c08, 0x002b1b08, 0x00251806, 0x00231708, 0x00201609, 0x001c1408, 0x001c1306, 0x001c1306, 0x001b1307, 0x00191108, 0x00181108, 0x00181308, 0x00171408, 0x00141308, 0x00161408, 0x001a170b, 0x001e1a0e, 0x001d180c, 0x001b1509, 0x001d1409, 0x001c1208, 0x001d1409, 0x001d1409, 0x001d1409, 0x001d150a, 0x001d160a, 0x001d1709, 0x00201708, 0x00201706, 0x00201707, 0x00221708, 0x00221708, 0x00241708, 0x00241708, 0x00241808, 0x00241808, 0x00231809, 0x0023180a, 0x00221708, 0x00211707, 0x00211807, 0x00201808, 0x001c1407, 0x001a1409, 0x001a140a, 0x0019120b, 0x00181209, 0x00171109, 0x0017120a, 0x0015130a, 0x0015130a, 0x0014130a, 0x0014130a, 0x0015120a, 0x0016120a, 0x00161109, 0x00161109, 0x0018110a, 0x0018110a, 0x0018110a, 0x0018110a, 0x0016120a, 0x0015140a, 0x0015140b, 0x0016140c, 0x0017140d, 0x0018140d, 0x0018140e, 0x0018150f, 0x00171610, 0x00161812, 0x00161813, 0x00141611, 0x0011140e, 0x0010140d, 0x000f150c, 0x000b140b, 0x00091409, 0x00091208, 0x000a1208, 0x00091108, 0x00091008, 0x00081007, 0x000a1309, 0x00081309, 0x00081409, 0x0008120c, 0x0009140d, 0x000b150f, 0x000c1710, 0x000e1811, 0x000f1812, 0x000f1912, 0x00101b14, 0x00121c14, 0x00141c14, 0x00151c14, 0x00171c15, 0x00181c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00171c14, 0x00151c16, 0x00141b14, 0x00121813, 0x00121813, 0x00141914, 0x00141814, 0x00131713, 0x00111511, 0x00101610, 0x00101710, 0x000f1610, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0041420d, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x004d4e10, 0x00847011, 0x00cba216, 0x00c9a116, 0x00827113, 0x00595a12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x00786e13, 0x00c19c17, 0x00cca417, 0x00b09115, 0x006c6412, 0x00595a12, 0x005b5b12, 0x00595a12, 0x00595a12, 0x00595a12, 0x00595a12, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x005c5c12, 0x005b5b11, 0x00646112, 0x00a38815, 0x00caa418, 0x00cca418, 0x00b89717, 0x006b6513, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x005b5b12, 0x00615d11, 0x00be9916, 0x00cca316, 0x00a88914, 0x00505010, 0x004c4d0f, 0x00494a0f, 0x0045470e, 0x0041420e, 0x003c3e0c, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x001d200a, 0x00191c0b, 0x0014180b, 0x000f130d, 0x000f130f, 0x000f130f, 0x000e150f, 0x000e150f, 0x00101610, 0x00101610, 0x00101610, 0x00101610, 0x00101611, 0x00101711, 0x00101610, 0x000f1610, 0x000f1710, 0x00101811, 0x00101711, 0x000f1610, 0x000f1710, 0x00101811, 0x00101811, 0x00101811, 0x00101811, 0x000f1610, 0x000f1610, 0x00101710, 0x00101710, 0x00101710, 0x00101710, 0x00101710, 0x00111610, 0x00161813, 0x00181814, 0x00181814, 0x00181713, 0x001a1813, 0x001c1a14, 0x001c1b14, 0x001c1c16, 0x001d1c14, 0x001d1d15, 0x001e1d15, 0x001d1c14, 0x001c1c14, 0x00181911, 0x00161810, 0x0016180e, 0x0016180e, 0x0015170d, 0x0014150c, 0x0014140c, 0x0014120c, 0x0014120c, 0x0014120c, 0x0014130a, 0x0013130a, 0x0014140a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x00141109, 0x00141107, 0x00141107, 0x00141108, 0x00151208, 0x00151308, 0x00161409, 0x0017140a, 0x00181309, 0x00181408, 0x00181408, 0x001a1408, 0x001b1408, 0x001b1408, 0x001c1407, 0x001c1408, 0x001d1508, 0x001c1406, 0x001c1405, 0x001c1405, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1308, 0x001c1309, 0x001c130a, 0x001c130a, 0x001c130a, 0x001c140b, 0x001c140b, 0x001e150a, 0x001d150a, 0x001b1409, 0x00191509, 0x001b160b, 0x001b160c, 0x001b160c, 0x00181409, 0x00141006, 0x00151408, 0x00151408, 0x00141408, 0x00151408, 0x00171408, 0x00181308, 0x001a1308, 0x001b1408, 0x001d1508, 0x001d1508, 0x00201708, 0x00241a08, 0x00281908, 0x002d1c08, 0x00311f08, 0x00362308, 0x003b2808, 0x00402e09, 0x0047340b, 0x00513a0a, 0x0064460b, 0x00846312, 0x00bca02e, 0x00ccb421, 0x00ccb80c, 0x00cab90a, 0x00cab80c, 0x00caba0d, 0x00c9b810, 0x00a68908, 0x00745200, 0x005e4000, 0x004a3406, 0x003c2c06, 0x00362a04, 0x0040350e, 0x003c3109, 0x00332904, 0x002a2103, 0x00251f06, 0x00241f0a, 0x00201d0e, 0x0018180c, 0x00131407, 0x00111408, 0x0012160c, 0x000e1409, 0x000a1007, 0x00060f04, 0x00070f04, 0x000b0e08, 0x000f1009, 0x0010100b, 0x00101109, 0x00121009, 0x00141008, 0x00151206, 0x00171305, 0x00191306, 0x001b1407, 0x001c1408, 0x001c1308, 0x001d1308, 0x00201508, 0x00231608, 0x00241508, 0x00241508, 0x00211508, 0x00231408, 0x00241408, 0x00241408, 0x00241407, 0x00241406, 0x00251608, 0x00261708, 0x00241408, 0x00211308, 0x00201409, 0x001f1409, 0x001c1309, 0x001b1309, 0x001a1108, 0x00191008, 0x00181008, 0x00161008, 0x00140f07, 0x00120f07, 0x00100f08, 0x000f0f07, 0x000f0f07, 0x00121309, 0x00131408, 0x0015140a, 0x00171407, 0x001a1507, 0x00201909, 0x00261c0c, 0x002a1c0b, 0x002e2009, 0x002e1c05, 0x0037260a, 0x00402b09, 0x0052340b, 0x00684506, 0x00ab8726, 0x00ccac28, 0x00cbb012, 0x00ccb10c, 0x00cbb00b, 0x00cbac1c, 0x00a9810e, 0x00764c01, 0x00593600, 0x004c3004, 0x00412c0a, 0x003a2804, 0x00382107, 0x00341e06, 0x00301c05, 0x002f1c06, 0x002d1c07, 0x00291906, 0x00271808, 0x00241809, 0x00211608, 0x00201407, 0x00201408, 0x00201407, 0x001c1306, 0x001a1207, 0x00191308, 0x00181407, 0x00171306, 0x00191408, 0x001d180c, 0x00231c0f, 0x00231b0f, 0x0021190c, 0x0024180c, 0x0024180b, 0x0025180c, 0x0027190c, 0x0026190c, 0x00271a0c, 0x00281b0c, 0x00281b0a, 0x00281a08, 0x00281a0a, 0x00281b0b, 0x002a1b0c, 0x00291a09, 0x002a1a09, 0x002a1a09, 0x002b1b09, 0x002b1b09, 0x002a1b0b, 0x002a1b0b, 0x00281a0a, 0x00271808, 0x00241906, 0x00231807, 0x00201708, 0x001e1708, 0x001d150a, 0x001c130a, 0x001a1309, 0x00181208, 0x00181109, 0x0018110a, 0x0017120a, 0x0017120a, 0x0016120a, 0x0016120a, 0x0016120a, 0x0016120a, 0x00141008, 0x00151008, 0x00151008, 0x00151109, 0x00141109, 0x00141008, 0x00131008, 0x00141109, 0x00141109, 0x0014120b, 0x0014120c, 0x0014120b, 0x0014130c, 0x0016140f, 0x00161510, 0x0014140f, 0x0014140e, 0x0014140e, 0x0016160f, 0x0015180f, 0x0014180e, 0x0010160c, 0x0010140b, 0x0010140b, 0x000e1309, 0x000c1108, 0x000c1007, 0x000d1208, 0x000c1308, 0x000a1308, 0x000a130b, 0x000a130c, 0x0009130c, 0x000b140d, 0x000c170f, 0x000d1810, 0x000e1810, 0x000f1911, 0x00111b13, 0x00141b13, 0x00161c14, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00161c17, 0x00161c17, 0x00141a14, 0x00141a14, 0x00161b15, 0x00141914, 0x00141914, 0x00141813, 0x00121712, 0x00121812, 0x00111711, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004d4e10, 0x00605911, 0x00c09a14, 0x00cca316, 0x00ae8e14, 0x005c5b12, 0x005c5c12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x007c7013, 0x00bf9b17, 0x00cca417, 0x00bc9916, 0x00847413, 0x00605d12, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005c5c12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x00786d13, 0x00b39317, 0x00cca418, 0x00cca418, 0x00bb9917, 0x00736a14, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5c12, 0x00595a12, 0x00887512, 0x00caa116, 0x00caa016, 0x007c6c11, 0x004d4e10, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0036370c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x000f130f, 0x00101610, 0x00101610, 0x00101710, 0x00101710, 0x00101710, 0x00101710, 0x00111611, 0x00121611, 0x00111711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00111711, 0x00111711, 0x00121812, 0x00121812, 0x00121810, 0x00121810, 0x00121810, 0x00121810, 0x00131910, 0x00151910, 0x00171810, 0x00191810, 0x00191810, 0x00191710, 0x001b1811, 0x001c1912, 0x001b1811, 0x00191810, 0x0018180f, 0x0018170e, 0x0018170e, 0x0018150c, 0x00141309, 0x00111309, 0x00111309, 0x00131309, 0x00141209, 0x00141209, 0x00141209, 0x0014100a, 0x00131009, 0x0013100a, 0x0013100a, 0x00111008, 0x00121108, 0x00121108, 0x00131109, 0x00141209, 0x0014130a, 0x0014130a, 0x0013120a, 0x0013120a, 0x0013120a, 0x0013120a, 0x00131209, 0x00131209, 0x00141208, 0x00141208, 0x00141207, 0x00151308, 0x00181309, 0x00181309, 0x001a140b, 0x001a140a, 0x001c140a, 0x001d1609, 0x001e160a, 0x0020160a, 0x00201609, 0x00201708, 0x00201708, 0x00201809, 0x00201808, 0x00221807, 0x00221807, 0x00241808, 0x00241809, 0x00241809, 0x00241809, 0x0024180c, 0x0024180c, 0x0024180c, 0x0024180c, 0x0024180d, 0x0024190e, 0x0025190e, 0x0023180c, 0x0021180c, 0x00211a0d, 0x00201a0f, 0x0020190e, 0x001f190e, 0x001b1409, 0x00181206, 0x00171508, 0x00171508, 0x00161407, 0x00171407, 0x001a150a, 0x001c140a, 0x001d1509, 0x001e1708, 0x0020180a, 0x00201809, 0x00241a09, 0x00281c08, 0x002c1c09, 0x00311e0a, 0x00352109, 0x003b2508, 0x0040290b, 0x00452f0c, 0x004a340c, 0x0054390a, 0x00644409, 0x00805e0d, 0x00ba9c2c, 0x00ccb421, 0x00ccb80c, 0x00cab90a, 0x00cab80c, 0x00c8b90c, 0x00c9b810, 0x00a88b09, 0x00755200, 0x005c3d00, 0x004b3407, 0x003a2a04, 0x00302400, 0x003d310a, 0x003d330a, 0x00342b08, 0x002c2207, 0x00241e08, 0x00201a08, 0x001b190b, 0x0014150b, 0x00101207, 0x000e1308, 0x0010150c, 0x000c1209, 0x00091006, 0x00071005, 0x00080f05, 0x00090d06, 0x000c0f07, 0x0010100b, 0x00101109, 0x0012110a, 0x00131008, 0x00151307, 0x00151305, 0x00181406, 0x001a1407, 0x001b1407, 0x001c1307, 0x001c1306, 0x001c1407, 0x00201408, 0x00201308, 0x00201308, 0x001e1307, 0x001f1207, 0x00211308, 0x00221208, 0x00201307, 0x00201406, 0x00221408, 0x00211407, 0x00211408, 0x001f1308, 0x001d1309, 0x001c1408, 0x00191308, 0x00191208, 0x00181208, 0x00181008, 0x00171008, 0x00151008, 0x00130f08, 0x00100f07, 0x00100f08, 0x000d0f05, 0x000d0f05, 0x00101308, 0x00111308, 0x00141208, 0x00161306, 0x00181306, 0x001c1408, 0x0022170b, 0x0027190b, 0x002c1d0a, 0x002e1c06, 0x00352405, 0x00402c06, 0x004e300a, 0x00644008, 0x00a27b28, 0x00c49e2c, 0x00c2a019, 0x00bf9f14, 0x00be9b13, 0x00c2941d, 0x009c6d0c, 0x006e4201, 0x00563400, 0x00493106, 0x00432e0b, 0x003d2907, 0x003b2208, 0x00382008, 0x00341e06, 0x00301c05, 0x00301c05, 0x002e1b06, 0x002b1908, 0x00281909, 0x00251808, 0x00251707, 0x00251607, 0x00241707, 0x00221508, 0x00201408, 0x001f150a, 0x001d160a, 0x001a1407, 0x00181206, 0x001b1305, 0x001d1407, 0x001e1508, 0x001e1406, 0x00231608, 0x00251808, 0x00251807, 0x00291a0b, 0x002c1c0c, 0x002e1c0c, 0x002f1d0b, 0x002f1d0a, 0x00301e0a, 0x00311e0b, 0x00321e0d, 0x00311e0c, 0x00301c08, 0x00301c08, 0x00311c09, 0x00321d0a, 0x00311d0a, 0x00301d0b, 0x00301d0c, 0x002e1c09, 0x002c1b08, 0x00291a07, 0x00281b08, 0x00271b08, 0x00241908, 0x00201608, 0x001d1408, 0x001e150b, 0x001c140a, 0x001a1208, 0x001a1208, 0x00191208, 0x0018120a, 0x0018130a, 0x0017130b, 0x0017130b, 0x0016130b, 0x00141008, 0x00111008, 0x00121008, 0x00121008, 0x00131009, 0x00131009, 0x00131009, 0x00131009, 0x00131009, 0x0013120b, 0x0013120b, 0x0012110a, 0x0013120b, 0x0013120a, 0x0012110a, 0x0013120b, 0x0013120a, 0x0014110a, 0x00141209, 0x0015140b, 0x0013140a, 0x0013140a, 0x0013140a, 0x0013140a, 0x0014140b, 0x0013140a, 0x0013140a, 0x0013140a, 0x0012150a, 0x00101409, 0x000d150b, 0x000c150c, 0x000c140c, 0x000c150c, 0x000c170d, 0x000e1810, 0x000f1910, 0x000e1810, 0x00121a11, 0x00151a11, 0x00171c12, 0x00191c14, 0x00191c14, 0x001b1c16, 0x00181c16, 0x00191c16, 0x00181d16, 0x00161c17, 0x00161c17, 0x00151c15, 0x00151c15, 0x00161b14, 0x00151a14, 0x00151a14, 0x00141813, 0x00131712, 0x00131712, 0x00131712, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280c, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x00494a0f, 0x004c4d0f, 0x00505010, 0x009e8213, 0x00cca316, 0x00c8a015, 0x007b6d12, 0x00595a12, 0x005c5c12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x00736a13, 0x00b49415, 0x00cba417, 0x00c9a318, 0x00b19216, 0x00897714, 0x00686212, 0x00605d11, 0x00605d12, 0x00605e12, 0x00636012, 0x007c7013, 0x00a68916, 0x00c6a118, 0x00cca418, 0x00cba418, 0x00b39317, 0x00706813, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5d12, 0x005b5b12, 0x00605c11, 0x00b49314, 0x00cca316, 0x00b69314, 0x00595510, 0x004d4e0f, 0x00494a10, 0x0045470e, 0x0043440e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0b, 0x00292b0a, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x00101711, 0x00101711, 0x00121812, 0x00121812, 0x00121812, 0x00111812, 0x00131712, 0x00121712, 0x00111611, 0x00111611, 0x00111611, 0x00121712, 0x00121712, 0x00111712, 0x00121712, 0x00121712, 0x00131712, 0x00141712, 0x00121611, 0x00141812, 0x00141812, 0x00141811, 0x00141811, 0x00141810, 0x00141810, 0x00161810, 0x00161810, 0x0016180e, 0x0017170e, 0x0018160e, 0x0018160e, 0x0017150c, 0x0016140c, 0x0016140b, 0x0016140b, 0x0015140b, 0x0018170e, 0x0018170e, 0x0016140b, 0x00131308, 0x00101208, 0x00101208, 0x00101006, 0x00121006, 0x00121008, 0x00131008, 0x00141009, 0x00130f08, 0x00130f09, 0x00111009, 0x00111008, 0x00111008, 0x00111108, 0x00131109, 0x0014120a, 0x0014120a, 0x0014120c, 0x0013120c, 0x0014120c, 0x0014120b, 0x0014130c, 0x0014130c, 0x0014130b, 0x00171108, 0x00181208, 0x00171005, 0x00181207, 0x00191208, 0x001a1209, 0x001b130a, 0x001c1308, 0x00201509, 0x00241609, 0x0024170b, 0x0024180b, 0x0024180a, 0x0025180b, 0x0026190c, 0x00271a0c, 0x00271b0a, 0x00281c08, 0x00281c08, 0x002a1c0a, 0x002a1c0a, 0x002a1c0a, 0x00281b09, 0x00271a0a, 0x00271a0a, 0x00271b0a, 0x00261a09, 0x00261a09, 0x00251a09, 0x0024190c, 0x0020180c, 0x001c1509, 0x001a1508, 0x00191508, 0x00181406, 0x00191407, 0x00191406, 0x001b1407, 0x001a1408, 0x001a1407, 0x00191407, 0x001a1407, 0x001d170a, 0x001f1709, 0x00201708, 0x00231808, 0x00241c09, 0x00241c08, 0x00271d09, 0x002c200a, 0x002f2008, 0x00342008, 0x00382408, 0x003e2706, 0x00442b0a, 0x0048300c, 0x004f350c, 0x00573a0b, 0x0064430a, 0x007c590d, 0x00b8992d, 0x00ccb423, 0x00ccb810, 0x00c9b80c, 0x00cab80c, 0x00c8ba0a, 0x00cbba11, 0x00ab8e0b, 0x00745400, 0x005b3e00, 0x00493204, 0x003b2a05, 0x002e2100, 0x00382c0a, 0x00392e0c, 0x0033280b, 0x002c240b, 0x00241c08, 0x001b1706, 0x00181609, 0x00111409, 0x000e1207, 0x000d1208, 0x000d140a, 0x000c1208, 0x00080f05, 0x00080e04, 0x00080e04, 0x00090d04, 0x00080c03, 0x000c0e06, 0x000c0f06, 0x00100f08, 0x00120f07, 0x00151108, 0x00171207, 0x00181407, 0x00191307, 0x00191307, 0x001b1307, 0x001b1207, 0x001b1207, 0x001c1308, 0x001c1107, 0x001c1107, 0x001c1207, 0x001c1107, 0x001e1108, 0x001e1108, 0x001e1108, 0x001e1108, 0x001e1107, 0x001d1107, 0x001e1408, 0x001c1308, 0x001b1409, 0x00191408, 0x00181308, 0x00181209, 0x00181108, 0x00171008, 0x00161008, 0x00130f08, 0x00110f07, 0x000f0e05, 0x000f0e06, 0x000c0f04, 0x000c1005, 0x000e1007, 0x00101207, 0x00131208, 0x00161208, 0x00181308, 0x00191308, 0x0020170b, 0x0025180a, 0x002a1b08, 0x002c1b05, 0x00352204, 0x00402a04, 0x004b2d09, 0x005b370a, 0x00724b08, 0x0088600b, 0x008a6102, 0x008b6303, 0x008b5f00, 0x00845300, 0x00754700, 0x005f3400, 0x00573406, 0x004a3008, 0x00442e0a, 0x00402a08, 0x003c2408, 0x00392207, 0x00361f06, 0x00341e06, 0x00321d04, 0x00311c05, 0x002e1c07, 0x002b1b07, 0x00281906, 0x00271804, 0x00271804, 0x00261804, 0x00261707, 0x00241809, 0x0024180b, 0x0023190b, 0x0020160a, 0x001c1406, 0x001b1204, 0x001c1104, 0x001c1305, 0x001c1304, 0x001d1101, 0x00201301, 0x00241404, 0x00271706, 0x002c1b08, 0x002f1c08, 0x00301d09, 0x0034200b, 0x0038220c, 0x0039230d, 0x003a230d, 0x003a230c, 0x0039210b, 0x003a210a, 0x0039210a, 0x00382009, 0x00382009, 0x00372009, 0x00352009, 0x00332009, 0x002f1f08, 0x002c1d07, 0x002b1c08, 0x002c1c08, 0x00291b08, 0x00261908, 0x00231608, 0x0022170a, 0x0022170b, 0x001f1408, 0x001d1206, 0x001c1108, 0x001a1208, 0x0019130a, 0x0017130b, 0x0016140b, 0x0014130a, 0x00111008, 0x00131209, 0x0014110a, 0x0012110a, 0x0012110a, 0x0013100a, 0x0013100a, 0x0012110a, 0x0012110a, 0x0013110b, 0x0013110b, 0x0012110a, 0x00101009, 0x00101008, 0x00121109, 0x0014120a, 0x00141109, 0x00141109, 0x00141008, 0x00131108, 0x00131108, 0x00121108, 0x00121108, 0x00121108, 0x00131208, 0x00141409, 0x0017140a, 0x0016140a, 0x0016150b, 0x0014150a, 0x0012160c, 0x0012170e, 0x0012180e, 0x0013180f, 0x00121810, 0x00121911, 0x00101810, 0x00101810, 0x00141911, 0x00181b12, 0x00191a12, 0x001a1b14, 0x001b1c14, 0x001b1c16, 0x00181b14, 0x001a1d17, 0x00191e17, 0x00161c17, 0x00161c17, 0x00151c15, 0x00151c15, 0x00161b14, 0x00151b14, 0x00141a13, 0x00141912, 0x00131812, 0x00131813, 0x00141813, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x001d200a, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x00393b0d, 0x003c3e0c, 0x0041420d, 0x0044450d, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00685f10, 0x00c39c15, 0x00cca316, 0x00b09014, 0x005e5c11, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x00636012, 0x00958014, 0x00c09d16, 0x00cba417, 0x00caa317, 0x00c6a117, 0x00bb9816, 0x00b49415, 0x00b69515, 0x00c19d17, 0x00c8a218, 0x00cca418, 0x00cba418, 0x00c19c18, 0x00978014, 0x00646213, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5c12, 0x00585912, 0x00887413, 0x00caa116, 0x00caa116, 0x00847012, 0x004f5010, 0x004c4d0f, 0x0048490f, 0x0045470e, 0x0041420e, 0x003e400c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x00292b0a, 0x0026280c, 0x0020230a, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00111812, 0x00111812, 0x00131812, 0x00131812, 0x00131812, 0x00131712, 0x00131812, 0x00131812, 0x00141813, 0x00141813, 0x00141814, 0x00141914, 0x00141a14, 0x00131914, 0x00141914, 0x00161814, 0x00171814, 0x00171711, 0x00151610, 0x0014150f, 0x0014150f, 0x0014140f, 0x0015140f, 0x0015140d, 0x0015140e, 0x0015150c, 0x0015150c, 0x0014140b, 0x0014140b, 0x0017150c, 0x0017150d, 0x0015140b, 0x0014130a, 0x0014120a, 0x00141109, 0x00141109, 0x0014130a, 0x0014130a, 0x00131209, 0x00101208, 0x00101108, 0x00101108, 0x00101008, 0x00101008, 0x00111008, 0x00121008, 0x00141109, 0x00110e07, 0x00101009, 0x00101009, 0x000f1008, 0x00101008, 0x00101008, 0x00101109, 0x0014100a, 0x0015100b, 0x0015100b, 0x0016100c, 0x0014120c, 0x0014120c, 0x0015120c, 0x0015120d, 0x0016120c, 0x001c1009, 0x001c1107, 0x001d1206, 0x001f1408, 0x00201408, 0x0020160b, 0x0023160b, 0x0024180b, 0x0026180a, 0x0027180a, 0x0029190b, 0x002b1b0c, 0x002c1c0c, 0x002c1c0f, 0x002d1d0e, 0x002e1d0d, 0x002d1e0b, 0x002d1c08, 0x002d1c08, 0x002d1e09, 0x002c1d08, 0x002b1c08, 0x00291a08, 0x00271805, 0x00251804, 0x00241704, 0x00201400, 0x001e1300, 0x001e1300, 0x001c1406, 0x001b1508, 0x00181507, 0x00161506, 0x00141505, 0x00151404, 0x00171304, 0x001c1404, 0x00201607, 0x00211708, 0x00211708, 0x00201605, 0x00201706, 0x00241908, 0x00281b0b, 0x00281a09, 0x002a1c08, 0x00281c06, 0x00281d05, 0x002c1f05, 0x00302008, 0x00332307, 0x00382506, 0x003b2704, 0x00402a04, 0x00442d06, 0x00482f08, 0x0050350c, 0x00583b0b, 0x0062420c, 0x00795510, 0x00b4902c, 0x00ccb228, 0x00ccb717, 0x00ccb610, 0x00ccb70c, 0x00c9b908, 0x00cab810, 0x00ae910d, 0x00725100, 0x00563a00, 0x00452d00, 0x00382802, 0x002d1e00, 0x00342509, 0x00362a10, 0x0030250c, 0x0029210a, 0x00211c09, 0x001e1909, 0x00181709, 0x00101207, 0x000e1105, 0x000e1208, 0x000f1308, 0x000e1007, 0x000b0e04, 0x000a0d03, 0x000a0d03, 0x000b0c02, 0x000b0c02, 0x000c0d04, 0x000e0f05, 0x00140f08, 0x00140e08, 0x00140e08, 0x00161009, 0x00181109, 0x00181006, 0x00171006, 0x00181006, 0x00181107, 0x001a1108, 0x001a1108, 0x00191007, 0x001a1007, 0x001b1007, 0x001b1007, 0x001c1108, 0x001b1108, 0x001b1108, 0x001b1108, 0x001a1108, 0x00191007, 0x00181107, 0x00181105, 0x00191306, 0x00191306, 0x00181108, 0x00181009, 0x00161008, 0x00151008, 0x00141008, 0x00120e07, 0x00110e06, 0x00100d05, 0x000f0d05, 0x000f0d05, 0x00100f05, 0x00101005, 0x00121108, 0x00131108, 0x00161108, 0x0019120c, 0x001a130b, 0x001f1508, 0x00241808, 0x00281a06, 0x00301c05, 0x00362004, 0x00402707, 0x004b2f09, 0x00523309, 0x005b3806, 0x00633c04, 0x00684005, 0x006b3f04, 0x006c4002, 0x00683c00, 0x00613b01, 0x00583502, 0x00543204, 0x004e3108, 0x00482d07, 0x00452c09, 0x0041290a, 0x003c2509, 0x00392209, 0x00382309, 0x00372108, 0x00341f07, 0x00321e05, 0x00301c05, 0x00301c05, 0x002d1c04, 0x002d1b05, 0x002c1b05, 0x002d1c08, 0x002e1d0c, 0x002e1d0d, 0x002e1d0d, 0x002b1d0d, 0x00271b0a, 0x00241807, 0x00231706, 0x00211407, 0x00211504, 0x00201401, 0x00221403, 0x00241504, 0x00281808, 0x002a1807, 0x002e1c08, 0x002e1c06, 0x00311d07, 0x00372008, 0x003c230c, 0x003e250a, 0x0040270b, 0x0042280d, 0x0042280d, 0x0042280f, 0x0042280e, 0x0040280d, 0x0040270b, 0x003d280c, 0x003c270e, 0x0038260f, 0x0033230a, 0x00302006, 0x00301e04, 0x00311c05, 0x002d1c08, 0x00281a08, 0x00271809, 0x0026180a, 0x00241608, 0x00211406, 0x001e1205, 0x001d1206, 0x001b1208, 0x00181309, 0x00161409, 0x0013140a, 0x00121108, 0x0013120a, 0x0013120b, 0x0012110a, 0x0012110a, 0x0012110a, 0x0012110a, 0x0012110a, 0x0012110a, 0x0013100a, 0x0013100a, 0x0013100a, 0x00121009, 0x00111009, 0x00101009, 0x00101009, 0x00111009, 0x00121009, 0x00131008, 0x00121008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00141109, 0x00161008, 0x00151108, 0x00151208, 0x00141308, 0x0016130b, 0x0016140b, 0x0016150c, 0x0016160d, 0x0017160f, 0x00181710, 0x0017160f, 0x0016160f, 0x00181710, 0x001c1910, 0x001c1910, 0x001a1811, 0x001a1710, 0x00191811, 0x001a1913, 0x001c1d18, 0x001b1e18, 0x00181d16, 0x00171d16, 0x00161c15, 0x00161c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00141b14, 0x00131a14, 0x00121a14, 0x00131b14, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x00515110, 0x00947c13, 0x00caa216, 0x00caa216, 0x00917c13, 0x00585912, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5d11, 0x006b6412, 0x00957f14, 0x00b59516, 0x00c7a117, 0x00cba418, 0x00cca418, 0x00cba418, 0x00cba418, 0x00c39e18, 0x00b19316, 0x00947f15, 0x006b6513, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5c12, 0x005b5b12, 0x00666011, 0x00bc9815, 0x00cca316, 0x00b08f14, 0x00565410, 0x004d4e10, 0x00494a0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0024250b, 0x00202309, 0x001d2008, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x00060c07, 0x00131914, 0x00131914, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00141a14, 0x00141a14, 0x00131914, 0x00141914, 0x00171813, 0x00171812, 0x00161510, 0x0014130d, 0x0014130c, 0x0014110b, 0x0014110b, 0x0014110b, 0x0014110b, 0x0014110b, 0x00141109, 0x00141109, 0x00121108, 0x00121108, 0x0014140b, 0x0015140c, 0x0013120a, 0x00101008, 0x00111008, 0x00121009, 0x00121009, 0x00121009, 0x00101009, 0x00101008, 0x00101108, 0x000f1007, 0x000f1007, 0x00101009, 0x00101009, 0x00100f08, 0x000f0e07, 0x0012110a, 0x000f1008, 0x000d1008, 0x000d1008, 0x000f1008, 0x00101008, 0x00121008, 0x00131008, 0x00141109, 0x0017100b, 0x00171009, 0x00181009, 0x0018110a, 0x0018110a, 0x0018130a, 0x0019140a, 0x001a130a, 0x001f1308, 0x001f1307, 0x00241808, 0x0028190a, 0x0028190a, 0x0029190b, 0x002a1a0c, 0x002c1b0b, 0x002c1b0b, 0x002d1c0c, 0x002e1d0b, 0x00301e0c, 0x00301f0d, 0x00301f0d, 0x0031200e, 0x0032200e, 0x00311f0a, 0x00301d06, 0x002f1c05, 0x002f1e08, 0x002d1d07, 0x002c1c06, 0x002b1a06, 0x00281805, 0x00281806, 0x00281808, 0x00241705, 0x00241506, 0x00221405, 0x00201404, 0x001f1506, 0x001d1606, 0x001d1807, 0x001c1805, 0x001f1906, 0x00231b08, 0x00271b08, 0x002b1c09, 0x002c1d0a, 0x002c1d0a, 0x002c1c08, 0x002c1c08, 0x002c1c08, 0x002c1c08, 0x002d1b06, 0x00301d04, 0x00302006, 0x00302104, 0x00342205, 0x00362508, 0x003b2a0d, 0x003e2d0d, 0x0041300c, 0x0046330c, 0x0048340d, 0x004a3610, 0x00503910, 0x00563c0c, 0x0061410e, 0x00784e10, 0x00a3791f, 0x00c8a126, 0x00c9a714, 0x00ccaa11, 0x00cbac0d, 0x00cbaf10, 0x00ccb018, 0x00ad8c14, 0x00704e00, 0x00553701, 0x00422800, 0x00362402, 0x002a1b00, 0x00312307, 0x0033270d, 0x002f240c, 0x0028200a, 0x00201b08, 0x001d1909, 0x00171608, 0x00121207, 0x00101106, 0x00101106, 0x00101106, 0x00101108, 0x000d0f05, 0x000e0f05, 0x000f0f06, 0x000f0d04, 0x000f0d04, 0x000e0d04, 0x00100f05, 0x00121008, 0x00140f08, 0x00120e06, 0x00140f08, 0x00141008, 0x00141007, 0x00141008, 0x00151108, 0x00151108, 0x00151108, 0x00151108, 0x00141007, 0x00141007, 0x00151007, 0x00151007, 0x00171008, 0x00171008, 0x00161008, 0x00151109, 0x00151009, 0x00141008, 0x00171108, 0x00181108, 0x00181209, 0x00181309, 0x00171109, 0x00171009, 0x00151008, 0x00141008, 0x00140f08, 0x00140f08, 0x00140f08, 0x00121008, 0x00121008, 0x00140f08, 0x00131008, 0x00131006, 0x00131107, 0x00151208, 0x00181108, 0x001c140c, 0x001c130c, 0x001e1508, 0x00241804, 0x002c1b05, 0x00352008, 0x0040280b, 0x004c310e, 0x004e3008, 0x00543407, 0x00593605, 0x005c3804, 0x005e3905, 0x005f3804, 0x00603804, 0x00603804, 0x005e3804, 0x00583504, 0x00543204, 0x00523206, 0x004d2e04, 0x00482c05, 0x00462d08, 0x00422a0c, 0x003f280b, 0x003f280c, 0x003d260c, 0x003c240b, 0x003a2309, 0x00392108, 0x00382108, 0x00372007, 0x00372007, 0x00342005, 0x00341f05, 0x00341e08, 0x00341d0a, 0x00341f0b, 0x00341f0a, 0x0032200a, 0x0030200b, 0x002f200c, 0x002d1c08, 0x002d1c07, 0x002c1b05, 0x002c1c06, 0x002c1904, 0x002f1c06, 0x002d1b04, 0x00301c04, 0x00331f05, 0x00372106, 0x00382306, 0x003b2408, 0x003d2707, 0x00402808, 0x00412b0a, 0x00412b0a, 0x00422c0c, 0x00432c0d, 0x00452c0c, 0x00462a0b, 0x0045290c, 0x0044290e, 0x0040290f, 0x00402b10, 0x003e290d, 0x003b250a, 0x00382409, 0x0033210a, 0x002e1d09, 0x002c1b0a, 0x002c190b, 0x00291809, 0x00261607, 0x00211404, 0x001f1304, 0x001d1306, 0x001a1208, 0x00191408, 0x0018140a, 0x00141308, 0x00141109, 0x00141109, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x00121009, 0x00121009, 0x00111009, 0x00101009, 0x00101009, 0x00101009, 0x00111009, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00140f08, 0x00140f08, 0x00131008, 0x00121108, 0x00141109, 0x00141109, 0x00141109, 0x0014120a, 0x0016110b, 0x0017120c, 0x0018130d, 0x001a140f, 0x001b140f, 0x001c140e, 0x001d150f, 0x001b1410, 0x0017100b, 0x0014130c, 0x00191812, 0x001b1c17, 0x001b1d17, 0x00181d16, 0x00181e17, 0x00171d16, 0x00171d16, 0x00151c16, 0x00151c15, 0x00151c15, 0x00151c15, 0x00131b14, 0x00121a14, 0x00131b14, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x0048490f, 0x004b4c0f, 0x004d4e10, 0x00595510, 0x00b79414, 0x00cca316, 0x00c39c15, 0x00786b12, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005c5d11, 0x00636011, 0x00706713, 0x00847413, 0x008d7a14, 0x00887714, 0x00786e13, 0x006c6514, 0x00626013, 0x005d5e13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5c11, 0x005b5b12, 0x005b5a11, 0x00a48714, 0x00cca316, 0x00c49d15, 0x00706410, 0x004f5010, 0x004b4c0f, 0x0048490f, 0x0045470e, 0x0041420e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0020230a, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00151a14, 0x00191c16, 0x00181712, 0x0013110b, 0x00110f08, 0x00141209, 0x00131008, 0x00151109, 0x00151109, 0x00151009, 0x00140f08, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00111008, 0x00101007, 0x00101008, 0x00110f08, 0x00110f08, 0x00121009, 0x00101009, 0x00101008, 0x00101108, 0x00101108, 0x00101108, 0x00101008, 0x00101008, 0x00100f08, 0x0012110a, 0x00121009, 0x00101009, 0x0010120a, 0x000f120a, 0x00131109, 0x00151109, 0x0018110a, 0x0018110a, 0x0018120a, 0x0018130a, 0x001b130a, 0x001c1309, 0x001e140b, 0x001e140b, 0x001f150b, 0x0023180d, 0x00241a0e, 0x00291c10, 0x002a1c0d, 0x002b1c0b, 0x002c1c08, 0x002d1c08, 0x002d1c08, 0x00301c0a, 0x00301c0a, 0x002f1c08, 0x00301c0a, 0x00301d09, 0x00301e09, 0x00301e09, 0x00301e09, 0x00301e07, 0x00301f07, 0x00321e06, 0x00321e04, 0x00321e04, 0x00322005, 0x00301f04, 0x00301e03, 0x002f1d02, 0x002f1e05, 0x002e1e06, 0x002e1e07, 0x002d1e08, 0x002c1d08, 0x002b1c08, 0x002a1b08, 0x00291c08, 0x00271c08, 0x00281e09, 0x002a210b, 0x002c210c, 0x002d2009, 0x002f1f09, 0x00301e08, 0x00342009, 0x0035210b, 0x0036230a, 0x0036220c, 0x0038240d, 0x0038230c, 0x0039230b, 0x003c2509, 0x003c2809, 0x003c2808, 0x003c2808, 0x00402a0c, 0x00422c0f, 0x00452f11, 0x00493110, 0x004a330f, 0x004d3610, 0x0050390f, 0x00543c0e, 0x0059400c, 0x0065440d, 0x00754809, 0x00885706, 0x00a06d07, 0x00a87803, 0x00af7c02, 0x00b18304, 0x00b28809, 0x00b38914, 0x00946e0e, 0x00664000, 0x00543404, 0x00422800, 0x003a2806, 0x002d1e01, 0x00302206, 0x002d2008, 0x002b2007, 0x00241c07, 0x001e1907, 0x001c1809, 0x00181509, 0x0015150b, 0x00141408, 0x00141409, 0x00141409, 0x0014130a, 0x0014130a, 0x00131209, 0x00131209, 0x00141109, 0x00141109, 0x0014130a, 0x00141109, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00111008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00101007, 0x00101007, 0x000f0f05, 0x000f0f05, 0x00100e05, 0x00110f07, 0x00121008, 0x00111008, 0x00101009, 0x00101009, 0x00101009, 0x00101009, 0x00140f08, 0x00140e08, 0x00151008, 0x00151008, 0x00151008, 0x00151008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00141109, 0x00151109, 0x00181108, 0x00181309, 0x00171408, 0x001a160b, 0x001a160a, 0x001e150a, 0x0020170c, 0x00241910, 0x00281d0c, 0x002a1d07, 0x002e1c04, 0x00412b10, 0x005b3d19, 0x00654519, 0x006a4816, 0x006c4711, 0x006f450e, 0x00724510, 0x00714610, 0x006c4410, 0x0068420d, 0x0064400b, 0x00603c08, 0x005c3704, 0x005b3704, 0x00583504, 0x00543204, 0x004f3004, 0x004c3007, 0x004b3008, 0x00472e07, 0x00462d08, 0x00462d08, 0x00462c09, 0x00432b0b, 0x00432b0b, 0x00452b0c, 0x00452b0c, 0x00462a0c, 0x00442809, 0x00422609, 0x0041250b, 0x0041240d, 0x0041250c, 0x003e240a, 0x003a2208, 0x00392409, 0x00382409, 0x00392308, 0x003a2308, 0x003a2308, 0x003b2409, 0x003c240a, 0x003d240c, 0x003c250b, 0x003c2609, 0x003f2708, 0x003f2707, 0x00412805, 0x00452c07, 0x004b3008, 0x0050340b, 0x0053360c, 0x0054360d, 0x0054360d, 0x0053350c, 0x00513109, 0x00513008, 0x004d2d06, 0x004c2d09, 0x00492d0c, 0x0045290d, 0x0043280d, 0x0041290d, 0x003d280b, 0x003a270c, 0x0038240e, 0x0034200d, 0x00301c0d, 0x002f1c0b, 0x002e1b09, 0x002a1908, 0x00251808, 0x0024180a, 0x0021160b, 0x001b1206, 0x00191208, 0x00181308, 0x00171209, 0x00161208, 0x0016120a, 0x0016120a, 0x00161209, 0x00151009, 0x00141008, 0x00141008, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0012110a, 0x0012110a, 0x0011110a, 0x00101009, 0x00111009, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00140f09, 0x00121009, 0x00101009, 0x00101009, 0x00101008, 0x00121008, 0x00141008, 0x00151109, 0x00161009, 0x0018110a, 0x0018110a, 0x001a120c, 0x001c140d, 0x001c130d, 0x001c120c, 0x0018100b, 0x00130c07, 0x0014120c, 0x001b1b14, 0x00191b14, 0x001b1e18, 0x001a2018, 0x00181f17, 0x00171d16, 0x00171d16, 0x00181e18, 0x00171d18, 0x00161c17, 0x00161c17, 0x00141c15, 0x00141c15, 0x00141c15, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x00141810, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a0f, 0x004c4d0f, 0x004f5010, 0x00726511, 0x00c39c15, 0x00cca316, 0x00b99615, 0x006a6312, 0x00595a12, 0x005b5b12, 0x005b5b11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x005c5c12, 0x005b5b12, 0x00585811, 0x008f7913, 0x00c9a116, 0x00c9a116, 0x00907812, 0x00505010, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0034350c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x000f130b, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00151a13, 0x00151a13, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00161a13, 0x00191b14, 0x0013120b, 0x000f0e07, 0x00100e05, 0x00100e05, 0x00131008, 0x00151109, 0x00151109, 0x00151009, 0x00140f08, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00110f07, 0x00100e05, 0x00100f05, 0x000f0f05, 0x00100f07, 0x00110f08, 0x00121009, 0x00121009, 0x00101009, 0x00101008, 0x00101108, 0x00101108, 0x00101008, 0x00101006, 0x00111006, 0x00131008, 0x00110f07, 0x00140d07, 0x00140f08, 0x0015120a, 0x0015130c, 0x0018120b, 0x001a120c, 0x001c130d, 0x001c130c, 0x001d140c, 0x001e140b, 0x0020160b, 0x0024180e, 0x0024190e, 0x00241a0d, 0x00251b0e, 0x00281a0c, 0x00291b0d, 0x00291b0d, 0x002a1b0c, 0x002b1909, 0x002c1906, 0x002c1a05, 0x002e1c06, 0x00301c06, 0x00321c06, 0x00301c05, 0x00311c06, 0x00331d08, 0x00352008, 0x00372108, 0x00382308, 0x00392408, 0x003a2608, 0x003b2608, 0x003b2608, 0x003c2708, 0x003c2809, 0x003c2807, 0x003b2706, 0x003a2605, 0x00382604, 0x00392605, 0x00382807, 0x00382709, 0x0036270a, 0x0035250b, 0x0035240a, 0x0036240c, 0x0032220a, 0x0032240c, 0x0033240c, 0x00322309, 0x00342209, 0x00352208, 0x00372108, 0x00392208, 0x003a2308, 0x003c2509, 0x003d280c, 0x003f280e, 0x00412910, 0x00432a0f, 0x00442c0d, 0x00452f0c, 0x00452f0b, 0x00462f0a, 0x004a300c, 0x004c330d, 0x0051350c, 0x0054380c, 0x0058390b, 0x005a3c0c, 0x005c3f0c, 0x0062430c, 0x0068480c, 0x00744f0f, 0x0082530c, 0x008a5504, 0x00975f04, 0x009a6401, 0x009d6201, 0x00945c00, 0x008d5800, 0x00865400, 0x00724800, 0x00603c08, 0x00503104, 0x00442c04, 0x003d2b0b, 0x00312005, 0x002f2006, 0x002b1d06, 0x002a1e08, 0x00241c08, 0x001f1808, 0x001d1809, 0x001a1609, 0x0018140b, 0x00171309, 0x0019160c, 0x0019150c, 0x0016120a, 0x0016120a, 0x00151109, 0x00151109, 0x00141008, 0x00141008, 0x00151109, 0x00141008, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00111008, 0x00101008, 0x00101008, 0x00101008, 0x00101108, 0x000f1008, 0x000f1008, 0x000c1007, 0x000d0f05, 0x000d0f05, 0x000f1007, 0x00101008, 0x00101108, 0x00101009, 0x00101009, 0x00101009, 0x00101009, 0x00110f08, 0x00120e08, 0x00140f09, 0x00140f09, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00131008, 0x00131008, 0x00141008, 0x00151109, 0x00161108, 0x00181309, 0x0019140b, 0x00191408, 0x001c150a, 0x001e1708, 0x00211608, 0x00241809, 0x00271b0d, 0x00291d0b, 0x002e1e07, 0x00342006, 0x00543b1c, 0x006d491e, 0x00724813, 0x00805418, 0x00845613, 0x0088550f, 0x008e5712, 0x008e5816, 0x008b5818, 0x00835518, 0x007a5314, 0x00765012, 0x00754c10, 0x006e450b, 0x00684008, 0x00623d08, 0x005a3805, 0x00583908, 0x00593908, 0x00573807, 0x00543504, 0x00543606, 0x0051350b, 0x004f340c, 0x004c310b, 0x004c300a, 0x004c300a, 0x004c300a, 0x004a2d08, 0x00482b0a, 0x0047290a, 0x0044270a, 0x0045280c, 0x0044280c, 0x0042280b, 0x0042280c, 0x0041280b, 0x00402609, 0x00412709, 0x00412709, 0x0043280c, 0x00452a0d, 0x00482c10, 0x004a2e0e, 0x004c2f0e, 0x0050310e, 0x00553511, 0x005e3c13, 0x00664312, 0x006c4715, 0x00744c18, 0x00784e1a, 0x00784e18, 0x00784e1a, 0x00784c18, 0x00744914, 0x006f4610, 0x006a430f, 0x00613d0d, 0x00553407, 0x004b2907, 0x00452705, 0x00402606, 0x003c2507, 0x00382306, 0x00372209, 0x0038230f, 0x0034200d, 0x00331f0a, 0x0033200b, 0x002e1d0b, 0x002a1b0a, 0x00291b0c, 0x0027190d, 0x00211509, 0x00201609, 0x0020170b, 0x001c140c, 0x001b130b, 0x001b130b, 0x001b130b, 0x0019130a, 0x00181209, 0x00151008, 0x00151008, 0x00141008, 0x00141008, 0x0014100a, 0x0013100a, 0x0013100a, 0x00101009, 0x00111109, 0x00101009, 0x00121009, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00131008, 0x00121009, 0x00101009, 0x00100f08, 0x00100f08, 0x00101008, 0x00101008, 0x00141008, 0x00151009, 0x00151108, 0x00161208, 0x0016130a, 0x0017120a, 0x0018130b, 0x0018120b, 0x0017120b, 0x00120d07, 0x000e0904, 0x00100f08, 0x00161810, 0x00191c15, 0x001b1f18, 0x00192018, 0x00181f17, 0x00181f17, 0x00181f17, 0x00181f18, 0x00171d18, 0x00161c17, 0x00161c17, 0x00151c16, 0x00151c15, 0x00151c15, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180c, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0041420d, 0x0044450e, 0x0048490f, 0x004b4c10, 0x004d4e0f, 0x004f4f10, 0x008b7512, 0x00c8a015, 0x00cca316, 0x00b39115, 0x00656011, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005d5e12, 0x005e5f13, 0x005d5e12, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5c12, 0x005b5b12, 0x00585811, 0x00867413, 0x00c59f15, 0x00cba216, 0x00a48614, 0x00535210, 0x004d4e0f, 0x004b4c10, 0x0048490f, 0x0044450e, 0x0041420e, 0x003e400c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a13, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00181a14, 0x00191a14, 0x0011120c, 0x000e0f07, 0x000c1007, 0x000c0f06, 0x000e1006, 0x00141109, 0x00151109, 0x00141008, 0x00141008, 0x00121006, 0x00121006, 0x00121006, 0x00121006, 0x00111007, 0x00110f06, 0x00110f07, 0x00130f08, 0x00121008, 0x00131008, 0x00131008, 0x00141209, 0x00121008, 0x00131107, 0x00131107, 0x00131208, 0x00131207, 0x00151307, 0x00141005, 0x00161006, 0x00191007, 0x00191007, 0x001a1108, 0x001e150c, 0x0020160f, 0x001e140d, 0x0021150e, 0x00231710, 0x00241610, 0x0024180e, 0x0025190d, 0x00261a0d, 0x0023160a, 0x0021180a, 0x00201708, 0x001f1607, 0x00211507, 0x00221608, 0x00211405, 0x00241405, 0x00271604, 0x002b1907, 0x00291a06, 0x002c1d08, 0x00301d08, 0x00342006, 0x00372206, 0x003b2609, 0x003e260c, 0x0043280e, 0x00462b0c, 0x00462c0a, 0x0048310a, 0x004a3308, 0x004b3308, 0x004b3308, 0x004c340a, 0x004c340c, 0x004c340b, 0x004d340b, 0x004d340c, 0x004e340c, 0x004b310b, 0x0049320d, 0x0044300c, 0x0041300c, 0x0040300c, 0x00402d0c, 0x0040290c, 0x003e270c, 0x003e260d, 0x003d240c, 0x003d250b, 0x003f250c, 0x0040250a, 0x00402609, 0x003f2708, 0x003f2708, 0x00422a09, 0x00442c0b, 0x00442c0c, 0x00482e11, 0x00452b0c, 0x004a300c, 0x004f340d, 0x004f350c, 0x0051370b, 0x00573b0c, 0x005c3c0c, 0x005e3b07, 0x00654009, 0x006c440a, 0x006e450a, 0x0074490c, 0x00794f0c, 0x007e540c, 0x008b5f11, 0x009b6912, 0x00a57416, 0x00af8017, 0x00bc8c1f, 0x00c08823, 0x00996109, 0x00824e04, 0x00784e04, 0x00633e00, 0x00553709, 0x00483205, 0x00403008, 0x003b2808, 0x00342207, 0x002e1e08, 0x00281b09, 0x0026190a, 0x00221809, 0x001f170a, 0x001d170a, 0x001a1509, 0x00191408, 0x00181309, 0x0018110a, 0x0018110a, 0x0018110a, 0x0018110a, 0x0017100b, 0x0017100b, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x0014100a, 0x0013100a, 0x00121009, 0x00121009, 0x00110f08, 0x00110e0a, 0x00110e0a, 0x00110e0a, 0x00110e0a, 0x00110d0a, 0x00100e0a, 0x000d0d08, 0x000c0d08, 0x000e0d06, 0x000f0e07, 0x00110f08, 0x00110f08, 0x00110f08, 0x00100f08, 0x00140f09, 0x00140f09, 0x00120f0b, 0x00120f0b, 0x0013100c, 0x0013100a, 0x00121109, 0x00121108, 0x00121108, 0x0013120a, 0x0014120b, 0x0014110b, 0x0014110a, 0x00141208, 0x00161208, 0x00181308, 0x00181308, 0x00191207, 0x001c1608, 0x00201608, 0x00221606, 0x00251706, 0x00291a08, 0x002c1d0c, 0x00311f0a, 0x003d2407, 0x00604016, 0x00744c17, 0x00845617, 0x00a77829, 0x00b38224, 0x00af7d1b, 0x00ac7716, 0x00a87314, 0x00a16c10, 0x009f6810, 0x0099630f, 0x00945d0d, 0x00905a11, 0x0088530c, 0x0085540c, 0x007c4e08, 0x00754908, 0x00714608, 0x006f440a, 0x006c410a, 0x0067400a, 0x0065400c, 0x00613f0d, 0x005b390a, 0x0058360a, 0x0058360c, 0x0057350a, 0x00543307, 0x00513306, 0x00503208, 0x00503208, 0x004b3108, 0x004a310b, 0x00462f0b, 0x00442c0a, 0x00472c0b, 0x00482c0c, 0x00492c0c, 0x00492d0f, 0x00492e10, 0x00492f0e, 0x004d300e, 0x00523410, 0x0054370c, 0x005b3d0c, 0x00694814, 0x006e4a14, 0x00785013, 0x00835412, 0x008a5915, 0x00935f19, 0x0099651b, 0x00986616, 0x00946413, 0x00936212, 0x00905f0f, 0x008e5a0c, 0x0088560e, 0x00815211, 0x00794c12, 0x006e400f, 0x005d3608, 0x004c2c05, 0x00402804, 0x003c2404, 0x00382208, 0x00341e08, 0x00301c05, 0x00301c04, 0x002e1c04, 0x002c1c07, 0x002b1c08, 0x002b1c0c, 0x00291c0e, 0x0025180c, 0x0024180e, 0x0024180e, 0x0022180e, 0x0021150c, 0x0021150c, 0x0020140c, 0x001e140b, 0x001c1409, 0x001b1309, 0x001a1208, 0x00181108, 0x00181108, 0x00181209, 0x00171009, 0x00141008, 0x00141008, 0x00140f08, 0x0014100a, 0x0014100a, 0x00140f09, 0x00140f09, 0x0014100a, 0x00141008, 0x00140f08, 0x00141006, 0x00141007, 0x00141007, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00130f09, 0x00140f09, 0x0014100b, 0x0015110a, 0x0017130a, 0x00171309, 0x0017140a, 0x0018140c, 0x0018140c, 0x00140f08, 0x000f0c04, 0x000c0c04, 0x000b0c04, 0x000c0e06, 0x0013150d, 0x00171c15, 0x00182017, 0x00192018, 0x00182018, 0x00192018, 0x00181f17, 0x00181f15, 0x00181f15, 0x00181f15, 0x00181f15, 0x00181e15, 0x00191e15, 0x00191e15, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x004d4e10, 0x00515110, 0x00967d12, 0x00c9a116, 0x00cca316, 0x00b29115, 0x006a6211, 0x00585912, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5c11, 0x005c5c12, 0x00595a12, 0x00585911, 0x00887513, 0x00c49e16, 0x00cca316, 0x00ac8b14, 0x00595510, 0x004d4e10, 0x004c4d0f, 0x0048490f, 0x0045470e, 0x0043440e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002d2f0b, 0x00292b0b, 0x0026280c, 0x0020230a, 0x00202308, 0x00191c08, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00151a11, 0x00151a11, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a13, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00181a14, 0x00191a14, 0x0011120c, 0x000d0f07, 0x000c1007, 0x000c0f06, 0x000c0f06, 0x0011110a, 0x0014110b, 0x00131008, 0x00121008, 0x00121008, 0x00121008, 0x00141006, 0x00141006, 0x00120f05, 0x00120f05, 0x00141006, 0x00161008, 0x00161007, 0x00151007, 0x00151007, 0x00151007, 0x00140f04, 0x00151005, 0x00151005, 0x00181206, 0x00181306, 0x00191408, 0x001e170b, 0x0021160a, 0x0022170b, 0x0020180b, 0x0020190c, 0x00221b0f, 0x0020190d, 0x0020190d, 0x0020180c, 0x001d150b, 0x001d140a, 0x001e1509, 0x001d1408, 0x001c1204, 0x001b1104, 0x001a1104, 0x00181202, 0x001a1203, 0x001c1203, 0x001e1204, 0x00231404, 0x00271804, 0x002b1906, 0x002f1c07, 0x00302008, 0x00332408, 0x003b280c, 0x003f2b0c, 0x00442f0c, 0x004a320e, 0x004e330f, 0x00533510, 0x00593810, 0x005c3c11, 0x00603f13, 0x00604010, 0x0061420d, 0x0061430b, 0x0062430b, 0x0060420a, 0x0060420b, 0x0061400c, 0x00613f0d, 0x005f3c0d, 0x005a390c, 0x0056370d, 0x0050340d, 0x004c340e, 0x004c340f, 0x004a330e, 0x0048300c, 0x00462c0c, 0x00452c0f, 0x00442a0e, 0x00442a0c, 0x00442a0c, 0x00442a0c, 0x00452c0b, 0x00452c09, 0x00452c08, 0x00482e0a, 0x004b300c, 0x004a300b, 0x004f330d, 0x0054340e, 0x00573810, 0x00593b13, 0x005a3c11, 0x00603f13, 0x00654212, 0x00704711, 0x0072470b, 0x007b4f0d, 0x0081540e, 0x0087590d, 0x00926414, 0x009c6f19, 0x00a6791f, 0x00b58c26, 0x00c39b25, 0x00c8a227, 0x00caa421, 0x00ccaa23, 0x00caa120, 0x009e7007, 0x007c4d00, 0x006c4600, 0x005f3f02, 0x00503407, 0x00443004, 0x003e2c07, 0x00372406, 0x00332108, 0x002e1c08, 0x00291b09, 0x00241809, 0x00211609, 0x001d1508, 0x001b1508, 0x001a1508, 0x00191409, 0x00181309, 0x0018110a, 0x0018110a, 0x0018110a, 0x0018110a, 0x0017100b, 0x0017100b, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x0014100a, 0x0013100a, 0x00121009, 0x00121009, 0x00110e0b, 0x00110e0c, 0x00110e0c, 0x00110e0c, 0x00110e0b, 0x00120d0a, 0x00110e0a, 0x000e0d08, 0x000c0d08, 0x000e0d06, 0x000f0e07, 0x00110f08, 0x00110f08, 0x00110f08, 0x00110f08, 0x00140f09, 0x00140f09, 0x00120f0b, 0x00120f0b, 0x0013100a, 0x00131009, 0x00121108, 0x00121108, 0x00121108, 0x0013120a, 0x0013110b, 0x0013100a, 0x00141109, 0x00141208, 0x00161307, 0x00181308, 0x00181308, 0x00191206, 0x001d1608, 0x00211609, 0x00241708, 0x00281808, 0x002c1c09, 0x002d1c0c, 0x0034200b, 0x00412709, 0x00644418, 0x00774f13, 0x008c6214, 0x00b8902d, 0x00cba32c, 0x00caa422, 0x00c99f1c, 0x00c89b1c, 0x00c5971b, 0x00c3921b, 0x00bd8c19, 0x00b88418, 0x00b07b16, 0x00a87312, 0x009d6a0b, 0x00976408, 0x00925f0a, 0x008e5c0c, 0x008b5a10, 0x00885710, 0x00855411, 0x00835414, 0x00805416, 0x007b5014, 0x00744b12, 0x00744912, 0x00714711, 0x006b430c, 0x00664008, 0x00603a04, 0x005b3803, 0x00543401, 0x00543604, 0x00523507, 0x00503308, 0x0050300b, 0x0051300c, 0x0052300d, 0x00502f0c, 0x0051320d, 0x0052330c, 0x005a3810, 0x005f3c10, 0x0068430c, 0x00734c0c, 0x00805911, 0x008c6416, 0x009c7118, 0x00aa7e1b, 0x00b48721, 0x00bb8d25, 0x00c29528, 0x00c19927, 0x00bd9724, 0x00bd9724, 0x00bc9423, 0x00b8841b, 0x00ad7a16, 0x009e6a10, 0x00915f0d, 0x0086560d, 0x00784d0d, 0x00674109, 0x00583707, 0x004b2c07, 0x00422509, 0x003a200a, 0x00301c05, 0x002c1a01, 0x002a1901, 0x00281804, 0x00261804, 0x00241706, 0x00231708, 0x0021180b, 0x0020180c, 0x0020180e, 0x0020180e, 0x00221a10, 0x00221a10, 0x0021180e, 0x0020160c, 0x0020150c, 0x0021180f, 0x0020170d, 0x001f150c, 0x001f150c, 0x001f160c, 0x001d140b, 0x001a1308, 0x001a1208, 0x00181208, 0x00181209, 0x00181209, 0x00181008, 0x00150f07, 0x00151008, 0x00161008, 0x00171008, 0x00171008, 0x00161007, 0x00151007, 0x00131008, 0x00121008, 0x00121008, 0x00121008, 0x00140f08, 0x00140f08, 0x0016120a, 0x0017130a, 0x00161208, 0x00181408, 0x001a160c, 0x00161209, 0x00120e06, 0x000f0d04, 0x000c0c03, 0x000b0c04, 0x00090c04, 0x000b0e05, 0x000e1109, 0x00171d16, 0x00182018, 0x00181e17, 0x001a2018, 0x001a2119, 0x00181f17, 0x00181f15, 0x00181f15, 0x00181f15, 0x00181f15, 0x00181e15, 0x00191e15, 0x00191e15, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0b, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003c3e0d, 0x0040400d, 0x0043440e, 0x0045470e, 0x00494a10, 0x004c4d0f, 0x004d4e10, 0x00525110, 0x00987e12, 0x00c8a016, 0x00cca316, 0x00b99615, 0x00786b12, 0x00585810, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5c11, 0x005c5d12, 0x005c5c12, 0x005b5b12, 0x00585912, 0x005e5c11, 0x00988013, 0x00c7a015, 0x00cba216, 0x00ac8b14, 0x005c5810, 0x004d4e10, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0043440e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x0024250c, 0x00202308, 0x001d2008, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00181b12, 0x00181b12, 0x00181a14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161b14, 0x00171c14, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00161711, 0x0011130b, 0x000f1008, 0x000d1008, 0x000b0e05, 0x000a0e05, 0x000d0e06, 0x00101009, 0x00141109, 0x00131107, 0x00131008, 0x00131008, 0x00131107, 0x00151308, 0x00181308, 0x00181208, 0x00191208, 0x001a1208, 0x001a1208, 0x001a1208, 0x001b1208, 0x001d140a, 0x001d140a, 0x001e1409, 0x001f1509, 0x001f170b, 0x0020190d, 0x00201a0c, 0x00201a0d, 0x0022180c, 0x00201509, 0x001c1508, 0x001c1608, 0x00191507, 0x00181406, 0x00171305, 0x00161104, 0x00141104, 0x00141104, 0x00151003, 0x00171002, 0x00181003, 0x001c1507, 0x00191404, 0x001b1605, 0x00201708, 0x0023180a, 0x00241808, 0x002a1c09, 0x00301e0a, 0x0034200a, 0x00382309, 0x003d280b, 0x00452f0e, 0x004a320d, 0x0050340f, 0x0057390c, 0x005d3c0c, 0x0064400c, 0x006b440c, 0x0072480d, 0x007a4e11, 0x00805415, 0x00835814, 0x00855a13, 0x00865c0f, 0x00865c0f, 0x00865c0f, 0x0083590c, 0x007f5708, 0x007b5308, 0x0079500a, 0x00714806, 0x006b430c, 0x00623c09, 0x005e3a0c, 0x0058370c, 0x0053360b, 0x004f340a, 0x004c320b, 0x004c320c, 0x004a300d, 0x00482f0d, 0x00482f0c, 0x004b300c, 0x004d330d, 0x004d330c, 0x004e330a, 0x0050340b, 0x0052360a, 0x00563709, 0x005c390c, 0x005f3b0c, 0x00643c0e, 0x00653f10, 0x00694310, 0x0070480e, 0x0078500f, 0x00845613, 0x008c5d13, 0x00986815, 0x00a4761a, 0x00b1851f, 0x00bb9121, 0x00c39b25, 0x00c9a429, 0x00ccaa24, 0x00ccad1b, 0x00ccb018, 0x00ccb215, 0x00ccb313, 0x00caac16, 0x00a17c04, 0x007d5300, 0x006e4803, 0x00593c00, 0x004c3305, 0x00442f04, 0x003d2804, 0x00362204, 0x00311f08, 0x002d1c08, 0x002a1908, 0x0027180b, 0x00211608, 0x001c1408, 0x001b1408, 0x00191407, 0x00181308, 0x00181108, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x0017100b, 0x0017100b, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x0015100b, 0x0015100b, 0x0014100a, 0x0014100a, 0x0014100c, 0x00120f0c, 0x00120f0c, 0x00120f0c, 0x00130f0c, 0x00140f0b, 0x00120f0b, 0x000f0e09, 0x000b0c06, 0x00100f08, 0x00100f08, 0x00121009, 0x00121009, 0x00140f0b, 0x00140f0b, 0x00140f0b, 0x00140f0b, 0x00110e0a, 0x00110f08, 0x00110f08, 0x00131108, 0x00131108, 0x00121108, 0x00111008, 0x00101008, 0x00111009, 0x00131008, 0x00131008, 0x00131107, 0x00171408, 0x00181107, 0x00181107, 0x001a1306, 0x001c1408, 0x00201408, 0x00241708, 0x00281808, 0x002c1c09, 0x002d1e0c, 0x00342009, 0x00422708, 0x00644418, 0x00795010, 0x00926710, 0x00bf9a26, 0x00ccad1f, 0x00ccb316, 0x00ccb011, 0x00ccae13, 0x00ccac14, 0x00ccaa16, 0x00cca819, 0x00cca61b, 0x00cba31e, 0x00c59c1c, 0x00c3991c, 0x00be9319, 0x00bb8c1a, 0x00b38216, 0x00ab7a14, 0x00a47311, 0x009f6c0e, 0x00a06a10, 0x009b6610, 0x0094600e, 0x00915d0f, 0x00905b10, 0x008d5810, 0x0088540e, 0x0083500a, 0x00804f0a, 0x007a4c0a, 0x0072490a, 0x006e470a, 0x00674107, 0x00623d06, 0x0060380c, 0x0060370c, 0x005e350b, 0x005c350a, 0x005c3708, 0x0064400e, 0x006d4512, 0x00744913, 0x0080530d, 0x00916410, 0x00a77d19, 0x00ba9322, 0x00c59f22, 0x00caa620, 0x00cca920, 0x00ccaa1e, 0x00ccac1d, 0x00ccaf1c, 0x00ccb01d, 0x00ccb01c, 0x00ccaf1c, 0x00cca81a, 0x00c9a019, 0x00c69a1d, 0x00b88a15, 0x00a67611, 0x00926309, 0x00885a0e, 0x00784c09, 0x00643c0a, 0x00532e09, 0x0046290a, 0x003b2407, 0x00332004, 0x002c1a02, 0x00281802, 0x00241602, 0x001f1201, 0x001b1102, 0x001a1104, 0x00161004, 0x00141005, 0x00141105, 0x00141206, 0x00171408, 0x0018160a, 0x001b140a, 0x001c140a, 0x001f160c, 0x0020180e, 0x0021180d, 0x0022180c, 0x0021180c, 0x0023180d, 0x0022180c, 0x0021160a, 0x00201509, 0x001e150a, 0x001c1308, 0x001c1308, 0x00191106, 0x00181206, 0x00181206, 0x00181008, 0x00181008, 0x00181107, 0x00171006, 0x00141007, 0x00141007, 0x00141007, 0x00141007, 0x00141008, 0x00141008, 0x0016120a, 0x00171309, 0x00181409, 0x00181408, 0x00171308, 0x00130f05, 0x000f0c04, 0x000d0c05, 0x000c0d05, 0x000b0e05, 0x000b0d07, 0x000b0d07, 0x000c0e08, 0x00161b14, 0x00161d15, 0x00181f17, 0x001a2018, 0x001a2119, 0x00181f17, 0x00171e14, 0x00182016, 0x00182016, 0x00182016, 0x00191f15, 0x00191e15, 0x00191e15, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0040400d, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x004d4e10, 0x00505010, 0x008f7812, 0x00c49e15, 0x00cca316, 0x00c49e16, 0x00947c14, 0x00605c10, 0x00585911, 0x00595a12, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5c11, 0x005c5c11, 0x005b5b12, 0x005b5b12, 0x00595a12, 0x00595911, 0x00756911, 0x00b09015, 0x00cba216, 0x00c9a116, 0x00a48614, 0x00585510, 0x004d4e10, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450e, 0x0041420d, 0x003e400c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0020230a, 0x001d2008, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181b12, 0x00181b12, 0x00181a14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161b14, 0x00161c14, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181b14, 0x00141510, 0x00101009, 0x000f1008, 0x000d1008, 0x000c0e08, 0x000a0d07, 0x000b0c04, 0x00100f08, 0x0017140c, 0x00151309, 0x00151308, 0x00151308, 0x00151308, 0x00181609, 0x001c1509, 0x001d1408, 0x0020150b, 0x0022170c, 0x0022170c, 0x0022170c, 0x0022170c, 0x0024180d, 0x0024180d, 0x0024180f, 0x0024180e, 0x0020140c, 0x001f150c, 0x001a170b, 0x001a170b, 0x00181309, 0x00181108, 0x00140e04, 0x00130f04, 0x00110f03, 0x00121004, 0x00141405, 0x00131304, 0x00141404, 0x00141504, 0x00151504, 0x00191404, 0x00191505, 0x001f1a09, 0x00201a09, 0x00211c09, 0x00241c0a, 0x002b200f, 0x002c200f, 0x0033230e, 0x0034220c, 0x003c280f, 0x00412910, 0x00492d0c, 0x0052340e, 0x005c3a11, 0x00643c11, 0x006b410a, 0x00754a0a, 0x00845811, 0x00906417, 0x009c6f16, 0x00aa7c19, 0x00b78924, 0x00bc9127, 0x00c09428, 0x00c09525, 0x00c09625, 0x00c09725, 0x00bc9421, 0x00b89020, 0x00b68c23, 0x00a67c1b, 0x0094690e, 0x00895f10, 0x007a500a, 0x0070470b, 0x00673f09, 0x005c3c0a, 0x0056390a, 0x0053370a, 0x0052370c, 0x0050350c, 0x004e340c, 0x004e340c, 0x0050340c, 0x0054370c, 0x0054380b, 0x0055380a, 0x005a3c0c, 0x005d3d0c, 0x00623f08, 0x00684009, 0x0070460c, 0x0073490e, 0x00784f0e, 0x00845912, 0x008c610e, 0x00996f13, 0x00a77c18, 0x00b48a1f, 0x00be951f, 0x00c8a220, 0x00ccaa20, 0x00ccac1e, 0x00ccb01c, 0x00ccb318, 0x00ccb314, 0x00ccb410, 0x00ccb50f, 0x00cbb60c, 0x00cbb70d, 0x00cab316, 0x00a38104, 0x007c5400, 0x006d4804, 0x00563900, 0x00493004, 0x00422c04, 0x003c2403, 0x00352005, 0x00301d06, 0x002b1908, 0x00281807, 0x00241608, 0x00201407, 0x001b1306, 0x001a1407, 0x00191407, 0x00181308, 0x00181108, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x0017100b, 0x0017100b, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x0017100b, 0x0017100b, 0x00150f0a, 0x00150f0a, 0x0014100a, 0x00130f0a, 0x00120e09, 0x00130f0a, 0x00130f0a, 0x00140f0b, 0x0012100b, 0x0011100b, 0x000c0d08, 0x0013120b, 0x0012110a, 0x00121009, 0x00121009, 0x00140f0b, 0x00140f0b, 0x00140f0b, 0x00140f0b, 0x00120f08, 0x00110e08, 0x00131007, 0x00131006, 0x00121008, 0x00121008, 0x00121008, 0x00111008, 0x00121008, 0x00131008, 0x00131008, 0x00131107, 0x00161307, 0x00181107, 0x00181107, 0x001a1306, 0x001c1408, 0x00201408, 0x00241608, 0x00291909, 0x002d1c0a, 0x002e1c0a, 0x00362009, 0x00432808, 0x00654518, 0x00805013, 0x00996810, 0x00c29a22, 0x00cbae16, 0x00ccb40c, 0x00cab30a, 0x00c9b20c, 0x00c9b20e, 0x00cab20f, 0x00cab110, 0x00cab114, 0x00cbb018, 0x00c9b01a, 0x00cab019, 0x00cbae1b, 0x00cca91d, 0x00c8a51d, 0x00c9a420, 0x00c79d1d, 0x00c4981b, 0x00c09018, 0x00be8a19, 0x00b98419, 0x00b37c15, 0x00af7714, 0x00aa7115, 0x00a36b15, 0x009c6510, 0x0098600e, 0x00935e0e, 0x00895c10, 0x00865810, 0x00825510, 0x007c5211, 0x00784b17, 0x00774a18, 0x00734615, 0x00704613, 0x006d440e, 0x006f450d, 0x00754a0f, 0x00885a1b, 0x00a07420, 0x00bd922b, 0x00c9a42c, 0x00ccad21, 0x00ccb116, 0x00ccb50f, 0x00cbb60d, 0x00cbb80d, 0x00c9b80d, 0x00cab710, 0x00cbb510, 0x00cbb511, 0x00cab510, 0x00cab40c, 0x00ccb411, 0x00ccb018, 0x00ccac1c, 0x00c89c1f, 0x00b98c1b, 0x00a07110, 0x008b5c09, 0x00805210, 0x0068400b, 0x0054340a, 0x00442c06, 0x003a2505, 0x00332208, 0x002e1f07, 0x00271a04, 0x00241705, 0x001e1404, 0x001c1405, 0x00181104, 0x00141105, 0x00101003, 0x000c0d00, 0x000d0f01, 0x000d0f02, 0x00101003, 0x00101003, 0x00101103, 0x00141407, 0x001c1408, 0x001f1309, 0x00201409, 0x0021170a, 0x0024180b, 0x0026180b, 0x0025190b, 0x0024190b, 0x00211709, 0x00211609, 0x001f1408, 0x001f1409, 0x001f150a, 0x001c1308, 0x001a1106, 0x00191006, 0x00191007, 0x00181106, 0x00181206, 0x00181106, 0x00171107, 0x00161208, 0x00161208, 0x00181309, 0x0018140a, 0x00191409, 0x00181408, 0x00161308, 0x00130f06, 0x000e0d04, 0x000c0d05, 0x000b0e05, 0x000b0e05, 0x000a0d07, 0x000c0e08, 0x000c0f08, 0x00161b14, 0x00151d15, 0x00181f17, 0x00182018, 0x00192018, 0x00181f17, 0x00171e14, 0x00182016, 0x00182016, 0x00182016, 0x00191e15, 0x00191e15, 0x00191e15, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180b, 0x0014180b, 0x00191c09, 0x001d2009, 0x001d2008, 0x0024250b, 0x0026280b, 0x00292b0a, 0x002d2f0b, 0x0030310c, 0x0034350c, 0x0036370c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x004d4e0f, 0x004d4e10, 0x00786911, 0x00bb9614, 0x00cba216, 0x00cba216, 0x00b49215, 0x007d6e12, 0x005c5a10, 0x00585810, 0x00585911, 0x00595a12, 0x00595a12, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x005c5c12, 0x005c5c12, 0x005c5c12, 0x005c5c12, 0x005b5b12, 0x00595a12, 0x00595a12, 0x00585912, 0x005c5b11, 0x00726811, 0x00a48713, 0x00c6a015, 0x00cca316, 0x00c49c15, 0x008f7812, 0x00535210, 0x004d4e10, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450e, 0x0041420e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002d2f0b, 0x002c2d0b, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x0014180e, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c16, 0x00181b17, 0x00191b17, 0x00191916, 0x00141510, 0x0010100b, 0x000f100a, 0x000d100a, 0x000a0f08, 0x000a0e07, 0x000c0c07, 0x000c0d05, 0x00141408, 0x0019170b, 0x0021180f, 0x0023180e, 0x0020180d, 0x001f180b, 0x0024170c, 0x0028160c, 0x0028180c, 0x0029180d, 0x0029180e, 0x0024170d, 0x0020160b, 0x001c170a, 0x00181408, 0x00181209, 0x0018130a, 0x00161108, 0x00120f04, 0x00100f04, 0x00100e04, 0x000f0e03, 0x00111006, 0x00151106, 0x00151005, 0x00141205, 0x00161408, 0x00181708, 0x00191709, 0x00191808, 0x001a1908, 0x001e1908, 0x00231807, 0x00241807, 0x00281c0a, 0x002b1f0c, 0x002b200b, 0x002b1f0a, 0x002d200a, 0x0034240b, 0x003f240c, 0x0042270d, 0x00442b0b, 0x00482f0b, 0x0050370b, 0x005f410f, 0x006c460c, 0x00805210, 0x00946314, 0x00a8781c, 0x00b48922, 0x00c19a28, 0x00c6a425, 0x00cbaa23, 0x00ccad22, 0x00ccaf20, 0x00ccb01e, 0x00ccb01c, 0x00ccb11a, 0x00ccb41a, 0x00ccb419, 0x00ccb419, 0x00ccb221, 0x00cbab26, 0x00c5a326, 0x00bc961f, 0x00a67f14, 0x00946810, 0x007d4d06, 0x006e4309, 0x00623c0b, 0x005a3a0c, 0x00583a0e, 0x0058390b, 0x00583809, 0x005b3a0b, 0x005f3f0c, 0x0060410b, 0x00614209, 0x0068450a, 0x00704a0e, 0x00754c0e, 0x007c4c09, 0x0084540d, 0x008c5c10, 0x00996a18, 0x00a5781b, 0x00b48823, 0x00be9424, 0x00c89f27, 0x00c6a423, 0x00c9ac24, 0x00ccb020, 0x00ccb11a, 0x00ccb315, 0x00ccb413, 0x00ccb413, 0x00ccb612, 0x00ccb70f, 0x00cab808, 0x00cab808, 0x00c9b808, 0x00ccb80c, 0x00ccb315, 0x00ab880b, 0x007d5600, 0x00694401, 0x00553804, 0x00462d05, 0x00402b08, 0x003a2404, 0x00342004, 0x002f1d07, 0x00291907, 0x00261706, 0x00221508, 0x001f1307, 0x001b1308, 0x00191207, 0x00181307, 0x00171309, 0x00171309, 0x00151108, 0x00151108, 0x0017100b, 0x0017100b, 0x00150f0a, 0x00150f0a, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x00160f08, 0x00170f08, 0x00151008, 0x00151008, 0x00141009, 0x0014100a, 0x0013100a, 0x0014140c, 0x000e1008, 0x00101109, 0x0012110a, 0x0013100a, 0x0014100a, 0x0014100a, 0x0014100a, 0x00150f0a, 0x00150f0a, 0x00151009, 0x00151008, 0x00151008, 0x00171009, 0x00151008, 0x00161108, 0x00161108, 0x00161108, 0x00161109, 0x00151109, 0x00151108, 0x00151108, 0x00161208, 0x00181207, 0x00191208, 0x001c1208, 0x001d1409, 0x00201408, 0x00241508, 0x00281808, 0x002d1c09, 0x002f1b09, 0x0037200a, 0x0044280a, 0x00674418, 0x007f5014, 0x009b6915, 0x00c59c26, 0x00cbac15, 0x00cbb10a, 0x00c8b209, 0x00c8b209, 0x00c9b30b, 0x00c9b30c, 0x00cab40f, 0x00cbb410, 0x00ccb410, 0x00ccb411, 0x00ccb40f, 0x00ccb40f, 0x00ccb310, 0x00ccb311, 0x00ccb211, 0x00ccb113, 0x00ccb012, 0x00ccaf13, 0x00ccac16, 0x00ccaa1a, 0x00caa61d, 0x00caa321, 0x00c9a023, 0x00c39820, 0x00be921c, 0x00b98c19, 0x00b48417, 0x00af7c18, 0x00a77211, 0x00a06c0f, 0x009a660b, 0x009a6412, 0x00925c14, 0x00895414, 0x00885414, 0x00845310, 0x00815010, 0x008b5a15, 0x00a87925, 0x00c4a02b, 0x00caad24, 0x00ccb11d, 0x00cab314, 0x00cab40f, 0x00c9b70c, 0x00c9b80b, 0x00c8b80c, 0x00c8b80c, 0x00c8b80c, 0x00c8b70c, 0x00c8b60c, 0x00c8b50c, 0x00cbb50c, 0x00cbb40d, 0x00c9b510, 0x00c9b412, 0x00ccb018, 0x00c9ac18, 0x00bf9d18, 0x00a87e0c, 0x00905f02, 0x00804f08, 0x00683c08, 0x004c3003, 0x00402a04, 0x003c2808, 0x00342307, 0x002e2008, 0x002b1d09, 0x00281a08, 0x00241606, 0x00201407, 0x001b1207, 0x00161207, 0x00121004, 0x00100f04, 0x000c0e02, 0x00090d01, 0x00080d01, 0x00060e01, 0x00081003, 0x000e1004, 0x00101005, 0x00101004, 0x00131405, 0x001b1408, 0x0021180b, 0x0023190c, 0x0024190d, 0x0024190c, 0x00261a0c, 0x00291c10, 0x0026180e, 0x0023160c, 0x0021180a, 0x0020180b, 0x001e140a, 0x001c1108, 0x001c1206, 0x001a1306, 0x00181406, 0x00181407, 0x00181508, 0x00181408, 0x001b1408, 0x001d1408, 0x001c1409, 0x00181308, 0x00140f07, 0x00100c04, 0x000d0c04, 0x000b0c03, 0x000a0d05, 0x000c0e08, 0x000c0e08, 0x000c1009, 0x000c0f08, 0x00121710, 0x001c2019, 0x00191e17, 0x001a1f18, 0x001b2018, 0x001a1f18, 0x00182018, 0x00182018, 0x001b2018, 0x001b2018, 0x001d211a, 0x001c1f18, 0x001c1e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250c, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004b4c10, 0x004c4d0f, 0x004f5010, 0x005d5810, 0x00a08413, 0x00c79f15, 0x00cca316, 0x00c9a116, 0x00b19015, 0x00887512, 0x00635e10, 0x005b5910, 0x00585810, 0x00595a11, 0x00585911, 0x00595a11, 0x00585911, 0x00585911, 0x00585911, 0x00595a11, 0x00595a11, 0x005c5a11, 0x00656010, 0x008a7613, 0x00ae8e14, 0x00c8a015, 0x00cca316, 0x00c9a116, 0x00b08f14, 0x00706410, 0x004f4f10, 0x004d4e10, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450e, 0x0041420e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c16, 0x00181b17, 0x00191b18, 0x00191a16, 0x0014150e, 0x00101009, 0x000f100a, 0x000d100a, 0x000a0f08, 0x00090e07, 0x000b0d07, 0x000b0c04, 0x000e0d02, 0x001c190d, 0x00281b12, 0x00271810, 0x0023160c, 0x0021160c, 0x0020140a, 0x00201409, 0x00201409, 0x00201409, 0x001e1408, 0x001a1305, 0x00151203, 0x00121201, 0x000d0f00, 0x000c0d02, 0x000e0d03, 0x000e0e01, 0x000f0f02, 0x00141105, 0x00131104, 0x00141205, 0x00181608, 0x001e180b, 0x001f180a, 0x00201809, 0x00221a0b, 0x00241c0d, 0x00241c0d, 0x00241d0c, 0x00271e0b, 0x002b1d0a, 0x00301c08, 0x00301c08, 0x00311e0a, 0x00331f0b, 0x0033200b, 0x00342209, 0x0037250a, 0x003c290c, 0x00492a10, 0x004e2f10, 0x0053320e, 0x005c3c11, 0x00664410, 0x007a5413, 0x00936917, 0x00b08422, 0x00c09728, 0x00c7a328, 0x00ccac24, 0x00ccaf1c, 0x00ccb216, 0x00ccb412, 0x00ccb512, 0x00ccb611, 0x00ccb811, 0x00ccb810, 0x00ccb80e, 0x00cbba0c, 0x00cbba0b, 0x00cbb90c, 0x00ccb911, 0x00ccb816, 0x00ccb619, 0x00ccb31c, 0x00cbae22, 0x00be9a21, 0x00a47a10, 0x00805703, 0x00704808, 0x00653f0a, 0x00613e0b, 0x00603d08, 0x00673f09, 0x006d440c, 0x0071480c, 0x00754c0a, 0x007e540d, 0x0084560e, 0x008d5f13, 0x00976717, 0x00a07115, 0x00ac801c, 0x00bc9026, 0x00c39929, 0x00cba427, 0x00cca824, 0x00ccac1e, 0x00ccad18, 0x00c9ae14, 0x00cbb314, 0x00ccb511, 0x00cbb50c, 0x00ccb60b, 0x00ccb60a, 0x00ccb70b, 0x00ccb80b, 0x00ccb80a, 0x00cab808, 0x00cab908, 0x00cab908, 0x00ccb80d, 0x00ccb718, 0x00af8c0d, 0x00825800, 0x00674000, 0x00563705, 0x00462d06, 0x003c2806, 0x00382201, 0x00332005, 0x002d1d07, 0x00291907, 0x00251707, 0x00221408, 0x001f1307, 0x001b1307, 0x00191207, 0x00181308, 0x00171309, 0x00171309, 0x00161208, 0x00151108, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x00161008, 0x00160f08, 0x00151008, 0x00151008, 0x00151009, 0x0014100a, 0x0012100a, 0x0014140c, 0x000e1008, 0x00101109, 0x0012110a, 0x0013100a, 0x0014100a, 0x0014100a, 0x0014100a, 0x0017100b, 0x0017100b, 0x00151008, 0x00151008, 0x00171009, 0x00171009, 0x00171008, 0x00171008, 0x00181209, 0x00181309, 0x00171209, 0x0016120a, 0x00151109, 0x00151108, 0x00151108, 0x00181207, 0x00191208, 0x001c1208, 0x001d1409, 0x00201408, 0x00231406, 0x00281808, 0x002e1b09, 0x00301a09, 0x0038200a, 0x0045290a, 0x00684619, 0x007f5014, 0x009a6916, 0x00c69d27, 0x00ccad18, 0x00c9b109, 0x00c8b308, 0x00c8b308, 0x00c9b408, 0x00c9b408, 0x00cab408, 0x00cbb509, 0x00cbb608, 0x00cbb708, 0x00cab707, 0x00c9b706, 0x00cab606, 0x00cab607, 0x00cab407, 0x00cab408, 0x00cbb408, 0x00cbb408, 0x00ccb40b, 0x00ccb20e, 0x00ccb011, 0x00ccaf13, 0x00cbad14, 0x00caac14, 0x00caab18, 0x00caab1b, 0x00cba81d, 0x00cca01c, 0x00c99d1c, 0x00c4981b, 0x00bf9217, 0x00b58716, 0x00b07f19, 0x00a36e15, 0x0096600d, 0x008d5b0c, 0x00905e13, 0x00aa7c27, 0x00c79f34, 0x00ccb025, 0x00ccb418, 0x00ccb512, 0x00ccb60c, 0x00ccb708, 0x00cbb708, 0x00cab509, 0x00cbb30b, 0x00cbb30a, 0x00cbb30a, 0x00ccb50c, 0x00ccb50c, 0x00ccb50b, 0x00ccb409, 0x00cbb509, 0x00c9b708, 0x00c9b707, 0x00ccb50e, 0x00cbb410, 0x00ccb318, 0x00c4a219, 0x00ae7f0d, 0x00935e02, 0x007c4c07, 0x00613a04, 0x004d3004, 0x00432906, 0x00392506, 0x00342408, 0x00312008, 0x00301e08, 0x002d1c09, 0x00291909, 0x0024170a, 0x0020170c, 0x001d150b, 0x001a1409, 0x00151006, 0x00101007, 0x000e0f06, 0x000c1006, 0x000a0f05, 0x000a0f04, 0x000b0f04, 0x000a0e04, 0x000a0e03, 0x000e0d03, 0x00140d03, 0x00161006, 0x00180f05, 0x00181004, 0x001b1207, 0x001e1409, 0x0020150a, 0x0022180c, 0x0024180e, 0x0024180d, 0x0024170c, 0x0022150b, 0x0022140b, 0x0021150b, 0x00201609, 0x001f1709, 0x001d1508, 0x001d1508, 0x001f1508, 0x00201508, 0x001c1408, 0x00141005, 0x00100c04, 0x000e0c04, 0x000c0c04, 0x00090d03, 0x00090c04, 0x000b0d07, 0x000c0f08, 0x000c1009, 0x000d100a, 0x000d120c, 0x001a1f18, 0x00191e17, 0x00191e17, 0x001a1f18, 0x001a1f18, 0x00182018, 0x00182018, 0x001b2018, 0x001b2018, 0x001d201a, 0x001c1f18, 0x001c1e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0045470e, 0x0048490f, 0x004b4c10, 0x004c4d0f, 0x004d4e0f, 0x00515010, 0x00726511, 0x00aa8a14, 0x00c8a015, 0x00cca216, 0x00c9a116, 0x00c49d15, 0x00af8f14, 0x009c8214, 0x008c7713, 0x007e6e12, 0x00786a12, 0x00726811, 0x00796c12, 0x00837212, 0x00907a13, 0x00a08514, 0x00b39114, 0x00c59e15, 0x00caa116, 0x00cca316, 0x00caa116, 0x00b89514, 0x00877312, 0x00565410, 0x004f5010, 0x004c4d0f, 0x004b4c10, 0x0048490f, 0x0047480e, 0x0044450e, 0x0041420e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0020230a, 0x001d2008, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x00141810, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x00181c15, 0x00181c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00191c16, 0x00191c16, 0x00181c15, 0x00181c16, 0x00191b17, 0x001b1c18, 0x00171813, 0x0013140c, 0x000f1008, 0x000f1008, 0x000d1008, 0x000b0f06, 0x000a0f06, 0x000c0e08, 0x000c1006, 0x000c0c01, 0x00181509, 0x0021150e, 0x001e0f09, 0x00190e07, 0x00180f07, 0x00161007, 0x00120f05, 0x00110f03, 0x00110e03, 0x00100e02, 0x000f0f01, 0x000d0f00, 0x000f1001, 0x000e1000, 0x00101204, 0x00141407, 0x00141405, 0x00141405, 0x001a1306, 0x001d1608, 0x00201708, 0x00241c0c, 0x00261c0c, 0x00271c09, 0x00261907, 0x00281b08, 0x002c1d09, 0x002d1e0a, 0x002e1e0a, 0x0030200a, 0x00332008, 0x00362008, 0x00372109, 0x00382209, 0x003c240c, 0x003c270d, 0x003c270b, 0x00402a0c, 0x00442d0c, 0x0050310f, 0x0055340c, 0x00603b08, 0x00724a11, 0x00875d14, 0x00a87f21, 0x00bf9924, 0x00c9a820, 0x00cbaf1c, 0x00cbb118, 0x00ccb413, 0x00ccb50f, 0x00ccb410, 0x00ccb10d, 0x00ccae0d, 0x00cbac0c, 0x00cbad0f, 0x00caae0f, 0x00c9af0d, 0x00cab10c, 0x00ccb50d, 0x00ccb50c, 0x00cbb70a, 0x00ccb809, 0x00ccbc09, 0x00ccba0e, 0x00ccb814, 0x00ccb41d, 0x00c4a718, 0x00a17d0b, 0x00785000, 0x00724704, 0x0072460a, 0x00764b0b, 0x0081540f, 0x008b5e12, 0x00926614, 0x009b6f13, 0x00a47814, 0x00af821d, 0x00bc9028, 0x00c49c2d, 0x00c6a023, 0x00cba824, 0x00cba81f, 0x00ccac1c, 0x00ccb014, 0x00ccb210, 0x00ccb40d, 0x00ccb409, 0x00cab608, 0x00c9b608, 0x00c9b707, 0x00c9b706, 0x00cab806, 0x00cab808, 0x00cbb808, 0x00ccb808, 0x00ccb808, 0x00ccb808, 0x00cab908, 0x00cbba0a, 0x00ccb80d, 0x00ccb518, 0x00b18e10, 0x00835a00, 0x00673f00, 0x00543403, 0x00452d06, 0x003c2805, 0x00362100, 0x00331f04, 0x002c1c08, 0x00281808, 0x00251607, 0x00221408, 0x001e1307, 0x001a1207, 0x00191207, 0x00181308, 0x00171309, 0x00171309, 0x00161208, 0x00161208, 0x0018110a, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00151109, 0x00171109, 0x0018110a, 0x0017110b, 0x0016110c, 0x0014120c, 0x0014140c, 0x000c0e06, 0x0012110a, 0x0013120b, 0x0014110b, 0x0015100b, 0x0017100b, 0x0017100b, 0x0017100b, 0x0017100b, 0x0018110a, 0x0018110a, 0x00171009, 0x00171009, 0x00181108, 0x00181108, 0x00181208, 0x00181208, 0x00171108, 0x00161208, 0x00151108, 0x00151108, 0x00161208, 0x00181207, 0x00191208, 0x001c1309, 0x001f140a, 0x00201408, 0x00231406, 0x00281707, 0x002c1a08, 0x00301b08, 0x00371f08, 0x00442707, 0x006a4819, 0x00805014, 0x009c6b18, 0x00c59c26, 0x00ccaf1a, 0x00cab30a, 0x00c9b407, 0x00c9b405, 0x00c9b405, 0x00c9b405, 0x00cab506, 0x00cab504, 0x00cbb605, 0x00c9b705, 0x00c9b707, 0x00c8b807, 0x00c9b707, 0x00c9b707, 0x00cbb607, 0x00cbb608, 0x00ccb508, 0x00ccb508, 0x00ccb507, 0x00ccb508, 0x00cbb408, 0x00cbb409, 0x00cab509, 0x00cbb50b, 0x00cbb40c, 0x00ccb410, 0x00ccb311, 0x00ccb212, 0x00ccb013, 0x00ccad14, 0x00ccac16, 0x00cba718, 0x00cba01d, 0x00c1901c, 0x00a06c06, 0x0099620a, 0x00a07017, 0x00c2982d, 0x00ccac27, 0x00cbb315, 0x00ccb60e, 0x00ccb70a, 0x00ccb805, 0x00cab504, 0x00ccb20c, 0x00cbaa0d, 0x00caa411, 0x00c8a010, 0x00c49d0c, 0x00c29c0a, 0x00c49f0c, 0x00c5a20d, 0x00c8a80e, 0x00ccb011, 0x00ccb410, 0x00ccb60c, 0x00ccb60d, 0x00ccb908, 0x00cbb707, 0x00ccb214, 0x00c8a218, 0x00ac7e08, 0x008e5c00, 0x00774903, 0x005e3805, 0x004e2f07, 0x00432804, 0x003c2608, 0x00382408, 0x00362006, 0x00331e07, 0x00301d08, 0x002c1c0a, 0x002a190e, 0x0028180d, 0x0026180e, 0x0024190e, 0x001e160b, 0x00181207, 0x00171409, 0x00131207, 0x00101105, 0x000c1003, 0x000c0f03, 0x000c0f03, 0x000d0c03, 0x00100c04, 0x00100c03, 0x00100c03, 0x000f0c02, 0x00100b01, 0x00120d02, 0x00151005, 0x001a1308, 0x001e1409, 0x001f1509, 0x0025180c, 0x0025190d, 0x0024180b, 0x0026190d, 0x0025170a, 0x00251609, 0x00241608, 0x00231608, 0x00231708, 0x001f1407, 0x00161002, 0x00100d02, 0x000e0c03, 0x000d0c04, 0x000a0d03, 0x00080e03, 0x00080d04, 0x00090e07, 0x000a0f09, 0x000d100a, 0x0010120c, 0x000e110b, 0x00151812, 0x00181d16, 0x00181d16, 0x00191e17, 0x00191e17, 0x00192018, 0x00192018, 0x001b2018, 0x001b2018, 0x001c2019, 0x001c1f18, 0x001c1e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0040400d, 0x0043440e, 0x0045470e, 0x0047480f, 0x00494a10, 0x004b4c0f, 0x004c4d0f, 0x004d4e10, 0x00525010, 0x00706311, 0x00a08413, 0x00be9815, 0x00cba116, 0x00cca216, 0x00cca216, 0x00caa116, 0x00c8a015, 0x00c7a015, 0x00c7a015, 0x00c8a015, 0x00c8a016, 0x00caa216, 0x00cca316, 0x00cca316, 0x00cca216, 0x00c8a015, 0x00af8e14, 0x00867111, 0x00595510, 0x004f5010, 0x004d4e0f, 0x004b4c0f, 0x00494a10, 0x0048490f, 0x0045470e, 0x0043440e, 0x0041420d, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c09, 0x00141809, 0x0014180b, 0x0014180e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c15, 0x00181c15, 0x001a1b15, 0x00181c15, 0x00181c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00191c16, 0x00191c16, 0x00181c15, 0x00181c16, 0x00191b17, 0x001c1c18, 0x00171812, 0x0013140c, 0x000f1007, 0x000f1007, 0x000d1007, 0x000c0f04, 0x00091006, 0x000a0f06, 0x000d1007, 0x00101005, 0x00151309, 0x001a120c, 0x00140d07, 0x00100b04, 0x000e0c04, 0x000c0d04, 0x000c0d04, 0x000e0f04, 0x00101005, 0x00101005, 0x00121205, 0x00131204, 0x00151405, 0x00161405, 0x001c180b, 0x00201a0c, 0x00201a0d, 0x00211a0c, 0x00241c09, 0x00281d0b, 0x00281f0c, 0x002b1f0c, 0x002c1e0b, 0x002d1e0a, 0x002f1e0a, 0x0030200a, 0x0033220a, 0x00342209, 0x00342209, 0x0037230a, 0x00382509, 0x003a270a, 0x003c280b, 0x003f290e, 0x00402a0f, 0x00412b0e, 0x00442c0c, 0x00482e0c, 0x004c320c, 0x0058380b, 0x00634009, 0x0078500d, 0x009c7224, 0x00b9902a, 0x00cba62e, 0x00caac1f, 0x00ccb313, 0x00cbb50c, 0x00cbb40a, 0x00ccb10c, 0x00cbac0a, 0x00caa30d, 0x00c49810, 0x00bd8f0a, 0x00b58906, 0x00b08405, 0x00b08406, 0x00af8604, 0x00b48c08, 0x00bc960d, 0x00c5a311, 0x00cbae14, 0x00cab50c, 0x00c9b806, 0x00cabb09, 0x00cbbb0e, 0x00c9b710, 0x00ccb616, 0x00c0a015, 0x008c6600, 0x00805104, 0x0081530c, 0x00966919, 0x00ad8328, 0x00b38b27, 0x00bb9527, 0x00c7a129, 0x00cba826, 0x00ccac28, 0x00ccae25, 0x00ccb122, 0x00cab01c, 0x00cbb418, 0x00ccb614, 0x00ccb710, 0x00cab70c, 0x00c9b608, 0x00cab607, 0x00c9b705, 0x00c8b807, 0x00c8b708, 0x00c9b608, 0x00c9b609, 0x00c9b709, 0x00c9b809, 0x00cbb80a, 0x00ccb80a, 0x00cab908, 0x00cab908, 0x00c8ba08, 0x00cabb0a, 0x00cbb90c, 0x00ccb618, 0x00b18e10, 0x00845b00, 0x00664000, 0x00543403, 0x00442d06, 0x00382603, 0x00331f00, 0x00311e04, 0x002c1c08, 0x00281708, 0x00241508, 0x00201307, 0x001c1206, 0x00191307, 0x00181307, 0x00171408, 0x00171309, 0x00171309, 0x00161208, 0x00161208, 0x00171008, 0x00171008, 0x00171008, 0x00171008, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00141109, 0x00141109, 0x0015110a, 0x0017120a, 0x0017110b, 0x0016110c, 0x0014120c, 0x0014140c, 0x000c0e06, 0x0012110b, 0x0013120b, 0x0014110b, 0x0015100b, 0x0017100b, 0x0017100b, 0x0018110c, 0x0018110c, 0x0018110a, 0x0018110a, 0x00171009, 0x00171009, 0x00181108, 0x00181108, 0x00171008, 0x00171008, 0x00161008, 0x00151108, 0x00151108, 0x00151108, 0x00161208, 0x00181207, 0x00191208, 0x001c1409, 0x001f140b, 0x00201408, 0x00231407, 0x00261706, 0x002c1908, 0x00301b08, 0x00381e08, 0x00442606, 0x006b491c, 0x00825417, 0x00a06e1b, 0x00c69c27, 0x00ccb01a, 0x00cab30a, 0x00c9b404, 0x00c9b404, 0x00c9b405, 0x00c9b405, 0x00cab506, 0x00cab506, 0x00ccb508, 0x00cbb508, 0x00cbb509, 0x00cbb50a, 0x00cbb50c, 0x00ccb40d, 0x00ccb40d, 0x00ccb40d, 0x00ccb40f, 0x00cbb40f, 0x00cbb40d, 0x00cab60c, 0x00c8b50a, 0x00c8b508, 0x00c9b508, 0x00cbb607, 0x00cbb609, 0x00cbb50c, 0x00cbb50c, 0x00cbb50c, 0x00cab40b, 0x00c9b30d, 0x00cbb210, 0x00ccad0d, 0x00cca710, 0x00c2910f, 0x00a46b00, 0x009c6504, 0x00b48720, 0x00cba82c, 0x00cbb217, 0x00cbb60c, 0x00ccb80c, 0x00ccb708, 0x00ccb805, 0x00cab109, 0x00c6a30e, 0x00b88c07, 0x00ae7902, 0x00a87002, 0x00a06d00, 0x00a06c00, 0x00a37000, 0x00a67402, 0x00b38308, 0x00bd900d, 0x00c79f14, 0x00ccaa18, 0x00cbb412, 0x00c8bb03, 0x00c9b900, 0x00ccb40b, 0x00ccb115, 0x00c4a014, 0x00a47804, 0x00815300, 0x00683f06, 0x00543306, 0x00482c04, 0x00422a07, 0x003f2707, 0x003b2305, 0x00372004, 0x00341f07, 0x00331e09, 0x00311c0c, 0x00301b0b, 0x002f1a0b, 0x002d1b0c, 0x00291a0d, 0x0026180c, 0x0024190c, 0x001f170b, 0x001b1709, 0x00181406, 0x00171306, 0x00141004, 0x00111004, 0x00101005, 0x000f0f04, 0x000c0c01, 0x000c0c01, 0x000e0c02, 0x000f0d03, 0x000d0c01, 0x00100d02, 0x00130f03, 0x00141002, 0x00191507, 0x001d1808, 0x001e1708, 0x00231809, 0x00281a0c, 0x0029190b, 0x0029180a, 0x0028180a, 0x00231707, 0x001c1101, 0x00130e00, 0x000e0c01, 0x000d0d03, 0x000c0d04, 0x000a0e04, 0x00070e03, 0x00080e04, 0x00090e07, 0x00090e07, 0x000c100a, 0x000f140c, 0x000e110b, 0x00151812, 0x00171c15, 0x00181d16, 0x00181d16, 0x00191e17, 0x00192018, 0x00192018, 0x001b2018, 0x001b2018, 0x001c2019, 0x001c1f18, 0x001c1e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0038380c, 0x00393b0d, 0x003c3e0d, 0x0040400d, 0x0041420e, 0x0044450e, 0x0045470e, 0x0048490f, 0x00494a10, 0x004b4c0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x005e5810, 0x007a6a11, 0x009c8013, 0x00b18f14, 0x00bc9815, 0x00c49c15, 0x00c8a015, 0x00c9a116, 0x00c8a015, 0x00c49d16, 0x00c09915, 0x00b69314, 0x00a98914, 0x008c7512, 0x006b6011, 0x00535110, 0x004d4e10, 0x004d4e0f, 0x004c4d0f, 0x004b4c10, 0x0048490f, 0x0047480e, 0x0044450e, 0x0043440e, 0x0040400d, 0x003c3e0c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1b15, 0x00151710, 0x00101208, 0x000f1006, 0x000f1007, 0x000d0f05, 0x000c0f04, 0x000c0f06, 0x000c1007, 0x000e0f08, 0x0015130c, 0x0014120c, 0x00141109, 0x000f0e07, 0x000e0d06, 0x000c0e06, 0x000c0e05, 0x000e1008, 0x00111108, 0x00151308, 0x00181408, 0x001d1809, 0x0021190b, 0x00241a0d, 0x0026190c, 0x002b1d0d, 0x002c1e0d, 0x002c1d0d, 0x002e1e0e, 0x002d1d0d, 0x002d1e0c, 0x00301f0c, 0x0033220d, 0x0034220c, 0x0035210c, 0x00352209, 0x0038240a, 0x0038270c, 0x003b290e, 0x003e2c11, 0x003f2d12, 0x00402e10, 0x00402f0f, 0x0040300c, 0x0044310d, 0x00473410, 0x00483310, 0x004b3410, 0x004f3610, 0x00543810, 0x0068400f, 0x00784f0f, 0x00a37823, 0x00c19530, 0x00c8ab26, 0x00ccb31d, 0x00ccb414, 0x00cab40f, 0x00ccb20f, 0x00c8a811, 0x00c29c13, 0x00b38708, 0x00a47300, 0x00976300, 0x00905a00, 0x00895400, 0x00885300, 0x00875100, 0x00855300, 0x00895700, 0x00906001, 0x009a6f07, 0x00af860e, 0x00c5a416, 0x00cbb416, 0x00cab60f, 0x00c8b80e, 0x00c8b80e, 0x00ccb80e, 0x00cbb017, 0x00a37c08, 0x00885902, 0x00916210, 0x00bb9030, 0x00cba732, 0x00c8ac26, 0x00cbb120, 0x00ccb319, 0x00ccb518, 0x00ccb618, 0x00cab715, 0x00cab813, 0x00c8b710, 0x00c8b80e, 0x00c9b80c, 0x00c9b80b, 0x00c9b809, 0x00c9b809, 0x00c9b809, 0x00c9b809, 0x00c9b80b, 0x00c9b80c, 0x00c9b80c, 0x00c9b70e, 0x00c9b70e, 0x00c9b80c, 0x00c9b80a, 0x00c8ba08, 0x00c8b908, 0x00c8b808, 0x00c8b809, 0x00cab90a, 0x00ccb90a, 0x00ccb713, 0x00b3900c, 0x00835c00, 0x00694500, 0x00543602, 0x00422c04, 0x00382504, 0x00321f00, 0x00301e08, 0x002c1a0b, 0x00251608, 0x00221406, 0x001f1406, 0x001c1205, 0x00181307, 0x00181307, 0x00171408, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x0018110a, 0x00171009, 0x00171009, 0x00171009, 0x00141208, 0x00141208, 0x00141108, 0x00161108, 0x00171109, 0x0016120a, 0x0016120a, 0x0016140b, 0x00131008, 0x00121108, 0x00141209, 0x00141109, 0x00141109, 0x00171009, 0x00171009, 0x0018100a, 0x0018100a, 0x00181108, 0x00161208, 0x00161208, 0x00161208, 0x00151108, 0x00151108, 0x00151108, 0x00151108, 0x00161108, 0x00171008, 0x00171008, 0x00171008, 0x00171309, 0x00171309, 0x00181309, 0x001c130c, 0x001d140b, 0x00201408, 0x00231407, 0x00261706, 0x002c1908, 0x00301b08, 0x00381f08, 0x00442608, 0x0069481e, 0x0085551a, 0x00a36f1c, 0x00c99e2c, 0x00ccaf1d, 0x00c8b20e, 0x00c8b408, 0x00c8b408, 0x00c8b40a, 0x00c8b40a, 0x00c8b509, 0x00cab409, 0x00cbb50b, 0x00cbb50c, 0x00cbb50c, 0x00cbb50c, 0x00cbb50c, 0x00cbb50c, 0x00ccb40d, 0x00ccb40d, 0x00ccb40c, 0x00ccb40c, 0x00cbb50a, 0x00cbb50a, 0x00cbb50a, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00cbb408, 0x00cbb408, 0x00cbb408, 0x00cbb409, 0x00ccb309, 0x00ccb008, 0x00cca80e, 0x00b78504, 0x00a16500, 0x00a1690e, 0x00c49a2c, 0x00ccb020, 0x00ccb90c, 0x00ccb90b, 0x00ccb80f, 0x00ccb810, 0x00cbb410, 0x00bc9c09, 0x00a97d03, 0x00976501, 0x00945e02, 0x008d5700, 0x008c5404, 0x008a5203, 0x008c5505, 0x008d5503, 0x00925d01, 0x009c6904, 0x00ab780a, 0x00c19018, 0x00cca619, 0x00ccb30d, 0x00cab804, 0x00ccb70a, 0x00ccb411, 0x00ccb014, 0x00c09a15, 0x00906001, 0x00744804, 0x005d3d04, 0x00503204, 0x00482e06, 0x00442b07, 0x00412909, 0x003d2507, 0x00382307, 0x00362008, 0x00341e08, 0x00321c08, 0x00321d09, 0x00301e0b, 0x002f1c0a, 0x002e1d0a, 0x002c1d09, 0x002a1d0a, 0x00251b0c, 0x0020180a, 0x00201709, 0x001d1409, 0x00191004, 0x00151004, 0x00141004, 0x00100f03, 0x00100e04, 0x00100f05, 0x000d0c04, 0x000d0c04, 0x000c0c02, 0x000c0c01, 0x000c0e00, 0x000d1002, 0x00101405, 0x00131405, 0x00171304, 0x001f1508, 0x0027190d, 0x00281c10, 0x0024190f, 0x001d1408, 0x00150f04, 0x000f0c01, 0x000e0e03, 0x000d0d04, 0x000c0c04, 0x000a0e04, 0x00080f05, 0x00080f05, 0x00080d04, 0x00080d06, 0x00090d05, 0x000a0d05, 0x000e1109, 0x0013160e, 0x00171c15, 0x00171c15, 0x00181d16, 0x00181d16, 0x00192018, 0x00192018, 0x00192018, 0x00192018, 0x001b2019, 0x001b201a, 0x001b201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0043440e, 0x0045470e, 0x0047480e, 0x0048490f, 0x00494a0f, 0x004b4c10, 0x004c4d0f, 0x004d4e0f, 0x004c4d0f, 0x004b4c10, 0x00515010, 0x00605810, 0x00685d11, 0x006d6011, 0x006f6110, 0x006c6010, 0x006a5f10, 0x00635b10, 0x00585410, 0x004c4d10, 0x004c4d10, 0x004d4e0f, 0x004c4d0f, 0x004b4c0f, 0x00494a0f, 0x0048490f, 0x0047480e, 0x0045470e, 0x0044450e, 0x0041420e, 0x0040400d, 0x003c3e0d, 0x00393b0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1c16, 0x00181812, 0x0012140c, 0x000f1007, 0x000f1005, 0x000d0f05, 0x000c0e04, 0x000c0f04, 0x000c0e04, 0x000d0f07, 0x00101009, 0x0016130c, 0x0017120c, 0x00121209, 0x000d1007, 0x000d1007, 0x000e1108, 0x00111208, 0x0015150c, 0x0019160b, 0x001d180a, 0x0021190a, 0x00281b0b, 0x002c1c0d, 0x002f1d10, 0x00301d0e, 0x00311f0c, 0x0032200b, 0x0033200b, 0x0034210c, 0x0035220e, 0x0035230f, 0x0035240c, 0x0039270e, 0x003b280e, 0x003b280c, 0x003d2a0d, 0x00402c0d, 0x00412f0d, 0x00453010, 0x00473311, 0x00463211, 0x00473311, 0x00473310, 0x00483510, 0x004c3910, 0x004e3c10, 0x00503b0d, 0x00523b0c, 0x00583c0d, 0x0060420f, 0x00744e0b, 0x009c7621, 0x00be9a2b, 0x00ccac28, 0x00ccb41a, 0x00ccb710, 0x00ccb611, 0x00c9ac0e, 0x00c29e10, 0x00ad8208, 0x00996902, 0x008a5800, 0x00815000, 0x007a4900, 0x00764500, 0x00724100, 0x00724201, 0x00744403, 0x00744401, 0x00774802, 0x007f5007, 0x00825504, 0x008f6001, 0x00ac840f, 0x00cbac1f, 0x00cbb511, 0x00c8b80b, 0x00c8bb08, 0x00cbb908, 0x00cbb514, 0x00a88204, 0x00906001, 0x00996a0d, 0x00c19926, 0x00ccb024, 0x00cab414, 0x00cbb60f, 0x00ccb70a, 0x00cab80c, 0x00cab80c, 0x00ccb80d, 0x00ccb80d, 0x00cab70c, 0x00cab70c, 0x00cbb70c, 0x00cbb70c, 0x00cab70c, 0x00cab70b, 0x00cab70b, 0x00cab809, 0x00cab809, 0x00cab70b, 0x00c9b80b, 0x00c9b80b, 0x00c9b80a, 0x00c9b809, 0x00c9b808, 0x00cab907, 0x00caba06, 0x00ccba08, 0x00ccb90a, 0x00ccb80a, 0x00ccb80d, 0x00ccb616, 0x00b38f0e, 0x00845d00, 0x006e4c03, 0x00513400, 0x003f2903, 0x00362606, 0x00321e04, 0x002f1c08, 0x00281809, 0x00241506, 0x00201305, 0x001d1204, 0x001a1305, 0x00181307, 0x00171407, 0x00161408, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x0016120a, 0x0016120a, 0x0016120a, 0x0016120a, 0x00141208, 0x00141106, 0x00161106, 0x00171006, 0x00181008, 0x00181108, 0x00181108, 0x00181309, 0x00141008, 0x00121107, 0x00141208, 0x00151108, 0x00151108, 0x00161208, 0x00171108, 0x00181108, 0x00181108, 0x00161307, 0x00161307, 0x00161307, 0x00161307, 0x00151208, 0x00151108, 0x00151108, 0x00151108, 0x00161108, 0x00181108, 0x00171008, 0x00181309, 0x00171309, 0x00171309, 0x00181309, 0x001c140c, 0x001d140b, 0x00201408, 0x00231406, 0x00261706, 0x002b1908, 0x00301c08, 0x00361f09, 0x00402408, 0x0065451d, 0x007c5013, 0x009a6712, 0x00c79927, 0x00cca91b, 0x00caaf0c, 0x00cab309, 0x00cab309, 0x00cab308, 0x00cab308, 0x00cbb408, 0x00cab408, 0x00cbb608, 0x00c9b608, 0x00c9b708, 0x00c9b708, 0x00c9b708, 0x00c9b707, 0x00cab608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00cbb408, 0x00cab307, 0x00cbb408, 0x00ccb408, 0x00ccb409, 0x00ccb20f, 0x00caa510, 0x00b07d02, 0x00a06301, 0x00ac7415, 0x00c7a02a, 0x00ccb31c, 0x00ccbb0a, 0x00ccbb0c, 0x00ccb810, 0x00ccb712, 0x00c4a60d, 0x00a88000, 0x00946500, 0x00885802, 0x00855405, 0x00815103, 0x0081500a, 0x00805008, 0x00804f08, 0x007f5007, 0x00835404, 0x00885802, 0x00916002, 0x00a06d08, 0x00b88c14, 0x00caa819, 0x00cbb212, 0x00ccb511, 0x00ccb510, 0x00ccb410, 0x00cbaa19, 0x00aa7c0f, 0x007d5300, 0x00664402, 0x00573804, 0x004d3306, 0x00482e07, 0x00462c09, 0x00442c0a, 0x003e2808, 0x00392306, 0x00392208, 0x00382108, 0x00362008, 0x00331f08, 0x00321e08, 0x00301e08, 0x002f1f08, 0x002f1f08, 0x002e1f0c, 0x002d1c0e, 0x002c1b0c, 0x002b190b, 0x0026180a, 0x0025180b, 0x00221809, 0x001e1707, 0x001b1408, 0x00161008, 0x00141007, 0x00121107, 0x00101006, 0x000f0f04, 0x000b0c01, 0x00090e00, 0x00081000, 0x00081000, 0x000b0f00, 0x00101001, 0x00171104, 0x001c140a, 0x001e170c, 0x0018140b, 0x00121006, 0x000f0d03, 0x000f0d03, 0x000e0d04, 0x000e0d04, 0x000c0e04, 0x00080f05, 0x00080f05, 0x00080d04, 0x00080d04, 0x00090c04, 0x00090c04, 0x000d1008, 0x0013160d, 0x00171c15, 0x00171c15, 0x00181d16, 0x00181d16, 0x00192018, 0x00192018, 0x00192018, 0x00192018, 0x001a2019, 0x001b201a, 0x001b201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x00393b0c, 0x003b3c0d, 0x003c3e0c, 0x0040400d, 0x0041420d, 0x0043440e, 0x0044450d, 0x0045470e, 0x0047480e, 0x0048490f, 0x00494a10, 0x00494a0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d10, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004c4d10, 0x004c4d0f, 0x004c4d0f, 0x004b4c10, 0x0048490f, 0x0048490f, 0x0047480e, 0x0045470e, 0x0044450e, 0x0041420e, 0x0040400d, 0x003e400c, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0026280b, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180b, 0x0014180e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00191b15, 0x001a1b15, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181c15, 0x00141710, 0x000d1008, 0x000d1008, 0x000d1007, 0x000c1005, 0x000c0e04, 0x000d1004, 0x000d0f05, 0x00101007, 0x0014120a, 0x0019130c, 0x0018110a, 0x00120e04, 0x00121007, 0x00141308, 0x0017140b, 0x001c180c, 0x00201c0e, 0x00261c0c, 0x00281d0c, 0x002c1f0c, 0x0030200c, 0x0032200c, 0x0036200d, 0x0038200c, 0x0039220c, 0x003c240c, 0x003c250b, 0x003d260b, 0x003c260b, 0x003c260b, 0x003c280b, 0x00402c0c, 0x00442e0e, 0x00442f0c, 0x0048310c, 0x0048330b, 0x004b340a, 0x0050380d, 0x0050380e, 0x00543810, 0x00543a0f, 0x00553b0e, 0x0059400f, 0x005b410f, 0x005d430b, 0x00604308, 0x005d4002, 0x00654404, 0x00704e0a, 0x008d6816, 0x00be9b32, 0x00caad27, 0x00cbb416, 0x00cab80c, 0x00ccb80c, 0x00cbb113, 0x00bc980c, 0x00a67603, 0x008f5b00, 0x00815003, 0x00784904, 0x00704402, 0x006a4202, 0x00684002, 0x00673e04, 0x00683f07, 0x00684008, 0x00684107, 0x006f4709, 0x00744c0b, 0x00794f08, 0x00855708, 0x009e710c, 0x00c3a01f, 0x00cbb414, 0x00c8b908, 0x00c8bc04, 0x00ccb907, 0x00cbb414, 0x00ab8304, 0x00926000, 0x00a06e0a, 0x00c49c1f, 0x00ccb219, 0x00cab40c, 0x00cab707, 0x00cbb704, 0x00c9b808, 0x00c9b808, 0x00ccb80a, 0x00ccb80a, 0x00ccb80c, 0x00ccb80c, 0x00ccb80c, 0x00ccb80c, 0x00ccb80c, 0x00ccb80c, 0x00ccb80a, 0x00ccb80a, 0x00ccb80a, 0x00ccb80a, 0x00ccb80a, 0x00cbb80a, 0x00ccb809, 0x00ccb808, 0x00ccb90b, 0x00ccb809, 0x00cbb408, 0x00cbb40b, 0x00ccb611, 0x00ccb312, 0x00ccb016, 0x00caac20, 0x00a98312, 0x00875f08, 0x00785512, 0x00513404, 0x003c2704, 0x00342307, 0x00301c05, 0x002c1906, 0x00271708, 0x00231407, 0x00201407, 0x001d1104, 0x001a1305, 0x00181307, 0x00161406, 0x00151308, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00181309, 0x00181309, 0x00161409, 0x00161409, 0x00161409, 0x00161409, 0x00161308, 0x00171205, 0x00181105, 0x00191105, 0x00191107, 0x00191208, 0x00191208, 0x001a1308, 0x00151106, 0x00141106, 0x00161307, 0x00161307, 0x00161307, 0x00161307, 0x00161307, 0x00171308, 0x00171308, 0x00171408, 0x00171408, 0x00171408, 0x00171408, 0x00161208, 0x00161208, 0x00161208, 0x00171309, 0x00171208, 0x00181108, 0x00181309, 0x00181309, 0x00171309, 0x00171309, 0x00181309, 0x001b130b, 0x001c140a, 0x00201408, 0x00211406, 0x00261607, 0x002a1a09, 0x002e1c0c, 0x00321d0a, 0x003a2008, 0x0060421c, 0x00724c11, 0x008d5f0e, 0x00ba8a21, 0x00c49a18, 0x00c8a313, 0x00caa711, 0x00ccaa10, 0x00cbab0c, 0x00cbac0c, 0x00ccb00e, 0x00ccb00e, 0x00ccb10d, 0x00cbb10c, 0x00c8b208, 0x00cab40b, 0x00cbb60a, 0x00cbb509, 0x00cbb509, 0x00ccb40a, 0x00ccb40a, 0x00cbb409, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00ccb508, 0x00cbb408, 0x00cbb408, 0x00ccb307, 0x00ccb308, 0x00ccb210, 0x00c9a410, 0x00ad7a02, 0x00a06402, 0x00b47c18, 0x00cba727, 0x00ccb418, 0x00cbb90d, 0x00cbbc0c, 0x00ccb80c, 0x00ccb310, 0x00ba9507, 0x009d6e00, 0x008c5b01, 0x00835107, 0x007f5008, 0x007a5006, 0x007a500c, 0x00794f0b, 0x00794f0b, 0x007b500d, 0x007c510c, 0x0080540a, 0x00875809, 0x008f600b, 0x009f6e0e, 0x00b98f19, 0x00caa81c, 0x00ccb61c, 0x00cab70e, 0x00ccb60b, 0x00ccb015, 0x00bc9612, 0x008b6200, 0x00704900, 0x00603c00, 0x00563506, 0x004f3005, 0x004c3007, 0x00482e08, 0x00452c08, 0x00402705, 0x00402506, 0x003e2508, 0x003c2509, 0x003a2409, 0x00362007, 0x00352007, 0x00342008, 0x00331f07, 0x00331e0a, 0x00341d0a, 0x00341c0b, 0x00341c0c, 0x00311a0a, 0x002f1b0a, 0x002c1c0c, 0x002b1c0c, 0x00281c0c, 0x00211809, 0x001d1508, 0x001b1408, 0x00161305, 0x00131004, 0x00100e02, 0x000c0e00, 0x00080e00, 0x00090f02, 0x000a1002, 0x000b0e02, 0x000d0e02, 0x00121004, 0x00181508, 0x0017150b, 0x00121006, 0x00100d02, 0x00100d01, 0x000f0e04, 0x000f0f05, 0x000c0f05, 0x00090f06, 0x00090f06, 0x00090e05, 0x00090e05, 0x000b0e05, 0x000b0e05, 0x000c1007, 0x0010130a, 0x00141810, 0x00191e17, 0x00171c15, 0x00171c17, 0x00182018, 0x00182018, 0x00192018, 0x00192018, 0x001b201a, 0x001c201b, 0x001c201b, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x0014180b, 0x00191c09, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x002d2f0a, 0x0030310c, 0x0032330c, 0x0036370c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x003e400c, 0x0040400d, 0x0041420d, 0x0043440e, 0x0044450e, 0x0045470e, 0x0045470e, 0x0047480e, 0x0048490f, 0x0048490f, 0x00494a0f, 0x00494a0f, 0x004b4c10, 0x00494a0f, 0x00494a0f, 0x004b4c10, 0x00494a0f, 0x00494a0f, 0x0048490f, 0x0047480e, 0x0047480e, 0x0045470e, 0x0044450e, 0x0043440e, 0x0041420e, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x00393b0d, 0x0038380c, 0x0036370c, 0x0032330c, 0x0030310c, 0x0030310b, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x001a1b15, 0x001a1b15, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x0013160f, 0x000c1008, 0x000d1008, 0x000d1007, 0x000c1005, 0x000d0f05, 0x000d1004, 0x000e0f04, 0x00141308, 0x0018130a, 0x001b1309, 0x00191007, 0x00180f04, 0x001c1207, 0x001f150a, 0x0022180d, 0x00241a0c, 0x00271d0c, 0x002c200d, 0x002e200b, 0x0030220a, 0x0033240a, 0x0034230a, 0x0038240c, 0x0039240b, 0x003c2509, 0x0040290c, 0x00422c0c, 0x00442d0d, 0x00442f0d, 0x00442f0c, 0x0046300a, 0x0049330c, 0x004d360f, 0x004e360e, 0x0051380d, 0x0052390a, 0x00543a0a, 0x0059400c, 0x005c400d, 0x005f420f, 0x00654610, 0x006b4b10, 0x006e4d0f, 0x0070500f, 0x0076540f, 0x007c5811, 0x00765006, 0x00714900, 0x007e5505, 0x00ac8629, 0x00cbaa34, 0x00ccb51e, 0x00caba09, 0x00c8bb04, 0x00ccb70b, 0x00c7a512, 0x00a67802, 0x008f5900, 0x00804c00, 0x00754804, 0x006a4602, 0x00664204, 0x00644008, 0x00643f08, 0x00643e07, 0x00653e08, 0x00653e08, 0x00664009, 0x006c460c, 0x00714b0d, 0x00784e0c, 0x00845510, 0x009d6f13, 0x00c39c22, 0x00cbb419, 0x00c8b909, 0x00c8bb05, 0x00ccb80c, 0x00cbb017, 0x00aa7d04, 0x00945e00, 0x00a87410, 0x00caa022, 0x00ccb118, 0x00cab40d, 0x00cab50c, 0x00cbb608, 0x00c9b80a, 0x00c9b80a, 0x00cbb80b, 0x00cbb909, 0x00cbb909, 0x00cbb909, 0x00cbb80a, 0x00cbb80b, 0x00cbb80b, 0x00cbb90a, 0x00ccb80a, 0x00ccb80b, 0x00ccb80c, 0x00ccb70d, 0x00ccb70d, 0x00ccb60c, 0x00cbb60a, 0x00cab50c, 0x00ccb50d, 0x00ccb20f, 0x00cbae10, 0x00c9aa12, 0x00c5a413, 0x00c09c12, 0x00b4900f, 0x009e7a09, 0x008c6004, 0x00825810, 0x006d4910, 0x004c2f04, 0x003b2604, 0x00332106, 0x002e1c04, 0x00281704, 0x00241406, 0x00231407, 0x001f1205, 0x001d1104, 0x001a1305, 0x00181306, 0x00151306, 0x00151308, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00181309, 0x00181309, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x00181407, 0x001a1405, 0x001a1305, 0x001a1204, 0x001b1206, 0x001a1206, 0x00191307, 0x001b1407, 0x00181105, 0x00161104, 0x00181306, 0x00181205, 0x00181205, 0x00171406, 0x00171406, 0x00171406, 0x00171406, 0x00171408, 0x00171408, 0x00171408, 0x00171408, 0x00161308, 0x00161208, 0x00171309, 0x00171309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00171309, 0x00171309, 0x00181309, 0x001b130b, 0x001c140a, 0x001f1308, 0x00211406, 0x00251507, 0x00291909, 0x002d1c0d, 0x00301c0c, 0x00351e08, 0x00513613, 0x006a4715, 0x007a4e0e, 0x00905e09, 0x00a06c04, 0x00a87403, 0x00ac7c08, 0x00b5860c, 0x00bb8d0d, 0x00c0940e, 0x00c49a10, 0x00c89f14, 0x00c9a115, 0x00cca717, 0x00caac12, 0x00ccb013, 0x00cbb012, 0x00cbb010, 0x00cbb010, 0x00ccb110, 0x00cab110, 0x00cbb30e, 0x00cbb50b, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00ccb508, 0x00cbb408, 0x00cbb408, 0x00ccb307, 0x00ccb307, 0x00ccb10c, 0x00c9a50c, 0x00ad7c00, 0x00a16600, 0x00b47e13, 0x00cca821, 0x00ccb614, 0x00cab80e, 0x00cbbb0e, 0x00ccb80c, 0x00ccad0c, 0x00ad8000, 0x00976300, 0x00885503, 0x007f5009, 0x007b5008, 0x00784f05, 0x007a4e0c, 0x007a4d0c, 0x007a4d0c, 0x007c5010, 0x007c5010, 0x007f5111, 0x00825210, 0x0085540f, 0x008d5b09, 0x009e6d09, 0x00c29a1b, 0x00ccb119, 0x00c9b709, 0x00cab806, 0x00ccb40f, 0x00c8a812, 0x009e7803, 0x007e5200, 0x006b4202, 0x00623d0a, 0x005a3809, 0x00533408, 0x00503208, 0x004c3008, 0x004a2e09, 0x00492c09, 0x00482d0b, 0x00452b0a, 0x0042280a, 0x0040270c, 0x003f270d, 0x003c250b, 0x00382108, 0x00382008, 0x00382008, 0x00381f09, 0x00371d09, 0x00361d09, 0x00311c08, 0x002e1c08, 0x002d1c0a, 0x002c1d0b, 0x002a1c0b, 0x00271c0a, 0x00251a0a, 0x00211808, 0x0021150b, 0x001d1409, 0x00160f03, 0x00100d01, 0x000e1003, 0x000c0f03, 0x000c0e04, 0x000c0f03, 0x000a0d00, 0x00131408, 0x0018150c, 0x00151208, 0x00130f04, 0x00131004, 0x00100f06, 0x000f0f05, 0x000c0f05, 0x000a0f06, 0x000a0f06, 0x00090e05, 0x00090e05, 0x000b0e05, 0x000b0e05, 0x000c1007, 0x000e1109, 0x0010160c, 0x00171b14, 0x00161b14, 0x00161b15, 0x00181f17, 0x00181f17, 0x00192018, 0x00192018, 0x001b201a, 0x001c201b, 0x001c201b, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0b, 0x00191c09, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0b, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x00393b0c, 0x00393b0d, 0x003b3c0d, 0x003c3e0c, 0x003e400c, 0x0041420d, 0x0041420e, 0x0043440e, 0x0044450e, 0x0044450e, 0x0044450d, 0x0045470e, 0x0047480e, 0x0047480e, 0x0045470e, 0x0045470e, 0x0047480e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0044450e, 0x0043440e, 0x0043440e, 0x0041420d, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0b, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c16, 0x00181c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181b14, 0x0012150f, 0x000d1009, 0x000d1008, 0x000c1007, 0x000c1005, 0x000e1005, 0x000f1004, 0x00101105, 0x0017140a, 0x0018140b, 0x001b1308, 0x001b1106, 0x00231508, 0x00251508, 0x00281809, 0x002b1c0b, 0x002c1e0c, 0x002f200c, 0x0033220c, 0x0034230a, 0x0035250a, 0x0037280b, 0x00382909, 0x003d2c0c, 0x003e2c0c, 0x00402c0c, 0x00442e0b, 0x0048300c, 0x004a300a, 0x004c320b, 0x004f340c, 0x004f3409, 0x0053370b, 0x00583c0f, 0x00583b0c, 0x005c400c, 0x005d440b, 0x0063450b, 0x006b490d, 0x00745011, 0x007a5412, 0x00815910, 0x008c6411, 0x00957016, 0x00a17e20, 0x00ac8a26, 0x00b5922b, 0x00966d0c, 0x007c4f00, 0x008b5f09, 0x00bc952e, 0x00cbaf28, 0x00ccb715, 0x00cab909, 0x00cbbb04, 0x00ccb60c, 0x00b79406, 0x00946600, 0x00834f00, 0x00764800, 0x006c4502, 0x00674502, 0x00644307, 0x0064400b, 0x00643f07, 0x00623d03, 0x00633e03, 0x00654006, 0x00684209, 0x006c440c, 0x00744b10, 0x0079500c, 0x0087590e, 0x00a77a1a, 0x00c9a428, 0x00ccb41a, 0x00c9b80d, 0x00c8b909, 0x00ccb70e, 0x00cba717, 0x00a47203, 0x00945f00, 0x00b4821b, 0x00cca523, 0x00ccb115, 0x00c9b40c, 0x00c8b608, 0x00c8b705, 0x00c8b70b, 0x00c9b80c, 0x00cbb80b, 0x00ccb90c, 0x00cbb809, 0x00cbb809, 0x00ccb809, 0x00ccb808, 0x00ccb806, 0x00ccb806, 0x00cbb809, 0x00cbb70c, 0x00ccb60d, 0x00ccb40d, 0x00ccb310, 0x00ccb010, 0x00ccae10, 0x00ccab11, 0x00cca817, 0x00c69f15, 0x00b9900f, 0x00ab8007, 0x00a07403, 0x00936801, 0x00855b00, 0x00775000, 0x006c4501, 0x0067430c, 0x00523305, 0x003f2500, 0x00362201, 0x00312004, 0x002c1c02, 0x00251804, 0x00241707, 0x00201406, 0x001d1307, 0x001b1205, 0x00191107, 0x00181207, 0x00171307, 0x00171308, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x0018140a, 0x0018140a, 0x00181309, 0x00181308, 0x001a1308, 0x001a1407, 0x001a1407, 0x001b1307, 0x001a1407, 0x001b1407, 0x001b1406, 0x001a1305, 0x001a1306, 0x001b1307, 0x001a1407, 0x001a1306, 0x00181004, 0x00161105, 0x00171307, 0x00171307, 0x00181307, 0x00181307, 0x00191207, 0x00191207, 0x00181307, 0x00181306, 0x00181307, 0x00181307, 0x00181307, 0x00181306, 0x00181208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191307, 0x001c1308, 0x001c1408, 0x001f1408, 0x00211407, 0x00241406, 0x00281809, 0x002c1c0d, 0x002e1c0c, 0x00321d08, 0x00392106, 0x0052320c, 0x0068400e, 0x0078490c, 0x00814f07, 0x00895406, 0x008c5607, 0x008f5904, 0x00925d00, 0x00986401, 0x009f6b01, 0x00a67004, 0x00ae7809, 0x00b47f0c, 0x00b8880b, 0x00ba8c0c, 0x00c39814, 0x00c89d17, 0x00cba016, 0x00cca415, 0x00cba612, 0x00ccab14, 0x00ccae0f, 0x00ccb00d, 0x00ccb10b, 0x00cab20a, 0x00c9b70b, 0x00c8b609, 0x00c8b409, 0x00cbb40b, 0x00c8b307, 0x00c8b406, 0x00cab406, 0x00ccb307, 0x00ccb208, 0x00ccb20c, 0x00c8a50c, 0x00af7f00, 0x00a16700, 0x00b78015, 0x00cca820, 0x00ccb513, 0x00cab80a, 0x00cabb0c, 0x00ccb80c, 0x00c9a80d, 0x00ad7c01, 0x00955d01, 0x00865405, 0x007a5008, 0x00765007, 0x00744e04, 0x00774c0b, 0x00794c0c, 0x007a4d0c, 0x007c500f, 0x007c500d, 0x007d5110, 0x00805110, 0x0080510f, 0x0084560c, 0x0093600c, 0x00ac7f11, 0x00c9a91b, 0x00c8b60b, 0x00c8b906, 0x00cbb60c, 0x00ccb114, 0x00b38c0c, 0x00885b00, 0x00784a06, 0x0073470e, 0x00684006, 0x00633e05, 0x005e3b09, 0x0057360a, 0x0055340c, 0x00513008, 0x004f2e08, 0x004d2e0b, 0x004a2c0c, 0x00492a0e, 0x00462a0e, 0x0042290c, 0x003f280b, 0x003d2608, 0x003d2407, 0x003c240a, 0x003a220a, 0x00382108, 0x00362108, 0x00332008, 0x002f1d07, 0x002e1c08, 0x002d1d08, 0x002d1c09, 0x002c1c0a, 0x002b1b09, 0x002b1a0c, 0x002a190c, 0x0024150a, 0x001c1005, 0x00151004, 0x00111005, 0x000f1106, 0x00091003, 0x00080e01, 0x00111407, 0x0018160c, 0x001a140a, 0x00181108, 0x00151006, 0x00121004, 0x00100f06, 0x000e1007, 0x000c1007, 0x000c1006, 0x000b0f06, 0x000a0f06, 0x000a0f04, 0x000c0f04, 0x000c1006, 0x000d1008, 0x0010150c, 0x00151a12, 0x00161b14, 0x00161b15, 0x00181d18, 0x00181e18, 0x00181f18, 0x00192019, 0x001b201a, 0x001b211a, 0x001b2019, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0b, 0x00191c09, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0024250b, 0x0026280b, 0x00292b0a, 0x002c2d0a, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x003c3e0d, 0x003c3e0c, 0x0040400d, 0x0040400d, 0x0040400d, 0x0041420e, 0x0041420e, 0x0043440e, 0x0043440e, 0x0044450e, 0x0044450e, 0x0043440e, 0x0043440e, 0x0041420e, 0x0041420d, 0x0040400d, 0x0040400d, 0x003e400c, 0x003c3e0c, 0x003c3e0d, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x002c2d0b, 0x0026280b, 0x0026280c, 0x0024250b, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x00191c16, 0x00171a14, 0x0011140d, 0x000d100a, 0x000c1008, 0x000c1007, 0x000d1008, 0x000f1005, 0x00101005, 0x00151408, 0x0018150a, 0x00181409, 0x001a1307, 0x00211609, 0x0029190b, 0x002c190a, 0x002d1c09, 0x00301f09, 0x0032220b, 0x0035240e, 0x003a270f, 0x003c280d, 0x003d2c0c, 0x003f2d0c, 0x0040300a, 0x0048330c, 0x0048340f, 0x00483410, 0x004c3410, 0x0050380f, 0x0050380b, 0x00533a0b, 0x00583d0c, 0x005c3d0b, 0x0061400d, 0x0065400a, 0x006a4409, 0x00704b0a, 0x0077530c, 0x00805910, 0x008c6416, 0x00987019, 0x00a77c20, 0x00b48b22, 0x00bf9824, 0x00c8a729, 0x00caad26, 0x00ccb529, 0x00cbb128, 0x00ae8810, 0x008b5f00, 0x0091670c, 0x00c29c29, 0x00caaf1c, 0x00ccb70f, 0x00ccb80d, 0x00ccb90a, 0x00ccb510, 0x00ba980d, 0x00946a00, 0x00815300, 0x00784b04, 0x00704708, 0x006c4609, 0x0068450d, 0x00674410, 0x0065420c, 0x00634008, 0x00624007, 0x0066450c, 0x0069470f, 0x006d4810, 0x00784f15, 0x007f540f, 0x00906712, 0x00b99224, 0x00ccad24, 0x00ccb711, 0x00cab909, 0x00ccb90c, 0x00ccb20d, 0x00bf920f, 0x00986400, 0x009c6806, 0x00c29424, 0x00cca920, 0x00ccb012, 0x00ccb10c, 0x00cbb404, 0x00c9b604, 0x00cab60b, 0x00cbb60c, 0x00ccb50c, 0x00ccb60c, 0x00cbb40c, 0x00cbb40c, 0x00cab40c, 0x00cbb40a, 0x00ccb509, 0x00ccb509, 0x00ccb30e, 0x00caae0e, 0x00ccac12, 0x00c8a40f, 0x00c49f10, 0x00c0980e, 0x00ba900b, 0x00b18407, 0x00a87804, 0x00986801, 0x008d5c00, 0x00825300, 0x007d5000, 0x00744901, 0x00704404, 0x00603900, 0x00533100, 0x004c2f03, 0x003f2700, 0x00382200, 0x00342103, 0x002e1f03, 0x002a1c02, 0x00241804, 0x00221807, 0x001e1508, 0x001c1407, 0x001a1107, 0x00191107, 0x00181107, 0x00171207, 0x00171308, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x0019140b, 0x0019140b, 0x00181309, 0x00181308, 0x001b1308, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001a1407, 0x001a1407, 0x001b1407, 0x001b1407, 0x00191306, 0x00181004, 0x00151106, 0x00161307, 0x00171408, 0x00181308, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00181306, 0x00181404, 0x00181404, 0x00181404, 0x00191305, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001b1206, 0x001b1206, 0x001c1305, 0x001c1407, 0x001f1408, 0x00221507, 0x00241406, 0x00281808, 0x002c1c0c, 0x002d1c0a, 0x00301b08, 0x00321c07, 0x00371c00, 0x00442402, 0x00532e06, 0x005d3405, 0x00683906, 0x006e3f06, 0x00724305, 0x00774804, 0x007d4d05, 0x00855206, 0x008c5506, 0x00925803, 0x00975d02, 0x009a6000, 0x009e6401, 0x00a46b04, 0x00a86f04, 0x00ad7405, 0x00b27904, 0x00b88508, 0x00be8e0c, 0x00c4940d, 0x00c89d11, 0x00cca515, 0x00cca814, 0x00cbab10, 0x00c8ad0c, 0x00caaf0e, 0x00ccb10f, 0x00ccb30c, 0x00ccb40c, 0x00ccb40a, 0x00cbb308, 0x00cbb309, 0x00ccb20f, 0x00c8a50e, 0x00b28204, 0x009f6500, 0x00b27c12, 0x00cba623, 0x00ccb414, 0x00c9b808, 0x00c9ba0a, 0x00ccb70f, 0x00caaa0f, 0x00ae8000, 0x00945f00, 0x00875406, 0x007c5108, 0x00755109, 0x00744f07, 0x00784e0b, 0x00784e0b, 0x00784f0c, 0x0079500c, 0x007b500a, 0x007c500b, 0x007c500b, 0x007d510c, 0x007d5409, 0x0089590c, 0x009f700e, 0x00c4a01c, 0x00c8b410, 0x00c8b809, 0x00cab60d, 0x00ccb312, 0x00c09b13, 0x00936400, 0x00804f04, 0x0080500e, 0x007c4d08, 0x00764804, 0x00724608, 0x006e430d, 0x00684010, 0x00633c0c, 0x005d3709, 0x0058330a, 0x0054300c, 0x0051300c, 0x004c2f0a, 0x00482e08, 0x00462e09, 0x00462e0a, 0x00452b09, 0x0043280a, 0x00402709, 0x003f2508, 0x003d260a, 0x003c250b, 0x0039230b, 0x00362008, 0x00352008, 0x00342009, 0x00321d0a, 0x00311b08, 0x00301c08, 0x00301c0a, 0x002c1909, 0x0028180a, 0x00201609, 0x00181306, 0x00141407, 0x000c1104, 0x000c1104, 0x00111206, 0x0019150b, 0x001e150c, 0x001c1409, 0x00161006, 0x00131005, 0x00100f08, 0x000f0f08, 0x000c1007, 0x000c1007, 0x000c0f06, 0x000a0f06, 0x000a1004, 0x000c0f04, 0x000c1005, 0x000c1006, 0x0010140c, 0x00141910, 0x00161b15, 0x00161b15, 0x00181e18, 0x00181e18, 0x00181e18, 0x0019201a, 0x001a2019, 0x001b2119, 0x001a2018, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x00202309, 0x0024250c, 0x0026280b, 0x00292b0b, 0x002c2d0b, 0x002c2d0a, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x0038380c, 0x0038380c, 0x003b3c0d, 0x003b3c0d, 0x003b3c0d, 0x003c3e0d, 0x003c3e0c, 0x003e400c, 0x003e400c, 0x0040400c, 0x003e400c, 0x003e400c, 0x0040400c, 0x003e400c, 0x003e400c, 0x003c3e0c, 0x003c3e0d, 0x003b3c0d, 0x003b3c0d, 0x00393b0c, 0x0038380c, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002d2f0b, 0x002c2d0a, 0x00292b0b, 0x0026280b, 0x0024250c, 0x0020230a, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180c, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x00161913, 0x0010140d, 0x000d110a, 0x000c1008, 0x000d1009, 0x000d1008, 0x000f1006, 0x00141307, 0x00181708, 0x00191509, 0x001a1509, 0x001e1507, 0x00261b0b, 0x002c1d0a, 0x002f1e0b, 0x00302009, 0x0033230b, 0x0037270c, 0x003c290d, 0x00412c10, 0x00452e0f, 0x0046310c, 0x0048340b, 0x004c340a, 0x0050380c, 0x0052390e, 0x0051380f, 0x00553b10, 0x005c3f10, 0x005d410e, 0x005e440d, 0x0064460c, 0x006c480b, 0x00744c0c, 0x007b500b, 0x0086590f, 0x00946512, 0x00a37319, 0x00ac821f, 0x00b89325, 0x00c29e27, 0x00c8a628, 0x00ccad25, 0x00ccb11e, 0x00ccb518, 0x00ccb812, 0x00ccbc12, 0x00cbb91c, 0x00b4950c, 0x008f6500, 0x008c6201, 0x00c09c24, 0x00caae18, 0x00ccb60c, 0x00ccb80d, 0x00ccb80d, 0x00ccb511, 0x00c8a918, 0x00a78209, 0x008e6200, 0x00845606, 0x00794f08, 0x00744b09, 0x00714a0d, 0x006f4812, 0x006c440e, 0x0069430c, 0x0068440c, 0x006b480f, 0x006d490e, 0x00744c10, 0x007c5312, 0x008d6313, 0x00ab8523, 0x00c7a828, 0x00ccb518, 0x00ccb90b, 0x00cab806, 0x00cbb30c, 0x00c8a30d, 0x00ab7b07, 0x00905d00, 0x00ac7c13, 0x00c89e24, 0x00cba81b, 0x00ccac12, 0x00ccb00f, 0x00ccb20a, 0x00cab309, 0x00cbb40c, 0x00ccb40c, 0x00cbb40c, 0x00cbb40c, 0x00cbb20e, 0x00ccb010, 0x00ccad11, 0x00c9a90f, 0x00c7a510, 0x00c4a00e, 0x00c09c10, 0x00b8900b, 0x00af8409, 0x00a67a05, 0x009c6d01, 0x00936400, 0x008d5c00, 0x00885901, 0x00845501, 0x007a4c00, 0x00704400, 0x00694004, 0x00643d05, 0x005b3704, 0x00543204, 0x004e3001, 0x00472a01, 0x00402703, 0x00382202, 0x00342004, 0x002f1e05, 0x002c1e08, 0x00281c06, 0x00231905, 0x00201705, 0x001d1407, 0x001b1406, 0x001a1107, 0x00191107, 0x00181208, 0x00171207, 0x00171308, 0x00181209, 0x00181209, 0x00181309, 0x00181309, 0x00181209, 0x00181209, 0x00181309, 0x00181309, 0x0019140b, 0x0019140b, 0x00181309, 0x00181308, 0x001b1308, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001a1306, 0x00181105, 0x00161207, 0x00181408, 0x00171408, 0x00181408, 0x001a1208, 0x001a1208, 0x001a1208, 0x001a1208, 0x00181306, 0x00181404, 0x00181404, 0x00181404, 0x00191305, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001b1206, 0x001b1206, 0x001c1305, 0x001c1406, 0x001f1408, 0x00231608, 0x00251508, 0x00271708, 0x002c1c0b, 0x002d1c0a, 0x00301b09, 0x00311c08, 0x00321d08, 0x00331d05, 0x00391d04, 0x00432206, 0x00492603, 0x004d2900, 0x00502d00, 0x00553101, 0x005c3704, 0x00653b05, 0x006b3d04, 0x00744406, 0x007c4905, 0x00834f04, 0x00875207, 0x008a5607, 0x008c5606, 0x008f5704, 0x00925a04, 0x00955d02, 0x009b6301, 0x009f6700, 0x00a66e02, 0x00ab7306, 0x00b27b0b, 0x00b9840c, 0x00be8d0a, 0x00c1940d, 0x00c59910, 0x00c9a111, 0x00caa50e, 0x00ccaa0f, 0x00ccad0e, 0x00ccb111, 0x00ccab14, 0x00caa316, 0x00b6850c, 0x009c6400, 0x00a97210, 0x00c8a124, 0x00cbb318, 0x00c9b70c, 0x00c9b80c, 0x00ccb70f, 0x00cbaf10, 0x00af8802, 0x00946300, 0x00885401, 0x007e5005, 0x00795009, 0x00755009, 0x00784e0a, 0x00784e0a, 0x00784f0b, 0x0079500b, 0x007b4f09, 0x007b500a, 0x007b500a, 0x007c510b, 0x007c5208, 0x0087560a, 0x00976709, 0x00bc9619, 0x00c9b114, 0x00c8b70c, 0x00cab70c, 0x00ccb411, 0x00c6a316, 0x009e7001, 0x008b5804, 0x009a6719, 0x00a16f1b, 0x0096650f, 0x00895806, 0x00865308, 0x0081510c, 0x007b4b0b, 0x00744609, 0x006e410a, 0x00683c08, 0x005f3807, 0x00593606, 0x00543407, 0x00503408, 0x00503409, 0x004c3107, 0x004c2f08, 0x004a2c08, 0x00452907, 0x00442807, 0x0044270a, 0x00412609, 0x003e2408, 0x003c2408, 0x003b240a, 0x003b230b, 0x00382008, 0x00362008, 0x00341f07, 0x00311d08, 0x002f1b09, 0x002c1a0c, 0x00261a0c, 0x001d1608, 0x00141205, 0x00141105, 0x00141004, 0x00191208, 0x0020160b, 0x001e150b, 0x00181206, 0x00151006, 0x00120f08, 0x000f0f08, 0x000e0e07, 0x000c0f07, 0x000c1006, 0x000a1006, 0x000a1004, 0x000c0f04, 0x000c1005, 0x000c0f04, 0x000d1309, 0x0012170f, 0x00151a14, 0x00161a16, 0x00171d18, 0x00181e18, 0x00181e18, 0x00181f19, 0x001a2019, 0x001b2119, 0x001a2018, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x0024250b, 0x0024250b, 0x0026280b, 0x00292b0b, 0x002c2d0a, 0x002d2f0a, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0032330c, 0x0036370c, 0x0036370c, 0x0036370b, 0x0038380c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x00393b0d, 0x00393b0d, 0x00393b0d, 0x00393b0d, 0x00393b0d, 0x003b3c0d, 0x00393b0d, 0x00393b0c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0034350c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0030310c, 0x002d2f0a, 0x002c2d0a, 0x002c2d0b, 0x0026280b, 0x0026280c, 0x0024250b, 0x00202309, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x001b1d17, 0x001a1c16, 0x00131610, 0x000d120b, 0x000d120b, 0x000c100a, 0x000d120b, 0x000e1108, 0x00121207, 0x00151407, 0x001a1809, 0x001b1608, 0x001d1507, 0x00241909, 0x002b1e0c, 0x0030200c, 0x0034240d, 0x0035250c, 0x0038280c, 0x003f2c0e, 0x00432f0f, 0x0048310f, 0x004c340f, 0x0050370e, 0x00533b0c, 0x00573d0c, 0x005c400c, 0x0061430f, 0x00654310, 0x006b4710, 0x00704b11, 0x00754f0f, 0x0078520c, 0x0080580c, 0x008f6611, 0x009a7015, 0x00a77c20, 0x00b68b28, 0x00c09826, 0x00c8a126, 0x00caa920, 0x00caae1b, 0x00cab219, 0x00cbb618, 0x00cbb817, 0x00ccb812, 0x00cbbb10, 0x00c9bd0d, 0x00cabd0e, 0x00cab814, 0x00b99a0c, 0x00956800, 0x00906001, 0x00b08816, 0x00cbae1a, 0x00cbb40c, 0x00cbb80d, 0x00cab80c, 0x00ccb80d, 0x00ccb417, 0x00c6a81b, 0x00ac880f, 0x009a7008, 0x00885f04, 0x00825704, 0x007e5208, 0x00794d09, 0x00764c09, 0x00764b0b, 0x00744b0a, 0x00754d08, 0x00785006, 0x00825708, 0x00916611, 0x00ae8724, 0x00c6a430, 0x00ccb424, 0x00c9b910, 0x00ccba0c, 0x00cbb50f, 0x00cbae1a, 0x00b6870c, 0x00945d00, 0x009b6408, 0x00bd8c24, 0x00c79921, 0x00c49914, 0x00c59b10, 0x00c8a011, 0x00cba513, 0x00cca913, 0x00ccaa14, 0x00cca912, 0x00cba811, 0x00cba711, 0x00c8a211, 0x00c49b10, 0x00bd930f, 0x00b08406, 0x00a47704, 0x009e6f04, 0x00946400, 0x008c5c00, 0x00895800, 0x00815200, 0x007c4c00, 0x007a4801, 0x00754403, 0x006f4104, 0x00694004, 0x00603c02, 0x00583801, 0x00533506, 0x00503307, 0x00492e07, 0x00432b04, 0x00402807, 0x003e2708, 0x003a2309, 0x00372008, 0x00301e08, 0x002c1e08, 0x00291c09, 0x00231908, 0x00221805, 0x00201604, 0x001c1407, 0x001a1306, 0x001a1107, 0x00191108, 0x001a1308, 0x00171207, 0x00161207, 0x00171008, 0x00181108, 0x00181309, 0x00181309, 0x00181108, 0x00181108, 0x00181309, 0x00181309, 0x0019140b, 0x0019140b, 0x00191209, 0x00191208, 0x001b1308, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1408, 0x00181206, 0x00171408, 0x0018150a, 0x00181408, 0x00181408, 0x001b1308, 0x001b1308, 0x001b1308, 0x001b1308, 0x00181306, 0x00181404, 0x00181404, 0x00181404, 0x00191305, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001c1307, 0x001c1307, 0x001c1305, 0x001c1305, 0x001f1408, 0x0023170a, 0x00251709, 0x0027170a, 0x0029190b, 0x002b1908, 0x002e1a09, 0x00301c0a, 0x002e1d09, 0x00301e0a, 0x00351e09, 0x003d210b, 0x00432408, 0x00462806, 0x00482908, 0x00482908, 0x00492c08, 0x004a2b07, 0x004d2b03, 0x00543003, 0x00593101, 0x005e3401, 0x00633804, 0x00663c04, 0x00683f04, 0x0074480d, 0x00794c0d, 0x007e4e0c, 0x0084510a, 0x008b5409, 0x008f5609, 0x00905607, 0x00955908, 0x00975c05, 0x00996002, 0x009d6604, 0x00a36c04, 0x00a87204, 0x00b07c08, 0x00b8840a, 0x00c08d0f, 0x00c59412, 0x00c79a17, 0x00c89c1d, 0x00c08c1d, 0x00a06708, 0x009a6404, 0x00b8911a, 0x00cab01c, 0x00c9b613, 0x00cbb80f, 0x00ccb80f, 0x00ccb411, 0x00bc9a0c, 0x009a6e00, 0x008e5a00, 0x00845004, 0x007e520b, 0x0079540d, 0x007a500c, 0x00784f0b, 0x0078500b, 0x0079500c, 0x007b500c, 0x007c510c, 0x007d520d, 0x0080540e, 0x007c5308, 0x0087560c, 0x0095650b, 0x00bc941e, 0x00cab11a, 0x00c9b70f, 0x00cab70c, 0x00ccb50f, 0x00c9a814, 0x00a77801, 0x00976202, 0x00b67f24, 0x00c7962f, 0x00c09222, 0x00b7881b, 0x00ab7910, 0x00a06c0a, 0x00935e07, 0x008b5705, 0x00875407, 0x00815006, 0x007a4b08, 0x00754809, 0x006f440c, 0x00623c05, 0x005c3c09, 0x00583908, 0x0055380a, 0x00523409, 0x004e3108, 0x004c3008, 0x004b2f0b, 0x00482d0c, 0x00462c0a, 0x00442b0a, 0x00432a0b, 0x0041250a, 0x00402408, 0x003e2408, 0x003b2306, 0x00382108, 0x00351f09, 0x00361c0e, 0x00311c0e, 0x0027170a, 0x00201608, 0x001e150b, 0x001e140b, 0x001c1208, 0x001f160b, 0x0020180c, 0x001c1408, 0x00181108, 0x0015110a, 0x0013100a, 0x00101008, 0x000f0e06, 0x000d0f06, 0x000b1006, 0x000a1004, 0x000c0f04, 0x000c0f04, 0x000c0f04, 0x000c1106, 0x0010140c, 0x00141914, 0x00151916, 0x00151b15, 0x00171d18, 0x00181e18, 0x00181f19, 0x001a2019, 0x001b2119, 0x00192018, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x00202309, 0x0024250b, 0x0024250b, 0x00292b0b, 0x00292b0b, 0x00292b0a, 0x002c2d0a, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0030310c, 0x0034350c, 0x0032330c, 0x0036370c, 0x0034350c, 0x0036370c, 0x0036370c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0036370c, 0x0036370c, 0x0034350c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x00292b0a, 0x00292b0a, 0x0026280b, 0x0026280c, 0x0024250c, 0x0020230a, 0x00202308, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x001b1e18, 0x00181c15, 0x0010140c, 0x000d120b, 0x000d120b, 0x000c110a, 0x000e1109, 0x00101208, 0x00141307, 0x00181407, 0x001c1809, 0x001a1405, 0x001f1606, 0x00281c09, 0x002f200b, 0x0035250c, 0x003a2a0f, 0x003e2c0e, 0x0042300e, 0x00483410, 0x004c3610, 0x00533811, 0x00583a10, 0x005f3f12, 0x00654611, 0x00694a0f, 0x006f4f0f, 0x0074500f, 0x007f520f, 0x0084570f, 0x00906214, 0x00986b15, 0x00a67a16, 0x00b08518, 0x00ba901c, 0x00c59d21, 0x00c8a527, 0x00c9aa24, 0x00ccb223, 0x00ccb418, 0x00ccb510, 0x00cbb80c, 0x00c9b90d, 0x00c8ba10, 0x00c9bb0f, 0x00cbbb0f, 0x00cabb10, 0x00c8bb10, 0x00c7ba10, 0x00c9b712, 0x00c1a010, 0x00a37402, 0x008c5800, 0x00966c06, 0x00bf9c19, 0x00ccb316, 0x00cbb80f, 0x00c8ba08, 0x00caba09, 0x00cbb90f, 0x00ccb514, 0x00cbae1c, 0x00c4a31f, 0x00b6911b, 0x00a67f11, 0x0099710c, 0x0092690c, 0x008c6208, 0x008a5f08, 0x008a6008, 0x0090650b, 0x00996e10, 0x00aa7e19, 0x00be9428, 0x00c6a42b, 0x00c9af24, 0x00cab818, 0x00c8bc0d, 0x00ccb90f, 0x00ccb218, 0x00b79014, 0x00996203, 0x008a4d00, 0x00955809, 0x00ab711b, 0x00a46c0d, 0x00a06704, 0x00a16803, 0x00a46d04, 0x00ab7608, 0x00b17d0c, 0x00b37e0c, 0x00b27d0b, 0x00ad7805, 0x00ad7807, 0x00a36e02, 0x00986400, 0x00905c00, 0x00895700, 0x00825100, 0x007c4c00, 0x00784901, 0x00734701, 0x006e4300, 0x00673d00, 0x00643b00, 0x00613802, 0x00603605, 0x005a3505, 0x00553404, 0x00513406, 0x004c3407, 0x00493307, 0x00473108, 0x00422e04, 0x003d2a04, 0x003b270c, 0x003b250d, 0x0036200a, 0x00331d0a, 0x002e1c0a, 0x00291a08, 0x00261a09, 0x00201807, 0x00201607, 0x001f1406, 0x001c1306, 0x001a1306, 0x00191107, 0x001a1208, 0x00191308, 0x00171307, 0x00161207, 0x00161008, 0x00171008, 0x00181208, 0x00181209, 0x00181208, 0x00181108, 0x00181209, 0x00181209, 0x0019140a, 0x0019140a, 0x00191208, 0x00191208, 0x001b1308, 0x001b1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001b1407, 0x001b1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001a1306, 0x00181207, 0x001a1409, 0x001a1408, 0x001a1408, 0x001c1308, 0x001c1208, 0x001c1208, 0x001c1308, 0x001a1304, 0x001a1304, 0x001a1304, 0x001a1304, 0x001a1305, 0x001a1207, 0x001a1307, 0x001a1307, 0x001a1307, 0x001a1306, 0x001a1306, 0x001a1306, 0x001b1206, 0x001c1308, 0x001c1308, 0x001c1306, 0x001d1306, 0x00201408, 0x0023160a, 0x00241608, 0x00251608, 0x00281608, 0x00281608, 0x002c1708, 0x002e1b08, 0x00301c06, 0x00301d06, 0x00341d05, 0x00381f04, 0x003d2106, 0x003f2408, 0x0043270b, 0x0044280c, 0x0044280c, 0x00452b0c, 0x00472c09, 0x004a2c07, 0x00492b03, 0x004b2b03, 0x004e2e06, 0x004f2f05, 0x004f3105, 0x004f3004, 0x00513003, 0x00583404, 0x005d3803, 0x00663c03, 0x006b3d04, 0x00744308, 0x0079470b, 0x007c4c0e, 0x007f500f, 0x00835310, 0x0085550c, 0x0089560a, 0x00905505, 0x00985b08, 0x009c5c03, 0x00a06302, 0x00a26c02, 0x00a8730a, 0x00a06a0c, 0x008e5600, 0x00915c04, 0x00a97d11, 0x00c8a71f, 0x00ccb418, 0x00ccb70f, 0x00ccb80b, 0x00ccb80c, 0x00c5aa11, 0x00a98207, 0x00966100, 0x00895402, 0x0084540b, 0x00805510, 0x007d5410, 0x007a510e, 0x0078500e, 0x0078500f, 0x007d5411, 0x007f530f, 0x0080540f, 0x0081560f, 0x007e5309, 0x0088570d, 0x0096640d, 0x00bf9421, 0x00cbb11c, 0x00c9b711, 0x00cab70c, 0x00ccb60c, 0x00ccac14, 0x00ae7d03, 0x009e6703, 0x00ba8320, 0x00ca9d26, 0x00cba61e, 0x00cca51c, 0x00caa01c, 0x00c59818, 0x00bd8c18, 0x00b07f10, 0x00a4730b, 0x00996805, 0x00925e05, 0x008c5805, 0x008a570d, 0x0081500c, 0x00754b0d, 0x006f480d, 0x0068440c, 0x00623f0c, 0x005c3a0b, 0x0058380b, 0x0054360c, 0x0050340c, 0x004d320b, 0x004c300b, 0x004c300c, 0x00482c0b, 0x00452908, 0x0044280a, 0x00422709, 0x003f2509, 0x003c2309, 0x003c210c, 0x0039200e, 0x00301a0a, 0x002a190a, 0x00281a0c, 0x0026190d, 0x0022170b, 0x001f1308, 0x0023180c, 0x0020160a, 0x001b1308, 0x0018130a, 0x0014120a, 0x00121008, 0x00101007, 0x000e1006, 0x000c1005, 0x000b1005, 0x000c0f04, 0x000c0f04, 0x000c0f03, 0x000a1004, 0x000e130a, 0x00141914, 0x00141815, 0x00141a15, 0x00161c17, 0x00181d18, 0x00181e19, 0x001a201b, 0x001a2019, 0x00192019, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x0024250b, 0x0024250c, 0x0024250b, 0x0026280b, 0x00292b0b, 0x00292b0a, 0x00292b0a, 0x002d2f0a, 0x002c2d0a, 0x0030310c, 0x0030310c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0030310c, 0x0030310c, 0x0030310c, 0x0030310c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x0026280a, 0x0026280b, 0x0026280c, 0x0024250c, 0x0020230a, 0x00202308, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c09, 0x00141809, 0x0014180b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x00191c16, 0x00191c16, 0x00191c16, 0x00171a14, 0x0010130c, 0x000f120a, 0x000f120a, 0x000e1109, 0x00101009, 0x00121107, 0x00171408, 0x001d170a, 0x00201809, 0x001c1304, 0x00281c0c, 0x002f210b, 0x0035260d, 0x003b2a0c, 0x00402e0c, 0x00443108, 0x004c350b, 0x00523a0c, 0x005c400f, 0x00644310, 0x006e4812, 0x00764d12, 0x007f5612, 0x00855d12, 0x008d6713, 0x009a7318, 0x00a8781b, 0x00b18420, 0x00ba9023, 0x00c09822, 0x00c7a21b, 0x00cba81a, 0x00ccac17, 0x00ccb018, 0x00ccb418, 0x00ccb817, 0x00ccb811, 0x00ccb80c, 0x00cab90a, 0x00cab90a, 0x00cbb90c, 0x00ccba0d, 0x00ccbb0e, 0x00cbbc0c, 0x00cbbc0c, 0x00cbbb0d, 0x00c9bc0d, 0x00c8ba0c, 0x00cbb317, 0x00b48d10, 0x00926100, 0x008a5a00, 0x009c7507, 0x00c1a11b, 0x00c9b116, 0x00cab80d, 0x00c8ba09, 0x00cabb08, 0x00cbbb07, 0x00ccb712, 0x00ccb51b, 0x00ccb31e, 0x00c9af21, 0x00c3a621, 0x00bc9f21, 0x00b8981c, 0x00b8961f, 0x00b89420, 0x00bb9621, 0x00c49e25, 0x00c9a425, 0x00ccaa24, 0x00ccb21b, 0x00ccb813, 0x00cab90b, 0x00c8ba0a, 0x00ccb410, 0x00bb9910, 0x00996a06, 0x00834b00, 0x00723e00, 0x00714000, 0x00754500, 0x00744200, 0x00713f00, 0x00743f02, 0x00754100, 0x007c4800, 0x00804b00, 0x00824c00, 0x00834c00, 0x00834c00, 0x00824b00, 0x00784400, 0x00724000, 0x00724202, 0x006c4003, 0x00663c00, 0x00633d03, 0x00603c04, 0x005a3a02, 0x00533600, 0x00513601, 0x00503404, 0x00503407, 0x00503407, 0x004c3006, 0x004b3008, 0x00472f09, 0x00422e0a, 0x00402c08, 0x003d2a06, 0x003c2905, 0x00382503, 0x00362106, 0x00342007, 0x00331d08, 0x002f1908, 0x002c1909, 0x00281908, 0x00221707, 0x00201806, 0x00201508, 0x001e1308, 0x001c1206, 0x001a1306, 0x00191207, 0x00181308, 0x00181308, 0x00151307, 0x00161207, 0x00171008, 0x00151007, 0x00151007, 0x00181108, 0x00181309, 0x00171008, 0x00181108, 0x00181108, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x001b1308, 0x001b1308, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1307, 0x00181105, 0x001c1509, 0x001c1408, 0x001c1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001c1104, 0x001c1104, 0x001c1107, 0x001b1108, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x00201408, 0x00211408, 0x00221407, 0x00241508, 0x00241409, 0x00271308, 0x00291607, 0x002d1807, 0x002f1b07, 0x002f1b05, 0x00311b03, 0x00331c01, 0x00341d04, 0x00372006, 0x003a2108, 0x003c230a, 0x0040240c, 0x00402508, 0x00402505, 0x00402504, 0x00412703, 0x00412804, 0x00422a07, 0x00442907, 0x00442908, 0x00472908, 0x004a2d0a, 0x004c2e09, 0x004e2e05, 0x00503003, 0x00533104, 0x00553004, 0x00573105, 0x00583205, 0x005d3508, 0x00613a09, 0x00643c0b, 0x006b3f0b, 0x00734005, 0x00784405, 0x00804a07, 0x00844f06, 0x00885306, 0x00885305, 0x00855004, 0x00814d02, 0x00885706, 0x009b680c, 0x00c29620, 0x00ccad1c, 0x00ccb510, 0x00ccb907, 0x00ccb907, 0x00cbb411, 0x00c09d14, 0x00a47503, 0x008f5e00, 0x00885704, 0x0084540c, 0x0080540e, 0x007c5210, 0x0079500f, 0x007a5112, 0x007d5211, 0x007f530f, 0x0080540d, 0x0083580e, 0x00835609, 0x008c5a0e, 0x009c6c11, 0x00c29a23, 0x00ccb21b, 0x00c9b611, 0x00cbb60c, 0x00ccb60b, 0x00ccac13, 0x00ae7c03, 0x009f6502, 0x00b98319, 0x00cca422, 0x00ccad14, 0x00cab010, 0x00ccb014, 0x00ccac14, 0x00cca814, 0x00c8a215, 0x00c69d19, 0x00c09418, 0x00bc8b19, 0x00b07b13, 0x00a97113, 0x009c650f, 0x00935c0d, 0x008b580d, 0x00865510, 0x00805110, 0x007c4c0f, 0x0076480f, 0x006f4410, 0x00674110, 0x00613d0e, 0x005b390a, 0x00553508, 0x00513208, 0x004c3008, 0x004c2e09, 0x004a2c0a, 0x00472a0c, 0x0044280b, 0x00422608, 0x0040240a, 0x00371e08, 0x00311c09, 0x002e1e0a, 0x002c1d0b, 0x00271a09, 0x00201404, 0x00211507, 0x0023180a, 0x001d1408, 0x001a1308, 0x00171209, 0x00131008, 0x00110f07, 0x00101006, 0x000c1005, 0x000c1007, 0x000c0f04, 0x000b0e02, 0x000b0e02, 0x000a1004, 0x000e130b, 0x00141813, 0x00141814, 0x00141815, 0x00161a17, 0x00181c19, 0x00191d1a, 0x00191f1a, 0x0019201a, 0x0019201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180b, 0x00141809, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x00202309, 0x0024250b, 0x0024250b, 0x0026280c, 0x0026280b, 0x00292b0b, 0x00292b0b, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x00292b0a, 0x00292b0b, 0x00292b0b, 0x0026280b, 0x0024250b, 0x0024250c, 0x0020230a, 0x00202308, 0x001d2008, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x00191c16, 0x00191c16, 0x00181c15, 0x00141710, 0x000f110b, 0x0010120a, 0x0010120a, 0x00101009, 0x00101008, 0x00141208, 0x001a140a, 0x0020180b, 0x00221808, 0x00241809, 0x002d200e, 0x0035260e, 0x003a2a0c, 0x00402e0c, 0x0048350c, 0x00543c0c, 0x005c3f0b, 0x00644408, 0x00714e0b, 0x007c560d, 0x00886011, 0x00986d14, 0x00a77c1b, 0x00b38821, 0x00bc9324, 0x00c49d28, 0x00c8a426, 0x00cba926, 0x00caab21, 0x00caad1c, 0x00cab011, 0x00ccb611, 0x00ccb810, 0x00ccb90f, 0x00ccba10, 0x00ccba0f, 0x00cbba0c, 0x00cab908, 0x00cab909, 0x00cab90a, 0x00cbba0b, 0x00cbba0b, 0x00cbba0b, 0x00cbbb0a, 0x00ccbb08, 0x00cbba08, 0x00cbbb06, 0x00cbbc08, 0x00ccb614, 0x00bf9e19, 0x00966a03, 0x007f4f00, 0x00835400, 0x009d7407, 0x00bc9a18, 0x00caad18, 0x00ccb416, 0x00ccb70e, 0x00cbba0a, 0x00ccbc0c, 0x00ccbc10, 0x00ccbc14, 0x00ccbc18, 0x00ccbb1b, 0x00ccb91c, 0x00cab61c, 0x00ccb41f, 0x00c9b21e, 0x00cab11d, 0x00ccb41d, 0x00ccb318, 0x00ccb414, 0x00ccb80a, 0x00ccb809, 0x00ccb60e, 0x00cab114, 0x00bc980f, 0x009c7002, 0x00805200, 0x00724100, 0x00603700, 0x005c3700, 0x005b3700, 0x005a3504, 0x005c340a, 0x005d3408, 0x005c3402, 0x005e3502, 0x00603802, 0x00633901, 0x00643a00, 0x00663b01, 0x00663c01, 0x00603800, 0x005b3500, 0x00593503, 0x00543403, 0x00533303, 0x00523404, 0x00513509, 0x004d3408, 0x00493407, 0x00483306, 0x00483207, 0x00483009, 0x0048300b, 0x00442d0a, 0x00412c0c, 0x003e2c0c, 0x003b290d, 0x003a280d, 0x0038250b, 0x0037240a, 0x00332005, 0x00321f06, 0x00321f08, 0x00301c08, 0x002c1808, 0x0029180b, 0x00251508, 0x00241508, 0x00201608, 0x00201508, 0x001e1308, 0x001c1206, 0x001a1306, 0x00191207, 0x00181308, 0x00181308, 0x00151307, 0x00161207, 0x00171008, 0x00171008, 0x00161008, 0x00181108, 0x00181209, 0x00171008, 0x00181108, 0x00181108, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x001b1308, 0x001b1308, 0x001b1407, 0x001b1407, 0x001c1307, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001b1407, 0x001e170b, 0x001d160a, 0x001e150a, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001c1104, 0x001c1104, 0x001c1108, 0x001b1108, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x00201408, 0x00211408, 0x00211507, 0x00221608, 0x00241409, 0x00261408, 0x00261504, 0x00291807, 0x002b1909, 0x002b190a, 0x002c1a08, 0x002d1b06, 0x002e1c06, 0x002f1c09, 0x00321d0b, 0x00341e0a, 0x0038200b, 0x00382108, 0x00392107, 0x003a2305, 0x003b2404, 0x003a2404, 0x003d2506, 0x00402607, 0x00422809, 0x00432809, 0x00442909, 0x00472a08, 0x00482b07, 0x00482c04, 0x00482c05, 0x00482c04, 0x004b2b05, 0x004c2c04, 0x004d2c03, 0x004d2c00, 0x004e2d00, 0x00502f00, 0x00542f01, 0x00583303, 0x005e3603, 0x00643803, 0x00653801, 0x006f4207, 0x0072460a, 0x00754a0b, 0x0080530c, 0x008d5e0f, 0x00ac7f1a, 0x00c5a422, 0x00cab218, 0x00ccb80d, 0x00ccb808, 0x00cbb40f, 0x00cbb11b, 0x00ba960f, 0x00a27703, 0x00946400, 0x008b5904, 0x00845408, 0x00805208, 0x007c5109, 0x007d510d, 0x0080520e, 0x0081530d, 0x0083540b, 0x0086580c, 0x00885908, 0x00915f0c, 0x00ab7d1a, 0x00c9a425, 0x00ccb417, 0x00cab70d, 0x00ccb60b, 0x00cbb70c, 0x00ccac13, 0x00b07b03, 0x009f6502, 0x00b9841b, 0x00cca520, 0x00cab30d, 0x00c8b708, 0x00c9b70e, 0x00ccb30e, 0x00ccb210, 0x00ccb114, 0x00ccae17, 0x00cbab18, 0x00cba117, 0x00c99e19, 0x00c8991c, 0x00c08f18, 0x00b78418, 0x00ac7814, 0x00a26e10, 0x009a640c, 0x00975f0c, 0x0091590d, 0x008c550e, 0x0084510e, 0x007d500c, 0x00774c0b, 0x006c4407, 0x00684009, 0x00613b07, 0x005c3705, 0x00583405, 0x00543108, 0x00502e0a, 0x004b2c07, 0x00472908, 0x003d2306, 0x00382108, 0x00362209, 0x0034210b, 0x002f1e09, 0x00281604, 0x00231403, 0x00241708, 0x00211708, 0x001c1408, 0x00181308, 0x00141007, 0x00110f05, 0x00101005, 0x000d0f05, 0x000c1005, 0x000c0f04, 0x000b0e02, 0x000c1001, 0x000a1004, 0x000e130b, 0x00131712, 0x00141814, 0x00141815, 0x00161a17, 0x00181c18, 0x00181d1a, 0x00191f1a, 0x0019201a, 0x0019201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x00202309, 0x0024250a, 0x0024250b, 0x0024250c, 0x0026280c, 0x0026280b, 0x0026280b, 0x00292b0b, 0x0026280a, 0x00292b0b, 0x0026280a, 0x0026280a, 0x00292b0b, 0x00292b0b, 0x0026280a, 0x0026280a, 0x00292b0b, 0x00292b0b, 0x00292b0b, 0x0026280b, 0x0026280b, 0x0024250b, 0x0024250b, 0x0024250b, 0x00202309, 0x00202309, 0x001d2008, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180e, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x00191e17, 0x00191d18, 0x00191d18, 0x001a1d18, 0x001a1d17, 0x001a1c16, 0x0013140e, 0x0010110b, 0x0012110a, 0x0012110a, 0x00121108, 0x00131008, 0x00181309, 0x001d160c, 0x0022180c, 0x00231808, 0x002c1e0e, 0x0034240f, 0x003b280f, 0x00402d0e, 0x0048340e, 0x00543d10, 0x00644510, 0x00745012, 0x00855d11, 0x00936b14, 0x00a17c18, 0x00b79124, 0x00c39e24, 0x00c9a823, 0x00ccac24, 0x00ccae20, 0x00ccb11e, 0x00ccb318, 0x00ccb516, 0x00ccb514, 0x00ccb610, 0x00ccb70c, 0x00ccb80b, 0x00ccb90c, 0x00cbba0c, 0x00ccb90c, 0x00ccb90c, 0x00ccb90c, 0x00ccb90c, 0x00cbba0c, 0x00cbba0c, 0x00cbba0c, 0x00cbba0c, 0x00cbba0b, 0x00cab908, 0x00cab908, 0x00c9b808, 0x00cab709, 0x00ccb30d, 0x00c6a814, 0x00b58d14, 0x008e6204, 0x00784a04, 0x007b4c07, 0x007f5200, 0x00946904, 0x00b48c13, 0x00c6a31c, 0x00cbaf18, 0x00ccb510, 0x00cbb90d, 0x00ccba0c, 0x00cbba0c, 0x00ccba0c, 0x00cbba0c, 0x00cbbb0c, 0x00cbba0f, 0x00ccba11, 0x00ccb911, 0x00ccb911, 0x00ccb810, 0x00ccb70d, 0x00ccb70b, 0x00ccb508, 0x00ccb10d, 0x00c8a614, 0x00b58e10, 0x009e6d05, 0x00805300, 0x00694101, 0x00583700, 0x00543305, 0x00533205, 0x00523104, 0x00503007, 0x00502f0a, 0x00522f07, 0x00523001, 0x00523004, 0x00523008, 0x00533003, 0x00533002, 0x00533003, 0x00543003, 0x00543104, 0x00533204, 0x00503205, 0x004c3004, 0x004a2e05, 0x00492e08, 0x00482e0b, 0x00462f0c, 0x00442e09, 0x00422b07, 0x00422a09, 0x00422a0a, 0x00422a0a, 0x003e2808, 0x003a2509, 0x0038250c, 0x0036260c, 0x0034240c, 0x00322009, 0x00312008, 0x00301d06, 0x002e1e07, 0x002d1c08, 0x002a1908, 0x00271508, 0x0028150b, 0x0026150b, 0x0024150c, 0x0020160b, 0x001f1409, 0x001d1207, 0x001c1206, 0x001a1306, 0x00191207, 0x00181308, 0x00181308, 0x00151307, 0x00171208, 0x00181108, 0x00181108, 0x00181309, 0x00171008, 0x00151007, 0x00181108, 0x00181309, 0x00181309, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x00191208, 0x00191208, 0x00191306, 0x00191306, 0x001b1307, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1307, 0x001c1307, 0x001e1409, 0x001c1408, 0x001b1408, 0x001e170b, 0x001d160a, 0x001d1409, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001c1104, 0x001c1104, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x00201408, 0x00201408, 0x00221407, 0x00221407, 0x00241409, 0x00241608, 0x00251607, 0x00271706, 0x00271706, 0x00281808, 0x00291807, 0x002c1906, 0x002c1a07, 0x002d1a07, 0x002e1b08, 0x00301b08, 0x00311c0a, 0x00331c09, 0x00331d08, 0x00351e06, 0x00351e05, 0x00351e05, 0x00351e05, 0x00382007, 0x003c230a, 0x003e230b, 0x0040240a, 0x00402409, 0x00402607, 0x003f2707, 0x003c2404, 0x003d2505, 0x00412909, 0x00442909, 0x00422806, 0x00442804, 0x00442802, 0x00422a00, 0x00442c03, 0x00482d07, 0x004b2c05, 0x00502f08, 0x00543008, 0x00553005, 0x00543302, 0x00593802, 0x00694305, 0x007f5214, 0x00946412, 0x00b48e1a, 0x00c7ac1d, 0x00c9b412, 0x00ccb80b, 0x00ccb70d, 0x00cab611, 0x00cab315, 0x00bf9b11, 0x00ab7a06, 0x00986401, 0x00905b08, 0x00885606, 0x00835305, 0x00815207, 0x0085540d, 0x0085540c, 0x0087570c, 0x008c5b0d, 0x00925f05, 0x00a37014, 0x00bd9426, 0x00ccac21, 0x00ccb510, 0x00cab808, 0x00ccb708, 0x00cab60b, 0x00c8a70f, 0x00ac7800, 0x00a46907, 0x00bc881e, 0x00cca61d, 0x00c8b40a, 0x00c6b804, 0x00c6b609, 0x00c9b60a, 0x00ccb60b, 0x00cbb60c, 0x00ccb40e, 0x00ccb30f, 0x00ccb00d, 0x00ccb00e, 0x00ccaf11, 0x00ccac13, 0x00cba819, 0x00c79e18, 0x00c29518, 0x00bd8c14, 0x00b88414, 0x00b17a12, 0x00a8700f, 0x00a0680c, 0x00976008, 0x00905c06, 0x00895808, 0x0085540c, 0x007d4e0a, 0x00764a08, 0x006f4408, 0x00683e0b, 0x00603709, 0x00553105, 0x004e2d04, 0x00472804, 0x00422706, 0x003f2508, 0x003b2108, 0x00392109, 0x00331d07, 0x00281502, 0x00241603, 0x00241807, 0x00201608, 0x001b1408, 0x00161008, 0x00141006, 0x00121006, 0x00101007, 0x000d1007, 0x000c1005, 0x000c0f03, 0x000c1001, 0x000b1004, 0x000c1109, 0x00101510, 0x00141814, 0x00141814, 0x00151916, 0x00161a17, 0x00171c18, 0x00181d18, 0x00181e18, 0x00181f19, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x001d200a, 0x001d2009, 0x001d2008, 0x001d2008, 0x00202308, 0x00202309, 0x00202309, 0x0024250b, 0x0024250b, 0x0024250b, 0x0024250c, 0x0024250c, 0x0026280c, 0x0026280c, 0x0026280c, 0x0026280c, 0x0026280c, 0x0026280c, 0x0024250c, 0x0024250c, 0x0024250b, 0x0024250b, 0x0020230a, 0x00202309, 0x00202309, 0x00202308, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x00191e17, 0x00191d18, 0x00191d18, 0x001a1d18, 0x001a1d17, 0x00191c16, 0x0011140d, 0x0012120c, 0x0014110b, 0x0013120a, 0x00121108, 0x00131008, 0x001b140b, 0x0020170c, 0x0024180a, 0x00251808, 0x00312310, 0x0038280e, 0x00402c0e, 0x0044300c, 0x00503910, 0x005f4211, 0x0079571a, 0x0090691f, 0x00a98220, 0x00bb9826, 0x00c6a82a, 0x00caae27, 0x00cbb41f, 0x00cab414, 0x00cbb613, 0x00ccb712, 0x00ccb910, 0x00cbb90d, 0x00ccbb0d, 0x00cbb90d, 0x00cbb90d, 0x00ccb80e, 0x00ccb80f, 0x00ccb810, 0x00ccb810, 0x00ccb80d, 0x00ccb80d, 0x00cbb90d, 0x00cbb90d, 0x00cbb90d, 0x00cbb90d, 0x00ccb80d, 0x00ccb80d, 0x00ccb80c, 0x00ccb80c, 0x00ccb70d, 0x00ccb510, 0x00cbb014, 0x00bf9810, 0x00a17802, 0x00895b00, 0x00764700, 0x00694005, 0x006c410a, 0x00704608, 0x007c5204, 0x008f6103, 0x00a07408, 0x00b79212, 0x00c6a717, 0x00cbaf13, 0x00cbb010, 0x00cbb10d, 0x00ccb40c, 0x00ccb60a, 0x00ccb509, 0x00ccb60b, 0x00ccb60c, 0x00ccb60d, 0x00ccb50d, 0x00ccb40e, 0x00ccb30e, 0x00ccb012, 0x00c7a412, 0x00be9812, 0x00aa7e0c, 0x008c5c00, 0x00804f01, 0x00704604, 0x00553802, 0x004b3607, 0x0048310e, 0x004a300f, 0x004a2f0a, 0x00492e0a, 0x00492d0c, 0x00492e08, 0x004a2e04, 0x004a2d09, 0x004a2c0d, 0x00492e0b, 0x00492e0b, 0x00492e0b, 0x00482d0a, 0x00472c08, 0x00472d08, 0x00462c07, 0x00452c06, 0x00442c06, 0x00442a08, 0x0043290a, 0x0042290c, 0x003f270a, 0x003e2509, 0x003e250b, 0x003e250b, 0x003e250a, 0x003c2307, 0x00382007, 0x00352008, 0x00342108, 0x00302007, 0x002d1d05, 0x002e1e06, 0x002d1d07, 0x002c1d08, 0x002b1c0a, 0x0028180a, 0x00251509, 0x0027140b, 0x0026150c, 0x0024150d, 0x0020150c, 0x001e1208, 0x001e1107, 0x001c1106, 0x001b1206, 0x00191207, 0x00181308, 0x00181308, 0x00161408, 0x00151308, 0x00181108, 0x00181209, 0x00181309, 0x00171008, 0x00151007, 0x00181108, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181308, 0x00191208, 0x00191208, 0x00191306, 0x00191306, 0x001b1307, 0x001c1307, 0x001c1408, 0x001c1407, 0x001c1407, 0x001c1307, 0x001c1307, 0x001e1409, 0x001e1409, 0x001b1407, 0x001c1509, 0x001b1407, 0x001d1409, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001c1104, 0x001c1104, 0x001c1206, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x00201408, 0x00201408, 0x00211507, 0x00211507, 0x00241409, 0x00241608, 0x00241607, 0x00271706, 0x00271706, 0x00281707, 0x002a1807, 0x002c1906, 0x002c1a05, 0x002e1a05, 0x002f1b06, 0x002f1b06, 0x002f1a08, 0x00301b08, 0x00301b08, 0x00311c08, 0x00311c06, 0x00311c06, 0x00311c06, 0x00341d08, 0x00351d08, 0x00371e09, 0x00381f08, 0x00392008, 0x00392207, 0x00382206, 0x00352105, 0x00362107, 0x00382309, 0x003a2408, 0x003b2408, 0x003b2407, 0x003c2404, 0x003c2404, 0x003e2606, 0x0042280b, 0x0044280b, 0x00492a0e, 0x004b2d0c, 0x004b2e08, 0x004f3408, 0x004e3202, 0x005a3704, 0x00704713, 0x00845610, 0x00946c09, 0x00b49415, 0x00c7ac18, 0x00ccb610, 0x00ccb80c, 0x00c8ba0b, 0x00c8b90c, 0x00ccb218, 0x00c9a01a, 0x00ba8813, 0x00a5700e, 0x00945f02, 0x00945f06, 0x00905c07, 0x00905c10, 0x00915c0f, 0x00935f0e, 0x0098630f, 0x00a6720f, 0x00b98a20, 0x00caa529, 0x00cbb11d, 0x00cab60c, 0x00cab805, 0x00ccb808, 0x00c8b107, 0x00c39e0a, 0x00a97200, 0x00a46c0a, 0x00bf8c20, 0x00cca91f, 0x00c9b408, 0x00c8b606, 0x00c8b40b, 0x00cbb50a, 0x00cbb50a, 0x00cbb50a, 0x00ccb40c, 0x00cbb50a, 0x00c9b608, 0x00c9b608, 0x00c8b508, 0x00cab50b, 0x00ccb50f, 0x00ccb413, 0x00ccae15, 0x00cba915, 0x00cba418, 0x00ca9e1c, 0x00c6981c, 0x00bf8d18, 0x00b98715, 0x00b27e14, 0x00a87410, 0x00a16c13, 0x00996611, 0x00925e0c, 0x008a560e, 0x00885619, 0x007c4c17, 0x00643c08, 0x00583706, 0x004d2f04, 0x00492c05, 0x00452808, 0x00432608, 0x003e2006, 0x00381f05, 0x002e1b04, 0x00231500, 0x00241806, 0x00221808, 0x001d1609, 0x00181208, 0x00141007, 0x00131008, 0x00101009, 0x000f1007, 0x000c1005, 0x000c0f04, 0x000c1004, 0x000c1004, 0x000d1008, 0x0011150f, 0x00141814, 0x00141814, 0x00151916, 0x00161a17, 0x00171c18, 0x00181d18, 0x00181e18, 0x00181f19, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x001d2008, 0x00202308, 0x00202308, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202308, 0x001d2008, 0x001d2008, 0x00202309, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180c, 0x0014180e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x001a1d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x001a1d18, 0x001a1d17, 0x00171a14, 0x0011140d, 0x0011130d, 0x0011120c, 0x00121309, 0x00131209, 0x0016120a, 0x001d140d, 0x0023170c, 0x00281a0a, 0x002c1d0c, 0x0035240e, 0x003a280c, 0x0044300d, 0x004c360c, 0x005c4010, 0x0076521f, 0x00956e28, 0x00b69530, 0x00c8ac26, 0x00ccb41e, 0x00cbb51c, 0x00cbb819, 0x00cbb914, 0x00cbbb0d, 0x00ccbb0d, 0x00ccbb0d, 0x00ccbc0a, 0x00cbbb07, 0x00cbba0a, 0x00cbba0c, 0x00cbb90d, 0x00cbb90f, 0x00cbb90f, 0x00cbb90d, 0x00ccb80d, 0x00ccb80c, 0x00ccb80c, 0x00cbba0c, 0x00cbba0c, 0x00ccb90b, 0x00ccb80c, 0x00ccb70e, 0x00ccb60f, 0x00cbb40c, 0x00cab00c, 0x00ccac13, 0x00c39d0f, 0x00b08609, 0x00956805, 0x007c5000, 0x006c4300, 0x00603902, 0x0059350a, 0x00583607, 0x005c3b06, 0x00614005, 0x00754b08, 0x007c5002, 0x00895c00, 0x009c7003, 0x00ad840b, 0x00b6900e, 0x00bf9911, 0x00c39e10, 0x00c6a10c, 0x00c7a20c, 0x00c7a20c, 0x00c7a10d, 0x00c7a00d, 0x00c49c0c, 0x00c1990e, 0x00b78e07, 0x00ad8104, 0x009d6c04, 0x008d5b00, 0x007a4c00, 0x006c4100, 0x00613b07, 0x00543204, 0x004c3007, 0x00452e09, 0x00442b0a, 0x0044290a, 0x0044280a, 0x0045270c, 0x0044260c, 0x0044260c, 0x0045270c, 0x0047270b, 0x0046280c, 0x0044290c, 0x0044290c, 0x00422a0c, 0x00412b0c, 0x00402a0b, 0x00402a0b, 0x0040290a, 0x003e2708, 0x003c2708, 0x003c2808, 0x003c280a, 0x003a2409, 0x0038220a, 0x0038220a, 0x0038200b, 0x00341e08, 0x0038200b, 0x00341e08, 0x00331c08, 0x00331d09, 0x00321d09, 0x00301d08, 0x002c1b07, 0x002c1b0a, 0x002c1c0c, 0x00281c0c, 0x00271a0a, 0x00241707, 0x00241607, 0x0026150a, 0x00241409, 0x00211308, 0x00201408, 0x00211308, 0x00201207, 0x001d1004, 0x001c1104, 0x001a1207, 0x00181308, 0x00181308, 0x00161408, 0x00151408, 0x0018140c, 0x0019130c, 0x0019110b, 0x0019110b, 0x00181108, 0x00181108, 0x00181108, 0x00181109, 0x0018110b, 0x0018110a, 0x0019130c, 0x0019140b, 0x00191208, 0x00191208, 0x00191306, 0x00191304, 0x001a1308, 0x001b1309, 0x001c1408, 0x001c1408, 0x001d1408, 0x001e1308, 0x001e1308, 0x001f1408, 0x001c1407, 0x00191407, 0x001c1509, 0x001e1409, 0x001e1409, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001e1407, 0x001c1407, 0x001c1406, 0x001c1407, 0x001d1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1408, 0x001f1409, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001e1308, 0x001e1308, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001f1206, 0x00201307, 0x00221509, 0x00231509, 0x00211407, 0x00241407, 0x00251709, 0x00261709, 0x00271809, 0x00291808, 0x00291808, 0x002c1909, 0x002c1a0a, 0x002c1a08, 0x002c1a08, 0x002c1a08, 0x002c1a08, 0x002c1b07, 0x002c1a07, 0x002f1a08, 0x00321c09, 0x00331c0a, 0x00311b06, 0x00331c09, 0x00331c09, 0x00321e08, 0x00321e06, 0x00341e07, 0x00341e07, 0x00341e07, 0x00351e07, 0x00361e07, 0x00381f08, 0x00381f06, 0x003c2105, 0x003e2408, 0x00402409, 0x0041270a, 0x00422808, 0x00422805, 0x00482e08, 0x00482e06, 0x00513007, 0x005e3807, 0x0074490e, 0x00835610, 0x009a6d0b, 0x00bf981c, 0x00cbad1c, 0x00ccb70f, 0x00c7ba06, 0x00c8b906, 0x00ccb80e, 0x00ccb414, 0x00cbad18, 0x00c69d18, 0x00bb8c0f, 0x00b9810e, 0x00b07509, 0x00ad7210, 0x00ac7310, 0x00b07710, 0x00b88117, 0x00c4981c, 0x00caa721, 0x00ccaf1c, 0x00c9b414, 0x00c9b80a, 0x00ccb806, 0x00ccb307, 0x00ccaf0c, 0x00bc8f06, 0x00a36a00, 0x00a87010, 0x00c39924, 0x00c8ad15, 0x00cbb407, 0x00cab40b, 0x00cbb50a, 0x00cbb608, 0x00ccb508, 0x00ccb508, 0x00ccb409, 0x00ccb40a, 0x00cbb50a, 0x00cbb50a, 0x00cbb50a, 0x00cbb50a, 0x00cab60a, 0x00c9b60b, 0x00c9b60b, 0x00c9b50b, 0x00cbb10a, 0x00ccad0f, 0x00ccac14, 0x00cca917, 0x00caa618, 0x00c9a319, 0x00c59c18, 0x00c0951a, 0x00be901b, 0x00ba8113, 0x00af7112, 0x00ac6f20, 0x00a06721, 0x0081500e, 0x00653f02, 0x00523600, 0x004c3306, 0x004a2e09, 0x00482908, 0x00432507, 0x003c2307, 0x00342008, 0x002a1a05, 0x00261704, 0x00251808, 0x0022180b, 0x001c140a, 0x00171008, 0x00141008, 0x00131009, 0x00101007, 0x00100f08, 0x000c0e08, 0x000e1008, 0x00101008, 0x00101006, 0x00111309, 0x00131610, 0x00141914, 0x00141914, 0x00151a14, 0x00161b15, 0x00161c17, 0x00181e18, 0x0019201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180a, 0x0014180a, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x00202309, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x00202309, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x00191c09, 0x001d200a, 0x00191c09, 0x00191c0a, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180c, 0x0014180e, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x001a1d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x001a1d18, 0x001a1d17, 0x00181914, 0x0011120c, 0x0012130d, 0x0013120c, 0x00131209, 0x0014130a, 0x00161208, 0x00211810, 0x00261a0e, 0x00281a09, 0x002e1e09, 0x0038250e, 0x003e2b0d, 0x0048320c, 0x00533c0e, 0x006a4b12, 0x00886420, 0x00ad892e, 0x00caad34, 0x00cbb81f, 0x00ccb914, 0x00cbb810, 0x00cbba0e, 0x00cbbb0b, 0x00ccbc09, 0x00cbbb07, 0x00ccbc08, 0x00ccbc06, 0x00cbbb06, 0x00cbba0a, 0x00cbba0c, 0x00cbba0b, 0x00cbba09, 0x00cbba08, 0x00cbba0b, 0x00cbba0a, 0x00ccb90a, 0x00ccb90a, 0x00ccb90c, 0x00cbb80b, 0x00ccb609, 0x00ccb30c, 0x00ccb011, 0x00c8aa12, 0x00c6a313, 0x00c09611, 0x00b2840f, 0x009f6e08, 0x00885700, 0x00744600, 0x00684001, 0x005c3703, 0x00553408, 0x0051340a, 0x00503408, 0x00503403, 0x00523401, 0x005a3807, 0x00643e09, 0x006e4606, 0x00754b03, 0x00784d00, 0x00815602, 0x00875b03, 0x008c5f04, 0x00906502, 0x00926701, 0x00936701, 0x00946601, 0x00946501, 0x00905f01, 0x008c5b00, 0x00855300, 0x007b4a00, 0x00744500, 0x00683c00, 0x00603700, 0x00573202, 0x00503005, 0x004b2c04, 0x00462c07, 0x00442c09, 0x00422808, 0x00412708, 0x00402608, 0x0041260a, 0x0040250b, 0x0040240b, 0x0040240a, 0x00402309, 0x00402308, 0x003f2308, 0x003d2408, 0x003c2409, 0x003a2509, 0x00392408, 0x00392409, 0x0039240a, 0x00382306, 0x00352206, 0x00352206, 0x00342006, 0x00332008, 0x00331f08, 0x00331e09, 0x00321d09, 0x002f1b06, 0x00321d09, 0x002f1b08, 0x00301b08, 0x00311e0b, 0x00301d0a, 0x002c1b07, 0x002a1907, 0x002b190b, 0x002a190c, 0x0027190c, 0x0024180a, 0x00241809, 0x00241809, 0x00241409, 0x00221408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x001d1104, 0x001c1204, 0x001a1207, 0x00181308, 0x00181308, 0x00161408, 0x00141308, 0x00151308, 0x00171208, 0x00181309, 0x00191209, 0x0018100a, 0x0018100a, 0x0018100a, 0x0018100a, 0x0018110a, 0x0018110a, 0x0019140b, 0x00191409, 0x00191208, 0x00191208, 0x00191306, 0x00191304, 0x001a1308, 0x001b1309, 0x001c1408, 0x001c1408, 0x001d1408, 0x001e1308, 0x001e1308, 0x001f1408, 0x001c1407, 0x00191407, 0x001c1509, 0x001e1409, 0x001f1409, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001e1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001d1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1408, 0x001f1409, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001e1308, 0x001e1308, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001e1205, 0x001e1205, 0x00201408, 0x00201408, 0x00201408, 0x00221509, 0x0023160a, 0x0023160a, 0x00241608, 0x00241506, 0x00251506, 0x00261708, 0x0028180a, 0x00281908, 0x00281908, 0x00281908, 0x00281908, 0x00291908, 0x002a1807, 0x002c1808, 0x002e1908, 0x00311c0b, 0x002f1a08, 0x002f1a08, 0x002f1a08, 0x00301b06, 0x00301a04, 0x00311b05, 0x00331b05, 0x00331b05, 0x00331b05, 0x00341b06, 0x00341b07, 0x00341c05, 0x00381c04, 0x00391e06, 0x003b2007, 0x003d2209, 0x003e230a, 0x003e2408, 0x00442b0c, 0x00452a09, 0x00492c08, 0x00523005, 0x00603704, 0x0075480e, 0x00815404, 0x009c700b, 0x00ba9318, 0x00cbac1a, 0x00cbb412, 0x00cab50c, 0x00ccb80e, 0x00ccb60d, 0x00cbb210, 0x00cbb018, 0x00cbaa17, 0x00cca618, 0x00caa31c, 0x00c89c18, 0x00c89c17, 0x00c9a017, 0x00cba519, 0x00ccac19, 0x00ccb116, 0x00cbb410, 0x00c9b70c, 0x00c8b908, 0x00cbb809, 0x00ccb30d, 0x00c4a40e, 0x00ae7f01, 0x00a06601, 0x00af7813, 0x00c89f23, 0x00c8b013, 0x00cab507, 0x00cab40b, 0x00cbb50a, 0x00cbb605, 0x00cbb503, 0x00cbb405, 0x00ccb507, 0x00ccb508, 0x00cbb608, 0x00cbb608, 0x00cbb50a, 0x00cbb50a, 0x00c9b60a, 0x00c9b60a, 0x00cbb50a, 0x00cbb609, 0x00cbb408, 0x00cbb208, 0x00ccb20c, 0x00ccb412, 0x00ccb313, 0x00ccb213, 0x00ccb116, 0x00c9ad16, 0x00c8a815, 0x00caa016, 0x00c38e13, 0x00c3871c, 0x00b47818, 0x009e6210, 0x00804d04, 0x00643c01, 0x00583704, 0x00503108, 0x004c2e0a, 0x00472b0b, 0x0040270a, 0x0039240c, 0x00301d08, 0x00281803, 0x00261806, 0x00251b0b, 0x001c1609, 0x00181308, 0x00161209, 0x00141109, 0x00101007, 0x00100f08, 0x000f100a, 0x000e1008, 0x000f0f05, 0x000f0f04, 0x00111309, 0x00131610, 0x00131712, 0x00131712, 0x00141813, 0x00141914, 0x00141a14, 0x00161c17, 0x00181e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180b, 0x00191c0b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x001d2009, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c18, 0x00191c18, 0x001a1d18, 0x00191d18, 0x00191d18, 0x00181e18, 0x00191d18, 0x00191d18, 0x00181c18, 0x00191d18, 0x00121510, 0x0010130c, 0x0013110c, 0x0014100b, 0x00141008, 0x00171208, 0x001d180c, 0x00241a0e, 0x00261a0c, 0x002c1c09, 0x0034240c, 0x003c280e, 0x00442d0e, 0x004d350d, 0x005c4313, 0x00775714, 0x009a771f, 0x00c2a42e, 0x00cbb721, 0x00ccc018, 0x00cbc010, 0x00cabc0b, 0x00cbbc07, 0x00cabc06, 0x00cbba07, 0x00cbba07, 0x00cbba07, 0x00cbbb05, 0x00cbbb06, 0x00cbba0a, 0x00cbba0c, 0x00cab908, 0x00caba06, 0x00cab907, 0x00ccb90c, 0x00cab70c, 0x00cbb50e, 0x00cbb20f, 0x00cab014, 0x00c9aa12, 0x00c6a50c, 0x00c09a07, 0x00b89008, 0x00ad8406, 0x00a07405, 0x00926403, 0x00875604, 0x00784703, 0x006c3c02, 0x00603a02, 0x00563400, 0x00513404, 0x004c3305, 0x00483008, 0x00473007, 0x00483106, 0x00483005, 0x004a3004, 0x004c2f03, 0x00543504, 0x005a3803, 0x005f3a04, 0x00613b03, 0x00643c03, 0x00643c01, 0x00653d00, 0x00673f00, 0x00684000, 0x00684000, 0x00684101, 0x00674002, 0x00623c01, 0x005d3701, 0x00593400, 0x00553200, 0x00502e00, 0x004e2b01, 0x00492a04, 0x00452908, 0x00432908, 0x00412808, 0x003f2708, 0x003e2407, 0x003c2306, 0x003c2107, 0x003d2209, 0x003c220a, 0x003c220a, 0x003b2109, 0x003a2009, 0x003a2009, 0x003b2009, 0x00392008, 0x00371f08, 0x00362008, 0x00341f09, 0x00341f09, 0x00341f08, 0x00341f08, 0x00331f07, 0x00331f07, 0x00321e09, 0x00311c09, 0x00301c08, 0x00301b08, 0x002e1b08, 0x002d1b08, 0x002d1b08, 0x002c1908, 0x002c1908, 0x002b1908, 0x002b1908, 0x00281806, 0x00261607, 0x00261608, 0x00251609, 0x0024170a, 0x00221509, 0x00221509, 0x00221509, 0x00241409, 0x00211408, 0x001f1407, 0x001d1407, 0x001d1205, 0x001e1205, 0x001d1205, 0x001c1305, 0x001b1308, 0x001a1408, 0x00181408, 0x00151307, 0x00141207, 0x00141308, 0x00151308, 0x00181309, 0x00181309, 0x00191209, 0x00181108, 0x00181108, 0x00191209, 0x0018120a, 0x00181309, 0x00191409, 0x00181307, 0x00191208, 0x00191208, 0x00191306, 0x00191304, 0x00191207, 0x00191208, 0x001a1307, 0x001b1407, 0x001c1207, 0x001c1106, 0x001c1106, 0x001e1407, 0x001f1508, 0x00181306, 0x001c1408, 0x001c1408, 0x001d1308, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1407, 0x001c1407, 0x001d1305, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201409, 0x00201409, 0x00201309, 0x00201308, 0x00201308, 0x00221407, 0x00221407, 0x00241508, 0x00241608, 0x00241707, 0x00241707, 0x00241707, 0x00241707, 0x00251706, 0x00261605, 0x00281707, 0x002b1808, 0x002c1a09, 0x002a1807, 0x002a1808, 0x002d1c09, 0x002c1a07, 0x002e1a05, 0x002e1a05, 0x002f1a05, 0x002f1a05, 0x002f1a05, 0x002f1a06, 0x00301b06, 0x00311a04, 0x00321b04, 0x00321b04, 0x00341c06, 0x00351e09, 0x00371f0a, 0x00372008, 0x003d260d, 0x003d260b, 0x00422809, 0x00492c08, 0x00502e04, 0x005d3507, 0x00704509, 0x007f5406, 0x00946807, 0x00b48915, 0x00c9a51d, 0x00ccb018, 0x00ccb214, 0x00ccb60d, 0x00ccb80c, 0x00cab710, 0x00cab610, 0x00cab410, 0x00cbb411, 0x00cbb311, 0x00cbb310, 0x00ccb40e, 0x00ccb40d, 0x00ccb60d, 0x00ccb70b, 0x00cab707, 0x00c9b804, 0x00c9b807, 0x00ccb80e, 0x00caac14, 0x00b48c08, 0x009f6c00, 0x00a06503, 0x00bd881c, 0x00cca823, 0x00cab210, 0x00cab507, 0x00cbb50c, 0x00cbb50a, 0x00cbb605, 0x00ccb604, 0x00ccb506, 0x00ccb508, 0x00ccb508, 0x00cbb608, 0x00cbb608, 0x00cbb50a, 0x00cbb50a, 0x00c9b60a, 0x00c9b60a, 0x00cbb50a, 0x00cbb609, 0x00cbb508, 0x00cbb406, 0x00cbb408, 0x00ccb509, 0x00ccb509, 0x00cbb50b, 0x00cbb50b, 0x00cab50c, 0x00ccb40f, 0x00ccaa0f, 0x00cc9d0e, 0x00cb9412, 0x00c48b12, 0x00bc8213, 0x00a66e0e, 0x00875408, 0x006d4306, 0x005d3b0a, 0x004f3308, 0x0048300c, 0x0043290c, 0x0040260e, 0x0038220b, 0x002e1b06, 0x00281704, 0x00261a09, 0x001c1708, 0x00161104, 0x00171208, 0x00141308, 0x00121208, 0x00101008, 0x000d0f08, 0x000c0f07, 0x00101007, 0x00101005, 0x00101108, 0x0011140e, 0x00101510, 0x00101510, 0x00131712, 0x00141813, 0x00141a14, 0x00151c16, 0x00151c16, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x00191c0b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x0014180f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c18, 0x00181c18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00181e18, 0x00191d18, 0x001a1f19, 0x00191e17, 0x00191e17, 0x0011150f, 0x0010120c, 0x0013100c, 0x0016100b, 0x00171009, 0x00181308, 0x001d170b, 0x00241a0c, 0x00271909, 0x002f200c, 0x0038260e, 0x00402c0e, 0x0048300c, 0x00563b10, 0x00654916, 0x00846214, 0x00b09027, 0x00cab025, 0x00cabc14, 0x00cbc210, 0x00cbc210, 0x00cabe0c, 0x00cbbc08, 0x00cbba07, 0x00cab909, 0x00cab90b, 0x00cbba0c, 0x00cbba08, 0x00cbbb06, 0x00cbbb09, 0x00ccb90c, 0x00cbb80b, 0x00cbb908, 0x00cbb70b, 0x00cab511, 0x00c8b014, 0x00c8a815, 0x00c39c11, 0x00b98f0e, 0x00ab7d04, 0x009e6f00, 0x00946400, 0x008e5d00, 0x00895700, 0x007d4e00, 0x00704700, 0x00674000, 0x005e3800, 0x005a3706, 0x0055350b, 0x004e3208, 0x00483207, 0x00453106, 0x00432f06, 0x00422e08, 0x00422d08, 0x00422d09, 0x00422d09, 0x00442e08, 0x00432a03, 0x00482e06, 0x004a2e04, 0x004c2e02, 0x004c2f03, 0x004c3003, 0x004c3002, 0x004d3203, 0x004d3403, 0x004d3403, 0x004f3403, 0x004e3401, 0x004c3101, 0x004c3105, 0x00492f04, 0x00482c04, 0x00472c05, 0x00462b0b, 0x0044290d, 0x0040260c, 0x003d260a, 0x003c2308, 0x003a2207, 0x00392106, 0x00381f05, 0x00361d05, 0x00361d07, 0x00351e08, 0x00341e08, 0x00341d08, 0x00331c08, 0x00341c07, 0x00341c07, 0x00341c08, 0x00341d09, 0x00321d09, 0x00311c0a, 0x00321d0b, 0x00301d0a, 0x00311d08, 0x00301d08, 0x00301d08, 0x00301c0a, 0x00301c0c, 0x002c1a08, 0x002c1a08, 0x002c1908, 0x002a1807, 0x002a1808, 0x00291809, 0x00281808, 0x00271708, 0x00261808, 0x00241606, 0x00241607, 0x00241608, 0x0024160a, 0x0023160c, 0x0021140a, 0x0021140a, 0x0021140a, 0x0022150b, 0x0020140a, 0x001d1408, 0x001c1408, 0x001c1305, 0x001d1205, 0x001c1205, 0x001c1305, 0x001b1407, 0x001a1308, 0x00181408, 0x00151207, 0x00141206, 0x00131306, 0x00141206, 0x00161307, 0x00181308, 0x00191307, 0x00191207, 0x00191307, 0x00191307, 0x00181308, 0x00181308, 0x00181307, 0x00181306, 0x00191307, 0x00191208, 0x00191306, 0x00191304, 0x00191207, 0x00191208, 0x001a1308, 0x001b1407, 0x001c1207, 0x001c1106, 0x001c1106, 0x001e1407, 0x001f1508, 0x00181306, 0x001c1408, 0x001c1408, 0x001d1408, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1407, 0x001c1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201208, 0x00201208, 0x00201208, 0x001e1208, 0x001d1208, 0x001d1207, 0x001c1106, 0x001f1207, 0x00201207, 0x00211308, 0x00221408, 0x00231509, 0x00221608, 0x00221708, 0x00221708, 0x00221708, 0x00241508, 0x00251508, 0x00261508, 0x00281408, 0x00281808, 0x00261606, 0x00261707, 0x00281908, 0x00281805, 0x00291806, 0x00291805, 0x00291805, 0x00291805, 0x00291805, 0x002a1806, 0x002a1806, 0x002b1905, 0x00301c08, 0x002f1c08, 0x002f1c08, 0x00301c08, 0x00301c0c, 0x00311e0b, 0x00341f0a, 0x00352008, 0x003c270c, 0x00442a0b, 0x00492b09, 0x004f2d08, 0x00583505, 0x00654104, 0x00795002, 0x008f6203, 0x00a87d0c, 0x00bf9918, 0x00cbab1b, 0x00ccb111, 0x00ccb50c, 0x00cab60c, 0x00cab70c, 0x00cab80c, 0x00cbb90d, 0x00cab90d, 0x00c8ba0b, 0x00c8b908, 0x00c8ba08, 0x00c9b908, 0x00c9b808, 0x00c9b806, 0x00cbb804, 0x00cab205, 0x00ccaf0f, 0x00bc9205, 0x00a57300, 0x009c6200, 0x00a16504, 0x00bf8b1b, 0x00caa41b, 0x00c9af0e, 0x00cbb40a, 0x00ccb40e, 0x00ccb50c, 0x00ccb508, 0x00ccb40a, 0x00ccb50a, 0x00ccb40a, 0x00ccb40a, 0x00cbb50a, 0x00c9b60a, 0x00c9b60a, 0x00c9b60a, 0x00c8b70a, 0x00c8b709, 0x00c9b609, 0x00c9b60a, 0x00cab509, 0x00cab408, 0x00cab509, 0x00cbb509, 0x00cbb50a, 0x00cbb50c, 0x00cbb50c, 0x00cbb50b, 0x00ccb40c, 0x00ccab0d, 0x00cba00c, 0x00c8980e, 0x00c99a14, 0x00cba315, 0x00bd8d12, 0x00a36f0e, 0x00855408, 0x00684108, 0x0057390a, 0x004a320a, 0x00472c0e, 0x0042280d, 0x003c260c, 0x00322007, 0x00291802, 0x00261b08, 0x00201908, 0x00191404, 0x00181206, 0x00141307, 0x00121108, 0x00100f08, 0x000d0f08, 0x000d0f07, 0x00101007, 0x00101005, 0x000f1108, 0x0012140e, 0x0010140f, 0x0010140f, 0x00111611, 0x00121712, 0x00131914, 0x00141a14, 0x00141a14, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180f, 0x000f130b, 0x0014180d, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130b, 0x000f130b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191d18, 0x00191d18, 0x00191d1a, 0x00181e18, 0x00181e18, 0x00181f17, 0x00171d18, 0x0019201a, 0x001b211a, 0x00141a13, 0x000f120c, 0x0010110c, 0x0011110b, 0x0014110a, 0x00161208, 0x001c170c, 0x0020190c, 0x00231809, 0x00281b0a, 0x0032230f, 0x0038260f, 0x00422e0c, 0x004c350c, 0x005b3f0c, 0x00724f14, 0x00906c17, 0x00c0a129, 0x00cbb41a, 0x00c9bc0e, 0x00cac110, 0x00cbc113, 0x00cbbf11, 0x00cbbc09, 0x00cbbb06, 0x00cabc09, 0x00c9bb09, 0x00c9bb07, 0x00cabb04, 0x00cbba04, 0x00ccb907, 0x00ccb80c, 0x00ccb40d, 0x00ccb110, 0x00caa910, 0x00c49f12, 0x00b8900c, 0x00a97a03, 0x009c6a00, 0x00925f00, 0x00855200, 0x007c4a00, 0x00774800, 0x00704400, 0x006b4000, 0x00643e02, 0x00593803, 0x00533502, 0x00503706, 0x004d3609, 0x0048330e, 0x0044300c, 0x00412f0a, 0x0040300a, 0x003e2c08, 0x003c2a05, 0x003d2808, 0x003d2808, 0x003d2808, 0x003e2909, 0x0040280a, 0x0041290b, 0x00402b0a, 0x00412b09, 0x00422b08, 0x00432a08, 0x00422a08, 0x00422a08, 0x00442b08, 0x00442b08, 0x00472c0a, 0x00482b0a, 0x00482b0c, 0x00482a0c, 0x00482a0c, 0x00472a09, 0x00452808, 0x00432509, 0x0040250c, 0x003c230b, 0x003a230a, 0x00382008, 0x00351e05, 0x00341d05, 0x00341d07, 0x00331c08, 0x00311c08, 0x00311c08, 0x00301c08, 0x00301c08, 0x00301c09, 0x00311c08, 0x00301b07, 0x00301a06, 0x00311b07, 0x00321d09, 0x00301c09, 0x002e1c08, 0x002c1c07, 0x002b1a06, 0x002c1b07, 0x002d1a07, 0x002d1a07, 0x002c1b07, 0x002a1906, 0x002a1907, 0x00281808, 0x00281809, 0x0028180b, 0x0027180a, 0x00241709, 0x00241608, 0x00231708, 0x00231708, 0x00231708, 0x00221608, 0x00221508, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1409, 0x001f1409, 0x001f1409, 0x001f1409, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001a1508, 0x001a1508, 0x00191408, 0x00181205, 0x00151204, 0x00151405, 0x00171305, 0x00181306, 0x00181306, 0x001b1407, 0x001b1407, 0x00191306, 0x00191306, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x001b1206, 0x001b1205, 0x001b1204, 0x001b1204, 0x001a1207, 0x00191208, 0x00191307, 0x00191306, 0x001c1206, 0x001d1207, 0x001d1207, 0x001d1205, 0x00201508, 0x001a1105, 0x001c1307, 0x001c1408, 0x001c1408, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1207, 0x001d1207, 0x001e1308, 0x001e1308, 0x001f140a, 0x001e130a, 0x001d1208, 0x001d1208, 0x001d130a, 0x001c140a, 0x001c1309, 0x001c1309, 0x001d1309, 0x001f1208, 0x001f1208, 0x00201409, 0x0020140a, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00221408, 0x00221408, 0x00231409, 0x0022160a, 0x0024150b, 0x00241509, 0x00251709, 0x00251708, 0x00261707, 0x00261607, 0x00271708, 0x00281708, 0x00281708, 0x00281708, 0x00281808, 0x00281809, 0x00281808, 0x002a1908, 0x002c1b09, 0x002f1c0a, 0x002f1c0a, 0x002d1c0a, 0x002f1c0b, 0x00321d09, 0x00341e08, 0x00372007, 0x003f250c, 0x0042270b, 0x00472a0b, 0x004a310a, 0x00503403, 0x005e3b00, 0x00754b06, 0x00845805, 0x00966a08, 0x00b08514, 0x00c49a14, 0x00cba814, 0x00cbb212, 0x00ccb411, 0x00ccb60e, 0x00ccb70c, 0x00ccb80b, 0x00cbb80b, 0x00cab80b, 0x00cab80b, 0x00cbb80a, 0x00cab409, 0x00cbb40b, 0x00ccb30c, 0x00cca810, 0x00bd8d08, 0x00aa7401, 0x009d6000, 0x00a16104, 0x00a16202, 0x00b47810, 0x00bc8910, 0x00c49511, 0x00c89f11, 0x00cca615, 0x00cca912, 0x00ccae13, 0x00ccb014, 0x00caaf0e, 0x00cab30c, 0x00cbb50a, 0x00cbb608, 0x00cbb608, 0x00cab608, 0x00c8b708, 0x00c8b708, 0x00c8b806, 0x00c9b707, 0x00c9b608, 0x00cbb509, 0x00cbb50a, 0x00cbb50c, 0x00cbb50c, 0x00cab50c, 0x00c9b50d, 0x00c9b60c, 0x00c9b60a, 0x00cbb508, 0x00ccac08, 0x00c8a108, 0x00c49c07, 0x00c8a80d, 0x00ccb416, 0x00caab18, 0x00be9318, 0x00a36e0c, 0x00875107, 0x006d4207, 0x00583809, 0x004c3007, 0x00432b08, 0x003f2a0b, 0x0038250b, 0x002f1d06, 0x00281805, 0x0027190a, 0x00201708, 0x00181305, 0x00161306, 0x00141008, 0x0014130c, 0x0010100b, 0x000e0e07, 0x00111008, 0x00101006, 0x0013120a, 0x0012140e, 0x000f140e, 0x00101610, 0x00101711, 0x000f1812, 0x00111914, 0x00121a15, 0x00131b16, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e1a, 0x00181e18, 0x00181e18, 0x00181f17, 0x00181f17, 0x001a2018, 0x001b2119, 0x00141a13, 0x0010110c, 0x0010100b, 0x0011110b, 0x0015130a, 0x00181209, 0x001e180c, 0x0021180a, 0x00241907, 0x002d200c, 0x00352710, 0x003c2911, 0x0046320d, 0x0053390d, 0x006a4812, 0x007f5a17, 0x00a58423, 0x00c9ad2c, 0x00ccb718, 0x00cbbd0e, 0x00cbc110, 0x00cbc111, 0x00ccc011, 0x00cbbd0b, 0x00cabc06, 0x00c9bc06, 0x00c8bb06, 0x00c8b805, 0x00c9b705, 0x00cab607, 0x00cbb40c, 0x00c8ab0c, 0x00c4a00a, 0x00bb8b07, 0x00ae7d04, 0x009c6d01, 0x008c5d00, 0x00835400, 0x00784c00, 0x006e4400, 0x00643d01, 0x00613c01, 0x005d3a01, 0x00583800, 0x00543400, 0x004f3303, 0x004f3309, 0x004c320a, 0x0049310c, 0x0046300e, 0x00412c0c, 0x003c2a09, 0x003b2807, 0x003a2807, 0x003a2707, 0x00382606, 0x00372405, 0x00362305, 0x00382307, 0x00382408, 0x00392409, 0x00392508, 0x00392709, 0x00392708, 0x00382606, 0x00372404, 0x00382406, 0x00382408, 0x003b2409, 0x003b240a, 0x00402509, 0x00412609, 0x0043270b, 0x0043260c, 0x0042250a, 0x00402406, 0x003f2306, 0x003c2108, 0x003a2108, 0x00371f08, 0x00351f08, 0x00331d06, 0x00321c05, 0x00301c05, 0x00301c06, 0x002f1a08, 0x002f1a09, 0x002e1a0a, 0x002e1b0a, 0x002e1b0a, 0x002e1b0a, 0x002e1b09, 0x002f1a08, 0x002e1908, 0x002e1907, 0x002f1b08, 0x002e1b0a, 0x002c1c0a, 0x00281a08, 0x00271908, 0x00281808, 0x00291808, 0x00291808, 0x00281807, 0x00281807, 0x00271808, 0x00251808, 0x00251709, 0x0024180a, 0x0024180b, 0x0024170b, 0x0023160a, 0x0023160a, 0x00231708, 0x00231708, 0x00221608, 0x00221608, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1409, 0x001f1409, 0x001f1409, 0x001f1409, 0x001e1407, 0x001e1407, 0x001d1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001b1407, 0x00181306, 0x00171305, 0x00181205, 0x00191306, 0x001a1306, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x001b1205, 0x001b1204, 0x001b1204, 0x001b1204, 0x001a1207, 0x00191208, 0x00191307, 0x00191306, 0x001c1206, 0x001d1207, 0x001d1207, 0x001d1205, 0x00201508, 0x001a1105, 0x001c1307, 0x001c1408, 0x001c1408, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1409, 0x001e1308, 0x001d1207, 0x001d1207, 0x001c1408, 0x001c1408, 0x001e1409, 0x001e1409, 0x001e1409, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201508, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201508, 0x00201408, 0x00211408, 0x00221608, 0x00221608, 0x00241508, 0x00241409, 0x0024150a, 0x0024160a, 0x0024160a, 0x0024160a, 0x0024160a, 0x0025170a, 0x00261608, 0x00281806, 0x00281807, 0x002b1908, 0x002c1b09, 0x002c1b09, 0x002d1c08, 0x00301c08, 0x00331d08, 0x00351d05, 0x00381f06, 0x003d2208, 0x0043290c, 0x00442e0c, 0x0048320a, 0x00503404, 0x005c3801, 0x006d4404, 0x007b4f01, 0x00895c00, 0x009d6d03, 0x00b0840c, 0x00bc9411, 0x00c7a015, 0x00cba814, 0x00ccad13, 0x00ccb00c, 0x00ccb00b, 0x00ccb00c, 0x00ccb10c, 0x00ccb00f, 0x00ccad0f, 0x00caa811, 0x00c49c0c, 0x00b78405, 0x00a87001, 0x009e6200, 0x00a96a0a, 0x00b57514, 0x00b0700c, 0x00ac6f05, 0x00a96d00, 0x00ac7200, 0x00b27a03, 0x00b98208, 0x00be890a, 0x00c59410, 0x00c39c10, 0x00c9a514, 0x00ccac14, 0x00ccb013, 0x00ccb40c, 0x00ccb40a, 0x00cbb508, 0x00cab608, 0x00cab707, 0x00cbb606, 0x00cbb607, 0x00cbb608, 0x00ccb409, 0x00ccb40b, 0x00ccb40c, 0x00cbb40d, 0x00cbb40d, 0x00cbb40d, 0x00cbb50c, 0x00c9b60a, 0x00cab508, 0x00ccae08, 0x00c8a309, 0x00c7a009, 0x00caac0f, 0x00cbb812, 0x00ccb514, 0x00cbad1d, 0x00bc8f14, 0x009c6a0c, 0x007f5208, 0x00644006, 0x00513303, 0x004a3008, 0x00402b0b, 0x003c280c, 0x00332108, 0x002a1a05, 0x00281908, 0x00241b09, 0x00191404, 0x00161304, 0x00151208, 0x00121109, 0x0011130b, 0x00101009, 0x00110f07, 0x00101006, 0x00101008, 0x0010120c, 0x000f140e, 0x00101610, 0x000f1811, 0x000f1912, 0x00101914, 0x00121a15, 0x00131b16, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e1a, 0x00181e1a, 0x00181e1a, 0x00181e18, 0x00181e18, 0x00182018, 0x00181f17, 0x001a2018, 0x001a1f18, 0x00141811, 0x0012140e, 0x0011110c, 0x0013100c, 0x00151209, 0x0019140a, 0x001e170b, 0x00221909, 0x00261a08, 0x0031220d, 0x00382710, 0x003e2b11, 0x004a330e, 0x00583c0d, 0x006f4c0e, 0x008a6417, 0x00b69628, 0x00c9b024, 0x00ccb814, 0x00cabc0d, 0x00c8be0d, 0x00c8c00c, 0x00cbc00e, 0x00ccc010, 0x00c8b60a, 0x00c8b309, 0x00c8af09, 0x00ccad0e, 0x00ccac11, 0x00caa815, 0x00c09c12, 0x00b08809, 0x00a17400, 0x00946000, 0x00885500, 0x00794c00, 0x00714800, 0x006a4403, 0x00603c02, 0x00583804, 0x00543708, 0x00513509, 0x004e3307, 0x004c3309, 0x004a330b, 0x0046320c, 0x0046300e, 0x00442c0d, 0x0042290e, 0x00402a0e, 0x003e290c, 0x003a2809, 0x00392608, 0x00372407, 0x00372407, 0x00362407, 0x00342107, 0x00342108, 0x00342007, 0x00342007, 0x00342107, 0x00342208, 0x00342208, 0x00322306, 0x00332206, 0x00342304, 0x00342204, 0x00342204, 0x00352204, 0x00372205, 0x00392307, 0x003c2308, 0x003c2408, 0x003c220b, 0x003c230a, 0x003b2307, 0x00382005, 0x00382008, 0x00372009, 0x00331d08, 0x00311d08, 0x00301c08, 0x002f1b06, 0x002d1c06, 0x002d1b08, 0x002c1a08, 0x002c180a, 0x002c180b, 0x002c180b, 0x002c180b, 0x002c180b, 0x002c180a, 0x002c1909, 0x002c1909, 0x002a1808, 0x002b1809, 0x00271708, 0x00261808, 0x00261a0a, 0x00271a0b, 0x0027180a, 0x0028180a, 0x00281809, 0x00271809, 0x00251808, 0x00251808, 0x00231709, 0x0023160a, 0x0023160c, 0x0023160c, 0x0023160c, 0x0023160b, 0x0023160a, 0x00221509, 0x00221608, 0x00211507, 0x00211507, 0x00221509, 0x00201408, 0x00201307, 0x00201307, 0x001f1409, 0x001f1409, 0x001f1409, 0x001f1409, 0x00201307, 0x00201307, 0x001e1407, 0x001d1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x00191306, 0x00181306, 0x00191306, 0x001c1307, 0x001c1307, 0x001d1207, 0x001d1207, 0x001e1308, 0x001c1206, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001b1204, 0x001b1204, 0x001b1204, 0x001b1204, 0x001b1308, 0x001b1309, 0x001a1308, 0x00191306, 0x001c1206, 0x001d1207, 0x001d1207, 0x001d1205, 0x00201508, 0x001b1206, 0x001c1307, 0x001e1409, 0x001e1409, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1409, 0x001e1308, 0x001d1207, 0x001d1207, 0x001c140a, 0x001c140a, 0x001c1309, 0x001c1208, 0x001c1209, 0x001e130a, 0x001e130a, 0x001e130a, 0x001e130a, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x00201409, 0x001f1409, 0x001e1409, 0x001d1409, 0x001e1407, 0x001e1407, 0x00201508, 0x00201508, 0x00211507, 0x00211506, 0x00211506, 0x00211506, 0x00211507, 0x00221607, 0x00221607, 0x00221607, 0x00241607, 0x00241607, 0x00251608, 0x00281709, 0x0028180a, 0x0028180a, 0x00291809, 0x002f1b0b, 0x00321d0b, 0x00341e0a, 0x00351d08, 0x00392009, 0x003e250c, 0x00402a0d, 0x00442c0d, 0x004a300a, 0x00503306, 0x005b3705, 0x00693f06, 0x007c4e08, 0x00885404, 0x00956004, 0x00a46e04, 0x00ad7807, 0x00b48008, 0x00bb8b08, 0x00c09206, 0x00c59a0c, 0x00c69a0c, 0x00c59b0c, 0x00c1980c, 0x00bb8f08, 0x00b58506, 0x00a77200, 0x00a16800, 0x00a66a06, 0x00b07510, 0x00c0891b, 0x00cb9b21, 0x00ca981b, 0x00c59114, 0x00bd880c, 0x00b57e05, 0x00af7501, 0x00ac7001, 0x00a96b00, 0x00a46800, 0x00a46f02, 0x00ae7c07, 0x00b6880d, 0x00c59b18, 0x00caa714, 0x00ccab14, 0x00cbac10, 0x00cbb00f, 0x00cbb10c, 0x00ccb30b, 0x00ccb30a, 0x00ccb40b, 0x00ccb40c, 0x00ccb40d, 0x00ccb40d, 0x00cbb40d, 0x00cbb40d, 0x00cbb40d, 0x00cab40b, 0x00c8b509, 0x00cab408, 0x00ccac08, 0x00c8a308, 0x00c9a30c, 0x00ccaf11, 0x00cab911, 0x00cbb90f, 0x00ccb814, 0x00c8aa13, 0x00a88007, 0x00895e00, 0x00734a04, 0x005c3a02, 0x004f3107, 0x00452c09, 0x0040290a, 0x003a250c, 0x002e1c05, 0x00261704, 0x00261b08, 0x001f1808, 0x00181404, 0x00161208, 0x00100e07, 0x0010120a, 0x00121108, 0x00101008, 0x00101006, 0x00101008, 0x0010110c, 0x000f140e, 0x00101510, 0x000f1611, 0x000e1813, 0x00101815, 0x00111816, 0x00121917, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e1a, 0x00181e1a, 0x00181e1a, 0x00181e18, 0x00181e18, 0x00182018, 0x00182018, 0x001a2018, 0x00191e17, 0x0010140d, 0x0010110c, 0x0012110c, 0x0013100b, 0x00161109, 0x0019140a, 0x0020180c, 0x00221808, 0x00271a07, 0x0031220a, 0x0039270f, 0x00402c10, 0x004d340e, 0x005c3d0d, 0x00704c08, 0x00986f1c, 0x00c4a72e, 0x00cab41e, 0x00ccba10, 0x00cabd0c, 0x00c8bd0d, 0x00c8bf09, 0x00cbbf0a, 0x00ccbc10, 0x00c5ac0d, 0x00bf9d08, 0x00bb9305, 0x00bc8c08, 0x00b88408, 0x00b37e0d, 0x00a07008, 0x008a5c00, 0x007c5000, 0x006f4500, 0x00684200, 0x005f3c00, 0x00593a00, 0x00573801, 0x00543605, 0x00513407, 0x004f3108, 0x004e3109, 0x004b300a, 0x00482f0c, 0x00442e0c, 0x00402c09, 0x003e2a09, 0x003e2708, 0x003d2409, 0x003c240a, 0x00392409, 0x00362407, 0x00342107, 0x00321e04, 0x00321e04, 0x00311d04, 0x002f1d05, 0x002f1c05, 0x00301d06, 0x00301d06, 0x00301d06, 0x00301d06, 0x00301d06, 0x00311d04, 0x00311d04, 0x00321c04, 0x00311d04, 0x00301e05, 0x00301e06, 0x00321e06, 0x00331e06, 0x00321e04, 0x00321d06, 0x00341d08, 0x00341e08, 0x00352006, 0x00341f05, 0x00341e08, 0x00331d09, 0x002f1b08, 0x002d1b08, 0x002c1c08, 0x002c1c08, 0x002c1b08, 0x002a1b0a, 0x00291809, 0x0028170a, 0x0028170b, 0x0028170b, 0x0028170b, 0x0028170b, 0x0028170a, 0x00281709, 0x00281709, 0x00281809, 0x0029190b, 0x00251709, 0x00241809, 0x00231809, 0x00231809, 0x00231708, 0x00241608, 0x00251709, 0x00241608, 0x00231708, 0x0023160a, 0x0020150a, 0x0020150a, 0x0020140b, 0x0021140c, 0x0021140c, 0x0021140c, 0x0021140a, 0x00221608, 0x00221608, 0x00211507, 0x00211507, 0x00221509, 0x00201408, 0x00201307, 0x00201307, 0x001f1409, 0x001f1409, 0x001f1409, 0x001f1409, 0x00201307, 0x00201307, 0x001e1407, 0x001d1407, 0x001d1308, 0x001e1308, 0x001e1308, 0x001d1308, 0x001a1206, 0x00181306, 0x001a1306, 0x001c1307, 0x001c1307, 0x001d1207, 0x001d1207, 0x001e1308, 0x001c1106, 0x001a1204, 0x00191304, 0x00191304, 0x00191304, 0x001b1204, 0x001b1204, 0x001b1204, 0x001b1204, 0x001b1308, 0x001b1309, 0x001a1307, 0x00191306, 0x001c1206, 0x001d1207, 0x001d1207, 0x001d1205, 0x00201508, 0x001b1206, 0x001c1307, 0x001e1409, 0x001e1409, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1304, 0x001d1304, 0x001e1405, 0x001e1406, 0x001f1408, 0x001d1205, 0x001d1205, 0x001d1205, 0x001c1409, 0x001c140a, 0x001c1309, 0x001c1208, 0x001c1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1508, 0x001d1508, 0x001c1508, 0x001c1405, 0x001c1405, 0x001f1608, 0x001f150a, 0x00201508, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00221608, 0x00221608, 0x00241608, 0x00241608, 0x00251709, 0x00251709, 0x00261808, 0x002b1809, 0x00301c0a, 0x00321c09, 0x00331c08, 0x00381f09, 0x003d240c, 0x0040280c, 0x00442a0d, 0x004c300d, 0x0052340c, 0x0059380c, 0x00613a08, 0x0073460c, 0x0084500d, 0x00a36a1b, 0x00b47817, 0x00ae730c, 0x00a86e04, 0x00a86e00, 0x00a66c00, 0x00a86d00, 0x00aa7000, 0x00a97000, 0x00a56e00, 0x00a46c00, 0x00a66c00, 0x00aa6c00, 0x00ac730c, 0x00bc871f, 0x00c69722, 0x00cca51d, 0x00ccae16, 0x00ccb013, 0x00ccb015, 0x00ccac15, 0x00cca515, 0x00c99c14, 0x00c38f16, 0x00ad730b, 0x009a5b00, 0x00975704, 0x00945600, 0x00975d00, 0x00a06c05, 0x00ad7e09, 0x00bb8e13, 0x00c09816, 0x00c7a318, 0x00caac13, 0x00ccb014, 0x00ccb113, 0x00ccb212, 0x00ccb211, 0x00ccb310, 0x00ccb40e, 0x00cbb40d, 0x00cbb40d, 0x00cbb40d, 0x00cab40b, 0x00c8b408, 0x00c9b407, 0x00cbac07, 0x00c8a208, 0x00c9a30c, 0x00cbb012, 0x00cab913, 0x00c9bb0e, 0x00cbb90d, 0x00c9b50f, 0x00b9980c, 0x00986e00, 0x00805403, 0x00684103, 0x00543407, 0x004a2f09, 0x00432a0a, 0x003d270c, 0x00321f07, 0x00281804, 0x00251906, 0x00231b0a, 0x001a1506, 0x00181408, 0x00111009, 0x00101208, 0x00121108, 0x0011110a, 0x00101007, 0x00101008, 0x0010110c, 0x0010130e, 0x00101510, 0x00101511, 0x000e1813, 0x00101816, 0x00121918, 0x00121918, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e18, 0x00182019, 0x00182019, 0x0019201a, 0x001b2018, 0x001c1f18, 0x00181a14, 0x0011130c, 0x0012110b, 0x0013120b, 0x0014110a, 0x00161108, 0x001b1309, 0x0020170b, 0x00231808, 0x002c1e0a, 0x0034240a, 0x003a280c, 0x00412c0c, 0x004e360e, 0x005c3e0e, 0x00744d0f, 0x00a27b21, 0x00c9ad2c, 0x00cbb818, 0x00ccbc0c, 0x00cabd0b, 0x00cabd0d, 0x00c9bc0a, 0x00cbbc0c, 0x00cab411, 0x00b8940c, 0x00a47503, 0x009f6b01, 0x00945d00, 0x008f5800, 0x00855600, 0x00795000, 0x006c4700, 0x00603f01, 0x005b3a05, 0x00583907, 0x00543806, 0x004e3405, 0x004d3507, 0x004b3407, 0x004c340b, 0x0048300b, 0x00442b08, 0x00442a0a, 0x0040270b, 0x003c2508, 0x003a2407, 0x00382408, 0x00382308, 0x00372008, 0x00351e08, 0x00331f08, 0x00331f08, 0x00331f08, 0x00311c06, 0x00311c08, 0x00301d08, 0x002d1c07, 0x002b1b06, 0x002c1b07, 0x002c1c08, 0x002c1c08, 0x002c1c08, 0x002e1b08, 0x002e1b08, 0x002d1b06, 0x002c1a05, 0x002c1a05, 0x002c1906, 0x002b1804, 0x002e1c06, 0x002f1c07, 0x00301d08, 0x00301d08, 0x00301c07, 0x00301c05, 0x002f1c04, 0x002e1904, 0x00301c08, 0x002f1c08, 0x002d1a09, 0x002c190a, 0x002c190a, 0x002b180a, 0x0028180c, 0x0028180c, 0x00261609, 0x0025150a, 0x0027150a, 0x0028150b, 0x0028150b, 0x0027160b, 0x0025170a, 0x00241608, 0x00241608, 0x00241608, 0x00241608, 0x0026180c, 0x0026180c, 0x0024170a, 0x00231409, 0x00221509, 0x00221509, 0x00221509, 0x0023160a, 0x0023160a, 0x0023160a, 0x00211408, 0x00201409, 0x00201409, 0x0020150a, 0x0020150a, 0x0020150a, 0x00201508, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00211408, 0x00201408, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201307, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001f1408, 0x001c1205, 0x001c1305, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1409, 0x001c1106, 0x001b1005, 0x001c1106, 0x001d1208, 0x001e1308, 0x001e1308, 0x001c1408, 0x001d1408, 0x001f1307, 0x001e1407, 0x001e1407, 0x001e1508, 0x001b1206, 0x001c1307, 0x0020150a, 0x001e1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001d1205, 0x001c1204, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1306, 0x001c1307, 0x001c1408, 0x001e1308, 0x001e1308, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001c1305, 0x001c1305, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1306, 0x001e1407, 0x001f1407, 0x00221509, 0x0024170b, 0x0024160a, 0x0024160a, 0x0024160a, 0x00241608, 0x00281809, 0x002b1b08, 0x002e1b08, 0x00311c08, 0x00341c08, 0x003a2108, 0x003f2608, 0x0040280b, 0x00462b0b, 0x004c3008, 0x00543505, 0x00643f0b, 0x00754a10, 0x008a5910, 0x00b88729, 0x00cb9e2a, 0x00cb9e20, 0x00c89918, 0x00c29117, 0x00b58211, 0x00b37f0a, 0x00b17c08, 0x00b17b0b, 0x00b17c0c, 0x00b27c0b, 0x00b7820d, 0x00c6921b, 0x00c89f1e, 0x00c9a81f, 0x00ccac1b, 0x00ccb014, 0x00ccb30e, 0x00ccb409, 0x00ccb409, 0x00cab40b, 0x00cbb410, 0x00ccb214, 0x00cca91a, 0x00b88913, 0x00945b00, 0x008b5107, 0x007f4800, 0x007d4902, 0x00804f01, 0x00875703, 0x00905f02, 0x009c6c05, 0x00a8780b, 0x00b4870c, 0x00c19515, 0x00c89e18, 0x00caa418, 0x00cba714, 0x00ccac13, 0x00ccaf10, 0x00ccb30f, 0x00ccb60f, 0x00cbb40c, 0x00cab40b, 0x00cab409, 0x00cab308, 0x00caab0c, 0x00c9a00b, 0x00c8a30f, 0x00cbb114, 0x00c9ba12, 0x00c8bb0b, 0x00c8bb07, 0x00c8ba0a, 0x00c9ad15, 0x00a67c04, 0x008a5c04, 0x00754c08, 0x005c3b03, 0x00503305, 0x00462c08, 0x003e270a, 0x00362309, 0x002b1c04, 0x00251804, 0x00221a09, 0x001a1506, 0x00181407, 0x00141407, 0x00121108, 0x00101108, 0x00101009, 0x000f1008, 0x0010120a, 0x0011120c, 0x0010130e, 0x00101411, 0x000f1411, 0x000d1712, 0x000f1816, 0x00101818, 0x00121918, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e18, 0x00182019, 0x00182019, 0x0019201a, 0x001c1f18, 0x001d1e18, 0x00181a14, 0x0010120c, 0x0012120c, 0x0014120c, 0x0014110b, 0x00181108, 0x001d160c, 0x0020160b, 0x00231707, 0x002e200a, 0x0037260a, 0x003c290d, 0x00442e0a, 0x0051390e, 0x00604010, 0x007e5817, 0x00af8828, 0x00cbb028, 0x00ccb918, 0x00ccbc0c, 0x00cbbe0b, 0x00cbbc0c, 0x00ccbb0c, 0x00ccb710, 0x00ba9b06, 0x009c7400, 0x00885802, 0x00835200, 0x007f4c04, 0x00784802, 0x006c4400, 0x00603e00, 0x005b3c02, 0x00543804, 0x00533607, 0x00503408, 0x004c3408, 0x00483006, 0x00452f06, 0x00412c04, 0x00432e08, 0x00402906, 0x003c2706, 0x003c2608, 0x003b2408, 0x00382108, 0x00342006, 0x00341f06, 0x00331f08, 0x00331d08, 0x00321d09, 0x00301d08, 0x00301d08, 0x002e1c06, 0x002c1904, 0x002c1906, 0x002c1a06, 0x002a1a06, 0x00281905, 0x00291808, 0x002b1909, 0x002b1909, 0x002b1909, 0x002c1808, 0x002c1808, 0x002a1807, 0x00291807, 0x00291806, 0x00281804, 0x00281603, 0x002a1806, 0x002c1a08, 0x002c1a08, 0x002c1a08, 0x002e1b08, 0x002f1c07, 0x002e1c04, 0x002c1904, 0x002c1a07, 0x002c1a08, 0x002c1808, 0x002c1809, 0x002c190c, 0x002b170c, 0x0028150b, 0x0027160b, 0x0025150a, 0x0025150a, 0x0027150b, 0x0028150b, 0x0027160b, 0x0025170b, 0x0024180a, 0x00231708, 0x00231708, 0x00231708, 0x00231708, 0x0024160a, 0x0024160a, 0x0025170b, 0x00231409, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00211408, 0x00211408, 0x00201508, 0x001f1608, 0x001f1608, 0x001f1608, 0x00201508, 0x00201408, 0x00211408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001e1407, 0x001d1407, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1308, 0x001d1207, 0x001d1207, 0x001d1207, 0x001f1208, 0x001f1308, 0x001e1308, 0x001d1308, 0x001f1308, 0x00201307, 0x001e1407, 0x001e1407, 0x001e1508, 0x001b1206, 0x001c1307, 0x001f1409, 0x0020150a, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1406, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1306, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x00201408, 0x00221509, 0x0024160a, 0x0024160a, 0x0024160a, 0x00241608, 0x00261708, 0x002a1a09, 0x002c1906, 0x00311c08, 0x00341c07, 0x00381f08, 0x003b2307, 0x003f2609, 0x00452a0c, 0x004b3008, 0x00533303, 0x00603c08, 0x0072480e, 0x00906314, 0x00c49b2e, 0x00ccaf22, 0x00ccb015, 0x00ccb011, 0x00ccac18, 0x00cba91e, 0x00caa718, 0x00caa517, 0x00caa419, 0x00cba51c, 0x00cba619, 0x00cba818, 0x00ccaa1a, 0x00ccad17, 0x00cbb016, 0x00cbb211, 0x00cbb30d, 0x00cbb40c, 0x00cbb50a, 0x00c8b706, 0x00c7b607, 0x00c8b70b, 0x00cbb40e, 0x00cbab14, 0x00b3840a, 0x00915b00, 0x007c4b02, 0x00704000, 0x006c3e01, 0x006f4302, 0x00714501, 0x007a4d03, 0x00845504, 0x00895800, 0x00905c00, 0x00986402, 0x009d6901, 0x00ac780a, 0x00b7840e, 0x00c08f12, 0x00c69614, 0x00cba017, 0x00cba615, 0x00cba910, 0x00ccab10, 0x00ccac0e, 0x00ccac0c, 0x00c9a60a, 0x00c89c07, 0x00c9a30a, 0x00cab310, 0x00cab911, 0x00cabb09, 0x00c8bb05, 0x00c8bb09, 0x00cbb314, 0x00b48e0c, 0x00906201, 0x0081560b, 0x00644004, 0x00533402, 0x00482d05, 0x0040290a, 0x0038240b, 0x002c1d05, 0x00241602, 0x00221808, 0x00211a0c, 0x00171404, 0x00151405, 0x00121106, 0x00101108, 0x00101009, 0x000f1008, 0x00101009, 0x0010100a, 0x000f120d, 0x00101410, 0x000f1410, 0x000e1613, 0x000f1816, 0x00101818, 0x00121918, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e18, 0x00181f19, 0x0019201a, 0x001b211b, 0x001c2019, 0x001c1d17, 0x00161711, 0x0014140e, 0x0014120c, 0x0014120c, 0x0015120b, 0x001b140c, 0x0020160c, 0x0021160b, 0x00271b0b, 0x0031230b, 0x00372708, 0x003f2b0c, 0x0048330c, 0x00543c10, 0x0062440f, 0x00866118, 0x00b9942a, 0x00ccb222, 0x00cbb916, 0x00ccbc0f, 0x00ccbc0c, 0x00ccbb0c, 0x00cbb70e, 0x00c7a911, 0x00a27d00, 0x00885f00, 0x00784e00, 0x00724b01, 0x00694402, 0x00603d00, 0x00573b00, 0x00513801, 0x004f3707, 0x004c3408, 0x004c3208, 0x004c320a, 0x0048310b, 0x00432e08, 0x003f2c07, 0x003c2805, 0x003c2808, 0x003a2507, 0x00382305, 0x00382206, 0x00372108, 0x00342008, 0x00321d07, 0x00301d06, 0x00301d08, 0x002f1c08, 0x002d1b08, 0x002e1b08, 0x002e1b08, 0x002c1a07, 0x002b1805, 0x00291807, 0x00281807, 0x00281907, 0x00281a07, 0x00281808, 0x00281809, 0x0028180a, 0x0028180a, 0x00291808, 0x00291808, 0x00281707, 0x00271706, 0x00271706, 0x00241504, 0x00241403, 0x00251605, 0x00281809, 0x0029190b, 0x002b1909, 0x002b1908, 0x002c1a07, 0x002d1c06, 0x002b1a06, 0x002c1a08, 0x002a1808, 0x00291808, 0x00291808, 0x002b180b, 0x0028170b, 0x0025150a, 0x0024160a, 0x00241509, 0x00241409, 0x0025150a, 0x0025150a, 0x0024160a, 0x0023160a, 0x0023160a, 0x00231708, 0x00231708, 0x00231708, 0x00231708, 0x00241409, 0x00241409, 0x00231408, 0x00221408, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00201408, 0x00201408, 0x001f1608, 0x001f1608, 0x001f1608, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001d1306, 0x001e1407, 0x00201508, 0x00201508, 0x00201508, 0x001e1407, 0x001d1306, 0x001f1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001d1207, 0x001d1207, 0x001d1207, 0x001f1208, 0x001f1308, 0x001e1308, 0x001d1308, 0x001f1308, 0x00201307, 0x001e1407, 0x001e1407, 0x001e1508, 0x001b1206, 0x001c1307, 0x0020140a, 0x0020160b, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1306, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1306, 0x001b1407, 0x001c1308, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x00201307, 0x00221509, 0x00241409, 0x00241409, 0x0024160a, 0x00241608, 0x00271709, 0x00281808, 0x002c1808, 0x00301b08, 0x00341c08, 0x00381f08, 0x003b2208, 0x003e240a, 0x0044290d, 0x00492e0a, 0x00533307, 0x005f3809, 0x006d4409, 0x00916414, 0x00c7a02c, 0x00c9b418, 0x00cab70c, 0x00cab808, 0x00cab60f, 0x00cbb412, 0x00cbb40e, 0x00ccb50f, 0x00ccb412, 0x00ccb514, 0x00ccb512, 0x00ccb50e, 0x00cbb40c, 0x00cbb40e, 0x00cab40e, 0x00cab40d, 0x00c9b50c, 0x00c8b60c, 0x00c8b708, 0x00c7b704, 0x00c8b708, 0x00cbb50c, 0x00ccb413, 0x00caa614, 0x00a87804, 0x00885200, 0x00734600, 0x00643700, 0x00603601, 0x005c3500, 0x005c3801, 0x00613c04, 0x00694204, 0x00714707, 0x00784b08, 0x0082510c, 0x0088540a, 0x008d5708, 0x00935a06, 0x00986008, 0x00a2690c, 0x00a9720d, 0x00af7c0c, 0x00b98b0c, 0x00c29510, 0x00c89c12, 0x00cba010, 0x00c5980d, 0x00c7940c, 0x00c8a00c, 0x00ccb512, 0x00cbb910, 0x00cbba09, 0x00cabc06, 0x00c8bb0a, 0x00ccb412, 0x00c19e12, 0x009c7003, 0x00875908, 0x006e4808, 0x00563501, 0x00482d02, 0x00402908, 0x00392508, 0x00301f08, 0x00271703, 0x00211507, 0x00241b0d, 0x00181505, 0x00141405, 0x00131107, 0x00121108, 0x00101008, 0x00101108, 0x00101108, 0x00101009, 0x0010110c, 0x00111310, 0x000f1412, 0x000e1514, 0x000e1716, 0x00101817, 0x00101818, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e18, 0x00181f19, 0x0019201a, 0x001b211a, 0x001f241c, 0x00181a14, 0x0014130c, 0x0014120c, 0x0014120c, 0x0014130a, 0x0018140c, 0x001d170d, 0x001f160b, 0x0020160b, 0x002b1d0d, 0x00322409, 0x00392808, 0x00422f0d, 0x004c380f, 0x00563d0e, 0x00684b11, 0x008d6919, 0x00c19e2b, 0x00cbb31c, 0x00cbba14, 0x00cabc0f, 0x00cbbc0b, 0x00cab90c, 0x00ccb410, 0x00b8970c, 0x00926600, 0x007f5304, 0x006e4a04, 0x00624201, 0x00583e03, 0x00503800, 0x004c3804, 0x00483504, 0x00483408, 0x00473008, 0x00482f0a, 0x00452c09, 0x00402b0a, 0x003c2808, 0x00382605, 0x00342304, 0x00342307, 0x00322006, 0x00301f05, 0x00301f04, 0x00311d08, 0x00301c08, 0x002e1c08, 0x002e1c08, 0x002c1c09, 0x002a1b0a, 0x002a1808, 0x002c1908, 0x002c1908, 0x00281805, 0x00281604, 0x00261605, 0x00251605, 0x00251705, 0x00241705, 0x00241604, 0x00241605, 0x00251706, 0x00261807, 0x00281809, 0x00281809, 0x00271708, 0x00251709, 0x00261709, 0x00231407, 0x00221406, 0x00221308, 0x00231408, 0x0025160a, 0x0028180b, 0x002b180b, 0x002b1909, 0x002a1b08, 0x00281806, 0x00281808, 0x00271708, 0x00281808, 0x00281809, 0x00261608, 0x0027160a, 0x0024160a, 0x0023160a, 0x00231509, 0x00221509, 0x0024150a, 0x0024160a, 0x0023160a, 0x0023160a, 0x0022170a, 0x00231708, 0x00231708, 0x00231708, 0x00231708, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00201408, 0x001f1407, 0x001c1407, 0x001e1508, 0x001c1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1408, 0x001e1407, 0x001f1408, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001d1207, 0x001c1106, 0x001d1207, 0x001f1208, 0x001f1308, 0x001e1308, 0x001d1308, 0x001f1308, 0x00201307, 0x001e1407, 0x001e1407, 0x001e1508, 0x001b1206, 0x001c1307, 0x0020150a, 0x0020150a, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001c1306, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1306, 0x001b1407, 0x001c1307, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x00211409, 0x00221509, 0x00241409, 0x00241409, 0x0024160a, 0x00241608, 0x0028180b, 0x00291808, 0x002c1a08, 0x00301b08, 0x00321c08, 0x00361e08, 0x003b220a, 0x003f250e, 0x00442810, 0x00482c0b, 0x00523209, 0x005e380c, 0x0070460c, 0x00986c19, 0x00cba530, 0x00c9b417, 0x00cab70b, 0x00cab808, 0x00cab70d, 0x00c8b60c, 0x00c8b709, 0x00c9b80a, 0x00c9b80c, 0x00cab80d, 0x00cab80c, 0x00c9b809, 0x00c8b807, 0x00c8b708, 0x00c9b608, 0x00c9b608, 0x00c8b708, 0x00c8b806, 0x00c8b704, 0x00c9b404, 0x00cbb10b, 0x00cbad0f, 0x00cba80f, 0x00c0950e, 0x009d6902, 0x00854f04, 0x006c4401, 0x005b3400, 0x00583306, 0x00523004, 0x004c3006, 0x004e3307, 0x00503205, 0x00543304, 0x00593705, 0x005d3a04, 0x00673d04, 0x0074460a, 0x007b4a09, 0x00814e0b, 0x0088530c, 0x008d5608, 0x008f5806, 0x00925c03, 0x00986300, 0x009c6900, 0x00a87402, 0x00b07708, 0x00b57b07, 0x00c49812, 0x00ccb319, 0x00cbb811, 0x00cbba09, 0x00cabc06, 0x00c9bc0b, 0x00ccb810, 0x00caaa14, 0x00a87d05, 0x00885800, 0x00714a08, 0x00593a02, 0x004b3003, 0x00432c09, 0x003c280b, 0x0036230b, 0x002c1b06, 0x00221405, 0x0021180b, 0x001c1908, 0x00141405, 0x00141207, 0x00121107, 0x00101008, 0x00101108, 0x00101108, 0x00101009, 0x0010110c, 0x0011140f, 0x00101412, 0x000e1514, 0x000e1716, 0x000f1817, 0x00101818, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181d18, 0x00182018, 0x00182018, 0x001a2018, 0x001d2119, 0x00161710, 0x0012120b, 0x0013120a, 0x0014120a, 0x0014130a, 0x0018150c, 0x001c170b, 0x001c1407, 0x00211907, 0x002c210b, 0x00322508, 0x003a2a06, 0x0043310d, 0x004c3a0e, 0x00583d0c, 0x00714f11, 0x0099731c, 0x00c8a62a, 0x00ccb518, 0x00caba11, 0x00c9bc0e, 0x00cbbc0b, 0x00ccb80b, 0x00c7ac0f, 0x00a78204, 0x00875b02, 0x00734b05, 0x00614204, 0x00573c03, 0x004f3907, 0x00483606, 0x00443408, 0x00423207, 0x00443008, 0x00432d08, 0x00422b08, 0x003f2808, 0x003a2507, 0x00362306, 0x00322104, 0x00312004, 0x002f1f03, 0x002e1e03, 0x002f1d06, 0x00301c09, 0x002e1c0a, 0x002c1b0a, 0x002b1a09, 0x00291908, 0x00281808, 0x00271808, 0x00271708, 0x00261605, 0x00261605, 0x00251504, 0x00241604, 0x00241507, 0x00241508, 0x00241508, 0x00241608, 0x00241608, 0x00241608, 0x00241608, 0x00251708, 0x00251608, 0x00261608, 0x0027160b, 0x0026160a, 0x00241609, 0x0023140a, 0x00201308, 0x001c1008, 0x0020140c, 0x0023140c, 0x0026150c, 0x0028180c, 0x0029180b, 0x00281708, 0x00281608, 0x00281709, 0x00251407, 0x00261608, 0x00261608, 0x00241408, 0x00251509, 0x00241509, 0x00241509, 0x00231409, 0x00231409, 0x00241409, 0x00231509, 0x00221609, 0x00211609, 0x00211609, 0x00201608, 0x00201608, 0x00211609, 0x00211609, 0x00211408, 0x00221408, 0x00211408, 0x00231509, 0x00211408, 0x00201408, 0x00211408, 0x00211408, 0x00201508, 0x00201508, 0x00201508, 0x00201408, 0x001e1306, 0x001d1306, 0x001d1306, 0x001d1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001d1205, 0x00201408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1307, 0x001e1306, 0x001e1306, 0x001d1205, 0x001e1306, 0x001e1306, 0x001e1306, 0x001e1306, 0x001d1306, 0x001d1306, 0x001f1406, 0x001f1407, 0x001d1304, 0x001d1304, 0x001d1208, 0x001e1308, 0x001d1208, 0x001d1208, 0x001f1208, 0x001f1308, 0x001e1308, 0x001e1409, 0x001e1408, 0x001e1406, 0x001e1406, 0x001d1407, 0x001c1407, 0x001c1306, 0x001c1307, 0x001f1409, 0x001f1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201407, 0x00201407, 0x001f1406, 0x001d1406, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1406, 0x001c1407, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1408, 0x001d1306, 0x001e1306, 0x001f1408, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001f1306, 0x001f1306, 0x00201307, 0x00201307, 0x001f1406, 0x001f1406, 0x001f1406, 0x001f1406, 0x001f1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00231409, 0x00231409, 0x00241409, 0x00241409, 0x0025150b, 0x0026160a, 0x0028180a, 0x00281809, 0x002b1908, 0x002f1b08, 0x00311b08, 0x00341c07, 0x0039210a, 0x003d250e, 0x00432810, 0x00482c0c, 0x0051320b, 0x005e390f, 0x006f470d, 0x009a6f1b, 0x00cba42f, 0x00cbb11b, 0x00ccb50e, 0x00ccb609, 0x00ccb50e, 0x00cbb50d, 0x00cbb608, 0x00cbb807, 0x00cbb709, 0x00cbb60c, 0x00cbb70b, 0x00cbb709, 0x00cab608, 0x00cab608, 0x00cbb708, 0x00cbb60a, 0x00cbb409, 0x00cbb208, 0x00ccaf08, 0x00cba80b, 0x00c6a00d, 0x00c0950f, 0x00b6860a, 0x00a57003, 0x008c5500, 0x007b4604, 0x00694004, 0x00593400, 0x00563206, 0x00503007, 0x004a3008, 0x004b3009, 0x004c3009, 0x004c2f0a, 0x004b2f06, 0x004b3003, 0x004f3000, 0x00523200, 0x00573500, 0x00603c03, 0x00664104, 0x006c4606, 0x0074480b, 0x00804c0f, 0x0083500c, 0x00845308, 0x00875604, 0x00915a02, 0x00a16607, 0x00bd8f18, 0x00cbb01c, 0x00ccb811, 0x00ccbb0a, 0x00cbbc08, 0x00cabc0b, 0x00ccb911, 0x00ccb016, 0x00b2880b, 0x008c5c00, 0x00744c04, 0x005c3c00, 0x004d3204, 0x00442f0b, 0x003d290c, 0x0038240b, 0x002e1e07, 0x00251806, 0x00201507, 0x001f1808, 0x00181306, 0x00141307, 0x00121207, 0x00111108, 0x00111108, 0x00101108, 0x000f1108, 0x000f110a, 0x000f110d, 0x000e120f, 0x000e1513, 0x000c1413, 0x000e1614, 0x00101815, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00191d18, 0x00192018, 0x00192018, 0x001a2018, 0x001d2119, 0x0016170e, 0x00121209, 0x00131209, 0x00141309, 0x00151309, 0x0018160b, 0x001c160b, 0x001c1404, 0x00261e09, 0x00291f05, 0x00342608, 0x003c2c08, 0x0044320d, 0x004e3a0c, 0x005c400c, 0x00775111, 0x00a88026, 0x00ccae2c, 0x00ccb714, 0x00c8bb0e, 0x00c9bc0c, 0x00ccbc09, 0x00ccb70c, 0x00c0a10c, 0x009a7301, 0x00805503, 0x00694604, 0x00583c01, 0x004f3602, 0x00493406, 0x0046340a, 0x0041310a, 0x003f2e08, 0x003f2a07, 0x003d2605, 0x003c2404, 0x00392304, 0x00352004, 0x00332005, 0x00301f05, 0x00301e06, 0x002f1d05, 0x002d1c04, 0x002c1b07, 0x002c1b08, 0x002c1a09, 0x00291908, 0x00281808, 0x00261706, 0x00261706, 0x00241406, 0x00251607, 0x00241706, 0x00231605, 0x00211404, 0x00211404, 0x00211407, 0x00211408, 0x00231508, 0x00231508, 0x00231509, 0x00231509, 0x00231509, 0x0024160a, 0x00241609, 0x00241609, 0x0025150b, 0x0024140a, 0x0023140a, 0x0023150b, 0x0020140a, 0x001a1007, 0x001d140b, 0x0020140b, 0x0024140b, 0x0025150a, 0x00261508, 0x00271609, 0x00261508, 0x00261508, 0x00261508, 0x00251508, 0x00241608, 0x00241608, 0x00241608, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00231409, 0x00211509, 0x00201609, 0x00201709, 0x00201508, 0x00201508, 0x00201609, 0x00201609, 0x00201508, 0x00201508, 0x00201508, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1306, 0x001d1306, 0x001e1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1104, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1306, 0x001e1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001f1406, 0x001f1406, 0x001d1304, 0x001d1304, 0x001d1207, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1208, 0x001f1308, 0x001f1409, 0x001f1409, 0x001e1408, 0x001e1405, 0x001e1405, 0x001c1407, 0x001c1407, 0x001c1305, 0x001c1407, 0x001f1409, 0x001f1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201406, 0x00201406, 0x001f1406, 0x001e1506, 0x001d1507, 0x001c1508, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001d1205, 0x001d1306, 0x00201508, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x001f1406, 0x001f1406, 0x001f1406, 0x001f1406, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x00201508, 0x00221509, 0x00211408, 0x00201408, 0x00201408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x0025140c, 0x0027160b, 0x00271609, 0x0028180a, 0x002a1908, 0x002e1b08, 0x00311c0c, 0x00331c0b, 0x00361f08, 0x003c240c, 0x0042280f, 0x00482d0c, 0x0050330b, 0x005d3b0f, 0x0070490f, 0x009d741d, 0x00cba72f, 0x00cbb019, 0x00ccb60c, 0x00ccb707, 0x00ccb60b, 0x00cbb60c, 0x00ccb707, 0x00ccb804, 0x00ccb707, 0x00ccb508, 0x00ccb506, 0x00cbb406, 0x00cbb306, 0x00ccb10c, 0x00ccac0c, 0x00ccab10, 0x00caa40f, 0x00c4990c, 0x00bc8c08, 0x00b28004, 0x00a67300, 0x009c6500, 0x009c6000, 0x00945800, 0x00885204, 0x00784908, 0x00603801, 0x00583401, 0x00533104, 0x004d2e04, 0x00482c04, 0x00462c05, 0x00462a07, 0x00472c0a, 0x00482b09, 0x00482b05, 0x00482b03, 0x00482b01, 0x00482c00, 0x004c3003, 0x004f3302, 0x00523603, 0x00583806, 0x00613909, 0x00643c07, 0x00694108, 0x00704806, 0x007d4f03, 0x00925d08, 0x00be9220, 0x00ccb320, 0x00ccb811, 0x00ccbb0a, 0x00cbbc08, 0x00ccbc0c, 0x00ccbc11, 0x00ccb414, 0x00bc960f, 0x00936200, 0x007a4f05, 0x005f3e02, 0x00503404, 0x00442f09, 0x003e2b0b, 0x00392508, 0x002f1f06, 0x00251804, 0x001f1504, 0x00201808, 0x001b1408, 0x00151407, 0x00121207, 0x00121109, 0x00121109, 0x00101008, 0x000e1108, 0x000e1109, 0x000e110b, 0x000d110e, 0x000e1612, 0x000a1410, 0x000d1512, 0x000f1714, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181f19, 0x001a1e19, 0x001a2018, 0x001a2018, 0x001b2118, 0x001b1f14, 0x0013150c, 0x00111109, 0x00121109, 0x00131208, 0x00151308, 0x001a170c, 0x001c150a, 0x00201606, 0x00281f08, 0x002d2208, 0x0035270a, 0x003d2d09, 0x0046330c, 0x00503b0c, 0x0064450c, 0x007e5812, 0x00b48f2d, 0x00ccaf25, 0x00ccb813, 0x00c8bb0d, 0x00c9bc0c, 0x00ccbc09, 0x00ccb411, 0x00b9960d, 0x00916801, 0x00774e01, 0x00614301, 0x004f3800, 0x00483300, 0x00443104, 0x00433008, 0x003f2d08, 0x003c2a06, 0x003c2605, 0x003b2304, 0x00392004, 0x00351f04, 0x00341e08, 0x00311d08, 0x00301d08, 0x002e1c08, 0x002d1c08, 0x002c1a08, 0x002a1906, 0x00281806, 0x00281806, 0x00281808, 0x00281807, 0x00251708, 0x00251608, 0x00241507, 0x00241608, 0x00221708, 0x00211607, 0x00201506, 0x00201406, 0x00211509, 0x00201509, 0x00201509, 0x0021160a, 0x00201409, 0x00201409, 0x00201409, 0x00211509, 0x0023150a, 0x0024160b, 0x0024150b, 0x00211309, 0x00201309, 0x0021140c, 0x0020150b, 0x00191208, 0x00191208, 0x001c1308, 0x001e1408, 0x00201408, 0x00221306, 0x00241408, 0x00231408, 0x00241408, 0x00251509, 0x00241509, 0x00241509, 0x00241509, 0x00241509, 0x00241409, 0x00241409, 0x00231409, 0x00231409, 0x00231409, 0x00221409, 0x00211508, 0x00201508, 0x001f1608, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x00201408, 0x00201408, 0x00201408, 0x00201308, 0x00201408, 0x001f1408, 0x001f1408, 0x001e1408, 0x001e1407, 0x001e1407, 0x001e1306, 0x001e1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001d1306, 0x001e1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001f1306, 0x001e1306, 0x001d1306, 0x001d1305, 0x001d1305, 0x001d1306, 0x001d1306, 0x001e1306, 0x001d1306, 0x001f1406, 0x001f1406, 0x001d1304, 0x001d1304, 0x001d1207, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1208, 0x001f1308, 0x001f1409, 0x001f1409, 0x001e1408, 0x001e1405, 0x001e1405, 0x001c1407, 0x001c1407, 0x001c1305, 0x001c1407, 0x001f1409, 0x001f1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201406, 0x00201406, 0x001f1406, 0x001d1405, 0x001c1406, 0x001c1406, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1306, 0x001e1306, 0x001f1408, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201308, 0x00211408, 0x00211408, 0x00201507, 0x00201506, 0x00201506, 0x00201506, 0x00201508, 0x00201508, 0x00211609, 0x0022170a, 0x0023170a, 0x0023160a, 0x00221509, 0x00211408, 0x00211408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x0025140c, 0x0027160b, 0x0027160a, 0x0028180a, 0x002a1908, 0x002e1b09, 0x00311c0c, 0x00331c0b, 0x00341e08, 0x0039210b, 0x0042280e, 0x00482d0a, 0x0050340b, 0x005e3c0e, 0x00714b0d, 0x00a37a20, 0x00caa82b, 0x00cbb114, 0x00c9b608, 0x00c9b804, 0x00c9b80b, 0x00c9b80c, 0x00cab607, 0x00ccb508, 0x00ccb20a, 0x00ccb008, 0x00ccaf07, 0x00cbab08, 0x00c8a707, 0x00c49e0a, 0x00bf9208, 0x00b98404, 0x00b37800, 0x00a86b00, 0x00a16600, 0x009c6400, 0x009c6603, 0x00a56c0b, 0x00ae710d, 0x009e6405, 0x00845202, 0x00774d0c, 0x005c3802, 0x00523001, 0x004f2f05, 0x004a2c05, 0x00452a04, 0x00442906, 0x00422707, 0x00432709, 0x00432708, 0x00432607, 0x00432607, 0x00432607, 0x00432608, 0x00452907, 0x00482c07, 0x004b3009, 0x004e310b, 0x0050320a, 0x00533508, 0x00573a08, 0x005f4006, 0x006e4804, 0x00855509, 0x00bc9327, 0x00ccb525, 0x00ccb813, 0x00ccba0a, 0x00ccbc08, 0x00ccbc0c, 0x00ccbc0e, 0x00ccb80e, 0x00c2a20f, 0x00976b00, 0x007c5003, 0x00623f00, 0x00513402, 0x00453008, 0x003e2c09, 0x003a2506, 0x00302004, 0x00271902, 0x00201402, 0x00201607, 0x001c1609, 0x00171408, 0x00131108, 0x00111009, 0x00101009, 0x000f1008, 0x000d1008, 0x000d1008, 0x000e100b, 0x000e110e, 0x000e1512, 0x000a1410, 0x000d1512, 0x000f1714, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181f19, 0x001a1f19, 0x001b2018, 0x001b2018, 0x001c2118, 0x00181c11, 0x0010140a, 0x00101109, 0x00101009, 0x00121009, 0x00151308, 0x001b140c, 0x001b1107, 0x00241809, 0x002c1f09, 0x00302208, 0x003a280c, 0x00422e0b, 0x0049340e, 0x00543c0c, 0x006a480c, 0x00876014, 0x00bf9c34, 0x00cbb121, 0x00cbb812, 0x00c9bb0d, 0x00cabc0b, 0x00ccbb0a, 0x00ccb014, 0x00ac8408, 0x00895d03, 0x006e4800, 0x00583f00, 0x00473800, 0x00423200, 0x00402e02, 0x003c2b04, 0x00382804, 0x00352503, 0x00362202, 0x00372004, 0x00351d04, 0x00321c06, 0x00301c08, 0x002c1908, 0x002b1908, 0x002b1a0a, 0x002a1908, 0x00281806, 0x00281806, 0x00261805, 0x00261804, 0x00261804, 0x00241605, 0x00231508, 0x00231508, 0x00231508, 0x00221608, 0x00201608, 0x001f1407, 0x00201508, 0x00201508, 0x001f1409, 0x0020150a, 0x001f1409, 0x0020160b, 0x001f1409, 0x0020140a, 0x0020150a, 0x0020150a, 0x00201409, 0x0021140a, 0x0022150b, 0x00201409, 0x001f1108, 0x001f1208, 0x001c1409, 0x00191307, 0x00151205, 0x00181307, 0x001b1407, 0x001e1407, 0x00201305, 0x00221408, 0x00221408, 0x00211408, 0x00211408, 0x00221509, 0x00211509, 0x00211509, 0x00211509, 0x00241409, 0x00241409, 0x00231408, 0x00221408, 0x00221408, 0x00221408, 0x00201408, 0x00201508, 0x001f1508, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201408, 0x00201307, 0x00201307, 0x001f1307, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1306, 0x001e1306, 0x001e1306, 0x001e1407, 0x001e1407, 0x001f1406, 0x001f1406, 0x001d1304, 0x001d1304, 0x001d1207, 0x001d1207, 0x001e1308, 0x001e1308, 0x001f1208, 0x001f1308, 0x001f1409, 0x001f1409, 0x001e1408, 0x001e1405, 0x001e1405, 0x001c1407, 0x001c1407, 0x001c1305, 0x001c1407, 0x001f1409, 0x001f1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201406, 0x00201406, 0x001e1405, 0x001c1405, 0x001c1405, 0x001b1405, 0x001c1406, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00201508, 0x00201508, 0x00201609, 0x0021170a, 0x0022160a, 0x00221509, 0x00211408, 0x00211408, 0x00211408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x0025140c, 0x0027160b, 0x0027160b, 0x0028180b, 0x002a180a, 0x002e1b09, 0x00311c0c, 0x00331c0b, 0x00341d08, 0x0039210b, 0x0041270e, 0x00482c0a, 0x00523409, 0x005e3c0c, 0x00734c0c, 0x00a88022, 0x00cba828, 0x00cbb113, 0x00cbb509, 0x00ccb70b, 0x00ccb712, 0x00cab410, 0x00cab10a, 0x00cbac0c, 0x00c9a40c, 0x00c89c0a, 0x00c49407, 0x00bb8b04, 0x00ae7d00, 0x00a87200, 0x00a56b00, 0x00a66800, 0x00a86802, 0x00ac6d0a, 0x00b17614, 0x00b38017, 0x00be8f20, 0x00c69824, 0x00ca9a26, 0x00b4801a, 0x00855402, 0x00744a0b, 0x00583603, 0x004d2e00, 0x004a2c04, 0x00442905, 0x00412805, 0x00402707, 0x003f2408, 0x003f2408, 0x003d2306, 0x003f2507, 0x00402609, 0x0040260c, 0x0040250c, 0x003f2508, 0x00412808, 0x00452c09, 0x00482f0c, 0x004a300c, 0x004a3108, 0x00503709, 0x00573c08, 0x0064440b, 0x007c520d, 0x00aa841f, 0x00c9b024, 0x00ccb611, 0x00ccb909, 0x00ccbc08, 0x00cbbc09, 0x00cabc0a, 0x00ccbb04, 0x00caae0e, 0x00a47c06, 0x007f5303, 0x00684201, 0x00553803, 0x00483308, 0x00412d08, 0x003c2604, 0x00332002, 0x002d1d04, 0x00231602, 0x001e1506, 0x001e170a, 0x00181409, 0x00141108, 0x0013100a, 0x0011100a, 0x000f1008, 0x000c1007, 0x000d1008, 0x000d100a, 0x000e120f, 0x000d1411, 0x000a1410, 0x000c1512, 0x000e1613, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181f19, 0x00191f19, 0x001b2019, 0x001b2019, 0x001c2118, 0x00171b11, 0x0010140a, 0x00101009, 0x00101009, 0x00121009, 0x00161309, 0x0019140a, 0x001d1108, 0x00271a0b, 0x002c1f0a, 0x00312108, 0x003c280c, 0x0043300c, 0x0049330c, 0x00573c0c, 0x006c480c, 0x008f6816, 0x00c2a332, 0x00cab420, 0x00cab912, 0x00c9bc0c, 0x00ccbd0a, 0x00ccba0c, 0x00c6a611, 0x00a07403, 0x00825602, 0x00684400, 0x00523c00, 0x00443600, 0x003f3000, 0x003c2c00, 0x00382804, 0x00362505, 0x00332303, 0x00332002, 0x00321e03, 0x00321c08, 0x00301c08, 0x002c1a08, 0x00281808, 0x00271809, 0x00271809, 0x00271808, 0x00261707, 0x00261807, 0x00241706, 0x00241605, 0x00241706, 0x00231606, 0x00221508, 0x00211407, 0x00211508, 0x00211508, 0x00201407, 0x00201407, 0x00201508, 0x00201508, 0x001c1206, 0x001f1408, 0x001e1308, 0x00201509, 0x001e1308, 0x00201509, 0x00201509, 0x001f1408, 0x001f1308, 0x00201408, 0x00201408, 0x00201408, 0x001f1208, 0x001e1207, 0x001c1408, 0x00181407, 0x00141104, 0x00161306, 0x00191407, 0x001c1407, 0x001e1307, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201609, 0x00201609, 0x00201609, 0x00201609, 0x00241409, 0x00241409, 0x00231409, 0x00221408, 0x00221408, 0x00221408, 0x00221409, 0x0022160a, 0x00221609, 0x00221409, 0x00211509, 0x00221609, 0x00211609, 0x00201508, 0x00201508, 0x00201609, 0x00201608, 0x00201408, 0x00201408, 0x001f1306, 0x001f1307, 0x001f1408, 0x001f1408, 0x001e1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001f1408, 0x001e1306, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201408, 0x00201307, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1406, 0x001f1406, 0x001d1304, 0x001d1305, 0x001d1205, 0x001d1206, 0x001e1308, 0x001f1308, 0x00201208, 0x00201308, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1406, 0x001f1406, 0x001d1407, 0x001d1407, 0x001c1305, 0x001c1306, 0x00201409, 0x001e1408, 0x001f1408, 0x00201508, 0x00211408, 0x00201408, 0x001f1305, 0x001f1305, 0x001e1406, 0x001d1405, 0x001c1306, 0x001c1306, 0x001c1307, 0x001d1408, 0x001d1408, 0x001d1408, 0x001f1308, 0x001f1308, 0x00201208, 0x00201208, 0x00201208, 0x00201208, 0x001f1208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1306, 0x001e1306, 0x001e1306, 0x001e1306, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001e1306, 0x001f1407, 0x001f1407, 0x001f1407, 0x001f1407, 0x001f1306, 0x001f1306, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00221508, 0x00221508, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221409, 0x00231509, 0x00221408, 0x00231408, 0x00241408, 0x00241408, 0x00241509, 0x0024150b, 0x0026160a, 0x0027160b, 0x0027180c, 0x0029180a, 0x002d1a0b, 0x00301c0c, 0x00321c0c, 0x00331d08, 0x0038210a, 0x0040270d, 0x00482c0a, 0x0051320a, 0x005e3c0c, 0x00734c0a, 0x00ac8423, 0x00cca92b, 0x00ccac14, 0x00ccac0d, 0x00ccaa0c, 0x00c8a40f, 0x00c69f0f, 0x00c3980b, 0x00bb8804, 0x00b37c01, 0x00b07301, 0x00a96a00, 0x00a46600, 0x00a56800, 0x00a86a02, 0x00ac7008, 0x00b37a10, 0x00be8919, 0x00c4941e, 0x00c99d20, 0x00cba61f, 0x00cbab1b, 0x00cbac1c, 0x00cca71f, 0x00b18213, 0x00885503, 0x00744408, 0x00533200, 0x004d2f02, 0x00452b04, 0x00412805, 0x00402508, 0x003f2409, 0x003c240b, 0x003c220c, 0x003c2309, 0x003b2108, 0x003b2309, 0x003d240c, 0x003e250c, 0x003e250b, 0x003f2608, 0x00402708, 0x00442a0a, 0x00452c0a, 0x00452d06, 0x004b3208, 0x00513809, 0x005e400c, 0x00744f0d, 0x00977414, 0x00c3a725, 0x00cbb415, 0x00ccb90c, 0x00ccbb08, 0x00cbbc08, 0x00cbbc08, 0x00ccbb05, 0x00cab00c, 0x00ae8909, 0x00845a01, 0x006c4404, 0x00583a04, 0x004c3607, 0x00423006, 0x003c2805, 0x00342203, 0x002f2006, 0x00261904, 0x001d1405, 0x001e170a, 0x00181409, 0x00141208, 0x0014110a, 0x0014130b, 0x00101008, 0x000c1007, 0x000d1008, 0x000d100a, 0x000e120c, 0x000c1410, 0x000a1410, 0x000c1512, 0x000d1512, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181f19, 0x00181f19, 0x00192018, 0x00192018, 0x001a2118, 0x00141910, 0x000e130c, 0x000f100a, 0x0011110a, 0x0014110a, 0x0017130a, 0x001a1409, 0x001e1308, 0x00281c0b, 0x002c1f0a, 0x00322208, 0x003d280d, 0x0042300b, 0x0049340c, 0x005b3f0e, 0x00714c0f, 0x009a741c, 0x00c8a930, 0x00cab51d, 0x00c8ba11, 0x00c8bc0a, 0x00cbbd09, 0x00cbb80d, 0x00be9c0d, 0x00946700, 0x007b5000, 0x00624100, 0x004c3701, 0x00413101, 0x003b2b00, 0x00382902, 0x00352604, 0x00342404, 0x00312204, 0x00311e04, 0x002d1b02, 0x002c1c07, 0x002b1a08, 0x00281807, 0x00261808, 0x00261909, 0x00241808, 0x00241607, 0x00241607, 0x00241507, 0x00231506, 0x00241607, 0x00241507, 0x00211407, 0x00221509, 0x001f1206, 0x00201408, 0x00211408, 0x00201407, 0x00201406, 0x00201406, 0x00211507, 0x001f1408, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x001f1208, 0x001c1408, 0x00191508, 0x00131003, 0x00141206, 0x00181306, 0x001b1408, 0x001c1208, 0x00201409, 0x00201409, 0x00211408, 0x00221608, 0x00201609, 0x00201609, 0x00201609, 0x00201609, 0x00241409, 0x00241409, 0x00241409, 0x00211308, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00201508, 0x00201408, 0x00201307, 0x00201508, 0x00201709, 0x00201508, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001e1205, 0x00201408, 0x00211408, 0x00201307, 0x00201307, 0x00201307, 0x001d1205, 0x001f1408, 0x00201508, 0x001f1408, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201307, 0x001e1407, 0x001c1205, 0x001c1205, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001e1306, 0x001d1306, 0x001e1407, 0x001e1306, 0x001d1206, 0x001d1207, 0x001e1308, 0x001e1308, 0x001f1308, 0x00201208, 0x00201208, 0x00201208, 0x00201208, 0x00211308, 0x00201105, 0x00201105, 0x001f1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001c1104, 0x001e1205, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001d1306, 0x001e1306, 0x001f1408, 0x00201508, 0x00201508, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241509, 0x00241409, 0x00221407, 0x00241508, 0x00241508, 0x00241608, 0x0023160a, 0x00231708, 0x0024180c, 0x0025180c, 0x0028170c, 0x002b180c, 0x002f1c0c, 0x00301b0a, 0x00321d08, 0x0037210b, 0x0040270c, 0x00482c09, 0x0052320c, 0x00633c10, 0x00744c0a, 0x00a2781c, 0x00c49824, 0x00c09410, 0x00b88908, 0x00b38000, 0x00af7700, 0x00ac7000, 0x00a76900, 0x00a66700, 0x00a46400, 0x00a66801, 0x00ad7106, 0x00b47c0d, 0x00ba8412, 0x00c38f19, 0x00c7981e, 0x00c9a220, 0x00ccaa20, 0x00ccaf1c, 0x00cbb214, 0x00cab40c, 0x00c8b608, 0x00c8b40c, 0x00cbab17, 0x00a97d08, 0x00885400, 0x00714002, 0x00523000, 0x004a2d02, 0x00422802, 0x003d2504, 0x003c2208, 0x003a1f08, 0x00361f0a, 0x00351f0d, 0x00351e0c, 0x00341c0c, 0x00341c08, 0x00351f08, 0x00392109, 0x003c240c, 0x003e250b, 0x003e260a, 0x0041290c, 0x00432c0b, 0x00432c08, 0x0048310c, 0x004e370c, 0x005e4010, 0x00705010, 0x008a670f, 0x00b5921f, 0x00ccb21d, 0x00ccb812, 0x00cbba0a, 0x00cabb08, 0x00cbba08, 0x00ccb80a, 0x00ccb412, 0x00b9980f, 0x008c6400, 0x006e4803, 0x00593b04, 0x004c3704, 0x00423004, 0x003c2805, 0x00372404, 0x00301f06, 0x00261803, 0x001c1404, 0x001d1609, 0x00181409, 0x00141208, 0x00141109, 0x00131209, 0x00101208, 0x000d1007, 0x000d1007, 0x000e1109, 0x000d110c, 0x000c140f, 0x000b1410, 0x000b1411, 0x000c1512, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181f19, 0x0019201a, 0x0019201a, 0x001b2119, 0x00192018, 0x00192017, 0x00131810, 0x000e130c, 0x000f1009, 0x0011100a, 0x0015120b, 0x0017130a, 0x00191309, 0x0020140a, 0x00281c0c, 0x002d200b, 0x00342409, 0x003e290e, 0x0044320d, 0x004b380e, 0x005d4110, 0x0074500f, 0x00a37f21, 0x00caac2d, 0x00cbb818, 0x00c8ba10, 0x00c8bc0a, 0x00cbba08, 0x00cab310, 0x00b18e0b, 0x008a5e00, 0x00764c03, 0x005d3f02, 0x00493402, 0x003f2f01, 0x00392800, 0x00352502, 0x00322402, 0x00312206, 0x00302005, 0x002c1c02, 0x00291900, 0x002b1a07, 0x00281807, 0x00241606, 0x00231707, 0x00241808, 0x00221606, 0x00211505, 0x00211505, 0x001f1305, 0x00211407, 0x00221608, 0x00211507, 0x00201408, 0x00221509, 0x001e1206, 0x00211408, 0x00221509, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x001f1308, 0x001c1408, 0x00191508, 0x00131003, 0x00131105, 0x00181308, 0x001b1308, 0x001c1208, 0x00201409, 0x00201409, 0x00221509, 0x00221608, 0x00201609, 0x00201609, 0x00201609, 0x00201609, 0x00241409, 0x00241409, 0x00241409, 0x00211308, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00201508, 0x00201408, 0x00201307, 0x00201508, 0x00201709, 0x00201508, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001e1205, 0x00201408, 0x00211408, 0x00201307, 0x00201307, 0x00201307, 0x001d1205, 0x001f1408, 0x00201508, 0x00201508, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001d1305, 0x001e1407, 0x001e1407, 0x00201307, 0x001e1205, 0x00201307, 0x00201307, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201307, 0x001e1407, 0x001c1205, 0x001c1204, 0x001e1306, 0x00201609, 0x001f1408, 0x001d1205, 0x001d1205, 0x001f1408, 0x00201508, 0x00201508, 0x00201609, 0x00201508, 0x001d1307, 0x001d1207, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x00201408, 0x001e1205, 0x001e1205, 0x001e1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1306, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201508, 0x00201508, 0x00201508, 0x00201508, 0x00201508, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241509, 0x0024160a, 0x00241409, 0x00221407, 0x00241508, 0x00241508, 0x00241608, 0x0023160a, 0x00231708, 0x0023170a, 0x0025180c, 0x0028170c, 0x002b180c, 0x002f1c0c, 0x00301b0a, 0x00321c07, 0x0037210b, 0x003f250b, 0x00472a07, 0x0055340a, 0x00673f0e, 0x0073460b, 0x00855408, 0x009c680b, 0x009a6200, 0x009a6100, 0x009c6300, 0x009c6300, 0x00a46902, 0x00aa7007, 0x00b2780a, 0x00ba8410, 0x00c39517, 0x00c79e1a, 0x00c8a31a, 0x00cca91c, 0x00ccac18, 0x00ccae14, 0x00ccb113, 0x00cab210, 0x00c8b30e, 0x00c6b40b, 0x00c6b706, 0x00c7b805, 0x00c9b60c, 0x00caa813, 0x00a47701, 0x00845300, 0x006d3e00, 0x00502d00, 0x00472a01, 0x003f2502, 0x003a2304, 0x00392007, 0x00371c07, 0x00341c09, 0x00321c0c, 0x00321c0c, 0x00331c0c, 0x00321c08, 0x00321c06, 0x00321d05, 0x00361f08, 0x00392209, 0x003a2308, 0x003c2609, 0x003f2809, 0x003f2907, 0x00422d0a, 0x0048340b, 0x00563e0f, 0x006b4c13, 0x00815d0e, 0x00a58018, 0x00caaf24, 0x00ccb718, 0x00ccb90d, 0x00cabb0a, 0x00cbba0a, 0x00ccb90a, 0x00ccb711, 0x00c0a212, 0x00936d01, 0x00734c03, 0x005c3d04, 0x004d3805, 0x00433005, 0x003d2a07, 0x00382404, 0x00312005, 0x00281904, 0x001c1404, 0x001b1406, 0x001a150a, 0x00141308, 0x00141109, 0x00131209, 0x00111309, 0x000e1107, 0x000d1007, 0x000e1109, 0x000d110c, 0x000c130e, 0x000b1410, 0x000b1411, 0x000b1411, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181f19, 0x0019201a, 0x0019201a, 0x001b2119, 0x00192018, 0x00171e14, 0x000f140b, 0x000e130b, 0x000d1009, 0x0011100b, 0x0015140c, 0x00171308, 0x00181208, 0x0020150b, 0x00281c0c, 0x002f200a, 0x0037250b, 0x003f2a0d, 0x00483611, 0x004e390f, 0x005f4310, 0x007c5810, 0x00ae8925, 0x00cbae2a, 0x00cbb814, 0x00c8bb0e, 0x00c8ba08, 0x00cab80c, 0x00c8af10, 0x00a07c03, 0x00825702, 0x00704807, 0x00573903, 0x00483404, 0x003e2d03, 0x003a2902, 0x00322201, 0x002e1f01, 0x002c1c03, 0x002a1c04, 0x00281a04, 0x00261802, 0x00261704, 0x00241505, 0x00211506, 0x00211508, 0x00201608, 0x001f1406, 0x001f1406, 0x001f1406, 0x00201408, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x0021140a, 0x00201208, 0x0021140a, 0x0021140a, 0x00201409, 0x00201409, 0x00201208, 0x00201208, 0x001d1205, 0x001d1205, 0x001c1104, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001f1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00211309, 0x001f1409, 0x00181407, 0x00141305, 0x00141005, 0x00181308, 0x001b1308, 0x001c1208, 0x00201309, 0x00201409, 0x00211408, 0x00221608, 0x00201609, 0x00201609, 0x00201508, 0x00201508, 0x00231409, 0x00241409, 0x00231408, 0x00221408, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00201508, 0x00211408, 0x00201307, 0x00201508, 0x001f1608, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001e1205, 0x00201408, 0x00201408, 0x001f1206, 0x001e1205, 0x001e1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x001e1205, 0x00201307, 0x00201307, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201307, 0x001e1407, 0x001c1205, 0x001c1204, 0x001f1408, 0x00201508, 0x001d1205, 0x001d1205, 0x001d1306, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201508, 0x001e1407, 0x001d1206, 0x001d1207, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201408, 0x001e1205, 0x001e1205, 0x001e1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x00201508, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1306, 0x001e1205, 0x001f1205, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x00201508, 0x00211408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00211406, 0x00221407, 0x00221407, 0x00241508, 0x0023160a, 0x00231708, 0x0023160a, 0x0024180c, 0x0027160c, 0x0028170b, 0x002c190a, 0x00301b0a, 0x00331c09, 0x0038210c, 0x0040270d, 0x004a2c08, 0x00593608, 0x006c410c, 0x00774609, 0x00804c01, 0x008e5500, 0x00985e01, 0x00a06803, 0x00ab760c, 0x00b68416, 0x00c19220, 0x00c89a22, 0x00caa01c, 0x00cca51a, 0x00ccab14, 0x00ccb013, 0x00cbb213, 0x00cab310, 0x00c9b30b, 0x00ccb509, 0x00cbb608, 0x00cab408, 0x00c8b60a, 0x00c8b708, 0x00c8b705, 0x00c8b605, 0x00cbb30e, 0x00c9a214, 0x009f7001, 0x00815000, 0x00693d03, 0x004f2c01, 0x00452803, 0x003d2404, 0x00392206, 0x00392008, 0x00361c08, 0x00341c0b, 0x00321c0e, 0x00301c0d, 0x00301c0c, 0x00301c0a, 0x00301b08, 0x00301c08, 0x00311d07, 0x00341f08, 0x00372108, 0x00382308, 0x003b2608, 0x003d2908, 0x003e2b07, 0x00422f08, 0x004d380c, 0x00614511, 0x0079540f, 0x009a6f14, 0x00c0a020, 0x00ccb41f, 0x00ccb912, 0x00cbbc0c, 0x00c9bc0c, 0x00cbbc0a, 0x00ccb80e, 0x00c3aa11, 0x009a7603, 0x00774f02, 0x00604006, 0x00503906, 0x00443006, 0x003e2a07, 0x00382405, 0x00342006, 0x002c1d07, 0x001d1405, 0x00191304, 0x001c170b, 0x0016140a, 0x00131008, 0x00121108, 0x00101208, 0x000e1208, 0x000d1007, 0x000d1008, 0x000d120b, 0x000a120e, 0x000a1410, 0x000b1310, 0x000b1411, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001b211b, 0x001b211b, 0x001b211b, 0x001c221b, 0x001b2119, 0x00141a10, 0x000c1108, 0x000b1008, 0x000d0f08, 0x0012110b, 0x0016140c, 0x00161408, 0x00191308, 0x0020180c, 0x00281c0c, 0x00302109, 0x0038270a, 0x003f2c0c, 0x00473710, 0x00513c11, 0x00634811, 0x00856114, 0x00b8952a, 0x00cab024, 0x00cbb910, 0x00cabb0c, 0x00c8ba07, 0x00c8b408, 0x00c4a811, 0x00967100, 0x00795003, 0x00664104, 0x00513603, 0x00423004, 0x003d2c05, 0x00372703, 0x00302001, 0x002c1c03, 0x002a1c05, 0x002a1c05, 0x00271a05, 0x00241704, 0x00241605, 0x00211506, 0x001f1305, 0x001e1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001e1407, 0x001e1308, 0x001d1308, 0x001f1409, 0x0020150a, 0x0021140c, 0x0020120a, 0x0021140c, 0x0021140c, 0x00201409, 0x00201409, 0x00201208, 0x00201208, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001f1408, 0x00201408, 0x00201409, 0x001f1409, 0x00191407, 0x00161305, 0x00141005, 0x00181308, 0x001b1308, 0x001c1208, 0x001f1208, 0x00201409, 0x00201408, 0x00221608, 0x00221509, 0x00221509, 0x00201408, 0x00201408, 0x00211308, 0x00211308, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00201508, 0x00211408, 0x00201307, 0x00201508, 0x001f1608, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001e1205, 0x00201408, 0x00201408, 0x001f1206, 0x001e1205, 0x001e1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x001e1205, 0x00201307, 0x00201307, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201307, 0x001e1407, 0x001c1205, 0x001c1105, 0x00201508, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1206, 0x001d1207, 0x001d1308, 0x001e1308, 0x001c1408, 0x001c1405, 0x001c1405, 0x001c1405, 0x001c1405, 0x001f1408, 0x001d1305, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x00201609, 0x00201508, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001e1205, 0x001f1206, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x00211408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00231409, 0x00211406, 0x00221407, 0x00221407, 0x00221407, 0x0023160a, 0x00231609, 0x0023160a, 0x0024170a, 0x0028180d, 0x00281608, 0x002b1808, 0x00301b0a, 0x00331d08, 0x0038220c, 0x00432810, 0x004c2e0e, 0x005c370a, 0x0070440c, 0x00845410, 0x00a26f1a, 0x00b17e18, 0x00bf8f1a, 0x00c89e23, 0x00caa11e, 0x00cba81f, 0x00ccac1f, 0x00ccaf1b, 0x00ccb015, 0x00cbb011, 0x00cab20d, 0x00cab50c, 0x00cab80a, 0x00cbba0a, 0x00ccb808, 0x00ccb709, 0x00ccb508, 0x00cbb409, 0x00cbb40a, 0x00cbb40a, 0x00ccb109, 0x00ccae0b, 0x00cca913, 0x00c09312, 0x00956100, 0x007e4d03, 0x00643804, 0x004c2b03, 0x00442502, 0x003b2204, 0x00382006, 0x00371d07, 0x00341a06, 0x00311908, 0x002f1a0b, 0x002c190a, 0x002c1a0a, 0x002c1908, 0x002c1808, 0x002d1a07, 0x002f1c08, 0x00301d06, 0x00331f08, 0x00352209, 0x00372407, 0x00382807, 0x003b2b06, 0x003c2c04, 0x0046360b, 0x00553b0b, 0x00714c0d, 0x008b600e, 0x00b28e19, 0x00ccb024, 0x00ccb715, 0x00cbbc0c, 0x00c8bc0b, 0x00cabc07, 0x00ccb908, 0x00c6b010, 0x009f7d04, 0x007b5200, 0x00644205, 0x00533b06, 0x00463206, 0x00402c09, 0x00392506, 0x00352206, 0x002d1d05, 0x001e1504, 0x00191304, 0x001a1709, 0x0018140a, 0x00131008, 0x00131008, 0x00111108, 0x000f1108, 0x000e1208, 0x000d1007, 0x000d120b, 0x000b130c, 0x000b140e, 0x000c1310, 0x000b1411, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001b211b, 0x001c221c, 0x001c211c, 0x001c211b, 0x001d221b, 0x0013170f, 0x000d1008, 0x000e1008, 0x00101109, 0x0013130c, 0x0016140c, 0x00151307, 0x00181408, 0x0020180c, 0x00291e0c, 0x00302209, 0x00392809, 0x003f2c09, 0x0046370d, 0x00523c11, 0x00684a10, 0x008a6610, 0x00c2a22c, 0x00ccb41d, 0x00ccba0d, 0x00c8bb0b, 0x00cbbc02, 0x00ccb80b, 0x00b8980c, 0x008c6500, 0x00754f04, 0x005f3f01, 0x004b3301, 0x00412f07, 0x003c2c09, 0x00352507, 0x002e1e04, 0x002a1c05, 0x00281a07, 0x00271a08, 0x00261808, 0x00231507, 0x00201408, 0x001e1407, 0x001c1406, 0x001c1305, 0x001d1207, 0x001c1307, 0x001c1408, 0x001c1408, 0x001c1409, 0x001c140a, 0x001c140a, 0x001c140a, 0x001d1409, 0x001e1409, 0x00201409, 0x00201409, 0x00201409, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1205, 0x001e1407, 0x00201508, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x001f1307, 0x001d1408, 0x001c1408, 0x001b1408, 0x00161003, 0x00141003, 0x00191208, 0x00191208, 0x001c1307, 0x001d1409, 0x001e1508, 0x00201607, 0x00231509, 0x00241409, 0x00201207, 0x00201207, 0x00211308, 0x00241409, 0x00241509, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00221509, 0x00201609, 0x00211408, 0x00211408, 0x001f1408, 0x001e1508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001f1408, 0x001f1408, 0x001d1205, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201406, 0x001f1204, 0x001e1204, 0x001e1204, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1205, 0x001e1205, 0x00201407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1608, 0x001d1408, 0x001c1407, 0x001c1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201207, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x00201709, 0x001d1207, 0x001b1005, 0x0020150a, 0x001f1409, 0x001d1207, 0x001d1207, 0x001e1308, 0x001e1308, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1306, 0x001b1204, 0x001b1205, 0x001c1407, 0x001c1407, 0x001c1405, 0x001c1405, 0x001c1405, 0x001c1405, 0x001e1407, 0x001e1407, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x00201609, 0x00201609, 0x001f1408, 0x00201408, 0x00241409, 0x00241409, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00211409, 0x00221509, 0x00221509, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x0021140a, 0x0024160a, 0x00271608, 0x00291808, 0x002c1a08, 0x00311b08, 0x00351e07, 0x0039210b, 0x00442811, 0x004a2c10, 0x005c360f, 0x0075480e, 0x00a17024, 0x00c89b32, 0x00cba624, 0x00cbad18, 0x00cbaf14, 0x00ccb110, 0x00ccb30e, 0x00cab40c, 0x00cab70d, 0x00c8b80b, 0x00c8b80a, 0x00c8b60a, 0x00c9b60a, 0x00c8b809, 0x00c8ba07, 0x00ccb808, 0x00ccb408, 0x00ccb108, 0x00ccb20a, 0x00cbaf09, 0x00caa90c, 0x00c8a311, 0x00c0940e, 0x00b6850b, 0x00a36c02, 0x008a5300, 0x00774604, 0x005e3501, 0x00482800, 0x00402401, 0x003a2104, 0x00361f06, 0x00361c08, 0x00331907, 0x002e1808, 0x002d1809, 0x002a1808, 0x00291808, 0x00281808, 0x00281808, 0x002b1908, 0x002c1a08, 0x002c1b07, 0x002d1c08, 0x002f1e09, 0x0034230a, 0x00342506, 0x00372805, 0x00392c03, 0x00423108, 0x00503808, 0x0068480c, 0x007d580a, 0x009c7610, 0x00c4a524, 0x00ccb519, 0x00cbba0f, 0x00c8bc06, 0x00c8bb03, 0x00c9b805, 0x00c9b40d, 0x00ae8d0a, 0x00805800, 0x006a4303, 0x00573904, 0x00483307, 0x00402c09, 0x003a2606, 0x00352304, 0x002e1e05, 0x00241908, 0x001a1102, 0x00191306, 0x0019150a, 0x0017130b, 0x00141109, 0x00121108, 0x00101108, 0x00101106, 0x000f1007, 0x000e1208, 0x000d1208, 0x000d120c, 0x000d130f, 0x000b1412, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001c221c, 0x001c221c, 0x001c211c, 0x001c201a, 0x00191e17, 0x0010140c, 0x000d1008, 0x00100f08, 0x00101109, 0x0014150c, 0x00141309, 0x00141306, 0x00191508, 0x00231b0c, 0x002c1f0c, 0x00332409, 0x003a2909, 0x003f2c09, 0x0048360c, 0x00574010, 0x006d4e0e, 0x00957217, 0x00c7a72c, 0x00ccb51e, 0x00cbba0d, 0x00c8bb0c, 0x00cbbb04, 0x00cab30b, 0x00ae8c08, 0x00825c00, 0x006e4a04, 0x00573a00, 0x00463000, 0x003d2c06, 0x00382807, 0x00322304, 0x002c1c03, 0x00281903, 0x00251606, 0x00241808, 0x00251809, 0x00231508, 0x00201409, 0x001c1408, 0x001c1408, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1508, 0x001c1408, 0x001c1408, 0x001c1308, 0x001c1307, 0x001c1408, 0x001e1508, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1305, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x001f1307, 0x001d1408, 0x001c1408, 0x001c1408, 0x00181004, 0x00140e01, 0x00181007, 0x00191208, 0x001c1307, 0x001c1408, 0x001e1508, 0x001f1507, 0x00231509, 0x00241409, 0x00201207, 0x00201207, 0x00211308, 0x00241409, 0x00241509, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00221509, 0x00201609, 0x00211408, 0x00211408, 0x001f1408, 0x001e1508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001f1408, 0x001f1408, 0x001d1205, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201406, 0x001f1204, 0x001e1204, 0x001e1204, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1205, 0x001e1205, 0x00201407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x00201508, 0x001f1608, 0x001d1408, 0x001c1407, 0x001c1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201207, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x00201709, 0x001d1207, 0x001b1005, 0x0020150a, 0x001f1409, 0x001d1207, 0x001d1207, 0x001e1308, 0x001e1308, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1307, 0x001b1206, 0x001b1207, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001e1407, 0x001e1407, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00211308, 0x00211308, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211409, 0x00221509, 0x00211408, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x0021140a, 0x0024170a, 0x00261708, 0x00291808, 0x002c1a08, 0x00311b08, 0x00351e07, 0x0039210b, 0x00442811, 0x004a2c0f, 0x005f380e, 0x00784b0f, 0x00ad8027, 0x00cca82d, 0x00cbaf18, 0x00ccb20d, 0x00ccb30a, 0x00ccb407, 0x00cbb408, 0x00c8b60b, 0x00c8b90d, 0x00c8ba10, 0x00caba0e, 0x00cbb809, 0x00cbb609, 0x00c8b408, 0x00c9b409, 0x00ccb10e, 0x00ccad0f, 0x00c8a60d, 0x00c09d09, 0x00ba9008, 0x00b27f04, 0x00a46f01, 0x009b6300, 0x00935a00, 0x008c5204, 0x00824807, 0x00704008, 0x00583102, 0x00482803, 0x00402303, 0x00382004, 0x00341e07, 0x00341c08, 0x00321a07, 0x002d1808, 0x002b170a, 0x00281809, 0x0028180b, 0x0028180b, 0x00281809, 0x00291909, 0x002c1a09, 0x002c1a08, 0x002c1a08, 0x002b1c08, 0x002e1f0a, 0x00322408, 0x00332605, 0x00372904, 0x003e2d07, 0x004b3408, 0x0060440c, 0x0075510a, 0x008f660b, 0x00b8941e, 0x00ccb41d, 0x00cbb911, 0x00c9bc0c, 0x00cabc06, 0x00ccb909, 0x00cab40c, 0x00b8980e, 0x00885f00, 0x006c4500, 0x00593c04, 0x00493405, 0x00412e09, 0x003b2707, 0x00362404, 0x002e1e04, 0x00241906, 0x001a1201, 0x001a1406, 0x001b180c, 0x0018140c, 0x00141109, 0x00131008, 0x00101108, 0x00101106, 0x000f1005, 0x000e1208, 0x000d1208, 0x000e130b, 0x000d130e, 0x000b1412, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001c221c, 0x001c221c, 0x001b211b, 0x001b2018, 0x00161b14, 0x000f120a, 0x000f0f08, 0x00100f08, 0x00111008, 0x0014150c, 0x00121108, 0x00141205, 0x00191608, 0x00231b0c, 0x002c1f0b, 0x00342408, 0x003c2809, 0x00442e0d, 0x004a340c, 0x005b400e, 0x0070500a, 0x00a07c1a, 0x00caac2c, 0x00ccb61c, 0x00ccbb0d, 0x00caba0d, 0x00ccb90a, 0x00c8ad0d, 0x00a17d01, 0x007d5704, 0x00674408, 0x00523704, 0x00412f01, 0x003c2c07, 0x00392808, 0x00332306, 0x002c1d04, 0x00251804, 0x00221608, 0x00211708, 0x00201409, 0x001f1409, 0x001c140a, 0x001c140a, 0x001c1409, 0x001a1408, 0x001b1407, 0x001b1407, 0x001a1407, 0x00181408, 0x001a1406, 0x001b1406, 0x001a1405, 0x00191304, 0x001a1304, 0x001c1305, 0x001e1206, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1308, 0x001c1106, 0x001c1206, 0x001c1106, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x00201508, 0x001e1407, 0x001e1407, 0x001f1407, 0x001f1307, 0x001d1408, 0x001c1408, 0x001c1408, 0x001b1206, 0x00160d01, 0x00181006, 0x001c1208, 0x001c1307, 0x001c1307, 0x001c1406, 0x001e1506, 0x00211408, 0x00221408, 0x00221408, 0x00211308, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00231409, 0x00211308, 0x00211308, 0x00211408, 0x00201508, 0x00211408, 0x00211408, 0x001f1408, 0x00201709, 0x00201508, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201406, 0x00201305, 0x00201305, 0x00201305, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x001f1206, 0x001f1206, 0x00201307, 0x00201407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201508, 0x001d1408, 0x001c1407, 0x001c1407, 0x001c1407, 0x001e1205, 0x001e1205, 0x001e1205, 0x001e1205, 0x001f1105, 0x001f1205, 0x001f1306, 0x001f1307, 0x001f1407, 0x00201307, 0x00201307, 0x001e1407, 0x001c1407, 0x001c1005, 0x001c1207, 0x001f1409, 0x001e1308, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001a1306, 0x00191306, 0x001a1407, 0x001b1407, 0x001a1307, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191306, 0x00191306, 0x001c1408, 0x001c1408, 0x001d1407, 0x001e1407, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001e1407, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001f1408, 0x0020150a, 0x0023170a, 0x0027180b, 0x00281808, 0x002e1908, 0x00321a08, 0x00371d07, 0x003a210b, 0x0042280e, 0x004c2d0a, 0x0060380a, 0x007c4f10, 0x00b08728, 0x00ccab27, 0x00ccb412, 0x00ccb508, 0x00ccb506, 0x00ccb605, 0x00cbb607, 0x00c9b50c, 0x00c8b60f, 0x00c9b510, 0x00cbb410, 0x00ccb10e, 0x00ccac0d, 0x00c9a710, 0x00c59e0e, 0x00be910c, 0x00b48406, 0x00a67501, 0x00a37000, 0x00a06700, 0x00a06100, 0x009f6100, 0x00a06504, 0x009e640b, 0x00885202, 0x00794402, 0x006c3e08, 0x00522d00, 0x00472804, 0x003e2204, 0x00382007, 0x00331d08, 0x00321c08, 0x002f1a08, 0x002b1909, 0x00271609, 0x0024180b, 0x0024180c, 0x0024180b, 0x0024180a, 0x00241708, 0x00261806, 0x00281908, 0x00291b0a, 0x002a1b0c, 0x002d1e0c, 0x0030220b, 0x00302408, 0x00342605, 0x003e2c08, 0x00463009, 0x00543b08, 0x006a4c0c, 0x00835809, 0x00a88218, 0x00cab023, 0x00cab715, 0x00c9bb10, 0x00cbbc0c, 0x00ccb80a, 0x00cab50c, 0x00bc9c0c, 0x008e6600, 0x006c4700, 0x005b3e02, 0x00493505, 0x00422f0a, 0x003c2506, 0x00362404, 0x002e2004, 0x00261a06, 0x001c1402, 0x00171102, 0x00191609, 0x0019150c, 0x00140f08, 0x00131008, 0x00111108, 0x00101106, 0x000f1005, 0x000e1208, 0x000d1208, 0x000e130b, 0x000d130e, 0x000c1312, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001c221c, 0x001c221c, 0x001b211b, 0x001c2019, 0x00161b14, 0x000f120a, 0x00100f08, 0x00110f08, 0x00121108, 0x0014140b, 0x00101005, 0x00141205, 0x001c1709, 0x00251c0c, 0x002e200c, 0x0036250a, 0x003e2a0c, 0x00493111, 0x00503710, 0x0060430f, 0x00755408, 0x00a8881e, 0x00ccb12c, 0x00ccb719, 0x00ccbb0d, 0x00c9b90c, 0x00ccb80b, 0x00c2a70d, 0x00946f00, 0x00744e04, 0x005d3d05, 0x004c3403, 0x00402e03, 0x003c2c08, 0x00392808, 0x00322305, 0x002a1b03, 0x00221601, 0x001e1405, 0x001d1407, 0x001c1409, 0x001c140b, 0x001c130c, 0x001c140c, 0x001b140c, 0x0019140a, 0x001b1407, 0x001b1407, 0x00191407, 0x00181407, 0x00181405, 0x00181404, 0x00181404, 0x00181404, 0x001a1404, 0x001c1404, 0x001e1304, 0x00201305, 0x001f1405, 0x00201507, 0x001f1406, 0x001e1405, 0x001e1406, 0x001c1107, 0x001e130a, 0x001f140b, 0x001d1208, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x00201508, 0x001e1407, 0x001e1407, 0x001e1306, 0x001f1307, 0x001e1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x00181004, 0x00191006, 0x001b1108, 0x001c1307, 0x001c1307, 0x001c1305, 0x001c1404, 0x00211408, 0x00221408, 0x00221408, 0x00211308, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00231409, 0x00211308, 0x00211308, 0x00211408, 0x00201508, 0x00211408, 0x00211408, 0x001f1408, 0x00201709, 0x00201508, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201406, 0x00201406, 0x00201305, 0x00201305, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x001f1206, 0x001f1206, 0x00201307, 0x00201407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001e1205, 0x001e1205, 0x001e1205, 0x001e1205, 0x001f1105, 0x001f1205, 0x001f1306, 0x001f1307, 0x001f1407, 0x00201307, 0x00201307, 0x001e1407, 0x001d1407, 0x001c1005, 0x001c1207, 0x001f1409, 0x001d1408, 0x001c1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001a1306, 0x00191306, 0x001a1407, 0x001b1407, 0x001a1307, 0x00191208, 0x00191208, 0x00191208, 0x00191308, 0x00191306, 0x00191306, 0x001b1508, 0x001c1408, 0x001d1407, 0x001e1407, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001e1407, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001f1408, 0x0020150a, 0x0023170a, 0x0027180a, 0x00291808, 0x002e1908, 0x00331a08, 0x00371d07, 0x003a2209, 0x00442a0c, 0x004c2f08, 0x00603807, 0x00805310, 0x00b88e2f, 0x00caab28, 0x00cbb414, 0x00ccb506, 0x00ccb506, 0x00ccb408, 0x00ccb308, 0x00cab00c, 0x00caaf10, 0x00c9a910, 0x00c6a00b, 0x00c09406, 0x00b88802, 0x00b07902, 0x00ab7101, 0x00a66800, 0x00a46600, 0x00a36400, 0x00a96c04, 0x00ac6e04, 0x00b6790d, 0x00bd8614, 0x00c4901a, 0x00c4941e, 0x009c6c05, 0x00804e00, 0x006c4004, 0x00502c00, 0x00442606, 0x003c2006, 0x00382008, 0x00331e09, 0x00301b08, 0x002c1a08, 0x00291909, 0x00241608, 0x0023160a, 0x0023160c, 0x0022170c, 0x0022170c, 0x00221608, 0x00221606, 0x00231607, 0x00261808, 0x0028190b, 0x002c1b0e, 0x002f200d, 0x00302009, 0x00332405, 0x003a2806, 0x0045300a, 0x004f380a, 0x00634910, 0x007d530e, 0x00987211, 0x00c5a825, 0x00c9b617, 0x00c9bb13, 0x00cbbb0f, 0x00cbb90d, 0x00ccb60c, 0x00c4a610, 0x00946d00, 0x006f4800, 0x005c3f01, 0x00483604, 0x00432f09, 0x003c2607, 0x00382505, 0x00302206, 0x00261b06, 0x001f1604, 0x00161001, 0x00171407, 0x001c180f, 0x0016110a, 0x00131008, 0x00111208, 0x00101106, 0x000f1005, 0x000e1208, 0x000e1208, 0x000e120c, 0x000d130e, 0x000c1311, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a221e, 0x001a221e, 0x001c211d, 0x001a211a, 0x00141810, 0x000e1108, 0x00101006, 0x00111006, 0x00131209, 0x00131409, 0x00101105, 0x00151307, 0x0021180c, 0x002a1b0d, 0x002f200c, 0x0036240a, 0x003e2a0b, 0x004a3210, 0x00543810, 0x00654512, 0x007c5a0d, 0x00b29224, 0x00ccb327, 0x00ccb716, 0x00cbb90d, 0x00c8b809, 0x00cab70c, 0x00b8990b, 0x00896100, 0x006d4802, 0x00583c04, 0x00483404, 0x003e2d04, 0x003c2a08, 0x00382608, 0x00312106, 0x00291c04, 0x00221703, 0x001c1405, 0x001c1407, 0x001b1309, 0x001b130c, 0x00191208, 0x00191208, 0x001a1108, 0x001b1007, 0x001b1206, 0x00191306, 0x00181306, 0x00181306, 0x00171406, 0x00171406, 0x00191608, 0x00181408, 0x001a1406, 0x001c1407, 0x001c1407, 0x001d1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001d1205, 0x001d1205, 0x00201307, 0x00201307, 0x001f1206, 0x00201408, 0x001d1205, 0x001e1306, 0x001f1408, 0x001f1408, 0x001e1508, 0x001d1409, 0x001c1408, 0x00191004, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1305, 0x001d1406, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00201307, 0x00201408, 0x001f1408, 0x00201609, 0x001f1408, 0x00201508, 0x00201508, 0x00201406, 0x00201406, 0x00201305, 0x00201305, 0x001e1407, 0x001e1407, 0x001d1205, 0x001f1408, 0x00211609, 0x001f1408, 0x001c1104, 0x001d1205, 0x001d1205, 0x001e1205, 0x001e1205, 0x001f1206, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201307, 0x00201408, 0x00201408, 0x001f1408, 0x001f1508, 0x001d1407, 0x001d1407, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1305, 0x00201508, 0x001c1104, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1107, 0x001e1107, 0x001e1107, 0x001e1107, 0x001e1206, 0x001e1205, 0x001f1306, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001e1205, 0x00201508, 0x001b1106, 0x001a1105, 0x001c1509, 0x001c1609, 0x001d1509, 0x001c1408, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1106, 0x001c1106, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1207, 0x001e1308, 0x001d1207, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1407, 0x001e1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00211408, 0x00211408, 0x00211408, 0x00221408, 0x00221408, 0x00211308, 0x00211308, 0x001f1408, 0x001f1408, 0x0020140a, 0x0023170a, 0x00261809, 0x002a1808, 0x002e1908, 0x00331a08, 0x00371d07, 0x003a2208, 0x00432a0b, 0x004d2e08, 0x00603908, 0x007c4f0a, 0x00bb912f, 0x00c9a827, 0x00ccb017, 0x00ccaf0b, 0x00ccab0b, 0x00caa50b, 0x00c59f09, 0x00be940c, 0x00b88a08, 0x00b07e02, 0x00ab7400, 0x00ad6b00, 0x00ab6800, 0x00a76700, 0x00aa6b04, 0x00ad710b, 0x00b37a10, 0x00bc8618, 0x00c59320, 0x00c89a20, 0x00cca520, 0x00ccab1c, 0x00ccac1c, 0x00c9a620, 0x00a47405, 0x00835101, 0x006a4002, 0x004f2b00, 0x00442509, 0x003c2008, 0x00371e08, 0x00321c08, 0x002f1b08, 0x002c1a08, 0x00281809, 0x00241609, 0x0023160a, 0x0023160a, 0x00211609, 0x00201608, 0x00201507, 0x00201606, 0x00211606, 0x00241808, 0x00251808, 0x00281a09, 0x002c1e09, 0x002c1d07, 0x00302005, 0x00382706, 0x0042300b, 0x004b360c, 0x00584010, 0x006f4d0c, 0x008a6411, 0x00bb9c26, 0x00cab61c, 0x00cbbb10, 0x00ccba0e, 0x00ccba0e, 0x00ccb80e, 0x00caad14, 0x009c7501, 0x00744d00, 0x005c4002, 0x00473704, 0x00433008, 0x003e2808, 0x00382606, 0x00312306, 0x00291c08, 0x00201705, 0x00181003, 0x00141005, 0x001c1910, 0x00161208, 0x00131107, 0x00101206, 0x000f1007, 0x000d0f05, 0x00101008, 0x00101109, 0x0010110c, 0x000e120f, 0x000b1210, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a221e, 0x001a221e, 0x001c221f, 0x00171d18, 0x000f140b, 0x000d1007, 0x00101006, 0x00131107, 0x0016140b, 0x00121208, 0x00101004, 0x00161408, 0x0023180d, 0x002d1c0f, 0x0030200c, 0x0038270c, 0x00402c0b, 0x004c330f, 0x00543810, 0x00664612, 0x00836111, 0x00b89928, 0x00ccb324, 0x00ccb813, 0x00cbba0c, 0x00c9b80b, 0x00cbb510, 0x00ad8d06, 0x00835a00, 0x006a4401, 0x00543804, 0x00443002, 0x003d2c04, 0x00392606, 0x00352305, 0x00301f04, 0x002a1c05, 0x00221703, 0x001c1404, 0x001c1407, 0x001b130a, 0x001b120c, 0x00181308, 0x00181308, 0x00191108, 0x001a1007, 0x001b1206, 0x00191306, 0x00181306, 0x00181306, 0x00171406, 0x00171406, 0x00191608, 0x00181408, 0x001a1406, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001d1205, 0x001d1205, 0x00201307, 0x00201307, 0x001f1206, 0x00201408, 0x001d1104, 0x001e1306, 0x00201508, 0x001f1408, 0x001f1608, 0x001f150a, 0x001e1409, 0x00180f04, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1306, 0x001f1507, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00201307, 0x00201408, 0x001f1408, 0x00201609, 0x001f1408, 0x00201508, 0x00201508, 0x00201406, 0x00201406, 0x00201305, 0x00201305, 0x001e1407, 0x001e1407, 0x001d1305, 0x001f1408, 0x0021170a, 0x001f1408, 0x001c1104, 0x001d1205, 0x001d1205, 0x001e1205, 0x001e1205, 0x00201408, 0x00221509, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201307, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1407, 0x001c1407, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1306, 0x00201508, 0x001c1104, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1206, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x00201508, 0x001a1106, 0x001b1105, 0x001c1509, 0x001b1609, 0x001c1509, 0x001c1408, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1106, 0x001c1106, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1207, 0x001c1106, 0x001d1208, 0x001d1408, 0x001c1407, 0x001e1508, 0x00201709, 0x00201608, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x001f1206, 0x001f1206, 0x001f1206, 0x001f1306, 0x00201307, 0x00201408, 0x00201308, 0x00211308, 0x00211308, 0x00211308, 0x00211308, 0x00201408, 0x00201408, 0x0021140a, 0x0024170a, 0x00261809, 0x002b1909, 0x002e1908, 0x00331a08, 0x00371e06, 0x003b2308, 0x00442b0d, 0x004e300b, 0x00603908, 0x00784a08, 0x00b5882d, 0x00c19824, 0x00c09816, 0x00bd8a0f, 0x00b58008, 0x00af7803, 0x00a77000, 0x00a26800, 0x00a36900, 0x00a46800, 0x00a56a01, 0x00a76c03, 0x00ab7408, 0x00b88416, 0x00c08f20, 0x00c59820, 0x00c9a221, 0x00cca820, 0x00ccac1c, 0x00cbad19, 0x00cab215, 0x00c8b313, 0x00c8b014, 0x00c8a61b, 0x009f7002, 0x00845104, 0x006b3f04, 0x004e2a00, 0x00442409, 0x003c2008, 0x00371e08, 0x00331c08, 0x002f1b08, 0x002b1908, 0x00281809, 0x00221509, 0x00221509, 0x00221509, 0x00201508, 0x001f1508, 0x001e1507, 0x001d1406, 0x001f1407, 0x00221809, 0x00241809, 0x00261a08, 0x00281c07, 0x00291c05, 0x002c1f03, 0x00352605, 0x003f2f09, 0x0048340b, 0x00533d0e, 0x006a4c0e, 0x007e5b0e, 0x00ae8d1e, 0x00c9b41c, 0x00cbb90d, 0x00cbba0c, 0x00cbb90d, 0x00ccb910, 0x00ccb217, 0x00a17c02, 0x007a5200, 0x005f4204, 0x004b3a05, 0x0047340b, 0x00422c0c, 0x003a2808, 0x00332407, 0x002b1d08, 0x00231807, 0x00181003, 0x00141005, 0x0018170d, 0x0018140b, 0x00121006, 0x000f1005, 0x00101108, 0x000f1007, 0x00101109, 0x0010120a, 0x0010110c, 0x000e120d, 0x000b120e, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a221e, 0x001a221e, 0x001d231f, 0x00151a14, 0x000f120a, 0x000f1007, 0x00121107, 0x0017140a, 0x00151308, 0x00101006, 0x00101104, 0x0019160a, 0x00251a0f, 0x002c1c0e, 0x0033210d, 0x0039260a, 0x00422e0b, 0x004b340c, 0x00543a0f, 0x00684710, 0x00896814, 0x00bfa12c, 0x00ccb31f, 0x00ccb810, 0x00cbba09, 0x00cab60c, 0x00cab116, 0x00a68205, 0x007e5500, 0x00654000, 0x00523504, 0x00443004, 0x003b2804, 0x00372204, 0x00321f02, 0x002f1d04, 0x002a1c06, 0x00221804, 0x001c1402, 0x001a1405, 0x00191208, 0x0019110b, 0x00171208, 0x00181207, 0x00181107, 0x00181006, 0x001b1206, 0x00191306, 0x00181306, 0x00181306, 0x00171406, 0x00171406, 0x00181408, 0x00181508, 0x00191306, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001d1205, 0x001e1306, 0x00201508, 0x001f1408, 0x001f1408, 0x001f1409, 0x001f1409, 0x001b1005, 0x001c1005, 0x001c1307, 0x001c1307, 0x001c1306, 0x001f1607, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00201307, 0x00201408, 0x001f1408, 0x00201508, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201406, 0x00201406, 0x00201406, 0x00201406, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x00201609, 0x001f1408, 0x001d1306, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201408, 0x00211409, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1306, 0x00201408, 0x00201408, 0x00201508, 0x001f1608, 0x001c1407, 0x001c1407, 0x001d1306, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001f1409, 0x001f1409, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1206, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001b1206, 0x001b1206, 0x001c1408, 0x001a1508, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1005, 0x001e1308, 0x001f1508, 0x001c1406, 0x001c1306, 0x001c1407, 0x001d1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00211308, 0x00211308, 0x00211308, 0x00211308, 0x00201408, 0x00201408, 0x0021140a, 0x0024160a, 0x00281709, 0x002b1909, 0x002f1a09, 0x00341b0a, 0x00381e06, 0x003c2409, 0x00462c10, 0x0053320e, 0x005f380c, 0x00703e08, 0x0088540b, 0x00925f02, 0x00945d00, 0x009c5a00, 0x009c5c00, 0x009b5c00, 0x009c6002, 0x00a56c03, 0x00aa7309, 0x00b37c11, 0x00be8c1c, 0x00c2951c, 0x00c8a020, 0x00caa720, 0x00ccac21, 0x00ccb01b, 0x00ccb116, 0x00cbb413, 0x00cbb60f, 0x00c9b70c, 0x00c8b808, 0x00c5b609, 0x00cab414, 0x00c4a014, 0x009e6e04, 0x00835006, 0x00663a03, 0x004d2802, 0x00422509, 0x003b2008, 0x00361d08, 0x00311b08, 0x002f1c0a, 0x00291808, 0x00271709, 0x00221509, 0x00211408, 0x001e1205, 0x001d1205, 0x001d1508, 0x001c1407, 0x001c1408, 0x001c1408, 0x001e1409, 0x00201609, 0x00231808, 0x00251b07, 0x00281d05, 0x002a1f04, 0x00322404, 0x003a2c05, 0x00433108, 0x004e3b0c, 0x0060440c, 0x0075520c, 0x00a07e16, 0x00c9af1f, 0x00ccba10, 0x00ccbb0c, 0x00cbb90d, 0x00ccba0e, 0x00ccb214, 0x00ac880b, 0x007c5400, 0x00604001, 0x004f3b05, 0x00463309, 0x00432b0b, 0x003c280a, 0x00322305, 0x002c1c08, 0x00241805, 0x00191104, 0x00130e04, 0x0017140b, 0x001a150c, 0x00141006, 0x000f1007, 0x000f1007, 0x000f1007, 0x00101009, 0x00101009, 0x000e1008, 0x0010140d, 0x000b120c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231c, 0x001a231c, 0x001d241e, 0x00151a13, 0x000f120a, 0x000f1007, 0x00111006, 0x00141108, 0x00141109, 0x00101007, 0x00111206, 0x001c190e, 0x00281c11, 0x002e1d0f, 0x0033220d, 0x003b280c, 0x00422f0c, 0x004b360d, 0x00573c0f, 0x006c4b10, 0x008c6c16, 0x00c5a830, 0x00cab41d, 0x00ccb90e, 0x00cbbb06, 0x00cbb60c, 0x00c7ac16, 0x009c7702, 0x00785000, 0x00623d02, 0x00503404, 0x00442f07, 0x003a2807, 0x00372205, 0x00331e03, 0x002d1d04, 0x00291d08, 0x00221805, 0x001c1404, 0x00191306, 0x00191208, 0x0019110b, 0x00171208, 0x00171307, 0x00181207, 0x00171106, 0x001b1206, 0x00191306, 0x00181306, 0x00181306, 0x00181406, 0x00171406, 0x00181408, 0x00181508, 0x00191306, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001d1205, 0x001e1306, 0x00201508, 0x001f1408, 0x001f1408, 0x001f1409, 0x001f1409, 0x001e1308, 0x001b1005, 0x001c1307, 0x001c1307, 0x001c1306, 0x001f1507, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00201307, 0x00201408, 0x001f1408, 0x00201508, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201406, 0x00201406, 0x00201406, 0x00201406, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x00201609, 0x001f1408, 0x001d1306, 0x001e1407, 0x001f1407, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1306, 0x00201307, 0x00201307, 0x001f1408, 0x001c1407, 0x001c1407, 0x001c1407, 0x001d1306, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1306, 0x001c1305, 0x001c1406, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001b1206, 0x001b1206, 0x001c1408, 0x001a1508, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001e1308, 0x001d1207, 0x001c1205, 0x001c1407, 0x001d1408, 0x001c1407, 0x001d1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201207, 0x00201207, 0x00211308, 0x00211308, 0x00201408, 0x00201408, 0x0021140a, 0x0024160a, 0x00281709, 0x002b1909, 0x00301b0a, 0x00341c0b, 0x00391f09, 0x003e260c, 0x00492f10, 0x00563612, 0x00643d0d, 0x00754408, 0x00865004, 0x00905800, 0x00985f01, 0x00a36608, 0x00aa710e, 0x00b17c14, 0x00ba891a, 0x00bd9218, 0x00c49c1c, 0x00cca925, 0x00ccac24, 0x00ccac1a, 0x00ccaf14, 0x00ccb10f, 0x00ccb50c, 0x00ccb507, 0x00ccb507, 0x00cab709, 0x00c9b80b, 0x00c8b807, 0x00c8b804, 0x00c8b708, 0x00ccb014, 0x00be9710, 0x00986500, 0x00804c04, 0x00623700, 0x004a2501, 0x0042240b, 0x003a2008, 0x00341e08, 0x00301b08, 0x002f1c0b, 0x00281808, 0x00261609, 0x00221509, 0x00201508, 0x001d1306, 0x001c1307, 0x001c1408, 0x00191408, 0x00191407, 0x001b1408, 0x001b1308, 0x001c1408, 0x00201806, 0x00231905, 0x00261d05, 0x00281f02, 0x00312404, 0x00382b05, 0x003e2f04, 0x00493809, 0x005a420c, 0x0070500e, 0x00967311, 0x00c6a81f, 0x00ccb811, 0x00ccbb0c, 0x00cbb90d, 0x00ccb90f, 0x00ccb414, 0x00af8c0c, 0x00805800, 0x00644200, 0x00513c07, 0x00463309, 0x00422a0a, 0x003c280a, 0x00332305, 0x002f1e09, 0x00271a08, 0x001c1507, 0x00140f04, 0x00141206, 0x001b150c, 0x00141006, 0x000f1007, 0x000f1007, 0x000f1007, 0x00101009, 0x00101009, 0x000e1008, 0x0010140c, 0x000b130c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231c, 0x001c221c, 0x001d211c, 0x00141710, 0x0010120a, 0x00101007, 0x00121108, 0x00131008, 0x000e0c03, 0x00131007, 0x00181409, 0x00201a0e, 0x00281c0e, 0x002f1d0c, 0x0034220c, 0x003b280c, 0x0041300d, 0x0049370f, 0x00583c0e, 0x00704c10, 0x00957417, 0x00c9ad2c, 0x00ccb617, 0x00cab909, 0x00ccb905, 0x00ccb80d, 0x00c2a312, 0x00946d00, 0x00744d00, 0x005d3c00, 0x004c3404, 0x00422e07, 0x003a2804, 0x00342302, 0x002e1f04, 0x002b1d06, 0x00281c08, 0x00201706, 0x00191304, 0x00181305, 0x00181207, 0x00161008, 0x00181207, 0x00181207, 0x00181207, 0x00171106, 0x00171106, 0x00171106, 0x00181308, 0x00191208, 0x00181207, 0x00181207, 0x00181308, 0x00191408, 0x001a1408, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001c1407, 0x001c1407, 0x00181304, 0x001b1405, 0x001c1508, 0x001b1204, 0x001d1205, 0x001e1407, 0x001f1307, 0x00211408, 0x00211408, 0x00201307, 0x001f1307, 0x001e1407, 0x001d1306, 0x001e1407, 0x001e1408, 0x001f1409, 0x0020150a, 0x001c1408, 0x00170e02, 0x001c140a, 0x001c140a, 0x001c1408, 0x001d1508, 0x00201408, 0x00211308, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00211408, 0x00211408, 0x00201508, 0x0022170a, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001d1207, 0x001e1308, 0x001d1307, 0x001f1508, 0x001f1608, 0x001c1406, 0x001c1104, 0x001d1205, 0x001d1205, 0x001f1408, 0x00201609, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1409, 0x001d1207, 0x001c1106, 0x001d1207, 0x001f1408, 0x00201508, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001c1104, 0x001a1003, 0x001b1105, 0x001c1308, 0x001b1206, 0x001b1206, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001d1408, 0x001e1308, 0x001d1208, 0x001c1005, 0x001c1106, 0x001a1105, 0x001a1105, 0x001b1407, 0x00191407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201507, 0x00211508, 0x00231409, 0x0025170b, 0x0028180a, 0x002c1a0a, 0x00301b0a, 0x00341c0b, 0x003b1f09, 0x0042240e, 0x004b2c10, 0x005c3b11, 0x006c4610, 0x008c5c18, 0x00a4711c, 0x00b4821b, 0x00b98d19, 0x00c49c1d, 0x00cba31f, 0x00cba61b, 0x00ccab19, 0x00ccae16, 0x00ccb014, 0x00ccb112, 0x00cbb310, 0x00cab410, 0x00c9b40d, 0x00ccb40b, 0x00ccb408, 0x00c8b807, 0x00c8b708, 0x00c8b40a, 0x00cab50d, 0x00ccb80e, 0x00ccb508, 0x00cab00c, 0x00ccac1b, 0x00b88910, 0x00915c00, 0x007f4d05, 0x005d3400, 0x00492603, 0x003e2308, 0x00371d06, 0x00341c09, 0x002f1b0a, 0x002c1c09, 0x00251808, 0x00211708, 0x001f1608, 0x001e140b, 0x001c140a, 0x001b1309, 0x00191209, 0x00181207, 0x00181308, 0x00181308, 0x00191408, 0x00191408, 0x001c1608, 0x00211908, 0x00231907, 0x00291e07, 0x00302306, 0x00372a07, 0x003b2d05, 0x0047380c, 0x00553e0d, 0x006c4d10, 0x008a6711, 0x00c2a122, 0x00ccb717, 0x00cbb90d, 0x00cbba0c, 0x00ccb90f, 0x00ccb413, 0x00b7930f, 0x00875e00, 0x00684401, 0x00543c06, 0x00473309, 0x00422b0b, 0x003c2709, 0x00342304, 0x002f1f05, 0x00271a04, 0x001e1604, 0x00151101, 0x00101002, 0x0017160a, 0x00151309, 0x00110f07, 0x000f1007, 0x000f1007, 0x000e1008, 0x000d1008, 0x000e110c, 0x000d130d, 0x000b130c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231b, 0x001c221b, 0x00181d16, 0x0010140b, 0x0010120a, 0x00101007, 0x00121108, 0x00111008, 0x000d0c02, 0x00141006, 0x001c1509, 0x00231b0e, 0x00281c0b, 0x002f1e0a, 0x0034220a, 0x003b2a0c, 0x0041310c, 0x004b3810, 0x005b3e0e, 0x00745111, 0x00a17f1d, 0x00ccb029, 0x00cbb813, 0x00cab908, 0x00ccb905, 0x00ccb40c, 0x00ba9b0f, 0x00886200, 0x006e4900, 0x00563800, 0x00483202, 0x003c2c04, 0x00352402, 0x00322001, 0x002d1e04, 0x00291c08, 0x00271c0a, 0x00201708, 0x00191306, 0x00181305, 0x00181207, 0x00161007, 0x00151108, 0x00151108, 0x00151107, 0x00141007, 0x00141005, 0x00141005, 0x00151106, 0x00181308, 0x00181207, 0x00181207, 0x00181308, 0x00181308, 0x00191308, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001a1507, 0x001a1507, 0x00191405, 0x001a1507, 0x001c1407, 0x001e1508, 0x00201609, 0x001e1407, 0x001d1104, 0x001f1306, 0x00201408, 0x00201307, 0x001f1407, 0x001e1306, 0x001d1306, 0x001e1407, 0x001e1408, 0x001f1409, 0x0020150a, 0x001f150a, 0x00180f03, 0x001b1108, 0x001c1208, 0x001b1407, 0x001c1407, 0x00201408, 0x00211308, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00211308, 0x00211308, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00211408, 0x00211408, 0x00201508, 0x0022170a, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1207, 0x001c1307, 0x001f1608, 0x001f1608, 0x001c1406, 0x001c1204, 0x001d1205, 0x001d1205, 0x001e1407, 0x00201508, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001e1308, 0x001e1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001c1004, 0x001a1105, 0x001c1308, 0x001b1206, 0x001b1206, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001b1206, 0x001c1307, 0x001a1105, 0x001a1105, 0x001b1407, 0x00191407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001c1408, 0x001c1408, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1308, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201507, 0x00211507, 0x0024150a, 0x0026180b, 0x0028180a, 0x002c190a, 0x00311c0c, 0x00351c0c, 0x003b1f0b, 0x00442610, 0x00502d0f, 0x005c3a0c, 0x00704609, 0x00ad7e2d, 0x00cb9e34, 0x00cca529, 0x00cba820, 0x00ccae18, 0x00ccaf14, 0x00ccb00f, 0x00ccb10c, 0x00ccb209, 0x00ccb309, 0x00ccb408, 0x00ccb608, 0x00c9b808, 0x00cab808, 0x00cbb605, 0x00cab604, 0x00c9b804, 0x00c9b707, 0x00cab409, 0x00cab00a, 0x00cbae10, 0x00caa913, 0x00c59f12, 0x00b78a0e, 0x00a06d04, 0x008b5300, 0x007c4c08, 0x00583000, 0x004a2805, 0x003e2308, 0x00361d06, 0x00311c0a, 0x002d1a0b, 0x00281a08, 0x00231705, 0x00201608, 0x001c1509, 0x001c140c, 0x001c140c, 0x001b130b, 0x00181108, 0x00181008, 0x00181309, 0x0018130a, 0x0019140b, 0x0019140b, 0x001c150b, 0x0021180b, 0x00231809, 0x002a1d0a, 0x00312208, 0x00372a08, 0x00392c05, 0x00423409, 0x00523b0c, 0x00684b12, 0x00846113, 0x00bb9820, 0x00ccb419, 0x00cbb90f, 0x00cbba0c, 0x00ccba0d, 0x00ccb613, 0x00ba970f, 0x008c6000, 0x006b4400, 0x00553a05, 0x00483408, 0x00432b0a, 0x003c2809, 0x00352404, 0x00302007, 0x00281c04, 0x00201604, 0x00161102, 0x00100f01, 0x00141408, 0x0018160e, 0x00121008, 0x00101007, 0x00101108, 0x000d1008, 0x000c1108, 0x000d110c, 0x000d130e, 0x000c130c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231b, 0x001c221b, 0x00131810, 0x00101009, 0x0011110a, 0x00110f07, 0x00121008, 0x00100f06, 0x000e0b02, 0x00141004, 0x001c1608, 0x00231a0c, 0x00291c0a, 0x002f1e06, 0x00352408, 0x003b2b09, 0x0041320b, 0x004c390d, 0x005d3f0d, 0x00795411, 0x00a98822, 0x00caaf22, 0x00cab910, 0x00c8ba08, 0x00cab805, 0x00cbb00c, 0x00b18e0b, 0x00835c00, 0x00694700, 0x00543901, 0x00443003, 0x00382805, 0x00312102, 0x002f1f01, 0x002c1c05, 0x00281b08, 0x00251909, 0x00201709, 0x001b1407, 0x00161205, 0x00151106, 0x00171008, 0x00141008, 0x00121008, 0x00121008, 0x00121008, 0x00141006, 0x00121006, 0x00131006, 0x00151108, 0x00161307, 0x00161307, 0x00181308, 0x00181308, 0x00191308, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x00191306, 0x00191306, 0x00191405, 0x00191405, 0x00191405, 0x001a1507, 0x001c1508, 0x001e1508, 0x001f1408, 0x001f1408, 0x00211408, 0x00211408, 0x00211408, 0x001f1306, 0x001d1105, 0x001e1407, 0x001e1407, 0x00201609, 0x0023180c, 0x0021160c, 0x0020150a, 0x001f160a, 0x00191004, 0x00191006, 0x001a1208, 0x001c1408, 0x001c1407, 0x00201408, 0x00211308, 0x00221408, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00241409, 0x00221509, 0x00201408, 0x00201609, 0x00211609, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1207, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1305, 0x001c1306, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1307, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001b1406, 0x001b1405, 0x001c1406, 0x001c1407, 0x001c1407, 0x001c1307, 0x001c1307, 0x001a1105, 0x001c1408, 0x001b1206, 0x001b1206, 0x001b1407, 0x00191407, 0x001b1407, 0x001b1405, 0x001b1405, 0x001b1405, 0x001e1409, 0x001c1408, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1207, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001a1306, 0x001a1306, 0x001a1306, 0x001a1306, 0x001b1204, 0x001b1204, 0x001c1305, 0x001c1305, 0x001c1307, 0x001c1307, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00201609, 0x00221608, 0x0024150a, 0x0028180b, 0x002c1a0b, 0x002c1a08, 0x00311c0c, 0x0036200d, 0x003b220a, 0x0044270d, 0x00543110, 0x00603b0c, 0x00784d0c, 0x00b88b2b, 0x00cca828, 0x00ccae1b, 0x00cab214, 0x00ccb40c, 0x00ccb40b, 0x00cbb408, 0x00cbb406, 0x00cbb406, 0x00cbb406, 0x00cab405, 0x00cab406, 0x00c9b407, 0x00cab307, 0x00ccb308, 0x00ccb006, 0x00caad08, 0x00cbab0b, 0x00caa70f, 0x00c09807, 0x00b78907, 0x00ac7a04, 0x00a47000, 0x00986100, 0x008f5600, 0x00844e04, 0x0077480b, 0x00512b00, 0x00442402, 0x003c2107, 0x00361d08, 0x00321c0a, 0x002f1d0d, 0x002a1b0a, 0x00231707, 0x00201508, 0x001c1409, 0x001c140a, 0x001b130b, 0x00191209, 0x00191209, 0x0018120a, 0x0018120b, 0x0018120b, 0x0018130c, 0x0019130c, 0x001a140c, 0x001e1409, 0x0022170a, 0x00291c0b, 0x00302108, 0x00342808, 0x00382b06, 0x00403008, 0x0051390c, 0x00644810, 0x00825d13, 0x00b28e1d, 0x00ccb31c, 0x00cab810, 0x00ccbb0b, 0x00ccbb0b, 0x00ccb70e, 0x00bf9d11, 0x00906400, 0x006d4400, 0x00583b04, 0x00493407, 0x00432c08, 0x003e2807, 0x00372403, 0x00322007, 0x002a1c04, 0x00241a08, 0x00171102, 0x000f0e00, 0x00121207, 0x0018160e, 0x0013100a, 0x00101007, 0x00101108, 0x000d1008, 0x000c1108, 0x000c100a, 0x000d110d, 0x000c120c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231b, 0x001c221b, 0x0010140d, 0x00101009, 0x00101009, 0x00121008, 0x00121008, 0x000f0d03, 0x00100d02, 0x00171206, 0x001f1808, 0x00241b0a, 0x00291c08, 0x002f1e04, 0x00352406, 0x003c2c09, 0x0042330a, 0x004c390c, 0x005f410d, 0x007e5811, 0x00b49127, 0x00ccb31f, 0x00c9b80b, 0x00c6b906, 0x00cab808, 0x00cbb010, 0x00ac880a, 0x007f5600, 0x00674402, 0x00523a04, 0x00403004, 0x00362907, 0x002f2204, 0x002d1f04, 0x002c1b07, 0x00271908, 0x0024180a, 0x001f160a, 0x001a1307, 0x00151104, 0x00141005, 0x00151007, 0x0015130a, 0x00131008, 0x00121008, 0x00111008, 0x00121008, 0x00121008, 0x00121008, 0x00131008, 0x00151106, 0x00161307, 0x00181308, 0x00181308, 0x00191308, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x00191306, 0x00191306, 0x00191405, 0x00191405, 0x00191405, 0x00191406, 0x001c1407, 0x001c1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00211408, 0x001f1206, 0x001e1206, 0x001e1407, 0x001d1205, 0x001f1408, 0x00201609, 0x001f1409, 0x001e1308, 0x0020170c, 0x001c1308, 0x00191006, 0x001b1309, 0x001c1408, 0x001c1407, 0x00201408, 0x00211308, 0x00221408, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00241409, 0x00221509, 0x00201408, 0x00201609, 0x00211609, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1207, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1307, 0x001c1407, 0x001c1406, 0x001c1305, 0x001c1306, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1307, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191405, 0x00191405, 0x001a1406, 0x001a1507, 0x001c1407, 0x001b1407, 0x001b1307, 0x00181105, 0x001c1408, 0x001b1205, 0x001a1105, 0x001c1408, 0x00191407, 0x001b1407, 0x001b1405, 0x001b1405, 0x001b1405, 0x001c1408, 0x001c1307, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1408, 0x001c1308, 0x001c1307, 0x001a1306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00181306, 0x00181306, 0x00191306, 0x00191306, 0x00191304, 0x00191304, 0x001b1204, 0x001b1204, 0x001c1307, 0x001c1307, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201609, 0x00221608, 0x0025170b, 0x0028180b, 0x002c1a0a, 0x002c1a08, 0x00311c0c, 0x0037200e, 0x003d260c, 0x00472c0d, 0x00583411, 0x00694011, 0x00845915, 0x00bf952e, 0x00ccac20, 0x00cab310, 0x00c7b50c, 0x00c9b708, 0x00c9b707, 0x00c8b606, 0x00cab507, 0x00cab408, 0x00cab408, 0x00cab20a, 0x00ccb10d, 0x00ccb00f, 0x00ccaa0d, 0x00caa50c, 0x00c69c08, 0x00c09007, 0x00b48001, 0x00ad7500, 0x00a56900, 0x00a46401, 0x00a26101, 0x009f6001, 0x00985804, 0x008a4c01, 0x00824c0a, 0x006f400b, 0x004d2800, 0x00462605, 0x003c2008, 0x00361d08, 0x00301a08, 0x002d1b0b, 0x00281908, 0x00221606, 0x00201508, 0x001c140a, 0x001b1308, 0x00191209, 0x00181109, 0x0018100a, 0x00181009, 0x0018110a, 0x0018110b, 0x0018120c, 0x0019130e, 0x001a130c, 0x001c140a, 0x0022170c, 0x0027190a, 0x002f2009, 0x00332508, 0x00382a08, 0x00403009, 0x004f380b, 0x00614410, 0x007d5813, 0x00ac881d, 0x00cbb120, 0x00cab812, 0x00ccbb0c, 0x00ccbc09, 0x00ccb90e, 0x00c1a312, 0x00936801, 0x006f4400, 0x00583b02, 0x004b3507, 0x00442d06, 0x003f2906, 0x00382403, 0x00342008, 0x002c1c05, 0x00251a08, 0x00181103, 0x00111004, 0x000f1004, 0x0017140c, 0x0015130c, 0x000f0f05, 0x000d0f05, 0x000d1008, 0x000c1108, 0x000b100a, 0x000d110d, 0x000c120c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00192219, 0x001a2018, 0x000f120c, 0x00101009, 0x00111009, 0x00141109, 0x00141109, 0x00100e04, 0x00120f04, 0x00181406, 0x00201808, 0x00241c07, 0x00291e06, 0x002e1d04, 0x00342305, 0x003c2c06, 0x00423408, 0x004e3b0b, 0x00654710, 0x00805910, 0x00ba992b, 0x00ccb41c, 0x00cab90a, 0x00c8bb09, 0x00cab80a, 0x00cab112, 0x00a48008, 0x007a5101, 0x00623f04, 0x00503806, 0x00413006, 0x00362708, 0x002d2104, 0x002b1f05, 0x002b1a08, 0x0027190a, 0x0024180b, 0x001f150a, 0x00181308, 0x00141005, 0x00141107, 0x00131008, 0x0017140d, 0x0014110a, 0x00100d06, 0x000f0e06, 0x00121008, 0x00131008, 0x00131007, 0x00131108, 0x00141208, 0x00151208, 0x00171208, 0x00181207, 0x00191207, 0x001a1306, 0x001a1306, 0x001b1407, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1307, 0x001b1307, 0x001b1406, 0x001a1406, 0x001a1406, 0x001a1406, 0x001b1405, 0x001c1305, 0x001e1407, 0x001e1407, 0x001d1104, 0x00201408, 0x00201408, 0x00201408, 0x001f1407, 0x001f1408, 0x001e1407, 0x001d1205, 0x001e1408, 0x001d1206, 0x001d1206, 0x0020160a, 0x001d1308, 0x001a1005, 0x001a1308, 0x001b1408, 0x001c1407, 0x00201509, 0x00221408, 0x00221408, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00211408, 0x00221408, 0x00231509, 0x00231509, 0x00231509, 0x00221509, 0x001f1306, 0x00201408, 0x001f1408, 0x001f1407, 0x001c1104, 0x001c1104, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001c1307, 0x001c1307, 0x001c1206, 0x001b1106, 0x001c1206, 0x001b1407, 0x001c1407, 0x001c1306, 0x001c1307, 0x001d1407, 0x001d1407, 0x001d1306, 0x001d1306, 0x001e1407, 0x001d1305, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1306, 0x001d1306, 0x001d1207, 0x001d1208, 0x001d1207, 0x001d1207, 0x001c1106, 0x001b1005, 0x001c1005, 0x001c1106, 0x001c1106, 0x001d1206, 0x001d1206, 0x001d1206, 0x001d1307, 0x001e1308, 0x001e1308, 0x001c1105, 0x001c1105, 0x001a1105, 0x001a1105, 0x001a1105, 0x001a1105, 0x00191105, 0x00191105, 0x00191105, 0x001a1206, 0x001b1306, 0x001b1407, 0x001b1407, 0x001b1407, 0x001a1406, 0x00191306, 0x00191306, 0x00181004, 0x00191306, 0x00191105, 0x00181105, 0x001c1408, 0x001a1405, 0x001b1406, 0x001c1406, 0x001c1406, 0x001c1406, 0x001c1408, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1308, 0x001c1307, 0x001c1307, 0x001a1306, 0x00191306, 0x00191306, 0x001a1306, 0x001a1306, 0x00191407, 0x001b1408, 0x001b1408, 0x001b1408, 0x001c1408, 0x001c1408, 0x001c1308, 0x001c1308, 0x001c1408, 0x001c1408, 0x001e1409, 0x001c1408, 0x001c1408, 0x001c1307, 0x001c1307, 0x001c1307, 0x001d1207, 0x001d1207, 0x001d1208, 0x001d1208, 0x001e1308, 0x001e1408, 0x001f1408, 0x001f1409, 0x001f1408, 0x001f1407, 0x001f1407, 0x001f1408, 0x00201509, 0x0021170a, 0x00231609, 0x0028190c, 0x002b1b0c, 0x002e1c0d, 0x00301c0b, 0x00331c0b, 0x0038200d, 0x003e270c, 0x00482d0e, 0x005a3513, 0x006d4414, 0x008c6214, 0x00c49c28, 0x00ccae18, 0x00cbb209, 0x00cab408, 0x00cbb608, 0x00cbb70b, 0x00cbb408, 0x00ccb208, 0x00ccb00e, 0x00ccac10, 0x00cca814, 0x00c7a010, 0x00c0940c, 0x00b58604, 0x00b17c01, 0x00ac7200, 0x00a66800, 0x00a66700, 0x00a66601, 0x00a76805, 0x00ab6d09, 0x00b57a11, 0x00be8418, 0x00b47918, 0x00915707, 0x00824d0b, 0x00683a06, 0x004c2700, 0x00422404, 0x003a2008, 0x00351c07, 0x002e1b08, 0x002b1809, 0x00281808, 0x00241707, 0x001e1405, 0x001b1206, 0x00191208, 0x00181208, 0x00181009, 0x0018100a, 0x0017100a, 0x00161009, 0x00171009, 0x0018110b, 0x0018120c, 0x0018120b, 0x001a1208, 0x001e1408, 0x00271b0c, 0x002e2008, 0x00322408, 0x00382808, 0x003f2f08, 0x004d360b, 0x005e400f, 0x007a5412, 0x00a5801b, 0x00caaf24, 0x00cbb615, 0x00ccbb0c, 0x00ccbb0a, 0x00ccba0f, 0x00c4a614, 0x00996e04, 0x00704400, 0x00593901, 0x004b3606, 0x00442e06, 0x003f2906, 0x00382404, 0x00342106, 0x002e1c05, 0x00281b0a, 0x001a1404, 0x00111005, 0x000d0c03, 0x0014140c, 0x0014130a, 0x00101007, 0x000e0f05, 0x000d1008, 0x000d1009, 0x000c0f09, 0x000c100c, 0x000c110c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001c251c, 0x00151c14, 0x000f110b, 0x00101009, 0x0013110b, 0x00141109, 0x00121008, 0x000f0c04, 0x00141007, 0x001b1708, 0x00211a07, 0x00251d05, 0x002a1f06, 0x00312008, 0x00372608, 0x003c2d06, 0x00433408, 0x004c3808, 0x0064440c, 0x00856013, 0x00c09f2e, 0x00ccb41c, 0x00cbba0c, 0x00c9bc0b, 0x00cbb80d, 0x00c8b011, 0x00a07c03, 0x00784f02, 0x00603e07, 0x004e3808, 0x00402f06, 0x00382608, 0x002e2105, 0x00291d06, 0x002a1909, 0x0026180b, 0x0022160a, 0x001d1409, 0x00181308, 0x00141004, 0x00101006, 0x000f1007, 0x00100f08, 0x00110e08, 0x0013100a, 0x0011100a, 0x00121007, 0x00110f07, 0x00131107, 0x00131107, 0x00131107, 0x00141107, 0x00171208, 0x00181107, 0x00181207, 0x00191306, 0x001a1306, 0x001b1407, 0x001b1407, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1405, 0x001c1305, 0x001e1407, 0x001e1407, 0x001e1205, 0x0023160a, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201508, 0x00201508, 0x0020150a, 0x001f1409, 0x00170e03, 0x00171004, 0x001b1508, 0x001d1407, 0x00201307, 0x00211308, 0x00211308, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00211408, 0x00211408, 0x00211408, 0x00221509, 0x00211408, 0x00211408, 0x00201408, 0x00221509, 0x00221509, 0x00201609, 0x00201508, 0x001d1305, 0x001d1305, 0x001d1306, 0x001e1306, 0x001d1306, 0x001d1306, 0x001c1308, 0x001c1308, 0x001b1206, 0x001b1206, 0x001a1306, 0x001b1407, 0x001c1408, 0x001c1308, 0x001c1408, 0x001d1407, 0x001d1407, 0x001d1306, 0x001d1306, 0x001d1306, 0x001d1306, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1306, 0x001d1306, 0x001d1306, 0x001d1208, 0x001d1208, 0x001d1207, 0x001d1207, 0x001d1208, 0x001e1308, 0x001f1409, 0x001f1409, 0x001f1409, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1106, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001a1306, 0x001b1407, 0x001b1408, 0x001c1408, 0x001c1408, 0x001b1408, 0x001a1306, 0x00191206, 0x001b1408, 0x00181105, 0x00181004, 0x001c1509, 0x001a1304, 0x001c1406, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001a1306, 0x00191306, 0x00191306, 0x00191306, 0x00191206, 0x00181105, 0x00181105, 0x00181105, 0x00181105, 0x001b1206, 0x001b1206, 0x001a1105, 0x001a1105, 0x001a1105, 0x001a1105, 0x001b1206, 0x001c1307, 0x001c1307, 0x001e1409, 0x001e1409, 0x001f150a, 0x001f1409, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001c1106, 0x001d1207, 0x001d1205, 0x001e1407, 0x001e1407, 0x00201609, 0x0022170a, 0x00221509, 0x00241608, 0x00281809, 0x002e1a0b, 0x002f1a09, 0x00331c0b, 0x0039200d, 0x003f270c, 0x00492c0e, 0x005c3814, 0x00714617, 0x00936618, 0x00c7a02b, 0x00ccac19, 0x00ccae0e, 0x00cbad0f, 0x00caa912, 0x00c8a70f, 0x00c8a20c, 0x00c39b08, 0x00ba8f07, 0x00b18303, 0x00ac7801, 0x00a67100, 0x00a36c00, 0x00a36a01, 0x00a36702, 0x00a76804, 0x00ab6d08, 0x00b0770f, 0x00b98417, 0x00c2901d, 0x00c89c24, 0x00cca324, 0x00cca421, 0x00bd8c17, 0x00925e04, 0x00804c08, 0x00643804, 0x004a2700, 0x00402202, 0x00371d04, 0x00301a04, 0x00301c08, 0x002a1909, 0x00261704, 0x00231504, 0x001f1305, 0x001b1106, 0x00191208, 0x00181308, 0x0017110a, 0x0017100b, 0x0017100b, 0x0017110a, 0x0017110a, 0x0017110a, 0x0018120c, 0x0017130b, 0x001a1308, 0x001c1408, 0x00291d0d, 0x002e2008, 0x00312407, 0x00382807, 0x003f2f08, 0x004e360c, 0x005c3f0e, 0x00785213, 0x00a27c1a, 0x00c9ad26, 0x00ccb717, 0x00ccbb0d, 0x00ccbb0d, 0x00cbba10, 0x00c4a813, 0x009d7005, 0x00744800, 0x00593c03, 0x004b3508, 0x00442e06, 0x003f2906, 0x00382405, 0x00342006, 0x00301c05, 0x002a1c0c, 0x001f1809, 0x00101005, 0x000d0c04, 0x0014130c, 0x0014130a, 0x00101007, 0x00101007, 0x000f1008, 0x000e110a, 0x000e100c, 0x000e110d, 0x000e130e, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00222922, 0x001b2018, 0x00151811, 0x00171610, 0x001a1812, 0x001c1810, 0x0017140c, 0x0016130b, 0x001e1910, 0x00231d10, 0x0027200d, 0x002c210b, 0x0030250c, 0x00382810, 0x003d2c0f, 0x0044350f, 0x004c3c10, 0x00554011, 0x006b4c13, 0x00906b1c, 0x00c5a534, 0x00ccb41e, 0x00cbbb0d, 0x00c9bb0c, 0x00cbb80f, 0x00c8ae11, 0x009e7901, 0x007b5004, 0x00624008, 0x00513c0d, 0x0045330b, 0x00402c0e, 0x0035280d, 0x0030240c, 0x002d1c0d, 0x00281b0e, 0x0025180d, 0x0020180c, 0x001e180d, 0x0019160b, 0x0016150b, 0x0014160c, 0x0016150e, 0x001b1812, 0x0017140e, 0x0015140e, 0x0018160d, 0x0018160e, 0x0018160c, 0x0019170d, 0x0018180d, 0x001a170d, 0x001d180e, 0x001f180e, 0x0020180d, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0021180c, 0x0021180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020190b, 0x00221a0c, 0x00241a0e, 0x00241a0e, 0x0025190d, 0x002a1e12, 0x00281b0f, 0x0025180c, 0x0024180c, 0x0024190d, 0x0024190c, 0x0024180c, 0x0024190c, 0x00271c10, 0x00281d10, 0x00281d12, 0x00281d12, 0x0020170c, 0x0020190c, 0x0020190d, 0x00231a0c, 0x00251a0d, 0x00281a0f, 0x0027190d, 0x0026190d, 0x0026180c, 0x0027180c, 0x0027180c, 0x0027180d, 0x0026190d, 0x00261a0e, 0x00281b0f, 0x00281b10, 0x00271a0e, 0x00281b0f, 0x00281b10, 0x00271a0e, 0x0025190d, 0x0024180c, 0x0024180c, 0x00251a0d, 0x0024190c, 0x0024190c, 0x0023180c, 0x0024190c, 0x0024190c, 0x00231a0e, 0x00231a0e, 0x0022190d, 0x0022190d, 0x0021190d, 0x0020190d, 0x0021190e, 0x0022190e, 0x0022190d, 0x00231a0d, 0x00241a0d, 0x0024190c, 0x0024190c, 0x0024190c, 0x0024190c, 0x00251b0e, 0x00251b0f, 0x00251b0e, 0x00261c0f, 0x00251b0e, 0x00251b0e, 0x00251a10, 0x00251a10, 0x0024190f, 0x0024190f, 0x0024190f, 0x0024180e, 0x0024190f, 0x0024190f, 0x0024190f, 0x0024190f, 0x0024190e, 0x0024190e, 0x0024190e, 0x0024190e, 0x0024190e, 0x0022180c, 0x0022180c, 0x0021180d, 0x0021180d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0021180d, 0x0022190d, 0x00221a0e, 0x00221b0f, 0x00211a0e, 0x0020190e, 0x00211a0e, 0x00211a0e, 0x00211a0e, 0x00211a0f, 0x00231c10, 0x0020190d, 0x00201a0e, 0x00241c11, 0x00231c0f, 0x00221b0d, 0x0020190a, 0x00211a0c, 0x00221b0c, 0x00231a0e, 0x00231a0e, 0x00221a0e, 0x0022190e, 0x0022190e, 0x0022190e, 0x0022190e, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190e, 0x0022190e, 0x0022190e, 0x0022190e, 0x0021180d, 0x0021180d, 0x0020190d, 0x0020190d, 0x0020190d, 0x0020190d, 0x0020190d, 0x0020190d, 0x00201a0e, 0x00201a0e, 0x00211a0e, 0x00231a0f, 0x00231a0f, 0x0022190e, 0x0022190e, 0x0022190e, 0x0022190e, 0x00231a0f, 0x00231a0e, 0x00231a10, 0x00231a0f, 0x00221a0f, 0x00221a0f, 0x0024190f, 0x0024190f, 0x0024190f, 0x0024190e, 0x0024190e, 0x0024180e, 0x0024180e, 0x0024190e, 0x0024190e, 0x00251c0f, 0x00251c0f, 0x00241a0d, 0x00261c10, 0x00271c10, 0x00281b10, 0x002c1e10, 0x00302010, 0x00342112, 0x0036210f, 0x00382110, 0x003d2512, 0x00442c12, 0x004e3113, 0x00623d1b, 0x00744819, 0x0092641b, 0x00c4982e, 0x00c39c17, 0x00bf9a0b, 0x00b89208, 0x00b08506, 0x00aa7d02, 0x00a47400, 0x009f6c00, 0x009c6800, 0x009c6601, 0x00a16704, 0x00a46709, 0x00ac6c14, 0x00b3741b, 0x00ba7c21, 0x00c48928, 0x00c6942a, 0x00c89d2b, 0x00cca42a, 0x00cca827, 0x00ccac22, 0x00cbad1c, 0x00ccad1b, 0x00b99210, 0x008f6000, 0x007f4e08, 0x00623804, 0x004c2c04, 0x00432606, 0x003e240c, 0x0038220c, 0x0034210f, 0x00301e0f, 0x002c1d0b, 0x00291c0c, 0x0024180b, 0x0021180c, 0x0020180d, 0x001f190e, 0x001f1811, 0x001f1812, 0x001e1811, 0x001d1810, 0x001e1811, 0x001f1811, 0x001f1812, 0x001e1911, 0x0020180f, 0x0022180d, 0x002e2313, 0x0032240d, 0x0034280b, 0x003c2c0b, 0x0044320c, 0x00513a11, 0x00604212, 0x00785212, 0x00a37c1b, 0x00c8ac25, 0x00ccb719, 0x00ccbb0f, 0x00ccbb0e, 0x00cbba10, 0x00c6a814, 0x00a27508, 0x007b4e04, 0x005f400b, 0x00503b0e, 0x0049330c, 0x00442e0d, 0x003f2a0c, 0x003b270d, 0x0036220c, 0x00302111, 0x00261e10, 0x0017160c, 0x0014130c, 0x00191811, 0x001b1b11, 0x00191810, 0x0017170e, 0x0014160e, 0x00141610, 0x00141510, 0x00131611, 0x00141813, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07}; \ No newline at end of file +uint32_t intense_milk[103320]; +// = {0x00152021, 0x00141f21, 0x00141d20, 0x00131d1f, 0x00131e1e, 0x00131e1e, 0x00141f1f, 0x00141f1f, 0x00141e20, 0x00131d1f, 0x00131d1f, 0x00131d1e, 0x00121c1c, 0x00111c1c, 0x00111c1a, 0x00111c1a, 0x00111c1a, 0x00111b19, 0x00111b19, 0x00111b19, 0x00111b19, 0x00101918, 0x00101918, 0x00101918, 0x00101918, 0x00101916, 0x00101916, 0x00101818, 0x00101817, 0x00101817, 0x00101817, 0x00101817, 0x00101817, 0x000f1817, 0x000f1816, 0x000e1816, 0x000d1714, 0x000d1714, 0x000d1714, 0x000c1613, 0x000c1512, 0x000c1512, 0x000e1611, 0x000e1611, 0x000e1611, 0x000e1511, 0x000d1410, 0x000c1410, 0x000c1410, 0x000c1410, 0x000c1410, 0x000c1410, 0x000c1410, 0x000c140f, 0x000c140e, 0x000c140d, 0x000c140d, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000f1310, 0x000d140e, 0x000d140e, 0x000c140c, 0x000c140c, 0x000c140c, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140f, 0x000b1410, 0x000b1510, 0x000c1510, 0x000c1511, 0x000c1512, 0x000c1610, 0x000c1611, 0x000c1710, 0x000f1610, 0x00101811, 0x000f1814, 0x00101914, 0x00101a17, 0x00101a17, 0x00101916, 0x00101915, 0x00101918, 0x00101918, 0x00101918, 0x000f1a18, 0x000f1b18, 0x000e1c19, 0x000c1d19, 0x000c1c19, 0x000d1c19, 0x000d1c19, 0x000d1c19, 0x000f1c19, 0x000e1b18, 0x000e1918, 0x000f1a18, 0x000f1a18, 0x00111c1a, 0x00121b18, 0x00111c18, 0x00101b17, 0x00141c19, 0x002d3030, 0x00454545, 0x00403e3e, 0x00444040, 0x00484446, 0x004a4649, 0x004a484b, 0x00494448, 0x004a4244, 0x004b4040, 0x004a3d3b, 0x004c3e3a, 0x0050403c, 0x004c3b35, 0x00493833, 0x00473530, 0x00473630, 0x0045322e, 0x00473430, 0x00413831, 0x0039322c, 0x00342c26, 0x00322b25, 0x0038332c, 0x00372e26, 0x003a2a22, 0x00412c23, 0x003e1e15, 0x00401b10, 0x003d1c0d, 0x003a1e09, 0x00462812, 0x0050301a, 0x004c2c16, 0x004e2c1a, 0x004f2c1c, 0x00492515, 0x00442210, 0x004c2e18, 0x00573a1f, 0x005e3419, 0x0064391c, 0x00673b1a, 0x00633914, 0x00643a18, 0x00532b0a, 0x004e2508, 0x00532a10, 0x005c3418, 0x005e3818, 0x00603a1a, 0x005c3515, 0x00573113, 0x00593417, 0x00583416, 0x005a3414, 0x005d3716, 0x00613819, 0x00643c1c, 0x006c4220, 0x00673d18, 0x00653c16, 0x00633a16, 0x00603414, 0x00633815, 0x00683c18, 0x006e441c, 0x006e421b, 0x00643910, 0x006a3f18, 0x005b320b, 0x00643c15, 0x00633b16, 0x00613b16, 0x00603a16, 0x005d3818, 0x00583414, 0x005b3518, 0x004c280b, 0x004a2508, 0x00502b0c, 0x005c3416, 0x00613719, 0x0061371a, 0x005e3716, 0x00502c0b, 0x003c220c, 0x00311c0c, 0x00261810, 0x00201414, 0x0017140d, 0x00141509, 0x0015160c, 0x001a1a10, 0x0018170f, 0x00191910, 0x0018180f, 0x0016160d, 0x0016160d, 0x0016160d, 0x0016160d, 0x0015170c, 0x0018160c, 0x001a160c, 0x00201810, 0x00281d16, 0x00342720, 0x00302a24, 0x00312924, 0x00302b24, 0x00282a20, 0x001b2420, 0x00182623, 0x00182824, 0x00152824, 0x00152824, 0x00152724, 0x00172625, 0x00182627, 0x00182627, 0x00182627, 0x00172526, 0x00162424, 0x00162425, 0x00172526, 0x00182526, 0x00172524, 0x00162423, 0x00152420, 0x00142320, 0x00152220, 0x0013201d, 0x00131f1e, 0x0013201f, 0x00121f1e, 0x00101d1d, 0x00101c1c, 0x000f1c1b, 0x00101b1b, 0x00101a1a, 0x000f1819, 0x000f1818, 0x000e1814, 0x000e1611, 0x000e170f, 0x000e170e, 0x000e1610, 0x00101610, 0x00101610, 0x00101610, 0x00101510, 0x0010140f, 0x000e140e, 0x000d140e, 0x000c140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000e140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1417, 0x000b1517, 0x00091416, 0x000a1417, 0x000b1616, 0x000c1716, 0x000c1716, 0x000c1717, 0x000c1718, 0x000c1819, 0x000d1819, 0x000d1818, 0x000c1818, 0x000c1716, 0x000c1715, 0x000c1715, 0x000c1715, 0x000c1514, 0x000c1514, 0x000c1514, 0x000c1514, 0x000b1413, 0x000b1413, 0x000b1413, 0x000b1413, 0x000a1410, 0x000a1410, 0x00091211, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081010, 0x0008100f, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00040e0b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d07, 0x00050d07, 0x00050d06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c08, 0x00060c07, 0x00060c07, 0x00050d05, 0x00050d05, 0x00050d05, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040f09, 0x00040f0a, 0x00040f0b, 0x00050f0a, 0x0005100a, 0x00061008, 0x00070f08, 0x00070f08, 0x0005100a, 0x0006100b, 0x0006100c, 0x0007110d, 0x0008120f, 0x0008120f, 0x00091311, 0x00091311, 0x00091311, 0x00081311, 0x00081412, 0x00071512, 0x00051612, 0x00061612, 0x00061512, 0x00061512, 0x00071512, 0x00081412, 0x00081411, 0x00081311, 0x00081311, 0x00081311, 0x000a1613, 0x000b1411, 0x000c1613, 0x000c1310, 0x001c2220, 0x00343734, 0x00343433, 0x00302c2c, 0x003a3436, 0x00464042, 0x00403c3d, 0x00393436, 0x003b3537, 0x003e3536, 0x003c3130, 0x003a2d2a, 0x003e2f29, 0x0044352f, 0x00483831, 0x003e2d26, 0x0032211a, 0x002d1c14, 0x00301d16, 0x0033241c, 0x0034271f, 0x00332820, 0x00342920, 0x002e241c, 0x00281e15, 0x00302219, 0x00342118, 0x00341e13, 0x00402216, 0x00472515, 0x00452513, 0x00371802, 0x00381802, 0x003a1a06, 0x00452410, 0x004c2c14, 0x004d2b14, 0x00502d15, 0x004c2a10, 0x00432304, 0x004c2d0e, 0x005d3315, 0x00603415, 0x00603514, 0x00623814, 0x005f3612, 0x005a320f, 0x004f2708, 0x00482001, 0x004c2406, 0x005b3414, 0x005a3413, 0x00552f10, 0x004f280b, 0x00441f04, 0x004d280b, 0x00583113, 0x005b3414, 0x005f3715, 0x00613a16, 0x00694019, 0x00643c14, 0x00653c14, 0x00633915, 0x00582e0d, 0x00582e0d, 0x00613612, 0x00683d18, 0x00633811, 0x00643813, 0x00603610, 0x005b320c, 0x00603711, 0x005d3510, 0x005d3611, 0x005d3814, 0x005c3616, 0x00583314, 0x00542f11, 0x00462104, 0x00421d00, 0x00553013, 0x005b3416, 0x00633a1c, 0x005c3416, 0x00542f10, 0x00472407, 0x00341904, 0x002c1709, 0x0021120a, 0x001b100d, 0x0016110b, 0x00151409, 0x00141309, 0x0018170e, 0x00131108, 0x00121007, 0x00121007, 0x00111108, 0x00111108, 0x00111108, 0x00111108, 0x00101206, 0x00101105, 0x00100e04, 0x00161007, 0x00191008, 0x001e140c, 0x00241c15, 0x00251c16, 0x0028211a, 0x0026271e, 0x0018201c, 0x0014201d, 0x0010201d, 0x000f211c, 0x000f201d, 0x0010201f, 0x0010201f, 0x00101f20, 0x00112020, 0x00112020, 0x00122021, 0x00112020, 0x00101f20, 0x00101e1f, 0x000f1d1e, 0x000f1d1c, 0x000d1c1b, 0x000c1c18, 0x000c1b18, 0x000d1a18, 0x000a1814, 0x000a1716, 0x000a1716, 0x00091615, 0x00081514, 0x00081414, 0x00071413, 0x00071313, 0x00071212, 0x00061111, 0x00061010, 0x00050f0c, 0x00060e09, 0x00060e06, 0x00060e06, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c07, 0x00050c06, 0x00050c06, 0x00040c06, 0x00040c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060b06, 0x00060b06, 0x00060b06, 0x00060b06, 0x00060b06, 0x00060b06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000b1517, 0x000b1517, 0x00091416, 0x00081415, 0x000a1414, 0x000a1414, 0x000a1414, 0x000a1414, 0x000b1516, 0x000b1517, 0x000b1517, 0x000b1516, 0x000b1515, 0x000a1414, 0x000a1513, 0x000b1413, 0x000b1413, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x00091211, 0x00091211, 0x0008120f, 0x0008120f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0006100e, 0x0006100d, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x00050c0a, 0x00060d0b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c09, 0x00070d08, 0x00070d08, 0x00060e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d09, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00060e09, 0x00060e09, 0x0005100a, 0x0005100a, 0x0006100c, 0x0007110d, 0x0007110d, 0x0008120f, 0x00091211, 0x00091211, 0x000a1412, 0x00081412, 0x00081413, 0x00081613, 0x00061512, 0x00061512, 0x00061512, 0x00061512, 0x00061512, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x000a1410, 0x000c1310, 0x00171b19, 0x00292c2b, 0x002e2d2c, 0x002c2828, 0x00393433, 0x00484041, 0x004e4545, 0x00474040, 0x003f3838, 0x00372e2d, 0x00312524, 0x00322420, 0x0034241e, 0x0034241c, 0x00312319, 0x003b2b22, 0x0044332a, 0x00402f25, 0x002e1e14, 0x002c190e, 0x0028170c, 0x0029180d, 0x002a190d, 0x002c1b10, 0x00312015, 0x00342219, 0x002c1910, 0x002c180c, 0x00341f10, 0x00381e0e, 0x00482816, 0x0052311c, 0x00502f17, 0x0041200b, 0x003d1c08, 0x003e1c08, 0x0045250e, 0x00503017, 0x004e2c11, 0x00502d10, 0x00563114, 0x004a2404, 0x00522808, 0x005e3214, 0x00592d0c, 0x00603611, 0x00643b14, 0x00633a14, 0x005c3411, 0x00502808, 0x00502808, 0x00542c0c, 0x005c3414, 0x00532c0c, 0x00451f04, 0x0048210c, 0x00462007, 0x00552f12, 0x005c3516, 0x005e3713, 0x00623b13, 0x00653c13, 0x00643c11, 0x00613810, 0x00623814, 0x00552c0a, 0x00522807, 0x00613817, 0x00653c18, 0x00582f0c, 0x005e3411, 0x005c330e, 0x005c340e, 0x005c340f, 0x005a330d, 0x0058310d, 0x005c3513, 0x00583112, 0x00583315, 0x00502b0f, 0x00462003, 0x00512c0f, 0x00563013, 0x005e3819, 0x0060391b, 0x005b3518, 0x0049260d, 0x003c1a03, 0x00301707, 0x00281307, 0x0023140b, 0x001d130c, 0x0019140c, 0x0019160c, 0x0018140c, 0x0016120a, 0x0014110a, 0x00141109, 0x00121008, 0x00131209, 0x0013130a, 0x00131209, 0x00131209, 0x00111308, 0x00101207, 0x000f1004, 0x00131006, 0x00161008, 0x00181108, 0x001c130c, 0x00271a15, 0x00251b15, 0x00242119, 0x001d231e, 0x00141d1c, 0x00121f1c, 0x0010201c, 0x0010201d, 0x0010201f, 0x00112020, 0x00122021, 0x00122021, 0x00112020, 0x00101f20, 0x00101e1f, 0x00101e1f, 0x00101e1f, 0x00101e1f, 0x000f1d1c, 0x000e1c1b, 0x000c1b18, 0x000b1a17, 0x000b1816, 0x000a1814, 0x00091615, 0x00091615, 0x000a1514, 0x000a1414, 0x00081414, 0x00081313, 0x00081212, 0x00071010, 0x00061010, 0x0006100f, 0x00050f0c, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000b1517, 0x000b1517, 0x00091416, 0x00081414, 0x000a1414, 0x000a1513, 0x000a1414, 0x000a1414, 0x000b1515, 0x000b1515, 0x000b1515, 0x000b1515, 0x000b1515, 0x000a1414, 0x000a1513, 0x000b1413, 0x000b1413, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091310, 0x00091310, 0x00091310, 0x0008120f, 0x0008120f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0006100e, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00040e09, 0x00050d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d08, 0x00070d08, 0x00060e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d09, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100c, 0x0007110d, 0x0007110d, 0x0008120f, 0x00091310, 0x00091310, 0x000a1412, 0x00081412, 0x00081413, 0x00081613, 0x00061512, 0x00061512, 0x00061512, 0x00061512, 0x00061512, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081410, 0x000a1410, 0x000c1210, 0x00101512, 0x001e201d, 0x00323030, 0x00464340, 0x00554d4c, 0x004f4645, 0x00443c3b, 0x00423838, 0x00403837, 0x003d3331, 0x003b2e2c, 0x00382924, 0x0034241c, 0x0034271c, 0x00392c22, 0x002f2217, 0x0034261a, 0x00433428, 0x00443428, 0x00312014, 0x00281608, 0x002b170a, 0x002a1808, 0x002b1708, 0x002c1609, 0x00331a10, 0x00371f14, 0x00321b0e, 0x002e1607, 0x00311905, 0x00442810, 0x004a2810, 0x00553218, 0x0058351a, 0x0046240c, 0x00391802, 0x003d1c07, 0x0043220e, 0x004f2c16, 0x00522e14, 0x004c260a, 0x005b3013, 0x0054280c, 0x00532909, 0x005d3210, 0x005c330d, 0x00623912, 0x00643b14, 0x00603813, 0x0059310d, 0x00532b09, 0x00532a09, 0x00583110, 0x00563010, 0x00452005, 0x00401905, 0x00442008, 0x0049240a, 0x00583114, 0x00643c15, 0x00633a11, 0x00653d11, 0x00643c10, 0x005e350c, 0x005e3510, 0x00512908, 0x004d2505, 0x00593210, 0x0055300e, 0x00542c0b, 0x005c3410, 0x00552e0a, 0x005f3713, 0x00562f0a, 0x0056300a, 0x0056300c, 0x00583210, 0x00542f10, 0x00553013, 0x004c280c, 0x00482306, 0x004e2b0d, 0x004f2c0e, 0x005b3718, 0x00573311, 0x00502c0e, 0x003c1a03, 0x00331604, 0x002d1408, 0x00251207, 0x0024140b, 0x001d140a, 0x00191309, 0x00181108, 0x001b150d, 0x001a150e, 0x00141009, 0x00100e06, 0x000f0e05, 0x000e0e05, 0x000e0e05, 0x000e0f06, 0x00101007, 0x00121107, 0x00131308, 0x00111308, 0x00141308, 0x00151308, 0x00181108, 0x001c120b, 0x0022150f, 0x00251b13, 0x00211d15, 0x0020241f, 0x00141e1b, 0x00101d1a, 0x0010201c, 0x0010201d, 0x0011201f, 0x00112020, 0x00122021, 0x00122021, 0x00112020, 0x00101f20, 0x00101e1f, 0x00101e1f, 0x00101e1d, 0x00101e1d, 0x000f1d1c, 0x000e1c1b, 0x000c1b18, 0x000b1a17, 0x000b1816, 0x000a1814, 0x00091615, 0x00091615, 0x000a1514, 0x000a1414, 0x00081414, 0x00081313, 0x00081212, 0x00071011, 0x00061010, 0x0006100e, 0x00050f0c, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1414, 0x00091414, 0x00081414, 0x00081313, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00091413, 0x000a1513, 0x000a1414, 0x000b1414, 0x000b1413, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x00091211, 0x00091310, 0x00091310, 0x00091310, 0x0008120f, 0x0008120f, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100d, 0x0006100e, 0x0006100d, 0x0006100c, 0x0006100c, 0x0008100c, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d05, 0x00040d07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008120d, 0x0008120d, 0x0007130f, 0x0007130f, 0x00081311, 0x00081311, 0x00081412, 0x00071512, 0x00061512, 0x00071512, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081510, 0x00081510, 0x00091410, 0x000f1514, 0x00101514, 0x00171c18, 0x00323633, 0x00424340, 0x004a4b48, 0x00424040, 0x00312e2c, 0x00302a28, 0x00342c2c, 0x00383132, 0x00413837, 0x003c3330, 0x003d342f, 0x00383128, 0x002f291e, 0x002f271d, 0x003c3128, 0x0033271e, 0x0035261d, 0x00403227, 0x00403126, 0x002c1c10, 0x00271708, 0x00291807, 0x002a1604, 0x002e1806, 0x00301709, 0x00351a0d, 0x00412718, 0x003e2411, 0x003e200c, 0x00401d08, 0x004c2910, 0x00512c10, 0x00543011, 0x00563315, 0x00462409, 0x00411f08, 0x003b1905, 0x003f1c0c, 0x004b2814, 0x004d2a10, 0x004c2807, 0x00553010, 0x00583212, 0x00562e0b, 0x005c320d, 0x0060350d, 0x00643b12, 0x00633a13, 0x00582f0b, 0x00552c0a, 0x00522b09, 0x00502a0b, 0x004e290c, 0x0045240a, 0x00351700, 0x003f1e09, 0x004b2813, 0x004c260c, 0x0068401b, 0x00623911, 0x00643b10, 0x00643c10, 0x005c350c, 0x005b3410, 0x004c2607, 0x00442105, 0x004c2a0e, 0x00462406, 0x004d280a, 0x00583212, 0x0055300f, 0x005a3412, 0x004d2804, 0x00542d0b, 0x004f2704, 0x00532c0c, 0x00522c0e, 0x00502c10, 0x00452409, 0x00482810, 0x00412008, 0x00492810, 0x004c2c11, 0x004a2c0f, 0x003e2106, 0x002e1300, 0x002c1404, 0x00291409, 0x0024120a, 0x0022150b, 0x001c140a, 0x00191408, 0x0018140b, 0x001e1a10, 0x00130f06, 0x00120f07, 0x00100f06, 0x000e0c04, 0x00121008, 0x0016140c, 0x0016140c, 0x00141309, 0x00141208, 0x00141208, 0x00141208, 0x00161409, 0x00161208, 0x0018140b, 0x001b130b, 0x001e130c, 0x00241b13, 0x00201f14, 0x0020251d, 0x0017211d, 0x00101e1b, 0x00111f1d, 0x00121f1e, 0x0013201f, 0x0013201f, 0x0013201f, 0x0011201f, 0x0011201f, 0x000f201e, 0x000f1d1d, 0x000f1d1d, 0x000f1d1c, 0x000f1d1c, 0x00101c1c, 0x000f1c1b, 0x000c1918, 0x000c1918, 0x000c1716, 0x000b1515, 0x000b1515, 0x000a1414, 0x00091414, 0x00081414, 0x00081313, 0x00081313, 0x00081211, 0x0007100f, 0x0006100e, 0x0006100e, 0x00050f0c, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1414, 0x00091414, 0x00081414, 0x00081311, 0x00081412, 0x00081410, 0x00081410, 0x00081410, 0x00081411, 0x00081412, 0x00091412, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x00081110, 0x0008120f, 0x00091310, 0x0009130e, 0x0008120d, 0x0007110c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0008100c, 0x00070f0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040d08, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008120d, 0x0008120d, 0x0007130f, 0x0007130f, 0x00081410, 0x00081410, 0x00081411, 0x00071512, 0x00061512, 0x00071512, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081513, 0x00061510, 0x00071510, 0x000c1410, 0x000c130f, 0x00121714, 0x002d312e, 0x00454845, 0x004c4d4b, 0x003d3e3c, 0x00333130, 0x00353231, 0x00373333, 0x00353130, 0x00332d2d, 0x00322d2c, 0x003d3635, 0x003e3935, 0x003c3833, 0x0037342d, 0x00342e28, 0x00312821, 0x00382c24, 0x00362822, 0x0031241c, 0x0041342a, 0x00403228, 0x00302015, 0x002b1a0b, 0x002c1807, 0x00301b08, 0x00341b0a, 0x00371c0c, 0x00371b09, 0x003c1f0c, 0x004b2914, 0x0048230d, 0x004c250c, 0x004f280c, 0x00502a09, 0x00583410, 0x005a3718, 0x004d2810, 0x00421e0c, 0x003e1a0c, 0x003f1d0b, 0x00482710, 0x004e2f12, 0x00442406, 0x004e2b0a, 0x005c3512, 0x0058300d, 0x005b300b, 0x00643a15, 0x00643b15, 0x005e3411, 0x00532a08, 0x004e2807, 0x00492507, 0x00442207, 0x0040230c, 0x00371d07, 0x00351a06, 0x00482915, 0x0044200a, 0x00673e1f, 0x00623b17, 0x005b340d, 0x005c350e, 0x0058330d, 0x00502a0a, 0x00462208, 0x00402008, 0x0041220d, 0x00402008, 0x004c280f, 0x004d280e, 0x00583315, 0x00512e0e, 0x004c2909, 0x004e290a, 0x004f2809, 0x00522c0c, 0x00502c0f, 0x00472509, 0x003f2008, 0x003d200a, 0x00391c08, 0x003c1f0a, 0x0040240c, 0x003e240c, 0x00311804, 0x002a1403, 0x00291408, 0x0028170c, 0x00231208, 0x0021140a, 0x001e1408, 0x001c1509, 0x001e180b, 0x00191208, 0x00171107, 0x00140e04, 0x00120e04, 0x00141007, 0x00151108, 0x00141006, 0x00140f06, 0x00151006, 0x00151005, 0x00181207, 0x00191408, 0x001a1409, 0x00181308, 0x00191408, 0x001a140a, 0x001f140b, 0x0021180f, 0x00211f14, 0x0023251d, 0x0018211c, 0x00101e1a, 0x00101f1d, 0x00111f1e, 0x00121f1e, 0x0013201f, 0x0013201f, 0x0011201f, 0x0011201f, 0x000f201e, 0x000f1d1c, 0x000f1d1c, 0x000f1d1c, 0x000f1d1c, 0x00101c1c, 0x000d1a19, 0x000c1918, 0x000b1818, 0x000c1716, 0x000b1515, 0x000b1614, 0x000a1513, 0x00081412, 0x00081311, 0x00081311, 0x00081311, 0x00081210, 0x0007100d, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081414, 0x00081414, 0x00081313, 0x00081311, 0x00081311, 0x00081410, 0x00081410, 0x00081410, 0x00081311, 0x00081311, 0x00081311, 0x00091211, 0x00091211, 0x00091211, 0x00091211, 0x000a1211, 0x000a1211, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0008120f, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x00060f0c, 0x00070e0c, 0x00060e09, 0x00050d08, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00050e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f0b, 0x00030f0b, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007130f, 0x0007130f, 0x0008120f, 0x0008120f, 0x00081310, 0x00081412, 0x00081412, 0x00081412, 0x00081513, 0x00081513, 0x00081412, 0x000c1816, 0x000c1816, 0x00081513, 0x00071711, 0x00081610, 0x000c1510, 0x000d1411, 0x00292c2b, 0x00444443, 0x004e4c4c, 0x004c4a48, 0x003c3c3a, 0x0041403f, 0x002e2c2b, 0x00201c1b, 0x00201d1c, 0x00252322, 0x002f2d2c, 0x00343031, 0x00353334, 0x003c3b3b, 0x003c3839, 0x00332c2c, 0x00342c27, 0x002e231d, 0x00382b24, 0x00342720, 0x0033251f, 0x00453830, 0x0044362c, 0x00322215, 0x002e1b0b, 0x002f1a08, 0x00311b08, 0x00341908, 0x003b1e09, 0x003f1f08, 0x0045230e, 0x004b250f, 0x004e2810, 0x0051280c, 0x00502807, 0x00522c08, 0x00593313, 0x00613b1e, 0x0059341c, 0x00441f08, 0x003c1b04, 0x003a1c07, 0x0041260f, 0x004d3115, 0x00472708, 0x00543010, 0x005f3817, 0x00552c0b, 0x005c3110, 0x00653a19, 0x00603614, 0x00542a0b, 0x00482405, 0x00422104, 0x003c1e04, 0x00381d08, 0x0039200d, 0x00301705, 0x003a1e0c, 0x003b1907, 0x005a341b, 0x005c3418, 0x00542d0c, 0x00542f0d, 0x00512d0e, 0x00472409, 0x00401f0a, 0x003b1d0c, 0x00381b0d, 0x00402212, 0x00401f0d, 0x0045220d, 0x0049270e, 0x004b290e, 0x0048250b, 0x004b290e, 0x004c290c, 0x00502d0f, 0x004d2c0d, 0x003e1e03, 0x00391d06, 0x00311a06, 0x00301806, 0x002e1805, 0x003a2311, 0x00311c0b, 0x00281506, 0x00241205, 0x00221407, 0x00201208, 0x00201409, 0x00201108, 0x00211309, 0x0022150b, 0x001d1006, 0x001a0d03, 0x001f1408, 0x0021160b, 0x0020160b, 0x001e150a, 0x001e150a, 0x001b1207, 0x001b1206, 0x001b1207, 0x0020170b, 0x0020170b, 0x0020170b, 0x001f160b, 0x001a1207, 0x00181105, 0x001a1308, 0x001f140b, 0x0021140c, 0x00251c13, 0x0026221a, 0x001b201a, 0x00101d18, 0x00101f1c, 0x00101e1d, 0x00101e1d, 0x00101e1d, 0x00101e1d, 0x00101e1d, 0x00111f1e, 0x00101e1d, 0x000e1c1b, 0x000e1c1b, 0x000e1c1b, 0x000e1c1b, 0x000f1c1b, 0x000d1a19, 0x000c1918, 0x000b1818, 0x000b1614, 0x000a1514, 0x000a1513, 0x00091412, 0x00091310, 0x00091310, 0x00081310, 0x0008120f, 0x0008120f, 0x0007100d, 0x0006100c, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081414, 0x00081414, 0x00081313, 0x00081311, 0x00081311, 0x00081410, 0x00081410, 0x00081410, 0x00081310, 0x00081311, 0x00081211, 0x00091211, 0x00091211, 0x00091211, 0x00091211, 0x000a1211, 0x000a1211, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0008120f, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x00070e0c, 0x00060e09, 0x00040c08, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f0b, 0x00030f0b, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007130f, 0x0007130f, 0x00081310, 0x0008120f, 0x00081310, 0x00081412, 0x00081412, 0x00081412, 0x00081513, 0x00081513, 0x00091513, 0x00101c1a, 0x000f1c19, 0x00081513, 0x00061711, 0x00081610, 0x000e1712, 0x001e2321, 0x00404442, 0x004f4d4c, 0x004f4949, 0x004b4646, 0x00413e3d, 0x003c3a39, 0x003c3a39, 0x00363434, 0x002e2c2a, 0x00262623, 0x00282827, 0x00303030, 0x00323135, 0x00333137, 0x003b363c, 0x003e363a, 0x00332a28, 0x00322623, 0x002e201b, 0x003c2f2a, 0x003a2c28, 0x00342720, 0x0044342c, 0x00433126, 0x00362213, 0x00351f0c, 0x00341c09, 0x00381e09, 0x00381904, 0x00422009, 0x0048230c, 0x004a240e, 0x00502911, 0x00542b10, 0x00532b0e, 0x00512b0b, 0x00552f0e, 0x005c3514, 0x0065401c, 0x0054300e, 0x00401f00, 0x00371b01, 0x00341a02, 0x00472d13, 0x0054341a, 0x004e2c0e, 0x00593415, 0x005c3314, 0x00522606, 0x005a2f0e, 0x005f3414, 0x00583012, 0x004b270a, 0x00442409, 0x003c1e07, 0x00321905, 0x00301b0a, 0x00341d0d, 0x00371c0d, 0x00371809, 0x004e2b16, 0x00543018, 0x00492509, 0x00452306, 0x00432205, 0x003c1c06, 0x00371808, 0x00381c10, 0x0031180c, 0x00361b0e, 0x00351608, 0x003e1d0c, 0x00442510, 0x0046280f, 0x003f2006, 0x004a2910, 0x004e2c11, 0x00533113, 0x0048290c, 0x00391c02, 0x00341a04, 0x00281605, 0x002c1a09, 0x002b1808, 0x00301d0f, 0x002b1a0c, 0x00231306, 0x00201305, 0x001e1407, 0x001d1408, 0x001f1308, 0x001e0f04, 0x0026150b, 0x0028170d, 0x002a180e, 0x002d1c11, 0x002d1c11, 0x002b1b10, 0x0028180e, 0x0024150a, 0x0024160b, 0x0026190e, 0x0026190e, 0x0025180c, 0x0022170b, 0x0022170a, 0x00201609, 0x00201609, 0x0021160a, 0x001f1408, 0x0020170b, 0x0024170e, 0x0024140c, 0x00281813, 0x00291f18, 0x001e1f18, 0x00111d18, 0x000e1e1c, 0x00101d1c, 0x00101c1c, 0x00101c1c, 0x00101c1c, 0x000f1d1c, 0x00101e1d, 0x000f1d1c, 0x000e1c1b, 0x000e1c1b, 0x000c1c1a, 0x000c1c1a, 0x000e1b1a, 0x000c1918, 0x000c1918, 0x000a1814, 0x000b1614, 0x000a1512, 0x00081411, 0x00081410, 0x0009140f, 0x0009130e, 0x0009120e, 0x0008120d, 0x0008120d, 0x0007110c, 0x0006100b, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091413, 0x00091413, 0x00081412, 0x00081311, 0x00071210, 0x00071310, 0x00071310, 0x00071310, 0x00081211, 0x00081211, 0x00091211, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00091110, 0x00091110, 0x00081010, 0x0008110e, 0x0007110e, 0x0007110c, 0x0008110c, 0x0007110c, 0x0005100b, 0x0005100a, 0x0005100b, 0x0005100b, 0x0004100b, 0x0004100b, 0x0005100b, 0x00060f0b, 0x00060e0a, 0x00050e0a, 0x00060e0a, 0x00060e0a, 0x00060e0a, 0x00060e0a, 0x00060e09, 0x00050e09, 0x00050e08, 0x00060d08, 0x00060d08, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00050d09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e08, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0005100a, 0x0004100a, 0x0006120c, 0x0008110d, 0x0008110d, 0x0008120f, 0x00091410, 0x00091210, 0x00091210, 0x00091211, 0x00081311, 0x00081412, 0x00081412, 0x00091412, 0x00091512, 0x000c1613, 0x0016201d, 0x00101c19, 0x00081612, 0x00091813, 0x000b1713, 0x0018201c, 0x003d3f3e, 0x004d4a4b, 0x00494645, 0x003f3a3a, 0x00332f2f, 0x002a2626, 0x00312f2e, 0x00393837, 0x00444442, 0x003e3e3c, 0x002c2d2b, 0x00222421, 0x00272828, 0x002c2f32, 0x002c2f34, 0x0036383c, 0x00383437, 0x00393030, 0x00372b28, 0x00352924, 0x00362a24, 0x00392c28, 0x003a2d27, 0x00332119, 0x00412d22, 0x00422d1d, 0x0038210d, 0x00381e09, 0x00442913, 0x003c1e08, 0x003c1903, 0x0049260e, 0x00512d15, 0x00532c13, 0x00562e14, 0x00583114, 0x00542c0e, 0x00502a08, 0x0058330c, 0x0058340f, 0x005f3a16, 0x00523011, 0x003b1d04, 0x00311703, 0x00381c09, 0x004d3018, 0x00543419, 0x004f2c0d, 0x00593112, 0x00572e0e, 0x004c2000, 0x00552c0c, 0x00552f10, 0x004c2b0f, 0x0048260e, 0x00381904, 0x00311804, 0x002d1809, 0x002c1508, 0x002d1608, 0x002e1504, 0x003c200c, 0x00462813, 0x003c2008, 0x00391c05, 0x00381b07, 0x00341807, 0x0030160a, 0x00331b10, 0x002c140a, 0x002d1408, 0x00351a0f, 0x0034190c, 0x00402511, 0x00391d05, 0x003b1d05, 0x00482910, 0x004e2e12, 0x004c2c10, 0x0044270c, 0x00341904, 0x002e1806, 0x00231406, 0x00251608, 0x002c1b0d, 0x002c1a0c, 0x00251608, 0x001e1103, 0x001d1203, 0x00201408, 0x0021170c, 0x00201409, 0x002b1b10, 0x002e1c10, 0x002f1a0d, 0x00361f11, 0x00382114, 0x00341f10, 0x002f1b0c, 0x002d190c, 0x0029180b, 0x0027170a, 0x00241509, 0x0024150a, 0x0024180c, 0x0022180b, 0x00201608, 0x001f1408, 0x00201408, 0x0022170c, 0x0023180c, 0x0022190e, 0x0028180e, 0x002c140c, 0x002c160e, 0x002c1c16, 0x001f1d18, 0x00121c18, 0x000e1e1b, 0x00101d1c, 0x000f1c1b, 0x000f1c1b, 0x00101c1c, 0x00101c1c, 0x00101d1c, 0x000e1c1b, 0x000d1c1a, 0x000c1c1a, 0x000c1b19, 0x000d1b19, 0x000d1a19, 0x000c1918, 0x000c1716, 0x000b1715, 0x000b1514, 0x00091414, 0x00081411, 0x00081510, 0x00081410, 0x0008140f, 0x0008120c, 0x0007100b, 0x0006100a, 0x0006100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d0a, 0x00050d09, 0x00050d09, 0x00050d07, 0x00050d06, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1513, 0x00091413, 0x00081412, 0x00081311, 0x00071210, 0x00071210, 0x00071210, 0x00071210, 0x00081211, 0x00091211, 0x00091211, 0x00081110, 0x00081010, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0007110d, 0x0007110c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00040f09, 0x00040f09, 0x00060f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x0005110b, 0x0007110d, 0x0007110d, 0x0007110d, 0x00091310, 0x00091211, 0x00091211, 0x00091211, 0x00081311, 0x00081412, 0x00081412, 0x00091412, 0x000a1511, 0x000c1613, 0x001b2420, 0x0018211e, 0x00091511, 0x000c1814, 0x0016201c, 0x00343938, 0x004d4c4c, 0x00443e40, 0x003b3736, 0x002c2828, 0x00252221, 0x001f1e1c, 0x00242221, 0x002a2b28, 0x00373836, 0x0040423f, 0x003c3d3b, 0x002d2e2c, 0x00232422, 0x00272827, 0x00282a29, 0x00353736, 0x003d3a39, 0x00352b2a, 0x003b2e2b, 0x00423530, 0x003f322c, 0x00392c27, 0x003e312a, 0x00402c24, 0x00342013, 0x00442b1c, 0x004b301c, 0x0041240f, 0x00472812, 0x004c2b15, 0x0045230d, 0x003c1801, 0x004c2810, 0x00532c14, 0x00573016, 0x00593217, 0x00563011, 0x00502c08, 0x00542f0a, 0x00512c08, 0x00502c0c, 0x00553315, 0x0043240e, 0x00341808, 0x002f1405, 0x003b1c0b, 0x0053321b, 0x00512d13, 0x004c2607, 0x00562f10, 0x00512a0b, 0x00482001, 0x004a2407, 0x0048250c, 0x0045240d, 0x00391b06, 0x00311706, 0x002a1508, 0x002a1608, 0x002c1608, 0x002c1606, 0x00341d0c, 0x003a2310, 0x00351c09, 0x00321906, 0x00301808, 0x002c1508, 0x002a1409, 0x002d170c, 0x002b150b, 0x002b1408, 0x00321a0e, 0x002f180a, 0x0037200e, 0x00331a04, 0x00351b04, 0x00482a13, 0x0047280f, 0x0045270d, 0x003c1e09, 0x002e1607, 0x00241206, 0x00201408, 0x0025180c, 0x002a1b0e, 0x00281808, 0x00211202, 0x001e1001, 0x00211406, 0x0024170a, 0x00281a10, 0x0026180c, 0x002a180c, 0x00301b0e, 0x00392213, 0x003a2010, 0x00381e0e, 0x00371c0c, 0x0031190b, 0x002e180a, 0x00291508, 0x00241409, 0x0024140c, 0x0022130b, 0x00201309, 0x001c1208, 0x001a1107, 0x001a1006, 0x00191005, 0x001a1005, 0x001a1006, 0x001c1308, 0x0026140c, 0x002f170f, 0x00341b11, 0x002c1c15, 0x00201c18, 0x00131c16, 0x000e1d1b, 0x00101d1c, 0x000f1c1b, 0x000e1b1a, 0x000e1b1a, 0x000e1b1a, 0x000e1b1a, 0x000d1c1a, 0x000c1c1a, 0x000c1c1a, 0x000d1a19, 0x000d1a19, 0x000c1918, 0x000b1818, 0x000c1716, 0x000c1716, 0x000b1515, 0x00081414, 0x00081412, 0x00081510, 0x00081410, 0x0007130e, 0x0007120c, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1513, 0x00091413, 0x00081412, 0x00081311, 0x00071210, 0x00071210, 0x00081210, 0x00081110, 0x00081110, 0x00091110, 0x00091110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0006100c, 0x0005100a, 0x00040e09, 0x00040e08, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x00030e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x0005110b, 0x0007110d, 0x0007110d, 0x0007110d, 0x0008120f, 0x00091110, 0x00091110, 0x00091211, 0x00091211, 0x00091312, 0x00091412, 0x00091412, 0x000b1411, 0x000c1613, 0x00202725, 0x00202724, 0x000d1411, 0x00171c1a, 0x00303534, 0x00464b48, 0x00454445, 0x00373435, 0x002c2b2a, 0x001d1c1b, 0x00141311, 0x000f100e, 0x000c0e0c, 0x0010110f, 0x00181a18, 0x002c2e2c, 0x003c3d3b, 0x003f3d3c, 0x0034302c, 0x00302a24, 0x003b332d, 0x0038302a, 0x00413833, 0x00423632, 0x003a2c27, 0x00473930, 0x0044372c, 0x0042342a, 0x00403127, 0x00493328, 0x00442c1d, 0x003e2411, 0x004f311c, 0x0054341d, 0x00502e18, 0x004c2813, 0x00512e16, 0x004a250d, 0x004b240b, 0x00542e14, 0x00573014, 0x00583114, 0x00593412, 0x0054300c, 0x00522e09, 0x00502c08, 0x00442000, 0x00462407, 0x00482813, 0x003b1f0f, 0x0034180c, 0x0036190c, 0x00442412, 0x00513018, 0x0049270c, 0x00482408, 0x00522c10, 0x00482106, 0x00432004, 0x00412008, 0x00432410, 0x003c1f0c, 0x00311909, 0x00241204, 0x00281608, 0x00281606, 0x00291605, 0x002f1a0b, 0x00321c0c, 0x00301a08, 0x002e1807, 0x002d1807, 0x00281406, 0x00271408, 0x0028150a, 0x00281509, 0x002a1508, 0x002c180b, 0x002c1709, 0x00301b0c, 0x00311a08, 0x00321804, 0x00452814, 0x003f2009, 0x003c2008, 0x00331906, 0x00291405, 0x00231308, 0x001c1409, 0x00241a0e, 0x0026180b, 0x00221404, 0x00201101, 0x00201203, 0x00241608, 0x00281a0c, 0x002b1b0f, 0x0028180c, 0x00301c0f, 0x00341c0c, 0x003d2211, 0x003c1f0e, 0x00371a09, 0x00381d0c, 0x00341909, 0x002d1709, 0x00291409, 0x0026140c, 0x0023140c, 0x0021110a, 0x0020120a, 0x001e140b, 0x001f150c, 0x001f140c, 0x001f140c, 0x001e140b, 0x001c1209, 0x001a1007, 0x001f1007, 0x00231208, 0x002a180c, 0x002c1c14, 0x00241c16, 0x00181a14, 0x00101b17, 0x000e1c1a, 0x000e1b1a, 0x000d1a19, 0x000d1918, 0x000d1919, 0x000d1919, 0x000c1a18, 0x000c1b19, 0x000d1c1a, 0x000d1a19, 0x000c1818, 0x000b1818, 0x000a1716, 0x000b1515, 0x000b1515, 0x000a1414, 0x00081414, 0x00071411, 0x00061410, 0x0006130f, 0x0006120d, 0x0007120c, 0x0006100b, 0x00050f0a, 0x0005100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e0a, 0x00060e09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091513, 0x00091413, 0x00081412, 0x00081311, 0x00071210, 0x00071210, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0007100d, 0x0005100a, 0x00040e09, 0x00040d08, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x00030f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x0005110b, 0x0007110d, 0x0008120e, 0x0008120f, 0x0008110e, 0x00091010, 0x00091010, 0x00091211, 0x000a1311, 0x00091312, 0x00091412, 0x000a1412, 0x000b1411, 0x000d1613, 0x00272e2c, 0x002c2f2e, 0x001f201f, 0x00393939, 0x004c4c4c, 0x00474848, 0x003a3939, 0x002e2f2f, 0x001f2020, 0x00111413, 0x000c100c, 0x000e110e, 0x000e100e, 0x00101210, 0x00101310, 0x00181b18, 0x00302f2d, 0x0044403e, 0x004a403c, 0x0040322a, 0x00403126, 0x0044372b, 0x003c2e24, 0x00463730, 0x00483830, 0x00403024, 0x004a3c2d, 0x00463829, 0x00443426, 0x00493124, 0x004c3322, 0x004c311c, 0x00472810, 0x004f2e15, 0x0058361c, 0x00573219, 0x00583017, 0x005c371b, 0x00532c0f, 0x00492204, 0x00502a0c, 0x005c3515, 0x005a3312, 0x0058310f, 0x0054300a, 0x00522d08, 0x004e2a08, 0x00432002, 0x003b1b04, 0x00371b0c, 0x00341910, 0x00301509, 0x003c200e, 0x00442510, 0x00472610, 0x00422009, 0x0047230d, 0x0047240d, 0x003d1d06, 0x00381a04, 0x003b1e0c, 0x00361c0a, 0x00301b0c, 0x00251506, 0x00241606, 0x00261506, 0x00261606, 0x002b1809, 0x002e1c0c, 0x002b1707, 0x002c1808, 0x002a1606, 0x00261406, 0x00261408, 0x00261408, 0x00271609, 0x00281809, 0x00291609, 0x002a1809, 0x002c1809, 0x002f1909, 0x00341d0c, 0x003c2210, 0x00381e08, 0x00371c08, 0x002c1504, 0x0029160a, 0x001f1108, 0x001c140a, 0x00241a0f, 0x0024180b, 0x00211406, 0x00201304, 0x00201304, 0x00241608, 0x00281a0c, 0x002a180c, 0x00331e10, 0x00341c0d, 0x00381e0d, 0x003c200c, 0x00381905, 0x003e200c, 0x003c1f0b, 0x00331806, 0x002d1407, 0x002b150a, 0x0026140c, 0x0021100a, 0x0021100a, 0x0022140c, 0x001f140c, 0x001e140b, 0x00221710, 0x001c120b, 0x001f140b, 0x001e140b, 0x0020130b, 0x001f160b, 0x001c1305, 0x00221708, 0x00281c0f, 0x00271d14, 0x001c1a14, 0x00101914, 0x000c1b17, 0x000d1a19, 0x000d1918, 0x000d1818, 0x000c1918, 0x000d181a, 0x000c1918, 0x000b1a18, 0x000d1c1a, 0x000c1918, 0x000a1817, 0x000b1817, 0x00091615, 0x000a1414, 0x000a1414, 0x00081414, 0x00081313, 0x00051310, 0x0005130f, 0x0006120e, 0x0006120c, 0x0008120c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081412, 0x00081412, 0x00081411, 0x00081311, 0x00081311, 0x00081311, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0006100e, 0x0007100d, 0x0008120e, 0x0007110b, 0x0005100a, 0x00040f09, 0x00050f0a, 0x00050f0a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x00060f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00040d08, 0x00040d08, 0x00050d09, 0x00050d09, 0x00060d09, 0x00060d09, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00060e08, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00050e09, 0x00040e09, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x00040f09, 0x0005110b, 0x0007110d, 0x0008130f, 0x00091310, 0x00091310, 0x0009110f, 0x0009120f, 0x00091210, 0x00081411, 0x00081412, 0x00091412, 0x000c1412, 0x000c1411, 0x000f1514, 0x002c3130, 0x00383a39, 0x00403e3d, 0x00534f4f, 0x004c4949, 0x003c3c3c, 0x00343434, 0x00292c2b, 0x001e2322, 0x00191d1d, 0x00181c1a, 0x00161917, 0x00111310, 0x00101110, 0x00101210, 0x00121311, 0x001b1918, 0x00342c2a, 0x004b3e37, 0x00534036, 0x004c3729, 0x004b3728, 0x0048372b, 0x003c2c23, 0x004e3e32, 0x00463428, 0x00463224, 0x004e392b, 0x004c3828, 0x004c3424, 0x004d3320, 0x00563823, 0x0053321b, 0x004c2a10, 0x00532e14, 0x005c351a, 0x005c3518, 0x005e3618, 0x005d3716, 0x00563010, 0x00462000, 0x00542d0d, 0x005c3414, 0x005b3410, 0x0058320c, 0x00542d0a, 0x00542e0a, 0x004b2708, 0x0043220b, 0x00371b09, 0x002f160b, 0x0030170a, 0x002f1504, 0x00381f0d, 0x003f2110, 0x003c1d0c, 0x00391a09, 0x00412310, 0x003c1e0a, 0x00361905, 0x00321804, 0x00321906, 0x00301a09, 0x0029190b, 0x00211304, 0x00241607, 0x00241606, 0x00261807, 0x00291a0a, 0x00271607, 0x00291909, 0x00281707, 0x00271708, 0x00241408, 0x00241508, 0x0027170a, 0x0028180a, 0x00281608, 0x002a1808, 0x002b1707, 0x002c1808, 0x00372010, 0x00341d0c, 0x00341b0a, 0x002e1807, 0x00281404, 0x0027170a, 0x001a0f04, 0x001c150a, 0x0022190d, 0x00201609, 0x00201407, 0x00211306, 0x00211307, 0x00251609, 0x0029180c, 0x00331e10, 0x00382011, 0x00361c0b, 0x003b1f0a, 0x0040210c, 0x003f1f0b, 0x00442410, 0x00381a05, 0x00331706, 0x0031190e, 0x002f1810, 0x0024140c, 0x0021130c, 0x001e1109, 0x001c1108, 0x00181007, 0x00140f04, 0x00150e06, 0x00150f06, 0x00150f06, 0x00150f06, 0x00180e06, 0x00161107, 0x00141305, 0x00191508, 0x0020180c, 0x00241a10, 0x001e1c14, 0x00141b11, 0x000f1a14, 0x000f1917, 0x000e1918, 0x000d1919, 0x000d191a, 0x000c181a, 0x000c1918, 0x000b1a18, 0x000c1c18, 0x000c1918, 0x000a1816, 0x000a1816, 0x00091614, 0x00091414, 0x00091414, 0x00081413, 0x00081312, 0x00051310, 0x0006130f, 0x0007120e, 0x0006110c, 0x0008120d, 0x0008120d, 0x0006100b, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f09, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050d09, 0x00040d07, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00061411, 0x00061411, 0x00071411, 0x00071411, 0x00081311, 0x00091311, 0x00091211, 0x00081110, 0x00081210, 0x0008120d, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110d, 0x0008110e, 0x0008120e, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0005100a, 0x00061009, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0007100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x0004100a, 0x0004100a, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110f, 0x0009130f, 0x00081410, 0x00081510, 0x00091511, 0x000a1511, 0x000c1411, 0x000e1513, 0x00151b19, 0x00303332, 0x00444444, 0x004c4b49, 0x004d4a49, 0x00423f3e, 0x00373735, 0x00333434, 0x002e3232, 0x00283030, 0x00262c2c, 0x00292c2b, 0x00222422, 0x00191817, 0x00131410, 0x00131310, 0x00151412, 0x001b1715, 0x002c2421, 0x003d3028, 0x0048372c, 0x00543e31, 0x004b3728, 0x004c3b2c, 0x00402f22, 0x00443428, 0x004f3b2f, 0x004a3426, 0x004a3023, 0x00543929, 0x00503524, 0x00513521, 0x00533620, 0x00583820, 0x00553418, 0x00522d10, 0x00552d10, 0x005d3415, 0x00663e1c, 0x00613a18, 0x00603917, 0x00552d0c, 0x00482000, 0x0057300e, 0x00643c19, 0x00603a16, 0x005c3410, 0x0058300b, 0x005b3515, 0x00502f15, 0x003f200d, 0x00301608, 0x002f1606, 0x002c1604, 0x002f1908, 0x00381d10, 0x00351b0c, 0x0034180a, 0x0036190c, 0x003a200e, 0x00341a06, 0x002f1604, 0x00311805, 0x00311c0b, 0x002d190c, 0x00241304, 0x00241406, 0x00231606, 0x00241808, 0x00281a0b, 0x00261708, 0x002b1b0c, 0x0028180c, 0x0028180a, 0x00241408, 0x00241407, 0x0028180b, 0x002a1a0c, 0x00271506, 0x002c1808, 0x002b1604, 0x002e1808, 0x00321b0c, 0x00311a0a, 0x002f180a, 0x002b1606, 0x00261505, 0x00211405, 0x001c1103, 0x001d1609, 0x001f1608, 0x00201408, 0x00221408, 0x00241508, 0x0026170b, 0x0028150b, 0x002b160c, 0x00321709, 0x00361b0b, 0x00381c09, 0x003c1f09, 0x0043230c, 0x00482810, 0x0041210c, 0x003a1c08, 0x00361a0b, 0x0031180e, 0x0028130c, 0x0023120c, 0x001c100a, 0x00161008, 0x00110f04, 0x000e0d03, 0x000c0d02, 0x000d0d02, 0x000d0d02, 0x000d0c04, 0x000c0c03, 0x000e0b04, 0x00090c02, 0x00060c02, 0x000a0e04, 0x00140d07, 0x0018120a, 0x001b1910, 0x001a1e12, 0x00131a12, 0x00101814, 0x00101818, 0x000e1819, 0x000d181a, 0x000c181a, 0x000a1819, 0x000a1916, 0x000a1916, 0x000a1814, 0x000a1814, 0x00081613, 0x00081412, 0x00081510, 0x00081510, 0x00081510, 0x00071410, 0x00051310, 0x0007130f, 0x0006100c, 0x0006100c, 0x0006100b, 0x0006100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00070f09, 0x00060e08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00051411, 0x00051411, 0x00071411, 0x00071411, 0x00081412, 0x000a1412, 0x00091211, 0x00081110, 0x0008120f, 0x0008120d, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0006100c, 0x00040e0b, 0x00040e09, 0x00051008, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x0004100a, 0x0004100a, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110d, 0x0009130e, 0x00081410, 0x00081510, 0x00081611, 0x000a1511, 0x000c1511, 0x00131816, 0x00202422, 0x00343534, 0x004e4e4e, 0x004e4c4d, 0x00444244, 0x00383839, 0x00343636, 0x00303535, 0x002d3434, 0x00272e30, 0x00252a2c, 0x00202224, 0x00242120, 0x00282724, 0x00201d1b, 0x00191513, 0x00181412, 0x0015120e, 0x001d1912, 0x002f241b, 0x003d2e22, 0x00443324, 0x004b3a2a, 0x004f3e30, 0x004a3a2c, 0x00412f23, 0x00453126, 0x00503b2e, 0x00472e21, 0x00493120, 0x004f3824, 0x004e3721, 0x00533720, 0x0054371d, 0x005e3f24, 0x005b381a, 0x00522c0e, 0x00542c0b, 0x005c3513, 0x006e4622, 0x00653d1a, 0x00603817, 0x00542c0c, 0x00482201, 0x005b3614, 0x00643e1c, 0x00643c1a, 0x00552e0b, 0x00573210, 0x005a381c, 0x0051311a, 0x0040230e, 0x00311502, 0x002c1403, 0x002e1708, 0x00321b0d, 0x0030180a, 0x002f1508, 0x00301809, 0x00371f0e, 0x00331c0a, 0x002f1605, 0x00301808, 0x00321b0c, 0x002e1909, 0x00291607, 0x00261406, 0x00241506, 0x00261708, 0x002b180b, 0x00281608, 0x002c190c, 0x002a180c, 0x0029180a, 0x00271408, 0x00261406, 0x0028180b, 0x002c1c0d, 0x00281506, 0x002c1707, 0x002c1504, 0x00301908, 0x00321b0b, 0x002f1809, 0x002e1709, 0x00281505, 0x00241404, 0x00201403, 0x00201406, 0x00211609, 0x00211408, 0x00241408, 0x00271509, 0x00271408, 0x0029170b, 0x002c180c, 0x002e160b, 0x0033180b, 0x0036190a, 0x00381c08, 0x003c200a, 0x00492912, 0x004c2b12, 0x0044240f, 0x0040240f, 0x003a2010, 0x002f170d, 0x0026130b, 0x001f1009, 0x00140d04, 0x000f0f04, 0x000c0d01, 0x00090f04, 0x00090f04, 0x000a0f04, 0x000b0e04, 0x000a0e05, 0x00080d05, 0x00080d04, 0x00060d04, 0x00050c04, 0x00050c02, 0x00090902, 0x000c0b03, 0x00111008, 0x00191912, 0x00181c15, 0x00101814, 0x000e1716, 0x000c1717, 0x000b1618, 0x00081717, 0x00091816, 0x00091814, 0x00091813, 0x000a1714, 0x000a1814, 0x00081412, 0x00051310, 0x00081510, 0x00081510, 0x00081410, 0x00071410, 0x00051310, 0x0006110e, 0x0005100c, 0x0005100b, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071411, 0x00071411, 0x00071411, 0x00071411, 0x00081412, 0x000a1412, 0x00091211, 0x00081110, 0x0008110e, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0007110d, 0x00050f0c, 0x0005100a, 0x00051008, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x0004100a, 0x0004100a, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110d, 0x0009130e, 0x0008140f, 0x00081410, 0x00081611, 0x000a1510, 0x000b120e, 0x00111512, 0x002c2e2b, 0x00484847, 0x004a4a4a, 0x00404244, 0x00363839, 0x00303335, 0x002e3234, 0x002c3234, 0x002b3434, 0x002b3235, 0x00292e30, 0x00292b2c, 0x00272524, 0x002a2622, 0x002a2521, 0x0025201c, 0x001c1713, 0x001b1813, 0x001e1a14, 0x00272014, 0x0034281c, 0x00392a1b, 0x003c2d1d, 0x00463628, 0x004f3d2f, 0x00473428, 0x003a281c, 0x00453224, 0x004a3427, 0x00422c1b, 0x004c3622, 0x004d3821, 0x004d361f, 0x0053391f, 0x00563a1d, 0x00604022, 0x005a3818, 0x00593413, 0x00562f0d, 0x00623a18, 0x0068401f, 0x005d3715, 0x005b3414, 0x004f2809, 0x00482103, 0x00563113, 0x00653e20, 0x0060381b, 0x00502a0c, 0x004c280c, 0x004c2c11, 0x004e2e15, 0x003f220c, 0x00341807, 0x002d1405, 0x002c1508, 0x002d160a, 0x002d160a, 0x002d1608, 0x002e1909, 0x00331e0e, 0x00301c0c, 0x002d1709, 0x0030190b, 0x00301c0d, 0x002c1809, 0x00271507, 0x00241506, 0x002a170a, 0x002a1609, 0x002c190c, 0x002e180c, 0x002b180c, 0x002b170c, 0x002c180b, 0x00271406, 0x0028170a, 0x002c1c0d, 0x002b1808, 0x002d1908, 0x00301a08, 0x00331c0c, 0x00341c0c, 0x0030190a, 0x002e1809, 0x002a1808, 0x00261404, 0x00231505, 0x00241709, 0x0025170b, 0x00241409, 0x00281509, 0x002c180d, 0x002c170c, 0x002f1a0e, 0x00392014, 0x00371b10, 0x00381b0d, 0x00351808, 0x00351905, 0x003f220d, 0x004b2a14, 0x004b2a12, 0x00492814, 0x00402410, 0x00311808, 0x00281308, 0x00221008, 0x00190f06, 0x00130d04, 0x000d0f03, 0x000c0f03, 0x00091003, 0x00081004, 0x00091008, 0x00091008, 0x00080f07, 0x00080f07, 0x00040f06, 0x00060e06, 0x00070e06, 0x00070e06, 0x00060e06, 0x00080d04, 0x000a0c04, 0x0014120d, 0x00181914, 0x00101714, 0x000c1414, 0x000c1515, 0x000b1517, 0x00091617, 0x00091615, 0x00091714, 0x00091712, 0x00081513, 0x00081513, 0x00081412, 0x00081412, 0x00081510, 0x00081510, 0x00071410, 0x0005130f, 0x0004120f, 0x0005100d, 0x0005100c, 0x0005100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00060e09, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071411, 0x00071411, 0x00071411, 0x00071411, 0x00081311, 0x00091211, 0x00081110, 0x00081110, 0x0008110e, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007100c, 0x0006100c, 0x0006100c, 0x00040d0a, 0x00040e0a, 0x0006100c, 0x00050f0c, 0x0005100a, 0x00051008, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c08, 0x00060c08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x0004100a, 0x0004100a, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110d, 0x0009130e, 0x0008140f, 0x00081410, 0x00081610, 0x000a1510, 0x00101713, 0x002d302e, 0x0050514f, 0x003e3c3c, 0x00313031, 0x002c2d2f, 0x00222426, 0x0024282b, 0x00282d2f, 0x00283032, 0x00263032, 0x00252d30, 0x0024292b, 0x00242628, 0x00252422, 0x0025231e, 0x0027201c, 0x0029231d, 0x002c261f, 0x001e1812, 0x001c180e, 0x0021180e, 0x002c2010, 0x00322616, 0x0037291a, 0x00372718, 0x00443224, 0x00443327, 0x00402f22, 0x00352315, 0x00473324, 0x0045301f, 0x003f2b18, 0x004d3823, 0x004e3822, 0x004a331a, 0x00563c20, 0x00543519, 0x005f3d1f, 0x005c3a1a, 0x005d3817, 0x0058300f, 0x005d3614, 0x005e3715, 0x00532c0c, 0x005c3517, 0x004a2408, 0x00401a00, 0x00532e13, 0x005d361c, 0x00593318, 0x004c280e, 0x00432107, 0x003c1c02, 0x003f2209, 0x00371c09, 0x0032190a, 0x002c1708, 0x002c170a, 0x002c180b, 0x002b1809, 0x002b1808, 0x002d190b, 0x00321e0f, 0x00311c0d, 0x002d180a, 0x00301a0d, 0x002e190c, 0x00281608, 0x00251406, 0x002d180b, 0x002d180b, 0x002e180c, 0x002e180c, 0x002d180c, 0x002c180c, 0x002c190c, 0x00291607, 0x00281708, 0x002e1d0d, 0x002f1a0b, 0x00321c0a, 0x00321c0a, 0x00331c0c, 0x00341d0d, 0x0030190a, 0x002f190a, 0x002d190a, 0x00281808, 0x00281809, 0x0028180b, 0x0028160c, 0x00281308, 0x0030170c, 0x00341b0d, 0x00361d0e, 0x00392010, 0x00432617, 0x00391c0c, 0x003a1c0c, 0x00361807, 0x003b1f0b, 0x00452812, 0x004a2a13, 0x004b2b13, 0x00472712, 0x00381c08, 0x002c1404, 0x00241306, 0x00201207, 0x00191007, 0x00140f06, 0x00121006, 0x00101008, 0x000c0f04, 0x000c1006, 0x000c0e08, 0x000c0e08, 0x000b0d07, 0x000a0e07, 0x00051008, 0x00070d08, 0x00090c08, 0x00080c08, 0x00050f06, 0x00060e06, 0x00080b04, 0x000e0e09, 0x00161814, 0x00101614, 0x000c1414, 0x000c1616, 0x000b1517, 0x00091617, 0x00091615, 0x00091714, 0x00091712, 0x00091513, 0x000a1513, 0x00081412, 0x00081412, 0x00081410, 0x00081410, 0x00081410, 0x0007130f, 0x0004120f, 0x0005100d, 0x0005100c, 0x0005100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00060e09, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071411, 0x00071411, 0x00071210, 0x00071210, 0x00081311, 0x00081311, 0x00081110, 0x0007100f, 0x0007100f, 0x0007110e, 0x0007110d, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0005100a, 0x00040e09, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040d09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00041008, 0x00031008, 0x00041008, 0x00041009, 0x00050f0c, 0x0007110d, 0x0008120f, 0x0008120f, 0x0008120f, 0x0008120f, 0x00081310, 0x0007140f, 0x0008150f, 0x000c1510, 0x00202622, 0x00484c48, 0x0040413d, 0x0032302f, 0x001e1d1e, 0x0019181b, 0x0027282c, 0x00292e30, 0x002a2f33, 0x00293034, 0x002a3537, 0x00283034, 0x00262b2d, 0x00242627, 0x00252422, 0x0024201e, 0x00201c18, 0x00231c17, 0x002b241c, 0x002b241b, 0x00231a10, 0x00271c0f, 0x002b1c0e, 0x002c1f0f, 0x00312415, 0x00312316, 0x00302014, 0x003f2f22, 0x00433125, 0x003e2c20, 0x003a2618, 0x003d2a1b, 0x003f2c1b, 0x003f2c1a, 0x004d3824, 0x004c3521, 0x00462e17, 0x00543921, 0x0054351c, 0x00614024, 0x005c381a, 0x00593314, 0x00593214, 0x00583010, 0x00572e0f, 0x005a3013, 0x005b3216, 0x00482107, 0x00441e06, 0x0048240d, 0x004f2b14, 0x004f2a14, 0x0044230c, 0x00391c01, 0x00371b04, 0x00371c0c, 0x00321a0c, 0x002f1a0c, 0x002c180b, 0x002d180b, 0x002c170a, 0x002c170a, 0x002e190b, 0x00331d0f, 0x00331d0f, 0x00301a0b, 0x0030180a, 0x002d180a, 0x002b1607, 0x002a1304, 0x0030180a, 0x00321b0d, 0x0030180a, 0x002e180c, 0x0030180c, 0x002e180c, 0x002f1a0b, 0x002c190a, 0x002f1b0b, 0x00321a0a, 0x00341809, 0x00361809, 0x00351c0a, 0x00341c09, 0x00331c0a, 0x00321c0b, 0x00321c0c, 0x00301909, 0x002d1808, 0x002e1a0b, 0x002e180b, 0x0030180c, 0x00361a0e, 0x003c1d0f, 0x0043200f, 0x00472510, 0x004a2810, 0x0048260f, 0x0043210a, 0x0043200c, 0x003c1c07, 0x0042230e, 0x00452811, 0x00482811, 0x0044210c, 0x003e1e09, 0x00381b08, 0x002e1807, 0x00271607, 0x00211407, 0x001c1207, 0x00181108, 0x00140f08, 0x00141008, 0x00141109, 0x00101007, 0x0013120b, 0x00111009, 0x00101009, 0x000c0d08, 0x000e100a, 0x000c0d08, 0x000b0d07, 0x00080c05, 0x00080c04, 0x00080c03, 0x00080b02, 0x000c1007, 0x00141814, 0x000f1514, 0x000b1514, 0x000c1714, 0x000c1614, 0x00091615, 0x00091615, 0x00081513, 0x00091513, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x000a1410, 0x000a1410, 0x0008120f, 0x0008120f, 0x00071210, 0x0006110d, 0x0004100c, 0x0004100b, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00040e07, 0x00030c06, 0x00030c06, 0x00030c06, 0x00040c09, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071411, 0x00071411, 0x00071210, 0x00071210, 0x00071210, 0x00071210, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007110e, 0x0008120e, 0x00050f0b, 0x00030d08, 0x0005100a, 0x0005100a, 0x00040e09, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040d09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00041008, 0x00031008, 0x00041008, 0x00041009, 0x00050f0c, 0x0007110d, 0x0008120f, 0x0008120f, 0x0008120f, 0x0008120f, 0x00081310, 0x0008140f, 0x0009140f, 0x000f1813, 0x003c403d, 0x003c403c, 0x0021231f, 0x00181817, 0x00202020, 0x002c2b2e, 0x00292b2e, 0x002c2f31, 0x002a2f33, 0x00283033, 0x002b3537, 0x002c3437, 0x00282d2f, 0x00252728, 0x00262424, 0x0023201e, 0x00241f1d, 0x00271f1c, 0x00282018, 0x00342a20, 0x002c2014, 0x002b1c0e, 0x002e1d0e, 0x002f1e0f, 0x002f2011, 0x002f2013, 0x002c1d10, 0x002e2013, 0x003a2a1d, 0x00433226, 0x00413022, 0x00352416, 0x00362415, 0x003b2a19, 0x00402e1d, 0x00483423, 0x0047321f, 0x0049301c, 0x00573c24, 0x00513318, 0x00603e22, 0x00543014, 0x00583216, 0x00573114, 0x00542d0f, 0x00562e10, 0x00573014, 0x00502c12, 0x00432009, 0x00401e09, 0x0044220c, 0x00482711, 0x00482810, 0x003c1f06, 0x00371c07, 0x00341b0b, 0x00311b0c, 0x002f1b0d, 0x002c190c, 0x002a1408, 0x002d180b, 0x002d180b, 0x002d180a, 0x00331c0e, 0x00341c0f, 0x00321b0c, 0x002e1809, 0x002d1809, 0x002c1708, 0x002c1406, 0x0030180a, 0x00321b0d, 0x0030190b, 0x002f190c, 0x0030180c, 0x002e180c, 0x002f190b, 0x00331e0d, 0x00361e0d, 0x00381d0c, 0x003a1c0c, 0x003e1e0e, 0x003a1c08, 0x003b1f08, 0x003b1f0a, 0x00391e09, 0x00381e0a, 0x00361c08, 0x00341907, 0x00341c0a, 0x00371c0a, 0x003f2010, 0x00442310, 0x0047230f, 0x004c260e, 0x00502a0f, 0x00542e10, 0x00542e10, 0x00502a0c, 0x004c280c, 0x00462108, 0x004c2b14, 0x0044240d, 0x0044240c, 0x003f1f07, 0x003a1a05, 0x00381c08, 0x00301a07, 0x00281608, 0x00241408, 0x00201308, 0x001b1008, 0x00181008, 0x00171009, 0x00161109, 0x00120f07, 0x00100c04, 0x00131008, 0x0015130b, 0x00121008, 0x0014110a, 0x00111009, 0x00111009, 0x00101008, 0x000f0f06, 0x000f0f06, 0x000e0e04, 0x00111108, 0x00151811, 0x000f1511, 0x000a1410, 0x000a1511, 0x000b1412, 0x000a1514, 0x000a1414, 0x00081412, 0x00081412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x000a1410, 0x00091310, 0x0008120f, 0x0008120f, 0x00071210, 0x0006110e, 0x0005100c, 0x0004100b, 0x00060f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00040e07, 0x00030c06, 0x00030c06, 0x00030c06, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00071210, 0x00071210, 0x00071210, 0x00071210, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007110e, 0x0007110d, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00041008, 0x00041008, 0x00051109, 0x00041008, 0x00040e0b, 0x0006100c, 0x0007110d, 0x00091310, 0x0008120f, 0x0007110d, 0x0008120e, 0x0008130e, 0x0008140e, 0x00202923, 0x003b403b, 0x002b2e29, 0x001f1f1b, 0x00242221, 0x002c2c2d, 0x0029292c, 0x0026272c, 0x0025282c, 0x00272c30, 0x00262e31, 0x002c3437, 0x002d3438, 0x002e3334, 0x002c2e30, 0x00282828, 0x00201d1c, 0x001f1a18, 0x00211815, 0x00251c14, 0x002c2116, 0x00362819, 0x00342212, 0x00301c0c, 0x00301d0d, 0x002e1f10, 0x002c1f11, 0x002c1d10, 0x002c1e11, 0x00312416, 0x00372a1c, 0x003c2d20, 0x003a2b1e, 0x00362819, 0x00382a1b, 0x003c2c1d, 0x003f2e20, 0x00402e1d, 0x00432e1b, 0x004c331e, 0x0052371f, 0x0054351c, 0x0058381d, 0x00512e15, 0x00543216, 0x00583417, 0x00542e0f, 0x00502c0f, 0x004b280e, 0x0044240c, 0x0040200a, 0x0040200c, 0x0040200c, 0x0043240d, 0x0041240e, 0x00391e0a, 0x00341c0b, 0x0030190b, 0x002e1a0c, 0x002e1a0e, 0x002c170a, 0x002d180b, 0x002c170a, 0x002d180b, 0x002f180c, 0x0030190c, 0x00361f10, 0x002d1608, 0x002e180a, 0x00301b0c, 0x002d1608, 0x0030180b, 0x00321b0d, 0x0030190b, 0x0030180c, 0x0030180c, 0x0030180c, 0x00311a0a, 0x00361f0d, 0x0039200d, 0x003c1f0a, 0x00422110, 0x00401d0b, 0x00401d06, 0x0044220a, 0x00402008, 0x00402009, 0x0040220a, 0x0040200b, 0x003c1e08, 0x003e200b, 0x0044240e, 0x00492810, 0x004c2810, 0x00572f14, 0x005c3114, 0x005d3310, 0x00603611, 0x005f340f, 0x005a300b, 0x00512907, 0x00492405, 0x00462309, 0x0044210a, 0x0044220b, 0x00401d06, 0x0040200c, 0x00351804, 0x00321807, 0x002c1608, 0x00281409, 0x0024140c, 0x0024150d, 0x001e140c, 0x001a110b, 0x00170f08, 0x0017100a, 0x001a140c, 0x0018130c, 0x0018120c, 0x0019140c, 0x001a150c, 0x00181209, 0x00161008, 0x00151108, 0x00151109, 0x0014110a, 0x0014120c, 0x0017140f, 0x00151610, 0x000d140d, 0x000b150e, 0x000a140e, 0x000a1410, 0x000a1412, 0x000a1412, 0x00091311, 0x00091311, 0x00091211, 0x00091211, 0x00081110, 0x00081110, 0x00091310, 0x000a1410, 0x0007110d, 0x0007110d, 0x0006110f, 0x0005100d, 0x0004100c, 0x0004100b, 0x00060f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00040e07, 0x00030c06, 0x00030c06, 0x00030c06, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00071210, 0x00071210, 0x00071210, 0x0007130f, 0x0007110d, 0x0007110d, 0x0007100e, 0x0007110e, 0x0007110d, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00050e08, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00041008, 0x00041008, 0x00051109, 0x00041008, 0x00040e0a, 0x0006100c, 0x0007110d, 0x00091310, 0x0008120f, 0x0007110d, 0x0008120e, 0x0008130e, 0x000b1610, 0x002b342e, 0x00313731, 0x00242621, 0x0022231f, 0x002b2b29, 0x00242526, 0x00242528, 0x0026282d, 0x0022252a, 0x00242a2c, 0x00262e2f, 0x00262e2f, 0x002a3034, 0x002f3334, 0x00323436, 0x00313233, 0x002a2827, 0x0024201c, 0x00211915, 0x00251d14, 0x002b1c11, 0x003a281a, 0x003b2715, 0x00321d0b, 0x00311c0b, 0x002c1c0d, 0x002b1c0f, 0x002b1c0f, 0x002b1e10, 0x002c2113, 0x00332819, 0x0033281a, 0x00372b1c, 0x003c2f21, 0x00382c1e, 0x00392d1f, 0x003d2f22, 0x00403021, 0x003f2d1e, 0x00432f1d, 0x00452f1b, 0x004b301b, 0x0052351e, 0x0053341d, 0x004d2f16, 0x004f2f13, 0x00523013, 0x004a2a0c, 0x004a2b12, 0x00462810, 0x0042250e, 0x003e200c, 0x003c1e09, 0x003d200a, 0x0040230e, 0x003f2410, 0x00381f0e, 0x00311a0c, 0x002f1b0c, 0x002f1b0f, 0x002f190c, 0x002c1709, 0x002b1507, 0x002c1709, 0x00311c0e, 0x00301a0b, 0x00341e10, 0x00301a0b, 0x00301b0c, 0x00301b0c, 0x002d1608, 0x0030190c, 0x00331c0e, 0x00311a0c, 0x00311a0d, 0x0030180c, 0x0030180c, 0x00321908, 0x00381e0c, 0x00402510, 0x0043240e, 0x0044230d, 0x0046220d, 0x00452007, 0x004d280c, 0x004c280c, 0x004c280d, 0x004b280d, 0x0048260d, 0x0046240b, 0x0048260c, 0x004d290f, 0x00542f14, 0x005c3517, 0x00633817, 0x00633512, 0x00653811, 0x00693c12, 0x0064370e, 0x00603309, 0x00582e06, 0x004e2804, 0x00482205, 0x0048240e, 0x0045240d, 0x0043220c, 0x00452510, 0x00381c09, 0x00341b08, 0x002d1507, 0x00291408, 0x0027160c, 0x0025160e, 0x0021160f, 0x001d140e, 0x001b130c, 0x001a130c, 0x0019120c, 0x001a130c, 0x0019120a, 0x0019120a, 0x00181008, 0x00160e06, 0x00181008, 0x00181008, 0x00171208, 0x00151208, 0x0015120a, 0x0017140d, 0x0015150f, 0x000e140c, 0x000b140c, 0x0009140d, 0x0008140f, 0x00091311, 0x00091311, 0x00091211, 0x00091211, 0x00091310, 0x00091310, 0x00081210, 0x00081210, 0x00091310, 0x000a1410, 0x0007110d, 0x0007110d, 0x0006100d, 0x00050f0c, 0x00050f0c, 0x0005100b, 0x00060f09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e08, 0x00040f08, 0x00051009, 0x00051008, 0x00040e07, 0x00030c06, 0x00030c06, 0x00030c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00081110, 0x0008120f, 0x0008120f, 0x0008120f, 0x0007110d, 0x0007110d, 0x0007100e, 0x0007110e, 0x0007110d, 0x0006100c, 0x0005100a, 0x0005100a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00040d06, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00050c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00030e07, 0x00020e07, 0x00020e07, 0x00020e07, 0x0005100a, 0x0005100a, 0x00040e09, 0x0006100b, 0x0007110d, 0x0007110d, 0x0008120e, 0x0008120e, 0x00101a14, 0x002b342c, 0x00282d27, 0x00242620, 0x0023241f, 0x00282827, 0x002a2c2c, 0x00282a2d, 0x00272a2c, 0x0024292c, 0x00202728, 0x00202728, 0x001d2425, 0x00212628, 0x00282c30, 0x002c2f32, 0x00303032, 0x0031302d, 0x00302c28, 0x002e2721, 0x002c2319, 0x002e1f14, 0x00341f10, 0x003b2414, 0x003c2513, 0x0035210f, 0x002f1d0f, 0x002d1d0e, 0x002c1e0e, 0x002f2211, 0x00322514, 0x00342817, 0x00352818, 0x00352818, 0x0038291a, 0x003b2c1d, 0x003b2c1e, 0x003c2c1f, 0x003c2c20, 0x003b2a1c, 0x003d2b1b, 0x0041301c, 0x0044311f, 0x0047311f, 0x004c3422, 0x0049301d, 0x00482e19, 0x004b2c18, 0x0050311b, 0x00482c13, 0x00442710, 0x00432510, 0x003e230d, 0x003b1f09, 0x00381c08, 0x00381c08, 0x0039200d, 0x00381f0f, 0x00311a0c, 0x00301a0d, 0x00301a0d, 0x00301b0d, 0x002e1b0c, 0x002f1c0c, 0x002c1809, 0x002c190a, 0x002e1c0c, 0x002d1c0c, 0x002f1c0d, 0x00311c0d, 0x00301a0c, 0x0030190b, 0x00331b0d, 0x00341c0e, 0x00331b0d, 0x00331a0e, 0x0033190d, 0x0034180c, 0x00351906, 0x0040200a, 0x0046270e, 0x0047280c, 0x0049280b, 0x004f2a0b, 0x004d2705, 0x00552d0c, 0x00542b09, 0x00562c0b, 0x00592f0f, 0x00582d0e, 0x00552b0c, 0x005a2e10, 0x005d3311, 0x00603713, 0x00663b14, 0x006c3d14, 0x006e3d14, 0x006f3d10, 0x006e3d10, 0x006e3c0f, 0x0068380b, 0x0060330b, 0x00582c07, 0x00542a0b, 0x004d250c, 0x0046240a, 0x0046240c, 0x0045240e, 0x00401f0c, 0x003a1c09, 0x00331808, 0x002c1708, 0x0028180a, 0x0026180d, 0x0024150c, 0x0020140b, 0x0020140c, 0x001c1209, 0x001f140c, 0x0020140c, 0x001f140c, 0x001f140c, 0x001e150c, 0x001e150c, 0x001e150b, 0x001c1309, 0x001c1309, 0x001c140a, 0x001c140b, 0x001a150c, 0x0018140d, 0x0014110e, 0x000d120d, 0x0009140c, 0x0006120c, 0x00081110, 0x00091211, 0x00091211, 0x00091310, 0x0009130d, 0x0008120c, 0x0009140d, 0x0009140d, 0x0007110c, 0x0008100c, 0x0007100b, 0x0007100b, 0x0007100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0a, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00081110, 0x0008120f, 0x0008120f, 0x0008120d, 0x0007110c, 0x0007110c, 0x0007110e, 0x0007110e, 0x0007110d, 0x0005100b, 0x0005100a, 0x0005100a, 0x00040e09, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00050c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00030e07, 0x00020e07, 0x00020e07, 0x00020e07, 0x0005100a, 0x0005100a, 0x00040e09, 0x0006100b, 0x0006100c, 0x0007110d, 0x0008120f, 0x0008120e, 0x000f1812, 0x00212822, 0x002a2e27, 0x002d3029, 0x002d2e28, 0x002c2f2c, 0x002c2f30, 0x002a2d30, 0x00282d31, 0x00292e31, 0x002b3234, 0x00282e30, 0x00242b2c, 0x00202426, 0x001f2126, 0x00232628, 0x00282a2c, 0x002b2a27, 0x002a2520, 0x002c241f, 0x0030271d, 0x0034251b, 0x00372316, 0x00372111, 0x0037200e, 0x00392210, 0x00342011, 0x00342111, 0x00342513, 0x00382815, 0x00382816, 0x003a2917, 0x003a2917, 0x003a2917, 0x003a2817, 0x003a2717, 0x003d2b1b, 0x003e2c1c, 0x003e2b1d, 0x003c281b, 0x003c2818, 0x003d2b18, 0x00402d1a, 0x00402f1b, 0x00402f1a, 0x00402f19, 0x004c3622, 0x00472a17, 0x00492c18, 0x00492c17, 0x00462b14, 0x00412611, 0x003d230d, 0x003a200a, 0x003a1f0b, 0x00381c09, 0x00351b0a, 0x00361d0e, 0x00321b0f, 0x00301a0d, 0x00321b0f, 0x00331c0f, 0x00331d0c, 0x00301b0a, 0x002e1808, 0x002d1808, 0x002f1c0a, 0x002f1c0a, 0x00301c0c, 0x00311b0b, 0x00321a0a, 0x0034190a, 0x00361b0c, 0x00371c0d, 0x00341a0c, 0x00351a0c, 0x00371b0d, 0x00391b0c, 0x003c1c08, 0x0047240a, 0x004c290c, 0x004e2909, 0x00552f0d, 0x005b320f, 0x00582c08, 0x005f320d, 0x005f300c, 0x0061320e, 0x00643510, 0x0062340e, 0x0061320c, 0x0065350f, 0x00693813, 0x006a3c12, 0x006d3d10, 0x00703c0f, 0x00733e0d, 0x0075400c, 0x0076400e, 0x0075400e, 0x00703c0a, 0x0069380c, 0x0061320b, 0x005b2c0c, 0x00512809, 0x004a2608, 0x0049260a, 0x0049250c, 0x0046220b, 0x00401f09, 0x00391c07, 0x00311a07, 0x002b1908, 0x00281809, 0x00251508, 0x00211307, 0x001f1205, 0x00201508, 0x0024170c, 0x0024170c, 0x00201509, 0x00201509, 0x0020140a, 0x0020140a, 0x001f150a, 0x0021170c, 0x0020160b, 0x0020150a, 0x001e150a, 0x001c1509, 0x001a150f, 0x00171410, 0x0010140d, 0x0008140c, 0x0006120c, 0x00081110, 0x00081110, 0x00091211, 0x00091310, 0x0008120c, 0x0008120c, 0x0008120b, 0x0008120b, 0x0009100c, 0x000a100c, 0x00090f0b, 0x00090f0b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00040c07, 0x00040c06, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00081110, 0x0008120f, 0x0008120f, 0x0008120d, 0x0008100c, 0x0008100c, 0x0008110c, 0x0007110d, 0x0006100c, 0x00050f0b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c05, 0x00040c04, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00050c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00030e07, 0x00020e07, 0x00020e07, 0x00020e07, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x00040e0b, 0x0007110d, 0x000a140f, 0x0009130d, 0x000f1710, 0x001f2720, 0x002b2f28, 0x0031332d, 0x0031302c, 0x002f302e, 0x00303434, 0x00303335, 0x002d3236, 0x002b3034, 0x00282f34, 0x00272b30, 0x00272c30, 0x00282c2e, 0x0025282b, 0x0026292c, 0x00242627, 0x00252320, 0x0024201a, 0x00271f18, 0x002c2118, 0x00392c20, 0x00413022, 0x00463020, 0x00432a18, 0x003b2210, 0x00371d0c, 0x00382310, 0x003d2a17, 0x0044301c, 0x0046301d, 0x00472f1d, 0x00452e1c, 0x00432b18, 0x00422b18, 0x00442c1a, 0x00442c1a, 0x00442c1c, 0x00422b1c, 0x0040281a, 0x00402917, 0x00402b16, 0x00402d17, 0x00402e18, 0x00402d16, 0x0043301a, 0x00442e19, 0x004a3320, 0x00442a18, 0x00442b17, 0x00442a16, 0x00402712, 0x003b240f, 0x0039220c, 0x0038200b, 0x003a1e0d, 0x00331809, 0x0031180b, 0x00311a0d, 0x00321a0e, 0x00341b10, 0x00351c0f, 0x00341c0c, 0x00331a09, 0x00321a08, 0x00311a08, 0x00301a08, 0x002f1908, 0x00301a08, 0x00321b09, 0x00341808, 0x00371b0b, 0x00371a0b, 0x00371a0b, 0x00361909, 0x00371a0b, 0x00391b0b, 0x003c1c0c, 0x00401f09, 0x004f2a10, 0x00573010, 0x00552c08, 0x005c310c, 0x0061340c, 0x00603009, 0x0067360f, 0x0068340d, 0x006c3810, 0x006e3b12, 0x006b3810, 0x006b370d, 0x006c380e, 0x006d390d, 0x00713e0f, 0x0074400e, 0x0079420e, 0x007e440f, 0x007e440e, 0x007e440f, 0x007d4410, 0x007a400d, 0x00713d0d, 0x0067350c, 0x0060300c, 0x00592e0c, 0x00502909, 0x004e2909, 0x004c2609, 0x00462108, 0x0044220b, 0x0041230e, 0x00371c0a, 0x002c1808, 0x00281808, 0x00251305, 0x00231205, 0x00231407, 0x00231608, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x0020160b, 0x0020160b, 0x001f1409, 0x001f1409, 0x00201409, 0x0020140a, 0x001f1409, 0x001d1409, 0x001c140e, 0x00181411, 0x00141610, 0x0009140c, 0x0005110c, 0x00091010, 0x00081110, 0x0008120f, 0x0009110f, 0x0008120c, 0x0008110b, 0x0007110a, 0x0008110a, 0x00090f0b, 0x00090f0b, 0x00080e0a, 0x00080e0a, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070c0b, 0x00070c0b, 0x00070c0b, 0x00070c0b, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00091211, 0x0008120f, 0x0008120f, 0x0007110c, 0x0008100b, 0x0008100c, 0x0007100c, 0x0006100c, 0x00050f0c, 0x00050f0b, 0x0005100a, 0x00050f0a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c05, 0x00040c04, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00050c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00030e07, 0x00020e07, 0x00020e07, 0x00020e07, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x00040e0b, 0x0006100c, 0x0008120d, 0x0009140d, 0x00131c14, 0x001f261f, 0x00282b24, 0x0031312c, 0x00353530, 0x00313130, 0x002d3132, 0x00303335, 0x002e3337, 0x002d3238, 0x002c3338, 0x002e3338, 0x00292e33, 0x00292f30, 0x00292c2f, 0x00252829, 0x00242424, 0x00252220, 0x002a241f, 0x002c241e, 0x002b2018, 0x0034281c, 0x003d2d20, 0x00463020, 0x004c3120, 0x00492d1b, 0x00432917, 0x00442e1a, 0x0049331c, 0x004c341f, 0x00503420, 0x00523521, 0x00513420, 0x004d311d, 0x004b301c, 0x004b311c, 0x004b311c, 0x004c311f, 0x00482f1d, 0x00452c1b, 0x00442c18, 0x00452d17, 0x00442e16, 0x00432d15, 0x00412b14, 0x00422c16, 0x00402814, 0x00442b18, 0x00452d1a, 0x00422a18, 0x003f2915, 0x003d2713, 0x003a250f, 0x0038230c, 0x0037200c, 0x00371c0c, 0x00351b0c, 0x0031180b, 0x0030180c, 0x0031180c, 0x0034180c, 0x0035180c, 0x00371b0c, 0x00371c0b, 0x00371c0a, 0x00361c0a, 0x00341c09, 0x00331c08, 0x00341c08, 0x00381c0a, 0x00351806, 0x00381a09, 0x00371908, 0x00381a09, 0x003a1b0a, 0x003b1c0b, 0x00422210, 0x0043210e, 0x0048240d, 0x00563014, 0x005c3210, 0x0060340d, 0x00683811, 0x006c3c12, 0x006b370d, 0x00733c12, 0x00703a0f, 0x00733b10, 0x00743d11, 0x00723b0e, 0x00703a0c, 0x00773e10, 0x0077400f, 0x007b4411, 0x00804812, 0x00844a11, 0x00874a11, 0x00884a11, 0x00884912, 0x00854811, 0x0080430c, 0x00753f0e, 0x006b370a, 0x0063320b, 0x005d310e, 0x00562d0c, 0x00532c0c, 0x0050280b, 0x004f270d, 0x004d2810, 0x0044220c, 0x00391c0b, 0x00301807, 0x002a1607, 0x00281509, 0x0028170b, 0x00241406, 0x00201305, 0x001f1408, 0x001f1408, 0x00201609, 0x00201508, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201408, 0x001f1408, 0x001d140c, 0x00181411, 0x0014160f, 0x000a140c, 0x0006110c, 0x00091010, 0x00081110, 0x0008120f, 0x0008100d, 0x0008110b, 0x0007110a, 0x0007110a, 0x0007110a, 0x0006100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00080c0b, 0x00080c0b, 0x00080c0b, 0x00080c0b, 0x00070b07, 0x00060b06, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x00091310, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0a, 0x00040e09, 0x00050f0a, 0x00040e09, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d0a, 0x00070e0d, 0x00040c0a, 0x00040c0a, 0x00040c08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00070f08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060d08, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e0b, 0x00060d0b, 0x0008100c, 0x0008100d, 0x000b130d, 0x00182018, 0x001d231c, 0x00252923, 0x0033342e, 0x00343530, 0x00323432, 0x00303434, 0x002f3335, 0x002c3034, 0x002c3036, 0x002e3338, 0x0032373c, 0x0033363b, 0x00323538, 0x00303334, 0x002a2c2d, 0x00262626, 0x0024211f, 0x0028211e, 0x002e241f, 0x002c2118, 0x00322619, 0x003a2c1c, 0x00442f1e, 0x004a301d, 0x004e3320, 0x004f3520, 0x004e331e, 0x0050351d, 0x0053341c, 0x0054341c, 0x00593820, 0x00583821, 0x00593822, 0x00573720, 0x00573821, 0x00563820, 0x0054341e, 0x0050331c, 0x0050321b, 0x0050331c, 0x004c2f18, 0x00442a13, 0x00442b12, 0x00452c14, 0x00442913, 0x00412813, 0x003e2610, 0x003f2613, 0x00422a17, 0x003f2713, 0x003d2610, 0x003c2510, 0x003a2310, 0x0038210d, 0x00371f0d, 0x00341c0c, 0x00331c0c, 0x00301909, 0x00351c0c, 0x00371c0c, 0x003a200d, 0x003c220e, 0x003d220e, 0x003a1e0a, 0x003d220e, 0x00381c08, 0x003a1e0a, 0x00402410, 0x003d200c, 0x003a1a08, 0x003b1b08, 0x003c1c09, 0x003e1e0b, 0x00401e0b, 0x0044230f, 0x004b2711, 0x004f2a10, 0x00562f0f, 0x005d330f, 0x0064360f, 0x006b380f, 0x00713c10, 0x00753f12, 0x00763e0f, 0x00763e0d, 0x00753d0c, 0x00783f0f, 0x007b4110, 0x00783f0c, 0x007c4210, 0x007f4512, 0x00824814, 0x00874912, 0x00884910, 0x00874910, 0x008b4c13, 0x008b4c14, 0x008b4c14, 0x008a4a14, 0x00874810, 0x007c410c, 0x00703c08, 0x0067350a, 0x0060300c, 0x005c2c0c, 0x00582c0d, 0x0054280c, 0x00562d12, 0x004c240b, 0x0047220c, 0x003a1a07, 0x00321808, 0x002d1608, 0x002a160b, 0x00281609, 0x00271609, 0x00221407, 0x0022170a, 0x0023180b, 0x00221509, 0x00221509, 0x00221509, 0x00211408, 0x00241509, 0x00201207, 0x00211308, 0x00231409, 0x0023150a, 0x0023170a, 0x0020180c, 0x001a170f, 0x0015160f, 0x000f110c, 0x0009100b, 0x00091010, 0x0007130f, 0x0007110d, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x00040e09, 0x0005100a, 0x0007100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x000a1410, 0x0007110d, 0x0007110d, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x00050f0c, 0x0005100b, 0x00040f0a, 0x00040e09, 0x0006100b, 0x00040e09, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00080d08, 0x00080d0a, 0x00070e0c, 0x00040c0a, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00080f0b, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e0b, 0x00070e0c, 0x00070e0c, 0x0008100c, 0x000b130d, 0x00182018, 0x001f241d, 0x002b2c26, 0x0032332d, 0x0033342f, 0x00303230, 0x002f3233, 0x002c2f32, 0x00282c30, 0x00282d31, 0x002c3034, 0x002e3337, 0x00303338, 0x00303335, 0x002c3030, 0x002c2d2d, 0x002b2b29, 0x00282420, 0x0027201d, 0x002c211e, 0x002f241c, 0x0034281a, 0x00382819, 0x00422d1c, 0x00472e1b, 0x004b301e, 0x004e3420, 0x00523620, 0x00563820, 0x0059381d, 0x005e3b1f, 0x00633e22, 0x00664027, 0x00674228, 0x00603c22, 0x005f3b20, 0x005e3a20, 0x005d3a20, 0x005a381d, 0x0057351a, 0x00563419, 0x00533018, 0x004c2e14, 0x00492d12, 0x00482c12, 0x00492c15, 0x00472c14, 0x00442813, 0x00432812, 0x00412511, 0x003e240e, 0x003f250f, 0x003f2510, 0x003e2410, 0x003c220e, 0x003b210d, 0x003a200d, 0x00381e0c, 0x00351b0a, 0x00371c0a, 0x003b1f0b, 0x0040240d, 0x0041240d, 0x0040240c, 0x003e1f08, 0x0042230c, 0x0040200a, 0x0045240e, 0x00472610, 0x0042210c, 0x00401d08, 0x00401d08, 0x0044220c, 0x0046240e, 0x0048240e, 0x004c2710, 0x00512b10, 0x00562e0f, 0x00603511, 0x00683a10, 0x006c3a0e, 0x00713c10, 0x00784112, 0x007c4313, 0x00804412, 0x00804412, 0x007f440f, 0x00824712, 0x00844814, 0x00804510, 0x00834811, 0x00844a13, 0x00874b13, 0x008c4c14, 0x008b4c11, 0x008b4c11, 0x008e4e14, 0x008e4f16, 0x008e4f16, 0x008c4c14, 0x008a4b12, 0x0081450e, 0x0074400a, 0x006b380b, 0x0061310b, 0x005f2e0d, 0x005d3010, 0x005c3013, 0x00582c11, 0x0052280e, 0x0049230b, 0x00401f0b, 0x003a1d0e, 0x002e1508, 0x002c180c, 0x002b180c, 0x0027170a, 0x00221407, 0x00201408, 0x00201609, 0x00201609, 0x0022170a, 0x0023160c, 0x0022150b, 0x00201308, 0x001d1005, 0x001c1005, 0x00201208, 0x00201308, 0x001f1308, 0x001d150a, 0x001d1810, 0x00191710, 0x0011100c, 0x000c100c, 0x00091012, 0x0007130f, 0x0006110d, 0x0005100a, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x00050f0a, 0x00010c06, 0x00060f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x000a1410, 0x0008110e, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x0006100b, 0x00040e09, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00080d08, 0x00080d0a, 0x00070e0c, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00071007, 0x00071007, 0x00051008, 0x00051008, 0x00040f08, 0x00050f08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00050c06, 0x00040b04, 0x00040b04, 0x00030c04, 0x00030c04, 0x00040d07, 0x00040d07, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040e09, 0x0005100a, 0x00050f0c, 0x00070e0c, 0x00070e0c, 0x0008100c, 0x000b110c, 0x0019201a, 0x001f241e, 0x00242622, 0x002a2b27, 0x0030302c, 0x00313431, 0x00303434, 0x002d3034, 0x00292e32, 0x002d3236, 0x002d3236, 0x002b2e32, 0x00292c30, 0x002c2e30, 0x002c2e2f, 0x00282828, 0x002a2827, 0x002b2824, 0x002b2421, 0x002a201c, 0x0030241c, 0x003a2c20, 0x003c2c1c, 0x00412c1b, 0x0048301e, 0x004b3020, 0x004d3320, 0x00523420, 0x005d3c27, 0x00603c23, 0x00664023, 0x006a4224, 0x006c4426, 0x006d4528, 0x006b4425, 0x00684224, 0x00653f20, 0x00633c1e, 0x00603a19, 0x005d3717, 0x00593314, 0x00593214, 0x00563313, 0x00513010, 0x004d2c0f, 0x004c2b0f, 0x004c2b0f, 0x004a2b0f, 0x0048290e, 0x0045250e, 0x0042220a, 0x0046270f, 0x0040230b, 0x0041220c, 0x0042230c, 0x0042230d, 0x0041220d, 0x003f200c, 0x0040200c, 0x0044240e, 0x00482810, 0x0049270d, 0x0048270b, 0x004a280c, 0x0049260a, 0x00482409, 0x004b260b, 0x004f2a0f, 0x004e290d, 0x00492408, 0x00482106, 0x004a2409, 0x004d250b, 0x004c240b, 0x0050280d, 0x00582d12, 0x005e3113, 0x00633512, 0x00693910, 0x006d3b0f, 0x00744010, 0x007b4411, 0x007e4411, 0x00824710, 0x00854911, 0x0086480f, 0x00884a10, 0x00894c13, 0x008a4c13, 0x008b4d12, 0x008b4d13, 0x008a4d12, 0x008b4d12, 0x008d4e11, 0x008d4e11, 0x008e4f12, 0x00905116, 0x00905016, 0x008f5015, 0x008f4f14, 0x008d4f14, 0x00874c12, 0x007b440e, 0x006e3c0d, 0x0062320a, 0x0060300d, 0x00603210, 0x00603516, 0x00572c0f, 0x00542a0e, 0x00492309, 0x00482710, 0x00351806, 0x00341c0d, 0x002c180c, 0x0029180c, 0x0028180b, 0x00231508, 0x00201408, 0x001d1205, 0x001e1308, 0x001f1407, 0x001f1408, 0x001f1408, 0x001f1308, 0x001d1106, 0x001c1107, 0x001d1208, 0x001e1209, 0x001b1108, 0x00181005, 0x00171209, 0x0018160e, 0x0014130c, 0x000c100c, 0x00081010, 0x0006110d, 0x0006100c, 0x00070f0a, 0x0006100b, 0x0008120c, 0x0006100b, 0x0005100a, 0x0007110c, 0x0007110c, 0x00050e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x000a1410, 0x0008110e, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x0006100b, 0x00040e09, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00080d08, 0x00080d08, 0x00070f0a, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040e09, 0x0005100a, 0x00050f0c, 0x00050f0c, 0x00070e0c, 0x0008100c, 0x000a100b, 0x00171d18, 0x001a201a, 0x00212520, 0x00292a26, 0x0030302c, 0x00313433, 0x00313437, 0x00313438, 0x002f3438, 0x002c3034, 0x00282d31, 0x0026282d, 0x00222529, 0x00242627, 0x00272928, 0x00272725, 0x00272623, 0x002e2926, 0x00362e2a, 0x002e221c, 0x002d2218, 0x003a2c20, 0x00423122, 0x00442f1d, 0x00493120, 0x004d3423, 0x00503623, 0x00543623, 0x0063422c, 0x006b462d, 0x0072492b, 0x00774c2d, 0x00764a2b, 0x00714726, 0x00704724, 0x006b4420, 0x0069421f, 0x00683e1b, 0x00663c18, 0x00643c17, 0x00623815, 0x00633715, 0x00603814, 0x005b3511, 0x0058310f, 0x00563010, 0x0054300f, 0x00532e10, 0x00522d0f, 0x004d280c, 0x00482509, 0x004c280d, 0x004b280d, 0x004a260e, 0x004a260e, 0x0049260e, 0x0047240b, 0x004c2810, 0x004c2810, 0x004d2a10, 0x00502b10, 0x00502c0e, 0x00532d0d, 0x00542d0d, 0x00542c0c, 0x00522a0b, 0x00562c0c, 0x00582d0f, 0x00572c0d, 0x00512708, 0x00532708, 0x0055290b, 0x0054290b, 0x0054290b, 0x005c2e10, 0x00623414, 0x00653613, 0x006a3912, 0x00703d10, 0x00794311, 0x00804813, 0x00824a12, 0x00844a10, 0x00884c10, 0x00894c0e, 0x00894c0d, 0x008c4c0f, 0x008d5010, 0x008c4e10, 0x008d4e10, 0x008d4e10, 0x008d4e10, 0x008d4e10, 0x00905013, 0x008f5011, 0x008f5011, 0x00905214, 0x00905114, 0x008f5014, 0x008f5013, 0x008e4f12, 0x00884e10, 0x007c470d, 0x006f3c0b, 0x0068380d, 0x0062320c, 0x0060320d, 0x005c330f, 0x0059300f, 0x00562c0d, 0x0050290c, 0x00422009, 0x0040240f, 0x00341b0a, 0x002b170c, 0x00281709, 0x00251508, 0x00221406, 0x00201308, 0x001c1104, 0x001b1005, 0x001b1104, 0x001a1105, 0x00191105, 0x00181105, 0x00181004, 0x00191006, 0x001c1208, 0x001c140a, 0x001e140b, 0x001c140a, 0x00181007, 0x0016120b, 0x0013130c, 0x000d100c, 0x00080f0e, 0x0005100c, 0x0006100b, 0x00080f0a, 0x0007100b, 0x0009130d, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00050d09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0007130f, 0x00081410, 0x0008130f, 0x0007110d, 0x0006100d, 0x0006100d, 0x0006100c, 0x0006100c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c09, 0x00040c08, 0x00040d08, 0x00040e07, 0x00040d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c07, 0x00060d06, 0x00050c06, 0x00050c05, 0x00050c05, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00060d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060f09, 0x00040e0a, 0x0005100a, 0x0005100b, 0x0008100c, 0x00080f09, 0x00161b16, 0x001c211c, 0x00212520, 0x002c2e2a, 0x0030322f, 0x00303232, 0x002e3134, 0x00303237, 0x002d3036, 0x002c2f34, 0x002b3034, 0x00272a2f, 0x0024282a, 0x00242525, 0x00222421, 0x0021221f, 0x0022201c, 0x0027221e, 0x00342c28, 0x00392e27, 0x0032261b, 0x0037291a, 0x00423120, 0x004a3424, 0x004a3422, 0x004c3422, 0x00503825, 0x005a3d2c, 0x00684834, 0x006f4932, 0x00754c2d, 0x007b4f2e, 0x007d4f2d, 0x007b4c29, 0x00784823, 0x0074441f, 0x0073441d, 0x0071421c, 0x006c3e18, 0x006a3c15, 0x00683b14, 0x00683a14, 0x00653a12, 0x00633910, 0x005f360c, 0x005e360d, 0x005c340f, 0x00593110, 0x00572f0d, 0x00542d0d, 0x00522c0c, 0x00512c0c, 0x00522e0e, 0x00512d0d, 0x00512d0d, 0x00512c0e, 0x00512a0c, 0x00542e10, 0x00542e0f, 0x00512b0b, 0x00542c0c, 0x00572f0e, 0x0059300d, 0x005b3210, 0x005c3110, 0x005c310f, 0x005d300f, 0x005e3110, 0x005f3210, 0x005e300f, 0x005c2e0d, 0x005d2f0c, 0x005e2f0c, 0x005e2f0b, 0x0062340d, 0x00673810, 0x006c3c10, 0x00713e11, 0x00774011, 0x007f4513, 0x00844910, 0x00874c10, 0x008c5013, 0x008e5014, 0x008e5010, 0x008c4d0e, 0x00904f0e, 0x00925010, 0x00935010, 0x00935010, 0x00925010, 0x00925010, 0x00925010, 0x00905311, 0x00905310, 0x00905110, 0x00905212, 0x00905111, 0x00905111, 0x00905010, 0x008f5010, 0x008a4c0e, 0x0081460c, 0x00743e09, 0x006d380c, 0x006a3911, 0x00633610, 0x005d310e, 0x005c3310, 0x005a300f, 0x00552b0d, 0x004c280d, 0x0040200b, 0x00341906, 0x002c1709, 0x002a170a, 0x00261408, 0x00211205, 0x001e1205, 0x001c1106, 0x001c1206, 0x001a1106, 0x001a1208, 0x001b1409, 0x001b1409, 0x001c140a, 0x001a1208, 0x00191208, 0x001c140a, 0x001e160d, 0x001f170e, 0x001c140c, 0x001c140c, 0x0018140d, 0x0011130d, 0x00080f0e, 0x0004100c, 0x0005100c, 0x00080e0a, 0x0006100b, 0x0006100b, 0x0007100a, 0x0007100a, 0x00050e09, 0x00050e09, 0x00040c08, 0x00040c08, 0x00040d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00060d08, 0x00060c08, 0x00050c08, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c08, 0x00070d09, 0x00060d08, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006130f, 0x0006130f, 0x0006110d, 0x0006110d, 0x0006110d, 0x0006110d, 0x0006100c, 0x0006100c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x0004100a, 0x0005100a, 0x000c120e, 0x000c130d, 0x00161c16, 0x00212520, 0x00282c28, 0x00303430, 0x002e322d, 0x00262828, 0x00232629, 0x00272a2e, 0x002c2f35, 0x0033353c, 0x0033383c, 0x002e3035, 0x002b2e30, 0x00292b2a, 0x00262825, 0x00242521, 0x00252420, 0x0026211d, 0x002a211d, 0x00352b21, 0x003c2e21, 0x00382819, 0x00433020, 0x004c3826, 0x004e3826, 0x004e3827, 0x00543e2d, 0x00624634, 0x006c4b38, 0x00704b34, 0x00795033, 0x007f5234, 0x00825231, 0x0080502c, 0x007d4a25, 0x007c4821, 0x007a4820, 0x0078461e, 0x0076441c, 0x0073421a, 0x00703f18, 0x006c3d13, 0x006c3d13, 0x006c3c11, 0x00683b10, 0x0066380d, 0x00643810, 0x00633610, 0x005f340f, 0x005c330e, 0x005c330e, 0x005b340e, 0x005b340e, 0x0058310d, 0x0058310d, 0x0059310d, 0x005a310d, 0x005c3410, 0x005e340f, 0x005c320c, 0x005f340f, 0x00623811, 0x00643813, 0x00643812, 0x00663812, 0x00673812, 0x00683812, 0x00683813, 0x00693914, 0x00683812, 0x00683711, 0x00683711, 0x00683810, 0x0068380e, 0x006c3c0e, 0x00704010, 0x00744110, 0x00794410, 0x00804710, 0x00874b14, 0x008b4e11, 0x008e5011, 0x008f5012, 0x00905113, 0x00905112, 0x00915010, 0x00935010, 0x00965111, 0x00975111, 0x00965211, 0x00955211, 0x00955211, 0x00945110, 0x00905110, 0x00905210, 0x00905111, 0x00905111, 0x00915110, 0x00915110, 0x0090500e, 0x0090500e, 0x008c4d10, 0x0086490d, 0x007c400d, 0x0070380b, 0x006b3810, 0x00663610, 0x00633410, 0x005d3310, 0x005a2f0d, 0x00562b0c, 0x004f280e, 0x0043200b, 0x00371906, 0x002d1808, 0x002b170a, 0x0029180c, 0x00251508, 0x00211408, 0x00201409, 0x001f150a, 0x001c140a, 0x001c140a, 0x001c140a, 0x001c1409, 0x001c1409, 0x00181207, 0x00181106, 0x00181108, 0x001b140c, 0x001c150c, 0x001d140c, 0x0020140e, 0x001c140e, 0x0014130c, 0x00080f0c, 0x0004100c, 0x00050f0c, 0x00080e0a, 0x0006100a, 0x0005100a, 0x0008100b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c08, 0x00080e08, 0x00070d07, 0x00070e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d02, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071410, 0x00071410, 0x0007120e, 0x0006120e, 0x0006110d, 0x0005110c, 0x0006100c, 0x0006100c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x0004100a, 0x0005100a, 0x0009120d, 0x000c130e, 0x00181c18, 0x00262924, 0x002c302b, 0x002c2f2a, 0x002c2e2a, 0x002c2e2d, 0x002c2f32, 0x00313438, 0x0035383e, 0x0034373d, 0x0033363b, 0x00303136, 0x00282c2d, 0x002a2c2b, 0x002a2c2a, 0x002a2b28, 0x002c2a25, 0x002c2723, 0x002d2520, 0x002f2419, 0x003c2f21, 0x003e2e1f, 0x00443021, 0x004c3627, 0x004e3827, 0x004e3828, 0x00543c2c, 0x00614535, 0x006d4c3b, 0x0075503c, 0x0080573a, 0x00845739, 0x00835433, 0x0084512f, 0x00824e28, 0x00804c25, 0x007e4b23, 0x007c4a21, 0x007c4920, 0x007b481e, 0x0078451c, 0x00754218, 0x00734016, 0x00714014, 0x006e3c10, 0x006c3910, 0x006c3b10, 0x00693a0e, 0x0067370c, 0x0064370c, 0x0063370c, 0x0062350f, 0x0061360f, 0x0061370e, 0x0062370f, 0x0063360d, 0x0063370e, 0x00683810, 0x00673810, 0x0067380e, 0x00693c10, 0x006c3c12, 0x006c3c12, 0x006e3d12, 0x006f3d11, 0x00703d12, 0x00713e13, 0x00713e14, 0x00723e14, 0x00713d13, 0x00703c11, 0x00703c11, 0x00703c10, 0x00713c0e, 0x0075400f, 0x0079440f, 0x007d450e, 0x00834810, 0x00884a0f, 0x008c4c10, 0x008f4f10, 0x00925013, 0x00935113, 0x00935113, 0x00935112, 0x00945112, 0x00965011, 0x00985011, 0x00985111, 0x00975210, 0x00975211, 0x00965111, 0x00955211, 0x00935311, 0x00905210, 0x00905111, 0x00915111, 0x0090500e, 0x0090500e, 0x0090500f, 0x0090500e, 0x008d4e10, 0x00884a10, 0x007d420e, 0x00743c0e, 0x006c380d, 0x0068380f, 0x00683811, 0x0060330e, 0x00592c0a, 0x00562b0c, 0x004f280e, 0x0044200c, 0x00391c09, 0x00301b0b, 0x00291508, 0x0028170b, 0x00271709, 0x0024150a, 0x0021140a, 0x0020160c, 0x001e170d, 0x001d150c, 0x001d150c, 0x001b1409, 0x00181107, 0x00181208, 0x00141006, 0x00130e04, 0x00171108, 0x0018130a, 0x001b130c, 0x001f140e, 0x001c150f, 0x0015140d, 0x000c110d, 0x0007110c, 0x00050f0c, 0x00080e0b, 0x0006100a, 0x0005100a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050c08, 0x00050c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d06, 0x00050c05, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060c05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c08, 0x00080e08, 0x00070e05, 0x00070e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d02, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x0007130f, 0x0007130f, 0x0006110d, 0x0005110b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00030f09, 0x00050e09, 0x00070d09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x0004100a, 0x0005100a, 0x0009120c, 0x000e1610, 0x001e241e, 0x00282b27, 0x002a2c28, 0x002d302c, 0x002d302c, 0x002c2e2d, 0x002a2d30, 0x002a2d32, 0x002d3037, 0x002c3036, 0x002d3034, 0x002e2f34, 0x002d2f32, 0x002b2c2d, 0x002a2c2b, 0x002b2c28, 0x002c2b26, 0x002d2824, 0x00302622, 0x0035291f, 0x003b2c20, 0x00413021, 0x00493526, 0x004a3426, 0x004c3426, 0x00503829, 0x005c4335, 0x006b4e40, 0x00755445, 0x007b5644, 0x0080563a, 0x00835538, 0x00855434, 0x00875431, 0x0086512c, 0x00845028, 0x00824e25, 0x00804c24, 0x007f4b22, 0x007d481f, 0x007c481d, 0x007c471c, 0x007c4519, 0x007a4317, 0x00784013, 0x00753e10, 0x00743f10, 0x00723c0e, 0x006e3b0b, 0x006d3c0b, 0x006c3b0c, 0x006b3a0f, 0x006b3a10, 0x006b3a0e, 0x006c3c0f, 0x006c3c0e, 0x006d3b0e, 0x00703e10, 0x00713e0f, 0x00734010, 0x00764311, 0x00774413, 0x00784313, 0x00784312, 0x007a4311, 0x007a4412, 0x007c4312, 0x007c4313, 0x007c4313, 0x007b4211, 0x007c4010, 0x007c4010, 0x007c410f, 0x007c420d, 0x0080460f, 0x0082480f, 0x00874b11, 0x008c4d14, 0x00914f14, 0x00945013, 0x00965114, 0x00965415, 0x00975415, 0x00975414, 0x00985414, 0x00995312, 0x009b5212, 0x009c5212, 0x009c5211, 0x00985411, 0x00985412, 0x00985414, 0x00985414, 0x00945412, 0x00915110, 0x00915111, 0x00915111, 0x00945110, 0x00945211, 0x00915210, 0x00915110, 0x008d4e10, 0x00884910, 0x007d420e, 0x00753c0f, 0x006e380d, 0x006c380e, 0x006b3810, 0x0064350f, 0x005e300d, 0x00582c0e, 0x004c240b, 0x0046210c, 0x003a1d0a, 0x002e1808, 0x00281406, 0x00261408, 0x00231407, 0x00201307, 0x001d1106, 0x001a1007, 0x00181008, 0x00181006, 0x00171005, 0x001b1409, 0x001b140b, 0x001c160d, 0x0018140b, 0x00151208, 0x00120f06, 0x00130e06, 0x001a110b, 0x001f140e, 0x001d150f, 0x0016140e, 0x0010130f, 0x0009110d, 0x00070f0c, 0x00080e0c, 0x0006100a, 0x0005100a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d06, 0x00050d05, 0x00060d03, 0x00060d03, 0x00060d03, 0x00060d04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c06, 0x00080f06, 0x00070e04, 0x00070e04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d02, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x0008130f, 0x0008120e, 0x0006110c, 0x0006110b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051009, 0x00040f08, 0x00040d08, 0x00030d08, 0x00040d08, 0x00040d08, 0x00040e08, 0x00040e08, 0x00050d08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050c08, 0x00050c08, 0x00050d07, 0x00050d06, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00050c07, 0x00050c06, 0x00050c06, 0x00040c06, 0x00040c06, 0x00050c07, 0x00050c07, 0x00050c06, 0x00040c06, 0x00050c06, 0x00050c07, 0x00050c07, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040d09, 0x00040d09, 0x00040d09, 0x00040d09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040f09, 0x00050e09, 0x00060e09, 0x00080c09, 0x00060e09, 0x00050e09, 0x00050e08, 0x00040e08, 0x00041009, 0x00051009, 0x000b140d, 0x00161e18, 0x00242a24, 0x00252823, 0x001c1f1a, 0x001c1e19, 0x001a1c18, 0x001c1f1e, 0x00202325, 0x00292c30, 0x00303439, 0x00313439, 0x00313438, 0x002f3034, 0x002b2c30, 0x002a2c2d, 0x00282b29, 0x00262624, 0x00282722, 0x002d2824, 0x00312721, 0x0033271d, 0x003a2c1f, 0x00443323, 0x004c3728, 0x0050382b, 0x00543c2e, 0x00563f30, 0x005c4436, 0x006c5042, 0x00775748, 0x007c5847, 0x00825a40, 0x00865a3e, 0x00885838, 0x008a5734, 0x0088542e, 0x0086512b, 0x00855028, 0x00854f26, 0x00834c23, 0x00814b20, 0x0080491f, 0x0080481c, 0x0081481a, 0x00834918, 0x00834a18, 0x007e4612, 0x007c4410, 0x007a420f, 0x0076400c, 0x0074400c, 0x0074400b, 0x00723d0d, 0x00723f0c, 0x00723f0c, 0x0073400c, 0x00743f0c, 0x00743f0b, 0x0078420d, 0x0078420c, 0x007c4610, 0x007e4811, 0x00804811, 0x00804911, 0x00814810, 0x00814810, 0x00834810, 0x00844911, 0x00844911, 0x00844810, 0x00834810, 0x0083460f, 0x00844610, 0x0084470e, 0x0084480f, 0x0085490c, 0x00874a0d, 0x008e4d12, 0x00925014, 0x00975314, 0x00995414, 0x00995412, 0x00995411, 0x009a5412, 0x009a5412, 0x009a5411, 0x009b5411, 0x009c5310, 0x009c5210, 0x009c5310, 0x00995410, 0x009a5411, 0x009b5414, 0x00995515, 0x00945212, 0x0091500f, 0x00915111, 0x00935111, 0x00955312, 0x00965413, 0x00955413, 0x00935311, 0x008e5011, 0x00874b11, 0x007d420e, 0x00773c0e, 0x00703a0d, 0x006e380e, 0x006c380f, 0x0067360f, 0x0061330f, 0x00592e0e, 0x004f280c, 0x0046220b, 0x003c1c09, 0x002c1705, 0x002a1707, 0x00241407, 0x00201204, 0x001d1205, 0x001b1005, 0x00160c04, 0x00140c04, 0x00130c02, 0x00120b01, 0x00130c03, 0x00140d04, 0x00130f06, 0x00121108, 0x00141309, 0x0017150d, 0x0019140d, 0x001c110c, 0x00201410, 0x001f1711, 0x0018150f, 0x0010130e, 0x0009110c, 0x0008100c, 0x00080d0c, 0x00050f09, 0x00050f09, 0x00060e09, 0x00060e08, 0x00050d09, 0x00050d09, 0x00060d08, 0x00060d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c06, 0x00070e07, 0x00070d05, 0x00070d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c04, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x0008120f, 0x0008120d, 0x0007110c, 0x0007110c, 0x0006100b, 0x0005100a, 0x00051009, 0x00040f08, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c09, 0x00040c09, 0x00060e0b, 0x00060e0a, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050c07, 0x00060d07, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00041008, 0x0008110a, 0x00121b14, 0x00222822, 0x00191c18, 0x000b0d08, 0x0010130e, 0x00161814, 0x00222424, 0x00282c2e, 0x00272a2e, 0x002b2e32, 0x002d3034, 0x002e3035, 0x002d2e33, 0x002c2e31, 0x002a2c2c, 0x00272828, 0x00242423, 0x00282724, 0x002f2823, 0x00312721, 0x0034281e, 0x003d2d21, 0x00443022, 0x004d3628, 0x00543c2e, 0x00583f31, 0x005a4134, 0x005e4738, 0x00684d3f, 0x00735344, 0x007a5546, 0x00855c48, 0x00885d42, 0x0089593a, 0x008a5734, 0x0088532e, 0x0087512b, 0x00885129, 0x00885027, 0x00875026, 0x00864f24, 0x00885023, 0x00884e20, 0x00864c1b, 0x00864a16, 0x00864c15, 0x00884c15, 0x00834a12, 0x00814810, 0x007e450f, 0x007e440f, 0x007d440e, 0x007c430d, 0x007c430c, 0x007e450d, 0x007e450c, 0x007e440d, 0x007f440c, 0x0082480e, 0x0082480f, 0x00844a12, 0x00874a12, 0x00884c10, 0x00884c10, 0x00884d10, 0x008a4c10, 0x008a4c12, 0x00894b11, 0x00894b10, 0x00884b0f, 0x00884b0f, 0x008a4c10, 0x008a4c12, 0x008a4c12, 0x008b4d12, 0x008d5012, 0x008f5111, 0x00945010, 0x00955210, 0x009a5612, 0x009c5711, 0x009f5612, 0x00a05713, 0x009e5511, 0x009e5511, 0x009e5512, 0x009e5513, 0x009e5512, 0x009d5411, 0x009d5510, 0x009c5712, 0x009c5714, 0x00995412, 0x00995414, 0x00955213, 0x00915010, 0x00915010, 0x00945010, 0x00945211, 0x00965413, 0x00965413, 0x00935311, 0x008e5011, 0x00884c13, 0x007e430e, 0x00773d0e, 0x00743c0e, 0x006f390c, 0x006c380d, 0x006b3810, 0x0063350f, 0x005b300d, 0x0050290b, 0x0048240a, 0x003c1d07, 0x00301907, 0x002a1707, 0x00251406, 0x00201305, 0x001c1304, 0x001c1307, 0x001a1308, 0x001a1209, 0x00191209, 0x00181109, 0x00171008, 0x00140f06, 0x00100d04, 0x00100e05, 0x00121008, 0x00141109, 0x0017110a, 0x001c100c, 0x00201410, 0x00201812, 0x0018150f, 0x0010120c, 0x0008110a, 0x0008100b, 0x00070c0b, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x0008120f, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100a, 0x0005100a, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040c04, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c08, 0x00040c08, 0x0008100b, 0x0008100b, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0004100a, 0x0005100b, 0x000c160f, 0x001e241f, 0x001c1f1a, 0x00171914, 0x001c1e1a, 0x002c2e2a, 0x00303330, 0x002f3333, 0x002b2d31, 0x002b2e32, 0x002c3034, 0x002d3034, 0x002e2f34, 0x002e2f32, 0x002c2d2f, 0x00292b2c, 0x00292a28, 0x002f2d2a, 0x002a241f, 0x00302520, 0x00372a20, 0x003f3023, 0x00453224, 0x004d3729, 0x00543c2e, 0x00583e31, 0x00583f32, 0x005c4436, 0x006b5042, 0x0078574b, 0x00805c4e, 0x00885f4b, 0x00895c44, 0x008a593a, 0x008a5634, 0x0089532c, 0x00875128, 0x008a5328, 0x008a5328, 0x00895227, 0x00885224, 0x008a5223, 0x00895221, 0x008b501c, 0x008c4f18, 0x008b4f17, 0x008c5015, 0x008c5015, 0x008a4e14, 0x00884c11, 0x00874b10, 0x00874a10, 0x00854a0f, 0x00854a0f, 0x00884c12, 0x00884c12, 0x008a4c10, 0x008a4c10, 0x008c4e13, 0x008c4f14, 0x008f4f15, 0x00905017, 0x00905014, 0x00905011, 0x00905011, 0x00905112, 0x00905113, 0x00905113, 0x00905213, 0x00905113, 0x00905112, 0x00905013, 0x00905015, 0x00905016, 0x00905114, 0x00905212, 0x00925311, 0x00965110, 0x00985310, 0x009d5811, 0x009f5810, 0x00a15812, 0x00a25914, 0x00a05813, 0x00a05713, 0x00a05713, 0x00a05713, 0x009f5612, 0x009f5612, 0x009e5611, 0x009d5712, 0x009c5713, 0x00995412, 0x00985313, 0x00965211, 0x00935010, 0x00925010, 0x0094500f, 0x00945010, 0x00955412, 0x00955412, 0x00935211, 0x008e5013, 0x00884d14, 0x00804410, 0x00783e0e, 0x00743c0d, 0x00703b0c, 0x00703c0f, 0x006e3c11, 0x0064370d, 0x005b300b, 0x00502a09, 0x00482509, 0x003d1d06, 0x00331a08, 0x00291304, 0x00271407, 0x00221306, 0x001e1405, 0x001e1308, 0x001d1108, 0x001c110a, 0x001c120b, 0x001c130c, 0x001d140c, 0x001b130a, 0x00191209, 0x00181109, 0x00140d06, 0x00140d06, 0x00170e08, 0x001a1009, 0x001f140e, 0x001e1710, 0x0018140c, 0x0011110c, 0x0008100a, 0x0007110c, 0x00080f0b, 0x00081009, 0x00081009, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x0008120e, 0x0007110c, 0x0006100b, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040c03, 0x00040c06, 0x00040d07, 0x00050e08, 0x00050d08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00050f0c, 0x0004100c, 0x00040f0c, 0x00050f0a, 0x00151a16, 0x00242520, 0x00252621, 0x00282824, 0x002d2f2b, 0x00303230, 0x00303334, 0x00303436, 0x00313438, 0x00323539, 0x00323539, 0x00313236, 0x002e2f32, 0x002e2f32, 0x002b2c2f, 0x002a2a2a, 0x00282623, 0x002c231f, 0x00302520, 0x00372821, 0x003f3024, 0x00453224, 0x004d382b, 0x00584034, 0x005e4238, 0x005f4438, 0x00684f44, 0x0075584c, 0x007f6054, 0x00815d52, 0x00885f4b, 0x008a5d44, 0x008c5b3c, 0x008a5533, 0x008a542d, 0x00895429, 0x00895325, 0x00895324, 0x00895324, 0x008a5322, 0x008a5320, 0x008a5320, 0x008c511b, 0x008f5018, 0x00915318, 0x00905116, 0x00905113, 0x00905113, 0x008f5011, 0x00905010, 0x00915013, 0x00915013, 0x00915012, 0x00905011, 0x00904f10, 0x00915011, 0x00914f11, 0x00935013, 0x00945214, 0x00945116, 0x00975215, 0x00965414, 0x00965413, 0x00965411, 0x00965411, 0x00945410, 0x0092520f, 0x00925210, 0x00935210, 0x00935211, 0x00935313, 0x00935214, 0x00935214, 0x00935314, 0x00985817, 0x009b5a16, 0x009e5814, 0x009f5812, 0x00a05910, 0x00a1590f, 0x00a05810, 0x00a05811, 0x00a15812, 0x00a15812, 0x00a15813, 0x00a05713, 0x009f5712, 0x009f5612, 0x009d5511, 0x009c5611, 0x009c5513, 0x009a5311, 0x0096500f, 0x0094500c, 0x0094500c, 0x0094500e, 0x0094510f, 0x0096500f, 0x00955210, 0x00955312, 0x00925112, 0x008e5013, 0x00884c14, 0x00844814, 0x007b4110, 0x00763e0e, 0x00713d0c, 0x00703c0d, 0x006e3c10, 0x00673a0e, 0x005d340b, 0x00522b08, 0x004a2507, 0x00401d05, 0x00381c0c, 0x002f1508, 0x002c180b, 0x0029190c, 0x0026190c, 0x0026190f, 0x0023160d, 0x0023150f, 0x0020150e, 0x0020150e, 0x0022160f, 0x0022160f, 0x0020150c, 0x0020140c, 0x001e1309, 0x001e1309, 0x001e140a, 0x001f140b, 0x0020150c, 0x001f160c, 0x0019140b, 0x0013110c, 0x00080f08, 0x00051008, 0x00070f0a, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x0008120e, 0x0007110c, 0x0006100b, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c05, 0x00040c04, 0x00040c06, 0x00040d07, 0x00050e08, 0x00050d07, 0x00040c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050f0c, 0x00050f0c, 0x0004100c, 0x0005100c, 0x0005100d, 0x0007110e, 0x00101611, 0x001c1d18, 0x00272824, 0x002c2c28, 0x002c2c2b, 0x00303231, 0x00303335, 0x00303337, 0x00303338, 0x00303338, 0x00303438, 0x00323438, 0x002f3034, 0x002c2e31, 0x00282a2b, 0x00282827, 0x002e2c29, 0x002c2420, 0x00302420, 0x003a2b24, 0x00423228, 0x00453427, 0x00503c2f, 0x005c4438, 0x005c4238, 0x005f4439, 0x006c5246, 0x0074584c, 0x007d5d53, 0x00836054, 0x008c6450, 0x008b5e47, 0x008c5a3b, 0x008a5731, 0x008b552c, 0x008b5629, 0x008c5526, 0x008b5524, 0x008b5322, 0x008c5220, 0x008b521e, 0x008b521c, 0x008c5018, 0x00925318, 0x0097581c, 0x0097561a, 0x00945415, 0x00945211, 0x00945110, 0x00945211, 0x00965413, 0x00965413, 0x00965413, 0x00945110, 0x00945110, 0x00955211, 0x00955211, 0x00955211, 0x00955211, 0x00975013, 0x00985212, 0x00985414, 0x00995614, 0x00995611, 0x00995610, 0x00995610, 0x00995610, 0x00985512, 0x00985412, 0x00985412, 0x00985413, 0x00985414, 0x00985414, 0x00995515, 0x009a5713, 0x009c5813, 0x009f5812, 0x009f5811, 0x00a0580e, 0x00a35a0f, 0x00a25a10, 0x00a25a11, 0x00a15810, 0x00a15810, 0x00a15811, 0x00a15812, 0x009f5810, 0x009f5710, 0x009d5610, 0x009c5611, 0x009c5613, 0x00995311, 0x0096500f, 0x0095500b, 0x0094510c, 0x0094510d, 0x0094510d, 0x00975110, 0x00975310, 0x00955312, 0x00925212, 0x008e4f13, 0x00884c13, 0x00834811, 0x007f4514, 0x007b4310, 0x0076400f, 0x00723e0f, 0x006e3c0e, 0x00693b0d, 0x0060360c, 0x00542d08, 0x004c2605, 0x00401f04, 0x003a1d0b, 0x00311809, 0x002b1408, 0x00281609, 0x0024160a, 0x0023160b, 0x00201409, 0x0020120a, 0x001d1209, 0x001c1108, 0x001c1108, 0x001d1108, 0x001e1107, 0x00201409, 0x0022150b, 0x00201409, 0x001e1409, 0x001e1308, 0x001d1308, 0x001c1309, 0x001a140c, 0x0013120b, 0x000a0f08, 0x00050f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x0008120e, 0x0007110d, 0x0007110c, 0x0005100a, 0x00040f08, 0x00051008, 0x00051008, 0x00060f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050e06, 0x00060e06, 0x00050e06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x0005100a, 0x0005110b, 0x0005100c, 0x0004110c, 0x0006100e, 0x00091110, 0x000d130e, 0x0020221e, 0x002f302c, 0x00343433, 0x00343434, 0x002f3132, 0x002b2e30, 0x002b2e32, 0x002d3037, 0x00303238, 0x0032343b, 0x0034353a, 0x00323437, 0x002e3033, 0x002c2d30, 0x002b2b2c, 0x002a2827, 0x002c2320, 0x002e211f, 0x00372822, 0x00423229, 0x004c3a2e, 0x00544033, 0x005b4438, 0x005d4439, 0x0062483c, 0x00684d43, 0x0074574d, 0x0085645c, 0x0089645b, 0x008c6453, 0x008c624a, 0x008c5c3c, 0x008c5934, 0x008d582e, 0x008d572a, 0x008c5625, 0x008d5423, 0x00915523, 0x008f531f, 0x008e521c, 0x008f531a, 0x008f5218, 0x00905418, 0x0096561a, 0x0098561a, 0x00985616, 0x00995514, 0x00985413, 0x00975312, 0x00975312, 0x00985414, 0x00985414, 0x00985414, 0x00985414, 0x00965411, 0x00965510, 0x0098540e, 0x0098540e, 0x0098540e, 0x00985410, 0x009a5512, 0x009c5713, 0x009c5813, 0x009c5812, 0x009c5711, 0x009c5711, 0x009c5711, 0x009c5711, 0x009c5711, 0x009c5812, 0x009c5812, 0x009c5812, 0x009c5812, 0x00a05914, 0x00a35c17, 0x00a25c13, 0x00a35c14, 0x00a45a10, 0x00a45a10, 0x00a35b10, 0x00a15c10, 0x00a05b10, 0x00a05b10, 0x00a0580f, 0x009f570f, 0x009f5810, 0x009c5510, 0x009a530e, 0x009a530f, 0x009a5310, 0x0098530f, 0x0096500d, 0x0096510c, 0x0096500d, 0x0097520e, 0x0097520e, 0x0098530f, 0x00975311, 0x00955314, 0x00925212, 0x008c4d10, 0x00884c13, 0x00844912, 0x00804711, 0x007f4713, 0x007c4514, 0x00784413, 0x00713d10, 0x0069390c, 0x0064340c, 0x005a2d08, 0x004d2404, 0x00482408, 0x00381c07, 0x002f1704, 0x002a1406, 0x00241307, 0x00231509, 0x00211408, 0x00201409, 0x00201408, 0x001d1205, 0x001b1004, 0x001c1205, 0x001d1307, 0x001e1308, 0x001e1407, 0x001f1408, 0x001e1408, 0x001e1508, 0x001f150b, 0x0020160c, 0x00231710, 0x00201713, 0x0014130d, 0x000b0f08, 0x00071007, 0x00051008, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c07, 0x00080e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0008120e, 0x0007110d, 0x0007110d, 0x0007110c, 0x0005100a, 0x00040f08, 0x00051008, 0x00051008, 0x00060f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050e06, 0x00060e06, 0x00050e06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040d08, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x0005100a, 0x0005110b, 0x0004110b, 0x0004130c, 0x0006100b, 0x000a100d, 0x0010140f, 0x00272824, 0x00353633, 0x002e2e2e, 0x00272728, 0x002a2b2e, 0x002f3234, 0x00303237, 0x002c2f35, 0x00282a30, 0x0024272c, 0x00242529, 0x0028292c, 0x002a2c2f, 0x002e2f31, 0x002c2c2c, 0x002b2926, 0x002e2722, 0x00312522, 0x00372823, 0x00423229, 0x004c3a2f, 0x00544034, 0x005c4439, 0x005d453a, 0x0063493d, 0x006f5449, 0x007f6159, 0x008a6a62, 0x008a665d, 0x008e6656, 0x008f644d, 0x008f5f40, 0x00905c38, 0x00905c30, 0x00905a2c, 0x008f5828, 0x00905624, 0x00925523, 0x00915420, 0x0090541d, 0x0091551b, 0x0090541a, 0x0093561c, 0x0097571c, 0x00985819, 0x009a5718, 0x009b5815, 0x009a5714, 0x00995614, 0x00995614, 0x009a5615, 0x00995515, 0x009a5515, 0x009a5616, 0x00995614, 0x00995613, 0x00995610, 0x009b5711, 0x009c5711, 0x009c5613, 0x009c5714, 0x009c5814, 0x009c5814, 0x009c5812, 0x009c5712, 0x009c5711, 0x009c5711, 0x009c5711, 0x009c5711, 0x009d5813, 0x009d5813, 0x009d5813, 0x009c5812, 0x00a15a15, 0x00a35c17, 0x00a25c14, 0x00a35c14, 0x00a45a11, 0x00a45a10, 0x00a45c13, 0x00a45d13, 0x00a05b10, 0x009f580e, 0x009f570e, 0x009d540f, 0x009c5510, 0x009b540f, 0x009b5410, 0x009b540f, 0x00995310, 0x00985410, 0x0096500d, 0x0097520e, 0x0097520e, 0x0097520e, 0x0096500d, 0x0096500d, 0x0094500f, 0x00935011, 0x00904f0f, 0x008c4d10, 0x00884d13, 0x00844912, 0x00804711, 0x007e4510, 0x007b4310, 0x0075400e, 0x00713d0e, 0x006c3b0c, 0x0064340b, 0x005b2d08, 0x00502506, 0x00472207, 0x00371a04, 0x00301603, 0x002b1306, 0x00251207, 0x00231308, 0x00231308, 0x00231208, 0x00221208, 0x00201207, 0x00241509, 0x0025170c, 0x00221509, 0x00211509, 0x00201609, 0x0022170a, 0x0022170a, 0x0020180b, 0x0020170c, 0x0022160e, 0x00231710, 0x00201712, 0x0014130d, 0x000c0f08, 0x00071007, 0x00051007, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c07, 0x00080e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0008120e, 0x0007110d, 0x0007110d, 0x0007110c, 0x0005100a, 0x00040f08, 0x00070f08, 0x00070f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040f06, 0x00040f08, 0x00020e08, 0x0004100a, 0x00041009, 0x00030e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00041008, 0x00051109, 0x00051109, 0x00071009, 0x000a110b, 0x00141711, 0x002c2f29, 0x00313330, 0x002b2b2c, 0x002c2c2e, 0x002f3033, 0x00303335, 0x00303336, 0x002c3034, 0x002c2f33, 0x00282c30, 0x0027282a, 0x00282a2c, 0x002d2f30, 0x002e3031, 0x002b2b2b, 0x002c2926, 0x00302824, 0x00342822, 0x00392a24, 0x0043332b, 0x004c3a30, 0x00554335, 0x00584236, 0x0060473c, 0x00684e44, 0x00745b51, 0x0084665e, 0x00886862, 0x0088655f, 0x008d6457, 0x00906451, 0x00916045, 0x00905c3b, 0x00905a30, 0x008f582b, 0x008f5827, 0x00905624, 0x00915422, 0x00905420, 0x0091541f, 0x0092561d, 0x0092561c, 0x0095581e, 0x0098581c, 0x0099581a, 0x009e5a18, 0x009e5914, 0x009e5814, 0x009c5613, 0x009c5714, 0x009c5614, 0x009a5412, 0x009a5513, 0x009b5514, 0x009c5516, 0x009c5614, 0x009c5612, 0x009c5610, 0x009c5814, 0x009b5514, 0x00995412, 0x009c5715, 0x009c5814, 0x009c5814, 0x009c5814, 0x009c5814, 0x009d5814, 0x009d5814, 0x009e5915, 0x009d5814, 0x009e5915, 0x009d5814, 0x009f5a16, 0x00a05917, 0x00a15b17, 0x00a35c14, 0x00a35c15, 0x00a45a12, 0x00a45a12, 0x00a25a10, 0x00a45c12, 0x00a45c12, 0x00a35b10, 0x00a05810, 0x009f5712, 0x009e5613, 0x009c5412, 0x009b5411, 0x009c5512, 0x009c5512, 0x00995410, 0x009a5411, 0x009a5411, 0x009a5411, 0x00985410, 0x00985410, 0x00995412, 0x00965210, 0x00945112, 0x008d4d10, 0x008a4c10, 0x00874b11, 0x00834811, 0x00814611, 0x00804712, 0x007c430f, 0x00753f0d, 0x00713c0c, 0x006c3b0d, 0x0066380c, 0x005c300b, 0x00502607, 0x00472005, 0x003b1905, 0x00331604, 0x0030160a, 0x002d170c, 0x0029170d, 0x00261409, 0x0027140a, 0x0028150b, 0x0027170c, 0x0028180c, 0x0025140c, 0x0024150c, 0x0024150c, 0x0023160c, 0x0023160a, 0x0022160a, 0x00201508, 0x001e1408, 0x00190e04, 0x001c1008, 0x001d140e, 0x0015130c, 0x000d1009, 0x00080f07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c06, 0x00060c07, 0x00080e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0008120e, 0x0007110d, 0x0007110d, 0x0007110c, 0x0005100a, 0x00040f08, 0x00070f08, 0x00070f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040e06, 0x00040e06, 0x00040e06, 0x00040f07, 0x00040f08, 0x00020f09, 0x00020f08, 0x00020e08, 0x00020e08, 0x00020e08, 0x00020e08, 0x00030f09, 0x00030f09, 0x00040f08, 0x00040f08, 0x00051008, 0x00041008, 0x00041007, 0x00041007, 0x00071008, 0x000e150d, 0x001a1f18, 0x00222520, 0x00252724, 0x002e2e2e, 0x002d2d30, 0x002a2c2f, 0x00282c2e, 0x002b2e30, 0x00282b30, 0x00282d31, 0x00292d31, 0x0028292c, 0x0028292b, 0x002c2d2f, 0x002d2d30, 0x002b2b2a, 0x002d2a26, 0x00312823, 0x00342822, 0x003c2c28, 0x0047372e, 0x00503f34, 0x005a483b, 0x005a4438, 0x0060483d, 0x006c5248, 0x00755b51, 0x007f6159, 0x00866761, 0x008b6861, 0x008f675b, 0x00936756, 0x00906046, 0x008e5b3b, 0x008d5830, 0x008d5629, 0x008e5524, 0x008f5523, 0x00925523, 0x0090541f, 0x0091541f, 0x0092561d, 0x0092561c, 0x0095581e, 0x0098581c, 0x009b591b, 0x009e5a18, 0x009e5913, 0x009e5914, 0x009e5914, 0x009e5914, 0x009c5711, 0x009b5610, 0x009b5512, 0x009c5714, 0x009d5515, 0x009e5715, 0x009e5714, 0x009c5611, 0x009e5713, 0x009b5512, 0x00995410, 0x009c5714, 0x009c5813, 0x009c5812, 0x009c5812, 0x009c5813, 0x009e5915, 0x00a15c18, 0x00a05b18, 0x009e5915, 0x009f5a16, 0x009f5a14, 0x009e5914, 0x009f5813, 0x009f5813, 0x00a05911, 0x00a05a13, 0x00a35a11, 0x00a45a12, 0x00a0590f, 0x00a25a10, 0x00a45c12, 0x00a25a10, 0x009f5710, 0x009e5510, 0x009c5412, 0x009c5411, 0x009b5410, 0x009c5412, 0x009b5412, 0x00995410, 0x009a5511, 0x009c5713, 0x009c5713, 0x009a5511, 0x009a5411, 0x009b5514, 0x00985412, 0x00935112, 0x008e4e10, 0x0087490d, 0x0085490f, 0x00834810, 0x0080460f, 0x00804610, 0x007c4510, 0x00753f0d, 0x00713c0c, 0x006c3a0c, 0x00643409, 0x00592c08, 0x004f2506, 0x004a2409, 0x003e1d09, 0x00361907, 0x002f1509, 0x002c160c, 0x0029160c, 0x00261409, 0x002a180d, 0x0029180d, 0x0028170c, 0x0029170d, 0x0028170e, 0x0028180f, 0x00271910, 0x0022150b, 0x00201308, 0x001f1407, 0x001e1306, 0x001e1408, 0x001b0f04, 0x001b0f06, 0x001a100b, 0x00121009, 0x000a0c06, 0x00080f07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c07, 0x00080e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0007110c, 0x0007110c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00071009, 0x000e150f, 0x00181f17, 0x001f241c, 0x001f211e, 0x00272928, 0x00262828, 0x00242527, 0x00242428, 0x00242729, 0x002a2f33, 0x00282d30, 0x00262c2f, 0x002c3031, 0x002e302f, 0x00302f31, 0x002e2c2c, 0x002d2c2a, 0x002d2a26, 0x002d2820, 0x00342824, 0x003c2d28, 0x00493830, 0x00564438, 0x00574438, 0x00594238, 0x0061493f, 0x006c544b, 0x00735851, 0x007c5e58, 0x00856560, 0x0088655f, 0x008e675c, 0x008d6353, 0x008d5d45, 0x008c593a, 0x008d5730, 0x008d5528, 0x00905525, 0x008f5422, 0x00915321, 0x00945623, 0x00945620, 0x0094571d, 0x0094571d, 0x0096571d, 0x0098581b, 0x009c5819, 0x009d5817, 0x009d5814, 0x009d5813, 0x00a05b15, 0x00a05b15, 0x009d5813, 0x009c5711, 0x009d5612, 0x009f5715, 0x009e5716, 0x009f5816, 0x009e5714, 0x009d5611, 0x009c5611, 0x009c5611, 0x009d5612, 0x009d5614, 0x009d5712, 0x009c5812, 0x009c5712, 0x009c5614, 0x009c5614, 0x009a5714, 0x009a5814, 0x009d5a15, 0x009d5a15, 0x009e5914, 0x009f5a14, 0x009d5811, 0x009c5710, 0x00a05910, 0x00a05912, 0x00a05810, 0x00a05810, 0x00a15a10, 0x00a45c12, 0x00a35b12, 0x00a25a11, 0x009f5710, 0x009f5710, 0x009d5611, 0x009c5510, 0x009c5511, 0x009c5512, 0x009c5611, 0x009b5610, 0x009b5610, 0x009c5613, 0x009c5613, 0x009c5614, 0x00985411, 0x00985310, 0x00945111, 0x00935011, 0x008e4f0f, 0x008b4e10, 0x0085490e, 0x0084480f, 0x0080450f, 0x007f4610, 0x007d4511, 0x0078400f, 0x00723d0d, 0x006c390c, 0x00653409, 0x005d300c, 0x004f2407, 0x00452005, 0x003b1a07, 0x00341706, 0x002e150a, 0x002c160d, 0x0029160a, 0x00261408, 0x00261408, 0x00261408, 0x00271509, 0x0026150c, 0x0026160c, 0x0024170f, 0x0023160d, 0x0020140a, 0x001d1308, 0x001c1005, 0x001c1204, 0x001f1609, 0x0020140a, 0x001f120a, 0x001c130c, 0x0013100a, 0x000b0d07, 0x00091009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0c, 0x00060d0b, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d07, 0x00060e07, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0007110c, 0x0007110c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100b, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00040f08, 0x00051008, 0x00071008, 0x000e150e, 0x00181d16, 0x0020241d, 0x0020221e, 0x00212421, 0x00282a2a, 0x002e3031, 0x002f3033, 0x002e2f32, 0x002a2d31, 0x00252a2e, 0x002a2f32, 0x00353738, 0x00363535, 0x00353134, 0x00332e30, 0x00302c2b, 0x002c2823, 0x002d2720, 0x00342824, 0x003c2c27, 0x00493830, 0x00514035, 0x00544034, 0x005a4338, 0x00614940, 0x006c544b, 0x00745952, 0x007b5e58, 0x0084645f, 0x0088645e, 0x00906860, 0x008c6153, 0x008b5b45, 0x008a573a, 0x008c5530, 0x008d5427, 0x00905625, 0x00945827, 0x00965826, 0x00975824, 0x00975823, 0x00965820, 0x0096581f, 0x0095571d, 0x0098561a, 0x00995717, 0x009b5814, 0x009c5812, 0x009c5812, 0x009b5610, 0x009b5610, 0x009a5510, 0x009b5610, 0x009c5510, 0x009c5612, 0x009e5513, 0x009e5513, 0x009e5511, 0x009c530d, 0x009e5610, 0x009e5610, 0x00a15812, 0x00a05813, 0x00a05812, 0x009e5713, 0x009d5712, 0x009c5612, 0x009c5612, 0x009c5613, 0x009c5712, 0x009c5814, 0x009d5812, 0x009e5813, 0x00a05913, 0x00a35c16, 0x00a76017, 0x00a75f16, 0x00a75e18, 0x00a75c15, 0x00a75c15, 0x00a55d14, 0x00a55d14, 0x00a35b12, 0x00a25a11, 0x009f570f, 0x009f570f, 0x009d5610, 0x009c5610, 0x009c5611, 0x009c5611, 0x009c5611, 0x009b5610, 0x009c5711, 0x009c5613, 0x009c5613, 0x009c5614, 0x00985411, 0x00985310, 0x00955111, 0x00915010, 0x008e500f, 0x00884b0d, 0x00874c10, 0x00864a10, 0x00834810, 0x00804611, 0x00804815, 0x007c4414, 0x00743f10, 0x006f3c0f, 0x0068380d, 0x005c2f0b, 0x004d2306, 0x00441e05, 0x003b1b08, 0x00331707, 0x002c140a, 0x002a160c, 0x00241407, 0x00211104, 0x00241508, 0x00241408, 0x00231407, 0x00201309, 0x001f1308, 0x001d130a, 0x001d140a, 0x001c1308, 0x001d1409, 0x001e1508, 0x001f1608, 0x001f1509, 0x0020150b, 0x0022160d, 0x00201610, 0x0017140d, 0x000e110b, 0x00091009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0c, 0x00060d0b, 0x00040c09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d07, 0x00060e08, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006100b, 0x0006100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070e0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00050f0a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00051008, 0x00040f08, 0x00040f08, 0x00051008, 0x00070f08, 0x00070f08, 0x00070e08, 0x000e140c, 0x00181e17, 0x0021251e, 0x00252724, 0x002b2c2a, 0x002c2e2d, 0x002c2e2f, 0x002e3030, 0x00303134, 0x00333437, 0x0034383a, 0x00333437, 0x00323032, 0x00322e30, 0x00332c2e, 0x00342c2e, 0x00322b29, 0x00302924, 0x00332a23, 0x003a2e28, 0x0040322b, 0x00493830, 0x004e3c33, 0x00523f35, 0x005a433a, 0x00644c44, 0x006d544c, 0x00745c53, 0x00795d56, 0x0082635c, 0x00886660, 0x008e665f, 0x008a5f53, 0x008b5b47, 0x008b583c, 0x008c5531, 0x008f5728, 0x00915826, 0x00945828, 0x00975826, 0x00975824, 0x00975823, 0x00995c22, 0x009a5c23, 0x009b5c22, 0x009d5c1f, 0x009e5c1b, 0x00a05c17, 0x00a15b14, 0x00a15b14, 0x009f5812, 0x009f5812, 0x00a05912, 0x00a05912, 0x00a45b14, 0x00a45c17, 0x00a65b17, 0x00a65c17, 0x00a65c15, 0x00a35911, 0x00a35910, 0x00a35911, 0x00a15710, 0x009e540d, 0x009d540c, 0x009d550f, 0x009d540d, 0x009e560f, 0x009f5811, 0x009f5814, 0x00a05914, 0x00a05a15, 0x00a35c16, 0x00a45c16, 0x00a86017, 0x00a86018, 0x00a86016, 0x00a85f15, 0x00a85e16, 0x00a85c14, 0x00a85c14, 0x00a75d14, 0x00a55c12, 0x00a35911, 0x00a35911, 0x00a35b12, 0x00a05810, 0x009e5810, 0x009c5610, 0x009c550f, 0x009c5510, 0x009c5611, 0x009c5711, 0x009c5712, 0x009e5915, 0x009c5814, 0x009c5614, 0x009a5413, 0x00985213, 0x00955111, 0x00915010, 0x008e4f0f, 0x00884b0d, 0x00884c10, 0x00864a10, 0x00834710, 0x00804511, 0x00804714, 0x00804718, 0x00774012, 0x00703b0d, 0x0068360b, 0x0060330e, 0x00502609, 0x00441f05, 0x00391906, 0x00301605, 0x002c1409, 0x0028130a, 0x00251408, 0x00261509, 0x0028180b, 0x00241408, 0x00231508, 0x00201409, 0x00191007, 0x00150d05, 0x00150e06, 0x00181007, 0x00191208, 0x001b1407, 0x001d1507, 0x001c1307, 0x0020140a, 0x0020120b, 0x00201813, 0x00191710, 0x000c0f08, 0x00080e08, 0x00060e09, 0x00050e08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0c, 0x00060d0b, 0x00040c09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d07, 0x00060e08, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006100b, 0x0006100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e07, 0x00030d06, 0x00040f08, 0x00051008, 0x00070f08, 0x00081009, 0x00070e08, 0x000d140c, 0x00181e17, 0x00242821, 0x002d2e2b, 0x0030302f, 0x00303231, 0x002f3032, 0x00303133, 0x00313334, 0x00323437, 0x00333337, 0x00313034, 0x00322e30, 0x00362f31, 0x00382e31, 0x0034282b, 0x00342828, 0x00352b27, 0x00362c24, 0x00392f28, 0x003f322a, 0x00483930, 0x004f3e34, 0x00544338, 0x005c473e, 0x00665047, 0x0070584f, 0x00755d54, 0x00795d57, 0x0080625c, 0x00886661, 0x008e6660, 0x00895f54, 0x008c5c49, 0x008e5b42, 0x008f5834, 0x0091592c, 0x00925927, 0x00945825, 0x00955624, 0x00955623, 0x00955721, 0x00975920, 0x00995c22, 0x009b5c22, 0x009d5c20, 0x009e5c1b, 0x00a15b17, 0x00a25c14, 0x00a25c14, 0x00a45e15, 0x00a45d14, 0x00a35d14, 0x00a45c14, 0x00a45b14, 0x00a45b13, 0x00a85f17, 0x00a96017, 0x00aa5e14, 0x00a75c11, 0x00a95e14, 0x00aa5e15, 0x00aa5e15, 0x00a85c13, 0x00a45b10, 0x00a45b10, 0x00a55c11, 0x00a75d13, 0x00a65d14, 0x00a55c18, 0x00a55d17, 0x00a55d17, 0x00a65d15, 0x00a85e16, 0x00a96017, 0x00a96016, 0x00a96015, 0x00ac6017, 0x00ac6018, 0x00ab6016, 0x00ab6014, 0x00a95d14, 0x00a65b12, 0x00a45a12, 0x00a35b12, 0x00a35b12, 0x00a15910, 0x009e5710, 0x009f5811, 0x00a05913, 0x009f5813, 0x009f5814, 0x009d5813, 0x009d5813, 0x009e5915, 0x009d5814, 0x009c5715, 0x009b5614, 0x00995414, 0x00975312, 0x00915010, 0x008d4f0f, 0x00884c0e, 0x00874c10, 0x0085490f, 0x0083470f, 0x00804510, 0x00804714, 0x007f4617, 0x00794214, 0x00703c0e, 0x0068360b, 0x0060330f, 0x0052280b, 0x00452007, 0x003a1a08, 0x00321706, 0x002c1409, 0x00281309, 0x00251408, 0x00251709, 0x00261609, 0x0026180c, 0x00231709, 0x001e1409, 0x00171005, 0x00130d04, 0x00100c03, 0x00130d04, 0x00181208, 0x00191408, 0x001a1405, 0x001b1306, 0x001c1107, 0x00180c04, 0x001b140d, 0x00161710, 0x000d110a, 0x00080e08, 0x00060e08, 0x00040d07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0c, 0x00060d0b, 0x00040c09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d07, 0x00060e08, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e07, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c08, 0x00080c08, 0x00080c07, 0x00080c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040a04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x000a120a, 0x00181f18, 0x00282a24, 0x0032302d, 0x00343433, 0x00343534, 0x00353738, 0x00323435, 0x00383839, 0x0038383a, 0x00373538, 0x00312f31, 0x00342c30, 0x00383033, 0x002e2528, 0x002e2426, 0x00382c2d, 0x00372d29, 0x00332b23, 0x00382f28, 0x0040332d, 0x00493b34, 0x0053433b, 0x005c4b42, 0x005f4942, 0x00675048, 0x006c554d, 0x00755c55, 0x007c5f58, 0x0082645e, 0x00856560, 0x0089675f, 0x008a6457, 0x00895e48, 0x008c5c41, 0x008f5835, 0x00935a30, 0x00935929, 0x00935824, 0x00945524, 0x00925420, 0x00975924, 0x00985a21, 0x00985b21, 0x00995b20, 0x009d5b1e, 0x009f5c1c, 0x009f5a14, 0x00a05b10, 0x00a05b10, 0x00a25a10, 0x00a1590f, 0x00a25a11, 0x00a15910, 0x00a35910, 0x00a65c13, 0x00a65c12, 0x00a85e13, 0x00a95e13, 0x00aa5f12, 0x00aa5f14, 0x00aa5f14, 0x00a95e13, 0x00a95e13, 0x00a96014, 0x00a85f13, 0x00a85e14, 0x00a75d14, 0x00a45c13, 0x00a45c14, 0x00a45c14, 0x00a85f17, 0x00a85e16, 0x00a95d14, 0x00ac6018, 0x00a95d14, 0x00ab6017, 0x00ab6015, 0x00ac6018, 0x00ac5f14, 0x00ab5e14, 0x00ab5e14, 0x00a95e13, 0x00a45b11, 0x00a45c12, 0x00a35b10, 0x00a1590f, 0x00a25a11, 0x00a25a11, 0x00a15a13, 0x00a05a13, 0x00a05912, 0x009f5813, 0x009f5813, 0x00a05814, 0x009f5814, 0x009c5514, 0x00995210, 0x00965010, 0x00945010, 0x00915010, 0x008f5010, 0x008c4f10, 0x00864b0c, 0x0084490e, 0x0082460e, 0x00814610, 0x00814813, 0x007f4714, 0x007a4312, 0x00703c0c, 0x00673509, 0x005c300b, 0x00512709, 0x00462008, 0x003a1a08, 0x002f1404, 0x002b1208, 0x002a170d, 0x00241507, 0x00231508, 0x00201409, 0x001c1408, 0x001c1408, 0x001b1408, 0x001a140a, 0x00181308, 0x00161106, 0x00131004, 0x00120f04, 0x00141005, 0x00151105, 0x00181106, 0x001b1108, 0x001b110a, 0x0018120b, 0x000e1008, 0x00090e07, 0x00060e06, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00060e09, 0x00060d0a, 0x00060e09, 0x00060e08, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e07, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c08, 0x00080c08, 0x00080c07, 0x00080c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040a04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00081109, 0x001d231c, 0x002d2d28, 0x0032302e, 0x00353434, 0x00343636, 0x00353738, 0x00323435, 0x0038383a, 0x0038383a, 0x00383638, 0x00383437, 0x00363034, 0x00342e30, 0x00342e31, 0x00362f30, 0x00342d2c, 0x00322925, 0x00322c25, 0x00383029, 0x003a2f2a, 0x00483b36, 0x0056473f, 0x0055443c, 0x005c4840, 0x00665149, 0x006f5850, 0x007b615b, 0x007f635c, 0x0081645d, 0x00856560, 0x0089665d, 0x008a6457, 0x00895f49, 0x008c5c42, 0x00905a38, 0x00925832, 0x0093582c, 0x00935726, 0x00955725, 0x00985925, 0x00985b25, 0x00985b22, 0x00985b21, 0x00995b20, 0x009d5c1f, 0x009f5c1c, 0x009f5914, 0x00a05a0f, 0x00a05a0f, 0x00a0580e, 0x00a1590f, 0x00a15810, 0x00a15810, 0x00a35910, 0x00a65c13, 0x00a75d14, 0x00a85e14, 0x00a95e13, 0x00aa5f14, 0x00aa5f14, 0x00aa5f14, 0x00a95e13, 0x00a95e13, 0x00a96014, 0x00a85f13, 0x00a85e14, 0x00a75d14, 0x00a45c12, 0x00a45c12, 0x00a35b11, 0x00a65c14, 0x00a75c15, 0x00a75d14, 0x00a65c13, 0x00a75c13, 0x00aa5e15, 0x00ac6016, 0x00ac6018, 0x00ac5f14, 0x00ab5e14, 0x00ac5f14, 0x00a95e13, 0x00a55c12, 0x00a25c12, 0x00a25b10, 0x00a25a10, 0x00a25a10, 0x00a25a11, 0x00a15a12, 0x00a05a13, 0x00a05a13, 0x00a05814, 0x00a05814, 0x00a05814, 0x00a05814, 0x009c5514, 0x009a5311, 0x00965011, 0x00945110, 0x00915010, 0x008f5010, 0x00894c0d, 0x00874c0e, 0x00864a0e, 0x0084480e, 0x0081470e, 0x007f460f, 0x007e4611, 0x007a4310, 0x00703c0b, 0x00673509, 0x005c300b, 0x00512709, 0x00452008, 0x00381908, 0x00321708, 0x002c140b, 0x0027140a, 0x00241508, 0x00221409, 0x001f150b, 0x001c140a, 0x001a140a, 0x00191407, 0x001a140a, 0x00181308, 0x00181207, 0x00181308, 0x00181308, 0x00181309, 0x00181308, 0x00171208, 0x00181109, 0x001a110c, 0x0016130c, 0x000d1209, 0x00091008, 0x00060e06, 0x00070e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060d0a, 0x00060d0a, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e07, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c07, 0x00080c07, 0x00080c05, 0x00080c04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00060f08, 0x00081008, 0x001b201a, 0x002e2e28, 0x0033302d, 0x00353434, 0x00343535, 0x00313436, 0x00303334, 0x00363839, 0x0037383a, 0x00323134, 0x00302f32, 0x002f2b30, 0x002f2a2f, 0x00353134, 0x00332f30, 0x00312d2b, 0x00322d28, 0x00312c25, 0x0038312c, 0x003f3530, 0x004e403c, 0x00574944, 0x0052433c, 0x00604d48, 0x0069544e, 0x00705953, 0x007c635e, 0x007e625c, 0x00846660, 0x00866660, 0x0089675e, 0x008a6558, 0x008c614d, 0x008c5d44, 0x0090583a, 0x00945a35, 0x0094592e, 0x00935828, 0x00925521, 0x00975823, 0x00985b24, 0x00985b21, 0x00985c20, 0x00995b1f, 0x009d5c1f, 0x009f5c1c, 0x009e5914, 0x009c570c, 0x009d570c, 0x009f580d, 0x00a0590f, 0x00a05810, 0x00a05810, 0x00a55b13, 0x00a55b14, 0x00a75b14, 0x00a85c15, 0x00a85c14, 0x00a95d14, 0x00aa5e15, 0x00aa5f14, 0x00a75c11, 0x00a75c11, 0x00a75c11, 0x00a85c12, 0x00a85d13, 0x00a65c13, 0x00a45a10, 0x00a35b10, 0x00a35b10, 0x00a25a11, 0x00a45c14, 0x00a85e14, 0x00a55c12, 0x00a55c12, 0x00a55c12, 0x00ac6016, 0x00ac6018, 0x00ad6016, 0x00ad6016, 0x00ac5f14, 0x00ac6016, 0x00a75d14, 0x00a25c11, 0x00a25a0f, 0x00a25a0e, 0x00a35b10, 0x00a35b10, 0x00a35b12, 0x00a35b12, 0x00a25913, 0x00a15812, 0x00a05912, 0x009f5811, 0x009d5711, 0x009c5412, 0x00995411, 0x00985210, 0x00965211, 0x00945313, 0x00905110, 0x00894c0d, 0x00874c0e, 0x00864a0e, 0x0084480e, 0x0081470c, 0x0080480f, 0x00804912, 0x007a4410, 0x00703c0b, 0x006c3a0d, 0x0062340f, 0x004f2406, 0x00462007, 0x00391a07, 0x002f1404, 0x002c160b, 0x00241108, 0x00201208, 0x001d1006, 0x001b100a, 0x001c120c, 0x00191408, 0x00191407, 0x001a140a, 0x0019140b, 0x00151005, 0x00151005, 0x00171006, 0x00181108, 0x00181208, 0x00181108, 0x0018100a, 0x001a120c, 0x0016140e, 0x000e110b, 0x000a0f08, 0x00070e06, 0x00070e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060d0a, 0x00060d0a, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e07, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c05, 0x00080c05, 0x00080c04, 0x00080c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00060f08, 0x00081008, 0x0010140d, 0x00282824, 0x0033322f, 0x00353434, 0x00343536, 0x00303436, 0x002f3234, 0x002e3134, 0x002d3032, 0x00303134, 0x002d2e31, 0x00333337, 0x00343337, 0x00343335, 0x00313131, 0x0031302e, 0x0035322d, 0x00312d27, 0x0038322c, 0x00443a36, 0x004a3c39, 0x0050423e, 0x00544642, 0x0064514e, 0x0069554f, 0x00715a54, 0x00785f5b, 0x007c605a, 0x00846660, 0x00876761, 0x0088655d, 0x00886357, 0x008c614e, 0x008d5e45, 0x0090593d, 0x00915636, 0x0090552c, 0x00925628, 0x00945723, 0x00985924, 0x00985b24, 0x00985b21, 0x00985c20, 0x00995b1f, 0x009c5b1e, 0x009c5a1a, 0x009c5813, 0x009c570e, 0x009c570e, 0x009e560e, 0x00a1590f, 0x00a35b12, 0x00a35b12, 0x00a55b14, 0x00a55b14, 0x00a75b14, 0x00a95d16, 0x00a85c15, 0x00aa5e16, 0x00ac5f16, 0x00ab5e14, 0x00a85b11, 0x00a85b11, 0x00a85c11, 0x00a85d12, 0x00a85e14, 0x00a65c13, 0x00a45a10, 0x00a45b10, 0x00a55c12, 0x00a55b14, 0x00a65c14, 0x00a85e14, 0x00a85e14, 0x00a85f15, 0x00aa6017, 0x00ab6118, 0x00ac6118, 0x00ad6016, 0x00ad6016, 0x00ad6016, 0x00ac6016, 0x00a85f15, 0x00a45e14, 0x00a45d11, 0x00a45d11, 0x00a45c11, 0x00a35b10, 0x00a35b11, 0x00a35b12, 0x00a25a11, 0x00a15812, 0x00a05912, 0x00a05912, 0x009d5711, 0x009c5412, 0x00995410, 0x00985411, 0x00975312, 0x00945314, 0x00905111, 0x008a4d0e, 0x00874c0f, 0x0085490f, 0x0084480e, 0x0082480d, 0x0081480e, 0x007f4810, 0x007a440e, 0x00713d0a, 0x006a380a, 0x0062340f, 0x00522808, 0x00452006, 0x00391906, 0x00321707, 0x002c160b, 0x00241208, 0x00201208, 0x001c0f07, 0x00190e08, 0x00180e09, 0x00181008, 0x001a140a, 0x0019140b, 0x001b150c, 0x00171108, 0x00151005, 0x00160f06, 0x00181008, 0x00181008, 0x00161008, 0x0018110a, 0x0019110c, 0x0016140e, 0x000f120c, 0x000a0f08, 0x00080f07, 0x00080f07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e0a, 0x00060d0a, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050c07, 0x00060c07, 0x00060d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00050d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040d07, 0x00070e08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060d08, 0x00060d08, 0x00060c07, 0x00040c05, 0x00050c06, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00051009, 0x00051008, 0x00081008, 0x000a1108, 0x000c0f0a, 0x00202020, 0x00383639, 0x003d3b40, 0x00393b40, 0x00323739, 0x002f3234, 0x002c3032, 0x002c2f31, 0x002e3134, 0x00303335, 0x00313437, 0x00313436, 0x00313334, 0x00303332, 0x00313330, 0x0034342e, 0x0034312b, 0x0038312d, 0x00403733, 0x00493e3a, 0x00514340, 0x005c4e4a, 0x0063504c, 0x00685450, 0x00705a54, 0x00745b56, 0x007c5f5c, 0x00846660, 0x0084655e, 0x0087645c, 0x00886357, 0x008c614f, 0x008d5e46, 0x0090593c, 0x00905736, 0x0090562c, 0x0093582a, 0x00975a25, 0x00985b24, 0x00985a22, 0x00995922, 0x0098591f, 0x009a591e, 0x009c5a1b, 0x009c5817, 0x009c5713, 0x009e5710, 0x009f5710, 0x00a15810, 0x00a45b11, 0x00a75d14, 0x00a75d14, 0x00a55a11, 0x00a55a11, 0x00a85c14, 0x00a95d15, 0x00ac6018, 0x00ab6016, 0x00ac5f14, 0x00ad5f15, 0x00ac5e14, 0x00ac5e14, 0x00ab5f14, 0x00aa5f14, 0x00a85d14, 0x00a75c13, 0x00a75c13, 0x00a55a10, 0x00a85c14, 0x00a95e17, 0x00a95e17, 0x00a85e15, 0x00a85f16, 0x00ab6018, 0x00ac611a, 0x00ac6218, 0x00ac6118, 0x00ac5f14, 0x00ad6014, 0x00ad6014, 0x00ad6115, 0x00ac5f14, 0x00aa5e14, 0x00a85f14, 0x00a85f13, 0x00a75e13, 0x00a75d12, 0x00a65c14, 0x00a45a12, 0x00a35912, 0x00a25a14, 0x00a25a14, 0x00a15913, 0x009e5810, 0x009a540f, 0x00995410, 0x00985411, 0x00955210, 0x00925313, 0x00905112, 0x008a4d10, 0x00874a10, 0x00864910, 0x00854810, 0x00874c13, 0x00824810, 0x007e4610, 0x0079430f, 0x006f3b08, 0x006a3808, 0x0063330c, 0x00552b0b, 0x00462006, 0x003a1b06, 0x00341806, 0x002c1508, 0x00251408, 0x00211409, 0x0020140b, 0x00180c07, 0x00170d08, 0x00150d07, 0x00150f08, 0x0019120b, 0x001c140c, 0x001b140b, 0x00191209, 0x00181108, 0x00181008, 0x00181008, 0x00161007, 0x00160f08, 0x0019130c, 0x00181610, 0x0010100b, 0x000a0e07, 0x00070e06, 0x00080d06, 0x00080e08, 0x00060d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d08, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00050d07, 0x00060d08, 0x00060d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00050c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x0005100a, 0x00051008, 0x00050f07, 0x00091008, 0x00181b16, 0x00303030, 0x003c3b40, 0x0038383e, 0x002e3034, 0x00252a2c, 0x0025282b, 0x00292c2f, 0x00292c2f, 0x002b2e30, 0x002f3234, 0x00303436, 0x00303335, 0x00303234, 0x00313433, 0x00333432, 0x00363730, 0x00383530, 0x003b3430, 0x003e3432, 0x00463a38, 0x00504240, 0x005e504c, 0x0064524e, 0x006b5852, 0x00705b55, 0x0079605c, 0x00806460, 0x00846661, 0x0085665e, 0x0088665e, 0x008b6559, 0x008f6450, 0x008f6049, 0x00905b3e, 0x00905837, 0x00915930, 0x00955c2d, 0x00975c28, 0x00985c24, 0x009a5a24, 0x009a5a24, 0x00995a21, 0x009c5c20, 0x009f5b1d, 0x009f5a19, 0x00a05916, 0x00a15814, 0x00a15812, 0x00a45a11, 0x00a65c12, 0x00a45b0e, 0x00a45b0d, 0x00a55a0e, 0x00a55a0e, 0x00a85c11, 0x00aa5f14, 0x00ad6018, 0x00ad6016, 0x00ad6014, 0x00af6116, 0x00ae6116, 0x00ae6116, 0x00ad6116, 0x00ac6014, 0x00ab6014, 0x00ab6015, 0x00ab6015, 0x00a95e14, 0x00ab6017, 0x00a95d14, 0x00a85c14, 0x00a85f15, 0x00ab6118, 0x00ac6219, 0x00b0651c, 0x00b0651c, 0x00af651a, 0x00af6418, 0x00af6417, 0x00af6315, 0x00af6315, 0x00af6315, 0x00af6215, 0x00ae6318, 0x00ac6318, 0x00ab6116, 0x00ab6015, 0x00ab6018, 0x00a85f17, 0x00a65c15, 0x00a45c16, 0x00a45c16, 0x00a35b14, 0x00a05811, 0x009d5812, 0x009c5814, 0x009a5714, 0x00965412, 0x00935413, 0x008f5214, 0x008c4e13, 0x00894c12, 0x00874911, 0x00884914, 0x00874a13, 0x00834913, 0x00804814, 0x007b4412, 0x00703c0a, 0x006c3809, 0x0063330c, 0x00552b0a, 0x00482207, 0x003c1c08, 0x00341805, 0x002b1508, 0x00251408, 0x00221408, 0x0020160a, 0x001e120a, 0x00191008, 0x00150e08, 0x00140d06, 0x00160e08, 0x001a120a, 0x001c140c, 0x001c140c, 0x001a130a, 0x00181008, 0x00171007, 0x00160f07, 0x00160f07, 0x00171109, 0x0016140e, 0x0010100b, 0x000a0d07, 0x00070e06, 0x00080d06, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00050c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060d08, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x0004100a, 0x00041008, 0x00030c04, 0x00091007, 0x00262a23, 0x003a3b38, 0x00343435, 0x0027262b, 0x001b1c1f, 0x00181d1e, 0x00202526, 0x002a2f30, 0x00292e2f, 0x00282b2d, 0x002e3134, 0x00303336, 0x00303236, 0x00323336, 0x00323434, 0x00343735, 0x00333330, 0x00302f2a, 0x0036312e, 0x00433b38, 0x004a3e3c, 0x00504341, 0x005e504e, 0x0064534e, 0x006b5852, 0x00745e58, 0x007d6461, 0x007f625f, 0x00826460, 0x0084655d, 0x0088655c, 0x008c655b, 0x00906454, 0x0090624c, 0x00915d40, 0x00905a38, 0x00935c32, 0x00945d2e, 0x00965c26, 0x00985c24, 0x009c5c26, 0x009d5d26, 0x009c5c24, 0x009d5d22, 0x00a05d1f, 0x00a25e1c, 0x00a55e1a, 0x00a65e18, 0x00a86017, 0x00ab6117, 0x00ac6417, 0x00ad6416, 0x00ad6416, 0x00ac6114, 0x00ac6114, 0x00ac6214, 0x00b06518, 0x00b06416, 0x00b06416, 0x00ae6114, 0x00ae6114, 0x00ac5f12, 0x00aa5c10, 0x00aa5e10, 0x00ab5f11, 0x00aa5e12, 0x00a95d11, 0x00a85d11, 0x00a75c10, 0x00aa6014, 0x00ac6218, 0x00ae641a, 0x00b1691e, 0x00b36b20, 0x00b46c21, 0x00b66e23, 0x00b46c21, 0x00b36a1e, 0x00b1681b, 0x00b36a1b, 0x00b36a1a, 0x00b36a19, 0x00b56a1b, 0x00b4691b, 0x00b2681a, 0x00ae6418, 0x00ab6116, 0x00aa6014, 0x00a95d14, 0x00a65b13, 0x00a55a12, 0x00a45c14, 0x00a45c14, 0x00a25a13, 0x00a05811, 0x009e5913, 0x009f5a14, 0x009c5814, 0x00965413, 0x00945414, 0x00905314, 0x008f5114, 0x008c4f14, 0x008a4c14, 0x00884a14, 0x00864913, 0x00824812, 0x00824a18, 0x00804817, 0x0074400e, 0x006c380a, 0x0064340b, 0x00552908, 0x00452003, 0x003c1b05, 0x00331704, 0x00291405, 0x00241406, 0x00231708, 0x0021170b, 0x001f140b, 0x001e140c, 0x001b130c, 0x0018110a, 0x00160e07, 0x00170f06, 0x00191209, 0x001c140c, 0x001e150d, 0x001e150d, 0x001c140c, 0x001b140c, 0x001c150d, 0x001c150e, 0x0019180f, 0x0012120c, 0x000b0d07, 0x00080d06, 0x00080d06, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00050c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060d08, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x0004100a, 0x00041008, 0x00040e08, 0x00151c15, 0x0030342c, 0x00282b26, 0x001a1c19, 0x00151818, 0x00141818, 0x00181c1c, 0x00212625, 0x00252a2a, 0x00292f2f, 0x002e3134, 0x00313539, 0x0033363c, 0x0034373c, 0x0036383b, 0x00343638, 0x00343635, 0x00323331, 0x00323230, 0x00383434, 0x003e3836, 0x00443a39, 0x00514644, 0x00625453, 0x00615350, 0x00685650, 0x00715e58, 0x0079605e, 0x007e6060, 0x00836460, 0x0085655e, 0x0087645e, 0x008b655b, 0x00906454, 0x0090614c, 0x00905f40, 0x00905c3a, 0x00915d32, 0x00935e2e, 0x00945e26, 0x009a5e26, 0x009d5d26, 0x009e5e27, 0x009e5e26, 0x009e5e22, 0x00a15d20, 0x00a35e1c, 0x00a55e18, 0x00a86016, 0x00aa6218, 0x00ad6418, 0x00ae6415, 0x00ad6414, 0x00ac6414, 0x00ae6314, 0x00ad6314, 0x00b36919, 0x00b66c1d, 0x00b56b1b, 0x00b56b1b, 0x00b56a1b, 0x00b5691a, 0x00b66b1c, 0x00b26617, 0x00b06516, 0x00b36818, 0x00b36818, 0x00b3681a, 0x00b3681a, 0x00b36b1c, 0x00b56d1f, 0x00b66e21, 0x00b46c1f, 0x00b36c20, 0x00b36d20, 0x00b56f21, 0x00b56f21, 0x00b26c1d, 0x00ad6717, 0x00b16a19, 0x00b46c1b, 0x00b46d1a, 0x00b46c1a, 0x00b66c1c, 0x00b46c1b, 0x00b46a1b, 0x00b06718, 0x00ac6418, 0x00ab6015, 0x00a95e14, 0x00a85c14, 0x00a65b12, 0x00a45b13, 0x00a15910, 0x00a05810, 0x009e560e, 0x009d5810, 0x009e5a11, 0x009b5813, 0x00945310, 0x00945414, 0x00905314, 0x00905214, 0x008c5013, 0x008c4e14, 0x00894b13, 0x00874913, 0x00804811, 0x00804816, 0x007e4715, 0x00754110, 0x00703c0c, 0x0068360e, 0x00582c0a, 0x00462102, 0x003c1a04, 0x00321602, 0x00281404, 0x00231404, 0x00221808, 0x0022170b, 0x001e140b, 0x001e140c, 0x001c150b, 0x001c150a, 0x001c140a, 0x00191208, 0x00181007, 0x00181108, 0x001b130a, 0x001c140c, 0x001c140c, 0x001c140c, 0x001c150d, 0x001c170f, 0x0019170f, 0x00100f09, 0x00090c06, 0x00080d06, 0x00080d06, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c06, 0x00050c06, 0x00050d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c09, 0x00050d08, 0x00050d08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050e08, 0x00060d07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040d09, 0x00050e09, 0x00040e09, 0x0004100a, 0x00041009, 0x00060f08, 0x00101710, 0x001c211b, 0x001a1e18, 0x001b1f1b, 0x001c1f1d, 0x00181b1a, 0x001c201f, 0x00252928, 0x002c3131, 0x00303636, 0x0034383a, 0x0034373c, 0x0036383e, 0x0034383c, 0x00343438, 0x00303234, 0x00303332, 0x00323432, 0x00303030, 0x00313030, 0x003c3636, 0x00484040, 0x00544a49, 0x005a4e4d, 0x005b4e4a, 0x00665651, 0x00715e59, 0x00785f5c, 0x007e6160, 0x00856763, 0x00866760, 0x0088655c, 0x008a645a, 0x008e6454, 0x008e624e, 0x008f5e44, 0x008e5c3c, 0x00915d35, 0x00935e2f, 0x00955f29, 0x00995e28, 0x009c5f28, 0x009f5f27, 0x009f5e25, 0x009f5e23, 0x00a05f20, 0x00a35e1d, 0x00a46019, 0x00a86116, 0x00ab6417, 0x00ae6416, 0x00b06414, 0x00b16614, 0x00b26714, 0x00ac6210, 0x00ad6411, 0x00b06815, 0x00b36b18, 0x00b66c1a, 0x00b66c1a, 0x00b66c1a, 0x00b66c1a, 0x00b56b18, 0x00b86d1b, 0x00b86e1c, 0x00b86e1c, 0x00b86f1d, 0x00ba701f, 0x00b86f1e, 0x00b46e1c, 0x00b6701e, 0x00b46e1e, 0x00b36c1c, 0x00b06c1b, 0x00b06c1b, 0x00b46f1f, 0x00b46f1f, 0x00b46f1f, 0x00b26d1b, 0x00b36d1c, 0x00b06b18, 0x00b26c18, 0x00b36c18, 0x00b66f1c, 0x00b46c19, 0x00b16718, 0x00ae6418, 0x00ac6117, 0x00aa6018, 0x00a85f15, 0x00a55c13, 0x00a35a10, 0x00a05910, 0x009f580f, 0x009f570e, 0x009d570d, 0x009d580f, 0x009c5810, 0x00995713, 0x00955412, 0x00955513, 0x00925313, 0x00905213, 0x008e5012, 0x008c4f13, 0x00894c12, 0x00854b12, 0x00804710, 0x007d4510, 0x007c4513, 0x0074400f, 0x00703d0d, 0x006c3a11, 0x005c300c, 0x00492405, 0x003d1c05, 0x00331603, 0x00281404, 0x00231405, 0x00211708, 0x00211609, 0x001f150a, 0x001e140b, 0x001c1409, 0x001b1407, 0x001e170d, 0x001e180d, 0x001c150a, 0x00181207, 0x00171007, 0x00181108, 0x00181008, 0x00181209, 0x00181109, 0x00141009, 0x0014120b, 0x000c0d08, 0x00080c06, 0x00070e07, 0x00070e07, 0x00060e08, 0x00050d07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00050c07, 0x00050d07, 0x00050d07, 0x00050c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00080c09, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00060f08, 0x00060e07, 0x000f140f, 0x00131812, 0x001d2220, 0x00202423, 0x00252928, 0x002c302f, 0x00303432, 0x002d3334, 0x002e3435, 0x00303437, 0x00313437, 0x00313438, 0x002f3234, 0x00303235, 0x002e3031, 0x002d302f, 0x002b2d2c, 0x002c2c2d, 0x00303030, 0x00383434, 0x00443d3e, 0x004d4545, 0x00534948, 0x005a4f4c, 0x00645752, 0x0074615c, 0x007a605e, 0x007f6260, 0x00856763, 0x00866760, 0x0088655c, 0x008a645b, 0x008c6457, 0x008e6352, 0x008e604a, 0x008e5d41, 0x00905e38, 0x00945e33, 0x00965e2c, 0x009a602c, 0x009c6029, 0x009e6028, 0x009f5e26, 0x009f5e24, 0x00a05f22, 0x00a25f20, 0x00a4601b, 0x00a56116, 0x00a96215, 0x00ae6416, 0x00b06515, 0x00b16414, 0x00b26514, 0x00b16715, 0x00b26b18, 0x00b36b18, 0x00b36b18, 0x00b56c1b, 0x00b56c1b, 0x00b46c19, 0x00b46c19, 0x00b56b19, 0x00b66c19, 0x00b56c19, 0x00b66c1a, 0x00b66d1c, 0x00b76d1c, 0x00b56d1c, 0x00b46d1c, 0x00b46c1c, 0x00b36c1c, 0x00b36c1c, 0x00b26d1d, 0x00b36e1d, 0x00b36e1e, 0x00b36e1e, 0x00b36e1e, 0x00b46f1d, 0x00b46f1d, 0x00b4701d, 0x00b46e1c, 0x00b46e1c, 0x00b46d1b, 0x00b36c19, 0x00af6718, 0x00ae6319, 0x00ab6018, 0x00a96018, 0x00a76017, 0x00a15c11, 0x009e580e, 0x00a0580f, 0x009f580f, 0x009f580f, 0x009f580f, 0x009f5810, 0x009c570f, 0x00995715, 0x00985614, 0x00955513, 0x00945212, 0x00915211, 0x008e5010, 0x008c5011, 0x00894d11, 0x00874c14, 0x00814810, 0x007c4410, 0x007c4511, 0x0073400c, 0x006e390b, 0x0069380f, 0x005d310c, 0x004c2808, 0x00401e09, 0x00331604, 0x00291407, 0x00241407, 0x001f1404, 0x001e1406, 0x001e140a, 0x001f140c, 0x001d160b, 0x001c1409, 0x00191408, 0x001b150a, 0x001a140a, 0x001a140a, 0x001a140c, 0x0019140a, 0x00171008, 0x00161008, 0x00141008, 0x0014100b, 0x0014130e, 0x000d0e0a, 0x00080d08, 0x00040f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00050d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00081009, 0x00080f0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00080c09, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00051009, 0x0005100a, 0x0008100a, 0x00080f09, 0x000d140f, 0x00161b17, 0x00222623, 0x00242827, 0x00323634, 0x00313534, 0x00303433, 0x002d3334, 0x002e3335, 0x00303337, 0x002f3234, 0x00303435, 0x002d3033, 0x002b2c30, 0x00282a2c, 0x002a2c2c, 0x00292b2c, 0x002a2c2d, 0x00313132, 0x003e3b3c, 0x00464141, 0x00484241, 0x004d4544, 0x005a4e4c, 0x00645853, 0x0075625d, 0x007b625f, 0x007f6461, 0x00856762, 0x00876760, 0x0087655c, 0x0089665d, 0x008d665b, 0x008c6557, 0x008e614d, 0x008d5f44, 0x00905f3c, 0x00936034, 0x00966030, 0x0099602e, 0x009b602c, 0x009d602b, 0x009f6028, 0x009f6025, 0x00a06022, 0x00a16020, 0x00a2601a, 0x00a46118, 0x00a86218, 0x00ad6418, 0x00b06417, 0x00b16616, 0x00b36818, 0x00b56d1c, 0x00b6701e, 0x00b36b19, 0x00b36b19, 0x00b36b19, 0x00b36b19, 0x00b46a19, 0x00b36918, 0x00b46918, 0x00b56a19, 0x00b46a19, 0x00b46b19, 0x00b46c1a, 0x00b46c1a, 0x00b46c1b, 0x00b36c1c, 0x00b36c1c, 0x00b46c1c, 0x00b46d1e, 0x00b46f1f, 0x00b46f1f, 0x00b46e1e, 0x00b36d1d, 0x00b36d1d, 0x00b46e1e, 0x00b67020, 0x00b67020, 0x00b56f1f, 0x00b46c1c, 0x00b16b1b, 0x00b06819, 0x00ae6518, 0x00ac6218, 0x00a75e15, 0x00a55e17, 0x00a45e17, 0x00a15b13, 0x009e5811, 0x009f5811, 0x009f5811, 0x009f5812, 0x00a05913, 0x009f5912, 0x009b5610, 0x009a5715, 0x00985514, 0x00955413, 0x00945210, 0x00905010, 0x008c4d0f, 0x008b4e10, 0x00884d11, 0x00884e14, 0x00844b13, 0x007e4611, 0x007c4511, 0x00733f0c, 0x006d390a, 0x00663409, 0x005d300a, 0x004f2a09, 0x00401e09, 0x00331705, 0x00291507, 0x00241408, 0x001d1205, 0x001c1105, 0x001c1209, 0x001c110b, 0x001b130b, 0x001c140d, 0x001c160e, 0x00171108, 0x00161008, 0x0019140b, 0x001a140b, 0x00181208, 0x00161008, 0x00151008, 0x00141008, 0x0015110c, 0x0014140f, 0x000c0f0b, 0x00080d08, 0x00050f08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00050d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00060c08, 0x00080c08, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00070f08, 0x00070f08, 0x00080e09, 0x00080f0b, 0x000f1410, 0x00151a17, 0x00222624, 0x00313534, 0x00343837, 0x00313534, 0x00303433, 0x002a3030, 0x002a3030, 0x00292c2e, 0x0025282a, 0x00242828, 0x00242828, 0x00262829, 0x00252728, 0x00282a2b, 0x002c2d2f, 0x002f3032, 0x00333334, 0x003a3738, 0x00403b3c, 0x00464040, 0x004e4644, 0x005b4f4d, 0x00645853, 0x0073605c, 0x007b625f, 0x007f6462, 0x00836761, 0x00886862, 0x0085665d, 0x00896860, 0x008d6961, 0x008c645c, 0x008c6250, 0x008c6046, 0x0090603d, 0x00916036, 0x00956031, 0x00996130, 0x009c602e, 0x009c602b, 0x009d6029, 0x009e6026, 0x009d6022, 0x009e601e, 0x009f601b, 0x00a3611a, 0x00a7621b, 0x00aa6218, 0x00ac6216, 0x00b16718, 0x00b46c1a, 0x00b46d1b, 0x00b06a18, 0x00b06918, 0x00b46c1a, 0x00b36918, 0x00b36918, 0x00b56b1a, 0x00b36918, 0x00b26515, 0x00b26515, 0x00b26718, 0x00b46918, 0x00b46a19, 0x00b46a19, 0x00b46a1a, 0x00b36a1b, 0x00b46b1c, 0x00b46b1c, 0x00b46c1c, 0x00b36c1c, 0x00b36c1c, 0x00b16b1b, 0x00b16b1b, 0x00b26b1b, 0x00b46d1e, 0x00b46c1d, 0x00b36c1c, 0x00b26b1c, 0x00b0681b, 0x00b0681b, 0x00ad6618, 0x00ac6418, 0x00a75f14, 0x00a35c12, 0x00a05c13, 0x00a05c15, 0x009e5813, 0x009e5712, 0x009f5813, 0x009f5813, 0x009f5813, 0x00a05914, 0x009e5814, 0x009b5512, 0x009a5714, 0x00985412, 0x00965413, 0x00945211, 0x00935111, 0x008e4e10, 0x008a4d10, 0x00884d11, 0x00884d14, 0x00854b13, 0x00814814, 0x007c4612, 0x0074400f, 0x00703b0c, 0x006b380d, 0x005d2f0a, 0x00502a09, 0x00401f08, 0x00341805, 0x002a1508, 0x00241409, 0x0021150c, 0x0020140c, 0x001c120c, 0x00190f0b, 0x00170f09, 0x0018100a, 0x0019130c, 0x001a140d, 0x0018130a, 0x00181309, 0x00181108, 0x00181108, 0x00181108, 0x00181109, 0x0018120c, 0x0018140f, 0x00181611, 0x000d100c, 0x00080e08, 0x00050f08, 0x00040c06, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00050d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e05, 0x00040d05, 0x00060c05, 0x00060c05, 0x00080c05, 0x00060c05, 0x00060c05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00060c08, 0x00060c08, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00060f08, 0x00070f08, 0x00080e09, 0x00080f0a, 0x00101611, 0x00171c18, 0x002c302e, 0x00313534, 0x00323534, 0x00303433, 0x002e3130, 0x00262b2c, 0x00212526, 0x00242726, 0x00232625, 0x00212526, 0x00242728, 0x00252728, 0x00282a2b, 0x00303133, 0x002d2f30, 0x002d2f30, 0x00313134, 0x00393838, 0x00403b3d, 0x00484243, 0x00534b48, 0x005d5250, 0x00655954, 0x00705d59, 0x007a605e, 0x007e6360, 0x00846863, 0x00876b64, 0x00876a60, 0x008b6a63, 0x008b6861, 0x008d6760, 0x008f6556, 0x008f624c, 0x00906040, 0x00926038, 0x00956032, 0x00986031, 0x009b602d, 0x009c6029, 0x009d6028, 0x009d6025, 0x009c5e20, 0x009b5d1c, 0x009d5d19, 0x00a2601a, 0x00a7621c, 0x00a66017, 0x00a86015, 0x00ab6214, 0x00ae6516, 0x00ac6616, 0x00aa6414, 0x00ab6414, 0x00ae6516, 0x00ae6314, 0x00ae6414, 0x00b16717, 0x00b16717, 0x00b26616, 0x00b36616, 0x00b16616, 0x00b16718, 0x00b06517, 0x00af6416, 0x00b06618, 0x00b36a1c, 0x00b3691c, 0x00b2681c, 0x00b1681b, 0x00af681a, 0x00ae6618, 0x00af6719, 0x00ae6719, 0x00af681a, 0x00b16b1c, 0x00af681a, 0x00af681c, 0x00af681c, 0x00af681c, 0x00ae681c, 0x00ab6418, 0x00a96115, 0x00a55e14, 0x00a05b12, 0x009e5a11, 0x009e5912, 0x009d5812, 0x009e5712, 0x009f5813, 0x009f5813, 0x009e5712, 0x009c5510, 0x009d5714, 0x009e5714, 0x009c5815, 0x00995513, 0x00985413, 0x00965312, 0x00945212, 0x00904f10, 0x008c4d10, 0x008a4c11, 0x00884c13, 0x00854a13, 0x00844815, 0x00804815, 0x0076400e, 0x00703c0c, 0x006d380d, 0x005e2f09, 0x00502a0a, 0x0043200b, 0x00341805, 0x002a1508, 0x0024140a, 0x0021150c, 0x0020150e, 0x001e140f, 0x001a0f0b, 0x00160e09, 0x00150f0a, 0x0015100a, 0x0018130c, 0x0018120b, 0x0018120b, 0x0018110a, 0x00171009, 0x00181208, 0x00181208, 0x001a140c, 0x001d1710, 0x001a1913, 0x000d100c, 0x00080e08, 0x00050f08, 0x00040c06, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c06, 0x00060c06, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060c05, 0x00060c05, 0x00080c05, 0x00060c05, 0x00060c05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00090d0a, 0x00060c08, 0x00060c07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100a, 0x00040c08, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00040c06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00070f0a, 0x0008100c, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00070f08, 0x00080e08, 0x00080f09, 0x00101410, 0x00262b25, 0x0030332f, 0x00343734, 0x002f3130, 0x00282c2b, 0x00222624, 0x00232627, 0x00202424, 0x00252928, 0x001d2020, 0x001e2222, 0x00272a2b, 0x0028292b, 0x00313334, 0x002c2d2f, 0x002a2c2f, 0x002d3032, 0x00313334, 0x00363536, 0x003e3a3c, 0x00494244, 0x00534b4b, 0x005d5150, 0x00685c56, 0x00725f59, 0x007b605c, 0x007e6360, 0x00846764, 0x00856c64, 0x00876a60, 0x008b6a62, 0x008b6861, 0x008c6660, 0x0090645b, 0x00906150, 0x00905f42, 0x00935e39, 0x00965f35, 0x00985f32, 0x009a5f2c, 0x009c5f28, 0x009c5f26, 0x009c5f24, 0x009c5d20, 0x009b5c1b, 0x009c5c18, 0x009e5c16, 0x00a15c17, 0x00a15b16, 0x00a35a14, 0x00a55e14, 0x00a55e14, 0x00a55d13, 0x00a96014, 0x00a96014, 0x00a96014, 0x00aa5f14, 0x00ac6014, 0x00b06418, 0x00ac6214, 0x00b06617, 0x00b3681c, 0x00b2681b, 0x00af6417, 0x00ac6316, 0x00ac6217, 0x00ac6317, 0x00ac6418, 0x00ac6318, 0x00ac6318, 0x00ac6318, 0x00ac6217, 0x00ab6116, 0x00aa6115, 0x00ac6217, 0x00ab6218, 0x00ab6118, 0x00a86016, 0x00a96118, 0x00a96118, 0x00aa6218, 0x00a86117, 0x00a65f14, 0x00a55e14, 0x00a25b12, 0x009f5a12, 0x009e5a12, 0x009c5811, 0x009c5812, 0x009e5912, 0x00a05814, 0x00a05814, 0x009e5712, 0x009f5813, 0x009f5814, 0x009f5814, 0x009c5816, 0x009c5614, 0x00985412, 0x00985411, 0x00955312, 0x00905010, 0x008d4e11, 0x00894b11, 0x00874b13, 0x00864912, 0x00844814, 0x00804714, 0x00784210, 0x0075400f, 0x006f3a0f, 0x0062300a, 0x00582c0c, 0x0048220a, 0x003a1a08, 0x002b1507, 0x0024140a, 0x0020140c, 0x001f140d, 0x001f130e, 0x001e130e, 0x0018120d, 0x0014100a, 0x0015100b, 0x0014100a, 0x0017120c, 0x0016120a, 0x00151008, 0x00171008, 0x00181308, 0x001a1409, 0x001d170d, 0x001f1810, 0x00191710, 0x000c0e09, 0x00070d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c06, 0x00060d04, 0x00060d04, 0x00060d03, 0x00060e01, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00090d0a, 0x00060c08, 0x00060c07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100a, 0x00040c08, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c0a, 0x00040c08, 0x00060e09, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00070f0a, 0x0008100c, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00070f08, 0x00080e08, 0x00080f08, 0x00121711, 0x00252a24, 0x002d312d, 0x002d2f2c, 0x00222422, 0x00202422, 0x00202422, 0x001b1f20, 0x00222526, 0x00242828, 0x00262a2a, 0x002a2d30, 0x002d3034, 0x002f3034, 0x002e2f32, 0x002a2c2d, 0x002b2c30, 0x002d3132, 0x00313334, 0x00363435, 0x00413e40, 0x004c4648, 0x00504848, 0x005a4f4c, 0x006c5d58, 0x0074615c, 0x007b605c, 0x007d635f, 0x00846865, 0x00856c64, 0x00876a60, 0x008b6a63, 0x008b6861, 0x008b645f, 0x0090645c, 0x00906150, 0x00905f42, 0x00935e39, 0x00955e34, 0x00985d31, 0x009b5e2c, 0x009c5e28, 0x009d5e26, 0x009d5d24, 0x009c5c20, 0x009b5b19, 0x009a5a16, 0x009b5914, 0x009c5815, 0x009f5814, 0x00a05814, 0x009f5912, 0x00a05911, 0x00a35b14, 0x00a55d16, 0x00a65e16, 0x00a65e16, 0x00a45b12, 0x00a75d14, 0x00a85f15, 0x00a65d11, 0x00a75e12, 0x00aa6016, 0x00aa6218, 0x00a96118, 0x00ab6419, 0x00a96119, 0x00a55d15, 0x00a75f16, 0x00a86017, 0x00a86017, 0x00a86018, 0x00a65e15, 0x00a96119, 0x00a96118, 0x00a55d14, 0x00a45c14, 0x00a45c15, 0x00a55f18, 0x00a45e17, 0x00a45e17, 0x00a45e17, 0x00a45f17, 0x00a45d16, 0x00a15c14, 0x00a05912, 0x009e5813, 0x009c5814, 0x009b5814, 0x009c5812, 0x009c5913, 0x009d5814, 0x009e5915, 0x009f5a16, 0x009f5a16, 0x009e5916, 0x009d5816, 0x009d5816, 0x009c5614, 0x00985412, 0x00985411, 0x00955412, 0x00915111, 0x008f5013, 0x00894d13, 0x00874b13, 0x00854811, 0x00844814, 0x00804714, 0x00794210, 0x00784311, 0x00703c0f, 0x0066340d, 0x00582b0a, 0x004b2208, 0x0041200a, 0x002d1506, 0x00251408, 0x001e120b, 0x001c130c, 0x001e140c, 0x001e160d, 0x001e160e, 0x001c140e, 0x00150f08, 0x00171009, 0x0018120b, 0x0018100a, 0x0018110a, 0x0019140b, 0x001b150c, 0x001c170c, 0x00201910, 0x001c160f, 0x0013110b, 0x00080c07, 0x00040b05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d03, 0x00060d03, 0x00060d04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00090d0a, 0x00060c08, 0x00060c07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100a, 0x00040c08, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00060e08, 0x00051007, 0x00051007, 0x00051007, 0x00040e05, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070d08, 0x00070d08, 0x00080c08, 0x000a0e09, 0x00151915, 0x00242823, 0x00292d29, 0x002a2c2a, 0x00222422, 0x00212524, 0x00202423, 0x00272b2b, 0x00292c2d, 0x002b2e2f, 0x002c3030, 0x002b2e30, 0x00272a2c, 0x00292b2e, 0x0025282b, 0x0026282b, 0x002b2c30, 0x002c2f31, 0x002e3030, 0x003a383b, 0x00434043, 0x00484243, 0x0052494a, 0x00605452, 0x006c5d58, 0x0074605c, 0x007b605c, 0x007d625e, 0x00836864, 0x00866b64, 0x00886a62, 0x008c6b64, 0x008c6864, 0x008c6660, 0x008f645b, 0x00906150, 0x008f5d41, 0x00925d3a, 0x00955e34, 0x00985d31, 0x009b5e2c, 0x009c5e29, 0x009d5e25, 0x009a5b20, 0x0099591b, 0x00995918, 0x00995915, 0x00995817, 0x009a5716, 0x009b5415, 0x009c5414, 0x009c5614, 0x009b5613, 0x009c5714, 0x009e5815, 0x009e5814, 0x009f5814, 0x009d5712, 0x00a05813, 0x00a05913, 0x00a05a12, 0x00a05911, 0x00a05912, 0x00a05912, 0x00a45c15, 0x00a75f18, 0x00a65e18, 0x00a55d17, 0x00a45b15, 0x00a45c15, 0x00a55c16, 0x00a65e18, 0x00a65e18, 0x00a75f18, 0x00a45c16, 0x00a35a14, 0x00a45b17, 0x00a45c18, 0x00a35c18, 0x00a45c18, 0x00a35c17, 0x00a35c17, 0x00a15c17, 0x00a05914, 0x009f5813, 0x009c5411, 0x009a5412, 0x00995513, 0x00995514, 0x009a5714, 0x009a5614, 0x009a5513, 0x009c5614, 0x009c5815, 0x009e5817, 0x009e5818, 0x009c5716, 0x009b5514, 0x00995412, 0x00955210, 0x00955210, 0x00945110, 0x00925212, 0x008f5013, 0x00894d12, 0x00874b13, 0x00844912, 0x00814814, 0x007f4814, 0x007e4816, 0x007a4413, 0x00743f12, 0x00683710, 0x00633413, 0x00502409, 0x003f1a04, 0x00301404, 0x00261407, 0x001f130c, 0x001d110b, 0x001c120a, 0x001e140c, 0x001f150c, 0x0020160c, 0x001c140b, 0x001b1308, 0x001b1208, 0x001a1008, 0x001b1309, 0x001c140a, 0x001c140b, 0x001c140d, 0x001b130e, 0x0017120d, 0x0011100c, 0x00080c08, 0x00050c06, 0x00040d07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c08, 0x00060c05, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c08, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080e0a, 0x00060c08, 0x00060c07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100a, 0x00040c08, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00040c08, 0x00040c08, 0x00040d07, 0x00061007, 0x00051007, 0x00051007, 0x00040e05, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x0004100a, 0x0004100a, 0x0004100a, 0x0005100a, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d08, 0x0009100a, 0x00151a14, 0x00242822, 0x00272b28, 0x00272927, 0x00282b29, 0x00242827, 0x002e3131, 0x002f3334, 0x002c3030, 0x00242829, 0x00222526, 0x00272a2c, 0x00242729, 0x0027282b, 0x002a2c2e, 0x002d2f32, 0x002a2c2f, 0x002c2f31, 0x00343537, 0x003c3a3c, 0x00434041, 0x00484344, 0x00554c4d, 0x00645858, 0x006f5f5c, 0x0076605c, 0x007c615d, 0x007d625f, 0x00836864, 0x00856a64, 0x00886a63, 0x008c6b64, 0x008c6964, 0x008d6760, 0x008f6459, 0x00906150, 0x008f5d41, 0x00925d3a, 0x00955c34, 0x00975c30, 0x00995c2b, 0x009a5c28, 0x009a5c23, 0x0098581c, 0x00955718, 0x00965515, 0x00965714, 0x00955714, 0x00965515, 0x00985314, 0x00985314, 0x00985413, 0x00985413, 0x00985414, 0x009a5615, 0x00995513, 0x00995413, 0x00995413, 0x009c5814, 0x009d5814, 0x009d5814, 0x009d5814, 0x009d5814, 0x009f5813, 0x009f5813, 0x009f5813, 0x009f5813, 0x009d5712, 0x009c5512, 0x009c5612, 0x009d5713, 0x009f5814, 0x00a05814, 0x00a05915, 0x00a05915, 0x00a05814, 0x009f5916, 0x00a05a18, 0x00a05c18, 0x009f5a18, 0x009e5a15, 0x009d5814, 0x009c5815, 0x009a5513, 0x00985310, 0x00985311, 0x00985313, 0x00975414, 0x00955414, 0x00945413, 0x00965412, 0x00955213, 0x00965314, 0x00985515, 0x00995718, 0x009a5718, 0x00985414, 0x00985413, 0x00985413, 0x00945210, 0x00945110, 0x00945110, 0x00925212, 0x00905114, 0x008b4e11, 0x00884c14, 0x00834a12, 0x007f4611, 0x007c4512, 0x007c4814, 0x007d4816, 0x00764012, 0x006f3c13, 0x00643411, 0x00582a0c, 0x00472108, 0x00301503, 0x00271306, 0x001f140c, 0x001c120b, 0x00181008, 0x00180f07, 0x001a1208, 0x001c1409, 0x001d150b, 0x0020180c, 0x001d140b, 0x001b1308, 0x001c1208, 0x001c1309, 0x001b120b, 0x0018120c, 0x0018110c, 0x00171210, 0x0010110d, 0x00080c08, 0x00050c06, 0x00040d07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00070e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c08, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c09, 0x00060c08, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060c08, 0x000b110d, 0x00101612, 0x00141916, 0x00212423, 0x00242625, 0x00252726, 0x00282c2c, 0x00303434, 0x002d3033, 0x00232628, 0x00242729, 0x002a2d30, 0x00242729, 0x0024282a, 0x0025272a, 0x002c2c30, 0x002c2d30, 0x002c2e31, 0x0034383a, 0x0035383b, 0x00383639, 0x00403c3d, 0x00444041, 0x005a5252, 0x00675959, 0x00705e5c, 0x00755f5d, 0x007b605e, 0x007f6460, 0x00846764, 0x00836864, 0x00886a66, 0x008f6d6c, 0x00906c68, 0x00906a65, 0x0091665c, 0x00926451, 0x00916044, 0x00925d3a, 0x00945c31, 0x00985c30, 0x0096592a, 0x00955826, 0x00955920, 0x00935619, 0x00915416, 0x00905113, 0x008d5010, 0x008e5010, 0x00905010, 0x00914e0f, 0x00914d0e, 0x00904e0c, 0x00925010, 0x00955311, 0x00965514, 0x00975514, 0x00955412, 0x00945211, 0x00955412, 0x00985412, 0x00985311, 0x00995412, 0x00995412, 0x009a5411, 0x009b5410, 0x009a5310, 0x009a5310, 0x009a5412, 0x00985311, 0x0096500f, 0x00985311, 0x009a5513, 0x009c5614, 0x009b5514, 0x009a5413, 0x00995413, 0x00975514, 0x00985716, 0x00985716, 0x00975614, 0x00975614, 0x00965413, 0x00945414, 0x00935013, 0x00914e11, 0x00924e11, 0x00935014, 0x00904f13, 0x008a4b0f, 0x00884c0e, 0x008b4e10, 0x008c4d10, 0x008b4c0e, 0x008c4d10, 0x008e5012, 0x00905013, 0x00915113, 0x00925012, 0x00915012, 0x00945314, 0x00975618, 0x00965517, 0x00925214, 0x008f5010, 0x008b4d0f, 0x00884c13, 0x00834914, 0x007e4613, 0x007c4514, 0x007d4814, 0x007d4612, 0x00794211, 0x00723e10, 0x006c3c12, 0x005a2c0a, 0x004a2306, 0x00341804, 0x00281305, 0x001e1408, 0x001c1308, 0x00191208, 0x00151009, 0x00130d08, 0x00140f08, 0x0019130c, 0x001b140e, 0x001d140c, 0x001e140c, 0x0020140d, 0x0024140f, 0x00191008, 0x0015110a, 0x0016110c, 0x00181310, 0x0010120c, 0x00070e06, 0x00040c04, 0x00040e05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e07, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040c06, 0x00030c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040f08, 0x00040f08, 0x00060e08, 0x00070f0a, 0x0008100c, 0x000a0f0c, 0x00141815, 0x001c1e1d, 0x00222424, 0x002b2e2f, 0x002c2f30, 0x0025282b, 0x002b2e30, 0x00282c2e, 0x00232628, 0x001d2023, 0x0025272a, 0x00282a2d, 0x002f3033, 0x002c2d30, 0x002c2d31, 0x00313435, 0x00323437, 0x00353435, 0x003b3838, 0x00484444, 0x00595150, 0x00645756, 0x00725f5c, 0x0078605d, 0x007c615d, 0x00806561, 0x00846865, 0x00846965, 0x00896c69, 0x0090706f, 0x00916d6a, 0x00916b67, 0x0094685c, 0x00946654, 0x00946248, 0x00945f3c, 0x00985f36, 0x0094592e, 0x00905628, 0x00905624, 0x00905620, 0x008d541a, 0x008c5217, 0x008a4e14, 0x00884d11, 0x008a4e10, 0x008c4c10, 0x008c4b0f, 0x008c4b0e, 0x008c4c0e, 0x008f4e10, 0x00905011, 0x00915112, 0x00915011, 0x00905010, 0x00904f10, 0x00915112, 0x00955111, 0x00975011, 0x00975011, 0x00975011, 0x00965010, 0x00965010, 0x00965010, 0x0095500f, 0x00965110, 0x00955112, 0x00945010, 0x00945010, 0x00945111, 0x00965212, 0x00945111, 0x00945010, 0x00945010, 0x00905112, 0x00925414, 0x008e5011, 0x008e5011, 0x008e5010, 0x008d5012, 0x008c4e14, 0x00884b11, 0x00884810, 0x00884910, 0x00874a12, 0x007f440c, 0x00753c05, 0x00764006, 0x00784108, 0x00773e05, 0x00773d04, 0x00794006, 0x007c4409, 0x0080440a, 0x00804409, 0x00854a0e, 0x00884c10, 0x008c4f13, 0x00905215, 0x008f5114, 0x008b4e11, 0x008a4e11, 0x00894d11, 0x00874c13, 0x00834914, 0x00804814, 0x007e4817, 0x007f4814, 0x007c4511, 0x007a4312, 0x00754013, 0x00703f13, 0x0063330c, 0x00522a0a, 0x003a1c04, 0x002e1807, 0x00201305, 0x001d1406, 0x001a1308, 0x00171208, 0x00161008, 0x00140e08, 0x00160f08, 0x0019120b, 0x001b1109, 0x001e140b, 0x00251810, 0x002c1a13, 0x0020140c, 0x001a140a, 0x00171109, 0x0019150f, 0x0011130c, 0x00080f07, 0x00040c04, 0x00040e05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00030c06, 0x00030c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050d09, 0x00060c08, 0x00080e0b, 0x00181c19, 0x00282828, 0x002d2d2d, 0x002b2c2e, 0x00282c2c, 0x00272a2c, 0x00212728, 0x00212427, 0x00232628, 0x002a2b2e, 0x002c2e31, 0x002c2c30, 0x002c2d30, 0x002c2e30, 0x00333435, 0x00303437, 0x002e3031, 0x00353334, 0x003e3a3a, 0x004c4646, 0x005d5453, 0x00675956, 0x0073605c, 0x0078615c, 0x007b625d, 0x007e6360, 0x00846865, 0x00856b67, 0x008d706d, 0x00937372, 0x00916e6c, 0x008f6a65, 0x0092675c, 0x00926451, 0x00936248, 0x00945f3d, 0x00915a34, 0x008d562d, 0x008c5428, 0x00885021, 0x00834e1c, 0x00804c18, 0x00824d18, 0x00844e18, 0x00834c15, 0x00844b13, 0x00864a14, 0x00884a14, 0x00884912, 0x00894b10, 0x008c4d12, 0x008c4d12, 0x008b4c11, 0x008c4c11, 0x008a4c10, 0x008c4d11, 0x008d4e13, 0x00914f14, 0x00935014, 0x00945014, 0x00945015, 0x00945114, 0x00945114, 0x00935013, 0x00935013, 0x00925014, 0x00914f14, 0x00904e11, 0x00904e11, 0x00904e11, 0x008f4d10, 0x008f4d10, 0x008f4d10, 0x008e4d11, 0x00894d10, 0x00894e12, 0x00894f11, 0x00864c0f, 0x00844b10, 0x00824810, 0x007d4410, 0x007c4211, 0x007c4312, 0x00784010, 0x00703b0c, 0x006c380a, 0x006a380b, 0x0067380a, 0x00653408, 0x00673508, 0x00673506, 0x00683706, 0x006c3a07, 0x00713d09, 0x0077400d, 0x00743f0b, 0x00763f0a, 0x007a420d, 0x00804610, 0x007c430d, 0x007c420c, 0x00814812, 0x00844b15, 0x00854b14, 0x00844b14, 0x00834b18, 0x007e4918, 0x007d4714, 0x007c4410, 0x00794211, 0x00764214, 0x00724011, 0x006b3a0d, 0x00582e08, 0x00412105, 0x00311904, 0x00251605, 0x00201404, 0x001c1104, 0x00191206, 0x001a1207, 0x001a1209, 0x001b1109, 0x001c1208, 0x001c1107, 0x001e1006, 0x0025140c, 0x0027140a, 0x0025150c, 0x0020150c, 0x001c140c, 0x0019160d, 0x0010140b, 0x00071007, 0x00051008, 0x00040f08, 0x00040f08, 0x00060e06, 0x00060e06, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00080f0a, 0x000c110e, 0x001e2120, 0x00303131, 0x002b2b2b, 0x00282a2b, 0x0025282a, 0x0026292c, 0x00272c2e, 0x002b2e30, 0x002b2e30, 0x002c2e31, 0x002e2d31, 0x00292b2e, 0x002d2f32, 0x00303233, 0x00303234, 0x002d3030, 0x00303334, 0x00333032, 0x00403c3c, 0x00514a49, 0x00615856, 0x006b5d5a, 0x0074605c, 0x007c6460, 0x007c635f, 0x007e635f, 0x00846a66, 0x00886c69, 0x00927572, 0x00937373, 0x0091706c, 0x00906c67, 0x0090665a, 0x0090614f, 0x00906045, 0x00905d3c, 0x008b5632, 0x00804c26, 0x007d4920, 0x007a461c, 0x00764516, 0x00714210, 0x006f3f0e, 0x00754413, 0x007a4815, 0x007b4612, 0x007c4512, 0x007f4513, 0x00804411, 0x0081460f, 0x00844810, 0x00854912, 0x00844810, 0x00844910, 0x00834710, 0x00844910, 0x00864b12, 0x008a4c13, 0x008c4c13, 0x008c4c13, 0x008c4c14, 0x008c4d13, 0x008c4e13, 0x008d4e13, 0x008f4e14, 0x008d4e13, 0x008a4b12, 0x00884911, 0x00884911, 0x00884911, 0x00884810, 0x00884810, 0x00884810, 0x00864810, 0x00824a10, 0x007f480f, 0x007d470e, 0x007a440c, 0x0075400c, 0x00723d0c, 0x00703c0d, 0x006c380a, 0x00663409, 0x00613108, 0x005c2d05, 0x00582b04, 0x00542a04, 0x00542c08, 0x00582d09, 0x00582d08, 0x00582d06, 0x005b3006, 0x00603408, 0x00643409, 0x0068380c, 0x0068380a, 0x00683808, 0x00683607, 0x00673303, 0x006c3808, 0x00723f0e, 0x007b4515, 0x007d4816, 0x007f4813, 0x00844c16, 0x00844d1a, 0x007e4917, 0x007c4614, 0x007b4310, 0x00784110, 0x00774213, 0x00764314, 0x006e3c0c, 0x0062350c, 0x00492606, 0x00351901, 0x00291604, 0x00231405, 0x00211406, 0x00201407, 0x00201408, 0x00201409, 0x0023170c, 0x0023170c, 0x0024150c, 0x0026150b, 0x0029150b, 0x002e180c, 0x00321e13, 0x00291910, 0x0020140b, 0x0018140b, 0x000b1007, 0x00071007, 0x00051008, 0x00031008, 0x00040f08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e06, 0x00060e06, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0009100c, 0x00151a17, 0x00232524, 0x00282828, 0x00222222, 0x00242726, 0x00242728, 0x00262b2d, 0x00282d2f, 0x0024282b, 0x00232428, 0x0029292c, 0x002c2b2f, 0x002c2e30, 0x002d2f30, 0x002f3032, 0x002e3030, 0x002d2f30, 0x002f2f2f, 0x00323031, 0x00433e3d, 0x00514a49, 0x00635958, 0x006d605c, 0x0076645f, 0x007e6761, 0x007d6460, 0x007d625e, 0x00856b67, 0x00886e6b, 0x00917572, 0x00917471, 0x00906f6a, 0x008c6963, 0x008d6758, 0x008b6250, 0x00865940, 0x00845637, 0x00825534, 0x00764926, 0x006e411e, 0x006c3f1d, 0x00714421, 0x006d401c, 0x00683b18, 0x00683a16, 0x006c3f14, 0x006e3f10, 0x00713f10, 0x00733e10, 0x00743d0f, 0x00753c0d, 0x00783e0f, 0x007b4112, 0x007f4515, 0x007b420f, 0x007b420d, 0x007e450f, 0x0080480f, 0x00834910, 0x00834910, 0x00844910, 0x00844910, 0x0084490f, 0x00884c11, 0x0084480d, 0x00874a0e, 0x00894c11, 0x00884812, 0x00854712, 0x00814411, 0x00824513, 0x00844713, 0x00834411, 0x007f440f, 0x007a410c, 0x0077400c, 0x0077400d, 0x0074400f, 0x006c3a0c, 0x0065360b, 0x0060330b, 0x005d330c, 0x0058300b, 0x00542b0a, 0x00522b0b, 0x004f2908, 0x004c2907, 0x004c2906, 0x004f2808, 0x00502808, 0x00542807, 0x00542805, 0x00542806, 0x005d320e, 0x00643814, 0x00643712, 0x005f340e, 0x005e320b, 0x0060310b, 0x0060320c, 0x0064340c, 0x0067380e, 0x006e3e12, 0x00744114, 0x00784413, 0x007d4815, 0x007f4918, 0x007e4918, 0x007b4714, 0x00794310, 0x00784211, 0x00784212, 0x00764212, 0x00743d0d, 0x006d3a10, 0x00542b09, 0x00381800, 0x002c1304, 0x00281408, 0x00251509, 0x00261507, 0x00261508, 0x002a190d, 0x002e190f, 0x002c150c, 0x002c150c, 0x00311b10, 0x00341d10, 0x00331b0d, 0x003c2518, 0x002c1a0f, 0x001e1308, 0x00131006, 0x00080d04, 0x00060e08, 0x00040f08, 0x00031008, 0x00040f08, 0x00070f09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060d0b, 0x00060d0b, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00080f08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040c06, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x000f130b, 0x000f130b, 0x0014180d, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130b, 0x000f130b, 0x000f130b, 0x0014180f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e06, 0x00060f04, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x000b110d, 0x00181e1a, 0x00242624, 0x00282828, 0x00242424, 0x00242625, 0x00242527, 0x001c2124, 0x001b2021, 0x001f2324, 0x00282a2d, 0x002d2c30, 0x00323135, 0x00323234, 0x00303133, 0x002d2f30, 0x002c2e2f, 0x00262828, 0x002c2c2c, 0x00373333, 0x003f3a3a, 0x00544d4e, 0x00665c5c, 0x00716260, 0x00796864, 0x007e6764, 0x00806863, 0x00806561, 0x00846865, 0x00856c68, 0x008c726e, 0x008f706e, 0x00886864, 0x0084645c, 0x007c594a, 0x00795441, 0x007c563e, 0x00754d33, 0x00704729, 0x00684020, 0x00643c1c, 0x00633a1c, 0x00653d1e, 0x00673d1e, 0x0064391a, 0x00603414, 0x005e330e, 0x0063370d, 0x0065370c, 0x0067380d, 0x0069360c, 0x006a360b, 0x006c360b, 0x006e380c, 0x00713b0f, 0x00733c0c, 0x00733d0b, 0x0077400b, 0x0078420c, 0x0078420c, 0x0078410c, 0x007c430d, 0x007c440c, 0x0080450f, 0x00844910, 0x0081460e, 0x0083480e, 0x00854911, 0x00844711, 0x00804510, 0x007b400f, 0x007b4010, 0x007a3f10, 0x00763d0d, 0x00733c0c, 0x006e3b09, 0x006c3808, 0x006b3909, 0x0068390c, 0x0060340a, 0x00592f08, 0x00552c09, 0x00502909, 0x004c2809, 0x004a270a, 0x004a270c, 0x0049280c, 0x004a280a, 0x004b2a09, 0x004c2909, 0x004f2809, 0x00512708, 0x00522807, 0x00532908, 0x00572d0a, 0x00582e0b, 0x005c3310, 0x005c340e, 0x0059300a, 0x00582d08, 0x00582c08, 0x005c2f09, 0x0060340c, 0x0064360c, 0x00693a0c, 0x006f3f10, 0x00754312, 0x007a4516, 0x007c4617, 0x007a4513, 0x00784210, 0x00784212, 0x00794314, 0x00784414, 0x00784010, 0x00733d10, 0x005c300e, 0x003b1b02, 0x002b0f01, 0x00261105, 0x00261409, 0x002c180c, 0x002f1b0d, 0x00321e10, 0x0030180c, 0x0034180d, 0x0031180c, 0x00371d11, 0x00382012, 0x00301808, 0x00381f13, 0x00301d12, 0x001a0f04, 0x00100c03, 0x00080d04, 0x00060e08, 0x00040f08, 0x00031008, 0x00040f08, 0x00070f0a, 0x00050d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060f08, 0x00070e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x000f130b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00071007, 0x00040e04, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x000a110c, 0x001b201c, 0x00242624, 0x00242323, 0x00201f20, 0x001d1e1e, 0x00202123, 0x00202426, 0x00222729, 0x00272a2c, 0x00303134, 0x002e2d31, 0x00303033, 0x00323032, 0x00303032, 0x002b2b2b, 0x002a2b2b, 0x00282828, 0x002b2b2a, 0x00343030, 0x003e3939, 0x00565050, 0x006b5f60, 0x00756665, 0x007b6864, 0x007e6864, 0x00816864, 0x00806664, 0x00816866, 0x00846d68, 0x008c736f, 0x008a6e6c, 0x007c5f59, 0x00785950, 0x006d503f, 0x006c4d3a, 0x00694834, 0x006b4630, 0x00654328, 0x00664428, 0x00634225, 0x005c3b1e, 0x00603c1f, 0x00603d20, 0x00603c1e, 0x005c3818, 0x005c3613, 0x005c3612, 0x005c340e, 0x005b310c, 0x00643711, 0x0063360f, 0x0061340b, 0x0063340c, 0x0063350c, 0x00693b0f, 0x006d3e10, 0x006c3d0d, 0x006f3f0c, 0x00723e0e, 0x00743e0c, 0x0075400e, 0x00794110, 0x007b4310, 0x007b420f, 0x007b420e, 0x007c430e, 0x007c440e, 0x007d4410, 0x007a4210, 0x00743d0e, 0x006f390c, 0x006e3810, 0x0069360f, 0x0068380e, 0x0061340a, 0x005e3207, 0x005d3308, 0x005d350c, 0x005a340f, 0x00552f0e, 0x00522c0f, 0x004e2a10, 0x004b2910, 0x0046240b, 0x0045230c, 0x0045240c, 0x0048280e, 0x004b2910, 0x00502c14, 0x00522a10, 0x00502809, 0x00532909, 0x00542808, 0x00552908, 0x005d310f, 0x00643816, 0x005c300d, 0x00572c09, 0x00562c08, 0x005b300c, 0x005c300d, 0x005a2f0a, 0x005d330b, 0x00603409, 0x0064390c, 0x006c3e10, 0x00754416, 0x00794418, 0x00794314, 0x00784112, 0x00784112, 0x00794314, 0x00794412, 0x0078410f, 0x00703b0b, 0x00633711, 0x00442509, 0x002f1301, 0x00261106, 0x0027140c, 0x0029140a, 0x002c160b, 0x002f170b, 0x00321708, 0x00371b09, 0x00341808, 0x003f2517, 0x00351c0e, 0x00301609, 0x00381f14, 0x00342016, 0x00180c02, 0x000f0c04, 0x00080e07, 0x00051008, 0x0005100a, 0x0004100a, 0x0005100a, 0x00070f08, 0x00050d06, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040d07, 0x00050d07, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180b, 0x00191c0b, 0x0014180a, 0x00191c0a, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x00191c0a, 0x00141809, 0x00191c0b, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00071007, 0x00040e04, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e06, 0x00060e06, 0x00060e06, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00080f0a, 0x00121714, 0x00212321, 0x00232222, 0x00222222, 0x00262827, 0x00292b2c, 0x002c2f31, 0x002d3334, 0x00323538, 0x00343538, 0x00323034, 0x00323134, 0x00353336, 0x002c2b2d, 0x002b2b2b, 0x002b2b2b, 0x00282928, 0x002c2c2a, 0x00363332, 0x00413d3c, 0x00595352, 0x006e6262, 0x00796866, 0x007c6864, 0x007f6864, 0x00806964, 0x00806664, 0x00826967, 0x00846d68, 0x00846c69, 0x007c615e, 0x00755953, 0x006f5348, 0x006e5440, 0x006e5440, 0x00674a37, 0x0061422d, 0x005b3e25, 0x00573a20, 0x005a3c20, 0x005c3e22, 0x005a3c1e, 0x00583a1c, 0x0058391b, 0x00573718, 0x00583817, 0x00583513, 0x00573211, 0x00593412, 0x00583210, 0x0057300d, 0x0058320e, 0x005c3410, 0x005c3410, 0x005e350f, 0x00613810, 0x0063380d, 0x00643a0c, 0x0069380e, 0x006c380e, 0x006c3910, 0x00703b12, 0x00723d0f, 0x00743e0c, 0x0075400f, 0x00773f0f, 0x0076400c, 0x0074400c, 0x00713f0c, 0x006d3c0d, 0x0066370c, 0x00623410, 0x005c310e, 0x005a300d, 0x0059340c, 0x00573109, 0x00553209, 0x00563610, 0x00563614, 0x004d2d0f, 0x004a2a0e, 0x0044240c, 0x003d2009, 0x003c1d06, 0x003c1b04, 0x003c1d04, 0x003f2008, 0x0041220c, 0x00482511, 0x0049240c, 0x004e2708, 0x00542a08, 0x005b2f0d, 0x005c2f0d, 0x005a2e0c, 0x005a2f0c, 0x005c300c, 0x005d320d, 0x005d330c, 0x00603410, 0x005c3310, 0x00542b05, 0x005b310b, 0x005d340a, 0x0062390d, 0x00693f11, 0x00734317, 0x00754117, 0x00784014, 0x00774011, 0x00784112, 0x007a4414, 0x007b4514, 0x007b440d, 0x00733d0a, 0x00693c15, 0x004a2b0c, 0x00321701, 0x00271105, 0x0028150d, 0x0029140d, 0x002e160d, 0x0033190d, 0x00381c0b, 0x003b1e08, 0x003d230f, 0x003a2111, 0x002c1406, 0x002c1408, 0x00361f14, 0x00382419, 0x00140b00, 0x00100c06, 0x00081008, 0x00051008, 0x0005100a, 0x0004100a, 0x0005100a, 0x00071008, 0x00050e04, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00040c06, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050f08, 0x00050f08, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180e, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x001d200a, 0x00191c09, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2008, 0x00202309, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d200a, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c0a, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d08, 0x00040d08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00050e06, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00070e09, 0x000a100c, 0x00181c1a, 0x00252726, 0x00292b2a, 0x002c2d2c, 0x002a2e2c, 0x002b2e2f, 0x002e3132, 0x00353738, 0x0039393b, 0x00353235, 0x00343033, 0x002f2d2e, 0x002c2a2b, 0x00302f2f, 0x00302f2e, 0x00302e2d, 0x00323030, 0x00383735, 0x00413e3e, 0x005c5454, 0x00736464, 0x007b6967, 0x007d6964, 0x007f6964, 0x00816866, 0x00806865, 0x00816a67, 0x00846d6b, 0x00836b6a, 0x007a615d, 0x00735a50, 0x006a5345, 0x0067503c, 0x0068503b, 0x00664c39, 0x00604530, 0x0062472f, 0x00604429, 0x005d4024, 0x005a3b1d, 0x00533517, 0x00503314, 0x004e3214, 0x00513415, 0x00523412, 0x00583714, 0x005b3918, 0x00543314, 0x004d2c0d, 0x004e2c0c, 0x00523010, 0x00523010, 0x00543412, 0x0054340f, 0x0058350e, 0x0059360c, 0x005b360b, 0x005f340a, 0x0063340a, 0x0065360b, 0x006a390d, 0x006c3a10, 0x00703c12, 0x00764214, 0x007a4514, 0x00794311, 0x00743e0d, 0x00703c0c, 0x006b3c0e, 0x0062360a, 0x0059310b, 0x00552f0a, 0x00573410, 0x00573411, 0x00573310, 0x00502d0c, 0x004c2a0c, 0x00442609, 0x003b2007, 0x00381c08, 0x00341a08, 0x00331a09, 0x00361c0c, 0x00341a08, 0x00391e0b, 0x00391f0b, 0x00442917, 0x00482c18, 0x0050331a, 0x00503111, 0x0054340e, 0x005a340e, 0x005c340e, 0x005c320d, 0x005e3410, 0x005e350e, 0x005e350e, 0x005e350e, 0x0060340f, 0x005b310c, 0x005b310c, 0x005c320d, 0x005d340c, 0x005e3710, 0x00643c14, 0x006b3e15, 0x006e3f14, 0x00734012, 0x00784112, 0x00794314, 0x007b4516, 0x007d4816, 0x007e4711, 0x007a4310, 0x006f3f15, 0x00562d0f, 0x00381700, 0x002b1304, 0x0025140c, 0x0027130d, 0x002e170c, 0x00351c0f, 0x003e200e, 0x0040200c, 0x00412713, 0x00301808, 0x00281104, 0x00281007, 0x00382016, 0x00372418, 0x00130d03, 0x000a1007, 0x00051008, 0x0005100a, 0x00060f0a, 0x0005100a, 0x0004100a, 0x00051007, 0x00040e04, 0x00040f04, 0x00040f06, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00050e07, 0x00050e07, 0x00060e08, 0x00050e07, 0x00040f06, 0x00050f07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00030c08, 0x00030c08, 0x00030c08, 0x00030c08, 0x00040e08, 0x00040e08, 0x00040d08, 0x00040d08, 0x00040e08, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060f09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00060e08, 0x00060e07, 0x00060e08, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00030c04, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00060d07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00050c06, 0x00040c07, 0x00070e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2009, 0x001d2008, 0x001d2008, 0x00202308, 0x00202308, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202308, 0x00202308, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c09, 0x00191c0a, 0x00191c0a, 0x00191c0c, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d05, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x000b100d, 0x001c201f, 0x002c302f, 0x00323534, 0x00303434, 0x00303334, 0x00333737, 0x00343536, 0x00313032, 0x002c282a, 0x00292528, 0x002e2c2c, 0x00333030, 0x00343231, 0x00353432, 0x00333130, 0x00353432, 0x00393836, 0x00413e3e, 0x005f5454, 0x00746463, 0x007c6966, 0x007d6a64, 0x00806964, 0x00816866, 0x00826967, 0x00806966, 0x00806865, 0x007a6261, 0x00745c58, 0x006f584f, 0x00695445, 0x0066503d, 0x0068503c, 0x00664c38, 0x00614630, 0x005e4129, 0x005d4024, 0x00604022, 0x00684427, 0x00644121, 0x005c3c1d, 0x00563818, 0x00543716, 0x00543714, 0x00563816, 0x005a3c1c, 0x0056381b, 0x00503114, 0x0046290d, 0x00422509, 0x0043260a, 0x00452a0c, 0x004c3210, 0x00533612, 0x00583914, 0x005a3912, 0x005c360e, 0x005d340c, 0x0062380c, 0x0064380c, 0x0068380e, 0x006d3c14, 0x00733f13, 0x00764010, 0x0078400f, 0x00753c0c, 0x00703b0d, 0x0068380c, 0x005f340a, 0x0059310a, 0x00542f0a, 0x00522f0e, 0x00502f10, 0x004c2b0c, 0x00462408, 0x00402108, 0x00371a03, 0x00341c07, 0x002f1907, 0x00291707, 0x00271708, 0x00261609, 0x00281708, 0x00281507, 0x002e1b0b, 0x002f1c0c, 0x0034200d, 0x003c240f, 0x00442c10, 0x004c3112, 0x00533313, 0x00563312, 0x00583210, 0x005b3512, 0x005b3611, 0x005c3710, 0x005c3510, 0x005e3410, 0x005c320d, 0x005c320d, 0x005b310c, 0x005b310c, 0x005b330f, 0x00603614, 0x00673b14, 0x006c3f13, 0x00734113, 0x007a4414, 0x007b4514, 0x007c4516, 0x007e4817, 0x007e4713, 0x007c4411, 0x00724016, 0x00603213, 0x00401c04, 0x002c1403, 0x00241309, 0x0024130a, 0x002b1609, 0x00331c0c, 0x003f2010, 0x00472615, 0x00381b09, 0x002c1301, 0x002b1003, 0x002c1108, 0x003d2418, 0x00362317, 0x00121005, 0x00081209, 0x0004110b, 0x0006100c, 0x00080f0b, 0x0005100a, 0x0004100a, 0x00040f08, 0x00040e05, 0x00040f05, 0x00040f06, 0x00040d07, 0x00040c08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00050e07, 0x00040f05, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00060d07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00040c06, 0x00030d06, 0x00051008, 0x00040f08, 0x00040f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180e, 0x0014180b, 0x0014180b, 0x00191c0b, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2008, 0x001d2008, 0x00202308, 0x00202309, 0x00202309, 0x0024250b, 0x0024250b, 0x0024250b, 0x0024250c, 0x0024250c, 0x0026280c, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280c, 0x0026280c, 0x0024250c, 0x0024250c, 0x0024250b, 0x0024250b, 0x0024250b, 0x0024250b, 0x00202309, 0x00202309, 0x00202308, 0x001d2008, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c09, 0x00191c0a, 0x00191c0c, 0x0014180b, 0x0014180c, 0x0014180d, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00050d08, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00070f0b, 0x00111815, 0x00282d2b, 0x00343936, 0x00313534, 0x00303334, 0x00363638, 0x00373838, 0x00302e30, 0x00322e30, 0x00332f30, 0x00333030, 0x00343030, 0x003a3535, 0x00393635, 0x003b3938, 0x00363433, 0x00353331, 0x00403c3b, 0x00605456, 0x00746363, 0x007d6966, 0x00806a64, 0x00816965, 0x00826967, 0x00826868, 0x007e6764, 0x007a6460, 0x00735c59, 0x006d5652, 0x006e5850, 0x00685348, 0x00654e3f, 0x00674e3c, 0x00674d38, 0x00644830, 0x005f4226, 0x005e3d20, 0x00623e1e, 0x00643e1e, 0x00623c1c, 0x005d3b1c, 0x005a381a, 0x0059391a, 0x00563919, 0x004d3214, 0x004a2e14, 0x00442a10, 0x00402510, 0x003c230d, 0x00381f0c, 0x0038200c, 0x0039220b, 0x003b250b, 0x0040270a, 0x00472c0e, 0x004e3112, 0x00553412, 0x005a3511, 0x00623c17, 0x00603810, 0x0063350c, 0x006c3c11, 0x00744012, 0x00774310, 0x007a4310, 0x00743c0c, 0x006f3a0c, 0x0067380a, 0x005e3408, 0x00583008, 0x00522c0a, 0x004b270b, 0x0048260c, 0x00402209, 0x003a1d08, 0x00351a06, 0x002c1503, 0x00261403, 0x00221302, 0x001d1104, 0x001a1105, 0x00191407, 0x001c170b, 0x00160f03, 0x00180e02, 0x00140b00, 0x00190f02, 0x00201104, 0x00261606, 0x0033210e, 0x003f2812, 0x00472c16, 0x004c3017, 0x00513518, 0x00533414, 0x00523410, 0x00563412, 0x005a3413, 0x005a3311, 0x005b3210, 0x0059300e, 0x00582f0c, 0x0058300f, 0x005e3412, 0x00663a14, 0x006c3f13, 0x00714011, 0x00774012, 0x00784313, 0x007b4415, 0x007d4718, 0x007c4716, 0x007b4412, 0x00734014, 0x00663714, 0x00462105, 0x002e1402, 0x00261509, 0x00241409, 0x002a1508, 0x00321809, 0x003f2011, 0x004a2819, 0x00381808, 0x00341405, 0x00341405, 0x00321404, 0x00422518, 0x00332015, 0x00110e05, 0x0008120c, 0x0004120c, 0x0008100c, 0x00090f0c, 0x0008100b, 0x0005100b, 0x00051009, 0x00040f07, 0x00051008, 0x00051008, 0x00050d09, 0x00040c09, 0x00060d0a, 0x00060d0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f07, 0x00070f08, 0x00070f08, 0x00060f08, 0x00040f05, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00041008, 0x00041008, 0x00041008, 0x00050f08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00050d07, 0x00050d07, 0x00040c07, 0x00040c07, 0x00040d07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x00202308, 0x0024250b, 0x0024250b, 0x0024250c, 0x0026280c, 0x0026280b, 0x0026280b, 0x00292b0b, 0x0026280a, 0x00292b0b, 0x00292b0b, 0x00292b0a, 0x002c2d0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x002c2d0a, 0x002c2d0b, 0x00292b0b, 0x00292b0b, 0x0026280a, 0x00292b0b, 0x0026280a, 0x00292b0b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280c, 0x0024250c, 0x0024250b, 0x0024250b, 0x00202309, 0x001d2008, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c09, 0x00040c09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d09, 0x0008100d, 0x00161d1a, 0x002c322e, 0x00383d3c, 0x00383a3c, 0x003d3d3f, 0x00363636, 0x00323031, 0x00343032, 0x00383435, 0x00383434, 0x00363130, 0x00383232, 0x00393535, 0x003b3838, 0x00343332, 0x00343130, 0x00433f3e, 0x00645758, 0x00756162, 0x007f6966, 0x00816a65, 0x00836a66, 0x00826967, 0x00826968, 0x00806868, 0x007d6663, 0x006e5851, 0x0068514b, 0x00665048, 0x00644d44, 0x0061493c, 0x00644938, 0x00654b34, 0x00654b2f, 0x00634425, 0x00613f1e, 0x0065401c, 0x00663d1b, 0x00643b1a, 0x005f381a, 0x005c3819, 0x00593718, 0x00513415, 0x00442d12, 0x003c260e, 0x00301905, 0x002e1807, 0x002b1808, 0x002b1809, 0x002d190b, 0x002d1a0a, 0x00301e0a, 0x00341f08, 0x00372008, 0x003d240c, 0x0046290c, 0x004f2f0f, 0x005c3a19, 0x005e3815, 0x00683c14, 0x00714013, 0x00744110, 0x0076400b, 0x0078400c, 0x00743b0b, 0x006e390c, 0x006a3b0d, 0x0061360b, 0x00593109, 0x00542d0c, 0x0049240c, 0x00401f0b, 0x00381c08, 0x00311a06, 0x00291504, 0x00241303, 0x00201304, 0x001e1406, 0x001b1206, 0x00181208, 0x0017140b, 0x0018160f, 0x00141009, 0x00110d04, 0x000f0e07, 0x000a0a03, 0x000d0c06, 0x00140f09, 0x0018100b, 0x00170c01, 0x00231407, 0x002c1c08, 0x0038230b, 0x00442c10, 0x004c3113, 0x004c2e11, 0x00523113, 0x00543010, 0x00542e0f, 0x00542f0f, 0x00563010, 0x00593210, 0x005f3513, 0x00643911, 0x006c4013, 0x00744314, 0x00794314, 0x00794313, 0x007c4517, 0x007e481b, 0x007d4719, 0x007c4414, 0x00733f12, 0x006a3b14, 0x004b2708, 0x00341a04, 0x002c1a0b, 0x00281709, 0x002b1609, 0x0032180b, 0x00402011, 0x004c2819, 0x00421d10, 0x003e190c, 0x003c1808, 0x003d1907, 0x004c2b1c, 0x002f1c10, 0x00121008, 0x0008120e, 0x0005130c, 0x0008100d, 0x0009100c, 0x0008100b, 0x0005110b, 0x0006100b, 0x00041009, 0x00051009, 0x00051009, 0x00060d0b, 0x00050d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060f07, 0x00060f08, 0x00060e08, 0x00060f08, 0x00040f05, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040f08, 0x00021008, 0x00021008, 0x00021008, 0x00041008, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040d06, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c09, 0x00191c09, 0x001d2008, 0x00202308, 0x00202308, 0x0020230a, 0x0024250b, 0x0024250b, 0x0026280b, 0x00292b0b, 0x00292b0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x002d2f0b, 0x0030310c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x002d2f0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x00292b0a, 0x00292b0a, 0x002c2d0a, 0x00292b0b, 0x00292b0b, 0x0026280b, 0x0026280c, 0x0024250c, 0x0024250b, 0x00202309, 0x00202308, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f09, 0x00060e08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c09, 0x00040c09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00040d08, 0x00040d08, 0x00040d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d06, 0x00050d06, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00070c07, 0x00070c07, 0x00050c07, 0x00050c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00060e0a, 0x00060e0a, 0x00060e0a, 0x00060f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050e08, 0x00050e08, 0x00050d09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d09, 0x00040d09, 0x00040d09, 0x00040d09, 0x00040d09, 0x00040d09, 0x00050e0a, 0x000b1410, 0x00141c18, 0x00272f2a, 0x00383d39, 0x00393c3c, 0x00404040, 0x00393838, 0x00343132, 0x00343032, 0x00373233, 0x003d3836, 0x003d3836, 0x003b3735, 0x003d3a39, 0x00373534, 0x00383635, 0x00373332, 0x00454040, 0x0066595b, 0x00766363, 0x007f6866, 0x00826b66, 0x00846c67, 0x00826968, 0x00836a69, 0x00846c6a, 0x007d6560, 0x006e5850, 0x00654f47, 0x00644d45, 0x00614b43, 0x0060483a, 0x00624834, 0x0064472e, 0x00634526, 0x00654420, 0x00603f1a, 0x005e3a15, 0x005f3b14, 0x005e3816, 0x00583416, 0x004d2d11, 0x0043250c, 0x00341c04, 0x00241400, 0x00231304, 0x001a0b00, 0x00201105, 0x00211207, 0x00231409, 0x0025160b, 0x0027180b, 0x00281909, 0x002c1b08, 0x00301c08, 0x00341e0a, 0x00381e07, 0x0043240a, 0x00543113, 0x00613c19, 0x006f421a, 0x00784417, 0x00784210, 0x007b410b, 0x007c420c, 0x00783f0c, 0x00743d0a, 0x00703e0b, 0x00693908, 0x0062340c, 0x0059300d, 0x0049240b, 0x003e1d0b, 0x00301a07, 0x00281403, 0x00241304, 0x00221207, 0x0022150b, 0x001d1108, 0x001c1109, 0x001f150d, 0x00231a14, 0x002c231c, 0x00211811, 0x001d140d, 0x0014100c, 0x0010110f, 0x00292825, 0x00120f0c, 0x001c130f, 0x0020140d, 0x002c1d14, 0x00261507, 0x00200d00, 0x00281300, 0x00321b04, 0x0039200c, 0x003f240c, 0x0042250c, 0x0045270c, 0x0049280c, 0x004e2c10, 0x00563011, 0x00603712, 0x00643910, 0x006c3f10, 0x00754312, 0x00794210, 0x007a4312, 0x007c4517, 0x007e471b, 0x007d461b, 0x007c4315, 0x00713c10, 0x006d3d13, 0x00522d09, 0x003a1d02, 0x00311c09, 0x002c190b, 0x002c170b, 0x0031180a, 0x003f1f10, 0x004c2819, 0x004f2618, 0x00471d0d, 0x00431908, 0x004d2412, 0x00533020, 0x0028170e, 0x0010110d, 0x0009110f, 0x0008110f, 0x00081010, 0x0009100f, 0x0007100c, 0x0005110b, 0x0006110b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f0b, 0x00050d0a, 0x00050d0a, 0x00050d0a, 0x00050d09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040f07, 0x00040f07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d09, 0x00040d09, 0x00040e0a, 0x00040e0a, 0x0005100a, 0x00050f0a, 0x00040f09, 0x00040e08, 0x00040f08, 0x00041008, 0x00041008, 0x00041008, 0x00040f08, 0x00060e09, 0x00050d09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060d08, 0x00060d08, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d06, 0x00050d06, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e08, 0x00040e08, 0x00040e08, 0x00040e08, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c04, 0x00060c04, 0x00060c04, 0x00060c05, 0x00050c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x0020230a, 0x0024250c, 0x0026280c, 0x0026280b, 0x00292b0a, 0x00292b0a, 0x002d2f0a, 0x002d2f0b, 0x0030310c, 0x0030310c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0034350c, 0x0034350c, 0x0032330c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0b, 0x0026280a, 0x0026280b, 0x0024250b, 0x0024250b, 0x00202309, 0x00202308, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c09, 0x0014180a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e0b, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x0008100c, 0x000d1510, 0x001c2420, 0x00323834, 0x0030322f, 0x00383735, 0x003f3a3c, 0x00342e30, 0x00363031, 0x00363030, 0x00403837, 0x00413c39, 0x00373430, 0x00393837, 0x003a3837, 0x00393535, 0x00383333, 0x00464040, 0x0066595b, 0x00776464, 0x007f6867, 0x00836b66, 0x00856c68, 0x00836a68, 0x00836a69, 0x00806766, 0x00765e58, 0x0071594f, 0x006b5248, 0x00674e44, 0x00644c3f, 0x00644a39, 0x00634631, 0x0064452b, 0x00634224, 0x0060401c, 0x00593916, 0x00553713, 0x00563815, 0x00482b0d, 0x00381f05, 0x00291502, 0x001c0d00, 0x00140900, 0x00130b03, 0x00140c04, 0x00171007, 0x001c140a, 0x0024170e, 0x0023150c, 0x0021140a, 0x0021140a, 0x00241409, 0x0028170b, 0x002b170a, 0x00311b0d, 0x00391e0d, 0x00462711, 0x00543114, 0x0068401f, 0x00784822, 0x00824c1f, 0x00884c1a, 0x008f5018, 0x00915118, 0x008c4f15, 0x00884c13, 0x00844c11, 0x007b440d, 0x006b370a, 0x005f300b, 0x00512a0c, 0x00432109, 0x00331b07, 0x00291502, 0x00281404, 0x00251508, 0x0023140b, 0x00201009, 0x0022110b, 0x00281810, 0x00302015, 0x003d2d21, 0x00372619, 0x002e1c10, 0x002c1f14, 0x00251d14, 0x002c2118, 0x002c1e12, 0x002d1c0d, 0x003b2113, 0x00482e1c, 0x00402814, 0x0037200b, 0x002c1401, 0x00291000, 0x002f1705, 0x00321a06, 0x00341a06, 0x00391d06, 0x0048270f, 0x004f2c12, 0x005a3310, 0x00653b14, 0x006a3d10, 0x00704010, 0x00774410, 0x007b4410, 0x007b4313, 0x007c4417, 0x007f471a, 0x007d461b, 0x007b4216, 0x00713c0f, 0x006d3c10, 0x005c330c, 0x00401f00, 0x00361b05, 0x002e1909, 0x002f190d, 0x0033190c, 0x0040200f, 0x004e2916, 0x00562c18, 0x004c200d, 0x00491d09, 0x005d311c, 0x004e2c1a, 0x001f120c, 0x000e1311, 0x000a120f, 0x000c1010, 0x00091111, 0x00091110, 0x0008110e, 0x0006120b, 0x0006120a, 0x0004100a, 0x0005110b, 0x0005110b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040f07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060d03, 0x00060d04, 0x00060c06, 0x00040b04, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280c, 0x0026280b, 0x00292b0a, 0x002c2d0a, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0034350c, 0x0036370c, 0x0036370c, 0x0036370c, 0x0036370c, 0x0036370b, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0036370c, 0x0036370c, 0x0036370c, 0x0038380c, 0x0038380c, 0x0036370c, 0x0034350c, 0x0034350c, 0x0034350c, 0x0032330c, 0x0034350c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x00292b0a, 0x00292b0b, 0x0026280b, 0x0024250b, 0x0024250b, 0x00202309, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e0b, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040c08, 0x00040c08, 0x00050e09, 0x0008100b, 0x0009110c, 0x00141c17, 0x002b302c, 0x0030332e, 0x00343330, 0x00423b3b, 0x00312828, 0x00322828, 0x00322928, 0x00372e2c, 0x00403935, 0x003d3938, 0x003c3a39, 0x003c3c3b, 0x003b3838, 0x00373131, 0x00484142, 0x00655658, 0x00796464, 0x00806a68, 0x00846b67, 0x00866c69, 0x00846a68, 0x00826868, 0x007c6262, 0x00735954, 0x00705649, 0x006c5345, 0x00684d40, 0x00654a3b, 0x00644837, 0x005e432f, 0x00593d24, 0x00553920, 0x0054381c, 0x004c3316, 0x0041280c, 0x002e1500, 0x00261200, 0x001c0d01, 0x00170c03, 0x00100a04, 0x001d1a19, 0x001f1c1c, 0x00120e08, 0x00181104, 0x00241a0a, 0x002d2011, 0x0028170c, 0x0026160e, 0x0022130c, 0x00211108, 0x00261409, 0x00281409, 0x002d180b, 0x003c2010, 0x004b2a14, 0x00553315, 0x006e4623, 0x00825029, 0x008a5226, 0x0092551f, 0x009a581a, 0x009c5b18, 0x00985615, 0x00945314, 0x00905014, 0x00844a10, 0x00733a09, 0x00633206, 0x00562c09, 0x00482407, 0x003a1c04, 0x00301701, 0x002f1804, 0x002c1706, 0x002b1608, 0x002c1508, 0x002d1408, 0x002e1508, 0x00331b0b, 0x003f2414, 0x00402715, 0x00361e0c, 0x003b2310, 0x00402812, 0x004a3017, 0x004f3217, 0x00543418, 0x00613c20, 0x00654224, 0x00613f1e, 0x00583816, 0x004e2c11, 0x0046250c, 0x00412008, 0x0044240a, 0x00442309, 0x004a2409, 0x004e2608, 0x00582c0d, 0x0062340d, 0x006c3d0f, 0x00744012, 0x00774310, 0x007b4511, 0x007c4511, 0x007c4512, 0x007c4416, 0x007d4519, 0x007d461b, 0x007c4318, 0x00733c10, 0x006f3c10, 0x0061340c, 0x00482300, 0x00391c04, 0x00301907, 0x00311b0e, 0x00351b0c, 0x003f1f0c, 0x004d2811, 0x00583017, 0x0050240c, 0x004b2006, 0x005f341a, 0x00462512, 0x001c130c, 0x000c1513, 0x00081310, 0x000c1210, 0x00091213, 0x000a1211, 0x0008120f, 0x0007130c, 0x0006120b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040f07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060d04, 0x00060c06, 0x00060c07, 0x00040b05, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280b, 0x00292b0b, 0x002c2d0a, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0032330c, 0x0034350c, 0x0038380c, 0x0038380c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x003b3c0d, 0x003b3c0d, 0x003b3c0c, 0x003b3c0d, 0x003b3c0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003b3c0d, 0x003b3c0d, 0x003c3e0d, 0x003b3c0c, 0x003c3e0d, 0x003b3c0d, 0x003b3c0d, 0x00393b0d, 0x003b3c0d, 0x00393b0c, 0x0038380c, 0x0038380c, 0x0036370c, 0x0036370c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x002c2d0a, 0x00292b0b, 0x0026280b, 0x0024250b, 0x0020230a, 0x00202309, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e0b, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00050d09, 0x00050d08, 0x0009110d, 0x000c140f, 0x0020241f, 0x0032332f, 0x00312f2b, 0x00443938, 0x00302423, 0x00281d1a, 0x002a1f1b, 0x0028201c, 0x0038302d, 0x0045403f, 0x00403e3f, 0x00404040, 0x003d3a3b, 0x00383133, 0x004c4444, 0x00645555, 0x00796564, 0x00806967, 0x00846b68, 0x00866c6a, 0x00846b68, 0x00836768, 0x007e6363, 0x00745954, 0x006c5144, 0x00674c3c, 0x00684b3c, 0x00634537, 0x005e402f, 0x00543925, 0x004d3420, 0x00432c17, 0x0034200b, 0x002b1904, 0x002e1c08, 0x00301e09, 0x0033200f, 0x00291b0c, 0x0022170d, 0x0019140c, 0x0022201f, 0x00242322, 0x00261f17, 0x00231808, 0x003a2b16, 0x003a2a15, 0x002a1706, 0x00251207, 0x00210f06, 0x00211006, 0x00271408, 0x002c1709, 0x002e1808, 0x003e2110, 0x004e2d18, 0x005b3518, 0x00724926, 0x0085532c, 0x008c5526, 0x00985c24, 0x00a3621e, 0x00a7641a, 0x00a45e15, 0x00a15a18, 0x00995415, 0x008c4b10, 0x00783e09, 0x00683505, 0x005a2e07, 0x004f2806, 0x00432005, 0x00381900, 0x003b1d06, 0x003a1e0a, 0x003c1d0b, 0x003e1e0c, 0x003f1e0c, 0x003f1d0b, 0x003e1d09, 0x0046240f, 0x004d2c15, 0x0054321b, 0x0058361c, 0x005e3a1b, 0x00653e1c, 0x006a421e, 0x00683f1a, 0x00623813, 0x00613810, 0x00643b10, 0x0060380d, 0x005d3410, 0x005d3412, 0x005c3512, 0x005f3814, 0x00643816, 0x00693c16, 0x006b3a13, 0x006e3c13, 0x00744110, 0x007c4814, 0x00804915, 0x00824914, 0x00814813, 0x007f4812, 0x00804615, 0x007c4413, 0x007b4215, 0x007b4419, 0x00794318, 0x00723c12, 0x00703c11, 0x0064370b, 0x00502803, 0x00422106, 0x00371c08, 0x0033190a, 0x00341908, 0x003f1e08, 0x004d280e, 0x00583014, 0x005a2f10, 0x00502506, 0x005d3414, 0x003e2008, 0x001a140d, 0x00081311, 0x00071512, 0x000b1410, 0x00091213, 0x00091213, 0x00071310, 0x0007130d, 0x0006130c, 0x0005110b, 0x0005110b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040f07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c08, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280b, 0x00292b0b, 0x002d2f0a, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0036370c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x003c3e0d, 0x003e400d, 0x003e400c, 0x003e400c, 0x0040400d, 0x0040400d, 0x0041420d, 0x0040400d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0040400d, 0x0040400d, 0x0040400d, 0x0040400d, 0x0041420d, 0x0040400d, 0x0040400e, 0x0040400d, 0x003e400c, 0x003e400c, 0x003e400c, 0x003e400d, 0x003c3e0d, 0x003b3c0d, 0x00393b0d, 0x00393b0c, 0x0038380c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002c2d0a, 0x002c2d0b, 0x0026280b, 0x0026280b, 0x0024250c, 0x00202309, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c07, 0x0008100c, 0x0008100b, 0x00141a14, 0x002a2d28, 0x002c2924, 0x00413633, 0x00302520, 0x001e120c, 0x0021150f, 0x00231a13, 0x0038302c, 0x004a4545, 0x00444244, 0x00404042, 0x003e3a3b, 0x003e3738, 0x004f4544, 0x00655754, 0x00796765, 0x00806a68, 0x00846c6b, 0x00866c6c, 0x00846969, 0x00836664, 0x007f6360, 0x00765851, 0x006c503d, 0x00664834, 0x005d402c, 0x00583826, 0x004d311d, 0x00432a16, 0x003a2410, 0x00301d0b, 0x00332111, 0x00342313, 0x00392614, 0x0044301b, 0x004b341f, 0x00402912, 0x0034200b, 0x00312010, 0x00302416, 0x0038291c, 0x00342414, 0x0035200c, 0x00402811, 0x003c240b, 0x00301801, 0x00311a07, 0x00321c0a, 0x00301b0a, 0x00351e0c, 0x0038200c, 0x003a200a, 0x0044240f, 0x00543019, 0x005f3618, 0x00744826, 0x0087542e, 0x008f5728, 0x009c6025, 0x00a6661f, 0x00ab6618, 0x00a85f12, 0x00a55b14, 0x009e5414, 0x00924b10, 0x007c410a, 0x006d3807, 0x00633309, 0x00592f0a, 0x0050290a, 0x00482305, 0x004a260c, 0x004b280f, 0x004c2810, 0x004e2810, 0x004f2710, 0x00502810, 0x004f270c, 0x00502a0d, 0x00542c0d, 0x00582f10, 0x005c3312, 0x005f3510, 0x005e340d, 0x0060350c, 0x0063380f, 0x0060350c, 0x0063380e, 0x00653c0f, 0x0064380c, 0x0064370c, 0x0068390f, 0x006c3c11, 0x00714014, 0x007a4819, 0x00804b1b, 0x00804a17, 0x00854c17, 0x008a5118, 0x008c5218, 0x008b5017, 0x00884c16, 0x00864b14, 0x00824913, 0x00814814, 0x007c4414, 0x007a4113, 0x00784115, 0x00744014, 0x00703d12, 0x006e3c11, 0x0065380c, 0x00512802, 0x00452407, 0x003b1e08, 0x00341909, 0x00341909, 0x003c1c08, 0x004a260c, 0x00583012, 0x00643817, 0x005c3010, 0x005c3412, 0x00341901, 0x0016140b, 0x00081514, 0x00071614, 0x000b1510, 0x000a1314, 0x00081412, 0x00071410, 0x0008140f, 0x0004130c, 0x0005110b, 0x0005110b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00040e09, 0x00040d08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0a, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c08, 0x00060c08, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250c, 0x0026280b, 0x00292b0b, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003b3c0d, 0x003c3e0d, 0x003e400c, 0x0040400d, 0x0041420d, 0x0043440e, 0x0043440e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0043440e, 0x0043440e, 0x0041420e, 0x0041420e, 0x0040400d, 0x0040400d, 0x003e400c, 0x003c3e0c, 0x003c3e0d, 0x00393b0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0b, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0024250c, 0x00202308, 0x00202308, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x0006100a, 0x000c130e, 0x0020241c, 0x002c2c24, 0x003e3731, 0x003e342e, 0x0024180f, 0x001f1208, 0x00281c14, 0x00382d2c, 0x00494444, 0x00464448, 0x00444146, 0x00403b3f, 0x003f3736, 0x004e4340, 0x006d5e5b, 0x007c6b67, 0x007f6a68, 0x00846c6c, 0x00886d70, 0x00866b6c, 0x00846865, 0x0081645c, 0x00765548, 0x006c4b34, 0x0066422c, 0x005c3822, 0x0054321b, 0x0043270f, 0x003e240f, 0x00462e1b, 0x004e3826, 0x00533b2c, 0x00593f2e, 0x005b3e28, 0x005e4025, 0x00614223, 0x00644424, 0x00644524, 0x00634122, 0x00603f20, 0x005c3c1f, 0x0059381f, 0x00512f18, 0x004c2813, 0x0048220e, 0x00442009, 0x00422108, 0x00442509, 0x0045260c, 0x004c2810, 0x00502c12, 0x004e290d, 0x004f2a0d, 0x005f381a, 0x00683c1c, 0x00784725, 0x008b5632, 0x0094592d, 0x00a06228, 0x00a86822, 0x00ab6619, 0x00ac6417, 0x00ae6119, 0x00a95c1a, 0x009c5417, 0x00874a13, 0x00773f0d, 0x006b380c, 0x0063350d, 0x005c330d, 0x00592f0d, 0x00592e10, 0x005e3116, 0x005f3318, 0x005e3116, 0x005c3015, 0x00603419, 0x00603413, 0x00592e0a, 0x00582d07, 0x005a2f09, 0x005c300a, 0x005d300b, 0x005e320c, 0x005c340c, 0x005c360d, 0x005c350d, 0x005c340c, 0x0061350f, 0x00663710, 0x006f3c11, 0x00784415, 0x007c4414, 0x00844918, 0x008b4c17, 0x008e5015, 0x00945418, 0x00985719, 0x00985919, 0x00975718, 0x00935418, 0x008d5017, 0x00884d14, 0x00854913, 0x00834815, 0x007d4412, 0x007b4214, 0x00764114, 0x00713d11, 0x006c3c10, 0x00683a10, 0x0062370c, 0x00502904, 0x003f1d00, 0x00371802, 0x0034180a, 0x00341910, 0x00391a0c, 0x0048240e, 0x00562e10, 0x00663918, 0x00653816, 0x00603718, 0x00331a04, 0x0013130c, 0x00071615, 0x00081517, 0x000c1411, 0x000a1414, 0x00081412, 0x00071411, 0x0005130f, 0x0004130c, 0x0005120c, 0x0007110c, 0x0007110c, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00021009, 0x00021009, 0x00021009, 0x00030f09, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00051007, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0b, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0045470e, 0x0047480e, 0x0047480e, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0047480e, 0x0048490e, 0x0047480e, 0x0047480e, 0x0045470e, 0x0045470e, 0x0044450e, 0x0043440e, 0x0041420e, 0x0041420e, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x00292b0a, 0x0026280b, 0x0024250c, 0x00202308, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040d08, 0x00040f09, 0x0006100b, 0x00121911, 0x00242820, 0x0038342f, 0x00463e37, 0x0031241c, 0x00231208, 0x00291811, 0x003c302e, 0x004d4446, 0x0048444a, 0x00464148, 0x00423c40, 0x00403837, 0x004f4440, 0x006c5d58, 0x007b6a66, 0x00806b6a, 0x00846c6f, 0x00886e71, 0x00886e6f, 0x008a6c66, 0x00846257, 0x00744e3c, 0x006e4629, 0x00643c1f, 0x005d3518, 0x00542c0f, 0x00532f12, 0x005e3d23, 0x006c4c35, 0x006c4d39, 0x00694836, 0x0065412d, 0x00664027, 0x00653c20, 0x00643915, 0x00643a13, 0x00653c14, 0x00643c14, 0x00603810, 0x005c340f, 0x00593010, 0x00542b10, 0x00522911, 0x00522810, 0x00552c10, 0x0058300f, 0x00593311, 0x005a3210, 0x00603414, 0x00643716, 0x00623412, 0x00613713, 0x006b401c, 0x00734623, 0x007c4c29, 0x008e5834, 0x00985f33, 0x00a0642c, 0x00a86826, 0x00ad681d, 0x00af671a, 0x00af651a, 0x00aa5e19, 0x009c5514, 0x008d4d14, 0x007d420c, 0x00763f10, 0x006e3b0f, 0x00693b10, 0x0065390f, 0x0062340e, 0x00633411, 0x00673817, 0x006c3c1c, 0x006f401f, 0x006e401c, 0x0070411b, 0x006a3c14, 0x0063340d, 0x0060300a, 0x005f2e08, 0x005e3009, 0x005d300b, 0x005b300b, 0x005b320a, 0x0060350d, 0x0065380f, 0x006a3a12, 0x006f3d13, 0x00774415, 0x00804a18, 0x00874d1a, 0x008d501c, 0x00935417, 0x00955414, 0x00995716, 0x009b5915, 0x009c5915, 0x009a5616, 0x00945315, 0x008f5014, 0x008b4d13, 0x00864912, 0x00834815, 0x007e4514, 0x007b4214, 0x00754013, 0x00703d10, 0x0069390e, 0x0064380e, 0x005a3209, 0x004e2805, 0x003e1d02, 0x00381b07, 0x00321709, 0x0031180e, 0x00381c0d, 0x0046240f, 0x00562e0f, 0x00663a15, 0x00683c18, 0x005f3818, 0x002f1801, 0x0013140c, 0x00081716, 0x00081517, 0x000c1410, 0x000a1513, 0x00081412, 0x00051411, 0x0004140f, 0x0004130c, 0x0005130c, 0x0006100b, 0x0006100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00021009, 0x00021009, 0x00021009, 0x00030f09, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d04, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00060e08, 0x00070f08, 0x00050e08, 0x00040d07, 0x00050e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00051007, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180b, 0x00191c0a, 0x00191c08, 0x001d2008, 0x0024250b, 0x0024250b, 0x00292b0b, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0040400d, 0x0043440e, 0x0044450e, 0x0047480e, 0x0048490f, 0x0048490f, 0x00494a0f, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d10, 0x004c4d10, 0x004c4d10, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004c4d10, 0x004c4d10, 0x004c4d10, 0x004c4d10, 0x004d4e10, 0x004c4d10, 0x004c4d0f, 0x004c4d0f, 0x004b4c0f, 0x004b4c0f, 0x004b4c0f, 0x004b4c10, 0x00494a0f, 0x00494a0f, 0x0048490f, 0x0047480e, 0x0045470e, 0x0045470e, 0x0043440e, 0x0041420e, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x003b3c0d, 0x0038380c, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0a, 0x0026280b, 0x0024250c, 0x00202308, 0x001d2008, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040d09, 0x0002100b, 0x00030f09, 0x0008120b, 0x00181d16, 0x002c2c24, 0x00474039, 0x0043342c, 0x002d1911, 0x0028140f, 0x00402f2f, 0x00504449, 0x004a444c, 0x0048404a, 0x00433c42, 0x00413737, 0x004f433f, 0x006b5c57, 0x007a6964, 0x007f6a6a, 0x00826c6f, 0x00866e72, 0x008a6e70, 0x008d6c67, 0x00896152, 0x007e5038, 0x007b4c27, 0x00774721, 0x00764620, 0x0074441f, 0x00774826, 0x007b4e31, 0x007b5036, 0x00795038, 0x00774e36, 0x0071472e, 0x006f4123, 0x006c3e1b, 0x006b3c12, 0x006a3c0e, 0x00673b0c, 0x0064390b, 0x0064390c, 0x0064390d, 0x00643810, 0x00603311, 0x005d3010, 0x005d2f0c, 0x00653610, 0x006a3910, 0x006c3c10, 0x006b3b0f, 0x00703d11, 0x00733e11, 0x00703c0e, 0x00704010, 0x00734417, 0x00794920, 0x00815028, 0x00905c37, 0x00986034, 0x00a0642c, 0x00a96824, 0x00af691f, 0x00b0681c, 0x00b0671a, 0x00ae6418, 0x00a25a12, 0x00944e10, 0x0088470c, 0x00804411, 0x0078400f, 0x00713e0b, 0x006e3c0b, 0x006e3a0c, 0x006e3a10, 0x00703b12, 0x00744017, 0x00754018, 0x00784318, 0x007b471b, 0x007a461b, 0x00774318, 0x00744015, 0x00713e14, 0x006c390f, 0x0068380f, 0x0067390f, 0x00683b0e, 0x006a3b0d, 0x006d3c0e, 0x00723c10, 0x00764010, 0x007f4714, 0x00874e16, 0x008e5118, 0x00935418, 0x00975515, 0x00995714, 0x009d5915, 0x009e5914, 0x009e5914, 0x009c5713, 0x00985412, 0x00915012, 0x008c4e13, 0x00874912, 0x00844815, 0x007d4412, 0x00784012, 0x00743e12, 0x006e3b10, 0x0068380f, 0x0063370f, 0x0058310a, 0x00472404, 0x003c1e04, 0x00391d0b, 0x00301809, 0x00301a0e, 0x00341a0b, 0x0040210b, 0x00542d0c, 0x00673912, 0x006a3d15, 0x00603814, 0x002f1801, 0x0014140c, 0x00081716, 0x00091618, 0x000c1410, 0x00081412, 0x00061514, 0x00071411, 0x0006130f, 0x0004140f, 0x0006120e, 0x0006100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00021009, 0x00021009, 0x00021009, 0x00030f09, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040e04, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00051007, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x0048490f, 0x00494a0f, 0x004b4c0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00515110, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00515110, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x004f5010, 0x004f5010, 0x004d4e0f, 0x004d4e0f, 0x004c4d0f, 0x004c4d0f, 0x004b4c0f, 0x00494a0f, 0x0048490f, 0x0047480e, 0x0045470e, 0x0044450e, 0x0041420e, 0x0040400d, 0x003e400d, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0a, 0x0026280c, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040d09, 0x00030f0b, 0x00030f09, 0x00041008, 0x000d160d, 0x0020211b, 0x003c3630, 0x0050423b, 0x003c271f, 0x002f1813, 0x00463434, 0x0055484c, 0x004d464e, 0x0048414b, 0x00443c41, 0x00403536, 0x004c403c, 0x00695b54, 0x00796865, 0x007e696c, 0x00826c70, 0x00886e73, 0x008c6e70, 0x008f6c65, 0x008a5e4d, 0x00855437, 0x008a582c, 0x008b572c, 0x00885429, 0x00865128, 0x00844f28, 0x0084502f, 0x00835233, 0x00825335, 0x007e5034, 0x00784a2c, 0x00704320, 0x006c3f16, 0x00683c10, 0x00653c0d, 0x00653d0e, 0x00673d10, 0x00653c10, 0x0062380d, 0x0060360c, 0x0061350d, 0x00663810, 0x006f3e13, 0x00784417, 0x00784111, 0x007c4514, 0x007a4511, 0x007d4812, 0x007b440d, 0x007e4810, 0x00804c16, 0x00824f1d, 0x00825022, 0x0088562c, 0x00925d38, 0x00975f33, 0x00a0642b, 0x00aa6924, 0x00af681c, 0x00af6718, 0x00b36a1c, 0x00b1671a, 0x00a65d13, 0x00995110, 0x008e480c, 0x0088480f, 0x0080430c, 0x007b4109, 0x00784008, 0x007c430e, 0x007b4210, 0x00794210, 0x007c4614, 0x007c4412, 0x007c4413, 0x007b4412, 0x007d4714, 0x00814a18, 0x00854e1e, 0x00865120, 0x00824f1c, 0x007c4b18, 0x007b4c19, 0x007a4c18, 0x007c4a18, 0x007f4815, 0x00804814, 0x00854b16, 0x008b5016, 0x0094571a, 0x00935415, 0x00965414, 0x00985413, 0x009f5a18, 0x00a05a17, 0x00a05a14, 0x009e5914, 0x009c5713, 0x00975412, 0x00905111, 0x008d4f14, 0x00894c16, 0x00844917, 0x007e4413, 0x00784213, 0x00743f14, 0x006e3c11, 0x00683810, 0x00623710, 0x0055300a, 0x00442102, 0x003a1c05, 0x00371c0b, 0x0030180a, 0x00301a0c, 0x00341c0c, 0x0040220c, 0x00552d0b, 0x00683910, 0x006c3d14, 0x00603814, 0x00301801, 0x0014140c, 0x00081817, 0x00091618, 0x000b1510, 0x00081412, 0x00061514, 0x00071411, 0x0006130f, 0x0004140f, 0x0005130f, 0x0008130f, 0x0009120e, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040e04, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00051007, 0x00040e05, 0x00040e05, 0x00040d05, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004b4c0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00525310, 0x00535410, 0x00535410, 0x00535410, 0x00545510, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00545510, 0x00545510, 0x00545510, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00525310, 0x00525310, 0x00515110, 0x00515110, 0x00505010, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004c4d0f, 0x004b4c0f, 0x00494a0f, 0x0047480e, 0x0045470e, 0x0043440e, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0024250c, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x00141810, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060c0b, 0x00080c0b, 0x00080d08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00070c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00051008, 0x0008110b, 0x0010140c, 0x002c2821, 0x0051443c, 0x0048352c, 0x0039221c, 0x004c3735, 0x00584b4c, 0x004a4549, 0x00484348, 0x00423a3e, 0x00403534, 0x004b3f3a, 0x00685953, 0x00796867, 0x007d686e, 0x00826b71, 0x00886f74, 0x008d6f71, 0x00906b67, 0x00906454, 0x00946143, 0x00946031, 0x00955f2e, 0x00945b29, 0x00925525, 0x00905425, 0x0090542a, 0x008e542e, 0x008a512d, 0x0085502a, 0x007d4b22, 0x0077441b, 0x00703e14, 0x006c3b0e, 0x006b3a0d, 0x006a3b0c, 0x006a3a0d, 0x006a3a0d, 0x006a3a0e, 0x006a3c0e, 0x00734414, 0x007e4c1b, 0x008a531d, 0x00885019, 0x008c531c, 0x008c531c, 0x008a4f16, 0x00884c10, 0x008a4d0e, 0x00894d11, 0x00874d14, 0x00885020, 0x0089542b, 0x008d5b34, 0x00936039, 0x00955e33, 0x00a0642a, 0x00ac6a23, 0x00af681c, 0x00af6718, 0x00b2691c, 0x00b06419, 0x00a45b10, 0x009a5010, 0x0090490b, 0x008c490d, 0x008a4910, 0x00864810, 0x0080440e, 0x00814510, 0x00814512, 0x00844814, 0x00874c18, 0x00874d18, 0x00844a15, 0x00824814, 0x00824814, 0x00844916, 0x00844a19, 0x00884d1b, 0x00844b17, 0x00834b15, 0x00844c16, 0x00844c17, 0x00854c18, 0x00884c16, 0x008c4e17, 0x00935118, 0x00985418, 0x009b5618, 0x009c5816, 0x009e5b17, 0x00a05a18, 0x00a05c19, 0x00a15c18, 0x009e5915, 0x009c5814, 0x00985410, 0x00945310, 0x00905111, 0x008d4e14, 0x00874c15, 0x00834815, 0x007e4715, 0x00784214, 0x00703c14, 0x006c3911, 0x0066370f, 0x005f340c, 0x00512907, 0x00441f03, 0x003a1a04, 0x00371b0b, 0x0035190d, 0x00321809, 0x00371c0a, 0x00472412, 0x005f3313, 0x006c3c10, 0x00714115, 0x006a401c, 0x00331803, 0x0014140c, 0x00081817, 0x00091618, 0x000c1610, 0x00081513, 0x00071614, 0x00081413, 0x00081410, 0x00051310, 0x00061411, 0x00061311, 0x0005110f, 0x0008110d, 0x0008100d, 0x00070e0c, 0x00060d0b, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f0a, 0x00050e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x0049490f, 0x00605710, 0x00645a10, 0x00645b10, 0x00665d10, 0x00685e10, 0x00685e11, 0x00685f11, 0x00686011, 0x00696012, 0x00696012, 0x00696011, 0x00696111, 0x00696112, 0x00696112, 0x00696011, 0x00696011, 0x00686011, 0x00686012, 0x00686012, 0x00686012, 0x00685f12, 0x00685f11, 0x00686011, 0x00686011, 0x00686012, 0x00685f12, 0x00665e12, 0x00665f11, 0x00655e11, 0x00655e11, 0x00645d11, 0x00645c10, 0x00635b10, 0x00605810, 0x00545210, 0x004d4e10, 0x004d4e10, 0x004c4d0f, 0x004b4c10, 0x0048490f, 0x0045470e, 0x0044450e, 0x0041420e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0024250b, 0x0020230a, 0x001d2008, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060d09, 0x00080c09, 0x00080d09, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00080c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x000c100c, 0x00282620, 0x0041372e, 0x00524138, 0x00402a21, 0x0045322c, 0x004f4140, 0x00484042, 0x00494245, 0x0040393b, 0x00403534, 0x004b3f3a, 0x00665852, 0x00786867, 0x007c696f, 0x00816c72, 0x00897074, 0x008d7074, 0x008f6c6a, 0x00906557, 0x00946344, 0x00976336, 0x00996232, 0x00985f2b, 0x00995c28, 0x00995a28, 0x0097592a, 0x00915628, 0x008c5426, 0x00885325, 0x00814c1e, 0x007d481a, 0x007e4819, 0x007d4a19, 0x00784413, 0x00754210, 0x00774412, 0x00784514, 0x007e4b1b, 0x00855220, 0x008c5924, 0x00915d24, 0x00945d23, 0x00915b20, 0x00945b20, 0x00945c20, 0x0093571c, 0x00925516, 0x008f5213, 0x008e5115, 0x008c501b, 0x008c5426, 0x008c5732, 0x00905d3b, 0x0094603b, 0x00935d32, 0x009e6028, 0x00a86720, 0x00ae681b, 0x00ad6617, 0x00b2681d, 0x00af641b, 0x00a45a14, 0x0098510f, 0x00904a0c, 0x008c490e, 0x008a4910, 0x00884a13, 0x00884a13, 0x00884912, 0x00864811, 0x008a4d16, 0x008f521b, 0x0092541e, 0x008f521b, 0x008c5018, 0x008b4e16, 0x00894c17, 0x00874814, 0x00864a15, 0x00864b15, 0x00874c15, 0x00874c15, 0x00884c16, 0x008c5019, 0x008d5017, 0x00935219, 0x0098541b, 0x009a5619, 0x00a25c1d, 0x00a4601d, 0x00a5601c, 0x00a6601d, 0x00a6611d, 0x00a35e1a, 0x009f5a16, 0x00995512, 0x00945110, 0x00935212, 0x00905014, 0x008c4e17, 0x00874a18, 0x00834718, 0x007c4316, 0x00774015, 0x006d3912, 0x00683610, 0x0063340d, 0x005c310c, 0x004f2708, 0x00421c04, 0x00391906, 0x00371b0d, 0x00381c10, 0x00371b0b, 0x003a1a07, 0x00502813, 0x00673814, 0x00734010, 0x00784717, 0x00794c25, 0x00371c05, 0x0014140c, 0x00081817, 0x00091618, 0x000c1610, 0x00081513, 0x00071614, 0x00081413, 0x00081410, 0x00051310, 0x00071411, 0x00061411, 0x0005120f, 0x0008110d, 0x0008100d, 0x00070e0c, 0x00060d0b, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x0014180f, 0x0014180b, 0x0014180a, 0x001d200a, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x00494a10, 0x00836f10, 0x00c39c15, 0x00c69d15, 0x00c69e15, 0x00c69e15, 0x00c59f15, 0x00c59f15, 0x00c59f16, 0x00c59f16, 0x00c59f16, 0x00c59f16, 0x00c49f16, 0x00c49f16, 0x00c49f16, 0x00c49f16, 0x00c49f17, 0x00c49f17, 0x00c49e17, 0x00c49e17, 0x00c49e17, 0x00c49e17, 0x00c49e17, 0x00c49e16, 0x00c49e16, 0x00c49e16, 0x00c49e16, 0x00c39d17, 0x00c39d17, 0x00c39d17, 0x00c39d16, 0x00c29c16, 0x00c29c16, 0x00c29c15, 0x00c19c15, 0x00bd9815, 0x00b19014, 0x00967c13, 0x00665d10, 0x00505010, 0x004d4e0f, 0x004b4c0f, 0x00494a10, 0x0047480e, 0x0044450d, 0x0041420e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060d09, 0x00080c09, 0x00080d09, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00080c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x0008100a, 0x00252620, 0x00322b24, 0x00504238, 0x00543f34, 0x004c362f, 0x004f3f3b, 0x004a3e3e, 0x004c4343, 0x00403838, 0x00403634, 0x00483d3a, 0x00625653, 0x00736766, 0x00786870, 0x00806d74, 0x00877378, 0x008d727a, 0x00906e6f, 0x0091665c, 0x00936349, 0x0098633b, 0x009a6334, 0x00995f29, 0x009b5e25, 0x009d5e28, 0x00985823, 0x0093561f, 0x00915620, 0x008c551e, 0x008c5420, 0x008a511e, 0x00874f1a, 0x00854d18, 0x00854c16, 0x00864e17, 0x0089511b, 0x008b521d, 0x008b531d, 0x008d541f, 0x0090561d, 0x0090571c, 0x00905719, 0x0091581a, 0x0094591c, 0x00975c1e, 0x00965a1c, 0x00945616, 0x00935618, 0x0093551c, 0x00945826, 0x00925830, 0x008e5838, 0x00905c3f, 0x00935f3d, 0x00945e33, 0x009c6027, 0x00a8651e, 0x00ad681b, 0x00aa6314, 0x00b3691f, 0x00af641c, 0x00a25b14, 0x0095500e, 0x008e4c0e, 0x008a4c0f, 0x00894c10, 0x00884b10, 0x00884b10, 0x008a4b11, 0x008b4c12, 0x008d4e12, 0x00915217, 0x0095561a, 0x0098591d, 0x00995a1d, 0x00955619, 0x00925318, 0x008d4d16, 0x00884a14, 0x00884912, 0x00884a12, 0x008a4c15, 0x008f5019, 0x00905019, 0x00925018, 0x00975418, 0x009a5619, 0x009c561a, 0x00a05a1b, 0x00a15c1a, 0x00a4601c, 0x00a86320, 0x00a5601c, 0x00a35e1a, 0x00a05b18, 0x00995514, 0x00935012, 0x00925015, 0x008c4d14, 0x00874914, 0x00814514, 0x007d4214, 0x00784014, 0x00753f15, 0x006c3810, 0x0068350e, 0x0062350c, 0x005c330d, 0x004e280a, 0x003f1c04, 0x00351806, 0x00341c0f, 0x00381c0f, 0x003c1e0e, 0x00421f09, 0x005b2d13, 0x00734018, 0x00834d18, 0x00804b16, 0x007b4b20, 0x00402309, 0x0014150d, 0x00081818, 0x000a1719, 0x000c1713, 0x00091714, 0x00081717, 0x000b1415, 0x00091411, 0x00071411, 0x00081412, 0x00061411, 0x0005120f, 0x0008110d, 0x0008100d, 0x0008100c, 0x00050c0a, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280c, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x00645810, 0x00c49c14, 0x00cca215, 0x00cba116, 0x00caa216, 0x00caa216, 0x00cba216, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba216, 0x00cba217, 0x00cca316, 0x00cca316, 0x00cba216, 0x00c49d16, 0x00987e12, 0x005c5710, 0x004f5010, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450d, 0x0041420e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002d2f0b, 0x00292b0a, 0x0026280b, 0x0020230a, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130d, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00060d08, 0x00080d08, 0x00080d08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00080c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f0a, 0x0005100b, 0x00232721, 0x0028251d, 0x0042382c, 0x005e4a3f, 0x00523c32, 0x0054403c, 0x00504040, 0x004e4441, 0x00403835, 0x003d3434, 0x00433a38, 0x005c5452, 0x006f6466, 0x0074666e, 0x007c6c72, 0x00847177, 0x008c737c, 0x00907074, 0x00906a60, 0x0090644c, 0x0094603a, 0x00966032, 0x00996029, 0x009c5f24, 0x009f5d25, 0x009e5d24, 0x009c5d20, 0x00955818, 0x008f5416, 0x008f5419, 0x0090541c, 0x0092551c, 0x008f5118, 0x008e5017, 0x008e5016, 0x00905218, 0x0092541c, 0x0093541c, 0x0094551c, 0x00905417, 0x00905415, 0x00905314, 0x0096581a, 0x00995c1c, 0x009c5f20, 0x009c5f1f, 0x009a5c1b, 0x0096591c, 0x00965822, 0x00965a2f, 0x00945b39, 0x008f583c, 0x00905c44, 0x00915f3f, 0x00935e33, 0x009c6128, 0x00aa6821, 0x00b16b1e, 0x00ab6316, 0x00b0651c, 0x00ac631c, 0x00a05b14, 0x0093500c, 0x008d4c0d, 0x00884a0d, 0x00874b0f, 0x00884b0f, 0x00884b10, 0x0088480c, 0x008e5011, 0x00935214, 0x00985718, 0x009a591a, 0x009d5c1d, 0x009c5c1b, 0x009b5a19, 0x009a581a, 0x0097561a, 0x00935219, 0x00905017, 0x008e4d14, 0x008d4d14, 0x00905017, 0x00905118, 0x00935016, 0x00985318, 0x009c5519, 0x009c5718, 0x00a05a1a, 0x00a15c1a, 0x00a45f1b, 0x00a35e18, 0x00a05a17, 0x009d5814, 0x00995513, 0x00955211, 0x00904e10, 0x008f4e13, 0x00894a12, 0x00834613, 0x007f4212, 0x007b4013, 0x00773f15, 0x00744015, 0x006b3910, 0x0068360e, 0x0063350c, 0x005d330e, 0x004b270b, 0x00391a04, 0x00311706, 0x00321b0f, 0x00381c0f, 0x003d1f0d, 0x004d260e, 0x00663416, 0x00814c1e, 0x0090581f, 0x00854e15, 0x00804e1f, 0x0046280d, 0x0014150d, 0x00081818, 0x000a1719, 0x000c1713, 0x00091714, 0x00081717, 0x000a1415, 0x00091411, 0x00071411, 0x00081412, 0x00061411, 0x0005120f, 0x0008110d, 0x0008100d, 0x0008100c, 0x0008100c, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f0a, 0x00050e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c10, 0x006c5f10, 0x00cca215, 0x00c59e15, 0x00927b13, 0x00927c13, 0x00927c14, 0x00927c14, 0x00937d14, 0x00947e14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f15, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00937d14, 0x00937d14, 0x00937d14, 0x00988014, 0x00a68914, 0x00bc9815, 0x00c9a116, 0x00cca316, 0x00cba216, 0x00b69315, 0x006f6210, 0x004f5010, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450d, 0x0041420e, 0x003c3e0c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050c06, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x0020241e, 0x00292a22, 0x00302b1e, 0x005c4c40, 0x00584139, 0x005d413f, 0x00593f40, 0x0054403f, 0x00433634, 0x003d3534, 0x00443b3c, 0x00514a4b, 0x006a6365, 0x0072676e, 0x007a6d73, 0x00817077, 0x00846d77, 0x00896c72, 0x008d6a67, 0x008e6454, 0x00915f41, 0x00925c37, 0x009a6030, 0x009c6027, 0x009e5e25, 0x00a36228, 0x00a66625, 0x00a36421, 0x009b5c1c, 0x0096581a, 0x0098581d, 0x0099581e, 0x0099581c, 0x00975519, 0x00965418, 0x00965519, 0x0096541a, 0x00945318, 0x00905013, 0x00905112, 0x00905212, 0x00975718, 0x009c5c1c, 0x009f5e1f, 0x00a26121, 0x00a1601e, 0x009c5e1c, 0x00995c20, 0x00965c2a, 0x00945d3b, 0x00935d46, 0x008e5a49, 0x008e5e4c, 0x00905f44, 0x00915c34, 0x009a5f28, 0x00a66520, 0x00ab641a, 0x00ab6119, 0x00aa6218, 0x00a96119, 0x00a05c14, 0x0092500c, 0x008b4a0b, 0x0087480c, 0x00864a0f, 0x00864a10, 0x00884a10, 0x008c4c11, 0x00905013, 0x00965314, 0x009b5815, 0x009d5a15, 0x00a05c16, 0x00a3601a, 0x00a35f1c, 0x00a15d1c, 0x009f5c1c, 0x009e5b1f, 0x009c591d, 0x009b581c, 0x00985519, 0x00985418, 0x0099561a, 0x009d581c, 0x00a15d20, 0x009e5a1c, 0x009f5919, 0x00a35d1c, 0x00a15c1a, 0x00a05b18, 0x00a05917, 0x009b5514, 0x00975411, 0x0092500e, 0x00904e0c, 0x008b4b0c, 0x0088480c, 0x0084450f, 0x007f4412, 0x007b4213, 0x00774114, 0x00723f15, 0x006d3c13, 0x00683910, 0x0064360e, 0x00633410, 0x005d3210, 0x004a260c, 0x00351802, 0x002e1605, 0x0030190c, 0x00381c0e, 0x00472411, 0x00592e11, 0x0074401c, 0x00904f20, 0x009c581b, 0x008f5213, 0x00814c1b, 0x004c2d12, 0x0013140b, 0x00091818, 0x00091618, 0x000c1512, 0x000a1714, 0x00071518, 0x00081416, 0x00081411, 0x00071411, 0x00051310, 0x00051310, 0x00061310, 0x0008120e, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0a, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003e400d, 0x0041420d, 0x0044450d, 0x0048490f, 0x004c4d0f, 0x006d6011, 0x00cca215, 0x00c29c15, 0x00595711, 0x00585810, 0x00595a12, 0x005b5b12, 0x005c5d11, 0x005c5d11, 0x005d5e12, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005e5f13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e13, 0x005d5e12, 0x005d5e12, 0x005c5d12, 0x005c5d12, 0x005c5d11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x00615e12, 0x007e7013, 0x00af8f14, 0x00caa216, 0x00cca316, 0x00c09a15, 0x00786911, 0x004f5010, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0043440e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x002c2d0b, 0x0026280c, 0x0020230a, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050c06, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c08, 0x00202420, 0x00252720, 0x00262418, 0x0052433a, 0x00644d46, 0x00684c48, 0x00583b3a, 0x00503938, 0x00423431, 0x00423a38, 0x00433c3b, 0x004c4645, 0x00696266, 0x00736870, 0x00796d74, 0x00807077, 0x00836d78, 0x00886c74, 0x008c6c6a, 0x008c6557, 0x008f5f48, 0x00905c3c, 0x009a6035, 0x009c602d, 0x009e5f29, 0x009d5d24, 0x00a05f20, 0x00a36420, 0x00a46424, 0x00a26123, 0x009c5b1d, 0x009c5a1c, 0x009c591c, 0x00985518, 0x00965416, 0x00955315, 0x00965416, 0x00935214, 0x00925114, 0x00945416, 0x00955414, 0x009b5a1a, 0x009d5c1c, 0x00a05f1d, 0x00a26220, 0x00a2601c, 0x009d5e1d, 0x00955920, 0x0092592c, 0x00945c40, 0x00915d4b, 0x0089584c, 0x008b5c4e, 0x008d5d44, 0x008e5a33, 0x00945b24, 0x00a05f1b, 0x00a65f17, 0x00a75d17, 0x00a65e16, 0x00a55e16, 0x009d5813, 0x00904e0b, 0x00874708, 0x0087480c, 0x0085480f, 0x00854910, 0x00884b13, 0x008c4c12, 0x00925014, 0x00975312, 0x009b5814, 0x009d5a14, 0x00a05d15, 0x00a36018, 0x00a3601a, 0x00a35f1d, 0x00a35f1f, 0x00a35f20, 0x00a05c1e, 0x00a05c1d, 0x00a05c1e, 0x00a05c1e, 0x00a25d1f, 0x00a25d1f, 0x00a15d1d, 0x009e5a1a, 0x009f5a18, 0x009d5816, 0x009a5413, 0x00995410, 0x00985311, 0x00924f0e, 0x0090500e, 0x008c4e0c, 0x00894c09, 0x00864808, 0x0084470c, 0x00824610, 0x007d4413, 0x00784314, 0x00764116, 0x00703f15, 0x006b3c14, 0x00653910, 0x0063360f, 0x00623411, 0x005c3111, 0x004c250f, 0x00341802, 0x002c1402, 0x0030180a, 0x00341908, 0x004a260f, 0x00653716, 0x007d451e, 0x0093501c, 0x009e5818, 0x008e500f, 0x007f4818, 0x004c2b10, 0x0014140b, 0x000a1818, 0x00091619, 0x000c1512, 0x000b1614, 0x00071518, 0x00081416, 0x00081511, 0x00071411, 0x00051310, 0x00051310, 0x00061310, 0x0008120e, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x006e6011, 0x00cca215, 0x00c29c16, 0x005c5910, 0x00595a12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5c11, 0x005b5b12, 0x005d5c12, 0x008b7713, 0x00c39c16, 0x00cca316, 0x00c29b15, 0x00746611, 0x004f5010, 0x004c4d0f, 0x0048490f, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130d, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050c06, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060d07, 0x001c1f1a, 0x00272821, 0x00232118, 0x00443831, 0x006f5853, 0x00694b46, 0x005a3936, 0x004d3732, 0x00483a34, 0x003b352f, 0x00403b38, 0x00454040, 0x00676164, 0x00736971, 0x00776b73, 0x007d6f76, 0x00806e7a, 0x00856c75, 0x00886b69, 0x00896558, 0x008e604e, 0x00905c42, 0x00965f3a, 0x009a5f31, 0x009f602e, 0x009f5f28, 0x009e5d22, 0x009d5d1c, 0x009e5e1c, 0x009f5f1d, 0x00a05e1f, 0x009e5c1d, 0x009c5819, 0x009a5618, 0x00985515, 0x00985515, 0x00975414, 0x009a5617, 0x009e5a1b, 0x00a25f1e, 0x00a05d1c, 0x00a05c1b, 0x00a05c1a, 0x00a05c1a, 0x00a05d1a, 0x009e5d1a, 0x009c5e1e, 0x00985d28, 0x00945c34, 0x00946047, 0x00936150, 0x00895c50, 0x00865b4f, 0x008c5c46, 0x008c5834, 0x00925824, 0x009c5c1a, 0x00a45d16, 0x00a65e17, 0x00a86018, 0x00a45c16, 0x0098540d, 0x008c4b08, 0x00874708, 0x0085460b, 0x0084480d, 0x0084490f, 0x00894c12, 0x008d4d13, 0x00935014, 0x00985413, 0x009a5713, 0x009d5a14, 0x009e5c13, 0x00a15e18, 0x00a25f19, 0x00a25e1d, 0x00a46020, 0x00a66221, 0x00a4601f, 0x00a5601f, 0x00a4611f, 0x00a76120, 0x00a76220, 0x00a66320, 0x00a25f1c, 0x00a05c1a, 0x009f5a16, 0x009c5614, 0x00985414, 0x00975111, 0x00945011, 0x008e4e0e, 0x008c4e0d, 0x00884c0c, 0x0086490a, 0x0084480a, 0x0081470f, 0x007e4511, 0x00784213, 0x00744014, 0x00704016, 0x006c3e17, 0x00653a14, 0x00623811, 0x00613612, 0x005e3413, 0x00593012, 0x004a230d, 0x00341501, 0x002a1201, 0x00301609, 0x003d1f09, 0x00542f10, 0x00703d18, 0x00854b1e, 0x00934f18, 0x0097510f, 0x00894809, 0x007b4417, 0x00482810, 0x0011130a, 0x00091715, 0x00081517, 0x000b1413, 0x00081514, 0x00081415, 0x00071314, 0x00051411, 0x00071411, 0x00051310, 0x00051310, 0x00061310, 0x0008120e, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x00494a0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005c5c12, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00606013, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x007a6c13, 0x00c09a15, 0x00cca316, 0x00bc9815, 0x00655d10, 0x004d4e10, 0x004b4c0f, 0x0048490f, 0x0044450e, 0x0040400d, 0x003c3e0c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x00292b0a, 0x0026280c, 0x00202309, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050c06, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050c07, 0x001b1e19, 0x00272822, 0x0023211a, 0x00362d28, 0x006e5754, 0x00674642, 0x00593531, 0x00533b32, 0x00473930, 0x0037322a, 0x003b3833, 0x00403c3a, 0x00605c5e, 0x0070666c, 0x0074696f, 0x00776b70, 0x007c6c75, 0x00826d74, 0x00836865, 0x00856458, 0x008c6053, 0x008e5d47, 0x00915c3b, 0x00945c32, 0x00995c2c, 0x009c5c28, 0x009c5b23, 0x009c5c1e, 0x009c5c1b, 0x009c5c19, 0x009d5c19, 0x009f5d1b, 0x00a05d1c, 0x009e5a18, 0x009e5a18, 0x00a05d1b, 0x00a05d1b, 0x00a25e1c, 0x00a25e1c, 0x00a6601f, 0x00a7621f, 0x00a4601c, 0x00a25d19, 0x009f5c18, 0x009f5c17, 0x009c5c1a, 0x009b5c1e, 0x00975c2a, 0x00945b37, 0x00915f46, 0x00905f50, 0x008c5f54, 0x00845b50, 0x00885a47, 0x008a5636, 0x00915627, 0x009c5a1d, 0x00a55d18, 0x00a9611b, 0x00ac641c, 0x00a15913, 0x0094500a, 0x008c4a08, 0x0088470a, 0x0085460c, 0x0084470d, 0x00854910, 0x008b4c13, 0x008e4c12, 0x00944f13, 0x00985314, 0x00975310, 0x009a5811, 0x009c5b12, 0x009e5c16, 0x00a05c18, 0x00a05c1c, 0x00a25e1d, 0x00a4601e, 0x00a4601e, 0x00a6601d, 0x00a5611d, 0x00a7611e, 0x00a7611e, 0x00a5621e, 0x00a4611d, 0x00a25f1a, 0x009f5a16, 0x009c5715, 0x00985414, 0x00945011, 0x00935013, 0x008d4e10, 0x00884c0e, 0x0084480a, 0x00824709, 0x00804508, 0x007e450e, 0x007b4311, 0x00764114, 0x00703e15, 0x006c3c15, 0x00683c16, 0x00643814, 0x00603712, 0x005e3412, 0x005c3414, 0x00583013, 0x0049220d, 0x00331401, 0x00281001, 0x002f1608, 0x0048280f, 0x00613818, 0x00764117, 0x00874919, 0x008d490e, 0x00904a06, 0x00864608, 0x007c4219, 0x00482710, 0x0011130b, 0x000b1615, 0x00081417, 0x000b1413, 0x00081514, 0x00081415, 0x00071314, 0x00051412, 0x00071411, 0x00051310, 0x00051310, 0x00061310, 0x0008120f, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x007c6e13, 0x00c49e16, 0x00cca316, 0x00ab8c14, 0x00545210, 0x004d4e0f, 0x00494a10, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d08, 0x00040d08, 0x00040d08, 0x00040c09, 0x00040c0a, 0x00060d0b, 0x00060d0a, 0x00070d09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080d09, 0x00080c09, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00060d09, 0x00060d09, 0x00060d09, 0x00060d09, 0x00060d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060d07, 0x00070d08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040c06, 0x00171c15, 0x00282b24, 0x0021201a, 0x002d2824, 0x006c5657, 0x00684642, 0x00653f2c, 0x00644431, 0x004c382c, 0x003c342f, 0x003b3833, 0x003c3836, 0x005a5458, 0x006b6268, 0x0073686d, 0x0073666b, 0x00786970, 0x007c696e, 0x007f6463, 0x00826259, 0x00886053, 0x008b5c48, 0x008d5a3d, 0x008e5833, 0x0093582a, 0x00945623, 0x00985822, 0x0098581f, 0x00975818, 0x00995c17, 0x009f5f19, 0x00a2601b, 0x00a35d1c, 0x00a35e1c, 0x00a45f1d, 0x00a35c1a, 0x00a05c18, 0x00a4601c, 0x00a6601d, 0x00a7611e, 0x00a4601c, 0x00a45f1b, 0x00a35f1b, 0x009f5c1a, 0x009c5918, 0x00995a19, 0x00985920, 0x00965c2d, 0x00935c38, 0x00905c44, 0x008d5c4d, 0x008b5d52, 0x00875c52, 0x00885a48, 0x008a5638, 0x00905628, 0x009c5c1f, 0x00a5601b, 0x00ac641c, 0x00ab631b, 0x00a15813, 0x00944f09, 0x008c4a08, 0x0088470a, 0x0087480c, 0x0084480e, 0x00854910, 0x008a4c11, 0x008d4c11, 0x00934e12, 0x00975113, 0x00975312, 0x00975411, 0x009a5814, 0x009d5c17, 0x009f5c19, 0x00a05c1a, 0x00a15d1c, 0x00a45f1c, 0x00a4601c, 0x00a7611d, 0x00a7621c, 0x00a5601b, 0x00a6601d, 0x00a6601d, 0x00a4601c, 0x00a05c18, 0x009d5915, 0x009a5714, 0x00975312, 0x00935011, 0x00905113, 0x008c4f11, 0x00864a0e, 0x0083480c, 0x0082450a, 0x0080440b, 0x007c4410, 0x00784212, 0x00724016, 0x006e3d17, 0x006c3d18, 0x00653917, 0x00603513, 0x00603514, 0x005e3413, 0x005d3414, 0x00593013, 0x0049220d, 0x00331403, 0x00281001, 0x00301807, 0x00533012, 0x006c3f18, 0x007c4415, 0x00864814, 0x008c4b10, 0x008c4806, 0x0087460c, 0x007c421a, 0x0044250e, 0x0011130a, 0x000a1614, 0x00081516, 0x000a1513, 0x00081513, 0x000a1414, 0x00081414, 0x00071412, 0x00081210, 0x00081110, 0x00081110, 0x0006100f, 0x0005100e, 0x0005100e, 0x0005100e, 0x0005100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0a, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e08, 0x00040e08, 0x00040d08, 0x00040d08, 0x00050e08, 0x00060e08, 0x00050e08, 0x00040e08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00050c08, 0x00060c08, 0x00060c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c09, 0x00040c09, 0x00040c08, 0x00040e08, 0x00040e08, 0x00040e08, 0x00040e08, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005d5b12, 0x005c5c11, 0x005c5d11, 0x00606013, 0x00606012, 0x00606012, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00626313, 0x00626313, 0x00626313, 0x00626313, 0x00626313, 0x00626313, 0x00626312, 0x00626312, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x00937c14, 0x00cba216, 0x00caa116, 0x00857212, 0x004d4e10, 0x004b4c0f, 0x0048490f, 0x0044450e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050f08, 0x00031008, 0x00031008, 0x00031008, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c09, 0x00060e0a, 0x00060e09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d07, 0x00060e06, 0x00060e06, 0x00040f06, 0x00031008, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00080d09, 0x00080d09, 0x00080d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040c06, 0x000e130c, 0x002b2c27, 0x00282621, 0x00282320, 0x00634f51, 0x0075524e, 0x00754c34, 0x006e4830, 0x00593e2e, 0x0044362e, 0x003f3831, 0x003c3836, 0x00534e50, 0x006c6368, 0x0073686c, 0x0071656a, 0x00786970, 0x007c686d, 0x007e6363, 0x007f6058, 0x00845d51, 0x00875b48, 0x0088573d, 0x00895534, 0x008d542a, 0x008f5322, 0x0091531f, 0x0092541c, 0x00925516, 0x00965816, 0x009c5a17, 0x009d5a17, 0x009e5917, 0x00a25c1b, 0x00a45e1c, 0x00a55e1c, 0x00a6601c, 0x00a6601d, 0x00a6601d, 0x00a4601c, 0x00a25c19, 0x009d5814, 0x009c5916, 0x009c5919, 0x00985619, 0x00955719, 0x00945620, 0x0094592f, 0x00935c38, 0x00905c43, 0x008e5c4c, 0x008a5c51, 0x00885e52, 0x008a5c49, 0x008b5839, 0x0091582a, 0x009c5c20, 0x00a6601c, 0x00ab641c, 0x00ab621b, 0x00a25812, 0x00954e0b, 0x00904c0c, 0x008b490d, 0x0088480d, 0x0085480f, 0x00854a0f, 0x00894c10, 0x008c4c10, 0x00904c13, 0x00944f13, 0x00955114, 0x00955412, 0x00985614, 0x009c5a17, 0x009e5c18, 0x00a05c18, 0x00a15c18, 0x00a35d1a, 0x00a45d1a, 0x00a4601c, 0x00a55f1a, 0x00a35e19, 0x00a4601c, 0x00a4601c, 0x00a3601b, 0x00a3601b, 0x009c5914, 0x009a5713, 0x00965212, 0x00915010, 0x008d4f11, 0x00894c10, 0x00874a0e, 0x0084470c, 0x0084440c, 0x0080430d, 0x007b4111, 0x00764014, 0x00703f16, 0x006b3c18, 0x00683916, 0x00623714, 0x005e3210, 0x005e3311, 0x005f3312, 0x005d3412, 0x005a3012, 0x0048230c, 0x00331405, 0x002b1104, 0x003a1f0e, 0x00593411, 0x0078481c, 0x00824915, 0x00834712, 0x0085470e, 0x008d4b0e, 0x00884811, 0x007a431a, 0x0040220b, 0x0012140a, 0x000b1514, 0x00091516, 0x000a1513, 0x00081513, 0x000a1414, 0x00081414, 0x00071412, 0x00081110, 0x00081110, 0x00081110, 0x0006100e, 0x00051010, 0x0005100e, 0x0005100e, 0x0005100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050c08, 0x00070c08, 0x00080c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005c5c12, 0x005c5d11, 0x00606013, 0x00606012, 0x00606012, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00626314, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00626313, 0x00626312, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x005e5f13, 0x005c5d11, 0x005c5c11, 0x00605c12, 0x00b79515, 0x00cca316, 0x00b69315, 0x00595510, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00141809, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050f08, 0x00031008, 0x00031008, 0x00031008, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d07, 0x00060e06, 0x00060e06, 0x00040f06, 0x00031008, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00050d07, 0x00040e08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040d07, 0x00090e08, 0x00232620, 0x0024241e, 0x0024201a, 0x005a4a49, 0x007c5d58, 0x00754c38, 0x0070472d, 0x0066432d, 0x00523929, 0x0045372c, 0x00403935, 0x004c484a, 0x00686265, 0x0070666a, 0x0070646a, 0x0075656c, 0x0078656a, 0x007d6264, 0x007f605c, 0x00825c52, 0x00845948, 0x0085563d, 0x00865432, 0x00885128, 0x00894f20, 0x008d501d, 0x008f501c, 0x00935519, 0x00945717, 0x00985616, 0x00985513, 0x009b5614, 0x009f5816, 0x00a05a17, 0x00a15b14, 0x00a45d18, 0x00a45f1a, 0x00a45f1b, 0x00a35e1a, 0x00a25c19, 0x00a15c18, 0x00a05c1b, 0x009a5818, 0x00975618, 0x0094571b, 0x00945621, 0x0092592f, 0x00935c3a, 0x008f5b41, 0x008e5c49, 0x008b5d50, 0x00885f50, 0x008c5e49, 0x008c5a3c, 0x0092592c, 0x009f6024, 0x00aa641f, 0x00af681f, 0x00b06820, 0x00a95f19, 0x009b5410, 0x00945010, 0x008e4d10, 0x008b4c12, 0x00874a10, 0x0083490e, 0x00864c10, 0x008a4c11, 0x008d4c14, 0x008f4d14, 0x00904f14, 0x00935013, 0x00965414, 0x009a5815, 0x009e5a18, 0x00a05a17, 0x00a05916, 0x00a15a17, 0x00a35b18, 0x00a45c18, 0x00a55c18, 0x00a45c18, 0x00a45e1b, 0x00a45f1b, 0x00a05d18, 0x009b5814, 0x009c5913, 0x00995512, 0x00955312, 0x00915011, 0x008d4e12, 0x008a4c10, 0x00874a0e, 0x0084460b, 0x0082420c, 0x00804110, 0x007a4014, 0x00743d15, 0x006e3d18, 0x00683b16, 0x00623713, 0x00603513, 0x005e3210, 0x005c3211, 0x005d3311, 0x005c3311, 0x00593010, 0x0049240c, 0x00351404, 0x00301404, 0x004c2c1a, 0x006c421e, 0x007b491b, 0x007d4411, 0x00783e0c, 0x007d420e, 0x008c4c14, 0x00894b15, 0x0078431a, 0x003a1e06, 0x0013140c, 0x000b1413, 0x00081415, 0x00081513, 0x00081513, 0x000a1414, 0x00081413, 0x00071412, 0x00081210, 0x00081110, 0x00081110, 0x0006100e, 0x00051010, 0x0005100e, 0x0004100d, 0x0004100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00050c08, 0x00070c08, 0x00080c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006e6011, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00626314, 0x00626313, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x005d5e12, 0x005c5d11, 0x005b5b12, 0x008c7914, 0x00caa116, 0x00cba216, 0x007b6a11, 0x004d4e10, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0036370c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0024250b, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040f08, 0x00031008, 0x00031008, 0x00031008, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d07, 0x00060e06, 0x00060e06, 0x00040f06, 0x00031008, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00080f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00061008, 0x00061008, 0x00050f08, 0x00050f08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00050e08, 0x00070d08, 0x001b1f18, 0x0022261f, 0x00222018, 0x004c423e, 0x007e6760, 0x00704937, 0x007d5034, 0x007a4f33, 0x0064422a, 0x004c3727, 0x00403833, 0x00474446, 0x00645e62, 0x006b6268, 0x0071656c, 0x0073656c, 0x00736165, 0x00786061, 0x007d605b, 0x00805b53, 0x00805748, 0x0082543c, 0x00825132, 0x00844f29, 0x00884f21, 0x008c501e, 0x008e501d, 0x0092541b, 0x00935518, 0x00955417, 0x00975414, 0x009b5514, 0x009e5814, 0x00a15c16, 0x00a45e16, 0x00a45f18, 0x00a15c18, 0x00a15c18, 0x00a05b18, 0x00a05b18, 0x009d5814, 0x009c5817, 0x00995718, 0x00955417, 0x0094541b, 0x00915423, 0x00905730, 0x00915b3c, 0x008e5a3f, 0x008e5c48, 0x008c5f4e, 0x0088604e, 0x008c5e48, 0x008f5c3d, 0x00945a2d, 0x00a16125, 0x00af6924, 0x00b46e23, 0x00b26a20, 0x00ab601b, 0x009c5411, 0x00965413, 0x00905012, 0x008c4e14, 0x00864c11, 0x0081490e, 0x0082490d, 0x00874c10, 0x00894c14, 0x00894c14, 0x00894d13, 0x008d4d12, 0x00945114, 0x00995314, 0x009e5616, 0x00a15818, 0x00a15816, 0x00a15815, 0x00a35a16, 0x00a45c18, 0x00a45c18, 0x00a25c17, 0x00a35c18, 0x00a25c18, 0x00a05b18, 0x009e5a15, 0x009c5812, 0x00985512, 0x00955312, 0x00925012, 0x008c4d11, 0x00894b10, 0x00874a0e, 0x00824509, 0x0080400c, 0x007f3e10, 0x00783e13, 0x00723b15, 0x006c3b16, 0x00653c15, 0x00633914, 0x00603513, 0x005e3410, 0x005c3311, 0x005c3311, 0x005c3110, 0x00582f0f, 0x004d280e, 0x003a1804, 0x003a1909, 0x0055301c, 0x006f421c, 0x00713d0f, 0x00713807, 0x006f3808, 0x00763c0d, 0x00854614, 0x00884a18, 0x00724016, 0x00331a01, 0x0013160e, 0x000b1413, 0x00081415, 0x00081412, 0x000a1513, 0x000b1412, 0x00081411, 0x00081412, 0x00081210, 0x00081110, 0x00081110, 0x0007100f, 0x00051010, 0x0005100e, 0x0004100d, 0x0004100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d06, 0x00040d06, 0x00050d06, 0x00070c06, 0x00080c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0047480e, 0x00494a10, 0x004d4e0f, 0x006e6011, 0x00cca216, 0x00c39d16, 0x00685f11, 0x00656012, 0x00686112, 0x00696412, 0x006a6414, 0x006b6513, 0x006b6513, 0x006b6513, 0x006c6613, 0x006c6613, 0x006c6613, 0x006c6613, 0x006c6613, 0x006c6713, 0x006c6813, 0x006c6713, 0x006c6713, 0x006c6713, 0x006c6713, 0x006c6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006d6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006a6614, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00616112, 0x00606012, 0x005e5f13, 0x005c5d11, 0x005c5c11, 0x00646012, 0x00c49e16, 0x00cca316, 0x009f8213, 0x004c4d10, 0x004c4d0f, 0x0048490f, 0x0044450d, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f09, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d06, 0x00040d06, 0x00050e07, 0x00050e07, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00050d07, 0x00050e06, 0x00050e06, 0x00050e06, 0x00050e08, 0x00050d09, 0x00050d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x0004100a, 0x0004100a, 0x00040f0a, 0x00040f0a, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f09, 0x00060e08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050e08, 0x00040e08, 0x00040f08, 0x00031008, 0x00040f09, 0x00050f08, 0x00050f08, 0x00050f08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050d07, 0x00060d08, 0x00060e08, 0x00060e09, 0x00050e09, 0x00050e09, 0x00040d09, 0x00060f09, 0x00060e09, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050f08, 0x00060e08, 0x00060d08, 0x00121812, 0x00222820, 0x00222118, 0x003e3834, 0x0076635e, 0x006e4e3c, 0x0081543b, 0x00815031, 0x006d4525, 0x00573a23, 0x0046382f, 0x00444041, 0x005f5b5f, 0x00686168, 0x006e646a, 0x0072646b, 0x00705e64, 0x00755e60, 0x00775c59, 0x007b5952, 0x007c5649, 0x007e543f, 0x007f5035, 0x0083502d, 0x00864f26, 0x008a5022, 0x008d5020, 0x008e521c, 0x00905218, 0x00965518, 0x00985618, 0x009d5817, 0x00a05b18, 0x00a25d17, 0x00a05c14, 0x009f5a14, 0x00a05c16, 0x00a05b18, 0x009e5915, 0x009e5915, 0x009f5917, 0x009c5818, 0x00975415, 0x00925215, 0x0090511b, 0x008e5121, 0x008c5430, 0x008d583c, 0x008f5d44, 0x008c5d4a, 0x008b5f50, 0x008b6150, 0x008d5f4b, 0x00905c41, 0x00975d32, 0x00a46228, 0x00b06924, 0x00b16c20, 0x00b1681e, 0x00b0661e, 0x00a55e16, 0x00985611, 0x00915313, 0x008c4e12, 0x00854a10, 0x0084480f, 0x0082480e, 0x00844910, 0x00854b13, 0x00854c15, 0x00854c14, 0x00884c11, 0x008d4d10, 0x00965014, 0x009c5215, 0x009d5415, 0x009d5514, 0x009f5714, 0x00a15917, 0x00a35b19, 0x00a25a18, 0x00a25b19, 0x00a35b19, 0x00a25c18, 0x009f5916, 0x009e5815, 0x009c5714, 0x00985411, 0x00945312, 0x00915010, 0x008a4c10, 0x0088480e, 0x0084460d, 0x0080430b, 0x007c3f0d, 0x00793c10, 0x00753e14, 0x006e3c15, 0x00693b16, 0x00653b17, 0x00643816, 0x00603514, 0x005d3411, 0x005c3311, 0x005c3311, 0x005c3210, 0x005a3111, 0x004e280f, 0x003d1a04, 0x00401a05, 0x005a301a, 0x00663512, 0x006c360b, 0x006d3608, 0x006c360d, 0x0070360d, 0x007e4012, 0x0081481b, 0x00663814, 0x002b1604, 0x00121510, 0x000b1412, 0x00081414, 0x00081412, 0x00081411, 0x000b1410, 0x00081410, 0x00071410, 0x00081210, 0x0008110f, 0x0008110f, 0x0007100e, 0x0008120f, 0x0007110f, 0x0005100c, 0x00040f0b, 0x0007110c, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x00050f0a, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040e0a, 0x00040e09, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f09, 0x00050f09, 0x00060f09, 0x00050e08, 0x00050e08, 0x00040f08, 0x00040f07, 0x00040f07, 0x00040f07, 0x00040f07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00040f07, 0x00040f07, 0x00040f07, 0x00040f07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f09, 0x00060e08, 0x00040d07, 0x00040d06, 0x00040d08, 0x00040d08, 0x00040d06, 0x00050c06, 0x00050d05, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00040d05, 0x00040e06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250b, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x00393b0c, 0x003c3e0c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004c4d0f, 0x006c6011, 0x00caa116, 0x00cba216, 0x00c69f16, 0x00c6a016, 0x00c6a017, 0x00c5a018, 0x00c5a018, 0x00c5a018, 0x00c5a018, 0x00c5a018, 0x00c5a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c49f18, 0x00c49f19, 0x00c49f19, 0x00c39f18, 0x00c39f18, 0x00c3a018, 0x00c3a018, 0x00c29f18, 0x00c29e18, 0x00c29e18, 0x00c29e18, 0x00bc9b18, 0x009e8716, 0x00696614, 0x00636414, 0x00626312, 0x00616112, 0x00606013, 0x00606013, 0x005e5f12, 0x005c5c11, 0x005c5b12, 0x00b49315, 0x00cca316, 0x00ae8d14, 0x004c4d10, 0x004c4d0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003c3e0c, 0x00393b0c, 0x0034350c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0024250b, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00070f0a, 0x00050d09, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x000b110b, 0x001b2219, 0x00212219, 0x00302c28, 0x006e625d, 0x00735a4b, 0x00835847, 0x00805032, 0x00744824, 0x00644023, 0x004a3428, 0x00443b3c, 0x005c585c, 0x00646068, 0x006b6369, 0x006e6169, 0x00706065, 0x00725d5f, 0x00745b59, 0x00785953, 0x007b584c, 0x007c5443, 0x007c513a, 0x00804f32, 0x00844e29, 0x00884f25, 0x008d5124, 0x008f5220, 0x0090531c, 0x0096571c, 0x00995819, 0x009c5919, 0x00a05c1a, 0x00a15d18, 0x00a05c15, 0x00a05c16, 0x00a15c18, 0x00a15c18, 0x009e5915, 0x009e5915, 0x009e5717, 0x00995415, 0x00945315, 0x00905014, 0x008d501a, 0x008b5023, 0x008d5634, 0x008d593f, 0x008b5c47, 0x00895c4c, 0x008b6051, 0x008d6354, 0x00916352, 0x00935f47, 0x00985e34, 0x00a66228, 0x00af6823, 0x00b26c1f, 0x00b46b1e, 0x00b0661a, 0x00a86114, 0x009c580f, 0x00955614, 0x008d4f11, 0x0086480e, 0x0082440d, 0x0080440c, 0x007f430c, 0x007c430c, 0x007a430c, 0x0079420c, 0x007e440c, 0x00854810, 0x008c4b14, 0x00914e15, 0x00955012, 0x00975310, 0x009b5514, 0x009d5618, 0x009e5718, 0x00a0581a, 0x00a35c1b, 0x00a45c1b, 0x00a35c1b, 0x00a05818, 0x009f5817, 0x009b5514, 0x00985412, 0x00945111, 0x008f4f0e, 0x00894a0f, 0x00884810, 0x0082430d, 0x007d400d, 0x00793f10, 0x00743c10, 0x00733f15, 0x006c3c18, 0x00683c17, 0x00653916, 0x00623714, 0x005e3414, 0x005c3211, 0x005c3311, 0x005c3110, 0x005a3010, 0x00583011, 0x004f280e, 0x00401b01, 0x00471e07, 0x005b2e17, 0x00653110, 0x00683208, 0x00683108, 0x006b3410, 0x00713711, 0x007a3c11, 0x007c451d, 0x005a3114, 0x00231206, 0x00101412, 0x00091514, 0x00081414, 0x00081414, 0x00081410, 0x000a120f, 0x0007130e, 0x0005130f, 0x0007120e, 0x0007110d, 0x0007110d, 0x0007110d, 0x0008110e, 0x0006100c, 0x0006100b, 0x00051009, 0x0007110b, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040d07, 0x00040d06, 0x00040c08, 0x00040c09, 0x00040d08, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0020230a, 0x00292b0b, 0x002c2d0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0048490f, 0x004c4d0f, 0x00535110, 0x009f8414, 0x00caa216, 0x00cba216, 0x00cba317, 0x00cba317, 0x00cba417, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cba419, 0x00a88d16, 0x00656414, 0x00626313, 0x00616112, 0x00616112, 0x00606012, 0x005e5f13, 0x005d5e11, 0x005c5c12, 0x00a78a14, 0x00cca316, 0x00b08f14, 0x004c4d10, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d06, 0x00040d06, 0x00040d06, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00070f0a, 0x00050d09, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00060e0a, 0x00060e09, 0x00070f08, 0x00111911, 0x001f211a, 0x00282823, 0x0068605b, 0x007d685e, 0x00846052, 0x007e5136, 0x007c4f28, 0x006e4624, 0x00503322, 0x00463835, 0x005c5559, 0x00645f68, 0x00696169, 0x006c6068, 0x006f6065, 0x00715e61, 0x00725c5b, 0x00745954, 0x0078584d, 0x007b5545, 0x007c523c, 0x007e4f34, 0x00814e2b, 0x00875027, 0x008c5226, 0x008e5322, 0x0090531f, 0x0096571f, 0x0098581c, 0x009b5718, 0x009e5a1b, 0x00a15e1b, 0x00a05c18, 0x00a05c16, 0x00a05c17, 0x00a15c18, 0x009d5814, 0x009d5816, 0x00985415, 0x00945214, 0x00904f14, 0x008b4c12, 0x00894e17, 0x00874d1f, 0x0085502c, 0x00845337, 0x00845641, 0x00855a4c, 0x00885f54, 0x008c6355, 0x00926657, 0x00926148, 0x00975e34, 0x00a56429, 0x00b06a25, 0x00b26c1f, 0x00b46a1c, 0x00b1661a, 0x00a85f14, 0x00a15b12, 0x00985613, 0x00904f11, 0x0088470d, 0x0081410b, 0x007e3f0a, 0x007b3c08, 0x00773c08, 0x00743c08, 0x00733c09, 0x00743c0a, 0x00773f0c, 0x007f4513, 0x00874a15, 0x008c4c12, 0x00904e10, 0x00945011, 0x00985216, 0x00995418, 0x00985315, 0x009c5819, 0x009f5818, 0x00a05818, 0x00a05819, 0x009e5718, 0x00995414, 0x00955212, 0x00905011, 0x008b4c0d, 0x0088490f, 0x00864610, 0x00804410, 0x007e4210, 0x00763d0e, 0x00703b0e, 0x00703e14, 0x006b3d17, 0x00663b15, 0x00633814, 0x00603513, 0x005c3311, 0x005c3211, 0x005d3412, 0x005b3010, 0x00582f0f, 0x00562f10, 0x004e290c, 0x00401c00, 0x0050280e, 0x005c3017, 0x0064300f, 0x00673109, 0x006a3309, 0x006b3410, 0x00733812, 0x00783c11, 0x0074411c, 0x004a290f, 0x00170d05, 0x000e1412, 0x00091413, 0x00071413, 0x00071413, 0x00081410, 0x0009120e, 0x0007130c, 0x0005130e, 0x0006110d, 0x0006100c, 0x0007100d, 0x0007100d, 0x00040e0b, 0x00040d0a, 0x0005100b, 0x0008110b, 0x00050f09, 0x0005100a, 0x0005100a, 0x00050f0a, 0x00050f0a, 0x00050f0a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e0a, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040d07, 0x00040d06, 0x00040d06, 0x00040d08, 0x00040d06, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c06, 0x00060c06, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0048490e, 0x004b4c0f, 0x004d4e0f, 0x00585410, 0x008b7612, 0x00957d13, 0x00967e13, 0x00978014, 0x00978014, 0x00988114, 0x00988214, 0x00998215, 0x009a8314, 0x009a8315, 0x009a8315, 0x009b8415, 0x009b8415, 0x009b8415, 0x009c8416, 0x009c8416, 0x009c8515, 0x009c8515, 0x009c8615, 0x009c8615, 0x009d8515, 0x009e8615, 0x009e8616, 0x009e8716, 0x009e8716, 0x009f8816, 0x009f8816, 0x009f8816, 0x009f8815, 0x00a08816, 0x00a08916, 0x00ba9918, 0x00cca519, 0x00c8a318, 0x00756c14, 0x00636414, 0x00626312, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5e11, 0x005c5c11, 0x00a08514, 0x00cca316, 0x00b09014, 0x004d4e10, 0x004f5010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x001d2009, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00060e08, 0x00060f06, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00070f0a, 0x00050d09, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e08, 0x000b130b, 0x00181d17, 0x00242720, 0x005a544f, 0x00816e6c, 0x007d5e59, 0x00785038, 0x007a4e28, 0x00784a25, 0x005f3c25, 0x0045332a, 0x00554c4e, 0x00645e68, 0x00676069, 0x006b6068, 0x006c5f65, 0x00705d60, 0x00705a58, 0x00725854, 0x0075584e, 0x00795747, 0x007a543f, 0x007c5036, 0x00804f2c, 0x00855128, 0x008a5329, 0x008d5425, 0x00905321, 0x0094561f, 0x0097561c, 0x009b591c, 0x009e5a1c, 0x009e5a1b, 0x009e5b18, 0x009c5814, 0x009d5814, 0x009e5915, 0x009b5612, 0x00985411, 0x00945214, 0x00904f14, 0x008a4c12, 0x0083460e, 0x00804711, 0x0080491a, 0x007c4924, 0x007e4e32, 0x007c4f3c, 0x007b5045, 0x0080584f, 0x00886055, 0x00906758, 0x0093644a, 0x00965f35, 0x00a6672c, 0x00b36e28, 0x00b26c20, 0x00b36a1c, 0x00b4671b, 0x00ac6117, 0x00a45c12, 0x009a5410, 0x00944f10, 0x0088450c, 0x00803f09, 0x007c3b08, 0x007c3c09, 0x007a3d0b, 0x00703607, 0x00693304, 0x00673204, 0x00673508, 0x006e3b0e, 0x00764010, 0x007e440f, 0x00884a10, 0x008f4d11, 0x00925014, 0x00945016, 0x00985418, 0x009a561b, 0x009c5818, 0x009c5818, 0x009b5518, 0x00985315, 0x00945011, 0x00904f10, 0x008c4d0f, 0x00894c0e, 0x00864810, 0x00834510, 0x007f4410, 0x007c4210, 0x00753f10, 0x00703c11, 0x006e3d14, 0x006a3d17, 0x00653a14, 0x00623713, 0x00603413, 0x005d3412, 0x005e3413, 0x005d3412, 0x005b3010, 0x00572e0d, 0x00552f0e, 0x004f2a0b, 0x00482102, 0x00572e10, 0x00613618, 0x00673411, 0x006c360e, 0x006f370e, 0x006e3813, 0x00713812, 0x00743c11, 0x00673a15, 0x00371d05, 0x00140e06, 0x000d1411, 0x00081412, 0x00051312, 0x00051312, 0x0008120f, 0x0009110d, 0x0007110c, 0x0006110d, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00040d0a, 0x0005100a, 0x0007110a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040d07, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d05, 0x00040e04, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c05, 0x00060c05, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c09, 0x00191c09, 0x001d2008, 0x0024250b, 0x0024250b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x0036370c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x00505010, 0x00525310, 0x00535411, 0x00555610, 0x00565711, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d13, 0x005d5e13, 0x005d5e13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606012, 0x00606012, 0x00606012, 0x00606013, 0x00606012, 0x00606012, 0x00616114, 0x00616114, 0x00616114, 0x00626314, 0x00626314, 0x00626314, 0x00636414, 0x00636414, 0x00736c14, 0x00c7a218, 0x00cca519, 0x00796f14, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x00606013, 0x005e5f12, 0x005c5c11, 0x00a08514, 0x00cca316, 0x00b09014, 0x004d4e10, 0x004f5010, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0036370c, 0x0034350c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e08, 0x00060f05, 0x00040e04, 0x00040e04, 0x00040e04, 0x00050d06, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d09, 0x00080e0a, 0x00060c08, 0x00080e0a, 0x00070c09, 0x00070c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060e0a, 0x00060e08, 0x00081008, 0x0010140e, 0x00242720, 0x004c4542, 0x00806e70, 0x007c5f5d, 0x00744f3c, 0x00774a28, 0x00794a26, 0x0069442c, 0x004e362d, 0x00514444, 0x00605860, 0x00666069, 0x006c6168, 0x006a5c62, 0x006e5c5e, 0x006c5859, 0x00705955, 0x0073584f, 0x0077584a, 0x00795644, 0x007a5139, 0x007e5030, 0x0083522c, 0x0088542b, 0x008c5427, 0x008e5523, 0x0090541f, 0x0093551c, 0x00965519, 0x00985418, 0x00985414, 0x00995413, 0x009c5715, 0x009c5615, 0x00995412, 0x00985411, 0x0092500e, 0x008c4c0f, 0x00884910, 0x0082450d, 0x007c400b, 0x00773e0b, 0x00723c0e, 0x006e3c16, 0x00784628, 0x00784934, 0x00784c3c, 0x007c5147, 0x00835a50, 0x008e6758, 0x0092674e, 0x00946038, 0x00a3662c, 0x00b06e27, 0x00b36d20, 0x00b3691c, 0x00b7691d, 0x00b06418, 0x00a45b12, 0x009c5410, 0x00954e11, 0x0089450c, 0x007d3b05, 0x007f3f08, 0x00925019, 0x0090501b, 0x008f501e, 0x00763b0d, 0x005f2800, 0x005f2e07, 0x0066360f, 0x006d3a11, 0x00733d0f, 0x007b400e, 0x0082450f, 0x00894a12, 0x008d4c14, 0x00904e14, 0x00945016, 0x00945214, 0x00945114, 0x00925013, 0x00914f11, 0x00915012, 0x008f4f11, 0x00884b0f, 0x00874b0f, 0x00834710, 0x0080440f, 0x007a400f, 0x00794110, 0x00743f12, 0x00703d12, 0x006c3d14, 0x006a3c16, 0x00653a14, 0x00623713, 0x00603513, 0x005d3412, 0x005e3413, 0x005f3414, 0x005b3110, 0x00552d0c, 0x00542e0d, 0x00502b0a, 0x004e2707, 0x005c3111, 0x00673a19, 0x006d3815, 0x00713914, 0x00733a11, 0x00743b14, 0x00753c14, 0x00703c12, 0x0056300f, 0x00231100, 0x0011100a, 0x000c1411, 0x00081410, 0x00051312, 0x00071210, 0x0008120f, 0x0008110d, 0x0007110c, 0x0006110d, 0x00050f0d, 0x00050f0c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00040e0b, 0x00040e09, 0x00051008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d09, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e09, 0x00060e09, 0x00060e08, 0x00050e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040e05, 0x00040e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060d06, 0x00060c05, 0x00060c05, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x002c2d0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x004f5010, 0x00515110, 0x00545510, 0x00565711, 0x00585810, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00686514, 0x00c6a219, 0x00cca519, 0x00796f14, 0x00636414, 0x00636414, 0x00626312, 0x00606013, 0x00606013, 0x005d5e12, 0x005c5c11, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d0f, 0x0048490f, 0x0044450e, 0x0040400d, 0x003b3c0c, 0x0038380c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0020230a, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x000c100b, 0x00161812, 0x003a3632, 0x00776868, 0x007b625f, 0x00714f3d, 0x00734829, 0x00764828, 0x00684130, 0x00593e36, 0x0052403f, 0x005d5359, 0x00645c64, 0x00685d64, 0x00695c62, 0x006c5a5c, 0x006c5858, 0x006e5855, 0x00705750, 0x0074584c, 0x00775849, 0x0079523d, 0x007d5137, 0x00805232, 0x0085542e, 0x00885429, 0x008a5424, 0x008c5420, 0x00905520, 0x0094561c, 0x0097561a, 0x00985517, 0x00995414, 0x00995414, 0x00985313, 0x00965214, 0x00905010, 0x008a4c0d, 0x0083480c, 0x007d440c, 0x0078400b, 0x00763e0f, 0x0070380a, 0x006d370c, 0x0075421c, 0x00895633, 0x008c5834, 0x008b5838, 0x0083543d, 0x00855a49, 0x008f6655, 0x00926852, 0x0094603e, 0x00a0632c, 0x00ad6b24, 0x00b46c20, 0x00b3681c, 0x00b4651a, 0x00b26519, 0x00a85d14, 0x009e5512, 0x00964e10, 0x008b440c, 0x0084410b, 0x008b4c12, 0x0098551c, 0x009c531a, 0x009d5418, 0x00904c15, 0x0071370b, 0x00572200, 0x00582507, 0x00613011, 0x00693612, 0x00703e14, 0x00794414, 0x00804812, 0x00844812, 0x00894b14, 0x008d4e14, 0x00904f15, 0x00904f15, 0x008e4f14, 0x008e4f13, 0x008f5014, 0x00884a0e, 0x0086480f, 0x0084460d, 0x007e430e, 0x0079400c, 0x00753d0b, 0x00723e0e, 0x00703f11, 0x006c3c10, 0x006c3c14, 0x006a3c16, 0x00663914, 0x00623713, 0x00603513, 0x005d3412, 0x00603514, 0x00603414, 0x005b3011, 0x00542c0c, 0x00542d0c, 0x00512a0c, 0x00502709, 0x005c3010, 0x006c3b19, 0x00703b15, 0x00733c14, 0x00743c11, 0x00753d10, 0x00744014, 0x00683c17, 0x003a2008, 0x00150d04, 0x000c100e, 0x00081410, 0x00081410, 0x0007130f, 0x0007130f, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100d, 0x00070e0f, 0x00070e0f, 0x00070e0d, 0x00070e0c, 0x00070e0d, 0x00070e0c, 0x00060e09, 0x00060e08, 0x00040e09, 0x00030f09, 0x0004100a, 0x00040f09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x00393b0d, 0x003c3e0c, 0x0041420e, 0x0044450d, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00515110, 0x00535410, 0x00555611, 0x00585810, 0x00585911, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca519, 0x00796f14, 0x00646414, 0x00626314, 0x00626312, 0x00616112, 0x00606012, 0x005d5e12, 0x005c5c11, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d0f, 0x00484910, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d09, 0x00080c08, 0x000a0e07, 0x002c2b26, 0x00736666, 0x007b625c, 0x00714f3c, 0x00734829, 0x00754828, 0x006d4632, 0x00604038, 0x00503936, 0x0056484c, 0x0060585e, 0x00655b62, 0x00685a60, 0x0068585a, 0x006a5656, 0x006a5654, 0x006c5650, 0x0071564d, 0x00745748, 0x00795441, 0x007c523b, 0x00805335, 0x00835430, 0x0085522b, 0x00865125, 0x00875020, 0x008c5420, 0x0090541c, 0x00915418, 0x00925214, 0x00925010, 0x00945011, 0x00935012, 0x00915014, 0x00894c10, 0x0082470e, 0x0078420b, 0x00733d09, 0x006c3607, 0x006c370b, 0x00683309, 0x007f4a20, 0x008e5830, 0x00945f36, 0x00945c30, 0x00945c33, 0x008f5c3a, 0x00906046, 0x00916752, 0x00966852, 0x0096603c, 0x00a0612b, 0x00aa6720, 0x00b0681c, 0x00b2661a, 0x00b4651a, 0x00b3661a, 0x00ac6016, 0x00a25815, 0x00964e11, 0x008b440c, 0x0089460f, 0x00925315, 0x009b581b, 0x009f5719, 0x00a05618, 0x00955018, 0x00854818, 0x005a2500, 0x00502001, 0x00572708, 0x0060300f, 0x00683812, 0x006e3c10, 0x00723d0b, 0x0078400d, 0x007f4410, 0x00834710, 0x00884810, 0x00884811, 0x008a4b13, 0x008a4c12, 0x00884a10, 0x0082440b, 0x0082440d, 0x007f410c, 0x00783f0b, 0x00733c09, 0x00733d0c, 0x00713f0f, 0x006f3e12, 0x006a3c10, 0x006a3c14, 0x00693c16, 0x00663914, 0x00633713, 0x00603513, 0x005c3311, 0x005e3413, 0x005e3113, 0x005a3010, 0x00542c0d, 0x00512b0c, 0x0050290a, 0x00502809, 0x005b3010, 0x006a3b19, 0x006f3d14, 0x00703d11, 0x006e3c0f, 0x006c3d0e, 0x006c3c13, 0x00532c0d, 0x00251000, 0x00100e06, 0x000b1310, 0x00081410, 0x0006120e, 0x0007130f, 0x0007130f, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x00070e0e, 0x00070e0d, 0x00070e0c, 0x00070f0a, 0x00070e0c, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00030c08, 0x0005100a, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0c, 0x0040400d, 0x0044450e, 0x0048490f, 0x004b4c0f, 0x004d4e10, 0x00505010, 0x00535410, 0x00545510, 0x00565710, 0x00585911, 0x00595a12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x00797014, 0x00636414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004f5010, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450d, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00141809, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e06, 0x00262521, 0x00736968, 0x00786058, 0x00704e39, 0x00744827, 0x00774925, 0x00724a33, 0x0067453b, 0x00503631, 0x00524244, 0x005f5659, 0x00645c61, 0x00685c61, 0x0069585b, 0x006b5858, 0x00695758, 0x006c5753, 0x006f584f, 0x0072584a, 0x00795444, 0x007d5440, 0x007f533a, 0x00825434, 0x0083522e, 0x00834f26, 0x00855024, 0x00885120, 0x008a511c, 0x008b5118, 0x008d5015, 0x008f4f12, 0x00905010, 0x008e4f10, 0x00884a0f, 0x0080450e, 0x0077400b, 0x00703c08, 0x00673305, 0x00623005, 0x005d2b04, 0x00713f18, 0x008b5730, 0x00935c33, 0x00986034, 0x009d602f, 0x009d6030, 0x009a613a, 0x00996444, 0x00996b53, 0x00976850, 0x00965e38, 0x00a26028, 0x00ac6820, 0x00ae671a, 0x00b06518, 0x00b06216, 0x00ae6115, 0x00a75c13, 0x00a25814, 0x00954d0f, 0x008c470c, 0x008c490d, 0x00945415, 0x009a5515, 0x009c5414, 0x009c5411, 0x00944f14, 0x00864817, 0x00643007, 0x00592c09, 0x00532508, 0x00562809, 0x005f3010, 0x00653710, 0x006c3c0d, 0x006f3c0c, 0x00743f0d, 0x007b4210, 0x00824510, 0x00844812, 0x00864913, 0x00854811, 0x0083450d, 0x0081430c, 0x0080410e, 0x007d3f0d, 0x00773f0e, 0x00713d0d, 0x006f3c0d, 0x006c3c10, 0x006b3c11, 0x006a3d12, 0x00683c14, 0x00673a14, 0x00643813, 0x00613613, 0x005f3411, 0x005c3311, 0x005a3010, 0x005a2d10, 0x00582e10, 0x00522b0c, 0x004d280b, 0x004c2809, 0x004c2808, 0x00562d0d, 0x00633714, 0x006b3b10, 0x006b3b10, 0x006a3e14, 0x00643c12, 0x00603615, 0x0044200a, 0x001d0c00, 0x000c0e08, 0x00081310, 0x0006110d, 0x0006110d, 0x0006110d, 0x0005100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00060d0c, 0x00060d0b, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00050c08, 0x00060c08, 0x00060c08, 0x00070d09, 0x00070d09, 0x00060c08, 0x00080f0b, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060d09, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004d4e0f, 0x00515110, 0x00525310, 0x00545511, 0x00565710, 0x00585910, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x00797014, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00031008, 0x00031008, 0x00031008, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f06, 0x0023241f, 0x00706665, 0x00745d55, 0x006e4c35, 0x00734825, 0x00764924, 0x00784c34, 0x00684638, 0x004c3129, 0x004d3d3c, 0x005b5154, 0x00625a5c, 0x00675b5f, 0x0068595b, 0x006b5859, 0x00685858, 0x006a5754, 0x006c554f, 0x006e544a, 0x00745345, 0x00795140, 0x007c503c, 0x007f5136, 0x00815130, 0x0081502a, 0x00814e23, 0x00864e20, 0x00874e1c, 0x00884e18, 0x00884e15, 0x00894d14, 0x008b4d11, 0x00874b0c, 0x0080470d, 0x00773f0c, 0x00703b0c, 0x0068380b, 0x00603006, 0x00542600, 0x00562703, 0x007b4b27, 0x00905f38, 0x00956035, 0x009c6338, 0x00a36132, 0x00a06234, 0x009e643e, 0x009d6748, 0x009c6c53, 0x0099684e, 0x00965c34, 0x00a05e24, 0x00aa651c, 0x00ac6418, 0x00ae6316, 0x00ac5e13, 0x00a6590d, 0x00a3580f, 0x009e5510, 0x00934c0c, 0x00904a0d, 0x008c4b0d, 0x00945414, 0x009a5613, 0x009c5412, 0x0098520d, 0x00904d0f, 0x007f430e, 0x006b370b, 0x005c2f0b, 0x00592e0d, 0x00572b0c, 0x00542809, 0x005c300c, 0x0065370d, 0x006b3b10, 0x006d3a0c, 0x00743f0f, 0x007c420e, 0x007e4410, 0x00804410, 0x0080440e, 0x0080430e, 0x007e420c, 0x007c3e0c, 0x00783c0b, 0x00753f10, 0x00703d0f, 0x006e3c0d, 0x006c3c10, 0x006a3d12, 0x00683e13, 0x00673c14, 0x00643913, 0x00613611, 0x00603512, 0x005e3412, 0x005c3212, 0x00572c0e, 0x00562b0e, 0x00562c0f, 0x00502b0b, 0x004c280a, 0x004c290b, 0x004c2808, 0x00522b0b, 0x00603412, 0x00623610, 0x00613612, 0x005c3514, 0x004f2c0c, 0x004f2a11, 0x00442613, 0x001c1002, 0x000b100a, 0x0007130f, 0x0007110d, 0x0007110d, 0x0007110d, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00060d0b, 0x00060e09, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e06, 0x00060f05, 0x00060e08, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00050c08, 0x00060c08, 0x00060c08, 0x00070d09, 0x00070d09, 0x00080c08, 0x000a0e0b, 0x00080c09, 0x00080c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004c4d0f, 0x00515110, 0x00525310, 0x00545511, 0x00565710, 0x00585910, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00626312, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x00797014, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00050e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x0008100b, 0x00060e0a, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100b, 0x0005110b, 0x0004100a, 0x0004100a, 0x00051009, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00050f06, 0x0010120c, 0x00564d4c, 0x006e5b53, 0x006c4c37, 0x00724828, 0x00784827, 0x00754a2d, 0x006c4833, 0x00573e31, 0x0050423e, 0x0058514f, 0x00605a5a, 0x00655c5d, 0x00695b5c, 0x00695858, 0x00685857, 0x00685553, 0x006a544f, 0x006c544c, 0x00715246, 0x00755143, 0x0078503e, 0x007a503b, 0x007e5134, 0x0080512e, 0x00835028, 0x00874e24, 0x00884c1d, 0x00884a18, 0x00894b18, 0x00884b18, 0x00844911, 0x007c450c, 0x0076400b, 0x006d3b09, 0x0066370b, 0x005e340e, 0x00542b05, 0x00542804, 0x005c300e, 0x00805230, 0x0094633e, 0x0095623b, 0x009a643b, 0x009d603b, 0x009c603e, 0x00996446, 0x00986850, 0x009b6c56, 0x00976447, 0x00955d30, 0x009b5b1f, 0x00a15b15, 0x00a55c13, 0x00a75c11, 0x00a4580e, 0x00a0560a, 0x009e540b, 0x0099520b, 0x00904a08, 0x008e4a0c, 0x008e4c10, 0x00915112, 0x00945412, 0x0091500d, 0x008e4c0b, 0x0088480e, 0x00783f0c, 0x00683409, 0x0063340f, 0x00623514, 0x005f3110, 0x00562908, 0x00582c0a, 0x005b300d, 0x00633610, 0x0068390d, 0x006b3b0c, 0x00703c0c, 0x00743d0c, 0x00763e0b, 0x00783e0c, 0x00773d0b, 0x00783d0c, 0x00773c0c, 0x00763c0c, 0x00733e10, 0x00703c10, 0x006c3b0e, 0x006a3c0e, 0x00693c15, 0x00673c16, 0x00663b14, 0x00633812, 0x00603613, 0x005e3412, 0x005c3313, 0x00562f10, 0x00532b0c, 0x00512a0c, 0x00532c0d, 0x00502b0d, 0x004d280b, 0x004d280e, 0x00472107, 0x004d270c, 0x00563014, 0x00583317, 0x00532f15, 0x0047260e, 0x003c1c06, 0x00442814, 0x003f2b17, 0x00251f0d, 0x000b1202, 0x00081409, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00090d0a, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00090d0a, 0x00090d0a, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00070c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004d4e0f, 0x00515110, 0x00525310, 0x00545511, 0x00565710, 0x00585910, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x00797014, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00616112, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00060e09, 0x0008100b, 0x0008100c, 0x0008100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005110b, 0x0005110b, 0x0004100a, 0x0004100a, 0x00041009, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00051008, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00041006, 0x00010800, 0x002e2927, 0x00645750, 0x006a523e, 0x00734f32, 0x00754c30, 0x0072492f, 0x00694530, 0x00533b2c, 0x00463832, 0x00544d4a, 0x005a5452, 0x00605756, 0x0068595b, 0x006b5b5b, 0x00665656, 0x00685453, 0x006a5450, 0x006c544c, 0x00705246, 0x00745042, 0x0076503c, 0x00784f39, 0x007a4e33, 0x007d4f2d, 0x00824e29, 0x00854e25, 0x00864c1f, 0x00854a1a, 0x00844918, 0x00804614, 0x007b440e, 0x00713d08, 0x006b3a07, 0x00673708, 0x005c3108, 0x00542b05, 0x00542a05, 0x005a2f0a, 0x00623614, 0x007f5034, 0x00906246, 0x00966548, 0x00946244, 0x00966044, 0x00956047, 0x0094624c, 0x00946452, 0x00936450, 0x008d5c3f, 0x008c5529, 0x0092541b, 0x00985412, 0x009c5410, 0x009e540f, 0x009e540e, 0x0098520c, 0x00945009, 0x008f4c09, 0x00894808, 0x0086480c, 0x00874b11, 0x008b4f14, 0x00884b10, 0x0084470c, 0x0080440d, 0x007b400e, 0x0070390c, 0x00643108, 0x0063320c, 0x006b3c18, 0x00643411, 0x00643410, 0x00552704, 0x00562a04, 0x005c3109, 0x00603409, 0x00643709, 0x0068390b, 0x006c3a0c, 0x00703b0b, 0x00703a0a, 0x00713c0c, 0x00713b0c, 0x00733d0e, 0x00743d0e, 0x00713d12, 0x006e3c10, 0x006c3c10, 0x00693c10, 0x00683c15, 0x00673c17, 0x00653a14, 0x00613712, 0x005f3511, 0x005d3512, 0x00593112, 0x00562f10, 0x00532c0f, 0x004e290b, 0x004c2709, 0x004c2609, 0x00482308, 0x004b230c, 0x00421c06, 0x0046220e, 0x00452611, 0x003e200e, 0x00381e0c, 0x002f1808, 0x00291405, 0x00352413, 0x00362919, 0x00282416, 0x0010150b, 0x00071008, 0x00060e09, 0x0009110d, 0x0008100c, 0x0008100b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00080e0a, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00070d09, 0x00070d09, 0x00080e0a, 0x00080e0a, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0041420d, 0x0044450e, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00505010, 0x00535410, 0x00555611, 0x00585810, 0x00585911, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f12, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x007a7014, 0x00646414, 0x00646414, 0x00636414, 0x00616112, 0x00616112, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00031008, 0x00031008, 0x00031008, 0x00031008, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x00050f0a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120d, 0x0008130d, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006110b, 0x0007110a, 0x0008110b, 0x0008120c, 0x0008120c, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x00061009, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00051008, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00031006, 0x0008130a, 0x000b0e08, 0x003f3a31, 0x00625441, 0x00654b32, 0x006b4834, 0x006e4831, 0x00633f29, 0x00503829, 0x00453831, 0x004f4846, 0x00565150, 0x005c5453, 0x00635456, 0x0069595a, 0x00675757, 0x00675452, 0x0067514c, 0x00685148, 0x00705144, 0x00735040, 0x00754e3c, 0x00784e38, 0x00784f33, 0x007a4f2f, 0x007f4e2b, 0x00804b26, 0x007e481c, 0x007c4517, 0x007b4414, 0x00784111, 0x00713f0c, 0x00693a08, 0x00643708, 0x005e330a, 0x00562d08, 0x00542d08, 0x005c340e, 0x00643915, 0x00643817, 0x0073472b, 0x00865940, 0x008e604b, 0x00875a44, 0x00845640, 0x00885a44, 0x00885b46, 0x00865b46, 0x00875c47, 0x00845739, 0x00875329, 0x008c501c, 0x008d4c11, 0x00904c0f, 0x00914c0e, 0x00934e10, 0x0090500e, 0x008d4f0f, 0x00884c0e, 0x0083480d, 0x007c440d, 0x00794510, 0x007a4614, 0x00754110, 0x00733d10, 0x00713b14, 0x0069340d, 0x005e2c06, 0x00602f08, 0x00693710, 0x006c3813, 0x006c3913, 0x006c3913, 0x00663510, 0x00592a03, 0x00562a02, 0x00582e05, 0x005c3108, 0x0062370c, 0x0065380e, 0x0069390c, 0x006c3b0d, 0x006d3b0c, 0x006f3c0e, 0x006d3c0d, 0x006e3c0d, 0x006d3c12, 0x006c3c12, 0x00693d12, 0x00683c11, 0x00643912, 0x00643914, 0x00633814, 0x00613514, 0x005d3411, 0x00583311, 0x00552f10, 0x00512c0f, 0x00502b0d, 0x004d280c, 0x004b250a, 0x004b270c, 0x00462108, 0x004c240f, 0x00371504, 0x00291001, 0x00241203, 0x00201104, 0x00201309, 0x00221810, 0x001c130b, 0x00241c12, 0x00262014, 0x00202018, 0x00101714, 0x00060f0c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00070f0a, 0x00050d08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0036370c, 0x00393b0d, 0x003c3e0c, 0x0041420e, 0x0044450d, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00525310, 0x00535410, 0x00555611, 0x00585810, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00636413, 0x00636414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00696614, 0x00c6a218, 0x00cca619, 0x007a7014, 0x00646414, 0x00646414, 0x00636414, 0x00616112, 0x00616112, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00021008, 0x00021008, 0x00021008, 0x00021008, 0x00021009, 0x00021009, 0x00021009, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120d, 0x0008130d, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006110b, 0x0007110a, 0x0008110b, 0x0008120c, 0x0008120c, 0x0007110c, 0x0006100b, 0x0007110c, 0x0007110c, 0x00061009, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00051008, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e08, 0x00041006, 0x00041007, 0x00060e08, 0x00101208, 0x00393120, 0x0056432d, 0x005e4433, 0x0064412e, 0x005f3d28, 0x00503b2c, 0x00443933, 0x004a4440, 0x00544e4c, 0x005c5252, 0x00605354, 0x00655555, 0x00675757, 0x00675452, 0x0067514c, 0x00685148, 0x006f5042, 0x00714f3e, 0x00724c38, 0x00744b34, 0x00744c31, 0x00764c2d, 0x007a4c28, 0x007b4924, 0x0079471b, 0x00784416, 0x00744113, 0x006f3c0e, 0x006a3a0c, 0x00643808, 0x005c3308, 0x00562d08, 0x00542c09, 0x005b340f, 0x00603912, 0x00673d17, 0x00673c18, 0x006a3c1f, 0x006f4328, 0x00754c34, 0x00734b36, 0x00714a34, 0x00744e35, 0x00785138, 0x00785138, 0x007c533c, 0x007e5136, 0x00804f28, 0x00844a19, 0x00844710, 0x0086470f, 0x0088480f, 0x008a480f, 0x0087480e, 0x0080460c, 0x007b430c, 0x0074400c, 0x006e3c0c, 0x006c3c0e, 0x006c3e13, 0x00693912, 0x00623010, 0x005a290c, 0x00542405, 0x005c2c0a, 0x00683611, 0x00703c13, 0x00703c12, 0x00713c14, 0x00703b13, 0x006c3810, 0x0064340b, 0x00582c04, 0x00542903, 0x00572f08, 0x005b320c, 0x00603710, 0x0064380f, 0x0068390e, 0x00693b0c, 0x006a3c0e, 0x006a3c0d, 0x006a3c0e, 0x00693b11, 0x00683c13, 0x00673c13, 0x00643b12, 0x00613810, 0x00623812, 0x00613614, 0x00603412, 0x005b3210, 0x0056300f, 0x00583113, 0x00532e10, 0x004c280c, 0x004d280c, 0x004b250c, 0x0048240a, 0x00422007, 0x00452310, 0x002c1404, 0x00120700, 0x00121002, 0x00151105, 0x001a150c, 0x001b1911, 0x00181710, 0x0019170f, 0x001c1b14, 0x00191c18, 0x000f1314, 0x00070f0d, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00050d09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040d07, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00050c08, 0x00050c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0024250b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x004f5010, 0x00525310, 0x00555611, 0x00565710, 0x00585911, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00696614, 0x00c6a218, 0x00cca619, 0x007a7014, 0x00646514, 0x00646414, 0x00636414, 0x00626312, 0x00606012, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x00494a10, 0x0045470e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006110c, 0x0005110b, 0x0006120c, 0x0007130d, 0x0006100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00040f08, 0x00040f08, 0x00060e08, 0x000b1008, 0x000c0d03, 0x001f1c0f, 0x00302c1c, 0x00413224, 0x00463426, 0x003d2f24, 0x00403630, 0x00423b38, 0x004e4845, 0x00584f4d, 0x00605452, 0x00645454, 0x00645454, 0x00675653, 0x0064504b, 0x00665048, 0x006c4f40, 0x00704f3e, 0x00704c37, 0x00704932, 0x00714a2f, 0x00714828, 0x00704320, 0x0070421c, 0x00734216, 0x00714012, 0x006f4013, 0x00683c10, 0x0062370c, 0x005b320a, 0x00562d07, 0x00562b07, 0x005d310f, 0x00653913, 0x00693d14, 0x006c3e10, 0x006d3c0f, 0x00683714, 0x00603414, 0x0060381f, 0x005c3822, 0x005b3724, 0x00603c29, 0x00684430, 0x00714d36, 0x00754f38, 0x00774c34, 0x00784829, 0x006e3c14, 0x00764012, 0x00773f0e, 0x00783f0e, 0x00793f0d, 0x00783f0d, 0x00753e0c, 0x006e3b0e, 0x00683b13, 0x00613814, 0x00572f10, 0x004c2507, 0x00471f03, 0x00411900, 0x004a2006, 0x00582a0e, 0x00683715, 0x006e3b14, 0x00733e12, 0x00744010, 0x00753f13, 0x00763f13, 0x00713c0d, 0x006b3808, 0x0065360b, 0x005b2e09, 0x00562c0b, 0x00592f10, 0x005d3412, 0x00603511, 0x00613710, 0x0061380d, 0x0061380c, 0x00643b0c, 0x00653c0d, 0x00663c12, 0x00663b14, 0x00653a14, 0x00633913, 0x00613811, 0x00613812, 0x00613814, 0x005c3210, 0x00582f0e, 0x00583112, 0x00583114, 0x00522b0f, 0x004e260d, 0x004c260c, 0x0048240a, 0x0047230a, 0x0044230c, 0x00402414, 0x00241405, 0x00100e00, 0x000e1406, 0x0015170a, 0x001c180e, 0x001c180e, 0x0018160e, 0x0013140f, 0x00131513, 0x00151914, 0x000d120c, 0x00081009, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d0a, 0x00080d09, 0x00080d09, 0x00080d08, 0x00080d0a, 0x00080c09, 0x00080c07, 0x00080c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c09, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x00292b0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a10, 0x004d4e0f, 0x00515110, 0x00525310, 0x00565610, 0x00595a11, 0x005b5b12, 0x005c5c12, 0x005e5f11, 0x00605f11, 0x00616012, 0x00626113, 0x00626113, 0x00636213, 0x00646313, 0x00646212, 0x00646313, 0x00646413, 0x00646413, 0x00656413, 0x00666412, 0x00666412, 0x00686513, 0x00686513, 0x00686613, 0x00696614, 0x00696614, 0x006b6814, 0x006b6814, 0x006c6814, 0x006c6914, 0x006c6914, 0x006d6a14, 0x006e6b14, 0x00938115, 0x00c9a419, 0x00cca619, 0x00797014, 0x00646414, 0x00646414, 0x00636414, 0x00626312, 0x00616112, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130c, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006110c, 0x0005110b, 0x0006120c, 0x0007130d, 0x0007100c, 0x0009110d, 0x0009110d, 0x0008100c, 0x0008100c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e06, 0x00080e05, 0x000c0f05, 0x00100f04, 0x00201a10, 0x002d251a, 0x002f261e, 0x002e2823, 0x00433e38, 0x0048413c, 0x00514744, 0x00615454, 0x00605251, 0x00615050, 0x00655451, 0x00624e49, 0x00644e45, 0x00684d40, 0x006d4d3f, 0x006f4c38, 0x006e4833, 0x006f472d, 0x006d4427, 0x006c401e, 0x006c4018, 0x006d3d13, 0x006b3b0f, 0x00683a10, 0x0061350e, 0x005b330c, 0x00573009, 0x00542b06, 0x00572c07, 0x00643710, 0x006b3c14, 0x006f3f13, 0x00724010, 0x00724010, 0x00703c15, 0x00683914, 0x0054290c, 0x0048240c, 0x0042200c, 0x003f1d08, 0x003f1f0c, 0x00543420, 0x00684631, 0x006f4832, 0x006c4229, 0x00653919, 0x0064340d, 0x0066350c, 0x0068340c, 0x0068350d, 0x0068350d, 0x0064340c, 0x005f310c, 0x00593010, 0x00482206, 0x00381600, 0x00351400, 0x003c1902, 0x00432009, 0x00512a0f, 0x00603414, 0x006c3a17, 0x00733e14, 0x00774111, 0x00784310, 0x007b4413, 0x007c4212, 0x0079420e, 0x00723f0a, 0x006e3b0d, 0x00663610, 0x005b2d0b, 0x00582e0c, 0x005b310f, 0x005c330f, 0x005d340f, 0x005e350d, 0x005e350c, 0x0060370c, 0x0060380c, 0x00623910, 0x00623812, 0x00623811, 0x00603710, 0x00603710, 0x00603711, 0x005e3411, 0x00592f0d, 0x0058300f, 0x00593112, 0x00593114, 0x0052280e, 0x004d240c, 0x004c240d, 0x0047220a, 0x0046230a, 0x0044240d, 0x003b2213, 0x001f1007, 0x00100d04, 0x000d1506, 0x00121306, 0x0021180f, 0x00241a10, 0x001c180d, 0x00151510, 0x00111310, 0x00101410, 0x000b1009, 0x0009100a, 0x0005100a, 0x00040f09, 0x0005100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070c0b, 0x00070d09, 0x00070d09, 0x00070d08, 0x00080e0a, 0x00070d09, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004d4e10, 0x00706411, 0x00b79414, 0x00bd9815, 0x00be9a16, 0x00be9a16, 0x00be9b16, 0x00be9b17, 0x00bf9b18, 0x00bf9b18, 0x00bf9b18, 0x00bf9b18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00c09d18, 0x00c09d18, 0x00c09d18, 0x00c09d18, 0x00c09d18, 0x00c09d18, 0x00c09e18, 0x00c09e18, 0x00c09e18, 0x00c09e18, 0x00c09f18, 0x00c8a418, 0x00cca619, 0x00c09e18, 0x00716c14, 0x00646514, 0x00646414, 0x00636414, 0x00626313, 0x00606013, 0x00606013, 0x005d5d12, 0x00a38814, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x00484910, 0x0044450e, 0x0040400d, 0x003b3c0c, 0x0038380c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040f09, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006110c, 0x0005110b, 0x0005110b, 0x0007130c, 0x000a140f, 0x000c140f, 0x000c140f, 0x0009110d, 0x0008100b, 0x0008120d, 0x0008120d, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00060e06, 0x00080d06, 0x00090c06, 0x000d0e09, 0x0022211c, 0x00282620, 0x00282620, 0x003c3833, 0x00443c38, 0x00544948, 0x005c504f, 0x005f5050, 0x00605050, 0x0062514e, 0x00624f49, 0x00604c43, 0x0062493d, 0x0066473a, 0x006c4a39, 0x006c4733, 0x006c452d, 0x006a4326, 0x00683f1d, 0x00683d18, 0x006a3c14, 0x0066380e, 0x0061340c, 0x005c320c, 0x0058300c, 0x00542c09, 0x00562c08, 0x00603510, 0x00683b11, 0x006c3d10, 0x00714010, 0x00733f10, 0x00743f10, 0x00764014, 0x006f3d15, 0x005f3211, 0x004f290a, 0x00442108, 0x003d1f07, 0x003c200b, 0x003a1d0b, 0x00432614, 0x00533421, 0x005b3924, 0x005c381e, 0x00593114, 0x005a2e10, 0x0054290a, 0x00582f10, 0x00593010, 0x00593013, 0x004c250a, 0x003e1a00, 0x00371700, 0x00361a09, 0x00391c0a, 0x003e1e09, 0x0048240c, 0x00542c0f, 0x00643715, 0x00703e17, 0x00744014, 0x00784210, 0x0079440f, 0x007c4410, 0x007e4410, 0x007c4410, 0x0077400e, 0x00703c0d, 0x006b3910, 0x0063340d, 0x00582e0a, 0x00582c09, 0x00582e0c, 0x005a300f, 0x005c3210, 0x005e3410, 0x005d340e, 0x005d340d, 0x00603610, 0x00623912, 0x00613811, 0x005e350e, 0x005c320c, 0x005d3410, 0x00603514, 0x005b3010, 0x00572d0f, 0x00593014, 0x00583014, 0x00582f15, 0x004f260f, 0x004f2611, 0x004f2a13, 0x0043200b, 0x003c1d08, 0x002e180b, 0x00180803, 0x00130e08, 0x00111409, 0x00161305, 0x0024180e, 0x00281c10, 0x00211a0d, 0x0018150e, 0x0012120f, 0x000e120e, 0x0009100c, 0x0008100c, 0x0005100a, 0x00040f09, 0x0005100a, 0x00050f0a, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070c0b, 0x00070d09, 0x00070d09, 0x00070d08, 0x00080e0a, 0x00070d09, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x00615910, 0x00bc9815, 0x00cca316, 0x00cca316, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00c2a018, 0x008b7c14, 0x00656614, 0x00646514, 0x00646514, 0x00636414, 0x00626313, 0x00616112, 0x00606012, 0x00605f12, 0x00ac8f15, 0x00cca417, 0x00b09014, 0x004f5010, 0x00505010, 0x004c4d0f, 0x00484910, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0036370c, 0x0034350c, 0x002d2f0b, 0x00292b0a, 0x0026280b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00040e09, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006110c, 0x0005110b, 0x0006120c, 0x0008140e, 0x0008120d, 0x0009110d, 0x0009110d, 0x0008100c, 0x0009110d, 0x0008120d, 0x0008110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00031006, 0x00031008, 0x00060e08, 0x00070c0a, 0x00070c0b, 0x00101512, 0x001c201a, 0x001e1e17, 0x00343129, 0x003e3832, 0x00504542, 0x00584c4b, 0x005a4c4b, 0x005c4d4c, 0x0062504e, 0x00604d48, 0x005d4c42, 0x0060493e, 0x0064483b, 0x00694b3b, 0x00694834, 0x0066442c, 0x00664024, 0x00663e1e, 0x00673d19, 0x00663b13, 0x0061350c, 0x005c330b, 0x0058300c, 0x00542d0c, 0x00542c0d, 0x005d3410, 0x00653a12, 0x006c3e12, 0x00703e0d, 0x0074400f, 0x00774010, 0x00784010, 0x00774011, 0x00713d12, 0x00653811, 0x00562f0c, 0x0048270a, 0x00402409, 0x003b1f0a, 0x00351b0a, 0x00341c0b, 0x00361e0c, 0x00412614, 0x0050311f, 0x00502f1a, 0x00502c17, 0x004c2511, 0x004e2915, 0x00492611, 0x0040200a, 0x00361702, 0x00341400, 0x00341801, 0x00381e0c, 0x003f220c, 0x004a260f, 0x00542c10, 0x005d3311, 0x00663813, 0x006f3d12, 0x00723e0f, 0x00744009, 0x0076400a, 0x0079410c, 0x007b420c, 0x007b420e, 0x0078400d, 0x00733d0c, 0x006c3a0c, 0x0067380c, 0x005e340e, 0x00582c09, 0x00542a09, 0x00552b0c, 0x00582e0f, 0x005b3010, 0x005c3210, 0x005d3410, 0x005e350e, 0x005d340d, 0x005d340d, 0x005c330c, 0x005b320b, 0x005e3410, 0x00582d0c, 0x005c3111, 0x00542a0d, 0x00542c10, 0x00532a0f, 0x00542c11, 0x0050260f, 0x004c250e, 0x004a240e, 0x00421f0a, 0x003c1c0a, 0x00281408, 0x00140703, 0x00130d09, 0x00131308, 0x00191404, 0x0025180c, 0x002f2014, 0x002a2011, 0x001e170e, 0x00181410, 0x00101410, 0x00081210, 0x0007120d, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x006e6011, 0x00cca215, 0x00c8a016, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48815, 0x00a48915, 0x00a48915, 0x00a48916, 0x00a48916, 0x00a48916, 0x00a48916, 0x00a38a15, 0x00a38a15, 0x00a38915, 0x00a38915, 0x00a28915, 0x00a28915, 0x00a28916, 0x00a28916, 0x00a18817, 0x00a18816, 0x00a18915, 0x00a18915, 0x00a18816, 0x00a18916, 0x00a08916, 0x00a08916, 0x00a08916, 0x00a08916, 0x00a08916, 0x00a08916, 0x00988416, 0x00787114, 0x00656614, 0x00656614, 0x00656614, 0x00646514, 0x00646414, 0x00626313, 0x00626312, 0x00606012, 0x00616012, 0x00bc9916, 0x00cca417, 0x00aa8b14, 0x004f5010, 0x00505010, 0x004c4d0f, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040f0a, 0x00040f09, 0x00040e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040f09, 0x0008110c, 0x0005100a, 0x00040d08, 0x00040d08, 0x0007110c, 0x0007110c, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0007110c, 0x0005100a, 0x0008120c, 0x0008120d, 0x0007120c, 0x0006120c, 0x0007130c, 0x0008140e, 0x0007130d, 0x0007110c, 0x0009120d, 0x0008120d, 0x0007110c, 0x0009130e, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x00061009, 0x00061009, 0x00040f08, 0x00051008, 0x0007100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040e05, 0x00040e05, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00031006, 0x00060e09, 0x00060e09, 0x0006100c, 0x000c120f, 0x00161a14, 0x0021211a, 0x002e2c22, 0x00352f28, 0x00493f3b, 0x00544845, 0x005a4d4c, 0x00544644, 0x00584945, 0x005c4a45, 0x005c4a43, 0x0060483d, 0x00604538, 0x0065483a, 0x00664838, 0x0067442f, 0x00644026, 0x00633d1f, 0x00633b18, 0x00633815, 0x005e3410, 0x0058320d, 0x0054300c, 0x00542f0e, 0x005c3014, 0x00633513, 0x006b3c12, 0x00724113, 0x0076400e, 0x0077410e, 0x007a4312, 0x00793f10, 0x00783e10, 0x00713c0f, 0x00693b11, 0x00603810, 0x00523111, 0x00482a0e, 0x0040240b, 0x003f250f, 0x003a2410, 0x0035210d, 0x00331e0a, 0x0038200c, 0x00422715, 0x00442818, 0x00452617, 0x00432414, 0x003d1f10, 0x00341605, 0x00351804, 0x003c1e0a, 0x00432510, 0x00482914, 0x004d2c14, 0x00522c11, 0x00582e11, 0x00643815, 0x00683b11, 0x006d3c10, 0x00703c0c, 0x00703c09, 0x00703c08, 0x00733c09, 0x0078400c, 0x00733d0c, 0x006c3808, 0x006c390b, 0x0068360a, 0x0066360e, 0x0061340e, 0x005b2f0d, 0x00562b0e, 0x00542b10, 0x00582f14, 0x00572c10, 0x005b3011, 0x005b3010, 0x005b320c, 0x005b310c, 0x005d3410, 0x005d3410, 0x005d3410, 0x005c3411, 0x00582f0e, 0x00582f10, 0x00542b0e, 0x00532c10, 0x0050280d, 0x00512a10, 0x00502910, 0x004b250c, 0x004c2610, 0x0044200b, 0x00381c0a, 0x00231206, 0x00120902, 0x00110f07, 0x00171408, 0x001f1708, 0x002c1c0f, 0x00342412, 0x0030220d, 0x00281c0f, 0x001f1810, 0x0012140f, 0x00091110, 0x00071310, 0x0006120c, 0x0004100a, 0x00030f09, 0x00040e08, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00060d09, 0x00080c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070e08, 0x00070e08, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c07, 0x00050d07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x00494a0f, 0x004d4e0f, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005b5811, 0x00595a12, 0x005b5b11, 0x005c5d12, 0x005d5e13, 0x005e5f13, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00616113, 0x00616113, 0x00616114, 0x00616114, 0x00616114, 0x00616114, 0x00626314, 0x00626314, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00646513, 0x00656614, 0x00656614, 0x00656613, 0x00666713, 0x00666713, 0x00666713, 0x00656614, 0x00646513, 0x00646414, 0x00636414, 0x00616112, 0x00606013, 0x00786c14, 0x00c8a116, 0x00cca417, 0x00927b13, 0x00515110, 0x00505010, 0x004c4d0f, 0x0047480e, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0038380c, 0x0030310c, 0x002d2f0a, 0x0026280a, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f09, 0x00040d08, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x0006100b, 0x00040f09, 0x00040d08, 0x00040d08, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0007110c, 0x0005100a, 0x0008120c, 0x0008120d, 0x0008120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0007110c, 0x0009130e, 0x0007110c, 0x0008120d, 0x0009130e, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x00061009, 0x00061009, 0x0008110b, 0x00040f08, 0x00040c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040e05, 0x00040e05, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00050f08, 0x00040e09, 0x00080f0b, 0x000e140f, 0x001b1c16, 0x0026251c, 0x00353028, 0x0048403a, 0x004e443e, 0x00524641, 0x00544743, 0x00584945, 0x00574640, 0x0056463d, 0x005e473c, 0x0062473b, 0x005e4334, 0x00604232, 0x0063412d, 0x00633f26, 0x00633c20, 0x00623b18, 0x005e3614, 0x005a3210, 0x0058300e, 0x0057310f, 0x00593110, 0x00613416, 0x00683914, 0x006c3d12, 0x00734011, 0x00794311, 0x00784311, 0x00784110, 0x00794110, 0x00763e10, 0x00703c10, 0x006b3c12, 0x00613810, 0x00573311, 0x00502d10, 0x00462508, 0x0047290f, 0x00402710, 0x003b240f, 0x0037200b, 0x00351e0a, 0x00341c08, 0x00341b0b, 0x00361b0c, 0x00391c0c, 0x003b1c0d, 0x00371908, 0x00391c09, 0x0040210c, 0x00482812, 0x004c2b12, 0x00502c13, 0x00542c11, 0x005b2e12, 0x00653514, 0x00683811, 0x006c380d, 0x006c3a0b, 0x006d3b0a, 0x006e3c0b, 0x006f390c, 0x00733c0e, 0x006e3a0b, 0x006c3b0c, 0x0068360b, 0x00613109, 0x005d2f08, 0x005d2e0b, 0x00582c0b, 0x00572a0f, 0x00552c12, 0x00562d13, 0x00592f13, 0x005a3012, 0x005b3010, 0x005a300c, 0x00582f0c, 0x005c3310, 0x005c3311, 0x005c3412, 0x005b3311, 0x0058300f, 0x00542c0d, 0x0050280b, 0x00532c10, 0x004f280c, 0x004e260c, 0x004d250b, 0x004a260b, 0x004d2810, 0x0044200c, 0x00361c0a, 0x001a0d00, 0x00100c04, 0x000d0d04, 0x00151306, 0x0023180b, 0x002f1d11, 0x003a2412, 0x0038240c, 0x002d1d0d, 0x0022180f, 0x0015140e, 0x000c1110, 0x00081310, 0x0006120c, 0x0004100a, 0x00030f09, 0x00020e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00060d09, 0x00080c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070e08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c07, 0x00050e08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x00202309, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606012, 0x00606012, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666713, 0x00666713, 0x00666714, 0x00666714, 0x00666714, 0x00666714, 0x00666713, 0x00666713, 0x00656614, 0x00646514, 0x00636414, 0x00626312, 0x00616113, 0x00a18815, 0x00cca417, 0x00c59f16, 0x006e6412, 0x00535410, 0x00505010, 0x004c4d0f, 0x0048490e, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130e, 0x000f130f, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f0a, 0x0005100a, 0x00040f09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x0008110c, 0x0008120d, 0x0008120d, 0x0007130c, 0x0007130d, 0x0007130d, 0x0005110b, 0x0008120c, 0x0008120d, 0x0008120c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120c, 0x0008120c, 0x0008120c, 0x0008120c, 0x0008120c, 0x0007110c, 0x00061009, 0x00061009, 0x00061009, 0x00040f08, 0x00060f09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00060e08, 0x00040e07, 0x00040f08, 0x00050e08, 0x00090e09, 0x0010120e, 0x001c1c17, 0x0034322b, 0x0048433b, 0x004b423c, 0x004c413a, 0x0050443c, 0x0050413a, 0x0053423a, 0x00534439, 0x005b463a, 0x0060483a, 0x005d4434, 0x005c412f, 0x005e3e2b, 0x00603c25, 0x005f391e, 0x005e3718, 0x005a3312, 0x0058300e, 0x00572f0d, 0x0059300f, 0x005c3010, 0x00633814, 0x00693a14, 0x006a3a0e, 0x006e3c0e, 0x00744012, 0x00733e10, 0x00733e10, 0x00794416, 0x00764113, 0x006d3c0f, 0x006a3a10, 0x00643611, 0x005c3010, 0x005c3417, 0x0050290f, 0x00522c13, 0x004b2b12, 0x00482b14, 0x003f230c, 0x003c1f09, 0x003b1e0a, 0x003b1e0b, 0x00381b08, 0x003a1c0c, 0x003f200e, 0x0040210d, 0x0040200a, 0x0045250c, 0x004d2c12, 0x004f2b11, 0x00542c11, 0x00562b0e, 0x005e3010, 0x00643413, 0x00693813, 0x006c3c12, 0x006f3c11, 0x006d3c0e, 0x006c3b0d, 0x006b370c, 0x006c380d, 0x00643306, 0x00633307, 0x00613308, 0x00643811, 0x005d300b, 0x00562908, 0x00582c0c, 0x0054290b, 0x00552c10, 0x00562c10, 0x00562b10, 0x005b3012, 0x005b3010, 0x00582f0c, 0x00572d0a, 0x005a300d, 0x00582f0d, 0x0059300f, 0x0058300f, 0x00552d0e, 0x00512a0c, 0x0050280c, 0x00502a10, 0x004d280d, 0x004f290f, 0x00502b10, 0x004a270b, 0x004a240c, 0x00411e0b, 0x00331909, 0x00140c01, 0x000e0e07, 0x000c0c06, 0x00141106, 0x0024170c, 0x00321c11, 0x003d2413, 0x003d260f, 0x00311e0e, 0x0026180e, 0x0019140e, 0x0010110e, 0x000a120e, 0x0005110c, 0x0004100a, 0x0004100a, 0x00040f09, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00060d09, 0x00080c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070e08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c07, 0x00050e08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005d5b12, 0x005c5d11, 0x005c5d11, 0x00606013, 0x00606012, 0x00606012, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00666714, 0x00656614, 0x00656614, 0x00646414, 0x00626313, 0x00756c14, 0x00c49f18, 0x00cca417, 0x00a68914, 0x00585811, 0x00535410, 0x00505010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f09, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x0005100a, 0x00040e08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x0007110c, 0x0008110c, 0x0007110c, 0x0005110b, 0x0006120c, 0x0008140e, 0x0008140e, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007110c, 0x00061009, 0x00061009, 0x0007110a, 0x00040f08, 0x00040e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00050e08, 0x00040e06, 0x00040f06, 0x00050f06, 0x00060e08, 0x00080c09, 0x000e100c, 0x00282721, 0x003c3932, 0x0048433a, 0x004b4338, 0x004e4439, 0x00504238, 0x0055443c, 0x00504136, 0x00584538, 0x005c4537, 0x00594030, 0x00583e2b, 0x00593c2a, 0x005c3c28, 0x005c3920, 0x005a3618, 0x00583212, 0x0055300e, 0x00572f0d, 0x005b300e, 0x005b310c, 0x0061360d, 0x00673810, 0x006b3b10, 0x006c3c10, 0x00703d11, 0x006c390d, 0x00703f13, 0x00734114, 0x00703f11, 0x006c3b0f, 0x006b3a11, 0x006b3b17, 0x006b3c1a, 0x00653818, 0x005b3012, 0x005c3416, 0x00543016, 0x004d2c14, 0x00492811, 0x0043220c, 0x0040210b, 0x003d200b, 0x003d1f0b, 0x003e1e0b, 0x003f1e0b, 0x0041200c, 0x0044220c, 0x0048260c, 0x004f2c10, 0x00532d10, 0x00552c0f, 0x005a2d0c, 0x0060300f, 0x00683717, 0x00683614, 0x00683810, 0x006c3c12, 0x0068380d, 0x0069380d, 0x0068370e, 0x0069370e, 0x005f3007, 0x005c2f06, 0x0060320c, 0x005f3310, 0x00542806, 0x00522407, 0x0053270a, 0x0054280b, 0x00542c0e, 0x00542b0f, 0x00552a0f, 0x00592f10, 0x005c3110, 0x005c320f, 0x00592f0d, 0x005a300e, 0x00592f0e, 0x00582f0d, 0x00542c0c, 0x00542c0c, 0x00502a0c, 0x0050280e, 0x004f2810, 0x004c260c, 0x004a240b, 0x00482208, 0x00482408, 0x00462009, 0x00401b0a, 0x002b1204, 0x000f0c02, 0x00090d07, 0x000c0e08, 0x00151009, 0x0025170c, 0x00341c12, 0x003e2212, 0x00402610, 0x00372311, 0x002a1c10, 0x001e160d, 0x0014140d, 0x000b120e, 0x0006120c, 0x0004100a, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00060d09, 0x00080c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070e08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c07, 0x00050e08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005d5b12, 0x005c5c11, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00626313, 0x00636413, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00666713, 0x00656614, 0x00646414, 0x00686413, 0x00b09317, 0x00cca418, 0x00c39e17, 0x00706612, 0x00565711, 0x00535410, 0x00505010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d08, 0x00070f0a, 0x00040d08, 0x00050e09, 0x00050e09, 0x00040f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050e08, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f0a, 0x00060f0a, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050f09, 0x00050e09, 0x00060d09, 0x00070e09, 0x00060d08, 0x00050c08, 0x00040c08, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100b, 0x0005100b, 0x0005100a, 0x0006100b, 0x0007120c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008110c, 0x0008110c, 0x0008110c, 0x0008110c, 0x0008120d, 0x0008110c, 0x0007110c, 0x0007100c, 0x0006100b, 0x0006110b, 0x00051009, 0x00051009, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00040e07, 0x00040f06, 0x00050e06, 0x00070e08, 0x00060c08, 0x00080d09, 0x001f1f1b, 0x0038352f, 0x00474339, 0x00484136, 0x004c4238, 0x0051433a, 0x0058483f, 0x00504034, 0x00564438, 0x00594334, 0x00543c2c, 0x004f3623, 0x00573d29, 0x005b3f2a, 0x00593b21, 0x0058361a, 0x00543313, 0x0054300e, 0x00542d0a, 0x005c330f, 0x005c320b, 0x0060360c, 0x0063360d, 0x0064350c, 0x00693a11, 0x00683910, 0x0066380e, 0x006c3b12, 0x006e3c14, 0x006b3b10, 0x006b3b10, 0x0067380f, 0x00683812, 0x006d3f1a, 0x00633611, 0x005f330f, 0x00603514, 0x005a3315, 0x00522c11, 0x00512a14, 0x0048240e, 0x0043200b, 0x0043230c, 0x0042230c, 0x0043210b, 0x00401e08, 0x00401e06, 0x0047250c, 0x004b270c, 0x004f2a0c, 0x00552f0d, 0x00572d0b, 0x00603410, 0x005e300f, 0x00683818, 0x00673715, 0x00643410, 0x00683911, 0x0064350d, 0x00643510, 0x00663611, 0x00643410, 0x005c2f0a, 0x005a2e08, 0x00592d0a, 0x00572c0c, 0x0054290b, 0x0055290d, 0x00502408, 0x0052280b, 0x0053280c, 0x0051280c, 0x00562c0f, 0x00592f0f, 0x005c3110, 0x005c3310, 0x005b3110, 0x005a3010, 0x0059300e, 0x00552e0c, 0x00542c0c, 0x00542c0d, 0x00542d10, 0x0050280f, 0x004f2910, 0x004d280f, 0x0049240b, 0x00462208, 0x00442308, 0x00421f0a, 0x00391c0b, 0x00200e00, 0x000d0d04, 0x00080e07, 0x000c0f09, 0x0016100a, 0x0024160c, 0x00311d10, 0x00392210, 0x003c2711, 0x00362313, 0x002c1d11, 0x00221a10, 0x0018150e, 0x0010140d, 0x000a130d, 0x0008100b, 0x00061009, 0x00050f09, 0x00040e0a, 0x00040e0a, 0x00040e0a, 0x00040e0a, 0x00050e09, 0x00050e09, 0x00070f09, 0x00060e09, 0x00060d09, 0x00060d09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00070e09, 0x00060d08, 0x00050c08, 0x00060c08, 0x00070c08, 0x00070c08, 0x00080c08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00080c09, 0x00080d09, 0x00060d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00060f09, 0x00070f09, 0x00060d08, 0x00060d08, 0x00070c08, 0x00080c08, 0x00080c08, 0x00070c08, 0x00050e08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00050d09, 0x00050d09, 0x00050d09, 0x00040c08, 0x00040c07, 0x00050d07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00050d08, 0x00050d09, 0x00050d0a, 0x00060e0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00050f08, 0x00050f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00050e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050f08, 0x00050f08, 0x00070e09, 0x00060e08, 0x00050e08, 0x00050e07, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00050c08, 0x00070c08, 0x00080c09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x001d200a, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005d5e11, 0x005e5f13, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00686614, 0x00a28916, 0x00cba418, 0x00caa418, 0x00907c14, 0x00595a11, 0x00585810, 0x00535410, 0x00505010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f07, 0x00040f07, 0x00040f07, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00050c08, 0x00050c08, 0x00050c08, 0x00040d08, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008120d, 0x0007110c, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x00050f0a, 0x0007100b, 0x00070f0a, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f07, 0x00050e07, 0x00070f09, 0x00040c08, 0x00090f0a, 0x0013140e, 0x002e2b24, 0x003b372d, 0x00463f34, 0x004d4339, 0x0051433a, 0x005a4941, 0x0058463c, 0x005a4539, 0x00573f30, 0x00543c2b, 0x004c321f, 0x00593f2b, 0x005e432d, 0x005a3c22, 0x0058361a, 0x00543213, 0x0054300d, 0x00532c09, 0x0058300c, 0x00502702, 0x005c320c, 0x005c310c, 0x005c300b, 0x00643814, 0x00623610, 0x00643712, 0x00683915, 0x006b3c18, 0x006a3c15, 0x006a3c14, 0x00693c15, 0x00693c15, 0x006c3e18, 0x00643811, 0x0060340d, 0x00603512, 0x005e3312, 0x005b3214, 0x00552c11, 0x00512811, 0x0049230b, 0x004c280f, 0x0047240b, 0x0048230a, 0x0049250c, 0x00452107, 0x00482408, 0x00502a0d, 0x00542d0c, 0x0059310c, 0x005b300c, 0x0060340f, 0x00603310, 0x00643413, 0x00643512, 0x0062340f, 0x0064350f, 0x0062340f, 0x00603210, 0x00603210, 0x005b2e0c, 0x00582c0b, 0x00562b0b, 0x0054290a, 0x0051280b, 0x00502609, 0x0051280c, 0x0053280c, 0x0054290f, 0x00542b10, 0x0053280c, 0x00582d10, 0x005b3010, 0x005b300f, 0x005a330f, 0x005a3210, 0x0056300d, 0x00542e0c, 0x00512c09, 0x00522c0b, 0x0050290a, 0x0050280c, 0x004b240b, 0x004c270e, 0x004b250d, 0x00441e07, 0x00462209, 0x003f2009, 0x003b1d0b, 0x00301a0c, 0x001a0e01, 0x000c0e04, 0x00090e06, 0x000c0f08, 0x0016100a, 0x00211608, 0x00281c0c, 0x002d1e0c, 0x0034210f, 0x00312113, 0x002a1c12, 0x00241a12, 0x001a170f, 0x0013140d, 0x000e130d, 0x000a100b, 0x00081009, 0x00060e09, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00050d09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060d0b, 0x00060d0b, 0x00060e08, 0x00060e08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050d09, 0x00050d09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e06, 0x00060e06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c08, 0x00070c08, 0x00080c09, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x00494a0f, 0x004f500f, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005c5c11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00616112, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646514, 0x00646513, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x006c6914, 0x00a48c17, 0x00caa419, 0x00cba418, 0x00a58b16, 0x00616012, 0x00595a11, 0x00585810, 0x00535410, 0x00505010, 0x004c4d0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00050d08, 0x00040c08, 0x0008100b, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00041004, 0x00041004, 0x00041004, 0x00041004, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d09, 0x00050f0a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x00040f09, 0x00040f09, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0008120c, 0x0008120c, 0x0008120c, 0x0008120c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x00040e09, 0x00050e09, 0x00070f0a, 0x00070f0a, 0x00060f09, 0x00050d08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060f08, 0x00040d07, 0x00080e08, 0x0010110b, 0x0027241e, 0x0038342a, 0x004b433a, 0x004c4238, 0x0051433c, 0x0057463f, 0x00544239, 0x00554035, 0x00553e30, 0x00543929, 0x004c321e, 0x005b412d, 0x005e432d, 0x005c3e24, 0x0058381b, 0x00543011, 0x00542e0e, 0x00542d0d, 0x00583010, 0x00522a0b, 0x005e3414, 0x005c3311, 0x00582d0e, 0x005d3212, 0x005c3010, 0x00643817, 0x00613514, 0x00653817, 0x00683b18, 0x006a3d19, 0x00683c17, 0x00693d18, 0x006a4019, 0x00643913, 0x00613610, 0x00613611, 0x005f340e, 0x005e3210, 0x005c2f10, 0x00582d10, 0x00542b0e, 0x00542c0f, 0x0050290c, 0x004e2708, 0x00522b0d, 0x0050280b, 0x00532c0c, 0x00572f0c, 0x00582f09, 0x0060360f, 0x0060330d, 0x005f310b, 0x00643710, 0x00633410, 0x0062340e, 0x005e300c, 0x00603210, 0x005f320f, 0x005d300f, 0x005a2f0e, 0x00572b0c, 0x00542a0b, 0x0051280b, 0x004f2709, 0x004c240a, 0x004a2108, 0x004b2309, 0x004d240b, 0x004f260c, 0x004f260c, 0x00542b10, 0x00592f11, 0x005a3010, 0x005c310f, 0x005b3410, 0x005b3310, 0x00552f0c, 0x00512b08, 0x00512c08, 0x00512b0a, 0x0050290a, 0x00522c10, 0x004b240c, 0x004b250d, 0x004b250f, 0x00462009, 0x0044220c, 0x003a1f0a, 0x00361b0c, 0x00291409, 0x00180d05, 0x000d0e04, 0x00090e05, 0x000d1007, 0x0016100a, 0x00201709, 0x0024190a, 0x00251708, 0x002a190c, 0x002c1e14, 0x00281c14, 0x00211b14, 0x00191710, 0x00141410, 0x000e140e, 0x000a110c, 0x00081009, 0x00060e0a, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00050d09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060d0b, 0x00060d0b, 0x00060e08, 0x00060e08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e06, 0x00060e06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c08, 0x00060c08, 0x00070d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x006e6011, 0x00cca215, 0x00c29c15, 0x005c5911, 0x00595a12, 0x005b5b12, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646514, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00686814, 0x00847815, 0x00b59718, 0x00cba519, 0x00cba419, 0x00ac9016, 0x00686413, 0x005d5e12, 0x005b5b12, 0x00585810, 0x00545511, 0x00505010, 0x004c4d0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00051008, 0x00051007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0006100b, 0x00050e09, 0x00070f0a, 0x0008100b, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00040e07, 0x00080e08, 0x000c0d07, 0x001c1812, 0x00332e26, 0x00463e36, 0x004d4239, 0x0053443d, 0x0056453e, 0x00534239, 0x0058443a, 0x005a4234, 0x004f3422, 0x004e3420, 0x005c422e, 0x005d412c, 0x005e4025, 0x005a381b, 0x00563010, 0x00542d0d, 0x00572f13, 0x00572e14, 0x00532c11, 0x00563013, 0x00552f13, 0x00563014, 0x00542d0f, 0x00583012, 0x00603818, 0x005a3112, 0x005e3414, 0x00623817, 0x00663c1b, 0x00623816, 0x00623815, 0x00653b16, 0x00643a14, 0x00663c15, 0x00653a14, 0x0060350d, 0x0060340c, 0x0060320d, 0x00603210, 0x005f3310, 0x005c320f, 0x00562e0a, 0x00572f0b, 0x0058300c, 0x005b320f, 0x005f3610, 0x00623810, 0x0063380e, 0x006b3d14, 0x006a3c13, 0x00673810, 0x00683910, 0x0064360d, 0x0062340e, 0x005f310d, 0x005e3110, 0x005a2e0e, 0x00582c0e, 0x00542b0d, 0x0051280c, 0x0050270b, 0x004d250c, 0x004b240a, 0x0048210a, 0x00441e08, 0x00441e06, 0x00482209, 0x00502812, 0x00532b13, 0x00582f13, 0x00542c0d, 0x00592f0e, 0x005c3310, 0x005d3511, 0x005d3511, 0x0057310c, 0x00512c06, 0x00502a07, 0x004f2809, 0x00512b10, 0x004f2a10, 0x0049240c, 0x004c2810, 0x004c2a14, 0x00482510, 0x00452510, 0x00381f0c, 0x00341b0e, 0x00241108, 0x00140c04, 0x000d0f07, 0x00080f05, 0x000c1008, 0x0016110a, 0x001f1809, 0x00261c0d, 0x00281c10, 0x0024150c, 0x0022140d, 0x001e1610, 0x001b1511, 0x00151511, 0x00121510, 0x000f140e, 0x000b120c, 0x0008110a, 0x00070f0a, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00070f0a, 0x0008100b, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060d0b, 0x00060d0b, 0x00060e08, 0x00060e08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e06, 0x00060e06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c08, 0x00050c08, 0x00060d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003c3e0d, 0x0041420d, 0x0044450e, 0x0048490f, 0x004c4d0f, 0x006d6011, 0x00cca215, 0x00c29c15, 0x005c5911, 0x005b5910, 0x005c5c11, 0x005e5d12, 0x00605e12, 0x00605e12, 0x00605f12, 0x00616012, 0x00616012, 0x00616012, 0x00626113, 0x00626113, 0x00626113, 0x00626113, 0x00626113, 0x00626113, 0x00626113, 0x00636213, 0x00636213, 0x00646413, 0x00646412, 0x00646412, 0x00656514, 0x00666614, 0x00666614, 0x00686714, 0x00686814, 0x00696814, 0x006a6914, 0x006b6a14, 0x006c6b14, 0x00706d14, 0x007b7315, 0x008f7f16, 0x00af9418, 0x00c6a319, 0x00cca61a, 0x00caa519, 0x00a88d17, 0x006a6713, 0x00606013, 0x005d5e12, 0x005b5b12, 0x00585810, 0x00545511, 0x00505010, 0x004c4d10, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040e07, 0x00040e06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0004100a, 0x0004100a, 0x0005100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100b, 0x0005100b, 0x0005100b, 0x0005100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00060f09, 0x00070f0a, 0x0008100b, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070e08, 0x000c0c07, 0x0012100a, 0x002e2921, 0x003a332a, 0x00453b32, 0x004c3e36, 0x0057453f, 0x00524238, 0x00544134, 0x00553e2f, 0x004c321f, 0x004f3520, 0x005d442f, 0x00644830, 0x005c3f25, 0x0059381a, 0x00583212, 0x00532c0f, 0x00522b10, 0x00502910, 0x004a250c, 0x004c280e, 0x004c280d, 0x004f2c11, 0x004f2c10, 0x004f2a0e, 0x00522e10, 0x00573012, 0x00603a1c, 0x005d3718, 0x00603a19, 0x00623919, 0x00613918, 0x00633916, 0x00633a15, 0x00683e18, 0x00683c14, 0x00673b11, 0x00683a10, 0x00673810, 0x00673811, 0x00653812, 0x00633811, 0x00603610, 0x005f350f, 0x005f350f, 0x00623811, 0x00653c14, 0x00673d13, 0x00693d12, 0x006c3f14, 0x006c3c13, 0x006c3c13, 0x0068380f, 0x0063340c, 0x0061330d, 0x0060330f, 0x005c2f0f, 0x00542a0c, 0x0051280c, 0x0050270b, 0x004e270c, 0x004e270c, 0x004b230a, 0x00492108, 0x004a220b, 0x00461e07, 0x00461d06, 0x00482109, 0x0049230c, 0x00512a13, 0x00532a0f, 0x00522809, 0x00592f0d, 0x005c330f, 0x005e370f, 0x005d360e, 0x0059320c, 0x00542d08, 0x00502908, 0x004c2406, 0x004c280c, 0x0048240a, 0x0049260c, 0x0044230c, 0x0043220c, 0x0040200c, 0x003c1c0a, 0x00361e0c, 0x00301b10, 0x001e1007, 0x00100c04, 0x000c1008, 0x00091007, 0x000c1006, 0x00141309, 0x001d1809, 0x00261c10, 0x002c2015, 0x002a1c14, 0x0020140f, 0x001c140f, 0x00181410, 0x00131510, 0x00111410, 0x000e140e, 0x000b120c, 0x0008110a, 0x00070f09, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080d09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050c0a, 0x00050d09, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c09, 0x00040c0a, 0x00060d0b, 0x00060e0a, 0x00060e08, 0x00060e08, 0x00040f08, 0x00031008, 0x00031008, 0x00031008, 0x00040f08, 0x00050e08, 0x00060e08, 0x00060e09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e07, 0x00060e06, 0x00040f06, 0x00031006, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a0f, 0x006c5f10, 0x00cca215, 0x00c9a016, 0x00ba9615, 0x00ba9615, 0x00ba9715, 0x00ba9716, 0x00ba9716, 0x00ba9716, 0x00ba9816, 0x00ba9815, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00bb9818, 0x00bb9818, 0x00bb9818, 0x00bb9818, 0x00bb9817, 0x00bb9917, 0x00bb9917, 0x00bb9a18, 0x00bb9a18, 0x00bb9b18, 0x00bb9b18, 0x00bb9b18, 0x00bc9b18, 0x00bc9c19, 0x00bc9c19, 0x00bd9d18, 0x00c4a119, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00c3a119, 0x00978415, 0x00686714, 0x00636414, 0x00616112, 0x005e5f12, 0x005b5b11, 0x00585910, 0x00545511, 0x00515110, 0x004c4d10, 0x0048490e, 0x0044450e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050c07, 0x00080c08, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x0008100b, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050f08, 0x00051008, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x0004100a, 0x00041009, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f0b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060f09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00070e08, 0x00090e08, 0x000e0e08, 0x0027241c, 0x00322c24, 0x003e342d, 0x004a3d36, 0x00504038, 0x0049392f, 0x004e3c2f, 0x004c3726, 0x004b301d, 0x00493019, 0x0058412a, 0x00614830, 0x005d4026, 0x005a381b, 0x00553111, 0x00542f10, 0x00552f13, 0x00502a11, 0x0046230a, 0x0044220b, 0x0044220b, 0x0045230a, 0x00462409, 0x0049280b, 0x00502d11, 0x00583416, 0x005c381b, 0x005b3617, 0x005c3618, 0x005d3618, 0x00603818, 0x00613818, 0x00633918, 0x00643915, 0x00653813, 0x00663910, 0x00673a10, 0x00673810, 0x00673811, 0x00673912, 0x00673a15, 0x00683c17, 0x00663b17, 0x00633813, 0x00603510, 0x0060340f, 0x00603410, 0x00603410, 0x00623510, 0x00633411, 0x0060310e, 0x005c2c0b, 0x00582806, 0x00582806, 0x00502301, 0x004c2000, 0x004b2003, 0x00461d01, 0x00451c00, 0x004b2102, 0x00512708, 0x00582d0f, 0x00592f13, 0x005c3115, 0x00562b0e, 0x0052280a, 0x004f250b, 0x0048220a, 0x004c240c, 0x00502708, 0x00542909, 0x0059300c, 0x005c340c, 0x0060370c, 0x005d340a, 0x00583008, 0x00562c08, 0x0050280b, 0x004c270a, 0x004a260b, 0x00462408, 0x0045230b, 0x0042220b, 0x0040210c, 0x003d200d, 0x00351c0b, 0x00321b0d, 0x0026150a, 0x00130a03, 0x00100e07, 0x000b1208, 0x000a1008, 0x000c1005, 0x00141409, 0x00191409, 0x00251910, 0x002d1c15, 0x002f2018, 0x00251910, 0x001c140b, 0x0018140c, 0x0012140c, 0x000f130e, 0x000e140e, 0x000c140e, 0x0009110b, 0x00070f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070e0c, 0x00070f0a, 0x00060e09, 0x00060e08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280c, 0x002c2d0b, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0044450d, 0x0048490f, 0x00565210, 0x00b08d14, 0x00cca215, 0x00cca216, 0x00cca316, 0x00cca316, 0x00cca316, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca518, 0x00cca518, 0x00cca519, 0x00cca519, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00caa61a, 0x00c3a119, 0x00a99017, 0x007c7315, 0x00656614, 0x00646514, 0x00636414, 0x00616112, 0x005e5f12, 0x005c5c11, 0x00585910, 0x00555610, 0x00515110, 0x004c4d10, 0x0048490f, 0x0044450e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050c07, 0x00060c08, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x0004100a, 0x00041009, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f0b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110c, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060f0a, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f08, 0x00080e08, 0x000c0f08, 0x001c1a14, 0x002a251e, 0x003c342d, 0x004b4038, 0x004e4038, 0x00473a30, 0x00534435, 0x00543d2c, 0x00543a27, 0x00503721, 0x005c432c, 0x00644b33, 0x00604328, 0x005c3c1d, 0x00563211, 0x00573211, 0x00583414, 0x00502a0f, 0x00482409, 0x0049250c, 0x004a240b, 0x00472108, 0x00441e03, 0x00482406, 0x00502b0c, 0x00522d0e, 0x00512c0e, 0x00532e10, 0x00542f10, 0x00542d0f, 0x00552d10, 0x00552c0f, 0x00572c0f, 0x00582e0d, 0x00582e09, 0x00582e07, 0x00582d07, 0x00582c07, 0x005a2c09, 0x005a2d0a, 0x005b2e0c, 0x005c2f0e, 0x005a2e0f, 0x00572b0c, 0x00512507, 0x00502406, 0x004f2304, 0x00502407, 0x00532408, 0x00542508, 0x00522204, 0x004e1d00, 0x004c1c00, 0x004c1d00, 0x004c1c00, 0x004f1f01, 0x00502104, 0x004f2304, 0x00542706, 0x00603210, 0x00683b15, 0x006c3f19, 0x0070421c, 0x0070411c, 0x00693b16, 0x00623410, 0x00582e0c, 0x004e2508, 0x004c240b, 0x00522a0b, 0x00572d0b, 0x005c340f, 0x00603610, 0x005d340c, 0x00582f07, 0x00562c08, 0x00532908, 0x0052280c, 0x00522c10, 0x00472208, 0x00412006, 0x0044240c, 0x0041220c, 0x003f210c, 0x003c200d, 0x00341c0b, 0x002d170a, 0x00211409, 0x00130c04, 0x000e0e07, 0x000c1108, 0x000c100a, 0x000e0f07, 0x00151409, 0x001d150b, 0x0023140a, 0x0029170d, 0x00312014, 0x00302416, 0x00281f14, 0x00211c13, 0x001c1b14, 0x00151711, 0x000d120c, 0x00091009, 0x00070f08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c0a, 0x00040c08, 0x00060e09, 0x00060e08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x0014180f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0045470e, 0x00494a10, 0x00605810, 0x00a08212, 0x00a48613, 0x00a58814, 0x00a58814, 0x00a58814, 0x00a58814, 0x00a58814, 0x00a48814, 0x00a58814, 0x00a48914, 0x00a58914, 0x00a48914, 0x00a48914, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48915, 0x00a48815, 0x00a48815, 0x00a48915, 0x00a48916, 0x00a48a15, 0x00a48b15, 0x00a48b16, 0x00a48b16, 0x00a48b16, 0x00a48c16, 0x00a48c18, 0x00a48c18, 0x00a48c18, 0x009e8917, 0x00908016, 0x00777114, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00646414, 0x00626312, 0x005e5f13, 0x005c5c11, 0x00585911, 0x00555610, 0x00515110, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d08, 0x00060c08, 0x00060d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00020e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x0004100a, 0x00041009, 0x00040d08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060f09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e0b, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00061009, 0x00061009, 0x00061009, 0x00061009, 0x00070f08, 0x00070f08, 0x00081009, 0x00060f08, 0x00040d05, 0x00071007, 0x00071007, 0x00071007, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00051009, 0x00051008, 0x00061009, 0x00070f0a, 0x00070f0a, 0x0007100b, 0x000a100a, 0x00191c16, 0x0025241e, 0x00342e28, 0x00433932, 0x00493e34, 0x0044382d, 0x004c3c2f, 0x00553f30, 0x00503724, 0x00503420, 0x00573d27, 0x00634932, 0x00604429, 0x005c3b1d, 0x005c3815, 0x0058330f, 0x00532d0c, 0x004f280a, 0x004b2607, 0x004b2406, 0x00522c0d, 0x00542e0f, 0x00532b0c, 0x00542c0c, 0x00572f0d, 0x00512908, 0x004d2605, 0x004c2507, 0x004c2506, 0x004d2406, 0x004e2508, 0x0051260b, 0x0050250a, 0x00502408, 0x004f2504, 0x004f2504, 0x004e2403, 0x004c2102, 0x004c2000, 0x004b1e00, 0x004c1f02, 0x004b1c00, 0x00481c00, 0x00481c01, 0x00471b00, 0x00451800, 0x00421600, 0x00431800, 0x00461900, 0x004b1c01, 0x004c1d01, 0x00542408, 0x005c2c10, 0x005d2c10, 0x005e2c0f, 0x00643114, 0x00643011, 0x00653311, 0x006b3814, 0x00744018, 0x00713e13, 0x00744214, 0x00764416, 0x00744013, 0x00703d10, 0x0065360a, 0x005d3008, 0x00582c0c, 0x00542b0f, 0x00542c0b, 0x005c3210, 0x005e3510, 0x005e350e, 0x005c330c, 0x00572d08, 0x00512806, 0x004f2407, 0x0051280d, 0x004e280f, 0x0048240c, 0x00401f06, 0x0040220b, 0x003e200a, 0x003c1f0c, 0x003e2210, 0x00321a0a, 0x002a160a, 0x001c1006, 0x00130f08, 0x000e100a, 0x000e100a, 0x000f100a, 0x00141009, 0x0019150c, 0x0021170d, 0x0028160d, 0x002a1408, 0x002e1b0a, 0x00312211, 0x002d2012, 0x00271e14, 0x001e1a13, 0x0013140f, 0x000c110c, 0x0009100a, 0x00081009, 0x00060e08, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060d0b, 0x00060e09, 0x00070f0a, 0x00070f09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00050e08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250b, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x003c3e0c, 0x0040400d, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4c0f, 0x004d4d10, 0x00505010, 0x00515110, 0x00535410, 0x00545411, 0x00555511, 0x00555511, 0x00565711, 0x00565710, 0x00585810, 0x00585810, 0x00585810, 0x00585810, 0x00585810, 0x00585811, 0x00585811, 0x00585811, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x005c5c12, 0x005d5d12, 0x005e5f13, 0x00606013, 0x00606013, 0x00626213, 0x00636314, 0x00646414, 0x00656514, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00686814, 0x00686814, 0x00646513, 0x00646414, 0x00616112, 0x005e5f13, 0x005c5c11, 0x00595a11, 0x00555610, 0x00515110, 0x004d4e0f, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0005100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x0004100a, 0x00041009, 0x00040d08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060f09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060d08, 0x00070d09, 0x00060e0b, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110c, 0x0009110d, 0x00070f0b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x00061009, 0x00061009, 0x00061009, 0x00061009, 0x00071007, 0x00071007, 0x0009120a, 0x00081008, 0x00040d05, 0x00071007, 0x00071007, 0x00071007, 0x0007110a, 0x0007110c, 0x0005100a, 0x0005100a, 0x00051009, 0x00051008, 0x00061009, 0x00070f0a, 0x00070f0a, 0x0006100b, 0x0009110b, 0x00161b15, 0x00282923, 0x002c2c25, 0x00353129, 0x00443c33, 0x00443c30, 0x00554538, 0x00554030, 0x00543928, 0x004c301c, 0x00573d29, 0x005e442e, 0x005e4227, 0x005a3b1c, 0x00573410, 0x0058340e, 0x00583210, 0x00542e0d, 0x00552d0d, 0x00532b09, 0x005b3210, 0x00633917, 0x00653c18, 0x00683e1c, 0x006c421f, 0x00683f1e, 0x00623818, 0x005e3618, 0x005e3618, 0x005e3519, 0x005d3519, 0x005e3418, 0x005c3015, 0x005c3010, 0x0054290a, 0x00532707, 0x00522507, 0x00502206, 0x00502004, 0x004d1d01, 0x004c1c00, 0x004c1d00, 0x004c1d00, 0x004d1e00, 0x00512103, 0x00542507, 0x00552809, 0x005c2f10, 0x005e3011, 0x00623414, 0x00663818, 0x00653617, 0x00673717, 0x00683616, 0x00693616, 0x006a3514, 0x006a3411, 0x006d3812, 0x00713a12, 0x00743f12, 0x00723c0c, 0x0076410c, 0x0078430e, 0x00753f0a, 0x00703d08, 0x006a3a08, 0x00633308, 0x005c2f0c, 0x005a2e10, 0x00572d0c, 0x005c3310, 0x005c340e, 0x005c340c, 0x005b320b, 0x00542a05, 0x00512806, 0x004e2508, 0x004e240a, 0x0048220a, 0x00431f08, 0x00412109, 0x0040210c, 0x003d1e09, 0x003b1d0b, 0x00361808, 0x00341c0c, 0x0028180c, 0x00170e04, 0x00121108, 0x000e110b, 0x000f100a, 0x00100f09, 0x0017130b, 0x001e170e, 0x00251810, 0x0028180d, 0x002a1609, 0x002e1c0b, 0x0030210f, 0x002b1e0e, 0x00261c10, 0x001d1810, 0x0013140f, 0x000c140d, 0x0009130c, 0x0007110a, 0x00061009, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e07, 0x00050e06, 0x00050e06, 0x00050e06, 0x00060e08, 0x00060e09, 0x00050d09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0a, 0x002c2d0a, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x004f5010, 0x00505010, 0x00515110, 0x00525310, 0x00535410, 0x00545510, 0x00545510, 0x00555611, 0x00545511, 0x00555611, 0x00565711, 0x00555610, 0x00555611, 0x00565710, 0x00565710, 0x00565710, 0x00585910, 0x00585911, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005d5e11, 0x005e5f12, 0x00606013, 0x00616112, 0x00626313, 0x00646414, 0x00646514, 0x00666714, 0x00686815, 0x006b6a14, 0x008a7c15, 0x008d7e15, 0x008d7e15, 0x008d7e15, 0x008c7d15, 0x008c7d16, 0x008c7c14, 0x008b7b14, 0x008b7a14, 0x00897814, 0x007c6f13, 0x005b5a11, 0x00555610, 0x00525310, 0x004d4e0f, 0x0048490f, 0x0045470e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00080d09, 0x00080c09, 0x00080d09, 0x00050e09, 0x00040e09, 0x00030d08, 0x00010d08, 0x00030f09, 0x00030f09, 0x0004100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x00090f0b, 0x00090f0b, 0x000a100c, 0x000a100c, 0x00081009, 0x00081009, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110a, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x0008110a, 0x0008110a, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x0008100b, 0x000c130f, 0x00131913, 0x002a2e29, 0x002e2f2a, 0x00323029, 0x00383329, 0x00403a2d, 0x00504434, 0x00534030, 0x0058402e, 0x00503422, 0x00533824, 0x00543924, 0x005c4025, 0x00563819, 0x0052310e, 0x005c3814, 0x005a3310, 0x0058300d, 0x005b3110, 0x005d330e, 0x00613610, 0x00673c14, 0x00683e14, 0x006c4219, 0x00744822, 0x00764a28, 0x00744728, 0x00714729, 0x006e4428, 0x006a4125, 0x00673d23, 0x006b401b, 0x0070431b, 0x00744218, 0x00764017, 0x00754018, 0x00743e19, 0x00743d1b, 0x00733d18, 0x00703d15, 0x006f3c14, 0x006c3910, 0x006c3910, 0x006c3a10, 0x006f3c13, 0x00703e15, 0x00703d16, 0x00703c15, 0x006d3b14, 0x006c3a13, 0x00693810, 0x00673610, 0x0067350f, 0x0068350f, 0x006a350f, 0x006a3510, 0x006c370f, 0x006c370c, 0x006e370a, 0x00703809, 0x00723a0a, 0x00743c0c, 0x00773f0d, 0x00753d0c, 0x00713b0c, 0x006d3c11, 0x0066360d, 0x005c2f09, 0x00592e0a, 0x005b320e, 0x005b330f, 0x005a330d, 0x005c320d, 0x005b320c, 0x00502804, 0x004e2805, 0x004f2809, 0x004c240b, 0x0048220a, 0x00411f07, 0x0040230c, 0x003e210c, 0x003c1f0a, 0x003c200e, 0x00351709, 0x0032180c, 0x001c1003, 0x00161004, 0x00111208, 0x0010140b, 0x0012110a, 0x00161008, 0x001e140b, 0x0024180d, 0x002a1a11, 0x002d1b11, 0x0028170a, 0x002a1908, 0x00302110, 0x002d2011, 0x00271d10, 0x00201710, 0x00151510, 0x000e150f, 0x000b130c, 0x0008120b, 0x0007110a, 0x0006100b, 0x0006100b, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0009120c, 0x0009120c, 0x0009130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a120c, 0x0009110c, 0x0009110c, 0x000a120e, 0x000a120e, 0x0009110d, 0x0008100c, 0x0008100c, 0x0008100c, 0x0009120b, 0x000a130c, 0x000a130c, 0x000a130c, 0x00081109, 0x00081109, 0x00081108, 0x00081008, 0x0009100b, 0x00080f0a, 0x00060e09, 0x00060f0a, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d09, 0x00040d09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00080f0a, 0x00081009, 0x00060e08, 0x00040d07, 0x00040e07, 0x00030e07, 0x00030e07, 0x00041008, 0x00041008, 0x0004100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060b07, 0x00050b05, 0x00070c06, 0x00070d06, 0x00060f08, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040e07, 0x00020e07, 0x00020e07, 0x00031008, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280a, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004b4c0f, 0x004c4d0f, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00525310, 0x00535410, 0x00535410, 0x00535410, 0x00545510, 0x00535410, 0x00545510, 0x00555611, 0x00545510, 0x00565711, 0x00565711, 0x00585810, 0x00585911, 0x00595a12, 0x005c5c11, 0x005d5e11, 0x005e5f13, 0x00606013, 0x00616112, 0x00636414, 0x00646514, 0x00666713, 0x00686714, 0x00a48c17, 0x00c8a519, 0x00caa51a, 0x00caa51a, 0x00caa51a, 0x00caa51a, 0x00caa41a, 0x00c9a419, 0x00c9a419, 0x00c9a418, 0x00c9a318, 0x00c7a017, 0x008e7a13, 0x00545511, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0040400d, 0x003c3e0d, 0x0036370c, 0x0032330c, 0x002d2f0a, 0x0026280a, 0x0026280c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00080d09, 0x00080c09, 0x00080c09, 0x00050e09, 0x00040e09, 0x00030d08, 0x00010d08, 0x00030f09, 0x00030f09, 0x0004100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x00081009, 0x00081009, 0x0008110b, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120b, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x0008110a, 0x0008110a, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0009100b, 0x00080f0a, 0x000b100c, 0x000e1310, 0x001a1e1b, 0x00303532, 0x0031322e, 0x002e2c26, 0x002d2920, 0x003d372a, 0x00473c2c, 0x00483928, 0x00503b28, 0x00533826, 0x0049301a, 0x0050351f, 0x00583c23, 0x0056381b, 0x00523211, 0x005b3716, 0x00593412, 0x005a310e, 0x005c320e, 0x00623711, 0x00693c14, 0x00683c12, 0x006e4218, 0x0070441a, 0x00784b24, 0x00764a28, 0x00754829, 0x0075482b, 0x0072462b, 0x006e4428, 0x006b4124, 0x006b411c, 0x006d4018, 0x00704015, 0x00743f14, 0x00763d13, 0x00783c13, 0x00783c13, 0x00783d13, 0x007c4217, 0x007c4317, 0x00774012, 0x00753d11, 0x00743c10, 0x00743c10, 0x00743c10, 0x00743c11, 0x00723a10, 0x006e350c, 0x006c360b, 0x0069340b, 0x0068350b, 0x0066360c, 0x0066370c, 0x0067370f, 0x0067370f, 0x0067360d, 0x0068360a, 0x006a3709, 0x006f3909, 0x00703a09, 0x00713b0a, 0x00743e0c, 0x00733d0c, 0x006f3a0b, 0x006d3c11, 0x0066360e, 0x005a2c06, 0x005c310c, 0x005e3511, 0x005c3511, 0x0058310c, 0x0058310c, 0x00552f09, 0x00512b06, 0x00492604, 0x00492708, 0x004a260c, 0x00432008, 0x003c1c05, 0x0040220c, 0x003d200c, 0x003c1f0b, 0x003c200e, 0x00371b0d, 0x002c170a, 0x00140c00, 0x00141006, 0x00141309, 0x0014140c, 0x0018140b, 0x001c1209, 0x0024170d, 0x00291b11, 0x002d1c12, 0x002d1d11, 0x002b1b0e, 0x0029190b, 0x002b1c0e, 0x002a1c10, 0x00271d12, 0x00211811, 0x00161610, 0x000f150e, 0x000c140e, 0x000b150e, 0x000a140d, 0x0009130e, 0x0009130e, 0x0008120c, 0x0008120c, 0x0008120d, 0x0008120d, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x0009110d, 0x0009110d, 0x000a120e, 0x000a120e, 0x000a120e, 0x000a120e, 0x000a120e, 0x000a120e, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x00081109, 0x00081108, 0x0009120a, 0x000a130b, 0x000b120d, 0x0009100c, 0x00070f0a, 0x00060f0a, 0x0006100b, 0x0006100b, 0x00050f0a, 0x0006100b, 0x0006100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00080f0a, 0x00091009, 0x00060e08, 0x00040d07, 0x00040e07, 0x00020e07, 0x00020e07, 0x00041008, 0x00041008, 0x0004100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00080c09, 0x00080c08, 0x00070d08, 0x00070e06, 0x00050f08, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040e07, 0x00020e07, 0x00020e07, 0x00031008, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0c, 0x00191c09, 0x001d2009, 0x00202308, 0x0020230a, 0x0026280b, 0x00292b0a, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003c3e0c, 0x0040400d, 0x0041420e, 0x0044450d, 0x0047480e, 0x0048490f, 0x00494a0f, 0x004b4c0f, 0x004c4d0f, 0x004f5010, 0x004f5010, 0x00505010, 0x004f5010, 0x00515110, 0x00505010, 0x00505010, 0x00515110, 0x00515110, 0x00525310, 0x00535410, 0x00535410, 0x00545510, 0x00545511, 0x00555611, 0x00565710, 0x00585911, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00626313, 0x00646414, 0x00656614, 0x006a6714, 0x00c5a219, 0x00cca71a, 0x00c4a019, 0x00c1a019, 0x00c1a019, 0x00c1a018, 0x00c19f18, 0x00c19f18, 0x00c19f18, 0x00c19f18, 0x00c6a018, 0x00cca418, 0x00b09014, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003b3c0c, 0x0036370b, 0x0034350c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00080d09, 0x00080c09, 0x00080c09, 0x00050e09, 0x00040e09, 0x00030d08, 0x00010d08, 0x00030f09, 0x0004100a, 0x0004100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x0008110a, 0x0008110a, 0x0009110d, 0x0009110d, 0x000a120e, 0x000a120e, 0x000a130c, 0x000a130c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009140b, 0x0009140b, 0x0009130b, 0x0009140b, 0x000b130c, 0x000b130c, 0x000b130c, 0x000b140b, 0x0009120c, 0x0009120c, 0x0009130c, 0x0009130c, 0x0009130c, 0x0009130c, 0x000b130e, 0x000b130f, 0x000b130e, 0x000b130e, 0x000b110e, 0x00101412, 0x00151918, 0x001c201e, 0x00222624, 0x00303230, 0x00343734, 0x00363733, 0x002d2b26, 0x0029251c, 0x00353024, 0x0041392a, 0x00403322, 0x00493523, 0x004c3521, 0x004b311a, 0x00523720, 0x00553b23, 0x0053351c, 0x00563519, 0x00573416, 0x005a3312, 0x005c320d, 0x005b310a, 0x005e340b, 0x00643a0f, 0x00693d10, 0x006c4013, 0x0070441b, 0x00754822, 0x00754925, 0x00714624, 0x00744728, 0x00744728, 0x00764c2c, 0x00734928, 0x006c4320, 0x006a3f19, 0x006c3e16, 0x00703d13, 0x00713b10, 0x0074390d, 0x0074390d, 0x0074390c, 0x00743a0d, 0x00743c0e, 0x00743c10, 0x00733b0f, 0x0070380c, 0x0070380c, 0x0070390c, 0x0070380e, 0x006d350c, 0x006a3208, 0x00693308, 0x00683309, 0x00663409, 0x0062360b, 0x0062370b, 0x0061370c, 0x0062370d, 0x0062360b, 0x0064380a, 0x006b3c0c, 0x006e3d0c, 0x006f3c0a, 0x00703d0b, 0x00713e0c, 0x006e3b09, 0x006b3808, 0x0068370d, 0x0062320a, 0x00582c05, 0x00582d08, 0x00562e08, 0x0058310c, 0x0059320c, 0x00562f09, 0x00522c09, 0x004c2907, 0x00462505, 0x00442608, 0x003c1d04, 0x003c1f07, 0x003c2008, 0x003a1e08, 0x003b1d09, 0x003e210f, 0x00371d0e, 0x00291405, 0x00201104, 0x00100c00, 0x000f0c02, 0x0015120c, 0x001a150e, 0x00241c12, 0x002a1d14, 0x002c1c11, 0x002d1c11, 0x002d1d11, 0x002e1e11, 0x002e1e10, 0x002f1f10, 0x002c1e11, 0x002a1d12, 0x00281e15, 0x00231914, 0x001a1812, 0x00131610, 0x000e140e, 0x000d140e, 0x000c140d, 0x000a120e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0008120c, 0x0008120d, 0x0009110c, 0x0009110d, 0x000a120e, 0x000a120e, 0x000c140d, 0x000c140d, 0x000c140e, 0x000c140d, 0x000c140d, 0x000c140e, 0x000d150f, 0x000d150f, 0x000c140f, 0x000c1410, 0x000c1410, 0x000d1510, 0x000d1510, 0x000d1510, 0x000d1510, 0x000c140f, 0x000a120e, 0x0009120c, 0x0009120c, 0x000c140d, 0x000c140d, 0x000a120b, 0x000c140c, 0x000a130b, 0x000a130b, 0x000b120d, 0x000b120e, 0x0009110d, 0x0008110c, 0x0008120c, 0x0009130e, 0x0009130e, 0x0008120c, 0x0008110c, 0x0009100c, 0x0009110c, 0x0008100c, 0x00070f0a, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f09, 0x00080e08, 0x00070f08, 0x00070f08, 0x00051008, 0x00031008, 0x00041008, 0x00041008, 0x00041008, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00090e0b, 0x00091009, 0x00080f08, 0x00061008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040e07, 0x00020e07, 0x00020e07, 0x00031008, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280a, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0040400d, 0x0043440e, 0x0044450d, 0x0045470e, 0x0047480f, 0x0048490f, 0x00494a0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004c4d0f, 0x004f5010, 0x004f5010, 0x004d4e10, 0x00505010, 0x00505010, 0x00505010, 0x00515110, 0x00515110, 0x00525310, 0x00535410, 0x00545511, 0x00555611, 0x00565710, 0x00585911, 0x005b5b12, 0x005c5d11, 0x005d5e12, 0x00606012, 0x00616112, 0x00626314, 0x00646414, 0x006a6714, 0x00c6a219, 0x00cca61a, 0x00847715, 0x00736e14, 0x00736e14, 0x00736e14, 0x00726d14, 0x00716c14, 0x00706a14, 0x006e6814, 0x009f8615, 0x00cca418, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x0030310c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00080d09, 0x00080c09, 0x00080c09, 0x00050e09, 0x00040e09, 0x00030d08, 0x00010d08, 0x00030f09, 0x0004100a, 0x0006120c, 0x0007120c, 0x00070f08, 0x00070f08, 0x0008110a, 0x0008110a, 0x0008120d, 0x0008120d, 0x0009130e, 0x0009130e, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x0009120c, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x0008140b, 0x0008140b, 0x0009150c, 0x000a150c, 0x000c150c, 0x000c150c, 0x000c150c, 0x000c150c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c1410, 0x000c1410, 0x000c1411, 0x000d1412, 0x000e1411, 0x00141816, 0x001b1f1c, 0x00282c29, 0x00353837, 0x00393b3b, 0x00363837, 0x00343434, 0x002d2c28, 0x0026241b, 0x002a281b, 0x00383324, 0x00423827, 0x00493826, 0x0049341f, 0x004d341c, 0x0050341c, 0x00563b24, 0x0052351f, 0x00573820, 0x005a381c, 0x005c3614, 0x005b330c, 0x005e340a, 0x0063380e, 0x0064390c, 0x006a3f10, 0x006d4213, 0x0074471d, 0x00794b24, 0x00754824, 0x00744624, 0x00704422, 0x00704423, 0x00734928, 0x00704724, 0x006b441f, 0x00693f1a, 0x006c3f19, 0x00693a11, 0x0068380b, 0x006c380b, 0x006c380c, 0x006c380c, 0x006b370c, 0x006a370c, 0x006a380d, 0x0069370d, 0x0066340b, 0x0067340b, 0x0067350c, 0x0068350c, 0x0064320a, 0x00633008, 0x00613108, 0x00613108, 0x005f3208, 0x005d3409, 0x005c3409, 0x0060370c, 0x0060380c, 0x0061380c, 0x00643b0c, 0x006a3e0d, 0x006c3e0d, 0x006d3c0b, 0x00703e0c, 0x00713f0c, 0x006c3c09, 0x00693808, 0x0065340a, 0x005e2e06, 0x00582c05, 0x00562c08, 0x00522c07, 0x00542f08, 0x004e2904, 0x00512c08, 0x004c2907, 0x00482506, 0x00442608, 0x0042260a, 0x003a1e05, 0x003b2007, 0x00391e08, 0x00381b07, 0x003c1d0c, 0x00371b0a, 0x00321b0c, 0x00241204, 0x00150c00, 0x000e0d00, 0x000e0c03, 0x0018140d, 0x00201811, 0x002a1f14, 0x002f2015, 0x00302014, 0x00312014, 0x00312014, 0x00322214, 0x00322214, 0x00322213, 0x00302114, 0x002d2016, 0x002a2018, 0x00241b16, 0x001b1813, 0x00141510, 0x0010140f, 0x000f140e, 0x000c120c, 0x000a140f, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x000b1410, 0x000b1510, 0x000c140f, 0x000c140f, 0x000b130e, 0x000a120e, 0x000c140d, 0x000c140e, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000c1410, 0x000c1410, 0x000d1510, 0x000d1510, 0x000d1510, 0x000d1510, 0x000d1510, 0x000c140f, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140c, 0x000d160e, 0x000b130c, 0x000a130c, 0x000b120d, 0x000b120e, 0x000a120e, 0x000b130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0009110d, 0x0009110d, 0x0009100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f09, 0x00080e08, 0x00070f08, 0x00070f08, 0x00051008, 0x00041008, 0x00051009, 0x00041008, 0x00041008, 0x00040f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00080f0b, 0x0008100a, 0x00070f08, 0x00061008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040e07, 0x00030e07, 0x00030e07, 0x00041008, 0x00041008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250c, 0x0026280b, 0x002c2d0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003b3c0c, 0x003e400c, 0x0040400d, 0x0043440e, 0x0044450d, 0x0045470d, 0x0047480e, 0x0048490f, 0x00494a10, 0x004b4c10, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e10, 0x004f5010, 0x00505010, 0x00515110, 0x00515110, 0x00525310, 0x00545510, 0x00555611, 0x00585810, 0x00585911, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00626313, 0x00646414, 0x00696614, 0x00c6a218, 0x00cca61a, 0x007c7315, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00646514, 0x00646414, 0x00616112, 0x009b8415, 0x00cca418, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e09, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e07, 0x00060e08, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e09, 0x00080c09, 0x00080c0a, 0x00070c0b, 0x00060e0b, 0x0005100a, 0x0004100a, 0x0007110d, 0x0008120d, 0x0008110b, 0x0008120a, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0008120c, 0x0008120c, 0x0009140c, 0x0009140c, 0x000c140d, 0x000c140d, 0x000b140d, 0x000b140d, 0x000b140d, 0x000b140d, 0x000c140d, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d160d, 0x000d160d, 0x000c150c, 0x000c150c, 0x000d140c, 0x000d140c, 0x000e140c, 0x000e140c, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c1510, 0x000b1410, 0x000f1614, 0x00151b18, 0x00171b17, 0x0020231e, 0x00292c27, 0x00343632, 0x00363636, 0x00323234, 0x002f2f2f, 0x0023231f, 0x001b1a11, 0x00242418, 0x002a2819, 0x00373020, 0x00403220, 0x0046341e, 0x00483018, 0x004f341c, 0x00593e28, 0x00543624, 0x00573723, 0x005b381f, 0x005c3718, 0x005b340e, 0x005c340c, 0x00603810, 0x00643a10, 0x006a3e14, 0x006e4016, 0x00774820, 0x00754720, 0x00754823, 0x00744823, 0x00704520, 0x00704520, 0x006d441f, 0x0069401b, 0x00673d18, 0x00633a13, 0x00613810, 0x0062360d, 0x0062360a, 0x00603508, 0x0060340a, 0x0060340c, 0x0060340c, 0x005f330a, 0x005b3108, 0x00582f06, 0x00593008, 0x005a3008, 0x00593008, 0x00593008, 0x005c320c, 0x005b310b, 0x00582d08, 0x005d2f08, 0x005f3108, 0x00603308, 0x00613409, 0x0064350b, 0x0063360b, 0x0064380c, 0x00683c0f, 0x006b3c0e, 0x006c3c0c, 0x00703d0b, 0x006e3c09, 0x006c3a08, 0x006b3a09, 0x00653808, 0x005a2f04, 0x00562c02, 0x0058310a, 0x0058310a, 0x00542e08, 0x00502c08, 0x004a2804, 0x004c2c08, 0x00402000, 0x00402104, 0x0043240b, 0x00371a02, 0x00381d06, 0x00391c07, 0x00381c08, 0x00381c08, 0x003b1d0b, 0x00351a09, 0x002c1708, 0x00201207, 0x00100c01, 0x000c0f06, 0x000e0d05, 0x00171208, 0x0022170c, 0x002e2013, 0x00342519, 0x002c1f14, 0x002a1e14, 0x00302118, 0x00332518, 0x00332517, 0x00302212, 0x002d2012, 0x002c2115, 0x002b221a, 0x00221c16, 0x001a1812, 0x00171511, 0x00121410, 0x0011140f, 0x000f140f, 0x000a140f, 0x000a140f, 0x000a140f, 0x000a140f, 0x000b150e, 0x000b150e, 0x000b150e, 0x000b150e, 0x000d150f, 0x000e1610, 0x000d150f, 0x000d150f, 0x000e1610, 0x000e1710, 0x000f1710, 0x000d150f, 0x000e1710, 0x000f1811, 0x000f1811, 0x000e1710, 0x000e1710, 0x000e1612, 0x000e1612, 0x000e1612, 0x000f1713, 0x000e1612, 0x000e1612, 0x000e1612, 0x000e1612, 0x000e1710, 0x000f1610, 0x000e150f, 0x000e150f, 0x000e1510, 0x000e1510, 0x000e1510, 0x000e1510, 0x000e140f, 0x000d130d, 0x000c120c, 0x000c130d, 0x000c140e, 0x000c140d, 0x000b130c, 0x0009120c, 0x0009120c, 0x0009130e, 0x0009130e, 0x0008120c, 0x0008110c, 0x0007110c, 0x0006100b, 0x0007110c, 0x0007110c, 0x0008120d, 0x0007130d, 0x0006120c, 0x0005100b, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x0005100a, 0x00040d08, 0x00040e09, 0x00040e09, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060f0a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100d, 0x0008100c, 0x0008100b, 0x00090f0b, 0x00080f0a, 0x00070f0a, 0x00060e0a, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040c06, 0x00040c08, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100a, 0x00051008, 0x00040f08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x0038380c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0047480e, 0x0047480f, 0x00484910, 0x00484910, 0x00494a10, 0x004b4c10, 0x004b4c0f, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00525310, 0x00525310, 0x00545510, 0x00555611, 0x00585810, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00626312, 0x00636414, 0x00686514, 0x00c6a219, 0x00cca619, 0x007c7215, 0x00686814, 0x00686814, 0x00666714, 0x00656613, 0x00656614, 0x00636414, 0x00626312, 0x009b8415, 0x00cca418, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x004b4c10, 0x0047480e, 0x0041420e, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e0a, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0006100b, 0x0006100b, 0x0005100b, 0x0005100a, 0x00050f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00060e06, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080f0b, 0x000a0f0b, 0x000a0f0c, 0x00090f0c, 0x00080f0b, 0x00070f08, 0x00051009, 0x0007110c, 0x0008120c, 0x0008130a, 0x0008130a, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c140e, 0x000c140e, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e170e, 0x000e170e, 0x000f1810, 0x000f1810, 0x0010160e, 0x0010160e, 0x0010160e, 0x0010160e, 0x000f1610, 0x000e1610, 0x000e1610, 0x000d1711, 0x000c1612, 0x00111815, 0x00151a17, 0x00181c16, 0x00272921, 0x00303028, 0x0034342e, 0x00323230, 0x002e2e2e, 0x00282828, 0x001b1c18, 0x0011130a, 0x001f2015, 0x0028281c, 0x00363024, 0x003b301f, 0x0042311c, 0x00432c15, 0x00472d16, 0x00523822, 0x00523625, 0x00563924, 0x0058391e, 0x00583616, 0x005b3713, 0x0059340e, 0x005c350f, 0x00613911, 0x006b3f17, 0x006e4218, 0x00754720, 0x00784a23, 0x00754823, 0x00744823, 0x00714620, 0x0070441e, 0x0069401c, 0x00673d18, 0x00643b14, 0x00603710, 0x005d340d, 0x005c340c, 0x005c3409, 0x005b3208, 0x00583107, 0x00562f08, 0x00562f0b, 0x00542e0a, 0x00502b09, 0x004e2807, 0x004f2908, 0x00502a08, 0x00502a08, 0x00502b08, 0x00522f0c, 0x0054300c, 0x00522c05, 0x005b300a, 0x0060340b, 0x0062340a, 0x0066360c, 0x0067380d, 0x0067380d, 0x0069390d, 0x006d3c10, 0x006f3c0e, 0x00703b0c, 0x00703c0c, 0x006f3c0a, 0x006b3909, 0x0068390a, 0x00603306, 0x005b3006, 0x005b320c, 0x0057310c, 0x0057310c, 0x00532f0a, 0x00502c09, 0x00492807, 0x004b2c0c, 0x00391c00, 0x003b1d01, 0x003d2008, 0x00381c06, 0x003b1d08, 0x00391c07, 0x00381c08, 0x00381c0b, 0x003a1d0c, 0x00341b0b, 0x00281708, 0x001c1106, 0x00110f07, 0x000b0f06, 0x000c0e06, 0x00171208, 0x0021170b, 0x002e2013, 0x00342619, 0x00281c12, 0x00241b13, 0x002a1f16, 0x002e2318, 0x00312518, 0x002e2213, 0x002e2416, 0x00292015, 0x00221c13, 0x001e1a14, 0x001a1813, 0x00161512, 0x00121410, 0x0011140f, 0x0010140f, 0x000c1410, 0x000c1410, 0x000d1510, 0x000d1510, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x00101711, 0x00101711, 0x000f150f, 0x000f150f, 0x000f1610, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1710, 0x000f1811, 0x000f1811, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x000f1811, 0x000f1811, 0x00101812, 0x00101812, 0x00121812, 0x00131712, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00101610, 0x000f150f, 0x000e150f, 0x000d150f, 0x000d150f, 0x000c140e, 0x000b130c, 0x000a130c, 0x000a140f, 0x000a140f, 0x000a140f, 0x000a140f, 0x0009130e, 0x0009130e, 0x0008120c, 0x0007110c, 0x0007130d, 0x0007130d, 0x0007130d, 0x0007130d, 0x0006110c, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040f09, 0x0005100a, 0x00040d08, 0x00040e09, 0x00040f09, 0x0008100b, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00060e09, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005100e, 0x0006100c, 0x0008100b, 0x00090f0b, 0x00080f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040c06, 0x00040c08, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100a, 0x00051008, 0x00040f08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x00191c08, 0x00202308, 0x0024250a, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0030310c, 0x0034350c, 0x0038380c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0040400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0047480d, 0x0047480e, 0x00484910, 0x00484910, 0x00494a10, 0x00494a10, 0x00494a10, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00515110, 0x00525310, 0x00535410, 0x00555611, 0x00585810, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00606013, 0x00636413, 0x00686414, 0x00c6a219, 0x00cca619, 0x007c7114, 0x00666714, 0x00666714, 0x00666713, 0x00656614, 0x00646414, 0x00646414, 0x00616112, 0x009b8415, 0x00cca417, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0047480f, 0x0041420e, 0x003e400d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250b, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f09, 0x0008110a, 0x00081009, 0x00070f08, 0x00070f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060f0b, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x0008100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0005100a, 0x00050f0a, 0x00060e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00060e06, 0x00081009, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f08, 0x00070f08, 0x00081009, 0x000a0f09, 0x000b0f0b, 0x000b0f0c, 0x000a100a, 0x000a100a, 0x0009120b, 0x0009120c, 0x000a130c, 0x000a130b, 0x000b140b, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000f150f, 0x00101610, 0x00101610, 0x00101710, 0x00101711, 0x00101711, 0x00111812, 0x00101711, 0x000f1510, 0x00111812, 0x00111812, 0x00121813, 0x00121813, 0x00121911, 0x00121911, 0x00131a12, 0x00131a12, 0x00141811, 0x00111610, 0x0010150e, 0x0010150e, 0x00101711, 0x00101711, 0x00101711, 0x00121913, 0x00101814, 0x00131a16, 0x00161914, 0x001c1d14, 0x0025251b, 0x002f2c24, 0x002f2d26, 0x00302d2a, 0x002e2c2b, 0x00252422, 0x00242420, 0x00181a14, 0x0013140c, 0x0024241a, 0x002e2b20, 0x0031281a, 0x003f301d, 0x0048351d, 0x003f2710, 0x00442c18, 0x004c3321, 0x00543924, 0x0055381c, 0x00543518, 0x00563416, 0x00573313, 0x005b3613, 0x00603b14, 0x00683f18, 0x00693f17, 0x006f421b, 0x00754923, 0x00744824, 0x00734823, 0x006e4520, 0x006b421d, 0x00683f1a, 0x00693e19, 0x00663c16, 0x00623912, 0x005f3710, 0x005d360e, 0x005d360c, 0x00583108, 0x00512a04, 0x00522c08, 0x00522c0c, 0x00502b0b, 0x00502a0c, 0x004e280b, 0x004e290c, 0x004d280b, 0x004d280b, 0x00542e10, 0x0053300f, 0x0054300c, 0x00552f09, 0x005e340d, 0x0064380e, 0x0065370c, 0x0067380d, 0x0067380d, 0x0068380e, 0x006b3a0f, 0x006f3d10, 0x00703c0e, 0x006f3b0b, 0x006e3a09, 0x006c3b0b, 0x0068390a, 0x00633508, 0x0062360b, 0x00603610, 0x005a300c, 0x005c3410, 0x0058300e, 0x00522c0b, 0x00502d0c, 0x00482709, 0x0047280b, 0x003a1d04, 0x003a1d04, 0x003c200b, 0x003a1e0a, 0x00381c0b, 0x00381c0b, 0x00381c0a, 0x00361a08, 0x00381c0b, 0x00311909, 0x00241507, 0x00181006, 0x00131209, 0x000c1107, 0x000d0f05, 0x00161107, 0x0020160b, 0x002b1e12, 0x00312418, 0x00271c11, 0x00231912, 0x00251d15, 0x002a2018, 0x002d2519, 0x0030271a, 0x002f261a, 0x00272116, 0x001f1c13, 0x001d1d15, 0x001a1b16, 0x00141813, 0x00141713, 0x00141612, 0x00131712, 0x00111814, 0x00101713, 0x00101512, 0x00101511, 0x00101711, 0x00111812, 0x00111812, 0x00111812, 0x00111611, 0x00111611, 0x00131712, 0x00131712, 0x00121812, 0x00111812, 0x00111812, 0x00101711, 0x00111812, 0x00111813, 0x00121813, 0x00121813, 0x00121813, 0x00111812, 0x00111812, 0x00101812, 0x00101812, 0x00101811, 0x00101811, 0x00111812, 0x00111812, 0x00131714, 0x00141614, 0x00131513, 0x00131513, 0x00131513, 0x00131513, 0x00131513, 0x00131513, 0x00121612, 0x00111711, 0x00101710, 0x00101610, 0x000e1610, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000b1510, 0x000b1510, 0x0008140f, 0x0007130d, 0x0008140d, 0x0008140e, 0x0008120c, 0x0006100b, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00050d09, 0x00040c08, 0x00040f09, 0x0005100a, 0x0004100a, 0x0003100d, 0x0004100c, 0x0006100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x00060e08, 0x00030d06, 0x00040d09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x0006100a, 0x00051008, 0x00040f08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180a, 0x00191c09, 0x00191c08, 0x001d2008, 0x00202308, 0x0026280c, 0x00292b0b, 0x00292b0a, 0x0030310b, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003b3c0d, 0x003e400c, 0x003e400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0045470e, 0x0047480d, 0x0047480e, 0x00484910, 0x00484910, 0x00494a10, 0x00494a10, 0x00494a10, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545511, 0x00565711, 0x00585911, 0x00595a12, 0x005c5c11, 0x005e5f13, 0x00606012, 0x00616112, 0x00686414, 0x00c6a219, 0x00cca619, 0x007b7014, 0x00666713, 0x00666713, 0x00656614, 0x00646514, 0x00646414, 0x00626313, 0x00606013, 0x009b8415, 0x00cca417, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0047480f, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e0a, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0007100b, 0x00060e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e06, 0x00081008, 0x00081008, 0x00070f08, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00081009, 0x00071009, 0x0008100a, 0x000a100a, 0x000b100a, 0x000c0f0a, 0x000b100a, 0x000d130c, 0x000d140c, 0x000c140c, 0x000d140c, 0x000d140b, 0x000d140b, 0x000f140d, 0x000f140e, 0x0010140f, 0x0010140f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x00101711, 0x00111812, 0x00111812, 0x00121813, 0x00121813, 0x00121813, 0x00121813, 0x00131914, 0x00141a14, 0x00141914, 0x00141914, 0x00151a14, 0x00151a14, 0x00151a13, 0x00151a13, 0x00141912, 0x00141912, 0x00161812, 0x00161812, 0x00171913, 0x00171913, 0x00141914, 0x00141914, 0x00141914, 0x00141a14, 0x00141a14, 0x00161a14, 0x00181a14, 0x001d1c13, 0x00211f14, 0x0028241a, 0x002a251e, 0x002d2923, 0x002f2b28, 0x00282724, 0x002c2b26, 0x00181914, 0x0011140d, 0x0023251e, 0x0026251c, 0x002e281c, 0x003c3122, 0x0046351f, 0x00402d15, 0x0048321c, 0x00493320, 0x004f361e, 0x0050351a, 0x00503318, 0x0053341a, 0x00513115, 0x00502e0c, 0x0058340f, 0x00633b15, 0x00684018, 0x00684017, 0x006c441c, 0x00744a25, 0x00704822, 0x006c4520, 0x006b411c, 0x00673d18, 0x00683c18, 0x00673e17, 0x00643b14, 0x00603710, 0x00613710, 0x0060380f, 0x005c330b, 0x00562c08, 0x00572c0c, 0x00572e0e, 0x00542c0c, 0x00542c0e, 0x00542b0d, 0x00542b0d, 0x0050280a, 0x00502809, 0x00522a0b, 0x00573010, 0x005a3310, 0x005c320e, 0x0060330c, 0x0064360d, 0x0066360c, 0x0067380d, 0x0067380d, 0x0067390e, 0x0067390b, 0x006b3c0c, 0x006b3c0a, 0x006c3a08, 0x006b3a08, 0x006a390b, 0x0068390d, 0x00623409, 0x0061340c, 0x00592e09, 0x00572d0a, 0x00583010, 0x00593111, 0x004f2809, 0x004d290c, 0x00452408, 0x003d2005, 0x003a1f06, 0x00381e08, 0x00381e09, 0x00361c0b, 0x00371c0a, 0x00381c0b, 0x00381c0c, 0x00341908, 0x00341b09, 0x002d1907, 0x00251809, 0x00161104, 0x00121408, 0x000c1107, 0x000d0f05, 0x00161008, 0x001f170b, 0x00281c0f, 0x002d2014, 0x00281d13, 0x00241a13, 0x00201813, 0x001f1912, 0x00241f15, 0x00282318, 0x00282418, 0x00242318, 0x00201f16, 0x001c1d14, 0x001b1c17, 0x00181a16, 0x00161814, 0x00161814, 0x00161814, 0x00141815, 0x00141815, 0x00141814, 0x00131714, 0x00141813, 0x00141914, 0x00141814, 0x00141813, 0x00141813, 0x00141813, 0x00141813, 0x00141612, 0x00141814, 0x00141914, 0x00141914, 0x00141813, 0x00141813, 0x00141914, 0x00141914, 0x00151a14, 0x00151a14, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00141913, 0x00141914, 0x00141914, 0x00141813, 0x00141813, 0x00141814, 0x00141814, 0x00141814, 0x00141814, 0x00141814, 0x00131813, 0x00121813, 0x00101812, 0x00101812, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000e1813, 0x000d1712, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000b1510, 0x000b1510, 0x000b1710, 0x0008140f, 0x0008140e, 0x0008140e, 0x0008130d, 0x0008110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00060e09, 0x00050d09, 0x00060e09, 0x00060e09, 0x0005100a, 0x0005100a, 0x0004100a, 0x0003100d, 0x0003100c, 0x00040f0a, 0x00040e09, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040e07, 0x00040d09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x0005100a, 0x00051009, 0x00051008, 0x00040f08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180a, 0x00191c09, 0x00191c08, 0x001d2008, 0x00202308, 0x0026280c, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0c, 0x003b3c0d, 0x003e400c, 0x003e400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0045470d, 0x0047480d, 0x0047480e, 0x00484910, 0x00484910, 0x00494a10, 0x00494a10, 0x00494a10, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00525310, 0x00535410, 0x00545511, 0x00565710, 0x00585911, 0x00595a12, 0x005c5c11, 0x005e5f13, 0x00606013, 0x00616112, 0x00666413, 0x00c6a219, 0x00cca619, 0x007b7014, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00636413, 0x00606013, 0x009a8215, 0x00cca417, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0047480f, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050d07, 0x00050e08, 0x00081008, 0x00071007, 0x00071007, 0x00060e08, 0x00040c07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x00050d07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060f08, 0x00060e0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050e09, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060e08, 0x00071007, 0x00071007, 0x00070f08, 0x00070f08, 0x00081009, 0x00061009, 0x0007110a, 0x0007110a, 0x0008120b, 0x0008120c, 0x000a110c, 0x000b110c, 0x000b110c, 0x000c120c, 0x000c130c, 0x000e120d, 0x000e120d, 0x000e130c, 0x000f140c, 0x00101610, 0x00101610, 0x00101610, 0x00101610, 0x00101510, 0x00111611, 0x00121712, 0x00131812, 0x00111812, 0x00121813, 0x00121813, 0x00131914, 0x00131913, 0x00131a12, 0x00131a13, 0x00121912, 0x00151c14, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161b14, 0x00181a14, 0x00181a15, 0x00181a15, 0x00181a15, 0x00171914, 0x00181a15, 0x00191c17, 0x00191c16, 0x00181c15, 0x00181a14, 0x00181a14, 0x00181b15, 0x00171914, 0x00181a14, 0x001e1c15, 0x00211e14, 0x00211c12, 0x00241d13, 0x00252016, 0x0027211a, 0x0028241e, 0x0026241f, 0x00292924, 0x0012140e, 0x00191d17, 0x0032342e, 0x0025241c, 0x00353127, 0x003b3226, 0x003d301e, 0x0040311c, 0x0045331c, 0x00432e17, 0x00473017, 0x004b3219, 0x004f361d, 0x004f341e, 0x004d3016, 0x004c2d0c, 0x00543210, 0x0054300c, 0x00623d17, 0x00643e18, 0x0069411c, 0x006b441e, 0x006b4420, 0x006b431f, 0x0069401d, 0x00673d1a, 0x00683c18, 0x00683d17, 0x00653b12, 0x00623810, 0x0060380f, 0x005e350c, 0x00593008, 0x00542b07, 0x00512707, 0x00582e0f, 0x00572d11, 0x00562f10, 0x00593111, 0x0058300d, 0x00512808, 0x00502708, 0x00532808, 0x005a2e10, 0x005e3210, 0x005e330d, 0x0060340c, 0x0064360c, 0x0066360e, 0x0066370c, 0x0068380c, 0x0068380c, 0x0069390c, 0x006a390a, 0x006a390b, 0x0069380c, 0x0069380c, 0x0067380d, 0x0064340c, 0x0061330a, 0x0060340c, 0x00562b07, 0x005d320f, 0x00582d0c, 0x00572d0e, 0x00542c0d, 0x00522e11, 0x00442408, 0x003c2005, 0x00391e08, 0x003b1f0b, 0x00371c08, 0x00371b09, 0x00371b09, 0x00381c0a, 0x00361c0b, 0x00321908, 0x00301807, 0x002c1a08, 0x00271a09, 0x00161002, 0x000c0d00, 0x00080c02, 0x00111309, 0x00171309, 0x001c1408, 0x0024180e, 0x002d2014, 0x00281d14, 0x00241b13, 0x001f1a13, 0x001f1c15, 0x001e1c14, 0x001f1c14, 0x00202014, 0x00212318, 0x00202219, 0x001d2019, 0x001c1e18, 0x00191c16, 0x00171a14, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00151a14, 0x00151a14, 0x00141914, 0x00151a14, 0x00141914, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00151a14, 0x00151b15, 0x00151c15, 0x00141a14, 0x00141914, 0x00171914, 0x00171914, 0x00181a15, 0x00161b15, 0x00151c14, 0x00151c14, 0x00141b13, 0x00121810, 0x00141912, 0x00141912, 0x00161b14, 0x00161b14, 0x00131815, 0x00131816, 0x00131917, 0x00131917, 0x00141a16, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141813, 0x00111812, 0x000f1912, 0x000f1912, 0x000d1710, 0x000c160f, 0x000c1712, 0x000e1814, 0x000c1713, 0x000c1713, 0x000c1610, 0x000d1510, 0x000c1410, 0x000c140f, 0x000a140f, 0x0008120d, 0x0007110c, 0x0007110c, 0x0007100c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x000a100c, 0x00070f0a, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100a, 0x0008110b, 0x0008120b, 0x00061009, 0x0006100b, 0x0007100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e08, 0x00040e09, 0x00040e09, 0x00040c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060f09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x00141810, 0x0014180b, 0x0014180a, 0x00191c09, 0x00191c08, 0x00202308, 0x0024250b, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0034350c, 0x0038380c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0040400d, 0x0043440f, 0x0043440e, 0x0045470e, 0x0045470e, 0x0047480d, 0x0047480e, 0x00484910, 0x00494a10, 0x00494a10, 0x00494a10, 0x00494a0f, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00525310, 0x00545510, 0x00555611, 0x00565711, 0x00585911, 0x00595a12, 0x005c5c11, 0x005e5f13, 0x00606013, 0x00606013, 0x00666413, 0x00c6a218, 0x00cca519, 0x007a7014, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00636414, 0x00616112, 0x00606013, 0x009a8215, 0x00cca417, 0x00b09015, 0x00515111, 0x00525310, 0x004f5010, 0x00494a0f, 0x0047480f, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00050e07, 0x00060e06, 0x00060e06, 0x00040c06, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x00040d07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00070f09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e07, 0x00060e09, 0x00040e09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060e08, 0x00071007, 0x00071007, 0x00060e08, 0x00060e08, 0x0008110b, 0x0008120b, 0x0008130c, 0x0008130c, 0x0009140c, 0x000a140d, 0x000c130d, 0x000c130d, 0x000c130d, 0x000d140e, 0x000d140e, 0x000f140e, 0x000f140e, 0x0010140f, 0x0010140f, 0x00101510, 0x00101510, 0x00111611, 0x00111611, 0x00111611, 0x00131712, 0x00141813, 0x00141813, 0x00121813, 0x00131914, 0x00131914, 0x00141a14, 0x00141a14, 0x00141b13, 0x00141b13, 0x00121911, 0x00151c14, 0x00161b15, 0x00161b14, 0x00181c14, 0x00181d14, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c17, 0x00181a16, 0x00181b17, 0x00191c16, 0x00191c16, 0x001b1c14, 0x001b1c14, 0x001c1d16, 0x001c1c15, 0x001a1b14, 0x001c1c15, 0x00201d17, 0x00231f15, 0x00241e14, 0x00272018, 0x0028201a, 0x0028211b, 0x00272219, 0x0025231b, 0x0022231c, 0x0010120c, 0x001c211a, 0x00383b34, 0x002c2c24, 0x002d2920, 0x00362e24, 0x002f2417, 0x00372917, 0x0041321a, 0x00412e15, 0x0048341a, 0x00503820, 0x00513822, 0x004b311a, 0x004a2f14, 0x00523414, 0x00593818, 0x0054320f, 0x00623e19, 0x00623c18, 0x0066401a, 0x0067411b, 0x0067411c, 0x0068401c, 0x0068401c, 0x00693d1b, 0x00683d19, 0x00683d17, 0x00663c13, 0x00623810, 0x0061380e, 0x0061380e, 0x005d340c, 0x00562d09, 0x00502706, 0x00552d0f, 0x00542c12, 0x00573013, 0x005b3314, 0x00582f0f, 0x00502608, 0x0054290c, 0x00562a0d, 0x005d3013, 0x005f330f, 0x005f320c, 0x0062350d, 0x0064370f, 0x0065370e, 0x0066380d, 0x0067390c, 0x00683a0d, 0x00693a0c, 0x006a390c, 0x0069380d, 0x0068380f, 0x0068370f, 0x0063340c, 0x00613209, 0x00603209, 0x005f330b, 0x005c2f09, 0x00592e0b, 0x00542b09, 0x005c3112, 0x00552c0e, 0x00502b0e, 0x00402004, 0x00391d03, 0x00371c05, 0x003a1e0a, 0x00371b08, 0x00371b09, 0x00371c0a, 0x00371c0a, 0x00331c09, 0x002e1707, 0x002d1708, 0x002c190a, 0x00271a09, 0x00161000, 0x000c0c00, 0x00090d03, 0x00101008, 0x0018140b, 0x001b1408, 0x0022160c, 0x002b1e14, 0x00291e14, 0x00241c14, 0x00201c14, 0x001d1c14, 0x001b1b12, 0x00181911, 0x00181a11, 0x001b1d14, 0x001b1d17, 0x001c1e18, 0x001c1e18, 0x00191c16, 0x00181c15, 0x00171c17, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161b15, 0x00161b15, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a13, 0x00151a13, 0x00161b14, 0x00161b14, 0x00161c16, 0x00171d18, 0x00171d18, 0x00161c17, 0x00171b16, 0x00181b17, 0x00181b16, 0x00181a15, 0x00181a15, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00171c15, 0x00171c15, 0x00161b14, 0x00161b14, 0x00141b17, 0x00141b17, 0x00151b17, 0x00151b17, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00131914, 0x00121b12, 0x00111b12, 0x00101810, 0x000e1710, 0x00101814, 0x00101814, 0x000f1713, 0x000f1713, 0x000f1713, 0x000d1510, 0x000e1611, 0x000c1410, 0x000b1410, 0x0009130e, 0x0007110c, 0x0007110c, 0x0007100c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00080f0b, 0x0008100c, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040f08, 0x00061009, 0x0007110a, 0x00061009, 0x0006100c, 0x0007110d, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x0020230a, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x003c3e0c, 0x0040400c, 0x0041420e, 0x0043440e, 0x0045470e, 0x0047480e, 0x0047480e, 0x00484910, 0x00484910, 0x00494a0f, 0x00494a0f, 0x004b4c0f, 0x004c4d0f, 0x004b4c0f, 0x004c4d0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00515110, 0x00525310, 0x00545510, 0x00565711, 0x00585810, 0x00585911, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00616112, 0x00666413, 0x00c6a218, 0x00cca519, 0x007a7014, 0x00646514, 0x00646514, 0x00646514, 0x00646414, 0x00626313, 0x00616112, 0x00606013, 0x009a8214, 0x00cca417, 0x00b09015, 0x00515110, 0x00525310, 0x004f5010, 0x004b4c10, 0x0047480f, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e07, 0x00050d07, 0x00040d06, 0x00040d05, 0x00071007, 0x00070f08, 0x00081009, 0x00081009, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050d07, 0x00070f08, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e07, 0x00060e09, 0x00040e09, 0x00080c09, 0x00080c09, 0x00070c08, 0x00050d08, 0x00040d08, 0x00070f0a, 0x00070f0a, 0x00050e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e06, 0x00070f08, 0x00070f08, 0x00081008, 0x00071007, 0x00060e07, 0x00050d07, 0x0009120c, 0x0009120c, 0x000a130c, 0x000b120c, 0x000c130c, 0x000c140c, 0x000c140d, 0x000d140e, 0x000e140e, 0x000f150f, 0x000f150f, 0x0010140f, 0x0010140f, 0x00101510, 0x00101510, 0x00131611, 0x00131611, 0x00141813, 0x00141712, 0x00141813, 0x00141813, 0x00141813, 0x00151814, 0x00151814, 0x00161914, 0x00161914, 0x00171914, 0x00171a14, 0x00171a14, 0x00181b14, 0x00181b14, 0x00181c15, 0x00181c16, 0x001a1d15, 0x001a1e14, 0x001a1d15, 0x001c1d18, 0x001c1d18, 0x001c1d18, 0x001c1d18, 0x001b1c18, 0x001b1c16, 0x001c1d17, 0x001c1d16, 0x001d1c15, 0x001c1c15, 0x001c1c15, 0x001e1d16, 0x001c1d17, 0x001d1d17, 0x00201d16, 0x00231e14, 0x00241d14, 0x00272017, 0x002a221c, 0x0028201a, 0x00241f15, 0x001c1a11, 0x00151610, 0x0010140e, 0x00242621, 0x003c3d38, 0x0036352e, 0x0027231b, 0x00282218, 0x0030261a, 0x003b3020, 0x00423420, 0x0044341b, 0x00432f16, 0x0047331a, 0x004f3820, 0x0048321a, 0x00452d13, 0x004f3014, 0x00543314, 0x00583616, 0x005c3815, 0x005f3915, 0x00633d18, 0x0065401b, 0x0066401c, 0x0067401c, 0x0068401c, 0x00693d1c, 0x00683c18, 0x00663b15, 0x00663c13, 0x00643a11, 0x00643a10, 0x0062380e, 0x005c340c, 0x0058300c, 0x00562e0a, 0x00572f0f, 0x00582e10, 0x005c3213, 0x005c3110, 0x005c300d, 0x005c2f0e, 0x005d3010, 0x005a2c0c, 0x00603210, 0x0060340c, 0x0061340d, 0x0063360f, 0x00643710, 0x0064380f, 0x0065380d, 0x00653a0c, 0x00663a0d, 0x00673b0c, 0x0067380c, 0x0066380e, 0x00673810, 0x0064370e, 0x0060340a, 0x005f3309, 0x005f340a, 0x005f340c, 0x005e320c, 0x005a2f0c, 0x00572b0b, 0x005d3213, 0x00562d0f, 0x004f290c, 0x00432207, 0x003d2107, 0x00351904, 0x00371b07, 0x003a1e0a, 0x00371c0a, 0x00351c09, 0x00341c0a, 0x002c1807, 0x002a1707, 0x002c1809, 0x002c190b, 0x0025180b, 0x00170e02, 0x000e0b00, 0x000c0f04, 0x000f0f04, 0x0018150c, 0x001b140a, 0x001f140b, 0x00251a10, 0x00271d14, 0x00272018, 0x00221d14, 0x001f1b14, 0x001d1b13, 0x001d1c15, 0x001b1c13, 0x00191c14, 0x00191c16, 0x00191c16, 0x00191d16, 0x00181d16, 0x00171c16, 0x00171c17, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00171c17, 0x00171c17, 0x00171c14, 0x00171c15, 0x00171c15, 0x00171c15, 0x00161c16, 0x00161c16, 0x00171d16, 0x00181f18, 0x001b1f18, 0x00191c17, 0x00181c15, 0x00181c16, 0x00181c16, 0x00181c14, 0x00171b13, 0x00171b13, 0x00171b13, 0x00161c13, 0x00161c13, 0x00171c14, 0x00171c14, 0x00161c16, 0x00151b15, 0x00151c16, 0x00151c16, 0x00151c15, 0x00141b15, 0x00141a14, 0x00141b15, 0x00161c17, 0x00151c16, 0x00151c16, 0x00151c16, 0x00151c16, 0x00161b15, 0x00161b15, 0x00151a14, 0x00141914, 0x00141b13, 0x00141b13, 0x00131b13, 0x00111912, 0x00121815, 0x00121814, 0x00121814, 0x00101814, 0x00101814, 0x00101813, 0x000e1611, 0x000e1611, 0x000c1510, 0x000a140f, 0x0008120d, 0x0008120c, 0x0007100b, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00070d09, 0x0008100c, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040e08, 0x00040f08, 0x00051008, 0x00061009, 0x0006100c, 0x0007110d, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x0038380c, 0x00393b0d, 0x003c3e0c, 0x003e400c, 0x0041420e, 0x0044450e, 0x0045470e, 0x0047480e, 0x0048490f, 0x00494a10, 0x004b4c10, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004d4e0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004d4e10, 0x004f5010, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00545511, 0x00555611, 0x00565711, 0x00585910, 0x00595a12, 0x005c5c12, 0x005c5d11, 0x005d5e12, 0x00606013, 0x00606013, 0x00666413, 0x00c6a218, 0x00cca519, 0x00796f14, 0x00646514, 0x00646514, 0x00646414, 0x00636414, 0x00626313, 0x00606013, 0x005e5f13, 0x009a8214, 0x00cca417, 0x00b09015, 0x00515110, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e06, 0x00050e06, 0x00060e08, 0x00060e08, 0x00050e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00070f08, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e07, 0x00060e09, 0x00040e09, 0x00080c09, 0x00080c09, 0x00070c08, 0x00040c08, 0x00050d08, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e06, 0x00070f08, 0x00081009, 0x00081108, 0x00081008, 0x00081008, 0x00081009, 0x000b130c, 0x000c140d, 0x000d140c, 0x000e140c, 0x000f140d, 0x000f140d, 0x000f140e, 0x000e140f, 0x000f150f, 0x00101610, 0x00101610, 0x00101510, 0x00101510, 0x00111611, 0x00111611, 0x00151814, 0x00151814, 0x00171914, 0x00171914, 0x00171814, 0x00171814, 0x00171814, 0x00171814, 0x00181915, 0x00181915, 0x00181914, 0x00181814, 0x00181914, 0x00181a14, 0x00181a14, 0x00191b15, 0x00191b15, 0x001a1c15, 0x001c1e15, 0x001b1d14, 0x001c1d14, 0x001d1d17, 0x001d1d17, 0x001d1d17, 0x001d1d17, 0x001c1c18, 0x001c1c17, 0x001d1d17, 0x001d1d16, 0x001f1e16, 0x001e1c14, 0x001e1c14, 0x001e1c15, 0x001e1d17, 0x001f1c16, 0x00201c15, 0x00201c12, 0x00211b13, 0x00231c14, 0x00241c16, 0x00231c15, 0x001f1910, 0x0019170e, 0x0014130c, 0x0012140e, 0x0020241e, 0x00373831, 0x00383730, 0x002b271f, 0x001f1a10, 0x002c261c, 0x00393023, 0x003c311f, 0x0041341d, 0x0045341c, 0x00453218, 0x0047331a, 0x0049351c, 0x00452c14, 0x00482910, 0x00543118, 0x005c381c, 0x005c3716, 0x00603917, 0x00603b18, 0x00613c18, 0x00643d1b, 0x00643e1a, 0x00653d1b, 0x00673d1a, 0x006a3c19, 0x00663b15, 0x00663c13, 0x00653b12, 0x00653b10, 0x00633a10, 0x0060370c, 0x005c340d, 0x005e3412, 0x005d3410, 0x005e340e, 0x0063370f, 0x0067390f, 0x00673a0f, 0x006a3b12, 0x006a3b12, 0x0064350c, 0x0067380f, 0x0064350b, 0x0065380e, 0x0063350e, 0x00643711, 0x0063360f, 0x0062380c, 0x0062380b, 0x0062380b, 0x0062370a, 0x0061370c, 0x0062370e, 0x0061360d, 0x0060350c, 0x005d3409, 0x005c3208, 0x005f340a, 0x005e340b, 0x005b310b, 0x005b300d, 0x005c3110, 0x00582e0f, 0x00552c0d, 0x004c280c, 0x00442408, 0x003e2208, 0x00351904, 0x00361a06, 0x003a1e0b, 0x00381c0a, 0x00331b09, 0x00301b08, 0x00281704, 0x00281808, 0x002a1809, 0x0028170b, 0x00221509, 0x00160d04, 0x000e0a00, 0x000c0e02, 0x00121207, 0x0019150c, 0x001b150b, 0x0021170c, 0x00251c12, 0x00241d13, 0x00241d15, 0x00231c14, 0x001f1a13, 0x001d1b13, 0x001c1c14, 0x001a1b14, 0x00181c14, 0x00191c15, 0x00191c16, 0x00191c16, 0x00181d16, 0x00181c16, 0x00181c18, 0x00181c18, 0x00181c18, 0x00181c18, 0x00171c16, 0x00171c16, 0x00161b14, 0x00161b14, 0x00171c17, 0x00171c17, 0x00171c15, 0x00171c14, 0x00171c14, 0x00171c14, 0x00161c14, 0x00161d14, 0x00171d14, 0x00171e15, 0x00181c15, 0x00191c15, 0x00191c15, 0x00191c15, 0x00191c15, 0x00191d14, 0x00191c13, 0x00191c13, 0x00191c13, 0x00181d13, 0x00181d13, 0x00181d13, 0x00181d14, 0x00181f16, 0x00161d14, 0x00151c13, 0x00151c13, 0x00151c15, 0x00151c15, 0x00141b14, 0x00151c16, 0x00161c17, 0x00161c17, 0x00171d18, 0x00181e18, 0x00181d18, 0x00181c18, 0x00181c18, 0x00171c16, 0x00161b15, 0x00141c14, 0x00141c14, 0x00141b13, 0x00141b13, 0x00151c15, 0x00151c16, 0x00151b16, 0x00131914, 0x00101814, 0x00101814, 0x00101814, 0x000e1611, 0x000c1610, 0x000c1610, 0x000b1510, 0x000a140f, 0x0008110c, 0x0009110c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00050d09, 0x00080f0b, 0x0008100b, 0x0008100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00061009, 0x0006100c, 0x0007110d, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0005100a, 0x0005100a, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00050d09, 0x00060d09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x00191c08, 0x00202308, 0x0020230a, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0045470e, 0x0048490f, 0x00494a10, 0x004b4c10, 0x004b4c0f, 0x004d4e0f, 0x004d4e10, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x004f5010, 0x00505010, 0x00515110, 0x00515110, 0x00505010, 0x00525310, 0x00515110, 0x00525310, 0x00535410, 0x00545510, 0x00555611, 0x00565711, 0x00585810, 0x00595a11, 0x005b5b12, 0x005c5c11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00616112, 0x00666413, 0x00c6a218, 0x00cca519, 0x00796f14, 0x00646414, 0x00646414, 0x00646414, 0x00636414, 0x00616112, 0x00616112, 0x005e5f13, 0x009a8214, 0x00cca417, 0x00b09015, 0x00515110, 0x00515110, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00050e07, 0x00060e07, 0x00050e08, 0x00050e08, 0x00040d07, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x0008100b, 0x00070f09, 0x00070f09, 0x00040d08, 0x00050d08, 0x00050e08, 0x0008100b, 0x00060e09, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e07, 0x00060e09, 0x00050e09, 0x00080d09, 0x00080d09, 0x00070d09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070e0b, 0x00070f09, 0x00070f09, 0x00070f08, 0x0008100a, 0x0008100a, 0x0009120b, 0x000a130c, 0x000b130b, 0x000c140c, 0x000c140d, 0x000c140d, 0x000f140e, 0x0010140e, 0x0011140f, 0x0013140f, 0x00111510, 0x00111510, 0x00111510, 0x00121510, 0x00121510, 0x00141510, 0x00141610, 0x00141611, 0x00141611, 0x00181914, 0x00181914, 0x00191b15, 0x00181a14, 0x00181814, 0x00181814, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181914, 0x00181914, 0x00181a14, 0x00181a14, 0x00181a14, 0x00191a14, 0x00191b14, 0x001b1c16, 0x001c1e18, 0x001c1c14, 0x001c1c14, 0x001c1c15, 0x001d1e16, 0x001e1d15, 0x001f1e15, 0x00201d17, 0x00201d17, 0x00201e16, 0x00201e15, 0x00201e14, 0x00201e14, 0x00201e14, 0x00201e14, 0x001f1e16, 0x00201d15, 0x00201c14, 0x00201b13, 0x00201b13, 0x00211b14, 0x00221c14, 0x00221c15, 0x001b180f, 0x0018150d, 0x0014140c, 0x0012140c, 0x001c1d17, 0x0034342c, 0x0036342c, 0x002c2920, 0x00201c12, 0x00241e16, 0x002e271c, 0x00352c1b, 0x003c301a, 0x00483820, 0x0048361c, 0x00443015, 0x00473018, 0x0049301b, 0x004a2c17, 0x004c2c16, 0x004c2a13, 0x00502c10, 0x00603a1b, 0x005f3918, 0x005f3815, 0x00603a16, 0x00623b17, 0x00633b17, 0x00643b17, 0x00673c18, 0x00643c14, 0x00653b12, 0x00663b11, 0x00663a10, 0x00663a10, 0x00643a10, 0x0063380f, 0x00643910, 0x00673910, 0x00693b10, 0x006f4013, 0x00734012, 0x00724010, 0x00734111, 0x00754313, 0x00723f10, 0x00713d0e, 0x006d390b, 0x006b380c, 0x0068350c, 0x0068370f, 0x0064370c, 0x0063360a, 0x00623508, 0x00613608, 0x005f3408, 0x0060340b, 0x00623710, 0x0060360e, 0x005e340c, 0x005d330a, 0x005d330a, 0x0061360d, 0x005c3109, 0x00572e07, 0x00582f09, 0x005c3311, 0x00542b0b, 0x00522c0c, 0x00492608, 0x00412106, 0x003c2007, 0x00381904, 0x00351804, 0x00381c0a, 0x00341c0b, 0x002f1b08, 0x00281704, 0x00241504, 0x00241504, 0x00271709, 0x0026170b, 0x0020140a, 0x00150c03, 0x000e0901, 0x000d0c04, 0x0014130c, 0x0018140f, 0x0019140e, 0x00211a0f, 0x00241d13, 0x00241d13, 0x00211c13, 0x00201c14, 0x00201b14, 0x001e1b14, 0x001c1b15, 0x001b1c15, 0x00191c15, 0x00191c16, 0x00191c16, 0x00191c17, 0x00181c17, 0x00191d18, 0x00181c18, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161c16, 0x00161c16, 0x00151c14, 0x00151b14, 0x00181e16, 0x00181e16, 0x00181e15, 0x00181e15, 0x00171d14, 0x00161d14, 0x00161d14, 0x00161d14, 0x00171e14, 0x00161d14, 0x00171c13, 0x00181c14, 0x00191c14, 0x00181c14, 0x00191c14, 0x00191c14, 0x00191c14, 0x00191c14, 0x00191c14, 0x00181c14, 0x00181c14, 0x00191c14, 0x00181d14, 0x00181f15, 0x00182016, 0x00171d14, 0x00171d14, 0x00181d16, 0x00181c16, 0x00181c15, 0x00181c16, 0x00181d17, 0x00181d16, 0x00181d17, 0x00181e18, 0x00181d18, 0x00191d18, 0x00191e18, 0x00191d18, 0x00171c15, 0x00181c16, 0x00181d17, 0x00181c17, 0x00171c16, 0x00161c17, 0x00151d17, 0x00141c16, 0x00131a14, 0x00101813, 0x00101813, 0x00101813, 0x00101813, 0x000e1711, 0x000d1610, 0x000d1710, 0x000d1610, 0x000a130d, 0x000a130d, 0x000a120d, 0x0009110c, 0x0009110c, 0x0009110c, 0x0008100b, 0x0008100b, 0x00060f0a, 0x00090f0b, 0x00080f0b, 0x00070f0a, 0x0005100a, 0x00060f0a, 0x00060f0a, 0x00060f0a, 0x00060f0a, 0x00050e08, 0x00050e08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f0b, 0x00040e0a, 0x00040e0a, 0x00040f0a, 0x0005100a, 0x00060f0a, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x0006100a, 0x00050e09, 0x00030c08, 0x00040e09, 0x0008100b, 0x0008100b, 0x0008100b, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x00141810, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x00393b0c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x0048490f, 0x004b4c10, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00515110, 0x00515110, 0x00525310, 0x00525310, 0x00525310, 0x00525310, 0x00535410, 0x00535410, 0x00535410, 0x00545510, 0x00555611, 0x00555611, 0x00565710, 0x00585910, 0x00585911, 0x00595a12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x00606013, 0x00606013, 0x00616112, 0x00666413, 0x00c6a218, 0x00cca519, 0x00796f14, 0x00646414, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x009a8114, 0x00cca417, 0x00b09015, 0x004f5010, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0c, 0x00393b0c, 0x0034350c, 0x0030310c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00070f0a, 0x0008100c, 0x00050d09, 0x00040c08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00070f0a, 0x0008100b, 0x00081009, 0x0008110b, 0x0009120c, 0x000a130c, 0x000c140d, 0x000c140c, 0x000c150c, 0x000e150d, 0x000e150d, 0x0011140f, 0x0013130f, 0x00131410, 0x00141410, 0x00141511, 0x00141712, 0x00141712, 0x00141712, 0x00141712, 0x00171812, 0x00171812, 0x00171812, 0x00171812, 0x00181813, 0x00181a14, 0x001a1b15, 0x00181914, 0x00181813, 0x00181813, 0x00181a14, 0x00181a14, 0x00191a14, 0x00191a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00191c18, 0x001c1d18, 0x001c1c17, 0x001c1c14, 0x001c1c15, 0x00201e17, 0x00201e15, 0x00221e15, 0x00231e18, 0x00231e17, 0x00231e16, 0x00231e14, 0x00201e14, 0x00201e14, 0x00201e14, 0x00201e14, 0x00201d14, 0x00201d14, 0x00201d14, 0x00211c14, 0x00221c14, 0x00211c14, 0x00211c14, 0x00201c14, 0x0018160e, 0x0016140c, 0x0014140b, 0x0012130a, 0x00181810, 0x002a2a22, 0x00302e25, 0x0029281f, 0x0026231a, 0x00201b13, 0x00221b10, 0x00342c1d, 0x003a2f1d, 0x00453722, 0x004a3821, 0x00453117, 0x0047301a, 0x0049301c, 0x004c301d, 0x004d311c, 0x0053341d, 0x0056351a, 0x005e3b1c, 0x005e3818, 0x005f3715, 0x00623815, 0x00633b16, 0x00643c18, 0x00653c18, 0x00643c17, 0x00633b14, 0x00643911, 0x00673a10, 0x00673a10, 0x00683b10, 0x006b3e14, 0x006c3e11, 0x00704010, 0x00724312, 0x00774416, 0x007c4a19, 0x00814c18, 0x0078440e, 0x007d4813, 0x00804914, 0x007e4712, 0x007f4712, 0x007b4310, 0x0078400f, 0x00733c0e, 0x006f3a0d, 0x006c380a, 0x00683808, 0x00663608, 0x00643508, 0x0060340a, 0x0060330c, 0x0061340e, 0x0060350f, 0x0061360f, 0x0062370f, 0x0062370f, 0x00643810, 0x005a3007, 0x00542c05, 0x00562e08, 0x0059300e, 0x00522a0a, 0x004d280a, 0x00442005, 0x003d1d04, 0x003e2008, 0x003b1c08, 0x00361806, 0x00361c0c, 0x002d1809, 0x00271607, 0x00221404, 0x00231404, 0x00231404, 0x00241508, 0x00241508, 0x001e1409, 0x00150c04, 0x00130c06, 0x0015100c, 0x00181310, 0x00181310, 0x0018140f, 0x001d180f, 0x001f1b10, 0x001f1c11, 0x001e1b12, 0x001e1a13, 0x001d1b14, 0x001c1b14, 0x001c1b16, 0x001b1c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c17, 0x00181c18, 0x00191d18, 0x00181d18, 0x00161b15, 0x00161c17, 0x00161c17, 0x00161c15, 0x00161c15, 0x00161c15, 0x00171d16, 0x00171e14, 0x00171e14, 0x00181f15, 0x00171e14, 0x00171e14, 0x00161d14, 0x00161d14, 0x00161d14, 0x00161d14, 0x00161d14, 0x00161c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00171e15, 0x00171e15, 0x00181e15, 0x00181e15, 0x001c1e18, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d15, 0x00181d14, 0x001a1f16, 0x001a1f15, 0x00191e16, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00161d18, 0x00151e18, 0x00141d17, 0x00131b14, 0x00121a14, 0x00111913, 0x00111913, 0x00111913, 0x00101811, 0x000e170e, 0x000e1710, 0x000e1710, 0x000c140d, 0x000c140d, 0x000c140e, 0x000c140f, 0x000c140f, 0x000a120e, 0x0008100b, 0x0008100b, 0x0008100b, 0x00090f0b, 0x00080f0b, 0x00070f0a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x0005100a, 0x00070f0a, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060f0a, 0x00050f0a, 0x0005100a, 0x00040e09, 0x00040d08, 0x0007100b, 0x00070f0a, 0x00070f0a, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00515110, 0x00515110, 0x00525310, 0x00535410, 0x00535410, 0x00545510, 0x00545511, 0x00545510, 0x00545510, 0x00545510, 0x00545510, 0x00555611, 0x00555611, 0x00555611, 0x00565711, 0x00585810, 0x00585810, 0x00585911, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00616112, 0x00626312, 0x00666414, 0x00c6a219, 0x00cca519, 0x00796f14, 0x00646414, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005d5e12, 0x009a8114, 0x00cca417, 0x00b09014, 0x00505010, 0x00515110, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040c06, 0x00050e08, 0x00050d07, 0x00050e08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00050d08, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e0a, 0x00070f0a, 0x00050d09, 0x00050d09, 0x00040c08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00070e0c, 0x0008100b, 0x0008100c, 0x0008100a, 0x0009120c, 0x000a130c, 0x000c130d, 0x000c140d, 0x000d140c, 0x000e150d, 0x0010150d, 0x0010150e, 0x00121510, 0x00131410, 0x00141511, 0x00151512, 0x00151713, 0x00161814, 0x00161814, 0x00161814, 0x00171814, 0x00171812, 0x00171812, 0x00181a14, 0x00181a14, 0x00181813, 0x00181a14, 0x00191b14, 0x00181a14, 0x00181813, 0x00181813, 0x00181914, 0x00181914, 0x00181a14, 0x00181a14, 0x00181914, 0x00181914, 0x00191a14, 0x001a1b15, 0x00191a14, 0x00181914, 0x00181a14, 0x00191c17, 0x001b1c16, 0x001c1b16, 0x001c1b14, 0x00201c17, 0x00241e18, 0x00241d16, 0x00241e14, 0x00241d16, 0x00241d16, 0x00241e14, 0x00241e13, 0x00221e14, 0x00201f14, 0x00201e14, 0x00201e14, 0x00211e14, 0x00211e14, 0x00201e14, 0x00221d14, 0x00231c14, 0x00221c14, 0x00211c14, 0x001e1a13, 0x0017150c, 0x0017140c, 0x0014140a, 0x00141209, 0x0015150b, 0x001f1e15, 0x0029271f, 0x0026241c, 0x00201e15, 0x00201d14, 0x001a180e, 0x00231c11, 0x0032281c, 0x003a2d1d, 0x0041321c, 0x00402e16, 0x0046301b, 0x004b3321, 0x004d3423, 0x004f3420, 0x0051341d, 0x0055351c, 0x005c3a1c, 0x005d3818, 0x005e3614, 0x00603614, 0x00643c16, 0x00663f19, 0x00643d18, 0x00643c17, 0x00623b14, 0x00643911, 0x00663910, 0x00683a10, 0x006b3c11, 0x00714114, 0x00754415, 0x00794715, 0x007b4814, 0x007d4914, 0x00814d17, 0x00824b11, 0x007c450b, 0x007e450c, 0x007f460c, 0x0081470e, 0x00854a11, 0x00834811, 0x007f4610, 0x007c4410, 0x00753f0d, 0x00703c0a, 0x006d3b08, 0x006c380a, 0x0069370b, 0x0064340c, 0x0063340c, 0x0064370f, 0x0062350d, 0x005f330b, 0x0060340c, 0x0060340c, 0x0062350e, 0x005b300a, 0x00562e09, 0x00522a07, 0x00542c0c, 0x0051280b, 0x004e280c, 0x00452209, 0x0041200b, 0x003e200b, 0x003c1e0c, 0x00381c0c, 0x00341d0d, 0x00281608, 0x00221408, 0x00201306, 0x00211407, 0x00211407, 0x00221407, 0x00201407, 0x001d1208, 0x001a1008, 0x0018110a, 0x0017130c, 0x0018130e, 0x0018130f, 0x0019140f, 0x001b170f, 0x001d1a11, 0x001c1912, 0x001c1911, 0x001a1811, 0x001b1812, 0x001b1a15, 0x001b1b16, 0x001b1c16, 0x001a1c16, 0x00191c16, 0x00181c15, 0x00181c16, 0x00181c18, 0x00181c18, 0x00181c18, 0x00161c16, 0x00161c17, 0x00161c17, 0x00161c16, 0x00171e17, 0x00171d17, 0x00181e17, 0x00151c14, 0x00151c14, 0x00161c16, 0x00161c16, 0x00151c14, 0x00151c14, 0x00151c15, 0x00151c15, 0x00151c16, 0x00151c15, 0x00161c15, 0x00171c15, 0x00171c15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00171c15, 0x00171c15, 0x00161c16, 0x00171d17, 0x00171d17, 0x00171d16, 0x001b1d17, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d15, 0x00181d14, 0x001a1f16, 0x001a1f16, 0x001a1f17, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00171e18, 0x00161e18, 0x00151d17, 0x00141c15, 0x00141c15, 0x00131b14, 0x00141c15, 0x00121a14, 0x00111a12, 0x00101810, 0x000f1810, 0x000f1811, 0x000c140e, 0x000c140e, 0x000c140f, 0x000c1410, 0x000c1410, 0x000b130f, 0x0008100c, 0x0008100c, 0x0008100c, 0x0009100c, 0x0008100b, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00050d07, 0x00040d07, 0x00050d08, 0x00050d08, 0x00050d09, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x00070f0a, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070f0a, 0x0005100a, 0x00040f09, 0x0006100b, 0x0006100b, 0x00050f0a, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a0f, 0x004c4d0f, 0x004f5010, 0x00505010, 0x00525310, 0x00535410, 0x00545510, 0x00555611, 0x00555611, 0x00565711, 0x00565710, 0x00565710, 0x00585810, 0x00585810, 0x00585810, 0x00585810, 0x00565710, 0x00585810, 0x00585911, 0x00585910, 0x00595a11, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00616112, 0x00626312, 0x00626313, 0x00666414, 0x00c6a219, 0x00cca519, 0x00796f14, 0x00646414, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606012, 0x005d5e12, 0x009a8114, 0x00cca417, 0x00b09014, 0x00505010, 0x00515110, 0x004d4e0f, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040c06, 0x00040d07, 0x00040d07, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00050e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00070f0a, 0x00070f0b, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100c, 0x0009110d, 0x000b130e, 0x000b130c, 0x000a130c, 0x000c140e, 0x000f150f, 0x000f150f, 0x0010160f, 0x00111710, 0x00131610, 0x00141710, 0x00151813, 0x00151813, 0x00171814, 0x00171814, 0x00171814, 0x00181a15, 0x00181a15, 0x00181a15, 0x00181a15, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181813, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181913, 0x00181914, 0x00181913, 0x00181813, 0x00181914, 0x00181b16, 0x001a1b15, 0x001b1a15, 0x001b1a14, 0x00201c16, 0x00231e18, 0x00241c16, 0x00241d14, 0x00241d16, 0x00241d14, 0x00241d13, 0x00241d12, 0x00241f13, 0x00242013, 0x00231f13, 0x00231f12, 0x00231f12, 0x00231f12, 0x00221e12, 0x00221d14, 0x00231c14, 0x00231c14, 0x00231c14, 0x001d1912, 0x001a1810, 0x0018150d, 0x0015130a, 0x00141208, 0x00131308, 0x0017150d, 0x001f1c14, 0x00211f17, 0x001d1c13, 0x001c1c13, 0x001c1b13, 0x0017130c, 0x00241c14, 0x0032281b, 0x003b2f19, 0x003c2e16, 0x0044311c, 0x00452f1e, 0x0048321d, 0x004a321c, 0x0051371f, 0x0055371d, 0x005d3a1e, 0x005e3818, 0x005e3614, 0x005e3411, 0x00633914, 0x00643d18, 0x00663e18, 0x00643c17, 0x00653c18, 0x00663c16, 0x00693d14, 0x006d4014, 0x00714014, 0x00784518, 0x007d4918, 0x007c4714, 0x007b4511, 0x0078420d, 0x007c4510, 0x00854d14, 0x00844910, 0x007c420a, 0x007c4109, 0x007e420a, 0x0081450c, 0x00854a10, 0x0081470e, 0x007c440c, 0x007c440e, 0x0078420c, 0x00733f09, 0x00703c0c, 0x006e3b0c, 0x006a380e, 0x0066360e, 0x0064360d, 0x0063340c, 0x0060340b, 0x0060340c, 0x0060340b, 0x005d3009, 0x005c310d, 0x005c3311, 0x00582f0f, 0x0052290d, 0x004c2409, 0x00462008, 0x0044200a, 0x0041200d, 0x003a1c0a, 0x003a1c0d, 0x00351c0e, 0x002a170a, 0x00241408, 0x001e1307, 0x001c1106, 0x001d1308, 0x001f1408, 0x00201408, 0x001f1408, 0x001e1409, 0x001c1209, 0x0019140b, 0x0017140b, 0x0016120a, 0x0016120a, 0x0018140d, 0x0019180f, 0x001c1a13, 0x001c1a14, 0x001c1a14, 0x001a1913, 0x00191913, 0x001a1a14, 0x001a1b15, 0x001b1c16, 0x001a1c16, 0x00181c15, 0x00181a14, 0x00181b15, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161c16, 0x00151c15, 0x00161c17, 0x00161c17, 0x00161c16, 0x00161c17, 0x00151c16, 0x00141b15, 0x00141b15, 0x00151c17, 0x00151c16, 0x00141b15, 0x00141a15, 0x00141c15, 0x00141c15, 0x00141c15, 0x00131b14, 0x00131a14, 0x00141a14, 0x00151a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00151b15, 0x00151b15, 0x00161c16, 0x00161c17, 0x00161c16, 0x00151b15, 0x00181b14, 0x00181b14, 0x00181b14, 0x00181b14, 0x00181c15, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d15, 0x00181d14, 0x001a1f16, 0x001b2017, 0x001a1f18, 0x00191d18, 0x00191d18, 0x001a1f19, 0x00191e18, 0x00181e18, 0x00171f18, 0x00171f18, 0x00171f18, 0x00161e18, 0x00161e18, 0x00161e18, 0x00131b14, 0x00121a12, 0x00121b12, 0x00111a12, 0x000f1811, 0x000e1710, 0x000e1710, 0x000e1610, 0x000d1510, 0x000d1510, 0x000c1410, 0x000b130f, 0x000a120e, 0x000a120e, 0x0009120e, 0x0008120d, 0x0005110b, 0x0005110b, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f09, 0x00070f08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060e09, 0x00070f0a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x00070f0a, 0x00080e0a, 0x00070d09, 0x00070d09, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0007110c, 0x00040c08, 0x00050d08, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a0f, 0x004c4d0f, 0x004b4c10, 0x004d4e10, 0x00505010, 0x00525311, 0x00535411, 0x00545510, 0x00555610, 0x00565711, 0x00585812, 0x00585811, 0x00585912, 0x00585912, 0x00585911, 0x00585911, 0x00585912, 0x00595a11, 0x00595a11, 0x00595a12, 0x00595a12, 0x005c5c12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005d5d11, 0x00606012, 0x00606013, 0x00616113, 0x00626213, 0x00636312, 0x00646412, 0x00646414, 0x00847714, 0x00c8a318, 0x00cca519, 0x00797014, 0x00646414, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606012, 0x005d5e12, 0x009a8114, 0x00cca417, 0x00b09014, 0x00505010, 0x00515110, 0x004c4d10, 0x00494a10, 0x0045470e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0020230a, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00070f08, 0x00040d07, 0x00040c07, 0x00040d08, 0x00040d08, 0x00070f0a, 0x00060e0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x0008100b, 0x0008100c, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060f08, 0x00060f08, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050e08, 0x00060d08, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0009110c, 0x000c140e, 0x000c140f, 0x000c140e, 0x000c140e, 0x000d150f, 0x00101711, 0x00101711, 0x00131811, 0x00141811, 0x00141811, 0x00151812, 0x00181814, 0x00181814, 0x00181914, 0x00181915, 0x00181a15, 0x00181a15, 0x00181a15, 0x00181a15, 0x00181a14, 0x00181a13, 0x00181a13, 0x00181a13, 0x00181a13, 0x00181913, 0x00181a14, 0x00181a14, 0x00181a13, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00171813, 0x00171812, 0x00171813, 0x00181813, 0x00181813, 0x00181a14, 0x001a1b15, 0x001b1a15, 0x001a1a15, 0x001c1c15, 0x001f1d16, 0x00201c14, 0x00211c13, 0x00241e14, 0x00241e13, 0x00241e13, 0x00241e11, 0x00241f12, 0x00261f12, 0x00251e11, 0x00251d11, 0x00241e11, 0x00241e11, 0x00241e11, 0x00241e11, 0x00241d13, 0x00231c15, 0x00231c14, 0x001f1a13, 0x001c1810, 0x0018160d, 0x0015140a, 0x00131308, 0x00141408, 0x0014130a, 0x0017150d, 0x001a1910, 0x001b1b12, 0x001b1b12, 0x001b1a13, 0x0015140d, 0x0016120c, 0x0020190f, 0x00352c1c, 0x00372b18, 0x0040311e, 0x0040301c, 0x0043301c, 0x0046321b, 0x0050381f, 0x0051361b, 0x00583418, 0x005b3616, 0x005d3612, 0x00603611, 0x00633914, 0x00653d18, 0x00673d18, 0x00673c18, 0x00683d19, 0x00683d17, 0x006f4319, 0x00714419, 0x00774418, 0x007c4718, 0x00804919, 0x007c4614, 0x007a4411, 0x00753d0b, 0x00743c09, 0x007d440f, 0x007c410c, 0x007e420d, 0x007e420d, 0x007c400c, 0x007d430c, 0x00834b10, 0x007f480f, 0x007c450e, 0x007a440d, 0x0078440d, 0x00743f08, 0x00703c08, 0x006e3a0a, 0x006c380e, 0x0069370f, 0x0066360e, 0x0067370f, 0x0063340b, 0x0061340b, 0x0060340b, 0x005c300a, 0x005c2f0c, 0x00582f0d, 0x00542c0e, 0x0050270b, 0x00482006, 0x00411c04, 0x00411f09, 0x003b1c0a, 0x00341908, 0x00361c10, 0x002c150c, 0x00201005, 0x001e1107, 0x001c1108, 0x001a1007, 0x001b1208, 0x001c1308, 0x001e1309, 0x001f1409, 0x001e1409, 0x001b1309, 0x0019140b, 0x0018140b, 0x0017140a, 0x0017130b, 0x0018160e, 0x0019170f, 0x001c1913, 0x001b1a15, 0x001a1b15, 0x001a1914, 0x00181a14, 0x00181a14, 0x00181c14, 0x00181c16, 0x00191c16, 0x001a1c16, 0x00191a14, 0x00181b15, 0x00171c17, 0x00161c17, 0x00151c16, 0x00141c15, 0x00131b14, 0x00141a14, 0x00151c15, 0x00151a14, 0x00151b16, 0x00141a16, 0x00141a15, 0x00141915, 0x00131915, 0x00131915, 0x00141a16, 0x00141a16, 0x00141c15, 0x00141c15, 0x00141c15, 0x00121a14, 0x00121913, 0x00131813, 0x00131813, 0x00121813, 0x00131813, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00141814, 0x00141814, 0x00141814, 0x00141914, 0x00141a14, 0x00141a14, 0x00141a14, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a14, 0x00161b14, 0x00171c15, 0x00181d16, 0x00181c16, 0x00181d16, 0x001a1e18, 0x00191d17, 0x00181d16, 0x00181d18, 0x00191d18, 0x001b201a, 0x001b201a, 0x00181e18, 0x00181e18, 0x00181e18, 0x00181e18, 0x00171f18, 0x00171f18, 0x00161e18, 0x00141c16, 0x00131b14, 0x00141c15, 0x00141b15, 0x00101812, 0x00101812, 0x00111812, 0x00101610, 0x000f1410, 0x000f1410, 0x000e1510, 0x000d1410, 0x000b120e, 0x000a120e, 0x0009130e, 0x0009130e, 0x0006100b, 0x0005110b, 0x0006100a, 0x00070f0b, 0x00070f0b, 0x00070f0b, 0x0008100b, 0x00081009, 0x00081009, 0x00070f09, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x00060f0a, 0x00070e0a, 0x00070d09, 0x00070e09, 0x0007100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040c08, 0x00060e09, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x003e400d, 0x0043440e, 0x0045470e, 0x00494a0f, 0x004c4d0f, 0x00685e10, 0x00aa8b14, 0x00af8e14, 0x00af8f14, 0x00b09014, 0x00b09014, 0x00b09014, 0x00b09115, 0x00b09115, 0x00b09115, 0x00b09115, 0x00b19315, 0x00b19215, 0x00b19215, 0x00b19215, 0x00b19216, 0x00b29316, 0x00b29316, 0x00b29316, 0x00b29316, 0x00b39316, 0x00b39317, 0x00b39317, 0x00b39417, 0x00b49417, 0x00b49417, 0x00b49417, 0x00b49417, 0x00b49517, 0x00b49518, 0x00b49518, 0x00b59518, 0x00c4a119, 0x00cca519, 0x00c4a019, 0x00746c14, 0x00646514, 0x00646414, 0x00636414, 0x00636413, 0x00616112, 0x00606012, 0x005d5e12, 0x009b8314, 0x00cca417, 0x00b09014, 0x00505010, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450d, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x0008110a, 0x0008110a, 0x000a130c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000e1610, 0x000e1610, 0x000f1811, 0x00101812, 0x00141813, 0x00141811, 0x00141912, 0x00141910, 0x00181813, 0x00181813, 0x00181914, 0x00181a14, 0x00191b14, 0x001a1b14, 0x00191b14, 0x00181a12, 0x00181a12, 0x00181910, 0x0017180f, 0x00181910, 0x00181910, 0x00181b12, 0x00181b12, 0x00181a12, 0x00161811, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00181814, 0x00181814, 0x00181813, 0x00181a14, 0x00181a14, 0x001a1815, 0x00181a14, 0x001b1c15, 0x001f1e14, 0x00211c13, 0x00221c11, 0x00251d11, 0x00261d11, 0x00261d11, 0x00261d11, 0x00271e10, 0x00271e10, 0x00271f0f, 0x00271e10, 0x00271e10, 0x00271e10, 0x00261d10, 0x00241c10, 0x00241c12, 0x00241c12, 0x00241e14, 0x00231c14, 0x001f1910, 0x001b180e, 0x0018170c, 0x0015150a, 0x00141408, 0x00141408, 0x00141408, 0x00191810, 0x00181810, 0x00181810, 0x00181710, 0x00161510, 0x00161410, 0x0016120a, 0x00282217, 0x00372d1f, 0x003f3320, 0x00453823, 0x0043321d, 0x0043301a, 0x004e3820, 0x004d341b, 0x0055341a, 0x005d3b1c, 0x005e3815, 0x005e3812, 0x00623a13, 0x00663c16, 0x00673c16, 0x00693c18, 0x00683c18, 0x00683c16, 0x0070441c, 0x006f4117, 0x0079481b, 0x00804a1e, 0x007c4619, 0x00763e11, 0x00733c0c, 0x00743c0d, 0x00703808, 0x00743b0b, 0x00773d0d, 0x00733909, 0x00753c0a, 0x00773e0c, 0x00743e0a, 0x00744009, 0x0074410c, 0x00764310, 0x0074410d, 0x00703d09, 0x006d3905, 0x006c3907, 0x006c3908, 0x006c390d, 0x0068360d, 0x0068370e, 0x00683810, 0x00603108, 0x00603208, 0x005c2f08, 0x005a2d08, 0x00592d0b, 0x00562c0c, 0x00542c0d, 0x004c2409, 0x00421d03, 0x00432007, 0x003c1e08, 0x00351c0a, 0x0030190c, 0x0025130c, 0x001e0d06, 0x001c1007, 0x001b1108, 0x00191108, 0x00191208, 0x00191208, 0x001c1309, 0x001c1309, 0x001c1208, 0x001c1307, 0x001a130b, 0x0019140b, 0x0018140b, 0x00171409, 0x0018140c, 0x001b170f, 0x001c1810, 0x001c1914, 0x001b1a17, 0x00181915, 0x00181915, 0x00181915, 0x00181a15, 0x00141a14, 0x00141c14, 0x00161b14, 0x00171a14, 0x00181712, 0x00161811, 0x00141812, 0x00111812, 0x00131915, 0x00131b16, 0x00121a15, 0x00131914, 0x00141914, 0x00151a14, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00131914, 0x00131914, 0x00131914, 0x00131914, 0x00121a14, 0x00121a14, 0x00111913, 0x00101812, 0x00121812, 0x00131712, 0x00121712, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00121511, 0x00131511, 0x00131511, 0x00131511, 0x00131511, 0x00141612, 0x00141813, 0x00131914, 0x00131b14, 0x00131b14, 0x00131b14, 0x00131b14, 0x00131a14, 0x00141a14, 0x00141b14, 0x00151c15, 0x00161c15, 0x00181b17, 0x00191c18, 0x00191c18, 0x00181b17, 0x00171c17, 0x00191e19, 0x001a1f18, 0x001a1f16, 0x001a1f16, 0x001a1f18, 0x001a201a, 0x001a1f19, 0x00181f17, 0x00181f17, 0x00181f17, 0x00161c15, 0x00151c14, 0x00151b17, 0x00151b17, 0x00141a16, 0x00141914, 0x00141914, 0x00131712, 0x00101510, 0x0010140f, 0x0010140f, 0x000e140e, 0x000c130d, 0x000c140d, 0x000b140d, 0x000a130c, 0x0008110a, 0x00081009, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x0005100a, 0x00040d08, 0x00040d08, 0x00040d08, 0x0006100b, 0x00040d08, 0x0005100a, 0x00040d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003c3e0d, 0x0041420e, 0x0044450d, 0x0048490f, 0x004c4d0f, 0x005c5710, 0x00b69314, 0x00cca316, 0x00cca316, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca619, 0x00cca619, 0x00c8a418, 0x00978315, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00626313, 0x00626312, 0x00606012, 0x005e5f12, 0x00a48914, 0x00cca417, 0x00b09014, 0x004f5010, 0x00505010, 0x004c4d10, 0x00484910, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0036370b, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x00081009, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f0a, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00060e08, 0x00070f08, 0x00081009, 0x00081009, 0x00081009, 0x0009120b, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c140d, 0x000e1610, 0x000e1610, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00141813, 0x00141811, 0x00141912, 0x00141910, 0x00181813, 0x00181813, 0x00181914, 0x00181a14, 0x001a1b14, 0x001c1c15, 0x001b1c14, 0x00181a12, 0x00181a12, 0x00181910, 0x0017180f, 0x00181910, 0x00181910, 0x00181a14, 0x00181a14, 0x00171914, 0x00161812, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00141813, 0x00131712, 0x00141612, 0x00151612, 0x00161713, 0x00161712, 0x00171812, 0x00191813, 0x001a1b12, 0x001c1c12, 0x001f1e12, 0x00221c10, 0x00241c10, 0x00281c11, 0x00291c12, 0x00291c12, 0x00291c10, 0x00291d10, 0x002a1e10, 0x002a1e11, 0x002a1e11, 0x002a1d13, 0x00291c11, 0x00281c13, 0x00281c13, 0x00281c13, 0x00251c10, 0x00261d11, 0x00241d11, 0x00221b0f, 0x001d190c, 0x001b190b, 0x0018180b, 0x00141508, 0x00121205, 0x00121206, 0x0018170c, 0x0017160d, 0x0016160d, 0x0014140c, 0x0014140b, 0x0014140c, 0x0016140b, 0x00151107, 0x00282315, 0x00352d1d, 0x003c3220, 0x00423421, 0x0044331f, 0x004c3823, 0x004c341d, 0x0055361e, 0x005c3c20, 0x005a3817, 0x005c3814, 0x005f3a15, 0x00633c18, 0x00653b18, 0x00683c1a, 0x00673c18, 0x00683c16, 0x006e411a, 0x006d3f16, 0x0078461c, 0x00764218, 0x006f3c11, 0x006e380f, 0x006f3a0e, 0x006e380c, 0x006b360a, 0x006e390b, 0x00703a0c, 0x006a3508, 0x006c3708, 0x00713c0c, 0x006c3808, 0x006c3b0a, 0x006d3c0c, 0x006d3c0d, 0x006d3c0d, 0x00693809, 0x00683808, 0x00683609, 0x0068370c, 0x0069380c, 0x0068380c, 0x0069390f, 0x0068380f, 0x005f3006, 0x00603209, 0x00582c06, 0x005a2d09, 0x00572c09, 0x0053280a, 0x0050290c, 0x00462107, 0x00401d04, 0x00402208, 0x00391f0b, 0x00311d0c, 0x00241408, 0x001d1108, 0x001c1009, 0x001a0f08, 0x00191008, 0x00181006, 0x00191107, 0x00191208, 0x001a1208, 0x001a1108, 0x00191006, 0x00181205, 0x00181408, 0x00181408, 0x00181408, 0x00181408, 0x001a160b, 0x001c180c, 0x001f190f, 0x001e1913, 0x001b1814, 0x00191816, 0x00181917, 0x00181917, 0x00191816, 0x00171814, 0x00161814, 0x00141811, 0x0013150f, 0x0010120c, 0x0010120a, 0x0010140b, 0x000d120b, 0x00101610, 0x00121914, 0x00111913, 0x00121813, 0x00131712, 0x00121812, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00131914, 0x00131914, 0x00131914, 0x00131914, 0x00131914, 0x00131914, 0x00111813, 0x00101711, 0x00121712, 0x00131712, 0x00121712, 0x00111611, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00121611, 0x00131712, 0x00111812, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00111813, 0x00131914, 0x00141b14, 0x00151c15, 0x00151c15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00141a14, 0x00171d18, 0x00181f17, 0x00181f15, 0x00181f15, 0x00181f17, 0x00181e18, 0x00181f19, 0x00181f17, 0x00181f17, 0x00181f17, 0x00171e16, 0x00161c16, 0x00161c17, 0x00161c17, 0x00141b15, 0x00141a14, 0x00141914, 0x00131712, 0x00111611, 0x0010140f, 0x0010140f, 0x000e140e, 0x000c130d, 0x000c140d, 0x000c140d, 0x000b140d, 0x0008110a, 0x0008100a, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x0006100b, 0x00040e09, 0x0005100a, 0x00040e09, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x00202309, 0x00202309, 0x0026280c, 0x00292b0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00706211, 0x00cca316, 0x00caa216, 0x00b59414, 0x00b39315, 0x00b39316, 0x00b39416, 0x00b39417, 0x00b39417, 0x00b39417, 0x00b39417, 0x00b39417, 0x00b29317, 0x00b29317, 0x00b19217, 0x00b19317, 0x00b19316, 0x00b19316, 0x00b09216, 0x00b09216, 0x00b09216, 0x00b09117, 0x00b09117, 0x00b09116, 0x00b09116, 0x00b09216, 0x00b09217, 0x00b09217, 0x00b09218, 0x00b09218, 0x00b09218, 0x00b09217, 0x00af9318, 0x00a88e17, 0x00857814, 0x00666713, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00636414, 0x00616112, 0x00606013, 0x00605e12, 0x00b49416, 0x00cca417, 0x00ac8c15, 0x004f5010, 0x00505010, 0x004c4d10, 0x00484910, 0x0045470e, 0x0040400d, 0x003c3e0d, 0x0036370c, 0x0034350c, 0x002d2f0a, 0x00292b0b, 0x0026280b, 0x00202309, 0x001d2008, 0x001d2009, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00050d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00050d05, 0x00060e06, 0x00060e06, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x0008100a, 0x000a130c, 0x000c140e, 0x000d140e, 0x00101610, 0x00101610, 0x00101610, 0x00101610, 0x00101610, 0x00121812, 0x00131914, 0x00141a14, 0x00161b15, 0x00161b14, 0x00171c15, 0x00171c14, 0x00181a14, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x001a1b14, 0x001a1b14, 0x00191b13, 0x00181a12, 0x00181a12, 0x00181a10, 0x00181a10, 0x0017180f, 0x00161810, 0x00141913, 0x00141914, 0x00141813, 0x00111611, 0x00131712, 0x00111611, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101610, 0x00101610, 0x00111510, 0x00141712, 0x00161814, 0x00161815, 0x00181613, 0x00191710, 0x001c1b0f, 0x001e1c0f, 0x00221d10, 0x00251c0e, 0x00281d0d, 0x002b1d0c, 0x002d1d0d, 0x002c1c0c, 0x002d1e0e, 0x002f200d, 0x0030210f, 0x00322310, 0x00332411, 0x00322312, 0x00302010, 0x002e1e0f, 0x002c1f10, 0x002c1f10, 0x002a1e0f, 0x00281c0d, 0x00281e0f, 0x00231a0c, 0x001f180a, 0x001d1a0a, 0x001b190a, 0x00171708, 0x00171408, 0x00141208, 0x0016140a, 0x001a180e, 0x001a180e, 0x0016150b, 0x00141408, 0x00141408, 0x00131308, 0x00141207, 0x00141105, 0x00241e13, 0x00342b1d, 0x00413424, 0x00403020, 0x0043301e, 0x004f3824, 0x00523520, 0x0054351c, 0x00573718, 0x00553412, 0x00573413, 0x005d3a18, 0x00623c18, 0x00643c1a, 0x00663b18, 0x00693c18, 0x006b3c17, 0x006c3d14, 0x00704118, 0x006f3f15, 0x006c3b11, 0x006d3b12, 0x006d3c12, 0x0066360d, 0x00623208, 0x00643409, 0x00613107, 0x00633308, 0x0064340a, 0x006a3b0e, 0x0066370a, 0x00643508, 0x0067380b, 0x006a3a10, 0x00633308, 0x0067380d, 0x0067380c, 0x0065350c, 0x0065350d, 0x0066360c, 0x0067390c, 0x0067390d, 0x00623709, 0x005c3005, 0x00582c04, 0x00542904, 0x00542908, 0x00532909, 0x004c2306, 0x004b2509, 0x00462309, 0x003f1f06, 0x003a210a, 0x00311e0a, 0x00221404, 0x00180f04, 0x00150f07, 0x00150f06, 0x00180e07, 0x00180e07, 0x00180f05, 0x00191108, 0x001a1208, 0x00191208, 0x00191208, 0x00181207, 0x00161307, 0x00161408, 0x00161408, 0x00171507, 0x001a1709, 0x001c170a, 0x001d170b, 0x00221b0e, 0x00221b12, 0x001e1913, 0x001c1812, 0x001a1913, 0x001b1812, 0x001b1711, 0x001d1810, 0x001d1912, 0x001c180f, 0x001c1b10, 0x0018190f, 0x00121408, 0x00101408, 0x000d1008, 0x000c100b, 0x000c130d, 0x00101610, 0x00101610, 0x00101610, 0x000e1611, 0x000c1710, 0x000c1710, 0x000c1710, 0x000c1710, 0x00101812, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000e1710, 0x000e1610, 0x000f1610, 0x00101610, 0x00101610, 0x000f150f, 0x000f150f, 0x0010140f, 0x0010140f, 0x0010140f, 0x0010140f, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101711, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x00101913, 0x00121a14, 0x00131b14, 0x00141c15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00151a14, 0x00141a14, 0x00161c16, 0x00171d16, 0x00171e14, 0x00171e14, 0x00171d16, 0x00171d18, 0x00171d18, 0x00181f17, 0x00181f17, 0x00182018, 0x00182018, 0x00171e18, 0x00171d18, 0x00171d18, 0x00161c17, 0x00151c15, 0x00151a14, 0x00141914, 0x00141813, 0x00111611, 0x00111611, 0x00101610, 0x000f150f, 0x000d150f, 0x000e1610, 0x000c140e, 0x000a130c, 0x000a130c, 0x000a1210, 0x0009110f, 0x0008100d, 0x0008100d, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0006100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x0005100a, 0x0006100b, 0x00040e09, 0x0006100b, 0x00060c07, 0x000f130f, 0x000f130f, 0x0014180f, 0x0014180b, 0x00191c0a, 0x001d200a, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004f5010, 0x00515110, 0x00706411, 0x00cca316, 0x00c7a016, 0x006d6612, 0x00605f12, 0x00626013, 0x00636212, 0x00646413, 0x00646413, 0x00656414, 0x00656414, 0x00656414, 0x00656414, 0x00656414, 0x00646413, 0x00646413, 0x00646413, 0x00646313, 0x00646312, 0x00646313, 0x00646313, 0x00646313, 0x00646313, 0x00646313, 0x00646413, 0x00646413, 0x00646414, 0x00656414, 0x00656414, 0x00656414, 0x00666514, 0x00666513, 0x00686714, 0x00686813, 0x00666713, 0x00666713, 0x00656614, 0x00656614, 0x00656614, 0x00646514, 0x00636414, 0x00626313, 0x00616112, 0x006c6613, 0x00c4a017, 0x00cca417, 0x00988014, 0x00515110, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x0008100b, 0x0008100b, 0x00050d08, 0x00050d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00060e06, 0x00060e06, 0x00050d05, 0x00060e08, 0x00060e08, 0x00081009, 0x00070f08, 0x00070f08, 0x0009110b, 0x0008100a, 0x0008100a, 0x0008110a, 0x0008110b, 0x000a130c, 0x000c140e, 0x000d140e, 0x00101510, 0x00101510, 0x00131712, 0x00131712, 0x00131712, 0x00141914, 0x00151a14, 0x00151a14, 0x00161b15, 0x00181a14, 0x00181c15, 0x00181c14, 0x00181813, 0x001a1c15, 0x001c1d18, 0x001b1c16, 0x001a1b14, 0x001a1b14, 0x00191a13, 0x00181911, 0x00181911, 0x00171810, 0x00171810, 0x00161710, 0x00141810, 0x00131812, 0x00121813, 0x00111812, 0x00101610, 0x00101711, 0x00101610, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x00101510, 0x00131713, 0x00161815, 0x00161815, 0x00181712, 0x001a1810, 0x001e1b10, 0x00201c0f, 0x00241d10, 0x00281c0c, 0x002b1c0a, 0x002f1c05, 0x00311f05, 0x00322004, 0x00312005, 0x0038260a, 0x0038270b, 0x00362509, 0x00352408, 0x00352408, 0x00352408, 0x00342408, 0x00342409, 0x0033230b, 0x0030220a, 0x002d200a, 0x002b1e09, 0x00261b08, 0x00241b0a, 0x00211c0a, 0x00201c0b, 0x001c1908, 0x0018170c, 0x0017140a, 0x0017140b, 0x0017140a, 0x0019180c, 0x0017170a, 0x00141408, 0x00131408, 0x00111408, 0x00111308, 0x00131208, 0x00141008, 0x00221c10, 0x00393021, 0x00423525, 0x003f2f1f, 0x0044311e, 0x004a321f, 0x004c311a, 0x0055371d, 0x00543415, 0x00553515, 0x00563414, 0x00603a1a, 0x00633c1c, 0x00643a18, 0x00673c18, 0x00683b15, 0x00673b12, 0x00693c13, 0x006c3d14, 0x006b3c14, 0x00683a11, 0x0064360f, 0x005e300a, 0x00582c05, 0x00572b04, 0x00542803, 0x00572b06, 0x005f320c, 0x0062340c, 0x0062350c, 0x005f3109, 0x005f310a, 0x0061340d, 0x005d300a, 0x005c2f08, 0x005d3009, 0x005f320c, 0x005f320c, 0x0061340c, 0x0064380e, 0x0064380e, 0x005d3308, 0x00592e05, 0x00572c06, 0x00542a08, 0x00542c0c, 0x00542c0d, 0x00492308, 0x00431f05, 0x003e1c06, 0x00381b06, 0x00341f0b, 0x00201200, 0x00181002, 0x00141004, 0x00141008, 0x00151007, 0x00160e06, 0x00170e04, 0x00171005, 0x00181208, 0x00191308, 0x00181308, 0x00181308, 0x00161307, 0x00141407, 0x00141506, 0x00161408, 0x00191709, 0x001c1809, 0x001d1707, 0x001e1607, 0x00251c0d, 0x00281d10, 0x00231a0f, 0x001e180c, 0x001c190c, 0x001d190b, 0x001d1609, 0x00261c0c, 0x002c200f, 0x002e2411, 0x00322a18, 0x002a2514, 0x00181606, 0x00131307, 0x00101308, 0x000f1009, 0x000e1109, 0x0010150e, 0x00101510, 0x00101610, 0x000e1611, 0x000c1810, 0x000c1810, 0x000c1810, 0x000c1810, 0x000e1811, 0x000c160f, 0x000c160f, 0x000c160f, 0x000c160f, 0x000c1710, 0x000c1710, 0x000d1810, 0x000d1610, 0x000c140e, 0x000c140e, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000e150f, 0x000d150f, 0x000c160f, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000e1811, 0x000e1811, 0x000f1912, 0x000f1912, 0x00101912, 0x00111812, 0x00111812, 0x00111812, 0x00101812, 0x00131b14, 0x00141c15, 0x00131c13, 0x00131c13, 0x00131c13, 0x00131c13, 0x00151e18, 0x00151e18, 0x00181f17, 0x00181f17, 0x00182018, 0x00182018, 0x00181e17, 0x00171d16, 0x00181e17, 0x00182018, 0x00181f18, 0x00161b15, 0x00151a14, 0x00141914, 0x00131712, 0x00131712, 0x00111711, 0x00101610, 0x000e1610, 0x000f1710, 0x000c140e, 0x000c140e, 0x000c140e, 0x000a120f, 0x0009110f, 0x0008100d, 0x0008100d, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0007100b, 0x0006100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x00040e09, 0x0008110c, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003e400c, 0x0043440e, 0x0047480e, 0x004c4d10, 0x004f5010, 0x00535410, 0x00716512, 0x00cca417, 0x00c7a116, 0x006c6713, 0x00606013, 0x00626313, 0x00646414, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666713, 0x00656614, 0x00646514, 0x00656614, 0x00646414, 0x00646514, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646514, 0x00646514, 0x00646513, 0x00656614, 0x00666714, 0x00666713, 0x00666714, 0x00666714, 0x00666714, 0x00666714, 0x00666713, 0x00656614, 0x00646513, 0x00646414, 0x00626313, 0x00606013, 0x00947f14, 0x00caa317, 0x00c8a117, 0x00746811, 0x00535410, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x0026280a, 0x0026280c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00081009, 0x00060e08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d07, 0x00070f08, 0x00070f08, 0x00081009, 0x0008100b, 0x0008100c, 0x000b130e, 0x000c1410, 0x000c140f, 0x000e140e, 0x000f150f, 0x000f150f, 0x00101510, 0x00121611, 0x00121711, 0x00141814, 0x00151a14, 0x00151a13, 0x00161b14, 0x00171c15, 0x00171c15, 0x001a1b15, 0x001a1b15, 0x001b1c16, 0x001b1c16, 0x001c1c18, 0x001b1c16, 0x00191b14, 0x001a1b14, 0x00171811, 0x00171812, 0x00161711, 0x00151610, 0x00151610, 0x00131611, 0x00131611, 0x00131510, 0x00131510, 0x00101510, 0x00101510, 0x00111611, 0x00101610, 0x000d1510, 0x000d1510, 0x000c1410, 0x000c1410, 0x000f150f, 0x000f150f, 0x000f150f, 0x000e140e, 0x000c140d, 0x000e150f, 0x00101610, 0x00101510, 0x00131714, 0x00161814, 0x00191711, 0x001c180f, 0x001e190e, 0x00241b10, 0x002c1c10, 0x00321b0d, 0x003c200d, 0x004f3414, 0x00583d1a, 0x004f340e, 0x00482f08, 0x00503812, 0x00503814, 0x004a330f, 0x00442c08, 0x00442b09, 0x00482d0c, 0x00462f0c, 0x0045300c, 0x00422f0c, 0x00382805, 0x00342404, 0x002f2104, 0x002a1e03, 0x00261b08, 0x00251c09, 0x00251d0b, 0x00231c0a, 0x001b190b, 0x00181609, 0x00181709, 0x00161407, 0x0019180a, 0x0019180c, 0x00141408, 0x00111406, 0x00101407, 0x000f1307, 0x00101207, 0x00101107, 0x00131107, 0x00211b10, 0x0033291c, 0x003a2d1f, 0x00483828, 0x0046311f, 0x00442e18, 0x00563d24, 0x00553920, 0x0058391c, 0x00553517, 0x005d391a, 0x005f3818, 0x00603718, 0x00653a18, 0x00623712, 0x00643911, 0x0064380f, 0x0064380f, 0x00653910, 0x005e320a, 0x00592c07, 0x00592c0b, 0x00582c0d, 0x00542b0c, 0x004d2408, 0x0051280c, 0x00552a0c, 0x00582d0e, 0x005c310c, 0x005d320c, 0x005b300b, 0x00582d09, 0x005c300c, 0x00542804, 0x005a2f0b, 0x005d320e, 0x005a2f09, 0x005f340e, 0x00623810, 0x0061370e, 0x005c3008, 0x00542a03, 0x00562b07, 0x00542c0a, 0x00542c0d, 0x004b2608, 0x004b260c, 0x0041210a, 0x00361c09, 0x002e1808, 0x00200e01, 0x00190e04, 0x00141005, 0x00121008, 0x00131008, 0x00151008, 0x00161007, 0x00171106, 0x00171207, 0x00181308, 0x00171408, 0x00151408, 0x00151408, 0x00141408, 0x00161408, 0x00181408, 0x0019140b, 0x001d160c, 0x001f170a, 0x00201806, 0x00261b09, 0x002d200e, 0x00342511, 0x00311f08, 0x002a1901, 0x002b1c05, 0x002e2007, 0x00302003, 0x003d2a08, 0x00463413, 0x00433415, 0x0040321a, 0x002f2410, 0x00181104, 0x00110f05, 0x00121006, 0x00110f05, 0x000f0d04, 0x000f100b, 0x0010140f, 0x000f1410, 0x000d1510, 0x000c1710, 0x000b1710, 0x000b1710, 0x000b1710, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000b1510, 0x000b1510, 0x000a140f, 0x0009130e, 0x000a140f, 0x000a140d, 0x000a140d, 0x000a140d, 0x000a140d, 0x0009140b, 0x0008130a, 0x0009140b, 0x0009140b, 0x000c140c, 0x000c140c, 0x000c140c, 0x000c140c, 0x000a140d, 0x000b150e, 0x000b150e, 0x000b150e, 0x000c1410, 0x000c1410, 0x000d1510, 0x000d1510, 0x000c1610, 0x000b170f, 0x000c1810, 0x000c1810, 0x000c1811, 0x000d1712, 0x000d1711, 0x000e1813, 0x000f1812, 0x00111913, 0x00131b14, 0x00131b14, 0x00131b14, 0x00131b15, 0x00131b14, 0x00141c15, 0x00141c14, 0x00161c16, 0x00181c18, 0x00191d18, 0x00191e18, 0x00191d18, 0x00181c18, 0x00181c17, 0x00181d15, 0x00181c15, 0x00171c17, 0x00171c17, 0x00161b15, 0x00141914, 0x00141612, 0x00131712, 0x00101812, 0x000e1710, 0x00101610, 0x00101610, 0x000c140e, 0x000b140d, 0x000a140d, 0x0009140d, 0x0008120c, 0x0008120c, 0x0009110c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0007100b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0004100a, 0x0004100a, 0x00030f09, 0x00030f09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0044450d, 0x00494a0f, 0x004d4e0f, 0x00515110, 0x00555610, 0x00726612, 0x00cca417, 0x00c7a118, 0x006f6913, 0x00636413, 0x00646514, 0x00656614, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00686814, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00656614, 0x00646514, 0x00636414, 0x006b6613, 0x00bc9917, 0x00cca418, 0x00ad8e15, 0x005b5911, 0x00545510, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0038380c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00081009, 0x00060e08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d07, 0x00070f08, 0x0009110b, 0x0009120b, 0x0008100c, 0x0008100c, 0x000b130e, 0x000c1410, 0x000e1510, 0x000f150f, 0x00101610, 0x00101710, 0x00111711, 0x00141814, 0x00141814, 0x00151a14, 0x00161a14, 0x00181a14, 0x00181a14, 0x00181c15, 0x00181c15, 0x001a1b15, 0x001a1b15, 0x001b1c16, 0x001b1c16, 0x001a1b17, 0x00181914, 0x00181913, 0x001a1b14, 0x00191b14, 0x00181813, 0x00161711, 0x00151610, 0x00141610, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x000f150f, 0x000f150f, 0x000e140e, 0x000e140e, 0x000c140d, 0x000c140d, 0x000b130c, 0x000b130c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140e, 0x000f1610, 0x00101510, 0x00121814, 0x00141711, 0x001a1811, 0x001e1910, 0x0020190c, 0x00281b0e, 0x00301c0a, 0x00402508, 0x005c3c16, 0x00755324, 0x0074501d, 0x0066440e, 0x00603f07, 0x00684811, 0x00684814, 0x0064430f, 0x005f3c08, 0x005c3a08, 0x005e3b0b, 0x005c3a0c, 0x005a3a0f, 0x00573a10, 0x00483008, 0x003b2704, 0x00332204, 0x002d1f05, 0x002b1d09, 0x00291d0a, 0x00281e09, 0x00241c08, 0x001e1c0b, 0x001b1909, 0x001b1a0a, 0x001c1c0c, 0x001b1a0a, 0x00191809, 0x00181809, 0x00101404, 0x000d1204, 0x000e1205, 0x000e1207, 0x000e1107, 0x00121308, 0x00151206, 0x001a1408, 0x002d2416, 0x003e3121, 0x00443220, 0x0045301d, 0x00523a25, 0x00583c27, 0x00563a1f, 0x00543518, 0x005a3818, 0x005a3415, 0x005d3415, 0x00613816, 0x005f3511, 0x00663c15, 0x0060370e, 0x0060340c, 0x005c320b, 0x005c320b, 0x00572b06, 0x0057290b, 0x0056290c, 0x00542a10, 0x004c250b, 0x004e250c, 0x004e250a, 0x00532a0c, 0x005a3110, 0x005c3310, 0x005a300d, 0x00562c09, 0x00552b08, 0x00562c09, 0x005c3310, 0x00603613, 0x005a310d, 0x005b310c, 0x00603611, 0x005f350f, 0x005c330c, 0x00552c07, 0x00542c09, 0x00532c0b, 0x00492607, 0x00411f04, 0x0042230c, 0x0039200b, 0x00291505, 0x001c0d01, 0x00160b00, 0x00160e06, 0x00140f09, 0x00120f0a, 0x00141009, 0x00161109, 0x00161208, 0x00171407, 0x00171408, 0x00171408, 0x00161408, 0x00161408, 0x00161407, 0x00151406, 0x00171406, 0x001a1408, 0x001b1308, 0x001e150c, 0x0021170a, 0x00281b08, 0x002b1d08, 0x00362410, 0x003f2a0f, 0x00432b08, 0x00462d03, 0x004e3407, 0x005a4010, 0x00563e0b, 0x0058400f, 0x00543d13, 0x0044300d, 0x0032230a, 0x00241707, 0x00170f04, 0x00110f05, 0x00121006, 0x00111005, 0x000f0d04, 0x00101009, 0x0011140e, 0x000f1410, 0x000d1410, 0x00091410, 0x00091410, 0x00091410, 0x00091410, 0x000a1410, 0x000a1410, 0x000a1410, 0x000a1410, 0x000a1410, 0x00091310, 0x00091310, 0x0008120f, 0x0009130f, 0x0009130e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0008120c, 0x0008120c, 0x0009140c, 0x0009140c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000a140d, 0x000b150e, 0x000a140d, 0x000a140d, 0x000c140f, 0x000c140f, 0x000c1410, 0x000c1410, 0x000b150f, 0x000a160e, 0x000b170f, 0x000c1810, 0x000c1811, 0x000c1713, 0x000c1711, 0x000c1711, 0x000d1710, 0x00101812, 0x00111913, 0x00131b14, 0x00131b14, 0x00141a16, 0x00141a14, 0x00151c15, 0x00151c14, 0x00161b15, 0x00161b15, 0x00171c17, 0x00181c17, 0x00181c18, 0x00181d17, 0x00181d15, 0x00181d14, 0x00181c14, 0x00171c17, 0x00171c17, 0x00161b15, 0x00141914, 0x00141813, 0x00121712, 0x00101812, 0x000e1710, 0x00101610, 0x00101610, 0x000e1710, 0x000c140e, 0x000a140d, 0x0009140c, 0x0008120c, 0x0008120c, 0x0009110c, 0x0009110d, 0x0008100b, 0x0008100b, 0x0007100b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0004100a, 0x0004100a, 0x00030f09, 0x00030f09, 0x00040e09, 0x0005100a, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0026280c, 0x00292b0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x004b4c0f, 0x00505010, 0x00535410, 0x00565711, 0x00746812, 0x00cca418, 0x00c7a118, 0x00706b14, 0x00646414, 0x00656614, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00666713, 0x00656614, 0x00646513, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00646514, 0x00646414, 0x00a28915, 0x00cba418, 0x00c6a118, 0x00786c13, 0x00565711, 0x00545511, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00081009, 0x00060e08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060e06, 0x00071007, 0x00060e06, 0x00060e06, 0x00081009, 0x00081009, 0x0009120c, 0x0009120c, 0x000a120e, 0x000b130e, 0x000c1410, 0x000d1510, 0x000e1510, 0x00101610, 0x00101711, 0x00111812, 0x00131812, 0x00161812, 0x00161812, 0x00181c15, 0x00191c15, 0x001a1b14, 0x001a1b14, 0x001a1b14, 0x001a1b14, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x001a1b17, 0x00181914, 0x00181813, 0x00181912, 0x00161810, 0x00141710, 0x00131610, 0x0012150f, 0x0011150f, 0x0010150f, 0x000f150f, 0x000e140f, 0x000c130d, 0x000c140d, 0x000c140e, 0x000a130c, 0x000a130c, 0x000a130c, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008130c, 0x0008130c, 0x0008120c, 0x0008120c, 0x0009130c, 0x000b140d, 0x000e150f, 0x00101510, 0x00111613, 0x00141510, 0x001b1811, 0x00201810, 0x0023190d, 0x002e1e0f, 0x003c2408, 0x00634414, 0x007f581b, 0x0091651c, 0x008e6212, 0x008c600f, 0x00895f0b, 0x00916814, 0x00916815, 0x008c6410, 0x008a600d, 0x008a600c, 0x00895e0c, 0x00855a11, 0x007e5514, 0x00684209, 0x00513302, 0x00432b02, 0x00372405, 0x002e1e06, 0x002e1e09, 0x002d1e0a, 0x002b1f09, 0x0029200b, 0x00221e0b, 0x001f1c0a, 0x00201c0b, 0x00201d0b, 0x001e1c09, 0x001a1908, 0x001a1b09, 0x00161a09, 0x000c1002, 0x000c1004, 0x000c1005, 0x000c1006, 0x000e1006, 0x00121108, 0x00151208, 0x00181307, 0x00292012, 0x003f3020, 0x00402e1e, 0x004b3623, 0x00503824, 0x0050351d, 0x00503419, 0x00563719, 0x00563417, 0x005d3417, 0x005f3414, 0x00623816, 0x00643c16, 0x005d350e, 0x005b330c, 0x00572f0a, 0x005b330d, 0x005b300e, 0x00582b0e, 0x0054280e, 0x0050270c, 0x004c240c, 0x004c240d, 0x004b250a, 0x00532c0e, 0x00532c0c, 0x00502808, 0x00512908, 0x00572c0c, 0x00562c0c, 0x00512807, 0x00572d0c, 0x005d3313, 0x005c3210, 0x00572d0a, 0x00582e0a, 0x0059300c, 0x00582f0a, 0x00512806, 0x004e2809, 0x00502c10, 0x0049270d, 0x003c1f08, 0x00331c0b, 0x00281608, 0x00190c02, 0x00140c04, 0x00120d05, 0x00110d08, 0x00120e0c, 0x00100f0c, 0x00120f0b, 0x00131009, 0x00141208, 0x00151406, 0x00161407, 0x00161408, 0x00161408, 0x00161407, 0x00181508, 0x00191507, 0x001b1406, 0x001d1408, 0x0020160b, 0x0024180c, 0x00281a0c, 0x002e1f0a, 0x00312008, 0x003f280d, 0x00503510, 0x006e4e1b, 0x008d682a, 0x009d7128, 0x00a0762a, 0x008e6b24, 0x006e4e16, 0x004d340a, 0x00352103, 0x00211400, 0x00180f02, 0x00131006, 0x00111005, 0x00100f04, 0x00111005, 0x00100e05, 0x000e0f08, 0x000e110b, 0x000e130e, 0x000c1410, 0x00081311, 0x00081312, 0x00081312, 0x00081312, 0x00091312, 0x00091312, 0x00091312, 0x00091312, 0x00091211, 0x00091111, 0x00091211, 0x00091211, 0x00091310, 0x00091310, 0x00091310, 0x0008120f, 0x0008120f, 0x0009130e, 0x0008120c, 0x0008110c, 0x0008110c, 0x0009110e, 0x0009110e, 0x0009110e, 0x0009110e, 0x0008130c, 0x0009140c, 0x0009140c, 0x0009140c, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009140e, 0x0009160e, 0x000a160e, 0x000b160e, 0x000b1610, 0x000c1511, 0x000c1610, 0x000c1610, 0x000c160f, 0x000d150f, 0x000f1710, 0x000f1811, 0x00111913, 0x00141815, 0x00151a14, 0x00141914, 0x00151a13, 0x00161a14, 0x00161a15, 0x00171c17, 0x00181c17, 0x00171c16, 0x00171c14, 0x00171c14, 0x00171c13, 0x00171c14, 0x00171c17, 0x00171c17, 0x00171c17, 0x00151a14, 0x00161b15, 0x00141a14, 0x00131914, 0x00101812, 0x00101610, 0x00101710, 0x000e1610, 0x000e1610, 0x000c1610, 0x000b150e, 0x000a140d, 0x0008120c, 0x0009110c, 0x0009110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110b, 0x0005110b, 0x0006120c, 0x0004100a, 0x0004100a, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00141809, 0x00191c09, 0x00202309, 0x00202309, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003e400d, 0x0043440e, 0x0048490e, 0x004c4d0f, 0x00505010, 0x00545510, 0x00585911, 0x00756a13, 0x00cca418, 0x00c7a218, 0x00716c14, 0x00656614, 0x00686814, 0x00696914, 0x006a6a14, 0x006b6b14, 0x006b6b14, 0x006b6b14, 0x006b6b14, 0x006b6b14, 0x006a6a14, 0x006a6a14, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00686814, 0x00686814, 0x00686814, 0x00656614, 0x00907e15, 0x00c8a418, 0x00cba418, 0x009c8415, 0x005c5c12, 0x00585810, 0x00545511, 0x00515110, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00081009, 0x00060e08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060e06, 0x00071007, 0x00081108, 0x00081108, 0x00081009, 0x00081009, 0x0009120c, 0x000a130c, 0x000c1410, 0x000d1510, 0x000d1510, 0x000e1610, 0x000f1610, 0x00101610, 0x00111812, 0x00141914, 0x00151a14, 0x00191a13, 0x00191a13, 0x001a1b14, 0x001a1b14, 0x001b1a14, 0x001b1a14, 0x001b1a14, 0x001b1a14, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x00181915, 0x00171813, 0x00161712, 0x00161710, 0x00141610, 0x00111610, 0x0011160f, 0x0010150e, 0x0010150e, 0x000d150f, 0x000d150f, 0x000c140e, 0x000c140d, 0x0009140c, 0x0009140c, 0x0009140c, 0x0009140c, 0x0009120a, 0x00081108, 0x00081108, 0x00081108, 0x0007110a, 0x0006120a, 0x0007120b, 0x0008130c, 0x0008130c, 0x000a150d, 0x000d1510, 0x000f1510, 0x00111613, 0x00141510, 0x001c1711, 0x00201810, 0x00261c0e, 0x0031200c, 0x00462a08, 0x007c571b, 0x00a97e2c, 0x00be8c28, 0x00c08e24, 0x00c09023, 0x00bd8e1d, 0x00c29422, 0x00c39523, 0x00c29423, 0x00c19421, 0x00c0931b, 0x00bd9018, 0x00bc8e22, 0x00b08223, 0x007c5003, 0x00583400, 0x004a2e00, 0x003c2707, 0x00322109, 0x00311f0a, 0x0030200a, 0x002d1f08, 0x002b1f08, 0x0024210c, 0x00222009, 0x00201d08, 0x00201d08, 0x00221e09, 0x001e1c09, 0x001a1b06, 0x00141803, 0x00151909, 0x000f1208, 0x000c0f04, 0x000c1007, 0x000c0f08, 0x000e0e07, 0x00100e06, 0x00141108, 0x00171004, 0x002c2314, 0x00382c1c, 0x0040301e, 0x003f2c17, 0x004f3720, 0x004d321b, 0x0055371d, 0x00553418, 0x005c3416, 0x005b3213, 0x00613916, 0x00603914, 0x005f3810, 0x00573009, 0x005c3410, 0x00572f0b, 0x005c3312, 0x00582b10, 0x0054280f, 0x0050270c, 0x004c240d, 0x0049240d, 0x004a250c, 0x00522b11, 0x00522b0e, 0x004f280a, 0x00572f10, 0x0053280c, 0x00572c0f, 0x00582e10, 0x00592e11, 0x00572e0e, 0x0059300f, 0x00572c0c, 0x00582e0c, 0x00562c0c, 0x00512808, 0x00492104, 0x00472008, 0x0048250f, 0x003d1e0a, 0x00311705, 0x00201004, 0x00170c04, 0x00130c07, 0x0013110b, 0x000f0e08, 0x000f0e08, 0x000f0e0b, 0x00110d0d, 0x0010100c, 0x00121109, 0x00141408, 0x00141407, 0x00161408, 0x00161408, 0x00151407, 0x0019170a, 0x001c190a, 0x001d1807, 0x001e1707, 0x00201608, 0x0024180a, 0x00281b0c, 0x002b1c0a, 0x00312109, 0x00352308, 0x00442c0c, 0x0055370a, 0x008c6528, 0x00b98c40, 0x00be862c, 0x00af7a1d, 0x008d6016, 0x005d3504, 0x00351a00, 0x00221200, 0x001a1103, 0x00131206, 0x00101108, 0x00110f05, 0x000e0c02, 0x000e0c02, 0x00101007, 0x0011130b, 0x000e110b, 0x000e120d, 0x000c1310, 0x00081110, 0x00071210, 0x00071210, 0x00071210, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0007100f, 0x00081110, 0x00081110, 0x00081210, 0x0008120f, 0x0008120e, 0x0007110d, 0x0007110d, 0x0008120d, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110b, 0x0008120c, 0x0009140d, 0x0009140d, 0x0008140e, 0x0008140e, 0x0007130d, 0x0007130d, 0x0008140d, 0x0008140d, 0x0008140d, 0x0008150e, 0x0008140f, 0x000a1410, 0x000b1410, 0x000c1610, 0x000c160f, 0x000d150f, 0x000d150f, 0x000d140e, 0x000e1610, 0x00121613, 0x00141813, 0x00121712, 0x00141811, 0x00141914, 0x00141914, 0x00151a14, 0x00161b16, 0x00171c15, 0x00171c14, 0x00171c13, 0x00161c12, 0x00161c13, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161b15, 0x00161c16, 0x00161c15, 0x00151b15, 0x00141914, 0x00131712, 0x00111813, 0x000f1610, 0x000f1610, 0x000d1710, 0x000c1710, 0x000c160f, 0x000a140d, 0x0009120c, 0x0008100c, 0x0008100b, 0x0008100c, 0x0007100c, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110b, 0x0005110b, 0x0006120c, 0x0004100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0020230a, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003e400c, 0x0043440e, 0x0048490f, 0x004c4d10, 0x00515110, 0x00555610, 0x00595a11, 0x00756a13, 0x00cca418, 0x00c7a218, 0x00726d14, 0x00686814, 0x00696914, 0x006b6b14, 0x006c6c14, 0x006c6c15, 0x006c6c15, 0x006c6c15, 0x006c6c15, 0x006c6c15, 0x006b6b14, 0x006a6a14, 0x006a6a14, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x006a6a14, 0x00696914, 0x00696914, 0x00686814, 0x00686814, 0x00938115, 0x00c6a219, 0x00cca518, 0x00b09217, 0x00646212, 0x005b5b11, 0x00585910, 0x00545510, 0x00515110, 0x004c4d10, 0x00484910, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00080f0a, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00081009, 0x0008110a, 0x00081009, 0x00060e08, 0x00040f08, 0x00081009, 0x000c120c, 0x000c130d, 0x000c130d, 0x000f150f, 0x00101610, 0x0010170f, 0x00121911, 0x00141912, 0x00151812, 0x00171910, 0x00181b12, 0x001a1b14, 0x001a1b14, 0x001b1c14, 0x001b1c14, 0x001a1b14, 0x001a1b14, 0x001b1c14, 0x001b1c14, 0x00181c15, 0x00181c15, 0x00171a14, 0x00161913, 0x00141813, 0x00141714, 0x00141714, 0x00121510, 0x00101510, 0x00101510, 0x0010140f, 0x0010140f, 0x000f140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000c130d, 0x0008120b, 0x0008120b, 0x0007110a, 0x0007110a, 0x00061009, 0x0007110a, 0x0007110a, 0x0007110a, 0x00061008, 0x00070f08, 0x00081009, 0x0009120b, 0x000b140e, 0x000c140f, 0x000c1210, 0x000d1211, 0x00101412, 0x00141510, 0x001b1610, 0x00201810, 0x00271c0c, 0x00351f0a, 0x004c2d0f, 0x00856021, 0x00c49936, 0x00c9a124, 0x00cca622, 0x00cca81d, 0x00cca819, 0x00cba817, 0x00cba817, 0x00cba918, 0x00c9a818, 0x00c8a914, 0x00c9a90e, 0x00cba615, 0x00c3981d, 0x00906208, 0x00633b01, 0x00523108, 0x00442c0c, 0x0038260f, 0x0034230b, 0x0034230b, 0x0033230b, 0x00302108, 0x002a2108, 0x00272008, 0x00241d08, 0x00241d09, 0x00241f0b, 0x00221e09, 0x001a1a08, 0x00151a08, 0x00141809, 0x000e1106, 0x000b0e04, 0x000c0f07, 0x000c0f08, 0x000d0f07, 0x00100f08, 0x00100f08, 0x00131007, 0x00151004, 0x00211a0c, 0x00322817, 0x003b2c18, 0x003f2c18, 0x0049311c, 0x0051341d, 0x00543419, 0x00563214, 0x00583312, 0x00583410, 0x0056310b, 0x0059340c, 0x0059340e, 0x0058320f, 0x0055300d, 0x00532c0c, 0x0052280c, 0x004d2408, 0x004f260c, 0x00502a10, 0x0048240b, 0x00442006, 0x00512c12, 0x00512c0f, 0x004c2508, 0x0050290a, 0x00542e0f, 0x00522a0c, 0x00532b0f, 0x00572f10, 0x00512c0b, 0x00532d0a, 0x00542d09, 0x00502907, 0x004e2708, 0x004b240c, 0x0046220b, 0x003e1e08, 0x00341c08, 0x00271703, 0x001a1000, 0x00171009, 0x00140e09, 0x00100d07, 0x00100e08, 0x00100e08, 0x00100d07, 0x000f0e06, 0x00101008, 0x00131009, 0x00131008, 0x00161309, 0x0018140b, 0x0018140a, 0x00181409, 0x001b170b, 0x00201c0c, 0x00201c0a, 0x00201807, 0x00221708, 0x00251809, 0x00281b09, 0x002d1f05, 0x002f2008, 0x0033240b, 0x003b2a0d, 0x00432b0a, 0x0055390c, 0x00805c20, 0x00a77b33, 0x00a77420, 0x0084540c, 0x00623604, 0x003d1800, 0x00291103, 0x00201004, 0x00181107, 0x00121208, 0x00111108, 0x000f0e05, 0x000b0b01, 0x00121108, 0x00101008, 0x00101109, 0x000e110b, 0x000d110c, 0x000c120d, 0x0009110e, 0x0009120f, 0x00081010, 0x00061110, 0x00091211, 0x00081110, 0x0007100f, 0x0007100f, 0x00091310, 0x0007110d, 0x0006100c, 0x0006100c, 0x0007100d, 0x0008120e, 0x0008110e, 0x0006110d, 0x0007110d, 0x0007110c, 0x00040e09, 0x00040f09, 0x0005100a, 0x0008120c, 0x0006100b, 0x0008110c, 0x0009130e, 0x0008120e, 0x0008120f, 0x0007110d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0008120e, 0x0008120e, 0x0008120f, 0x0007130f, 0x0007130f, 0x0007130f, 0x0007130f, 0x0008120f, 0x000b1411, 0x000a1410, 0x000a1410, 0x000b1510, 0x000c1610, 0x000c1610, 0x000c1610, 0x000e1410, 0x00101512, 0x00111611, 0x00111610, 0x00121911, 0x00131a12, 0x00131a12, 0x00131a12, 0x00141a13, 0x00151a13, 0x00161b14, 0x00161b14, 0x00161c15, 0x00181e18, 0x00181e18, 0x00171d16, 0x00181d15, 0x00191c16, 0x00181c15, 0x00181b14, 0x00161913, 0x00141914, 0x00141813, 0x00111611, 0x0010140f, 0x000f1410, 0x000e1610, 0x000c160f, 0x000a140c, 0x000a130d, 0x000b120e, 0x0009110d, 0x0009110d, 0x0008120c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x0005100a, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250c, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x003b3c0d, 0x0040400d, 0x0044450e, 0x00494a0f, 0x004d4e0f, 0x00525310, 0x00565711, 0x005c5c12, 0x00776c14, 0x00cca518, 0x00c7a218, 0x00736e14, 0x00696914, 0x006b6b14, 0x006c6c15, 0x006d6d15, 0x006d6d15, 0x006e6e15, 0x006d6d15, 0x006d6d15, 0x006c6c15, 0x006c6c15, 0x006b6b14, 0x006b6b14, 0x00696914, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x006a6a14, 0x006a6a14, 0x006a6a14, 0x00686814, 0x00757014, 0x00a58d17, 0x00c8a419, 0x00cca619, 0x00b79817, 0x006f6813, 0x005e5f12, 0x005c5c12, 0x00585910, 0x00555610, 0x00515110, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040c08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00050d09, 0x00040c08, 0x0008100a, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00070f08, 0x00081009, 0x00070f08, 0x00081009, 0x00051008, 0x0008110b, 0x000d140e, 0x000d140e, 0x000d140e, 0x00101610, 0x00101710, 0x00111810, 0x00131810, 0x00151812, 0x00171812, 0x00191b12, 0x001b1c13, 0x001a1b14, 0x001a1b14, 0x001b1c14, 0x001b1c14, 0x001a1b15, 0x001a1b15, 0x001b1c16, 0x001b1c16, 0x00181c15, 0x00171c15, 0x00151a13, 0x00141811, 0x00111613, 0x00111613, 0x00121714, 0x00101512, 0x00101510, 0x000f150f, 0x000f150f, 0x000d140e, 0x000d140e, 0x000c120c, 0x000c120c, 0x000c120c, 0x000a110c, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00040f08, 0x00051008, 0x00051008, 0x00051008, 0x00070f08, 0x00070f08, 0x00081009, 0x0009120b, 0x000a130c, 0x000a120e, 0x000b1110, 0x000d1211, 0x00101412, 0x00141510, 0x001b1610, 0x00201810, 0x00271c0c, 0x0035200b, 0x004c2c0e, 0x00876123, 0x00c39c33, 0x00cbab24, 0x00ccb020, 0x00ccb219, 0x00ccb414, 0x00ccb412, 0x00ccb412, 0x00ccb411, 0x00cbb410, 0x00cbb40e, 0x00cbb30b, 0x00ccb011, 0x00c09b18, 0x008a6102, 0x00684006, 0x0058360c, 0x0048300e, 0x003c2b10, 0x0037250a, 0x0037250a, 0x0038260b, 0x00342408, 0x00302407, 0x002d2207, 0x002b1f08, 0x002a1f09, 0x00281f09, 0x00241d09, 0x0020200d, 0x00191c0b, 0x00151a09, 0x00111508, 0x000c1004, 0x000b0e05, 0x000c0f07, 0x000d0f07, 0x000f1008, 0x000f1008, 0x00111109, 0x00141006, 0x00151105, 0x001b1404, 0x00261d0c, 0x00362915, 0x00422f1c, 0x004f3520, 0x0051341c, 0x00533417, 0x00543414, 0x00543110, 0x00502d08, 0x0058350f, 0x0056330d, 0x00502c0a, 0x004c2808, 0x004c280a, 0x004d270a, 0x004a2306, 0x00482406, 0x004d280c, 0x00482408, 0x004a260a, 0x004f2c10, 0x00502c0e, 0x004b2508, 0x004d2809, 0x004f2b0b, 0x004c2808, 0x004c2808, 0x00502c0c, 0x004c2a06, 0x004e2d08, 0x004d2a04, 0x00492602, 0x00472505, 0x00432409, 0x0040220c, 0x00301804, 0x00231000, 0x001b1000, 0x00160f02, 0x00131009, 0x00121009, 0x00110f08, 0x00100d07, 0x000f0f05, 0x000f0f05, 0x000e0e04, 0x00111008, 0x00131107, 0x00131107, 0x0018140b, 0x001a160c, 0x001b150d, 0x001c160d, 0x001e180c, 0x00221c0c, 0x00241c0c, 0x00251b09, 0x00271b08, 0x002b1c08, 0x002e1f0a, 0x00302209, 0x0032240a, 0x0038290f, 0x0038290d, 0x00392409, 0x00412704, 0x00543308, 0x00633d0b, 0x005d3504, 0x00482200, 0x00381800, 0x002c1104, 0x0025120d, 0x001d100d, 0x0018100b, 0x00141108, 0x00121107, 0x00111007, 0x00101007, 0x00131209, 0x000f0f05, 0x000d0f07, 0x000c1009, 0x000c100c, 0x000c120c, 0x0008100a, 0x000b1310, 0x00091310, 0x00081311, 0x00091310, 0x0008120f, 0x0007110d, 0x0007110d, 0x00091310, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110d, 0x0006110d, 0x0006100b, 0x0005100a, 0x0006100b, 0x0006100b, 0x0007110c, 0x0006100b, 0x0005100a, 0x0008110c, 0x0007100d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0007110e, 0x0007130f, 0x0007130f, 0x0007130f, 0x0007130f, 0x0008110d, 0x000a1410, 0x00091310, 0x00091310, 0x0009130e, 0x000a140f, 0x000b1510, 0x000b1410, 0x000c130f, 0x000f1410, 0x00101610, 0x0010160e, 0x00121911, 0x00121911, 0x00111810, 0x00111810, 0x00131812, 0x00141813, 0x00141913, 0x00141913, 0x00151b15, 0x00161c17, 0x00161c16, 0x00171d16, 0x00181d14, 0x00191c16, 0x00181c15, 0x001a1d17, 0x00181b14, 0x00161b16, 0x00151a14, 0x00141813, 0x00111611, 0x00101411, 0x0010150f, 0x000e150f, 0x000c150d, 0x000c130e, 0x000b120e, 0x0009110d, 0x0009110d, 0x0008120c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008110c, 0x0008110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0b, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x0040400e, 0x0045470e, 0x004b4c0f, 0x004f5010, 0x00535410, 0x00585811, 0x005c5d12, 0x00786c14, 0x00cca518, 0x00c7a318, 0x00746f14, 0x006a6a14, 0x006c6c14, 0x006d6d15, 0x006e6e15, 0x006f6f14, 0x006f6f14, 0x006f6f14, 0x006e6e15, 0x006d6d15, 0x006c6c15, 0x006c6c14, 0x006b6b14, 0x006a6a14, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x006a6a14, 0x006c6b14, 0x00716e14, 0x007d7414, 0x009f8a16, 0x00c09e19, 0x00cca71a, 0x00cba51a, 0x00b49618, 0x00716c14, 0x00626313, 0x005e5f13, 0x005c5c11, 0x00585911, 0x00555610, 0x00515110, 0x004d4e0f, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x000f130b, 0x000f130f, 0x000f130f, 0x0008100b, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040f09, 0x0005100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00070f08, 0x00081009, 0x00060e08, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d05, 0x00040c08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00060e08, 0x0008110b, 0x0008110a, 0x0008110b, 0x00061009, 0x000a130c, 0x000f150f, 0x000f150f, 0x00101510, 0x00121712, 0x00141812, 0x00141810, 0x00161912, 0x00181913, 0x00181913, 0x001a1a12, 0x001c1c14, 0x001b1c14, 0x001b1c14, 0x001a1b14, 0x001a1b14, 0x001b1c16, 0x001b1c16, 0x001a1b15, 0x001a1b15, 0x00171913, 0x00151a13, 0x00141811, 0x00111610, 0x00101411, 0x00101411, 0x00121613, 0x00101512, 0x000e140f, 0x000d140e, 0x000d140e, 0x000c120c, 0x000b110c, 0x0009120c, 0x00081009, 0x0008110a, 0x00070f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x0008110a, 0x0009120c, 0x000a110d, 0x000d1210, 0x00101410, 0x0015140e, 0x001c1510, 0x0020170f, 0x00271b0a, 0x00311f08, 0x0044280c, 0x006f4c14, 0x00aa8628, 0x00c5a524, 0x00cbae20, 0x00ccb017, 0x00cbb310, 0x00ccb410, 0x00ccb410, 0x00cbb50c, 0x00cab408, 0x00cbb508, 0x00cbb508, 0x00ccb112, 0x00b99513, 0x00845b00, 0x00683e04, 0x005a380c, 0x004a310c, 0x00402e0c, 0x003b2a09, 0x003b2a09, 0x003c2b0a, 0x00392808, 0x00372808, 0x00342508, 0x00332307, 0x0033220a, 0x002f220b, 0x00261e08, 0x00201e08, 0x001e1f0b, 0x001b1f0c, 0x00141807, 0x000c1002, 0x000b0d04, 0x000a0d04, 0x000c0e06, 0x000d0f07, 0x000d0f07, 0x00101009, 0x00101008, 0x00141208, 0x00161105, 0x00181203, 0x00221908, 0x00372817, 0x00483421, 0x004c331c, 0x00503218, 0x00543417, 0x00583718, 0x00533310, 0x0050300c, 0x004c2c09, 0x004b2809, 0x004a270b, 0x00482509, 0x004a260a, 0x00492608, 0x004a2709, 0x004c280a, 0x004e290b, 0x004e290c, 0x004d280a, 0x004c2808, 0x00482606, 0x00482505, 0x004b2908, 0x004e2d0b, 0x00502f0c, 0x004c2c08, 0x004b2b08, 0x004d2f0a, 0x0051310f, 0x00492a0b, 0x00402408, 0x003d230c, 0x002d1704, 0x00211000, 0x001c0f04, 0x00191005, 0x00151108, 0x0013120b, 0x00101009, 0x00101008, 0x000e0e06, 0x000e0d04, 0x000e0d04, 0x00100e06, 0x00121207, 0x00161409, 0x00171408, 0x001a160b, 0x001b150b, 0x001c150b, 0x001f170b, 0x00251c0d, 0x0028200d, 0x00281e0a, 0x002c200a, 0x0030220b, 0x00312109, 0x00312109, 0x00302108, 0x00302308, 0x00302206, 0x002d1e04, 0x002d1a03, 0x00321902, 0x00381a01, 0x00381600, 0x00331804, 0x002c1605, 0x00241106, 0x001d0e08, 0x001a0e0c, 0x001a100d, 0x0018100b, 0x00161008, 0x00141108, 0x00131108, 0x00121008, 0x00111108, 0x000e0e05, 0x000d0f07, 0x000c1008, 0x000a0f08, 0x000c120b, 0x000c140d, 0x0008110b, 0x0009130f, 0x00081410, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x00091310, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0004100c, 0x0005100c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100c, 0x0006100c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0007100d, 0x00050f0c, 0x0005100c, 0x0006110d, 0x0006110d, 0x0006110d, 0x0006110d, 0x0007110d, 0x0007110d, 0x00091310, 0x00091310, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x000b130e, 0x000c1410, 0x000d150f, 0x000d160d, 0x00101710, 0x00111810, 0x00111810, 0x00101710, 0x00121711, 0x00131712, 0x00141813, 0x00141914, 0x00141a14, 0x00151c15, 0x00151c15, 0x00161c15, 0x00171c14, 0x00181c15, 0x00181c15, 0x001a1d17, 0x00181c15, 0x00171c17, 0x00161b15, 0x00151a14, 0x00141813, 0x00141614, 0x00111611, 0x00101610, 0x000e160e, 0x000d1410, 0x000c1410, 0x000c140f, 0x000a120e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120c, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120d, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f1612, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x0014180a, 0x001d2009, 0x001d2008, 0x0024250b, 0x00292b0b, 0x002d2f0b, 0x0030310c, 0x0036370c, 0x003b3c0d, 0x0040400d, 0x0045470e, 0x004b4c0f, 0x00505010, 0x00545510, 0x00585911, 0x005c5d12, 0x00786c14, 0x00cca518, 0x00caa419, 0x00b19518, 0x00af9418, 0x00b09418, 0x00b09418, 0x00b09518, 0x00b09518, 0x00b09518, 0x00b09518, 0x00b09518, 0x00b09518, 0x00b09418, 0x00b09418, 0x00af9418, 0x00af9318, 0x00af9318, 0x00af9318, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00ae9117, 0x00ae9117, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00af9218, 0x00af9318, 0x00af9318, 0x00af9418, 0x00b39618, 0x00bc9c18, 0x00c8a519, 0x00cca71a, 0x00cca71a, 0x00c8a419, 0x00a48c17, 0x006d6a14, 0x00646514, 0x00626314, 0x00606013, 0x005c5d11, 0x00595a11, 0x00555610, 0x00525310, 0x004d4e0f, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x0006100b, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00081009, 0x00081009, 0x00060e08, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d06, 0x00040c08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00060e08, 0x0009120b, 0x0008110a, 0x0008110b, 0x0009130c, 0x000c140d, 0x00101711, 0x00101711, 0x00101510, 0x00141612, 0x00141812, 0x00151811, 0x00181a12, 0x00181a14, 0x00191a13, 0x001a1a12, 0x001d1c14, 0x001c1c14, 0x001b1c14, 0x001a1b14, 0x001a1b14, 0x001b1c16, 0x001b1c16, 0x001a1b15, 0x001a1b15, 0x00161913, 0x00151a13, 0x00141811, 0x00111610, 0x00101411, 0x00101411, 0x00101411, 0x000f1310, 0x000d120e, 0x000a130c, 0x000a130c, 0x0008110a, 0x0008110a, 0x00061009, 0x00040f08, 0x00051008, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x00081109, 0x0009120a, 0x000a120c, 0x000d130f, 0x0012140f, 0x0015140e, 0x001c160f, 0x0020160c, 0x00261b08, 0x002d1c04, 0x003c2109, 0x00542f06, 0x00734d04, 0x0099710d, 0x00b68f1d, 0x00be981a, 0x00c5a318, 0x00caaa14, 0x00ccb013, 0x00ccb10e, 0x00ccb208, 0x00ccb208, 0x00ccb00b, 0x00caaa12, 0x00ac8208, 0x00805100, 0x00683e04, 0x0058380b, 0x004a3308, 0x00403008, 0x003f2f09, 0x003f2f0a, 0x00402f0a, 0x003e2c08, 0x003c2b07, 0x003b2807, 0x00382508, 0x00382409, 0x0034250c, 0x002b2109, 0x00241e08, 0x00201f09, 0x001c1f0b, 0x00161b08, 0x00111405, 0x000c0f03, 0x000c0e04, 0x000c0e06, 0x000d0f07, 0x000d0f07, 0x000e1109, 0x000f1009, 0x0012120a, 0x00141208, 0x00151306, 0x00171402, 0x00181100, 0x002d210e, 0x0044301c, 0x004f341c, 0x00523418, 0x00503415, 0x004f3210, 0x004f310e, 0x004b2c0b, 0x0048280a, 0x004c2a0d, 0x004b290c, 0x00472507, 0x00482707, 0x004c2a0a, 0x004b2a09, 0x004b2808, 0x004a2808, 0x00492706, 0x00492805, 0x00472605, 0x00462605, 0x00492b09, 0x004d2f0b, 0x0050320c, 0x004d3009, 0x004b2e0b, 0x004d300e, 0x004b2f10, 0x0041280e, 0x00371e0c, 0x00281102, 0x001e0d00, 0x001a1004, 0x00181106, 0x00181108, 0x0016140b, 0x0012140c, 0x0010120a, 0x00101009, 0x000d0f07, 0x000c0e04, 0x000e0d04, 0x00100e06, 0x00121207, 0x00161406, 0x00161406, 0x00181609, 0x00181808, 0x00201705, 0x00251a05, 0x002c2008, 0x002e2408, 0x002f2207, 0x00332308, 0x0036240b, 0x00352108, 0x00332107, 0x00302005, 0x002f2105, 0x002f2105, 0x002d1e04, 0x002c1b03, 0x002f1905, 0x00301808, 0x002e1408, 0x00271809, 0x00231707, 0x00201609, 0x001c1408, 0x00181105, 0x00171106, 0x00171008, 0x00171009, 0x00141008, 0x00131008, 0x00121008, 0x000f0f05, 0x000e0e04, 0x000c0d05, 0x000b0e05, 0x000a0f08, 0x000c120b, 0x000b130b, 0x0009120b, 0x0009130c, 0x0007120c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008120f, 0x0007100d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100c, 0x0005100c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100c, 0x0006100c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x00040f0c, 0x00050f0c, 0x0006100d, 0x0006110d, 0x0006110d, 0x0005100c, 0x0005100c, 0x0007110d, 0x0007110d, 0x00091310, 0x00091310, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009110c, 0x000a120e, 0x000c140e, 0x000d160d, 0x000f150d, 0x0010160e, 0x0010170f, 0x00101710, 0x00121711, 0x00141813, 0x00141813, 0x00141813, 0x00141a14, 0x00151c15, 0x00151c15, 0x00161c15, 0x00171c14, 0x00181c15, 0x00181c15, 0x001a1d17, 0x00181c15, 0x00171c17, 0x00161b15, 0x00151a14, 0x00151a14, 0x00161815, 0x00141813, 0x00131712, 0x00101710, 0x00101510, 0x000e1510, 0x000d1510, 0x000b130f, 0x0009130e, 0x0008120d, 0x0008120d, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0041420d, 0x0045470e, 0x004b4c0f, 0x00505010, 0x00545511, 0x00585911, 0x005d5e12, 0x006d6813, 0x00bd9c18, 0x00cca61a, 0x00cca71a, 0x00cca71a, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca71a, 0x00cca71a, 0x00cca61a, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca61a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cba61a, 0x00c9a41a, 0x00b59818, 0x00887a16, 0x00686814, 0x00686814, 0x00646514, 0x00626313, 0x00606013, 0x005c5d11, 0x00595a11, 0x00555611, 0x00525310, 0x004d4e0f, 0x00494a10, 0x0045470e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070e0c, 0x00070f0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x00081009, 0x00081009, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00050e08, 0x00091009, 0x0009120c, 0x000b130c, 0x000b150e, 0x000c140e, 0x000c140e, 0x00101610, 0x00131813, 0x00161814, 0x00181814, 0x00181814, 0x00191a14, 0x001b1b14, 0x001d1b14, 0x001c1b14, 0x001b1a14, 0x001e1d16, 0x001e1e18, 0x001c1b16, 0x001a1b15, 0x001a1b15, 0x00181c15, 0x00181c15, 0x00171812, 0x00171812, 0x00111711, 0x00111711, 0x00101610, 0x000e140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000d110d, 0x000b110c, 0x0009120a, 0x00081108, 0x00081008, 0x00081009, 0x0006100a, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00071008, 0x00071007, 0x00071007, 0x00081008, 0x0008110a, 0x000a110b, 0x000d130d, 0x0012140f, 0x0015140e, 0x001b150e, 0x001e140b, 0x00241809, 0x002a1a08, 0x00371d09, 0x00442203, 0x00552e00, 0x00683d00, 0x00764a01, 0x00845801, 0x00946806, 0x00aa800b, 0x00b8910f, 0x00c39e12, 0x00c9a510, 0x00cba814, 0x00cca81a, 0x00bd9410, 0x00946800, 0x00784c02, 0x0064400c, 0x00573a0b, 0x004a3408, 0x00433309, 0x00413209, 0x00413209, 0x00413209, 0x00413208, 0x00423007, 0x003d2d06, 0x003b2b06, 0x00392b08, 0x00352808, 0x002d2406, 0x00261f05, 0x00211e07, 0x00201e0a, 0x001e1d0c, 0x00181709, 0x000c1002, 0x000c0f04, 0x000d0f05, 0x000d0f05, 0x000c0e05, 0x000f1008, 0x000d1008, 0x00101008, 0x0016140b, 0x0017140c, 0x0018140b, 0x00191509, 0x00181002, 0x00241807, 0x00382610, 0x00432f14, 0x00442f13, 0x00472f11, 0x00482d0e, 0x004c2c0e, 0x00482809, 0x004c280b, 0x004d2b0c, 0x004b2b0c, 0x004a2a0b, 0x00462707, 0x00472808, 0x00472808, 0x00482809, 0x00482809, 0x00482809, 0x00482c0c, 0x00472c0c, 0x00482c0c, 0x004b2f0e, 0x004b300c, 0x00503414, 0x00493012, 0x0044290f, 0x003b230c, 0x002e1807, 0x00241204, 0x00201004, 0x001c1106, 0x00181105, 0x00171107, 0x00171008, 0x0014130a, 0x00131209, 0x00101007, 0x00101008, 0x000e0f08, 0x000d0f07, 0x000f0f05, 0x00131107, 0x00161409, 0x00181408, 0x00181407, 0x001a1507, 0x001d1707, 0x00261908, 0x002a1b08, 0x0030200a, 0x00403014, 0x003d2c0c, 0x003d2b09, 0x003e2b05, 0x00402a07, 0x00402a0c, 0x00392307, 0x00352006, 0x00321f06, 0x00301e04, 0x002e1c04, 0x002c1a06, 0x002b1908, 0x00271606, 0x00241705, 0x00221604, 0x00201605, 0x001b1302, 0x00181304, 0x00181106, 0x00181109, 0x0017100a, 0x0016100a, 0x00141109, 0x00121008, 0x00100e05, 0x00100f06, 0x000e0f05, 0x000c0f06, 0x000c1007, 0x000c1108, 0x000a1008, 0x000a1008, 0x0009120c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x00060e0b, 0x0008100c, 0x0008120d, 0x0007110c, 0x0005100b, 0x0007100c, 0x0008100c, 0x0005100b, 0x0006100b, 0x0005110b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f0a, 0x0008110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006110c, 0x0008100c, 0x00050d09, 0x00060f0a, 0x000a120e, 0x0009110d, 0x0008100c, 0x0009130e, 0x0005100b, 0x0008120c, 0x0007110a, 0x0009140c, 0x000a140b, 0x000c150c, 0x000d160d, 0x000f150d, 0x0010160e, 0x00101710, 0x00111812, 0x00131812, 0x00141914, 0x00141914, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161c12, 0x00171c14, 0x00171c14, 0x00171c14, 0x00171c14, 0x00171c17, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161b15, 0x00151a14, 0x00141813, 0x00131712, 0x00101510, 0x000f150f, 0x000e140f, 0x000c140e, 0x000a130c, 0x0009120c, 0x0009120c, 0x0008110a, 0x00070f08, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x0007100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0038380c, 0x003b3c0c, 0x0041420d, 0x0047480f, 0x004c4d0f, 0x00505010, 0x00545511, 0x00595a12, 0x005d5e12, 0x00606013, 0x007d7314, 0x00b09418, 0x00b29618, 0x00b39718, 0x00b39818, 0x00b49819, 0x00b49819, 0x00b49819, 0x00b49819, 0x00b49819, 0x00b49819, 0x00b39819, 0x00b39718, 0x00b39618, 0x00b29618, 0x00b29618, 0x00b19518, 0x00b19518, 0x00b19418, 0x00b19317, 0x00b19317, 0x00b19317, 0x00b09317, 0x00b09317, 0x00b19317, 0x00b19317, 0x00b19317, 0x00b19417, 0x00b19518, 0x00b19518, 0x00b19518, 0x00b29618, 0x00b29618, 0x00b19518, 0x00ad9218, 0x009f8a17, 0x00837815, 0x006c6b14, 0x00696914, 0x00686814, 0x00666714, 0x00656614, 0x00626313, 0x00606013, 0x005c5d11, 0x00595a11, 0x00565711, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070e0c, 0x00070f0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f08, 0x00081009, 0x00081009, 0x00081009, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x0008110a, 0x000a1009, 0x0009130c, 0x000b130c, 0x000b150e, 0x000d150f, 0x000d150f, 0x00101610, 0x00141813, 0x00181814, 0x00181814, 0x00181814, 0x00191b14, 0x001b1b14, 0x001c1c14, 0x001c1b14, 0x001c1b14, 0x001e1d16, 0x001d1e18, 0x001b1c16, 0x001a1b15, 0x001a1b15, 0x00181c15, 0x00181c15, 0x00161812, 0x00161812, 0x00111611, 0x00101711, 0x00101610, 0x000d140e, 0x000d130d, 0x000c130d, 0x000c120c, 0x000b100b, 0x0009110a, 0x00081108, 0x00081108, 0x00081008, 0x00081009, 0x0006100b, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100a, 0x00081009, 0x00081008, 0x00081007, 0x0008110a, 0x0009120c, 0x000a120c, 0x000c120c, 0x0011140f, 0x0015140e, 0x001b150c, 0x001c1409, 0x00221708, 0x0028180a, 0x00311a08, 0x00391c01, 0x00442201, 0x00502c05, 0x00583204, 0x005e3700, 0x00684000, 0x00714800, 0x007b5200, 0x00886001, 0x00966d07, 0x00a2780c, 0x00ab8013, 0x00996e09, 0x007d5200, 0x006c4406, 0x005d3d0d, 0x0054390a, 0x004c3609, 0x0048350a, 0x0048360b, 0x0048360b, 0x0048350a, 0x00483509, 0x00463408, 0x00413106, 0x003c2f06, 0x003b2f08, 0x00372c08, 0x00302705, 0x00272003, 0x00241e05, 0x00221d0a, 0x00201c0c, 0x0018180a, 0x000f1104, 0x000d1004, 0x000f1007, 0x000d0f05, 0x000c0e04, 0x000d0f05, 0x000c1005, 0x00101008, 0x00141109, 0x0017130b, 0x0016140c, 0x0018140b, 0x001c140a, 0x001d1407, 0x00241906, 0x00271803, 0x0033210a, 0x00402a13, 0x00432c10, 0x00472c12, 0x00492c10, 0x0049280b, 0x0048280a, 0x0047280c, 0x0046280c, 0x0045270b, 0x0045280c, 0x0047280c, 0x0048290d, 0x0047280c, 0x0047280c, 0x00442a0d, 0x00442a0e, 0x00432a0d, 0x00442b0e, 0x003c2308, 0x003d240c, 0x00381e09, 0x00311705, 0x002b1404, 0x00241003, 0x00201004, 0x00201408, 0x001d1408, 0x001a1508, 0x00181308, 0x00171008, 0x00151109, 0x00131008, 0x00100e05, 0x00110f07, 0x00100f08, 0x000f0e07, 0x00100e05, 0x00131107, 0x00181408, 0x00191408, 0x001b1407, 0x001e1508, 0x00221809, 0x002a1c0c, 0x002d1d0c, 0x00382411, 0x004b3519, 0x0049300e, 0x004e3209, 0x00533706, 0x00563808, 0x0058390a, 0x004f3305, 0x00452b04, 0x003c2406, 0x00362006, 0x00301d06, 0x002c1c07, 0x00291b08, 0x00261808, 0x00241506, 0x00241508, 0x00221608, 0x001c1404, 0x00191204, 0x00181107, 0x00181109, 0x0017100b, 0x0016100b, 0x0014100a, 0x00121008, 0x00110f07, 0x00110f07, 0x000f0f05, 0x000d0f05, 0x000c1007, 0x000b1007, 0x000b1007, 0x000b1008, 0x000a110b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0009110e, 0x0008100c, 0x0008100b, 0x00071009, 0x00061009, 0x00051109, 0x0008100b, 0x0008100c, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x0006100b, 0x00040f09, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0007100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x0007110c, 0x0006120c, 0x0008120c, 0x0007110a, 0x0008130a, 0x00081308, 0x000a130b, 0x000c150c, 0x000f150d, 0x000d140c, 0x000e150e, 0x00111812, 0x00121812, 0x00141813, 0x00141914, 0x00141914, 0x00161b15, 0x00161b14, 0x00161c12, 0x00161c12, 0x00161c12, 0x00171c14, 0x00171c14, 0x00171c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00161b15, 0x00151a14, 0x00141813, 0x00131712, 0x00101510, 0x000f150f, 0x000d140e, 0x000e150f, 0x000b140d, 0x000a130c, 0x0009120c, 0x0009120c, 0x00081009, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x003b3c0c, 0x0041420d, 0x0047480f, 0x004c4d0f, 0x00505010, 0x00555610, 0x00595a12, 0x005d5e12, 0x00606013, 0x00646314, 0x00686614, 0x006c6914, 0x006d6b14, 0x00706d15, 0x00706e15, 0x00716f16, 0x00716f16, 0x00716f16, 0x00716f15, 0x00706e15, 0x006f6c15, 0x006f6d15, 0x006e6c15, 0x006c6b14, 0x006c6a14, 0x006a6814, 0x00686714, 0x00686614, 0x00656414, 0x00656413, 0x00646312, 0x00646313, 0x00646313, 0x00646312, 0x00646313, 0x00656414, 0x00666514, 0x00686714, 0x00696813, 0x006a6814, 0x006c6a14, 0x006c6a14, 0x00706d14, 0x00706d14, 0x006f6d14, 0x006f6d14, 0x006f6d14, 0x006e6c14, 0x006d6c14, 0x006c6914, 0x006a6814, 0x00686713, 0x00656413, 0x00626011, 0x005e5d11, 0x00565711, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0040400d, 0x003b3c0c, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00031008, 0x00041008, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f0a, 0x00070f0a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x00081009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x0009120c, 0x000a120c, 0x000b140d, 0x000c140e, 0x000c1710, 0x000e1610, 0x000f160f, 0x00111610, 0x00151812, 0x00181914, 0x00181a14, 0x00191a14, 0x001a1b14, 0x001c1c15, 0x001c1d16, 0x001c1d15, 0x001c1d15, 0x001c1c15, 0x001b1c16, 0x001a1b15, 0x00181a14, 0x00181a14, 0x00171913, 0x00161913, 0x00141811, 0x00141811, 0x00101510, 0x000f1510, 0x000e150f, 0x000c140d, 0x000b130c, 0x000a130c, 0x000a120c, 0x00081009, 0x00071008, 0x00081008, 0x00081008, 0x00071007, 0x00071009, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100a, 0x00081008, 0x0008110a, 0x0009120c, 0x000a120c, 0x000c110c, 0x0011130e, 0x0015140d, 0x001a140c, 0x001c1308, 0x001f1408, 0x00241608, 0x002a1809, 0x00311a05, 0x00371c04, 0x003b2108, 0x00402408, 0x00482907, 0x004f2e04, 0x00583405, 0x005a3602, 0x005f3900, 0x00633f00, 0x00694400, 0x00704700, 0x00694200, 0x005c3700, 0x00543201, 0x004e3406, 0x004b3204, 0x004b3104, 0x004c3509, 0x004c3508, 0x004a3407, 0x00483306, 0x00493407, 0x00463408, 0x0047370c, 0x0041340c, 0x0040340c, 0x003c310a, 0x00382b08, 0x002c2204, 0x00281f04, 0x0026200c, 0x00221f0c, 0x001b1b0a, 0x00141508, 0x00101104, 0x000d0f04, 0x000c0d04, 0x000c1005, 0x000c1007, 0x000d1008, 0x00101008, 0x00131008, 0x00141008, 0x0014130a, 0x0018140b, 0x001d160b, 0x0021180b, 0x0023180a, 0x00241505, 0x00241302, 0x00281403, 0x00291701, 0x0034210a, 0x003f2811, 0x0040280d, 0x0041270c, 0x0043280e, 0x0045280f, 0x00462810, 0x00462810, 0x0045280f, 0x0044260d, 0x0041240c, 0x003f2309, 0x003c250c, 0x003a2209, 0x00351d04, 0x00351d04, 0x00301802, 0x002c1401, 0x002c1303, 0x002c1408, 0x002a150a, 0x0027160c, 0x00211408, 0x001f1406, 0x001c1708, 0x001b1608, 0x00191408, 0x00171108, 0x0016120a, 0x00141008, 0x00100e05, 0x00110f07, 0x00100f08, 0x00100f08, 0x00110f06, 0x00151108, 0x00191408, 0x001b1408, 0x001c1307, 0x00201507, 0x00251808, 0x002b1d0b, 0x0032220e, 0x003d2910, 0x004c3410, 0x00593b0b, 0x006c480c, 0x007c5810, 0x00896616, 0x00947020, 0x007e5b0f, 0x00583600, 0x004c2e04, 0x0041280c, 0x00342008, 0x002f1d09, 0x002a1c09, 0x0029190b, 0x00241608, 0x00241409, 0x00211408, 0x001c1305, 0x00191105, 0x00181108, 0x0018110b, 0x0017100b, 0x0016100b, 0x0014100a, 0x00141008, 0x00121008, 0x00110f07, 0x000e0e04, 0x000d0f05, 0x000c1007, 0x000c1108, 0x000c1007, 0x000c0f08, 0x000a0f09, 0x0009100a, 0x0008100c, 0x0008100c, 0x0009110c, 0x000a120e, 0x0008110a, 0x0007100a, 0x00061009, 0x00051109, 0x0008100c, 0x0008100c, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x0006100b, 0x00040e09, 0x0005100a, 0x0007110c, 0x0006110c, 0x0005110b, 0x0006120c, 0x0006120c, 0x0006100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100b, 0x00070f0a, 0x0007110c, 0x0003100a, 0x00061009, 0x00051008, 0x00071208, 0x00081308, 0x0009120a, 0x000a120a, 0x000c130b, 0x000c140c, 0x000c130c, 0x00101610, 0x00111711, 0x00111611, 0x00121712, 0x00131812, 0x00141813, 0x00141912, 0x00151a11, 0x00161c12, 0x00161c12, 0x00171c13, 0x00171c14, 0x00181d16, 0x00181d16, 0x00171c15, 0x00171c15, 0x00171c16, 0x00151a14, 0x00141914, 0x00131712, 0x00111611, 0x00101510, 0x000f150f, 0x000e150f, 0x000c140e, 0x000b140d, 0x000a130c, 0x0009120c, 0x00081009, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x003b3c0c, 0x0041420d, 0x0047480f, 0x004c4d0f, 0x00505010, 0x00545511, 0x00595a12, 0x005d5e12, 0x00756c14, 0x00c29f18, 0x00c2a019, 0x00c2a119, 0x00c2a11a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x009e8918, 0x006a6a14, 0x00686814, 0x00686814, 0x00656614, 0x00646514, 0x00636413, 0x00616112, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00626312, 0x00636413, 0x00646414, 0x00646514, 0x00656614, 0x00686814, 0x006b6914, 0x00bc9c18, 0x00c4a119, 0x00c4a119, 0x00c4a119, 0x00c4a119, 0x00c4a119, 0x00c4a019, 0x00c4a019, 0x00c4a019, 0x00c39f18, 0x00c39e18, 0x00c39e18, 0x00aa8c14, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003b3c0c, 0x0036370c, 0x0032330c, 0x002d2f0a, 0x0026280a, 0x0026280c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00031008, 0x00041008, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x0006100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00050f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x00081009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00081009, 0x0009120c, 0x000b130c, 0x000c140d, 0x000c160f, 0x000c1710, 0x000e1610, 0x00111810, 0x00141911, 0x00181b14, 0x001b1c16, 0x001b1c16, 0x001c1c17, 0x001c1d17, 0x001c1e16, 0x001c1e16, 0x001c1e16, 0x001c1c15, 0x001a1b14, 0x001b1a15, 0x001b1a15, 0x00181913, 0x00171812, 0x00151812, 0x00141710, 0x00141710, 0x00131610, 0x0010140f, 0x000f150f, 0x000c140e, 0x000b130c, 0x0009120c, 0x0008120c, 0x0008120c, 0x00071009, 0x00060f08, 0x00081008, 0x00081008, 0x00071007, 0x00070f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100d, 0x0008100c, 0x0008100c, 0x0008100a, 0x0008110a, 0x0009120c, 0x000a120c, 0x000c110c, 0x0011130e, 0x0014140c, 0x0019140b, 0x001c1208, 0x001e1407, 0x0021140a, 0x0026170c, 0x00291808, 0x002e1b08, 0x00331d0a, 0x00371e0a, 0x003c2008, 0x00412406, 0x00492a07, 0x004a2b05, 0x004c2d04, 0x00513105, 0x00543103, 0x00543004, 0x00543005, 0x00503008, 0x004a2f06, 0x00483306, 0x004f3809, 0x005b3d10, 0x005e4012, 0x005b3e10, 0x00573c0d, 0x004e3304, 0x004c3103, 0x00443104, 0x003f3004, 0x003d3004, 0x0040340b, 0x0041340d, 0x003c2f0b, 0x00332708, 0x002c2004, 0x00282008, 0x0024200c, 0x00201f0c, 0x00181909, 0x00101104, 0x000c0e03, 0x000b0c03, 0x000c1005, 0x000c1007, 0x000d1008, 0x00101007, 0x00131008, 0x00151109, 0x00141109, 0x0018140b, 0x001c150b, 0x0020180c, 0x0023190d, 0x0024190e, 0x0028180e, 0x0029190c, 0x00251708, 0x00231704, 0x00281905, 0x002a1801, 0x002c1700, 0x00361c05, 0x003c230c, 0x003e240e, 0x003f250e, 0x003c230c, 0x003b200a, 0x00381f08, 0x00351c05, 0x00301b04, 0x00311b04, 0x002f1902, 0x002d1800, 0x002c1600, 0x002d1804, 0x002c1807, 0x00291406, 0x002b180f, 0x0027180f, 0x00211608, 0x001f1506, 0x001d1707, 0x001a1508, 0x00181308, 0x00181108, 0x0016120a, 0x00141008, 0x00100e05, 0x00110f07, 0x00100f08, 0x00111009, 0x00140f07, 0x00181207, 0x00191408, 0x001b1406, 0x001f1406, 0x00221706, 0x00261808, 0x002d2008, 0x0037280a, 0x0046300c, 0x00583c0c, 0x008a6825, 0x00aa872d, 0x00b9982b, 0x00c6a62c, 0x00c8a62d, 0x00b48b21, 0x00785001, 0x00553400, 0x00462908, 0x0038240c, 0x00311f09, 0x002c1c09, 0x002a1b0a, 0x00261808, 0x00241507, 0x00201404, 0x001b1302, 0x00181204, 0x00181106, 0x0018110b, 0x0017100c, 0x0016100b, 0x00151009, 0x00141008, 0x00121008, 0x00111008, 0x00101007, 0x000f1007, 0x000d1008, 0x000c1108, 0x000c1007, 0x000c0f08, 0x000b0e09, 0x000a0f09, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100c, 0x0008110b, 0x0007110a, 0x00061009, 0x00051109, 0x0008110c, 0x0008100c, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x0006100b, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0005110b, 0x0006120c, 0x0007130c, 0x0006100a, 0x00060e09, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00060e09, 0x0006100b, 0x00030f09, 0x00051008, 0x00051008, 0x00061108, 0x00061106, 0x00081008, 0x00081108, 0x000b110a, 0x000c120b, 0x000c120c, 0x00101610, 0x00101610, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00121710, 0x00141810, 0x00161c12, 0x00161c12, 0x00161c12, 0x00171c13, 0x00181d15, 0x00181d15, 0x00181d15, 0x00171c14, 0x00171c17, 0x00161b15, 0x00151a14, 0x00141813, 0x00131712, 0x00101711, 0x00101610, 0x000f1610, 0x000e1610, 0x000c140d, 0x000a130c, 0x0009120c, 0x00081009, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x003b3c0c, 0x0041420d, 0x0047480f, 0x004c4d0f, 0x00505010, 0x00545511, 0x00585911, 0x005d5e12, 0x00786d14, 0x00cca519, 0x00cca619, 0x00cca71a, 0x00cca71a, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00a48c18, 0x00696914, 0x00686814, 0x00666714, 0x00646514, 0x00636413, 0x00616112, 0x00606013, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00616112, 0x00636413, 0x00646414, 0x00646514, 0x00656614, 0x006b6814, 0x00c4a119, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca61a, 0x00cca619, 0x00cca619, 0x00cca519, 0x00cca418, 0x00cca418, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003b3c0c, 0x0036370b, 0x0034350c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00041008, 0x00041008, 0x00051009, 0x00051009, 0x00051009, 0x00051009, 0x0006100a, 0x0006100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00070f09, 0x00070f09, 0x0008100a, 0x0008100a, 0x00081009, 0x00071008, 0x00071008, 0x00071008, 0x00070f08, 0x00070f08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00070f08, 0x0008110b, 0x0009130c, 0x000c140d, 0x000c150e, 0x000c1710, 0x000c180f, 0x00101912, 0x00131a12, 0x00161b14, 0x00181c15, 0x001c1c17, 0x001d1c17, 0x001d1d17, 0x001d1d16, 0x001d1d16, 0x001d1d16, 0x001d1d16, 0x001c1c15, 0x001a1a13, 0x001b1a15, 0x001b1a15, 0x00181813, 0x00151811, 0x00141711, 0x00131611, 0x00111510, 0x0010140f, 0x000f150f, 0x000d140e, 0x000b130c, 0x000a120c, 0x0008110b, 0x0008110b, 0x0008110a, 0x00071009, 0x00060f08, 0x0006100a, 0x0007100a, 0x0006100a, 0x0006100a, 0x0005100a, 0x00051009, 0x00040f08, 0x00040f08, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0007100b, 0x0007100c, 0x0007100b, 0x0007100b, 0x0007100a, 0x0008110b, 0x000a120c, 0x000c110b, 0x0010130c, 0x0013140b, 0x0017140a, 0x00191408, 0x001b1408, 0x0020150c, 0x0023160c, 0x0026180c, 0x002a190b, 0x002d1a0a, 0x00301b09, 0x00341c07, 0x00371e04, 0x003d2207, 0x00402308, 0x0044270b, 0x00472b0c, 0x00482c0b, 0x00482c0b, 0x00482e0c, 0x004b320e, 0x004d3410, 0x0052370f, 0x00644612, 0x006e4c0c, 0x006b4805, 0x006c480c, 0x00644308, 0x005f3f08, 0x00543404, 0x00443000, 0x003c2c00, 0x00392b00, 0x003c2e07, 0x00433611, 0x003f300d, 0x00382a09, 0x002f2303, 0x00292005, 0x0025210a, 0x0024220e, 0x001c1c0a, 0x00121404, 0x000c0f02, 0x000b0d04, 0x000c0f05, 0x000b0f06, 0x000c1008, 0x00101008, 0x0013100a, 0x0016110b, 0x0014110a, 0x0018140c, 0x001c140b, 0x0020180c, 0x00231a0f, 0x00241a0e, 0x00281c0f, 0x002b1d0f, 0x002b1c0c, 0x002d1f0c, 0x002c1e0a, 0x002c1d07, 0x002f1a04, 0x00301701, 0x00321903, 0x00321a04, 0x00341c05, 0x00341b05, 0x00301803, 0x00331c06, 0x00341d07, 0x00301905, 0x00321b07, 0x00341c08, 0x00331b06, 0x00301b04, 0x00301b07, 0x002c1807, 0x002c1808, 0x002c190e, 0x0028180e, 0x00241709, 0x00201607, 0x001e1607, 0x001b1407, 0x00191308, 0x00181008, 0x00141008, 0x00141008, 0x00121008, 0x00121008, 0x00111008, 0x00121008, 0x00141007, 0x00181207, 0x001a1407, 0x001b1204, 0x00201704, 0x00241a07, 0x00281c08, 0x00322309, 0x003d2b09, 0x0050360a, 0x00715114, 0x00b7983a, 0x00c9ae30, 0x00ccb321, 0x00ccb41b, 0x00ccb11b, 0x00c3a01f, 0x00876002, 0x005c3500, 0x004e2f0b, 0x003e280b, 0x0035220b, 0x002c1c06, 0x002a1b09, 0x00251705, 0x00241604, 0x00201404, 0x001b1202, 0x00191104, 0x00181106, 0x00181109, 0x0017100a, 0x00151009, 0x00141008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00101008, 0x000f1008, 0x000d1008, 0x000c0d07, 0x000c0e08, 0x000c0f08, 0x000a100a, 0x0008100b, 0x0007100b, 0x0006100b, 0x0007100c, 0x0008100a, 0x00081009, 0x00071009, 0x00061009, 0x0007100b, 0x0007100b, 0x0006100b, 0x0007100c, 0x0007100b, 0x00060f0a, 0x0007100b, 0x0007100b, 0x0007100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0007110c, 0x0006100c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100b, 0x0007110c, 0x0007120c, 0x0005100a, 0x00060f0a, 0x0006100b, 0x0006100b, 0x0006100b, 0x00050f0a, 0x00040d08, 0x0005100a, 0x0005100a, 0x0006100a, 0x0006100a, 0x0007110a, 0x00071109, 0x00071008, 0x00071008, 0x0008120b, 0x000a120b, 0x000a120c, 0x000e150f, 0x000f1610, 0x00101610, 0x00101610, 0x00111410, 0x00111410, 0x00121510, 0x00121510, 0x00141812, 0x00151a14, 0x00151a14, 0x00151b14, 0x00181c14, 0x00191d15, 0x00191c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00171b15, 0x00161913, 0x00141812, 0x00131711, 0x00121610, 0x00101610, 0x000f160f, 0x000d140e, 0x000c140d, 0x000b130c, 0x0008110b, 0x0009110c, 0x0009110c, 0x0008110b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008110c, 0x0008110c, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0007100b, 0x0007100b, 0x0007100c, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x004b4c0f, 0x00505010, 0x00545511, 0x00585910, 0x005c5d12, 0x00786c14, 0x00cca518, 0x00c8a418, 0x008b7c16, 0x00897c16, 0x00897c17, 0x00887c16, 0x00887c16, 0x00887c16, 0x00887c17, 0x00867b16, 0x00b19618, 0x00cca71a, 0x00a48c17, 0x00686814, 0x00666714, 0x00646514, 0x00636413, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005c5d11, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00616112, 0x00636413, 0x00646414, 0x00656614, 0x006a6814, 0x00c4a019, 0x00cca71a, 0x00958316, 0x00887c15, 0x00887a16, 0x00867915, 0x00857816, 0x00847714, 0x00827514, 0x00807414, 0x00998315, 0x00c9a218, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x00292b0b, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x00071007, 0x00071007, 0x00071007, 0x00071008, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x0009120c, 0x000a140c, 0x000c140e, 0x000c1710, 0x000c1710, 0x000d180f, 0x00131b12, 0x00131a13, 0x00171c15, 0x00191c16, 0x001c1b16, 0x001c1c17, 0x001e1c16, 0x001e1d16, 0x001e1d16, 0x001d1d16, 0x001d1d16, 0x001c1c14, 0x001b1912, 0x001b1a15, 0x001b1a15, 0x00171813, 0x00141810, 0x00101610, 0x00101610, 0x000f1610, 0x000c140e, 0x000c140e, 0x000b130c, 0x0009120b, 0x0008100a, 0x00080f09, 0x00080f09, 0x00071008, 0x00070f08, 0x00060f09, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00061009, 0x00040f08, 0x00040f07, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x00061009, 0x0009120b, 0x000b130c, 0x000b1109, 0x000e1109, 0x00101208, 0x00131208, 0x00151308, 0x00181408, 0x001e150c, 0x001f1409, 0x0024180b, 0x0027180b, 0x002a180a, 0x002c1909, 0x00301c09, 0x00301c06, 0x00371f08, 0x003b200a, 0x003d2309, 0x003e260b, 0x003f280c, 0x0040290d, 0x00432c0c, 0x0048340e, 0x00503612, 0x00624115, 0x008d6d2c, 0x00a4842c, 0x00a07e1d, 0x008f6a13, 0x00815d08, 0x00745004, 0x00654204, 0x00573d03, 0x00483404, 0x003d2c01, 0x00342603, 0x003c300d, 0x003f3010, 0x00392b09, 0x00342604, 0x002b2105, 0x00282108, 0x0027230c, 0x00201e0a, 0x00151605, 0x000c1002, 0x000b0e04, 0x000c0f06, 0x000a0f06, 0x000c1007, 0x000f0f08, 0x0014100b, 0x0018120c, 0x0014110b, 0x0018140c, 0x001a130a, 0x001e170c, 0x0022190e, 0x00241a0d, 0x00281c0c, 0x002c1e0d, 0x002c1c0a, 0x002e1d0c, 0x00301f0c, 0x0032200a, 0x00331f08, 0x00372008, 0x0038210a, 0x0039230c, 0x003c260e, 0x003c260f, 0x0038240c, 0x003a230d, 0x0038220c, 0x0038200b, 0x0038200c, 0x0039200c, 0x00341a07, 0x00341c08, 0x00311b07, 0x002c1706, 0x00291808, 0x002a180c, 0x0028170b, 0x00251709, 0x00221508, 0x001f1407, 0x001c1407, 0x001a1308, 0x00181008, 0x00140e08, 0x00131008, 0x00131008, 0x00121008, 0x00131008, 0x00121008, 0x00151108, 0x00181308, 0x001b1407, 0x001d1606, 0x00221c08, 0x00241c06, 0x00281e06, 0x0035260c, 0x00442f0c, 0x00583c0c, 0x007c5a15, 0x00bfa034, 0x00cbb424, 0x00ccb713, 0x00cab810, 0x00cab714, 0x00c4ab1b, 0x00906a01, 0x00643c00, 0x00503208, 0x00422d08, 0x0039260a, 0x00301f04, 0x002b1c08, 0x00271805, 0x00241605, 0x00201406, 0x001c1104, 0x001a1105, 0x00181108, 0x00181009, 0x00171009, 0x00141109, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00111108, 0x000e1008, 0x000e0f08, 0x000f100a, 0x000f100a, 0x000c1009, 0x000a100a, 0x0007100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0009100a, 0x00081009, 0x00081009, 0x00071009, 0x0006100a, 0x0006100b, 0x0007100b, 0x0008100c, 0x0007100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100b, 0x0007110c, 0x0007110c, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x00061009, 0x00061009, 0x00061108, 0x00081109, 0x000c140d, 0x000c140e, 0x000c140e, 0x000f140f, 0x0010140f, 0x0010140f, 0x00121511, 0x00121611, 0x00131712, 0x00151a14, 0x00151a14, 0x00151a14, 0x00181a14, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181c15, 0x00181c15, 0x00181c15, 0x00171913, 0x00171812, 0x00161812, 0x00141811, 0x0012160f, 0x0010140e, 0x000d140e, 0x000d140e, 0x000c140d, 0x0008120c, 0x0009120c, 0x0009120c, 0x0008110a, 0x0008100b, 0x0008100d, 0x0008100d, 0x0007110d, 0x0006110d, 0x0008120d, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x0041420d, 0x0045470e, 0x004b4c0f, 0x004f5010, 0x00545510, 0x00585811, 0x005c5c12, 0x00776c14, 0x00cca518, 0x00c6a219, 0x006b6814, 0x006a6a14, 0x006b6b14, 0x006c6c15, 0x006c6c15, 0x006d6d15, 0x006c6c15, 0x006a6a14, 0x00a99018, 0x00cca71a, 0x00a38b18, 0x00666714, 0x00656614, 0x00636414, 0x00616112, 0x00606013, 0x005d5e12, 0x005c5d11, 0x005c5c11, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x00606013, 0x00616112, 0x00636413, 0x00646414, 0x00686614, 0x00c4a019, 0x00cca61a, 0x007c7315, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00646414, 0x00626313, 0x00887814, 0x00c8a218, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00050f08, 0x00050f08, 0x00050f08, 0x00051008, 0x00051008, 0x00051008, 0x00050f09, 0x00050f0a, 0x00040f0a, 0x0004100a, 0x0004100a, 0x0004100a, 0x00050f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081008, 0x00071007, 0x00071007, 0x00071008, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00071009, 0x0008110a, 0x000a130c, 0x000c140e, 0x000e150f, 0x000f1610, 0x000f1610, 0x00111911, 0x00141b13, 0x00141b12, 0x00181c14, 0x001b1d16, 0x001c1c16, 0x001d1c16, 0x001e1c16, 0x001e1d16, 0x001d1d16, 0x001c1e16, 0x001c1d16, 0x001a1b14, 0x00181912, 0x00191914, 0x00191a14, 0x00151812, 0x00111610, 0x000f1610, 0x000f150f, 0x000d150f, 0x000c140d, 0x0008120c, 0x0008120b, 0x00071009, 0x00071008, 0x00060f08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060f09, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00061009, 0x00040f08, 0x00040f07, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100a, 0x000a130c, 0x000c140d, 0x000c110a, 0x000d1008, 0x000f1007, 0x00111006, 0x00131107, 0x00161307, 0x001b1208, 0x001c1307, 0x00211609, 0x00231608, 0x00251708, 0x0028180a, 0x002c1c0a, 0x002e1e08, 0x00311c06, 0x00341d07, 0x00361f08, 0x00382209, 0x003b250c, 0x003d270c, 0x00432c0d, 0x0048330b, 0x00543b0e, 0x00705118, 0x00b0923d, 0x00caae3d, 0x00c8ac2b, 0x00c4a528, 0x00b8981f, 0x00ac881a, 0x0094700f, 0x006d4e00, 0x00543901, 0x00443004, 0x00382806, 0x00342504, 0x003c2e0d, 0x003b2c0b, 0x00362807, 0x002d2203, 0x002a2006, 0x002a230b, 0x00242009, 0x00181806, 0x000d1002, 0x000c0f04, 0x000b0f06, 0x000a0f07, 0x000c1008, 0x000e0e07, 0x00141009, 0x0018110c, 0x0014110b, 0x0018130c, 0x00191209, 0x001c150b, 0x0021180c, 0x0024180c, 0x00281c0c, 0x002b1e0d, 0x002d1c0b, 0x002e1d0c, 0x002e1d0a, 0x002e1d06, 0x00321c06, 0x00382008, 0x0039210b, 0x00382008, 0x003a230b, 0x003d250c, 0x00392108, 0x003c240c, 0x003c240c, 0x003a220b, 0x0039200a, 0x003a210a, 0x00381e09, 0x00341c08, 0x00321b07, 0x002e1908, 0x002a1707, 0x00281508, 0x00271509, 0x00251609, 0x00221407, 0x00201406, 0x001c1406, 0x001a1208, 0x00171008, 0x00140f08, 0x00131008, 0x00131008, 0x00121008, 0x00131008, 0x00131008, 0x00171108, 0x001a1408, 0x001c1408, 0x00221a0a, 0x0028200d, 0x00271e08, 0x00281e06, 0x0038280d, 0x0048320d, 0x005c3e0d, 0x00836018, 0x00c3a236, 0x00ccb421, 0x00cbb710, 0x00cab80c, 0x00cab80f, 0x00c7ae18, 0x00987303, 0x00684000, 0x00543707, 0x00443006, 0x003b2608, 0x00342304, 0x002d1c05, 0x002b1c08, 0x00241806, 0x00201406, 0x001c1104, 0x001a1105, 0x00181108, 0x00181009, 0x00181009, 0x00141008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00141008, 0x0014130a, 0x000e0f08, 0x000f1008, 0x0010100b, 0x0010100b, 0x000c0f08, 0x000b1009, 0x0007100a, 0x0006100a, 0x0006100a, 0x0008110c, 0x0009100a, 0x00081009, 0x00080f09, 0x00061009, 0x0006100a, 0x0006100b, 0x0007100b, 0x0008100b, 0x0006100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0006100b, 0x0006100b, 0x00050f0a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x00061009, 0x00061009, 0x00061008, 0x00071008, 0x000a120c, 0x000b140d, 0x000c140e, 0x000c140e, 0x000f140f, 0x0010150f, 0x00101610, 0x00101610, 0x00121712, 0x00141914, 0x00151a14, 0x00151a14, 0x00181a14, 0x00181c15, 0x00191c16, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181a14, 0x00171813, 0x00171813, 0x00151811, 0x0012160f, 0x0010140e, 0x000e140f, 0x000e140f, 0x000c140e, 0x0009130c, 0x0009120c, 0x0009120c, 0x0008110a, 0x0008100b, 0x0008100d, 0x0008100d, 0x0007100d, 0x0006110d, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002d2f0b, 0x0030310c, 0x0036370c, 0x003b3c0d, 0x0040400d, 0x0045470e, 0x00494a0f, 0x004f5010, 0x00535410, 0x00585811, 0x005c5c12, 0x00776c14, 0x00cca518, 0x00c6a118, 0x006a6714, 0x00696914, 0x006a6a14, 0x006b6b14, 0x006c6c15, 0x006c6c15, 0x006c6c14, 0x00686814, 0x00a99017, 0x00cca71a, 0x00a38b17, 0x00646514, 0x00646414, 0x00616113, 0x00606013, 0x005d5e12, 0x005c5c11, 0x005b5b12, 0x00595a12, 0x00585911, 0x00585911, 0x00585911, 0x00585911, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00616112, 0x00636413, 0x00686514, 0x00c3a018, 0x00cca619, 0x007c7114, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00646514, 0x00646414, 0x00616112, 0x00887814, 0x00c8a217, 0x00b09015, 0x00525311, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e06, 0x00060e06, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00070f0a, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081008, 0x00081008, 0x00081008, 0x00081008, 0x00081009, 0x00081009, 0x00081009, 0x0008110a, 0x0009120b, 0x000a130c, 0x000c140d, 0x000d140e, 0x00101510, 0x00111610, 0x00121812, 0x00141a13, 0x00151a13, 0x00171a11, 0x00191c14, 0x001d1f17, 0x001e1c15, 0x001d1c15, 0x001e1d16, 0x001d1d17, 0x001c1d17, 0x001b1e16, 0x001b1e15, 0x00181c14, 0x00171810, 0x00161812, 0x00151812, 0x00111610, 0x0010160e, 0x000c150f, 0x000c140d, 0x000b140d, 0x0008110b, 0x0007110a, 0x0007110a, 0x00061009, 0x00061009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060f09, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00061009, 0x00040f08, 0x00040f07, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110c, 0x0009110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007100a, 0x0009110b, 0x000a120c, 0x000b1109, 0x000c1006, 0x000e0f05, 0x00121107, 0x00131107, 0x00151307, 0x00191208, 0x001b1307, 0x001f1508, 0x001e1404, 0x00201408, 0x0024180b, 0x00271908, 0x002b1c08, 0x002f1c07, 0x00311e08, 0x00321f08, 0x0034210b, 0x003a250e, 0x003c260c, 0x00432d0c, 0x004a350b, 0x00583e0a, 0x00795c13, 0x00bba038, 0x00ccb42a, 0x00ccb818, 0x00ccb612, 0x00c8b111, 0x00cbb01b, 0x00c4a41e, 0x0099750e, 0x00674700, 0x004c3400, 0x003d2c05, 0x00342504, 0x00302100, 0x003c2d0c, 0x003a2c0a, 0x00302403, 0x002e2406, 0x002c2309, 0x00272008, 0x001e1b07, 0x00101406, 0x000d1007, 0x000a0f06, 0x000a0f08, 0x000c1008, 0x000d0f07, 0x00100f08, 0x0016100b, 0x0014100b, 0x00161109, 0x001a120a, 0x001c140a, 0x0020170c, 0x0021170a, 0x00261b0b, 0x00291c0b, 0x002e1d0c, 0x002f1e0c, 0x002e1d0b, 0x00301f08, 0x00342009, 0x003a230c, 0x003b230c, 0x003a230a, 0x003c240c, 0x003e250c, 0x003c230a, 0x003d2409, 0x003f250b, 0x003a2109, 0x00381f07, 0x00381f06, 0x00371d05, 0x00341c05, 0x00301a06, 0x002f1a08, 0x002c1909, 0x00281608, 0x00261508, 0x00241608, 0x00211406, 0x001f1306, 0x001b1305, 0x00181108, 0x00170f07, 0x00151008, 0x00131008, 0x00131008, 0x00121008, 0x00121008, 0x00141109, 0x00181309, 0x001c1408, 0x001c1608, 0x00241c0a, 0x002f2711, 0x00291f08, 0x002a1d05, 0x0039290c, 0x0048330a, 0x005d400b, 0x00836017, 0x00c0a030, 0x00ccb420, 0x00cbb80e, 0x00cab80b, 0x00cab80c, 0x00cab215, 0x00a17d05, 0x006e4700, 0x00563804, 0x00483104, 0x003c2704, 0x00372402, 0x002f1d04, 0x002c1c08, 0x00261808, 0x00211406, 0x001d1204, 0x001a1105, 0x00181108, 0x00181009, 0x00161008, 0x00141008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00141008, 0x00141109, 0x00100f08, 0x000f1008, 0x000f100a, 0x000f100a, 0x000d1009, 0x00090f08, 0x00060f08, 0x00070f08, 0x00061009, 0x0008120c, 0x000a100a, 0x00080f08, 0x00070f08, 0x00061008, 0x00051009, 0x0005100a, 0x0006100a, 0x0007100b, 0x0006100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040f09, 0x00040f09, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00040e09, 0x00040f08, 0x00051008, 0x00051008, 0x00071008, 0x0008110b, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c130d, 0x000d140e, 0x00101610, 0x00101610, 0x00111611, 0x00131712, 0x00141814, 0x00141814, 0x00171913, 0x00171913, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181b14, 0x00181a14, 0x00181913, 0x00151811, 0x00121610, 0x0010150e, 0x00101610, 0x00101610, 0x000d150f, 0x000a140d, 0x000a130c, 0x000a130c, 0x0008110b, 0x0008100a, 0x0008100d, 0x0008100d, 0x0006100c, 0x0005100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0006100b, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x0024250b, 0x00292b0b, 0x002d2f0b, 0x0030310c, 0x0036370c, 0x003b3c0d, 0x0040400e, 0x0045470e, 0x00494a10, 0x004d4e0f, 0x00525310, 0x00565711, 0x005b5b12, 0x00766a13, 0x00cca418, 0x00c6a118, 0x00696614, 0x00686814, 0x00696914, 0x006a6a14, 0x006a6a14, 0x006a6a14, 0x006a6a14, 0x00686814, 0x00a99017, 0x00cca61a, 0x00a28a16, 0x00636414, 0x00626313, 0x00606013, 0x005d5e12, 0x005c5c11, 0x00595a12, 0x00585911, 0x00585810, 0x00565710, 0x00565710, 0x00565710, 0x00565710, 0x00585810, 0x00585911, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00616112, 0x00656314, 0x00c3a018, 0x00cca619, 0x007a7014, 0x00656613, 0x00656613, 0x00656614, 0x00656614, 0x00646514, 0x00626313, 0x00606012, 0x00887814, 0x00c8a217, 0x00b09015, 0x00515110, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e06, 0x00060e06, 0x00060e08, 0x00040f08, 0x00040f08, 0x00030f08, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00080f0a, 0x0008100b, 0x0008100b, 0x00060e0a, 0x00040d08, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x0008100a, 0x000c140e, 0x000d140e, 0x000f140f, 0x0010150f, 0x00111610, 0x00131812, 0x00151813, 0x00171913, 0x00161b14, 0x00181b13, 0x001c1c15, 0x001f1e16, 0x001e1c15, 0x001e1c15, 0x001e1d16, 0x001c1d17, 0x001c1d17, 0x00191e16, 0x00181d15, 0x00161c13, 0x00141811, 0x00111610, 0x00101610, 0x000e170e, 0x000c170e, 0x000a140d, 0x0009140c, 0x0008110b, 0x00061009, 0x00061009, 0x0007110a, 0x00061009, 0x00061009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060f09, 0x0006100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00061009, 0x00050f08, 0x00050f08, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0007100a, 0x0008100a, 0x0009110a, 0x000b1008, 0x000b0f06, 0x000d1006, 0x00111108, 0x00121107, 0x00141207, 0x00181207, 0x00191306, 0x001b1306, 0x001b1104, 0x001d1308, 0x00201508, 0x00231808, 0x00261907, 0x00281806, 0x002c1b06, 0x002f1d06, 0x00332009, 0x0038250c, 0x003b270b, 0x0044300c, 0x004d380b, 0x005d440c, 0x00836618, 0x00baa12e, 0x00ccb720, 0x00cbba09, 0x00cbbb05, 0x00cbbb07, 0x00ccb80c, 0x00ccb518, 0x00b79618, 0x00755400, 0x00543a00, 0x00443203, 0x00382a04, 0x002c1c00, 0x00392b0a, 0x003d300c, 0x00372b08, 0x00312807, 0x002f2608, 0x00282006, 0x0024200b, 0x00171608, 0x00101106, 0x000c0f06, 0x000a0f08, 0x000c1007, 0x000d1007, 0x00100f08, 0x00141009, 0x0014110b, 0x00161109, 0x00191209, 0x001c140a, 0x001f150a, 0x00201608, 0x00251909, 0x00281a0b, 0x002c1c0c, 0x002f1d0c, 0x002e1d0b, 0x0032200a, 0x0038240c, 0x003a220c, 0x003a220c, 0x003b230b, 0x003d240c, 0x003e250c, 0x003e250b, 0x003d2309, 0x003d2309, 0x00392008, 0x00371e06, 0x00381f08, 0x00371e08, 0x00341b06, 0x00301805, 0x002d1806, 0x002e1b09, 0x002b180a, 0x00261607, 0x00251608, 0x00211406, 0x00201406, 0x001c1306, 0x00191108, 0x00170f08, 0x00151008, 0x00141008, 0x00131008, 0x00121008, 0x00121008, 0x00141008, 0x0019140a, 0x001e170a, 0x001f1807, 0x0028200c, 0x00352c14, 0x00291e05, 0x002b1d03, 0x0039290a, 0x00483309, 0x005c3f0b, 0x00805d13, 0x00bc9c2c, 0x00cab41d, 0x00cbb80c, 0x00cab908, 0x00cab80a, 0x00cab314, 0x00a88408, 0x00754e00, 0x00573a00, 0x00483303, 0x003e2804, 0x00372401, 0x00301e03, 0x002c1c08, 0x00261808, 0x00221608, 0x001e1407, 0x001a1105, 0x00171208, 0x00161008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00140f08, 0x00110f06, 0x00100f08, 0x000f1008, 0x000f100a, 0x000f1009, 0x000f120b, 0x00080d06, 0x00080f08, 0x00070f08, 0x00071009, 0x0008120b, 0x0008110a, 0x00080f08, 0x00060f08, 0x00061008, 0x00051009, 0x0006100a, 0x0006100a, 0x0008100c, 0x0009120d, 0x0009110c, 0x0009110c, 0x0009110c, 0x0009110c, 0x0009110c, 0x0009110c, 0x0008100b, 0x0008100b, 0x0005100c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0007100c, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040d08, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00040f08, 0x00051008, 0x00051007, 0x00061008, 0x0008100a, 0x0009120c, 0x0009120c, 0x000a130c, 0x000c130d, 0x000c130d, 0x000e150f, 0x00101610, 0x00101510, 0x00121712, 0x00141812, 0x00141812, 0x00161913, 0x00171913, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181b14, 0x00171a14, 0x00141812, 0x00131710, 0x00111610, 0x00101610, 0x00101610, 0x000e150f, 0x000c140e, 0x000b140d, 0x000a130c, 0x0009120b, 0x00081009, 0x0008100c, 0x0008100c, 0x0006100c, 0x0005100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x0040400d, 0x0044450e, 0x00494a10, 0x004d4e0f, 0x00515110, 0x00555610, 0x00595a11, 0x00756a13, 0x00cca418, 0x00c6a118, 0x00686514, 0x00666714, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00656614, 0x00a88f17, 0x00cca619, 0x00a28917, 0x00616113, 0x00606013, 0x005e5f13, 0x005c5c11, 0x00595a12, 0x00585810, 0x00585810, 0x00555610, 0x00545511, 0x00545511, 0x00545511, 0x00545511, 0x00555611, 0x00565710, 0x00585911, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00646113, 0x00c3a018, 0x00cca519, 0x007a7014, 0x00646514, 0x00656614, 0x00646514, 0x00646514, 0x00636414, 0x00626312, 0x00606013, 0x00887714, 0x00c8a117, 0x00b09015, 0x00515110, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040e07, 0x00020e07, 0x00020e07, 0x00020e08, 0x00020e08, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081009, 0x00081009, 0x0008110a, 0x0008110a, 0x000c130d, 0x000f150f, 0x0010140f, 0x00111510, 0x00141810, 0x00151912, 0x00181813, 0x00181913, 0x00181c13, 0x001a1d14, 0x001d1c15, 0x00201c14, 0x001f1c14, 0x001f1c14, 0x001e1c17, 0x001c1c17, 0x001a1d17, 0x00171b14, 0x00151812, 0x00141912, 0x00121911, 0x00101811, 0x000e1610, 0x000c160f, 0x0008150d, 0x0009140c, 0x0008120b, 0x00051008, 0x00051008, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00081009, 0x00081009, 0x00081009, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0006100b, 0x0007100c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0009100b, 0x000a100a, 0x000a1009, 0x00091007, 0x00091006, 0x000b1007, 0x000e1108, 0x00101108, 0x00121006, 0x00151005, 0x00161006, 0x00181105, 0x001a1307, 0x001c1408, 0x001c1408, 0x00201608, 0x00241809, 0x00261809, 0x00291b08, 0x002c1d07, 0x00312006, 0x00382508, 0x003c2809, 0x0046300b, 0x00503a0a, 0x005f460c, 0x00846819, 0x00bda432, 0x00ccb81e, 0x00ccbc09, 0x00cbbc09, 0x00cbbc0a, 0x00caba0c, 0x00cbb910, 0x00b79c0f, 0x00795800, 0x00573c00, 0x00453400, 0x00392c02, 0x002e2000, 0x00382908, 0x003f330d, 0x003b3009, 0x00352c08, 0x00302808, 0x002c2409, 0x00271e08, 0x001f1705, 0x00141104, 0x000d0f07, 0x000b1008, 0x000c1007, 0x000d1007, 0x00101008, 0x00101008, 0x0014110b, 0x00161109, 0x00181108, 0x001b1308, 0x001e1409, 0x00201608, 0x00231809, 0x0028180a, 0x002b1a0a, 0x002e1c0c, 0x00311e0c, 0x00321f09, 0x00341d07, 0x00372008, 0x0039210a, 0x003a220c, 0x003c250e, 0x003e240c, 0x003f250d, 0x003c240a, 0x003c2309, 0x00382008, 0x0038200a, 0x00371f0c, 0x00361e0e, 0x00371c0c, 0x00331a08, 0x00301a08, 0x002e1b08, 0x002c1a08, 0x00281706, 0x00261808, 0x00231507, 0x00201407, 0x001d1407, 0x001b1108, 0x00181008, 0x00171009, 0x00141109, 0x00141109, 0x00131008, 0x00121009, 0x00141008, 0x001a150b, 0x001e1809, 0x00201806, 0x002b210c, 0x00382d14, 0x00281c02, 0x002f2004, 0x003a2808, 0x0048330a, 0x005a3c09, 0x007e5b13, 0x00bc9c2c, 0x00c9b21c, 0x00cbb80c, 0x00cab908, 0x00cab808, 0x00cbb314, 0x00ae880b, 0x00775100, 0x00583b00, 0x004a3401, 0x003f2a04, 0x00382401, 0x00301f04, 0x002d1c08, 0x00271807, 0x00241506, 0x00201307, 0x00181105, 0x00171208, 0x00171109, 0x00141008, 0x00141009, 0x00151109, 0x00151109, 0x00151109, 0x00151109, 0x00141008, 0x00131008, 0x00101009, 0x00101009, 0x00100f08, 0x00100f08, 0x000f1009, 0x000a0f06, 0x000a0f08, 0x00091008, 0x00081008, 0x00071208, 0x0008110a, 0x00061008, 0x00061009, 0x00051109, 0x0008100b, 0x0008100c, 0x0006100a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0009100c, 0x0007110c, 0x0005100a, 0x0007110c, 0x0007110c, 0x0006100b, 0x0008120d, 0x0005100a, 0x0005100a, 0x0005100b, 0x0006100b, 0x0005100b, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00040f09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051008, 0x00051008, 0x00040e06, 0x00050e07, 0x00070f08, 0x0008110a, 0x0008110a, 0x0008110b, 0x000a120c, 0x000c140e, 0x000c140e, 0x000d150f, 0x000f140f, 0x00101610, 0x00121710, 0x00131810, 0x00131712, 0x00151a14, 0x00161b15, 0x00161b15, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181c17, 0x00151a14, 0x00151a14, 0x00141814, 0x00131712, 0x00131712, 0x00101510, 0x00101510, 0x00101510, 0x000d150f, 0x000a120c, 0x0008110b, 0x0008110a, 0x00081009, 0x0008100a, 0x0007110a, 0x00051109, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008110c, 0x0008110c, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003e400c, 0x0044450e, 0x0048490f, 0x004c4d10, 0x00515110, 0x00555611, 0x00585911, 0x00746913, 0x00cca418, 0x00c6a118, 0x00666414, 0x00646514, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00646514, 0x00a88e16, 0x00cca519, 0x00a18816, 0x00606012, 0x005e5f13, 0x005c5d11, 0x005b5b12, 0x00585910, 0x00565710, 0x00555611, 0x00535410, 0x00525310, 0x00525310, 0x00525310, 0x00535410, 0x00545510, 0x00555611, 0x00565710, 0x00585911, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00636013, 0x00c39f18, 0x00cca518, 0x00786e14, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00626313, 0x00616112, 0x00606013, 0x00887614, 0x00c8a117, 0x00b09015, 0x00505010, 0x00515110, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040e07, 0x00020e07, 0x00020e07, 0x00020e08, 0x00020e08, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081009, 0x00081009, 0x0008110a, 0x0009110a, 0x000c130d, 0x00101610, 0x00111610, 0x00121712, 0x00141812, 0x00161913, 0x00181913, 0x00181a14, 0x001a1c14, 0x001c1e16, 0x001e1d16, 0x00201c14, 0x00201c14, 0x001f1c14, 0x001d1c16, 0x001a1c16, 0x00191c16, 0x00181b14, 0x00151812, 0x00131811, 0x00111810, 0x00101711, 0x000e1610, 0x0009140c, 0x0008140d, 0x0009140c, 0x0007110a, 0x00040f08, 0x00040e07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00081009, 0x00081009, 0x00081008, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0006100b, 0x0006100b, 0x00040e09, 0x0007110c, 0x000a140f, 0x0008120d, 0x0007110c, 0x0007110c, 0x0009100b, 0x000a100a, 0x000a1009, 0x00091008, 0x00091006, 0x000a0f06, 0x000d1007, 0x00101108, 0x00121006, 0x00141007, 0x00151008, 0x00151006, 0x00181207, 0x00191409, 0x001a140a, 0x001f1509, 0x0022170a, 0x0025180b, 0x00281c0a, 0x002c1d08, 0x00302008, 0x00352508, 0x003b2908, 0x0044310a, 0x00503a09, 0x0062470c, 0x00886b1a, 0x00c0a835, 0x00ccb820, 0x00ccbb0c, 0x00cbbc09, 0x00cabb0b, 0x00caba0d, 0x00cbb910, 0x00b6980b, 0x007c5900, 0x005c3e00, 0x004a3802, 0x003d3004, 0x00322400, 0x003a2c0a, 0x00413410, 0x003f340a, 0x003b3008, 0x00352b0a, 0x0031250a, 0x002c230b, 0x00211a07, 0x00181404, 0x000f0f05, 0x000c1007, 0x000c1005, 0x000e1208, 0x00101108, 0x00101008, 0x0014110b, 0x00161009, 0x00181108, 0x001b1308, 0x001e1409, 0x001f1406, 0x00221608, 0x00281809, 0x002b190a, 0x002e1c0c, 0x00301d0c, 0x00321f09, 0x00341d08, 0x00371f08, 0x0039210a, 0x003a220c, 0x003c240d, 0x003e240c, 0x003e240d, 0x003c230b, 0x003c230a, 0x003a230a, 0x00382108, 0x00371f0b, 0x00371f0c, 0x00371c0c, 0x00331a08, 0x00301a08, 0x002f1a08, 0x002c1a08, 0x00281706, 0x00261807, 0x00231607, 0x00201407, 0x001d1407, 0x001b1108, 0x00181008, 0x00171009, 0x00141109, 0x00141109, 0x00131008, 0x00131009, 0x00141109, 0x001c170d, 0x001f1809, 0x00201805, 0x00302610, 0x00382c14, 0x002b1d01, 0x00332205, 0x003c2a08, 0x0048340b, 0x005a3d0d, 0x007b5812, 0x00b7972b, 0x00c9b21e, 0x00ccb80c, 0x00cab908, 0x00cbb808, 0x00cbb516, 0x00b08b0c, 0x00785000, 0x005a3b00, 0x004c3501, 0x00412c04, 0x00382401, 0x00301f04, 0x002d1c07, 0x00281806, 0x00241506, 0x00201305, 0x00181105, 0x00171208, 0x00171109, 0x00151008, 0x00141009, 0x00151109, 0x00151109, 0x00151109, 0x00151109, 0x00141008, 0x00131008, 0x00111009, 0x00101009, 0x00100f08, 0x00100f08, 0x000f1009, 0x000c0f05, 0x000a0f06, 0x00091008, 0x000a1008, 0x00081108, 0x0008110a, 0x00061008, 0x00061009, 0x00051109, 0x0008100b, 0x0008100b, 0x0006100a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0007110c, 0x0005100a, 0x0007110c, 0x0007110c, 0x0006100b, 0x0008120d, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040f09, 0x0006100b, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00040f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051008, 0x00051008, 0x00040e06, 0x00050e07, 0x00070f08, 0x0008110a, 0x0008110a, 0x0008110a, 0x0009120c, 0x000c140e, 0x000c140d, 0x000c140e, 0x000d140e, 0x00101610, 0x0010170f, 0x00111810, 0x00131712, 0x00131712, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161b14, 0x00181c15, 0x00181d16, 0x00181c17, 0x00151a14, 0x00151a14, 0x00141814, 0x00131712, 0x00131712, 0x00101510, 0x00101510, 0x00101510, 0x000c140e, 0x0009120b, 0x0008110a, 0x0008110a, 0x0009120c, 0x0009120c, 0x0008130c, 0x00051109, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008110c, 0x0008110c, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250c, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003e400c, 0x0043440e, 0x0048490e, 0x004c4d0f, 0x00505010, 0x00545511, 0x00585810, 0x00746813, 0x00cca418, 0x00c6a018, 0x00656313, 0x00646414, 0x00646514, 0x00666713, 0x00656613, 0x00666713, 0x00666714, 0x00636414, 0x00a88e16, 0x00cca519, 0x00a18815, 0x005e5f13, 0x005c5d11, 0x005b5b12, 0x00585911, 0x00585810, 0x00555611, 0x00535410, 0x00525310, 0x00515110, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00545510, 0x00555611, 0x00565710, 0x00585911, 0x005b5b12, 0x005c5d11, 0x00626013, 0x00c39e18, 0x00cca518, 0x00786e14, 0x00636414, 0x00636414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x00887614, 0x00c8a117, 0x00b09015, 0x00505010, 0x00515110, 0x004d4e0f, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e06, 0x00060e06, 0x00070d08, 0x00050e08, 0x00040f08, 0x00031008, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008110a, 0x0008110a, 0x0009120c, 0x0009120c, 0x000d140e, 0x00101610, 0x00111611, 0x00121712, 0x00171912, 0x00171913, 0x00181a14, 0x001b1c16, 0x001c1e16, 0x001c1e16, 0x001f1c16, 0x00201c14, 0x00201c14, 0x00201c14, 0x001c1b14, 0x00191b16, 0x00181a15, 0x00151811, 0x0012160f, 0x0010150e, 0x0010160e, 0x000f150f, 0x000b140d, 0x0009140c, 0x0008140c, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x0008100a, 0x00070f0a, 0x00060f0a, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008110a, 0x00081009, 0x00070f08, 0x0008100b, 0x0008100b, 0x00060e09, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008120d, 0x0008120d, 0x0007110c, 0x0007100a, 0x00081009, 0x00091008, 0x000a0f08, 0x000a0f08, 0x000b1008, 0x00090e05, 0x000a0f06, 0x000c0f04, 0x000f1007, 0x00101005, 0x00141008, 0x00141008, 0x00141006, 0x00171008, 0x0019140b, 0x0019140b, 0x001c1308, 0x00201508, 0x00231809, 0x00271b0b, 0x002b1c08, 0x00302008, 0x00342408, 0x003c2a08, 0x00443109, 0x0051390b, 0x0063470c, 0x00896c18, 0x00c0a835, 0x00ccb721, 0x00cbba0d, 0x00cbba08, 0x00cab90a, 0x00cbb90d, 0x00ccb811, 0x00b6950b, 0x007d5700, 0x00603e00, 0x004b3702, 0x00403006, 0x00342502, 0x003c2e0b, 0x00443610, 0x0040340a, 0x003e3208, 0x00382c08, 0x00342709, 0x0030240a, 0x00271e08, 0x001a1505, 0x00100e04, 0x000c0e06, 0x000c1005, 0x000e1208, 0x00101208, 0x00121108, 0x00131008, 0x00141008, 0x00170f07, 0x00181108, 0x001e1409, 0x001f1406, 0x00211507, 0x00271809, 0x002b1a0b, 0x002e1b0a, 0x00301c0b, 0x00331e09, 0x0037200a, 0x00382009, 0x0039210a, 0x0039220a, 0x003b240b, 0x003c230b, 0x003f260d, 0x003c220a, 0x00392006, 0x00392207, 0x00372005, 0x00372008, 0x00361e09, 0x00361c0a, 0x00331a08, 0x00301a08, 0x002f1a08, 0x002d1a08, 0x00281808, 0x00261807, 0x00241607, 0x00231709, 0x001f1408, 0x001a1108, 0x00181008, 0x00170f08, 0x00151109, 0x00151109, 0x00141008, 0x0015100b, 0x0016130b, 0x001c170d, 0x001e180a, 0x00221a06, 0x00342811, 0x003c2e14, 0x002e1f03, 0x00342206, 0x003c2b08, 0x0048340b, 0x005a3e0d, 0x00785712, 0x00b49529, 0x00ccb220, 0x00ccb80f, 0x00cab809, 0x00cab808, 0x00cbb416, 0x00b18a0c, 0x007b5000, 0x005d3b00, 0x004e3403, 0x00432c04, 0x00382401, 0x00311f04, 0x002d1d05, 0x00291a06, 0x00261808, 0x00201406, 0x00181204, 0x00171208, 0x00171109, 0x00161109, 0x00141209, 0x0014130a, 0x0014120a, 0x00141109, 0x00141109, 0x00141008, 0x00141008, 0x00121009, 0x00101009, 0x00110f08, 0x00111009, 0x00101009, 0x000d0f05, 0x000c1006, 0x000a0f06, 0x000a1008, 0x00081108, 0x00081009, 0x00061009, 0x0007110a, 0x00061009, 0x0007100a, 0x0007100b, 0x0006100a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0008120d, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007110c, 0x0006100b, 0x0006100b, 0x00051008, 0x00051008, 0x00061008, 0x00071008, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x0008100a, 0x000a130c, 0x000a130c, 0x000c140e, 0x000d140e, 0x00101610, 0x00101610, 0x00111810, 0x00131712, 0x00131712, 0x00141914, 0x00141914, 0x00151a13, 0x00151a13, 0x00171c15, 0x00171c15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00141914, 0x00141814, 0x00121711, 0x00101510, 0x00101510, 0x000d150f, 0x000d150f, 0x000b130c, 0x0009120c, 0x00081009, 0x00081009, 0x0008120b, 0x00051109, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250c, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x00535410, 0x00565710, 0x00736812, 0x00cca418, 0x00c6a018, 0x00646212, 0x00626313, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00616114, 0x00a88d16, 0x00cca518, 0x00a08716, 0x005d5e12, 0x005c5c11, 0x00595a11, 0x00585810, 0x00555611, 0x00535410, 0x00525310, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00545510, 0x00555610, 0x00585810, 0x00595a12, 0x005c5c11, 0x00615f12, 0x00c39e17, 0x00cca418, 0x00786c14, 0x00616112, 0x00616112, 0x00626312, 0x00616112, 0x00606013, 0x00606013, 0x005e5f12, 0x00877514, 0x00c8a117, 0x00b09014, 0x00505010, 0x00515110, 0x004d4e0f, 0x00494a10, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e06, 0x00060e07, 0x00070d08, 0x00060e08, 0x00040f08, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008110b, 0x0009120c, 0x0009120c, 0x0009120c, 0x000d140e, 0x00101610, 0x00131712, 0x00141813, 0x00171913, 0x00171913, 0x001a1b15, 0x001c1c17, 0x001c1e16, 0x001c1e16, 0x001f1c16, 0x001f1c14, 0x00201c14, 0x001f1c14, 0x001c1b14, 0x001a1b14, 0x00181a14, 0x00151811, 0x0012160f, 0x0010150e, 0x000f150f, 0x000b130e, 0x000a120e, 0x0009130e, 0x0008140d, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060f09, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008110a, 0x00081009, 0x00070f08, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110d, 0x0006100b, 0x0006100b, 0x0009130d, 0x0006100b, 0x0006100b, 0x0008110c, 0x0008100b, 0x00081009, 0x000a0f08, 0x000a0f08, 0x000a0f08, 0x000b1008, 0x00090e05, 0x000b0e05, 0x000c0f06, 0x000f1007, 0x00101007, 0x00131008, 0x00131008, 0x00141006, 0x00151108, 0x00171309, 0x00171309, 0x00191308, 0x001d1509, 0x00201808, 0x00241b0a, 0x00291c08, 0x002e2008, 0x00342508, 0x003c2a09, 0x0045320a, 0x0051390b, 0x0064480b, 0x00896c16, 0x00c0a834, 0x00ccb721, 0x00cbb90e, 0x00cbba0a, 0x00cab909, 0x00cbb90d, 0x00ccb810, 0x00b5950b, 0x007e5800, 0x00603f00, 0x004d3703, 0x00403005, 0x00342601, 0x003e300c, 0x00473913, 0x0043360c, 0x00403309, 0x003c2e09, 0x00362808, 0x00312709, 0x00292008, 0x001c1705, 0x00111002, 0x000d0f05, 0x000c1005, 0x000f1308, 0x00101208, 0x00121108, 0x00131008, 0x00161109, 0x00181008, 0x00181108, 0x001c1408, 0x001e1407, 0x00201507, 0x00251709, 0x002b1a0c, 0x002d1a0a, 0x002f1c09, 0x00321d08, 0x0037200b, 0x003a220c, 0x003b240c, 0x003b240c, 0x003b230a, 0x003c230b, 0x00392008, 0x003c220a, 0x00392007, 0x00392104, 0x00382004, 0x00381f08, 0x00381e09, 0x00371c08, 0x00331a08, 0x00301a08, 0x002f1a08, 0x002d1a08, 0x00281808, 0x00271708, 0x00241608, 0x00221708, 0x001f1408, 0x001a1108, 0x00181008, 0x00161008, 0x00151109, 0x00151109, 0x00141008, 0x0016110c, 0x0016130b, 0x001d180e, 0x001d1709, 0x00221a06, 0x00342910, 0x003c2f14, 0x002f2004, 0x00342206, 0x003c2c0a, 0x0049350c, 0x005c3f0f, 0x00785712, 0x00b4942a, 0x00ccb320, 0x00ccb70e, 0x00ccb80a, 0x00ccb809, 0x00cbb415, 0x00b18a0c, 0x007b5000, 0x005e3c00, 0x004f3404, 0x00442c05, 0x00382501, 0x00312004, 0x002d1d05, 0x00291a06, 0x00261808, 0x00201504, 0x00191104, 0x00171307, 0x00161209, 0x00151109, 0x00141109, 0x0014130a, 0x0014120a, 0x00141109, 0x00141109, 0x00141008, 0x00141008, 0x00121009, 0x00101009, 0x00110f08, 0x00121009, 0x00101009, 0x000f0f06, 0x000c0f05, 0x000c1007, 0x000b1008, 0x00081108, 0x00081009, 0x00061009, 0x0007110a, 0x0006100a, 0x0007100a, 0x0007100b, 0x0007100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0007110c, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008110c, 0x0007110c, 0x0006100b, 0x00061009, 0x00061009, 0x00061009, 0x00061008, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00081009, 0x0009120c, 0x0008110a, 0x000a130c, 0x000c140d, 0x000d150f, 0x000e1710, 0x00101810, 0x00111711, 0x00121711, 0x00141914, 0x00141914, 0x00151a14, 0x00151a13, 0x00171c15, 0x00171c15, 0x00161b14, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00151a14, 0x00131712, 0x00101510, 0x00101510, 0x000d150f, 0x000d150f, 0x000b130c, 0x0009120c, 0x0008100a, 0x0008100b, 0x0008120c, 0x0005110b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f1612, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003e400d, 0x0041420e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x00525310, 0x00565711, 0x00736812, 0x00cca417, 0x00c6a018, 0x00646113, 0x00616112, 0x00626313, 0x00646414, 0x00646414, 0x00646414, 0x00636414, 0x00606013, 0x00a78c16, 0x00cca418, 0x00a08715, 0x005c5d11, 0x005b5b12, 0x00585910, 0x00565711, 0x00545510, 0x00525310, 0x00515110, 0x004f5010, 0x004f5010, 0x004d4e0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545511, 0x00565711, 0x00585810, 0x00595a12, 0x00605d11, 0x00c39e17, 0x00cca418, 0x00776c14, 0x00616112, 0x00606012, 0x00616112, 0x00606013, 0x00606013, 0x005e5f13, 0x005c5d11, 0x00877514, 0x00c8a117, 0x00b09014, 0x004f5010, 0x00505010, 0x004d4e10, 0x0048490f, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e0b, 0x00050e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00041007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x0009120c, 0x000a130c, 0x000c120c, 0x000d140d, 0x000f150d, 0x00101710, 0x00141811, 0x00151a13, 0x00181c15, 0x00181c15, 0x001b1c14, 0x001e1d14, 0x00201e15, 0x00201e15, 0x001f1c14, 0x001e1d14, 0x001e1d14, 0x001c1c14, 0x00191812, 0x00181810, 0x00171812, 0x00141611, 0x0011140f, 0x0010140f, 0x000b130e, 0x000a1410, 0x000a1410, 0x0008120f, 0x0007100c, 0x00051009, 0x00040f08, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051008, 0x00061009, 0x00061009, 0x00061009, 0x00061009, 0x0008110b, 0x00081009, 0x00081009, 0x0006100b, 0x0007110c, 0x0007110c, 0x0008100a, 0x00081008, 0x000a0f08, 0x000a0f08, 0x000a0f07, 0x000a0f06, 0x000c0f06, 0x000c0d08, 0x000c0d08, 0x000c0f08, 0x000c0f08, 0x000f1008, 0x000f1007, 0x00111008, 0x00141208, 0x00161409, 0x00161409, 0x00171308, 0x001a1508, 0x001f180a, 0x00241b0a, 0x00271c07, 0x002e1f08, 0x0034240a, 0x003b2b0a, 0x0045330b, 0x00513b0c, 0x0064480b, 0x00886b14, 0x00c0a730, 0x00cbb620, 0x00cbba0c, 0x00cbba0a, 0x00cbba0a, 0x00cbb90c, 0x00ccb810, 0x00b2930a, 0x00805a00, 0x00604000, 0x004c3803, 0x00403006, 0x00342701, 0x003e300b, 0x00483913, 0x0046370e, 0x0043340c, 0x003f300c, 0x00322503, 0x00342a0a, 0x002d250b, 0x00201c06, 0x00111000, 0x000d1004, 0x000c1005, 0x000f1308, 0x00101208, 0x00111008, 0x00131008, 0x00161108, 0x00181009, 0x00191209, 0x001c1208, 0x001e1407, 0x00211509, 0x00241609, 0x00241607, 0x002b190a, 0x002f1b0a, 0x00321d0a, 0x00371f0b, 0x003a200b, 0x003d240c, 0x003c230b, 0x003c230b, 0x0040240e, 0x003d220b, 0x003c210a, 0x003c2208, 0x003b2007, 0x003c2009, 0x003b1f09, 0x003a1e0a, 0x00381f08, 0x00341c08, 0x00311a06, 0x002f1a08, 0x002d190a, 0x002a180b, 0x00261509, 0x00231409, 0x00201408, 0x001d1508, 0x001a1308, 0x00181108, 0x0018120b, 0x0018110a, 0x00140e07, 0x00161009, 0x0016120a, 0x0018140b, 0x001c170c, 0x001c1408, 0x00241b07, 0x00362c10, 0x003f3214, 0x002f2004, 0x00342208, 0x003c2b0a, 0x0049350d, 0x005c400f, 0x00785614, 0x00b4942a, 0x00ccb321, 0x00ccb60d, 0x00ccb80a, 0x00ccb809, 0x00cbb414, 0x00ab8305, 0x007b5000, 0x005f3c00, 0x004f3404, 0x00452c08, 0x00382600, 0x00312004, 0x002d1d05, 0x00291a06, 0x00251908, 0x001e1506, 0x00191306, 0x00181207, 0x00171208, 0x00141209, 0x00141109, 0x00141109, 0x00141109, 0x00131008, 0x00131008, 0x00140f09, 0x00121009, 0x00121009, 0x00120f0b, 0x00120f0b, 0x00120f0b, 0x00110f08, 0x00121108, 0x00141008, 0x000f1007, 0x000c1108, 0x00091008, 0x00081009, 0x00081009, 0x0009110c, 0x0008110c, 0x0007100b, 0x0008100b, 0x0008100c, 0x0008100d, 0x00070e0c, 0x0008100c, 0x0008100d, 0x0008100d, 0x0008100d, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00060f0b, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0007110d, 0x0006100c, 0x00050f0c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110b, 0x0005110b, 0x00030f09, 0x00030f09, 0x0004100a, 0x0005100b, 0x00040f09, 0x0004100a, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008100b, 0x000a120e, 0x0009110d, 0x000c140f, 0x000f150f, 0x00101610, 0x00101811, 0x00101811, 0x00101812, 0x00121a14, 0x00141814, 0x00151a14, 0x00171c17, 0x00171c15, 0x00181e15, 0x00181f16, 0x00171e15, 0x00161d14, 0x00171c14, 0x00171913, 0x00141813, 0x00141614, 0x00131714, 0x000e1811, 0x000e1811, 0x000a140d, 0x0009140d, 0x00091310, 0x0008120e, 0x0008120f, 0x0008120f, 0x0008100b, 0x0008100b, 0x0008100b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280b, 0x00292b0a, 0x002d2f0c, 0x0032330c, 0x00393b0c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x00525310, 0x00555611, 0x00726612, 0x00cca417, 0x00c6a017, 0x00636013, 0x00606013, 0x00616112, 0x00626313, 0x00636413, 0x00636413, 0x00626313, 0x00606012, 0x00a78c15, 0x00cca418, 0x00a08615, 0x005b5b12, 0x00595a12, 0x00585810, 0x00555611, 0x00535410, 0x00515110, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004c4d0e, 0x004d4e0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00525310, 0x00545510, 0x00565711, 0x00585910, 0x00595a12, 0x00605c12, 0x00c39e17, 0x00cca418, 0x00766c14, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005e5f12, 0x005c5d11, 0x00867414, 0x00c8a116, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d0f, 0x00484910, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00060d0b, 0x00060d0b, 0x00060e0a, 0x00050f08, 0x00040f08, 0x00040f08, 0x00041007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x0009120c, 0x000c130d, 0x000e140e, 0x000f150f, 0x0010170f, 0x00121911, 0x00141912, 0x00161b14, 0x00181c15, 0x00181c15, 0x001c1d15, 0x001e1d14, 0x00201e15, 0x00201e15, 0x001e1d14, 0x001d1e14, 0x001c1c14, 0x001a1b14, 0x00181913, 0x00171812, 0x00161812, 0x00131610, 0x0010140e, 0x000e150f, 0x000a120e, 0x0008120f, 0x0008120f, 0x0007100d, 0x0006100c, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051009, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100c, 0x0008100b, 0x0008100b, 0x0006100b, 0x0007110d, 0x0007110c, 0x0008100a, 0x00091008, 0x000a0f08, 0x000a0f08, 0x000a0f07, 0x000a0f06, 0x000c0f06, 0x000c0e06, 0x000c0e06, 0x000c1007, 0x000c1007, 0x000f1008, 0x000f1007, 0x00111108, 0x00141208, 0x00141308, 0x00141308, 0x00151208, 0x00191408, 0x001d1809, 0x00221a09, 0x00271c07, 0x002e1e08, 0x0035250b, 0x003b2c0b, 0x0045340c, 0x00523b0c, 0x0064480b, 0x00886a15, 0x00c0a730, 0x00cbb61f, 0x00cbba0b, 0x00cbba0a, 0x00cbba0a, 0x00cbba0c, 0x00ccb910, 0x00af9008, 0x007c5800, 0x00604100, 0x004c3903, 0x003e2f04, 0x00342701, 0x003e300b, 0x00483912, 0x0047380f, 0x0044350e, 0x0040300c, 0x00322602, 0x00352b0b, 0x0031280d, 0x00231e08, 0x00121101, 0x00101005, 0x000c1005, 0x000e1208, 0x00101208, 0x00111008, 0x00131008, 0x00171208, 0x0018100a, 0x00191209, 0x001b1108, 0x001d1205, 0x00211408, 0x00241508, 0x00251608, 0x002a1909, 0x002e1909, 0x00301c08, 0x00351c09, 0x00381d08, 0x00392009, 0x003c220a, 0x003e250c, 0x0040240e, 0x003d220b, 0x003c210a, 0x003c2208, 0x003c210a, 0x003b2008, 0x003b1f09, 0x003a1e0a, 0x00381f08, 0x00341c08, 0x00301a06, 0x002f1a08, 0x002c1909, 0x00281609, 0x00261509, 0x00241409, 0x00201408, 0x001c1407, 0x00191208, 0x00181108, 0x00171009, 0x00161009, 0x00161009, 0x00161009, 0x0018130c, 0x0019160c, 0x001c160d, 0x001f180b, 0x00271f0a, 0x00382e10, 0x00423414, 0x00312204, 0x00342206, 0x003c2b0a, 0x0049350c, 0x005c4010, 0x00785614, 0x00b4942b, 0x00ccb322, 0x00cbb50d, 0x00ccb90c, 0x00ccb80a, 0x00cbb414, 0x00aa8305, 0x007b5000, 0x00603c00, 0x004e3404, 0x00462d08, 0x00392701, 0x00332104, 0x002d1d04, 0x00291a06, 0x00251908, 0x001e1506, 0x001b1407, 0x00181207, 0x00171208, 0x00141309, 0x00141009, 0x00131008, 0x00131008, 0x00121008, 0x00121008, 0x00140f09, 0x00121009, 0x00121009, 0x00120f0b, 0x00120f0b, 0x00120f0b, 0x00121008, 0x00141209, 0x00141108, 0x00101008, 0x000a0d05, 0x000a1109, 0x0008110a, 0x00081009, 0x000a130c, 0x0009130c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x00060e09, 0x0008100b, 0x0009110d, 0x0008100c, 0x0008100c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0007100d, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x0007100b, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0004100a, 0x00040f09, 0x0004100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0008100b, 0x0009110d, 0x0008100c, 0x0009110d, 0x000c130d, 0x000d140e, 0x000d150f, 0x000e1710, 0x000f1811, 0x00101812, 0x00141815, 0x00141914, 0x00161b15, 0x00161b14, 0x00171d14, 0x00171e14, 0x00171e14, 0x00161d14, 0x00171c13, 0x00171912, 0x00141812, 0x00141612, 0x00131714, 0x000e1811, 0x000e1811, 0x000a140d, 0x0009130d, 0x00091310, 0x0008120e, 0x0008120f, 0x0008120f, 0x0008100b, 0x0008100b, 0x0008100b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x00494a10, 0x004d4e0f, 0x00515110, 0x00545510, 0x00726612, 0x00cca417, 0x00c6a016, 0x00615f12, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x005e5f13, 0x00a78b15, 0x00cca418, 0x00a08614, 0x00595a12, 0x00585910, 0x00565711, 0x00545510, 0x00525310, 0x00515110, 0x004f5010, 0x004d4e0f, 0x004c4d0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545511, 0x00565710, 0x00585911, 0x005e5c12, 0x00c39e17, 0x00cca418, 0x00766b14, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005c5c11, 0x00867414, 0x00c8a116, 0x00b09014, 0x004f5010, 0x00505010, 0x004c4d0f, 0x0048490f, 0x0044450e, 0x0040400d, 0x003b3c0c, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0020230a, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00041007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00060e09, 0x0008100b, 0x00060e09, 0x00050d09, 0x00070f0a, 0x0008100c, 0x000a120e, 0x000a120d, 0x000c140d, 0x000d140f, 0x00101610, 0x0010160f, 0x00101710, 0x00111810, 0x00151a13, 0x00171c15, 0x00191c16, 0x001b1d18, 0x001c1e16, 0x001e1d14, 0x001f1c14, 0x001e1d14, 0x001d1e16, 0x001b1c15, 0x00181c13, 0x00181b12, 0x00141810, 0x00131610, 0x00131612, 0x00101411, 0x000c140f, 0x000c140f, 0x0008110c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110e, 0x0009110e, 0x0008100c, 0x0007100d, 0x0006100d, 0x0007110c, 0x0008100a, 0x000a0f07, 0x000b0f06, 0x000c0f06, 0x000c0f06, 0x000c0f06, 0x000c0f06, 0x000c0e06, 0x000c0e06, 0x000c1007, 0x000c1007, 0x000f1008, 0x000f1007, 0x00101008, 0x00131107, 0x00141208, 0x0014130a, 0x00151108, 0x00191408, 0x001e1809, 0x00221a09, 0x00271c07, 0x002d1f08, 0x0034240a, 0x003b2d0b, 0x0044340c, 0x00523b0c, 0x0066480c, 0x00876814, 0x00c2a732, 0x00ccb61f, 0x00ccb90c, 0x00ccb90a, 0x00ccb90c, 0x00ccb90c, 0x00ccb810, 0x00af9009, 0x007c5800, 0x00604200, 0x004c3903, 0x003f3005, 0x00352801, 0x0042340d, 0x00483811, 0x0044350c, 0x0043340c, 0x0040310d, 0x00342805, 0x00322809, 0x00342a10, 0x0027210c, 0x00191707, 0x00101105, 0x000d0f05, 0x000d1107, 0x00101208, 0x00131209, 0x00121006, 0x00161108, 0x0018100a, 0x0019110b, 0x001b1108, 0x001d1205, 0x00221609, 0x00241609, 0x00251608, 0x00281808, 0x002e1a0a, 0x00311b08, 0x00341b07, 0x00381d09, 0x0039200a, 0x003a2108, 0x003b2209, 0x003e230d, 0x003c2109, 0x00391e07, 0x003c2007, 0x00391e06, 0x00391e06, 0x00381c07, 0x00381c08, 0x00371d07, 0x00341c06, 0x00311b07, 0x002f1907, 0x002c1808, 0x00281408, 0x00241408, 0x00221207, 0x001f1307, 0x001c1306, 0x00181108, 0x00181108, 0x0018110a, 0x00181009, 0x00170f08, 0x00170f08, 0x0018120b, 0x001a150c, 0x001c140c, 0x0021180c, 0x0029200b, 0x00382f0e, 0x00443815, 0x00322402, 0x00352304, 0x003c2c09, 0x00483409, 0x005b3f0f, 0x00785514, 0x00b4922b, 0x00ccb122, 0x00cbb40e, 0x00ccb80b, 0x00ccb80a, 0x00cbb214, 0x00ab8205, 0x007a4e00, 0x00603b00, 0x004e3104, 0x00472d0b, 0x00392602, 0x00322104, 0x002d1d04, 0x00291a06, 0x00251908, 0x001e1506, 0x001b1407, 0x00181207, 0x00171208, 0x00141309, 0x00131109, 0x00121108, 0x00111108, 0x00101008, 0x00111008, 0x00121009, 0x00121009, 0x00121009, 0x00120f0b, 0x00120d0a, 0x00120d0a, 0x00130f08, 0x00141109, 0x00151208, 0x00101008, 0x000c0e06, 0x000c1009, 0x000b130c, 0x0008110b, 0x0008110b, 0x000c140e, 0x0008110b, 0x0008110a, 0x0008110b, 0x0009120b, 0x0009120c, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110b, 0x0007110c, 0x0006100b, 0x0006100b, 0x0008120c, 0x0009120c, 0x00081009, 0x00081009, 0x00081009, 0x00061009, 0x00061009, 0x00061009, 0x00061009, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00060f0a, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x0006100c, 0x0007130d, 0x0007130d, 0x0006120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0005110b, 0x0005110b, 0x0006100b, 0x0006100b, 0x00050d09, 0x0008100c, 0x0009110c, 0x000a120e, 0x000c120e, 0x000d1410, 0x000c140e, 0x000c140e, 0x000d150f, 0x000f1811, 0x00141815, 0x00141914, 0x00151a14, 0x00161b14, 0x00171d14, 0x00171e14, 0x00171e14, 0x00161c13, 0x00171c11, 0x00181b11, 0x00161811, 0x00141711, 0x00131712, 0x000e1811, 0x000e1811, 0x000b150e, 0x000a140e, 0x000a1410, 0x00091310, 0x0008120f, 0x0008120f, 0x0008100c, 0x0008100c, 0x0008100c, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0c, 0x0040400d, 0x0044450d, 0x0048490f, 0x004c4d10, 0x00505010, 0x00545510, 0x00716512, 0x00cca417, 0x00c6a016, 0x00605d11, 0x005e5f13, 0x00606013, 0x00606013, 0x00606012, 0x00606012, 0x00606013, 0x005d5e13, 0x00a78b15, 0x00cca418, 0x00a08614, 0x00595a12, 0x00585810, 0x00555610, 0x00535410, 0x00525310, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004c4d0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00525310, 0x00545510, 0x00565710, 0x00595a11, 0x005e5c13, 0x00c39e17, 0x00cca418, 0x00756a13, 0x005e5f13, 0x00606013, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005c5d11, 0x005b5b11, 0x00867414, 0x00c8a116, 0x00b09014, 0x004d4e10, 0x004f5010, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0036370c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00050e08, 0x00040f08, 0x00040f08, 0x00041007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00060e09, 0x0008100b, 0x00060e09, 0x00070f0a, 0x0009110c, 0x0009110c, 0x0009110e, 0x000c140e, 0x000c140e, 0x000f1610, 0x00101710, 0x00101711, 0x00111810, 0x00131a12, 0x00161b14, 0x00171c15, 0x001a1c17, 0x001c1e18, 0x001c1e16, 0x001e1d14, 0x001e1d14, 0x001d1e14, 0x001b1c14, 0x00181c13, 0x00181a13, 0x00171913, 0x00141611, 0x00131410, 0x00101410, 0x000e1410, 0x000b130f, 0x000a130e, 0x0006100b, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x00040f09, 0x00040e08, 0x00051009, 0x00051009, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x000b1310, 0x000b1310, 0x000b1310, 0x00091310, 0x0008120f, 0x0007110c, 0x0009100a, 0x000a0f08, 0x000b0f07, 0x000c0f06, 0x000c0f06, 0x000c0f05, 0x000c0f04, 0x000c0e04, 0x000c0f04, 0x000c1005, 0x000c1005, 0x000f1008, 0x000f1007, 0x00101008, 0x00131107, 0x00131308, 0x0014130a, 0x00141208, 0x00181408, 0x001e1809, 0x00221a09, 0x00271c07, 0x002d1f08, 0x00342509, 0x003c2d0c, 0x0044340c, 0x00523b0c, 0x0068480c, 0x00876813, 0x00c2a732, 0x00ccb61e, 0x00ccb90c, 0x00ccb90a, 0x00ccb90c, 0x00cbbb0c, 0x00ccb910, 0x00af9009, 0x007d5800, 0x00604400, 0x004c3a04, 0x00413208, 0x00382b04, 0x0044370f, 0x0047380f, 0x0044340b, 0x0042340c, 0x00413410, 0x00342806, 0x002e2304, 0x00342a11, 0x002b2510, 0x00191605, 0x00111104, 0x000e1006, 0x000d1007, 0x00101208, 0x00111208, 0x00121006, 0x00161108, 0x0018100a, 0x0019110a, 0x001b1108, 0x001d1205, 0x00221609, 0x00241608, 0x00251608, 0x00281808, 0x002d1a09, 0x00301a08, 0x00331a06, 0x00351c08, 0x00381f09, 0x00381f08, 0x00392008, 0x003c210b, 0x003b2008, 0x003c2008, 0x003a1f06, 0x00371c04, 0x00381c05, 0x00371c06, 0x00371b08, 0x00371c08, 0x00341c06, 0x00321b07, 0x002f1907, 0x002c1809, 0x00281408, 0x00241408, 0x00221207, 0x001f1306, 0x001b1305, 0x00181107, 0x00181108, 0x0018110a, 0x00181009, 0x00170f08, 0x00170f08, 0x0018120b, 0x001a150c, 0x001c140c, 0x0021180c, 0x0029200a, 0x00382f0c, 0x00443813, 0x00342502, 0x00352401, 0x003e2d09, 0x0048340a, 0x005c3f0e, 0x00785514, 0x00b3932b, 0x00ccb222, 0x00cab40e, 0x00ccb80c, 0x00ccb80a, 0x00cbb214, 0x00ab8205, 0x007a4f00, 0x00603b00, 0x004d3003, 0x00472d0b, 0x003a2802, 0x00322104, 0x002d1d04, 0x00291a06, 0x00251908, 0x001e1506, 0x001b1407, 0x00181207, 0x00171208, 0x00141309, 0x00131109, 0x00121108, 0x00111108, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00121009, 0x00120f0b, 0x00140f0b, 0x00130e0a, 0x00140f08, 0x0015110a, 0x00151208, 0x00111008, 0x000d0f07, 0x00080e06, 0x000a120c, 0x000c140e, 0x000d140f, 0x00101711, 0x000d150e, 0x000e150e, 0x000c140c, 0x000a110a, 0x00091109, 0x00091008, 0x00091008, 0x00091008, 0x00081109, 0x0007110a, 0x00061009, 0x00061009, 0x0008130c, 0x0009120c, 0x00081009, 0x00081009, 0x00081008, 0x00061008, 0x00061108, 0x00061009, 0x0006100a, 0x0008110a, 0x0008110a, 0x0008100b, 0x0008100c, 0x0008100c, 0x0006100d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x0006100c, 0x0008120d, 0x0007130d, 0x0006120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0007120c, 0x0007120c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100c, 0x0009110d, 0x0009110d, 0x000a120e, 0x000a120e, 0x000c1410, 0x000c140f, 0x000c140f, 0x000d1510, 0x000f1812, 0x00141815, 0x00141914, 0x00151a14, 0x00161b14, 0x00171c14, 0x00171e14, 0x00171e14, 0x00161c13, 0x00161c12, 0x00181b11, 0x00161810, 0x00141710, 0x00131810, 0x000f1811, 0x000e1811, 0x000c150e, 0x000a140e, 0x000a1410, 0x00091310, 0x0008120f, 0x0008120f, 0x0008100c, 0x0008100c, 0x0008100c, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00141809, 0x00191c09, 0x00202309, 0x00202309, 0x0026280c, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0040400e, 0x0044450e, 0x0048490f, 0x004c4d0f, 0x00505010, 0x00535410, 0x00716412, 0x00cca316, 0x00c5a016, 0x00605d11, 0x005d5e12, 0x00606013, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x005c5d13, 0x00a68b15, 0x00cca418, 0x00a08514, 0x00585912, 0x00585910, 0x00555610, 0x00535410, 0x00525310, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004d4e0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545510, 0x00565710, 0x00585910, 0x005e5c12, 0x00c39e17, 0x00cca418, 0x00756a13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005b5b12, 0x00867414, 0x00c8a016, 0x00b09014, 0x004c4d10, 0x004f5010, 0x004c4d0f, 0x0048490e, 0x0044450e, 0x0040400e, 0x003c3e0d, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x00060e08, 0x00060e08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00080f0b, 0x00080f0a, 0x00060e08, 0x00050e07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f07, 0x00040f07, 0x00051008, 0x00051008, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00081009, 0x00081009, 0x00060e08, 0x00060e08, 0x00081009, 0x00081009, 0x00081009, 0x0008110a, 0x000b130c, 0x000e140e, 0x00101610, 0x00111812, 0x00121813, 0x00151a13, 0x00151a13, 0x00161b14, 0x00191c16, 0x001d1c18, 0x001e1c18, 0x001e1d16, 0x001e1d14, 0x001e1d16, 0x001c1e16, 0x001b1c14, 0x00181b12, 0x00151a13, 0x00141811, 0x00121710, 0x0010150f, 0x000e1410, 0x000c1410, 0x000c140f, 0x000a140f, 0x0008130e, 0x0006110d, 0x0006110d, 0x0005100c, 0x0005100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00040e0b, 0x0006100b, 0x00061009, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0006110b, 0x0006120c, 0x0005120c, 0x0005110b, 0x0005110b, 0x0005120c, 0x0006120c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0006110c, 0x0006120c, 0x0008130d, 0x0008120d, 0x0007100c, 0x0009120e, 0x000a120e, 0x000a120e, 0x000a1210, 0x0008100c, 0x00091009, 0x000a0f08, 0x000a0f08, 0x000a0f07, 0x000b0f05, 0x000c0f04, 0x000c0f04, 0x000b0f04, 0x000a1004, 0x000b1005, 0x000b1005, 0x000c1007, 0x000c1005, 0x000d0f05, 0x00101108, 0x00131209, 0x00131209, 0x00141208, 0x00181408, 0x001c1709, 0x00211808, 0x00271c08, 0x002c1f08, 0x00322408, 0x003a2e0b, 0x0044340c, 0x00523b0c, 0x0066480c, 0x00856611, 0x00c0a630, 0x00cbb61f, 0x00cbba0b, 0x00cbba0c, 0x00ccbb0c, 0x00ccba0e, 0x00cbb80e, 0x00ac8d09, 0x007c5700, 0x00614400, 0x004d3c04, 0x00413209, 0x00382b04, 0x0044370e, 0x0045380e, 0x0045380c, 0x00413409, 0x003f320c, 0x003a2f0d, 0x00281d01, 0x0033280f, 0x002a240f, 0x001c1a08, 0x00121204, 0x000f1007, 0x000e1006, 0x000e1208, 0x00101108, 0x00131107, 0x00151007, 0x00181009, 0x00181009, 0x001c1208, 0x001d1205, 0x00211509, 0x00241609, 0x00241608, 0x0028180a, 0x002c1a0a, 0x002f1a08, 0x00311807, 0x00351806, 0x00371b08, 0x00371b08, 0x00351c08, 0x00381f08, 0x00381f08, 0x00371e08, 0x00371e07, 0x00381e06, 0x00361c07, 0x00351c07, 0x00341907, 0x00351807, 0x00341907, 0x00311908, 0x002e1708, 0x002b1709, 0x0028140a, 0x0024130a, 0x00221209, 0x001d1107, 0x001c1106, 0x00191007, 0x00181108, 0x0018100a, 0x00171009, 0x00151008, 0x00151008, 0x0018120b, 0x00191409, 0x001b130a, 0x0020180a, 0x00281f08, 0x003c330f, 0x00453914, 0x00342603, 0x00362404, 0x003e2d09, 0x00483409, 0x005c400d, 0x00785514, 0x00b3932b, 0x00ccb222, 0x00cbb40e, 0x00ccb80c, 0x00ccb80a, 0x00cbb213, 0x00ab8204, 0x007b4f00, 0x00603c00, 0x00513408, 0x00462c0a, 0x003b2804, 0x002e1d01, 0x002d1d05, 0x00291a06, 0x00251908, 0x001e1504, 0x001a1305, 0x00181308, 0x0018130a, 0x00141209, 0x00121008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00121009, 0x00121009, 0x00140f09, 0x00140f09, 0x00140f09, 0x00151009, 0x00140f08, 0x00121008, 0x000d0e06, 0x000c0d08, 0x000e120b, 0x0010140e, 0x00151712, 0x00171712, 0x00181711, 0x00171710, 0x00171710, 0x0016160f, 0x0015150e, 0x0014140c, 0x0012140c, 0x0010140b, 0x000c1209, 0x000a140a, 0x000b140d, 0x000a140c, 0x0008120c, 0x0008120c, 0x0007110c, 0x0007110c, 0x0007110d, 0x0006110e, 0x0006110e, 0x0007110d, 0x0007100d, 0x0006100a, 0x00061009, 0x00061009, 0x00071008, 0x0008100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0008120c, 0x000c140f, 0x000c140f, 0x000c1511, 0x000c1512, 0x000c1713, 0x000e1814, 0x00121816, 0x00141815, 0x00151916, 0x00151a14, 0x00181c17, 0x00191d17, 0x00181d15, 0x00171c14, 0x00171c14, 0x00171c15, 0x00171c15, 0x00141912, 0x00141811, 0x00121812, 0x00111812, 0x000f150f, 0x000c140f, 0x000c1411, 0x000c1310, 0x00091310, 0x00081410, 0x0009110d, 0x0009110d, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002d2f0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x00525310, 0x00716412, 0x00cca316, 0x00c5a017, 0x00605c12, 0x005d5e11, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005c5c13, 0x00a68b15, 0x00cca417, 0x00a08514, 0x00585912, 0x00585810, 0x00565711, 0x00535410, 0x00525310, 0x00515110, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00525310, 0x00535410, 0x00555611, 0x00585810, 0x00585911, 0x005e5c13, 0x00c39d17, 0x00cca417, 0x00756a12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5c11, 0x005b5b12, 0x00867414, 0x00c8a016, 0x00b09014, 0x004c4d10, 0x004f5010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00070f08, 0x00070f08, 0x00080e08, 0x00070f08, 0x00070f08, 0x00051008, 0x00051008, 0x00051008, 0x00070d08, 0x00080f0b, 0x0008100a, 0x00050f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00051007, 0x00051008, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x0008100a, 0x000a130c, 0x000c140e, 0x000f150f, 0x00101711, 0x00111812, 0x00131813, 0x00151a13, 0x00151a13, 0x00171c14, 0x00191c16, 0x001d1c18, 0x001e1c18, 0x001e1d16, 0x001e1d14, 0x001e1d16, 0x001c1c14, 0x001b1c14, 0x00181b12, 0x00151a13, 0x00141811, 0x00131810, 0x0012160f, 0x000e150f, 0x000b1510, 0x000b1410, 0x0008120d, 0x0006100b, 0x0004100c, 0x0004100c, 0x0005100c, 0x0005100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00040e0b, 0x0006100b, 0x00061009, 0x0008110b, 0x0008110b, 0x0008110c, 0x0008110c, 0x0007110c, 0x0006100b, 0x0006100a, 0x00051109, 0x00061109, 0x0006120a, 0x0007110a, 0x000b110c, 0x000b110c, 0x000a100a, 0x0009100a, 0x000b130c, 0x000b130c, 0x000c140d, 0x000c140d, 0x000d140e, 0x00101610, 0x000e140e, 0x000e140e, 0x000c130f, 0x0009100b, 0x00090f08, 0x000a0f08, 0x000a0f06, 0x000a0f06, 0x000b0f05, 0x000c0f04, 0x000c0f04, 0x000a1004, 0x000a1004, 0x000b1005, 0x000b1005, 0x000b1007, 0x000c1005, 0x000d0f05, 0x00101108, 0x00111309, 0x00111309, 0x00131308, 0x00171509, 0x001c170a, 0x00231809, 0x00271c08, 0x002c2009, 0x00322408, 0x003a2e0b, 0x0044350c, 0x00523c0c, 0x0066480e, 0x00856611, 0x00c0a630, 0x00cbb61f, 0x00cab90a, 0x00cbba0c, 0x00cbba0c, 0x00cbbb0e, 0x00c9b810, 0x00ac8c08, 0x007c5700, 0x00624500, 0x004f3c05, 0x0044340c, 0x003b2d07, 0x0044380f, 0x0045380d, 0x0045390b, 0x00403408, 0x003e330c, 0x00392f0e, 0x00261c00, 0x002e240b, 0x002a240f, 0x00201e0b, 0x00111302, 0x000c0e04, 0x000c0e04, 0x000d1107, 0x00101208, 0x00121107, 0x00141007, 0x00181009, 0x00181009, 0x001c1208, 0x001d1205, 0x00211509, 0x00231709, 0x00231708, 0x0026180a, 0x002a1a0b, 0x002c1a08, 0x00301806, 0x00331906, 0x00351c08, 0x00351c09, 0x00351c09, 0x00361f08, 0x00361f08, 0x00361f08, 0x00361f08, 0x00381e08, 0x00361c08, 0x00351c08, 0x00341907, 0x00331806, 0x00321808, 0x00301808, 0x002e1808, 0x002c1709, 0x0027150a, 0x0024140a, 0x0021140a, 0x001e1208, 0x001c1307, 0x00181107, 0x00181108, 0x0017110a, 0x00151109, 0x00141008, 0x00151009, 0x0017130b, 0x00191409, 0x001b1308, 0x00201808, 0x00282008, 0x003d3210, 0x00453914, 0x00352804, 0x00362404, 0x003f2e08, 0x00493609, 0x005c400c, 0x00775512, 0x00b2932b, 0x00cab322, 0x00c9b50e, 0x00cab80c, 0x00ccb80a, 0x00cbb313, 0x00ac8406, 0x007c5000, 0x00603c00, 0x00513408, 0x00462c09, 0x003c2805, 0x002f1d02, 0x002d1d05, 0x00291a06, 0x00251908, 0x001e1504, 0x001a1304, 0x00181309, 0x0018130a, 0x00141209, 0x00121008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00121009, 0x00121009, 0x0013100a, 0x00121009, 0x00121009, 0x00141209, 0x00140f09, 0x00121008, 0x000e0d06, 0x000c0f06, 0x000e110a, 0x0012140e, 0x00151410, 0x0016140f, 0x0018140d, 0x0018130d, 0x0018130c, 0x0017120b, 0x0017120b, 0x0014130a, 0x0014130a, 0x0016180e, 0x0014180f, 0x0013180f, 0x0012170e, 0x0010150e, 0x000e140c, 0x000b110c, 0x000a110c, 0x0009100b, 0x0009100c, 0x0007110c, 0x0006110c, 0x0007110c, 0x0007110c, 0x0008120c, 0x0008120c, 0x0008100b, 0x00070f08, 0x00081009, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0006100b, 0x0007110c, 0x000a140f, 0x000a140f, 0x000b1411, 0x000b1411, 0x000c1713, 0x000c1713, 0x00101614, 0x00141814, 0x00141815, 0x00151914, 0x00161b17, 0x00171b18, 0x00171c16, 0x00171c14, 0x00171c14, 0x00171c15, 0x00171c15, 0x00161b14, 0x00141811, 0x00131712, 0x00111812, 0x000f150f, 0x000c140f, 0x000c1411, 0x000c1411, 0x00091310, 0x00081410, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x0040400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x00525310, 0x00706411, 0x00cca316, 0x00c5a017, 0x00605c12, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x005e5f13, 0x005e5f13, 0x005c5c13, 0x00a68a14, 0x00cca417, 0x00a08514, 0x00585912, 0x00585910, 0x00565711, 0x00545511, 0x00535410, 0x00515110, 0x00505010, 0x004f5010, 0x004f5010, 0x004d4e10, 0x004f5010, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545510, 0x00555611, 0x00565710, 0x00595a11, 0x005e5c13, 0x00c39e17, 0x00cca417, 0x00756a12, 0x005d5e12, 0x005e5f13, 0x005e5f12, 0x005d5e11, 0x005d5e11, 0x005c5c11, 0x00595a12, 0x00867413, 0x00c8a016, 0x00b09014, 0x004c4d10, 0x004d4e0f, 0x004b4c10, 0x0047480e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00080e08, 0x00080e08, 0x00080e08, 0x00070f08, 0x00070f08, 0x00051008, 0x00051008, 0x00051008, 0x0009100b, 0x0009100c, 0x0008110b, 0x00071008, 0x00051007, 0x00051007, 0x00051007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00061108, 0x00041008, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00081009, 0x00081009, 0x0009120c, 0x0008120c, 0x0008110b, 0x0008110a, 0x0008110a, 0x000a130c, 0x000c140e, 0x00101610, 0x00101711, 0x00131712, 0x00141813, 0x00181a14, 0x00181c15, 0x00191c16, 0x001a1d17, 0x001c1d18, 0x001c1d18, 0x001c1e16, 0x001c1e14, 0x001c1d15, 0x001a1b14, 0x001a1b14, 0x00171913, 0x00141813, 0x00131811, 0x00101610, 0x0010150e, 0x000c140e, 0x00091310, 0x0008120e, 0x0006100c, 0x0006100c, 0x00030f0b, 0x00030f0b, 0x0005100c, 0x0005100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100b, 0x00061009, 0x0007110a, 0x0007110a, 0x0007110c, 0x0007110c, 0x0007110b, 0x00061009, 0x00050f08, 0x00081009, 0x0009120b, 0x000a130b, 0x000b130b, 0x000c130c, 0x000c130c, 0x000f130c, 0x000e130c, 0x0010150e, 0x00111610, 0x0010150e, 0x0010150e, 0x00141811, 0x00161912, 0x0011160f, 0x0010140d, 0x000d120b, 0x00090e07, 0x00090e06, 0x00090f05, 0x000a1004, 0x000a1004, 0x000b1005, 0x000c0f06, 0x000c0f06, 0x000a1004, 0x000a1004, 0x000b1005, 0x000b1005, 0x000b1007, 0x000c1005, 0x000d0f05, 0x00101108, 0x00111309, 0x0013120b, 0x00141109, 0x0018140b, 0x001d160a, 0x00231809, 0x00271c08, 0x002c2009, 0x00322408, 0x003a2d0b, 0x0044350c, 0x00503c0d, 0x0065480d, 0x00846311, 0x00c0a430, 0x00ccb520, 0x00ccb80b, 0x00cab90a, 0x00cbb90c, 0x00cbb90d, 0x00cbb810, 0x00aa8a08, 0x007c5700, 0x00624500, 0x004f3c04, 0x0044350b, 0x003c2e07, 0x00483a11, 0x0045380d, 0x0044380a, 0x00403408, 0x00392e08, 0x003b3010, 0x002b2104, 0x00291f06, 0x0028220c, 0x00201e0b, 0x00141404, 0x000d0d02, 0x000c0e04, 0x000c1005, 0x00101109, 0x00131208, 0x00161108, 0x00181009, 0x00181009, 0x001c1208, 0x001d1205, 0x00211408, 0x00231708, 0x00241809, 0x00241809, 0x00281a0a, 0x002c1a08, 0x002e1906, 0x00311906, 0x00341b08, 0x00341b08, 0x00341b08, 0x00341c08, 0x00341c08, 0x00341c08, 0x00341c08, 0x00341b06, 0x00341b08, 0x00341a0a, 0x00341a0a, 0x00331806, 0x00311908, 0x00311a09, 0x002e1908, 0x002a1709, 0x00261509, 0x00231409, 0x00211409, 0x001c1308, 0x001a1308, 0x00181207, 0x00151108, 0x00141109, 0x00141109, 0x00131008, 0x00141109, 0x0017140c, 0x00181409, 0x001b1308, 0x00211709, 0x002a2008, 0x003c3110, 0x00443812, 0x00352804, 0x00382505, 0x00402f09, 0x0049370a, 0x005c400c, 0x00755410, 0x00af8f27, 0x00ccb323, 0x00cab40e, 0x00ccb80c, 0x00ccb80a, 0x00cbb412, 0x00ac8606, 0x007c5100, 0x00603c00, 0x004f3308, 0x00432b09, 0x003b2804, 0x002e1c01, 0x002d1d05, 0x00291a06, 0x00251908, 0x001e1504, 0x001a1304, 0x00181309, 0x0018130a, 0x00141209, 0x00121008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00121009, 0x00110f08, 0x00101009, 0x000f0e08, 0x00100f08, 0x00110f08, 0x00121009, 0x00100e08, 0x000e0d06, 0x000e1109, 0x000d1209, 0x0010140b, 0x0014140c, 0x0014130a, 0x0016110a, 0x00181309, 0x00181309, 0x00181309, 0x00181108, 0x00171309, 0x00161409, 0x00151409, 0x0014140a, 0x0015170d, 0x0016170f, 0x00171810, 0x0015170f, 0x0014160f, 0x00141610, 0x0014150f, 0x0010130e, 0x000c140d, 0x000c140d, 0x000c140d, 0x0009120b, 0x0008110a, 0x0008110a, 0x0009120b, 0x00081009, 0x00081009, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x00070f0a, 0x0008100c, 0x0006100b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0007100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0007110c, 0x0007110c, 0x0009130e, 0x0009130e, 0x00091310, 0x00091310, 0x000b1411, 0x000c1713, 0x00101614, 0x00111613, 0x00111613, 0x00141813, 0x00151916, 0x00151917, 0x00171b17, 0x00171c16, 0x00171c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00151a14, 0x00131712, 0x00111812, 0x00101710, 0x000d150f, 0x000d1510, 0x000d1510, 0x000a140f, 0x000a140f, 0x0009130e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0009110d, 0x0009110d, 0x0008100c, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x00515110, 0x00706412, 0x00cca316, 0x00c5a016, 0x005e5c12, 0x005c5c11, 0x005d5e11, 0x005e5f12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005b5b12, 0x00a68a14, 0x00cca417, 0x00a08514, 0x00585912, 0x00585810, 0x00565711, 0x00555611, 0x00535410, 0x00525310, 0x00515110, 0x00505010, 0x00505010, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00535410, 0x00545511, 0x00565711, 0x00585910, 0x00595a12, 0x005e5c12, 0x00c39e17, 0x00cca418, 0x00756a13, 0x005d5e12, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x005b5b12, 0x00867413, 0x00c8a016, 0x00b08f14, 0x004c4d10, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x0040400c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x0026280a, 0x0026280c, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x000a100a, 0x000a100a, 0x000a100a, 0x0008110a, 0x0008110a, 0x0007110a, 0x0007110a, 0x0007110a, 0x0009100b, 0x0009100c, 0x0008110b, 0x00081109, 0x00061108, 0x00071208, 0x00071208, 0x00061108, 0x00061108, 0x00061108, 0x00061108, 0x00071208, 0x00051008, 0x0008100b, 0x0008100b, 0x0009110c, 0x0008100c, 0x0008110a, 0x0008110a, 0x0009120c, 0x0009140c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000c140e, 0x000e1510, 0x00101711, 0x00131813, 0x00141914, 0x00151a14, 0x00181c15, 0x001a1d17, 0x001b1e18, 0x001c1f18, 0x001c1d18, 0x001c1d18, 0x001c1e16, 0x001c1d14, 0x001a1b14, 0x001a1b14, 0x00181813, 0x00141811, 0x00131712, 0x00101610, 0x000f150f, 0x000d140e, 0x000a120d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0004100c, 0x00030f0b, 0x0005100c, 0x0005100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100a, 0x00061009, 0x0007110a, 0x0007110a, 0x0009130d, 0x0009130e, 0x0009120c, 0x000a130c, 0x000d140d, 0x000f150e, 0x0010160f, 0x0011170e, 0x0012170e, 0x0014170f, 0x0013160e, 0x0013140c, 0x0012150c, 0x0012150c, 0x0013160d, 0x0012150c, 0x0012150c, 0x0014160d, 0x0016180e, 0x0013160c, 0x0011140c, 0x000e1209, 0x00090f05, 0x00080e04, 0x00070e03, 0x00090e02, 0x000b0e03, 0x000c0f05, 0x000c0f07, 0x000c0f06, 0x000a1004, 0x000a1004, 0x000b1005, 0x000b1005, 0x000b1007, 0x000c1005, 0x000d0f05, 0x00101108, 0x00111309, 0x0013120b, 0x00141109, 0x0018140b, 0x001d160a, 0x00231809, 0x00271c08, 0x002c2008, 0x00332408, 0x003a2d0b, 0x0044350c, 0x00523c0d, 0x0064460e, 0x00846210, 0x00c0a330, 0x00ccb420, 0x00ccb80c, 0x00cab90a, 0x00cab80c, 0x00cab80c, 0x00ccb811, 0x00a68606, 0x00795400, 0x00604300, 0x004c3a02, 0x00413208, 0x00382b04, 0x00463810, 0x0045380d, 0x00423509, 0x003f3307, 0x003b3008, 0x003a3010, 0x002e2407, 0x00281f07, 0x0028220c, 0x00201e0b, 0x00141404, 0x000e0e03, 0x000c0e04, 0x000c0f04, 0x0010120a, 0x00131208, 0x00161108, 0x00181009, 0x00181009, 0x001c1208, 0x001d1206, 0x00201408, 0x00221608, 0x00231809, 0x00231808, 0x00261909, 0x002b1b08, 0x002c1a06, 0x002e1a05, 0x00301c07, 0x00311c08, 0x00321c08, 0x00331a07, 0x00331a07, 0x00331a07, 0x00331a07, 0x00341b08, 0x00341b08, 0x00341a0a, 0x00341a0b, 0x00311906, 0x00311908, 0x00301808, 0x002c1707, 0x00281608, 0x00241409, 0x00211308, 0x001f1308, 0x001b1307, 0x00181208, 0x00161106, 0x00131107, 0x00121108, 0x00131008, 0x00111008, 0x00131209, 0x0017140c, 0x00181409, 0x001b1308, 0x00211709, 0x002b2008, 0x003c300f, 0x00433710, 0x00332400, 0x00342303, 0x003c2c07, 0x00473407, 0x005b3f0c, 0x0074520c, 0x00af8f26, 0x00ccb224, 0x00cbb510, 0x00ccb80b, 0x00ccb80a, 0x00ccb411, 0x00b08909, 0x007d5200, 0x00603c00, 0x004f3207, 0x00422a08, 0x003a2704, 0x00301d02, 0x002d1c05, 0x00291a06, 0x00251907, 0x001e1504, 0x001a1304, 0x00181308, 0x0018130a, 0x00141209, 0x00121008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00101009, 0x00100f08, 0x000f100a, 0x000d0f08, 0x000f100a, 0x000f1008, 0x00121009, 0x00100d07, 0x000e0d04, 0x00101108, 0x0010140a, 0x00101409, 0x00121308, 0x00141309, 0x0016140a, 0x00161409, 0x00161409, 0x00151408, 0x00161307, 0x00161408, 0x00161408, 0x00141408, 0x00141409, 0x00151409, 0x0017140a, 0x0017140c, 0x0018160d, 0x0018170e, 0x0018170e, 0x001b1b12, 0x00181810, 0x00171810, 0x00171810, 0x00171810, 0x0014150e, 0x0010140c, 0x000c140c, 0x000a130b, 0x0009120a, 0x0008100a, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x000a120e, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0009110c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0009110d, 0x0007110c, 0x0007110c, 0x0008120d, 0x0008120d, 0x00091310, 0x00091310, 0x000b1410, 0x000c1512, 0x00101614, 0x00111613, 0x00111613, 0x00141813, 0x00151917, 0x00161a18, 0x00171b18, 0x00171c18, 0x00171c16, 0x00171c15, 0x00171c15, 0x00181d16, 0x00171c15, 0x00141813, 0x00121813, 0x00111812, 0x000f1810, 0x000e1611, 0x000e1611, 0x000b1510, 0x000b1510, 0x0008140e, 0x0008140e, 0x0007130d, 0x0007130d, 0x0009110d, 0x0009110d, 0x0008100c, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x00393b0c, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x00515110, 0x00706311, 0x00cca316, 0x00c59f16, 0x005e5c12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005c5c12, 0x00a68a15, 0x00cca417, 0x00a48814, 0x005b5b12, 0x00585910, 0x00565710, 0x00555611, 0x00545511, 0x00535410, 0x00525310, 0x00515110, 0x00515110, 0x00515110, 0x00515110, 0x00515110, 0x00525310, 0x00535410, 0x00545510, 0x00555611, 0x00585810, 0x00585911, 0x00595a12, 0x00615e12, 0x00c5a017, 0x00cca418, 0x00756b13, 0x005e5f12, 0x005e5f13, 0x005d5e11, 0x005d5e11, 0x005c5d11, 0x005b5b12, 0x00595a12, 0x008c7813, 0x00caa116, 0x00af8f14, 0x004b4c10, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x0008110a, 0x0008110a, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x0009130c, 0x0009120a, 0x0009120a, 0x000a130b, 0x000a130b, 0x0009140b, 0x0009140b, 0x0008130a, 0x0008130a, 0x0009120c, 0x0009120c, 0x000a130c, 0x000c120c, 0x000a100a, 0x000a100a, 0x000a130c, 0x0009140c, 0x000b140d, 0x000d140e, 0x000f150f, 0x00101510, 0x00121611, 0x00141813, 0x00151a14, 0x00171914, 0x00181a15, 0x001a1d17, 0x001a1d17, 0x001d1e18, 0x001d1e18, 0x001c1e16, 0x001c1e16, 0x001c1e16, 0x001b1c14, 0x001a1b14, 0x00181a14, 0x00141811, 0x00111611, 0x00101511, 0x00101511, 0x000e1411, 0x000b120e, 0x0008120e, 0x0006120d, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005100a, 0x0006100b, 0x0008100c, 0x0008100c, 0x0009100c, 0x0009100c, 0x0008100c, 0x0009110c, 0x00081009, 0x0009120c, 0x000a140d, 0x000a140d, 0x000f140e, 0x00121410, 0x00131610, 0x00131710, 0x0012170e, 0x0011170e, 0x0012170e, 0x0013160c, 0x0013160c, 0x0015150c, 0x0014140c, 0x0014130a, 0x0014130a, 0x0013140b, 0x0012140b, 0x0013140c, 0x0013140c, 0x0012140a, 0x0013140b, 0x000f1308, 0x0011140a, 0x000c1208, 0x00090e04, 0x00070e03, 0x00070e03, 0x000a0e02, 0x000b0e03, 0x000c0e04, 0x000c0e06, 0x000c0e06, 0x000c1007, 0x000c1007, 0x000c0f08, 0x000c0f08, 0x000f100a, 0x000f1008, 0x000e0f08, 0x00101108, 0x00131209, 0x00131209, 0x0014130a, 0x0019150b, 0x001e1809, 0x00231909, 0x00271c08, 0x002c2008, 0x00342407, 0x003b2d0a, 0x0044350c, 0x00523c0f, 0x0064460d, 0x00846311, 0x00c0a430, 0x00ccb420, 0x00ccb80c, 0x00ccb80a, 0x00ccb80c, 0x00cab80c, 0x00c8b40d, 0x00a48404, 0x00785300, 0x005f4200, 0x004b3802, 0x003f3005, 0x003c2e05, 0x00473910, 0x0045370c, 0x00423408, 0x003e3108, 0x00392e09, 0x00342a0a, 0x002e2408, 0x00231b02, 0x002c2510, 0x00231e0c, 0x00171505, 0x000c0d02, 0x000b0e04, 0x000b0f05, 0x000d1209, 0x0014120c, 0x0016110c, 0x0018100b, 0x00181009, 0x001a1008, 0x001b1007, 0x001c1005, 0x001f1406, 0x00221708, 0x00231708, 0x00251708, 0x00271706, 0x00281805, 0x002c1906, 0x002e1b08, 0x002f1a08, 0x00301a06, 0x00311b08, 0x00331a08, 0x00341908, 0x00341908, 0x00331a07, 0x00331a07, 0x00341b08, 0x00341b08, 0x00341c08, 0x00301807, 0x002d1809, 0x002c180b, 0x00261509, 0x0024140b, 0x00201409, 0x001d1409, 0x001a1208, 0x00181107, 0x00161106, 0x00141007, 0x00121007, 0x00121008, 0x00121008, 0x0014120a, 0x0017140c, 0x0018140b, 0x001b120a, 0x0021180b, 0x002b210b, 0x003b3010, 0x00413510, 0x00342702, 0x00332000, 0x003a2905, 0x00463309, 0x00593d0c, 0x0074520d, 0x00ad8c24, 0x00ccb224, 0x00ccb610, 0x00ccb80a, 0x00ccb808, 0x00cbb411, 0x00b08b0a, 0x007c5300, 0x005f3b00, 0x004e3307, 0x00412b09, 0x00382603, 0x00311e03, 0x002f1d06, 0x002a1c05, 0x00241704, 0x00201604, 0x001b1405, 0x00171106, 0x00161309, 0x00131308, 0x00111007, 0x00101006, 0x00121107, 0x00101006, 0x000e0e05, 0x000f0d06, 0x000f0d07, 0x0010100b, 0x0010100c, 0x000f0f0c, 0x000f0f0c, 0x000d100c, 0x000d100c, 0x00100f08, 0x00101007, 0x000f0f06, 0x00131209, 0x00111309, 0x00101208, 0x00121108, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014140a, 0x00141408, 0x00141407, 0x00141308, 0x00141308, 0x00141408, 0x00141408, 0x0014130a, 0x0014130a, 0x00141308, 0x00141308, 0x00161408, 0x00161408, 0x00171509, 0x0019150c, 0x0019150c, 0x0019160c, 0x0018170c, 0x0018170e, 0x0018180f, 0x00181811, 0x00181810, 0x0016150f, 0x0011130d, 0x000d130e, 0x000c140d, 0x00081009, 0x0008100a, 0x0009120c, 0x00081009, 0x00061009, 0x0008120c, 0x0008120d, 0x0008120d, 0x0008110c, 0x0008120d, 0x0008120f, 0x0008120f, 0x0007110d, 0x0007110d, 0x0008110d, 0x0009110d, 0x0009110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x000a110f, 0x000b100f, 0x000c1110, 0x000d1411, 0x00101513, 0x00101513, 0x00111514, 0x00141716, 0x00141815, 0x00141a16, 0x00151c15, 0x00151c15, 0x00161b15, 0x00181a15, 0x00181b15, 0x00171c17, 0x00151a14, 0x00151a14, 0x00141914, 0x00111812, 0x00111812, 0x000f1713, 0x000f1713, 0x000c1410, 0x000b1510, 0x000c1410, 0x000c1310, 0x000a1410, 0x00091310, 0x000a1210, 0x000a1210, 0x000a1210, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003e400d, 0x0041420e, 0x0045470e, 0x0048490f, 0x004c4d10, 0x00515110, 0x006e6210, 0x00cba216, 0x00c69f15, 0x00646012, 0x005b5b12, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005c5c11, 0x00a08615, 0x00cca417, 0x00b09115, 0x005d5c12, 0x00585911, 0x00585810, 0x00565710, 0x00555611, 0x00545511, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00545511, 0x00555611, 0x00565710, 0x00585910, 0x00595a12, 0x005b5b12, 0x007b6e12, 0x00c8a116, 0x00c49f18, 0x006f6612, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x005c5c12, 0x00595a11, 0x009c8314, 0x00cca316, 0x00ab8c14, 0x004c4d10, 0x004c4d10, 0x00494a0f, 0x0045470e, 0x0041420e, 0x003c3e0c, 0x00393b0c, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130e, 0x000f130f, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000b140d, 0x000c140d, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x0009120a, 0x0009120a, 0x000a130b, 0x000a130b, 0x000a140c, 0x000a140c, 0x0009140b, 0x0009140b, 0x000a130c, 0x000a130c, 0x000a130c, 0x000c120c, 0x000c120c, 0x000b110c, 0x000c140d, 0x000a140d, 0x000c130d, 0x000d140e, 0x00101510, 0x00111611, 0x00121712, 0x00141914, 0x00151a14, 0x00171914, 0x00191c18, 0x001a1d17, 0x001b1e18, 0x001d1e18, 0x001c1d18, 0x001c1e16, 0x001c1e16, 0x001c1e16, 0x001b1c14, 0x001a1b14, 0x00181a14, 0x00141811, 0x00111611, 0x00101511, 0x00101512, 0x000e1411, 0x000a110e, 0x0008120d, 0x0008110c, 0x00051009, 0x00081009, 0x00081009, 0x00081009, 0x0008110a, 0x000a100a, 0x000b110c, 0x000d110c, 0x000e120d, 0x000e120d, 0x000e140e, 0x000d140d, 0x00101710, 0x00101710, 0x00101710, 0x00141610, 0x0016160f, 0x0016160f, 0x0015150e, 0x0014150c, 0x0013140b, 0x0012140a, 0x0014130a, 0x0014130a, 0x00141408, 0x00141408, 0x00141308, 0x00141308, 0x0014130a, 0x0013130a, 0x00121209, 0x00121108, 0x00111108, 0x00131209, 0x00101208, 0x0012140a, 0x00101409, 0x000c1005, 0x000b0e04, 0x00090d03, 0x000a0e03, 0x000b0e04, 0x000c0e04, 0x000c0e04, 0x000c0e05, 0x000c1007, 0x000c1007, 0x000c0f08, 0x000d0e0a, 0x00100f0a, 0x000f1008, 0x000e0f08, 0x00101108, 0x0014130a, 0x0014130a, 0x00161409, 0x001a160b, 0x001f180a, 0x00241b0a, 0x00271c07, 0x002c2008, 0x00342508, 0x003c2e0a, 0x0044340c, 0x00523c0f, 0x0064460d, 0x00846311, 0x00c0a430, 0x00ccb420, 0x00ccb80c, 0x00ccb80a, 0x00ccb80c, 0x00cab80c, 0x00c8b40d, 0x00a48404, 0x00785300, 0x00604300, 0x004c3903, 0x003f3005, 0x003c2e05, 0x00463810, 0x0044370c, 0x00413408, 0x003d3108, 0x00382d0a, 0x0033290a, 0x002c2509, 0x001f1a00, 0x0025200b, 0x00211e0c, 0x00191809, 0x000d1004, 0x00090e03, 0x00090f06, 0x000b1008, 0x0012120b, 0x0014130c, 0x0016100b, 0x00171009, 0x00181108, 0x00181107, 0x001a1105, 0x001d1408, 0x00211808, 0x00231708, 0x00251708, 0x00261807, 0x00271706, 0x00281808, 0x002c1808, 0x002d1806, 0x002d1806, 0x00301808, 0x00301808, 0x00311809, 0x00341909, 0x00321a07, 0x00311b07, 0x00311b07, 0x00311b07, 0x00311b08, 0x00301808, 0x002c1609, 0x002a160b, 0x00241408, 0x00201409, 0x001f1308, 0x001c1308, 0x00191208, 0x00181107, 0x00171106, 0x00141007, 0x00121006, 0x00120e07, 0x00120e07, 0x0015120a, 0x0017140c, 0x0018140b, 0x001b130a, 0x0020180b, 0x002b210b, 0x003a2f10, 0x0040340f, 0x00342702, 0x00332001, 0x00392808, 0x0048330d, 0x005a3d0f, 0x0073510e, 0x00ac8c23, 0x00ccb224, 0x00ccb610, 0x00ccb808, 0x00ccb806, 0x00cbb40f, 0x00b18c09, 0x007c5300, 0x005e3b00, 0x004c3306, 0x00412c09, 0x00372502, 0x00332004, 0x002f1d06, 0x002a1c05, 0x00241704, 0x00211504, 0x001c1505, 0x00181106, 0x00161308, 0x00141308, 0x00131207, 0x00111006, 0x000f0f04, 0x00101005, 0x00101008, 0x00121009, 0x00111009, 0x0010100b, 0x0010100c, 0x00100f0a, 0x00100f0a, 0x000f100a, 0x0010100b, 0x00100f08, 0x00101007, 0x00141109, 0x0014130a, 0x00131008, 0x00141109, 0x00141109, 0x00141109, 0x0014120a, 0x0016120b, 0x00161209, 0x00161208, 0x00161307, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x0016120a, 0x0016120a, 0x00161208, 0x00161208, 0x00171309, 0x00171309, 0x00181408, 0x00181408, 0x00181309, 0x00181309, 0x00161409, 0x0016150b, 0x0017160c, 0x0019170f, 0x00191710, 0x00181710, 0x00191811, 0x00181a14, 0x00171914, 0x00131811, 0x00121710, 0x000f140d, 0x000c110a, 0x000b1009, 0x000a1009, 0x000a100b, 0x000b110c, 0x000a100a, 0x000a100b, 0x000a100c, 0x000a100c, 0x0008100c, 0x0008100c, 0x0009110c, 0x0009110d, 0x0009110c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0009110f, 0x0009110f, 0x000a1210, 0x000c1411, 0x000e1613, 0x000e1613, 0x00101513, 0x00131615, 0x00131815, 0x00131914, 0x00141b14, 0x00151c15, 0x00151c15, 0x00161b15, 0x00161b15, 0x00171c17, 0x00161b15, 0x00151c15, 0x00141a14, 0x00121813, 0x00111812, 0x00101814, 0x00101814, 0x000d1510, 0x000c1711, 0x000f1412, 0x000c1210, 0x000c1411, 0x000a1310, 0x000a120f, 0x000a120e, 0x000a120e, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0044450e, 0x0048490f, 0x004c4d0f, 0x004f5010, 0x006b6010, 0x00c8a015, 0x00c8a015, 0x00736812, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f12, 0x005e5f13, 0x005c5d11, 0x008c7914, 0x00cba417, 0x00c49f17, 0x00696312, 0x00595a12, 0x00585910, 0x00585810, 0x00565710, 0x00555611, 0x00545511, 0x00545511, 0x00535410, 0x00535410, 0x00545510, 0x00545511, 0x00545511, 0x00555610, 0x00565710, 0x00585910, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x00a28814, 0x00cca418, 0x00b79617, 0x00646213, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005b5b12, 0x005b5911, 0x00b09015, 0x00cca316, 0x00a38613, 0x004b4c10, 0x004c4d0f, 0x0048490f, 0x0045470e, 0x0041420d, 0x003e400d, 0x0038380c, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x00292b0b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c130d, 0x000c130d, 0x000c140d, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140d, 0x000b140c, 0x000c140c, 0x000c140c, 0x000c140c, 0x000c140c, 0x000c140c, 0x000b140c, 0x000a130b, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c130d, 0x000c120c, 0x000c130d, 0x000c140d, 0x000b170f, 0x000d160f, 0x00101610, 0x00121812, 0x00141813, 0x00141813, 0x00141914, 0x00161b15, 0x00191a17, 0x001c1c18, 0x001c1c17, 0x001d1e18, 0x001d1e18, 0x001d1e18, 0x001c1e16, 0x001c1e16, 0x001c1e16, 0x001a1c15, 0x00181b12, 0x00171913, 0x00131712, 0x00101511, 0x00111611, 0x00101510, 0x000d1310, 0x000a100b, 0x000a100b, 0x000a1009, 0x00091008, 0x000b1008, 0x000b1009, 0x000f140c, 0x000f140c, 0x0010130c, 0x0010130d, 0x0012140e, 0x0012140e, 0x0013140f, 0x00141510, 0x00141610, 0x00161810, 0x0015160f, 0x0014150f, 0x0014120c, 0x0016140c, 0x0017140d, 0x0018140d, 0x0016140c, 0x0014120c, 0x0014120b, 0x0014120b, 0x0014120b, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x00151208, 0x00161208, 0x00171309, 0x00171309, 0x00141008, 0x00121007, 0x00131108, 0x00131308, 0x0014140a, 0x00101309, 0x000f1007, 0x000c0f04, 0x000c0e04, 0x000c0e04, 0x000c0e04, 0x000d0f05, 0x000d0f06, 0x000e1108, 0x000e1109, 0x000e100b, 0x000f100c, 0x0011100c, 0x0010110a, 0x000f1008, 0x00101208, 0x0014130a, 0x0014130a, 0x00171409, 0x001b150b, 0x001f180a, 0x00241b0a, 0x00271c07, 0x002c2008, 0x00342508, 0x003c2e09, 0x0045340c, 0x00503c10, 0x0064470e, 0x00866413, 0x00c0a432, 0x00ccb420, 0x00ccb80c, 0x00ccb80a, 0x00ccb80c, 0x00ccb80c, 0x00c8b40d, 0x00a48404, 0x00785200, 0x005f4100, 0x004c3803, 0x003d2f04, 0x003a2d05, 0x0044380f, 0x0041340a, 0x0042350c, 0x003c300a, 0x00342b0b, 0x0030280c, 0x002b240b, 0x001d1802, 0x001d1b08, 0x00211f0f, 0x001a190c, 0x00101208, 0x000a0e03, 0x00090e05, 0x000a0e07, 0x000f1009, 0x0013100c, 0x0014100c, 0x00150f0a, 0x0018100a, 0x00181108, 0x00181107, 0x001c1407, 0x00201708, 0x00211707, 0x00221606, 0x00261808, 0x00251605, 0x00281708, 0x00291808, 0x002b1807, 0x002b1807, 0x002d1809, 0x002e1709, 0x00301709, 0x00301809, 0x00301906, 0x00301905, 0x00301905, 0x00301905, 0x00301908, 0x002c1808, 0x002b1709, 0x0028150b, 0x0024140a, 0x00211409, 0x001f1308, 0x001c1308, 0x001a1108, 0x00191008, 0x00181008, 0x00141007, 0x00121008, 0x00120e07, 0x00120e07, 0x0016120a, 0x0017140c, 0x0018140b, 0x001b130a, 0x001f170a, 0x002b210c, 0x00382d11, 0x003f3210, 0x00342602, 0x00321f04, 0x00392809, 0x00453210, 0x00573c11, 0x00725110, 0x00ad8c25, 0x00ccb024, 0x00ccb510, 0x00ccb809, 0x00ccb806, 0x00cbb40f, 0x00b08e0a, 0x007c5400, 0x005e3b00, 0x004c3104, 0x00402c09, 0x00372502, 0x00342005, 0x002f1c05, 0x002b1c06, 0x00261805, 0x00221604, 0x001e1506, 0x00181104, 0x00171308, 0x00151207, 0x00141106, 0x00131107, 0x00121106, 0x00121106, 0x00131107, 0x00131008, 0x0013100a, 0x0012100a, 0x0012100a, 0x00110f09, 0x000f0c06, 0x00100d07, 0x00121008, 0x00121008, 0x00151309, 0x00161409, 0x00141308, 0x00141208, 0x00141208, 0x00141108, 0x00141008, 0x00151108, 0x00161208, 0x00171307, 0x00181206, 0x00181306, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00171408, 0x00171408, 0x00171408, 0x00171408, 0x00181208, 0x00161208, 0x00161309, 0x00151409, 0x0015140a, 0x0015140b, 0x0015140b, 0x0015140b, 0x0015140c, 0x0014140c, 0x0014140c, 0x0016160f, 0x00181710, 0x00181810, 0x00181811, 0x00151710, 0x0014150e, 0x0010110b, 0x0010110c, 0x0010110c, 0x000d100b, 0x000c0f09, 0x000c100c, 0x000c100c, 0x000a110c, 0x000b110c, 0x000a110c, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006120c, 0x0006120c, 0x0005110b, 0x0005110b, 0x0006120c, 0x0007110c, 0x0008110d, 0x0008110d, 0x0009120f, 0x000b1410, 0x000c1411, 0x000c1411, 0x000e1513, 0x00101614, 0x00111814, 0x00111913, 0x00131a14, 0x00141c15, 0x00151c15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151c15, 0x00151c15, 0x00141a14, 0x00111812, 0x00101812, 0x00101813, 0x000f1811, 0x000e1610, 0x00111414, 0x000f1311, 0x000f1412, 0x000c1411, 0x000c1410, 0x000c1410, 0x000c1410, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0048490e, 0x004b4c0f, 0x004f5010, 0x00635b10, 0x00c09b14, 0x00c9a116, 0x008a7613, 0x00595a12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e12, 0x005d5e11, 0x006d6612, 0x00c49f17, 0x00cba417, 0x00988114, 0x005b5b12, 0x00595a12, 0x00585910, 0x00585810, 0x00565710, 0x00565711, 0x00555611, 0x00565711, 0x00555611, 0x00555611, 0x00555611, 0x00565710, 0x00585810, 0x00585910, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x00756b13, 0x00c4a018, 0x00cca418, 0x009e8415, 0x005c5d13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x00605c11, 0x00c39c16, 0x00cca216, 0x00917912, 0x004d4e10, 0x004b4c0f, 0x0048490f, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x000f130b, 0x000f130f, 0x000f130f, 0x000b140d, 0x000b140d, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000e140e, 0x000e140e, 0x000d140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140d, 0x000c140c, 0x000c140c, 0x000c150c, 0x000c150c, 0x000c140c, 0x000c140c, 0x000c150c, 0x000c140c, 0x000c140e, 0x000c140e, 0x000c140d, 0x000c130d, 0x000c130d, 0x000e140f, 0x000c140e, 0x000c1710, 0x000e1610, 0x00101710, 0x00131813, 0x00141914, 0x00141914, 0x00151a14, 0x00181a16, 0x001b1c18, 0x001c1c18, 0x001e1c18, 0x001d1e18, 0x001e1e18, 0x001d1e18, 0x001c1e16, 0x001b1d15, 0x00191c14, 0x00181c14, 0x00181b12, 0x00171913, 0x00141711, 0x00121410, 0x00101410, 0x00111610, 0x00111610, 0x0010140e, 0x0010140d, 0x0010140c, 0x0010140c, 0x0012140c, 0x0014140e, 0x0014150e, 0x0014160f, 0x00141610, 0x00151610, 0x00181710, 0x00181710, 0x0014140c, 0x0016140f, 0x0017150e, 0x0018150e, 0x0018140d, 0x0018140d, 0x0016130b, 0x00181209, 0x0017130c, 0x0018140c, 0x0017140c, 0x0017130c, 0x0017130c, 0x0017140d, 0x0017140d, 0x0016140b, 0x0016140b, 0x00161309, 0x00161309, 0x00151308, 0x00141208, 0x00141007, 0x00151108, 0x00151108, 0x00151208, 0x00141308, 0x00141308, 0x0014140a, 0x00131209, 0x00101208, 0x000f1007, 0x000c0e04, 0x000c0e04, 0x000c0e04, 0x000d0f05, 0x000d1006, 0x000e1109, 0x000e1109, 0x000e110b, 0x0010100c, 0x0012100c, 0x0010120a, 0x00101109, 0x0012140a, 0x0014130a, 0x0015140b, 0x0018140b, 0x001c160c, 0x0021180b, 0x00241c0b, 0x00291f09, 0x002e2209, 0x00352708, 0x003d2f0a, 0x0044360c, 0x00503c0f, 0x0064480e, 0x00866414, 0x00c1a433, 0x00ccb421, 0x00ccb80c, 0x00ccb80a, 0x00ccb80c, 0x00cbb80c, 0x00c8b40d, 0x00a48404, 0x00765300, 0x005f4000, 0x004b3704, 0x003d2e04, 0x00392c04, 0x0044380e, 0x003d3007, 0x003c3008, 0x00342c08, 0x00302809, 0x002c250c, 0x0028220b, 0x001c1904, 0x001b1a08, 0x001e1d0f, 0x0017180c, 0x000f1108, 0x000a0f04, 0x00080e05, 0x00090e07, 0x000d0d08, 0x0011100a, 0x0014100b, 0x0014100a, 0x0018110a, 0x00181108, 0x00181107, 0x001a1304, 0x001e1506, 0x001e1505, 0x00201504, 0x00241807, 0x00221404, 0x00271608, 0x00281708, 0x00291807, 0x002a1706, 0x002b1808, 0x002c1708, 0x002d1708, 0x002f1708, 0x002e1805, 0x002d1804, 0x002d1804, 0x002d1804, 0x002e1808, 0x002c1608, 0x0029150a, 0x0027140b, 0x0023140a, 0x00201309, 0x001f1308, 0x001c1207, 0x001a1008, 0x00191008, 0x00170f07, 0x00141007, 0x00110f07, 0x00120e07, 0x00120e07, 0x0016120a, 0x0018140c, 0x0018140b, 0x001a1409, 0x001c1407, 0x00271e08, 0x00362c10, 0x003d3010, 0x00332404, 0x00311e03, 0x0038260a, 0x0044310f, 0x00553910, 0x00704f0f, 0x00ac8b28, 0x00ccaf2a, 0x00ccb416, 0x00ccb70e, 0x00ccb80a, 0x00cbb40d, 0x00b08e0a, 0x007b5400, 0x005e3b00, 0x004b3004, 0x00402b09, 0x00372502, 0x00342005, 0x002e1c05, 0x002b1c06, 0x00281b07, 0x00241806, 0x00201705, 0x001c1204, 0x00191408, 0x00181307, 0x00151308, 0x00141308, 0x00141308, 0x00141308, 0x00141308, 0x00141108, 0x00131008, 0x00131009, 0x00141109, 0x00141108, 0x00110e04, 0x00110e04, 0x00141007, 0x00141307, 0x00141207, 0x00161408, 0x00161408, 0x00141308, 0x00141307, 0x00151408, 0x00161408, 0x00181308, 0x001a1307, 0x001a1305, 0x00191305, 0x00191305, 0x00191306, 0x00191307, 0x00191307, 0x00191208, 0x00191208, 0x00191208, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x00171408, 0x00171408, 0x00181108, 0x00161208, 0x00141208, 0x00141308, 0x00141309, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x00141309, 0x00141309, 0x00141409, 0x00141409, 0x00161309, 0x00161309, 0x001a170d, 0x0018150c, 0x0018150e, 0x0018150e, 0x0018160e, 0x0014140c, 0x0014130c, 0x0012140c, 0x0012140e, 0x000f120c, 0x000a100a, 0x00080f08, 0x0007100a, 0x0006100b, 0x0007110c, 0x0006120c, 0x0006120c, 0x0005130c, 0x0005130c, 0x0004110b, 0x0004110b, 0x0005130c, 0x0005120c, 0x0006110d, 0x0006110d, 0x0006110d, 0x0008130f, 0x000a1511, 0x000a1511, 0x000c1512, 0x000f1714, 0x000f1714, 0x00101912, 0x00101a13, 0x00111b14, 0x00141c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00131914, 0x00111913, 0x00121a14, 0x000f1811, 0x00101812, 0x00111514, 0x00101211, 0x00101412, 0x000f1412, 0x000d1410, 0x000d150f, 0x000c140f, 0x00060c07, 0x000f130f, 0x000f130f, 0x0014180f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x002c2d0b, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c10, 0x004d4e0f, 0x00585510, 0x00b69314, 0x00cca316, 0x00a48814, 0x005b5a12, 0x005b5b12, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5d11, 0x009f8615, 0x00cca417, 0x00c49f17, 0x00736813, 0x00595a12, 0x00595a12, 0x00585910, 0x00585910, 0x00585810, 0x00585810, 0x00565711, 0x00565711, 0x00565710, 0x00585810, 0x00585810, 0x00585911, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x00646112, 0x00b19316, 0x00cca418, 0x00c7a118, 0x00766c14, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x007f7012, 0x00c8a016, 0x00cba216, 0x00786811, 0x004d4e10, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x0030310c, 0x00292b0a, 0x0026280b, 0x0024250b, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x000c140e, 0x000c140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000f150f, 0x000f150f, 0x000d150f, 0x000d150f, 0x000c140e, 0x000c140e, 0x000c140d, 0x000c140c, 0x000c140c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000d140d, 0x000d140d, 0x000e140e, 0x000f150f, 0x000f150f, 0x0010140f, 0x000f1410, 0x00101510, 0x00131713, 0x00141714, 0x00151814, 0x00171814, 0x00171814, 0x00181914, 0x00191a17, 0x001c1c18, 0x001d1c18, 0x001f1e18, 0x001d1e18, 0x001d1f18, 0x001b1d16, 0x001b1d15, 0x001a1d15, 0x00181c13, 0x00171a11, 0x00161910, 0x00161811, 0x00151711, 0x00141610, 0x0012140d, 0x0012160e, 0x00141810, 0x00141710, 0x0014160d, 0x0015150d, 0x0015150d, 0x0017150d, 0x0017150d, 0x0017150e, 0x0017150d, 0x0014130b, 0x0015140b, 0x0016130c, 0x0017140c, 0x0014130b, 0x0015130b, 0x0016140a, 0x0016140b, 0x0016140b, 0x0017140b, 0x0017140a, 0x00151308, 0x0017140b, 0x0018140c, 0x0018140b, 0x0018140b, 0x0018140b, 0x0018140c, 0x0018140c, 0x0017140b, 0x0017140a, 0x00161409, 0x00161409, 0x00151409, 0x00151409, 0x0017130a, 0x0017130a, 0x0017140b, 0x0017130a, 0x00151209, 0x0016130a, 0x0017130a, 0x0016130a, 0x00141208, 0x00111108, 0x000f1006, 0x000f0d04, 0x000f0d05, 0x00111008, 0x00101008, 0x00101209, 0x00101209, 0x0010120a, 0x0010110a, 0x00121109, 0x00121109, 0x00141209, 0x00151309, 0x00161309, 0x0018140a, 0x001a150a, 0x001e1809, 0x00231808, 0x00271a09, 0x002c1e08, 0x00302208, 0x00372708, 0x003e2f09, 0x0044370b, 0x004f3d0c, 0x0064480c, 0x00866414, 0x00bea130, 0x00ccb421, 0x00ccb80c, 0x00cbb80a, 0x00cbb80c, 0x00cbb90d, 0x00c9b60f, 0x00a48604, 0x00765200, 0x005f4000, 0x004a3604, 0x003c2f05, 0x00382c04, 0x0044370f, 0x003b2f06, 0x00352b04, 0x00342c08, 0x0030290c, 0x0029230b, 0x0024210c, 0x001c1a08, 0x00191808, 0x001a1b0c, 0x00131509, 0x000d1107, 0x00090f04, 0x00070e04, 0x00080e05, 0x000c0e07, 0x00100f08, 0x0013100b, 0x0014100a, 0x0016100a, 0x00181108, 0x00181207, 0x00181305, 0x001c1407, 0x001c1405, 0x001e1406, 0x00201508, 0x00211407, 0x00251709, 0x0028180a, 0x00281708, 0x00281708, 0x00281708, 0x00281708, 0x00291708, 0x002b1608, 0x002b1706, 0x002b1706, 0x002c1806, 0x002c1806, 0x002b1708, 0x00291509, 0x00261409, 0x0024130a, 0x0021140a, 0x001e1309, 0x001d1208, 0x001c110a, 0x001b1008, 0x00191008, 0x00170f07, 0x00141008, 0x00120e07, 0x00110f08, 0x00110f08, 0x00141109, 0x0016140a, 0x0018140b, 0x00191408, 0x001c1407, 0x00231b08, 0x00322711, 0x003b2e14, 0x00312408, 0x002f1e03, 0x00382809, 0x0044310c, 0x0052370c, 0x006d4b0c, 0x00ac8a28, 0x00ccb12b, 0x00ccb417, 0x00cbb50f, 0x00cbb60a, 0x00cbb60e, 0x00af8e0a, 0x007a5300, 0x005e3a00, 0x004c2f04, 0x00402b09, 0x00362602, 0x00342005, 0x002f1c07, 0x002c1c08, 0x00291b08, 0x00261808, 0x00221706, 0x00201408, 0x001c1508, 0x001a1407, 0x00181306, 0x00181208, 0x00181208, 0x00171107, 0x00151208, 0x00151208, 0x00141208, 0x00121108, 0x00141308, 0x00151408, 0x00181409, 0x00151206, 0x00151106, 0x00181208, 0x00161005, 0x00171207, 0x00181208, 0x00171208, 0x00181409, 0x00171408, 0x00181508, 0x001b1408, 0x001c1408, 0x001c1405, 0x001c1405, 0x001c1405, 0x001d1405, 0x001d1407, 0x001e1408, 0x001d1408, 0x001c1408, 0x001c1409, 0x001c1408, 0x001d1508, 0x001c1508, 0x001c1608, 0x00181307, 0x00171408, 0x00181108, 0x00171109, 0x00161109, 0x00141108, 0x00141209, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x00141309, 0x00141309, 0x00151008, 0x00171109, 0x00171109, 0x0018120a, 0x0019130b, 0x0019130b, 0x0017140c, 0x0017140c, 0x0019170f, 0x0018160e, 0x0017150f, 0x0017150f, 0x00181710, 0x00181710, 0x00141510, 0x00101510, 0x00101410, 0x000c120d, 0x000b110c, 0x0008100b, 0x0008110b, 0x0006130c, 0x0006130c, 0x0006110a, 0x0006110a, 0x0007110b, 0x0007110b, 0x0006110a, 0x0008120c, 0x0006120b, 0x0006130c, 0x0008140f, 0x000b1510, 0x000b1510, 0x000d1712, 0x000e1812, 0x000f1812, 0x00101a13, 0x00111c14, 0x00131c15, 0x00141c14, 0x00141c14, 0x00161c15, 0x00161c15, 0x00161c15, 0x00161c15, 0x00161c14, 0x00151a14, 0x00131a14, 0x00131914, 0x00101812, 0x00101812, 0x00131714, 0x00111412, 0x00101512, 0x00101411, 0x000d140f, 0x000d150f, 0x000c140e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004c4d0f, 0x004d4e10, 0x00a48714, 0x00cca316, 0x00be9915, 0x00615d12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x00696412, 0x00b99816, 0x00cca417, 0x00b49415, 0x00696312, 0x005b5b12, 0x00595a12, 0x00585911, 0x00585910, 0x00585910, 0x00585910, 0x00585910, 0x00585910, 0x00585911, 0x00595a12, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x00605e12, 0x00a38815, 0x00cca418, 0x00cca418, 0x00a48815, 0x00605f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5c11, 0x005b5b12, 0x00595a11, 0x00a08514, 0x00cca316, 0x00bf9915, 0x00615a10, 0x004d4e0f, 0x00494a0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0036370b, 0x0034350c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x000d150f, 0x000c150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x00101610, 0x00101610, 0x000e150f, 0x000d150f, 0x000d150f, 0x000e1610, 0x000d150f, 0x000d150f, 0x000d150f, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x0010160d, 0x0010160d, 0x00101710, 0x00101710, 0x00101610, 0x00101510, 0x00141613, 0x00151613, 0x00161714, 0x00171814, 0x00171814, 0x00181814, 0x00181814, 0x001a1a15, 0x001c1b17, 0x001e1c17, 0x001f1e18, 0x001f1e18, 0x001f1e18, 0x001e2018, 0x001c1e16, 0x00191c13, 0x00171a10, 0x0017190f, 0x0014170c, 0x0013150d, 0x0014150d, 0x0015150f, 0x0014140d, 0x0013140b, 0x0013140b, 0x0012140b, 0x0014140b, 0x0014140b, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0015130a, 0x0015130a, 0x0014130a, 0x0014130a, 0x00151108, 0x00151108, 0x00141108, 0x00151208, 0x00141308, 0x00161409, 0x00151409, 0x00151409, 0x00151408, 0x00171408, 0x00171409, 0x00181409, 0x00181409, 0x00181408, 0x001a1408, 0x001b1408, 0x00191408, 0x00181408, 0x00181408, 0x00181408, 0x00181409, 0x00181308, 0x00181309, 0x0018130a, 0x0018130a, 0x0018130a, 0x0018130a, 0x00181309, 0x00181109, 0x00181008, 0x00181007, 0x00161208, 0x00141207, 0x00141108, 0x00141108, 0x00141008, 0x00131007, 0x00131108, 0x00131409, 0x00121308, 0x00121308, 0x00131308, 0x00141208, 0x00151108, 0x00181308, 0x00191408, 0x001a1408, 0x001b1409, 0x001e1708, 0x00221808, 0x00261808, 0x002b1a08, 0x002f1e08, 0x00342208, 0x00382709, 0x003e2f09, 0x0044360b, 0x00503c0c, 0x0064480c, 0x00876414, 0x00bca02e, 0x00ccb421, 0x00ccb80c, 0x00cab90a, 0x00cbb90c, 0x00cbba0e, 0x00cab810, 0x00a48805, 0x00745100, 0x00604100, 0x004a3505, 0x003c2f07, 0x00382c04, 0x0042370f, 0x003b2f07, 0x00342803, 0x002e2605, 0x002b2509, 0x00262009, 0x00221f0c, 0x001b1809, 0x00161507, 0x0017180b, 0x00131509, 0x000e1208, 0x000a1006, 0x00070e04, 0x00070e04, 0x000c0e08, 0x00100f08, 0x00100e0a, 0x00101009, 0x00140f09, 0x00141008, 0x00171207, 0x00181205, 0x001a1407, 0x001b1407, 0x001d1408, 0x0020140a, 0x00201409, 0x00241809, 0x0026170a, 0x0027170a, 0x0027170a, 0x00241708, 0x00241708, 0x00261608, 0x00261508, 0x00261607, 0x00261607, 0x00281708, 0x00281809, 0x0028160a, 0x00251409, 0x0023140a, 0x0021140a, 0x0020140a, 0x001d140a, 0x001c120a, 0x001b1008, 0x001a1008, 0x00181008, 0x00161007, 0x00140e08, 0x00110f07, 0x00100f08, 0x00100f08, 0x00131109, 0x00141409, 0x0017140b, 0x00181408, 0x001c1507, 0x00221a0a, 0x002b2010, 0x00342713, 0x0030210a, 0x002f1d04, 0x00382708, 0x00422e0a, 0x0053350b, 0x006e4c0b, 0x00a98823, 0x00caac24, 0x00cbb10f, 0x00cab408, 0x00cbb406, 0x00ccb411, 0x00ae8c0b, 0x00785000, 0x005c3800, 0x004c3004, 0x00412c09, 0x00372703, 0x00342006, 0x00301c07, 0x002f1c08, 0x002c1c08, 0x002b1b08, 0x00251806, 0x00231708, 0x00201609, 0x001c1408, 0x001c1306, 0x001c1306, 0x001b1307, 0x00191108, 0x00181108, 0x00181308, 0x00171408, 0x00141308, 0x00161408, 0x001a170b, 0x001e1a0e, 0x001d180c, 0x001b1509, 0x001d1409, 0x001c1208, 0x001d1409, 0x001d1409, 0x001d1409, 0x001d150a, 0x001d160a, 0x001d1709, 0x00201708, 0x00201706, 0x00201707, 0x00221708, 0x00221708, 0x00241708, 0x00241708, 0x00241808, 0x00241808, 0x00231809, 0x0023180a, 0x00221708, 0x00211707, 0x00211807, 0x00201808, 0x001c1407, 0x001a1409, 0x001a140a, 0x0019120b, 0x00181209, 0x00171109, 0x0017120a, 0x0015130a, 0x0015130a, 0x0014130a, 0x0014130a, 0x0015120a, 0x0016120a, 0x00161109, 0x00161109, 0x0018110a, 0x0018110a, 0x0018110a, 0x0018110a, 0x0016120a, 0x0015140a, 0x0015140b, 0x0016140c, 0x0017140d, 0x0018140d, 0x0018140e, 0x0018150f, 0x00171610, 0x00161812, 0x00161813, 0x00141611, 0x0011140e, 0x0010140d, 0x000f150c, 0x000b140b, 0x00091409, 0x00091208, 0x000a1208, 0x00091108, 0x00091008, 0x00081007, 0x000a1309, 0x00081309, 0x00081409, 0x0008120c, 0x0009140d, 0x000b150f, 0x000c1710, 0x000e1811, 0x000f1812, 0x000f1912, 0x00101b14, 0x00121c14, 0x00141c14, 0x00151c14, 0x00171c15, 0x00181c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00171c14, 0x00151c16, 0x00141b14, 0x00121813, 0x00121813, 0x00141914, 0x00141814, 0x00131713, 0x00111511, 0x00101610, 0x00101710, 0x000f1610, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0041420d, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x004d4e10, 0x00847011, 0x00cba216, 0x00c9a116, 0x00827113, 0x00595a12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x00786e13, 0x00c19c17, 0x00cca417, 0x00b09115, 0x006c6412, 0x00595a12, 0x005b5b12, 0x00595a12, 0x00595a12, 0x00595a12, 0x00595a12, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x005c5c12, 0x005b5b11, 0x00646112, 0x00a38815, 0x00caa418, 0x00cca418, 0x00b89717, 0x006b6513, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x005b5b12, 0x00615d11, 0x00be9916, 0x00cca316, 0x00a88914, 0x00505010, 0x004c4d0f, 0x00494a0f, 0x0045470e, 0x0041420e, 0x003c3e0c, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x001d200a, 0x00191c0b, 0x0014180b, 0x000f130d, 0x000f130f, 0x000f130f, 0x000e150f, 0x000e150f, 0x00101610, 0x00101610, 0x00101610, 0x00101610, 0x00101611, 0x00101711, 0x00101610, 0x000f1610, 0x000f1710, 0x00101811, 0x00101711, 0x000f1610, 0x000f1710, 0x00101811, 0x00101811, 0x00101811, 0x00101811, 0x000f1610, 0x000f1610, 0x00101710, 0x00101710, 0x00101710, 0x00101710, 0x00101710, 0x00111610, 0x00161813, 0x00181814, 0x00181814, 0x00181713, 0x001a1813, 0x001c1a14, 0x001c1b14, 0x001c1c16, 0x001d1c14, 0x001d1d15, 0x001e1d15, 0x001d1c14, 0x001c1c14, 0x00181911, 0x00161810, 0x0016180e, 0x0016180e, 0x0015170d, 0x0014150c, 0x0014140c, 0x0014120c, 0x0014120c, 0x0014120c, 0x0014130a, 0x0013130a, 0x0014140a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x00141109, 0x00141107, 0x00141107, 0x00141108, 0x00151208, 0x00151308, 0x00161409, 0x0017140a, 0x00181309, 0x00181408, 0x00181408, 0x001a1408, 0x001b1408, 0x001b1408, 0x001c1407, 0x001c1408, 0x001d1508, 0x001c1406, 0x001c1405, 0x001c1405, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1308, 0x001c1309, 0x001c130a, 0x001c130a, 0x001c130a, 0x001c140b, 0x001c140b, 0x001e150a, 0x001d150a, 0x001b1409, 0x00191509, 0x001b160b, 0x001b160c, 0x001b160c, 0x00181409, 0x00141006, 0x00151408, 0x00151408, 0x00141408, 0x00151408, 0x00171408, 0x00181308, 0x001a1308, 0x001b1408, 0x001d1508, 0x001d1508, 0x00201708, 0x00241a08, 0x00281908, 0x002d1c08, 0x00311f08, 0x00362308, 0x003b2808, 0x00402e09, 0x0047340b, 0x00513a0a, 0x0064460b, 0x00846312, 0x00bca02e, 0x00ccb421, 0x00ccb80c, 0x00cab90a, 0x00cab80c, 0x00caba0d, 0x00c9b810, 0x00a68908, 0x00745200, 0x005e4000, 0x004a3406, 0x003c2c06, 0x00362a04, 0x0040350e, 0x003c3109, 0x00332904, 0x002a2103, 0x00251f06, 0x00241f0a, 0x00201d0e, 0x0018180c, 0x00131407, 0x00111408, 0x0012160c, 0x000e1409, 0x000a1007, 0x00060f04, 0x00070f04, 0x000b0e08, 0x000f1009, 0x0010100b, 0x00101109, 0x00121009, 0x00141008, 0x00151206, 0x00171305, 0x00191306, 0x001b1407, 0x001c1408, 0x001c1308, 0x001d1308, 0x00201508, 0x00231608, 0x00241508, 0x00241508, 0x00211508, 0x00231408, 0x00241408, 0x00241408, 0x00241407, 0x00241406, 0x00251608, 0x00261708, 0x00241408, 0x00211308, 0x00201409, 0x001f1409, 0x001c1309, 0x001b1309, 0x001a1108, 0x00191008, 0x00181008, 0x00161008, 0x00140f07, 0x00120f07, 0x00100f08, 0x000f0f07, 0x000f0f07, 0x00121309, 0x00131408, 0x0015140a, 0x00171407, 0x001a1507, 0x00201909, 0x00261c0c, 0x002a1c0b, 0x002e2009, 0x002e1c05, 0x0037260a, 0x00402b09, 0x0052340b, 0x00684506, 0x00ab8726, 0x00ccac28, 0x00cbb012, 0x00ccb10c, 0x00cbb00b, 0x00cbac1c, 0x00a9810e, 0x00764c01, 0x00593600, 0x004c3004, 0x00412c0a, 0x003a2804, 0x00382107, 0x00341e06, 0x00301c05, 0x002f1c06, 0x002d1c07, 0x00291906, 0x00271808, 0x00241809, 0x00211608, 0x00201407, 0x00201408, 0x00201407, 0x001c1306, 0x001a1207, 0x00191308, 0x00181407, 0x00171306, 0x00191408, 0x001d180c, 0x00231c0f, 0x00231b0f, 0x0021190c, 0x0024180c, 0x0024180b, 0x0025180c, 0x0027190c, 0x0026190c, 0x00271a0c, 0x00281b0c, 0x00281b0a, 0x00281a08, 0x00281a0a, 0x00281b0b, 0x002a1b0c, 0x00291a09, 0x002a1a09, 0x002a1a09, 0x002b1b09, 0x002b1b09, 0x002a1b0b, 0x002a1b0b, 0x00281a0a, 0x00271808, 0x00241906, 0x00231807, 0x00201708, 0x001e1708, 0x001d150a, 0x001c130a, 0x001a1309, 0x00181208, 0x00181109, 0x0018110a, 0x0017120a, 0x0017120a, 0x0016120a, 0x0016120a, 0x0016120a, 0x0016120a, 0x00141008, 0x00151008, 0x00151008, 0x00151109, 0x00141109, 0x00141008, 0x00131008, 0x00141109, 0x00141109, 0x0014120b, 0x0014120c, 0x0014120b, 0x0014130c, 0x0016140f, 0x00161510, 0x0014140f, 0x0014140e, 0x0014140e, 0x0016160f, 0x0015180f, 0x0014180e, 0x0010160c, 0x0010140b, 0x0010140b, 0x000e1309, 0x000c1108, 0x000c1007, 0x000d1208, 0x000c1308, 0x000a1308, 0x000a130b, 0x000a130c, 0x0009130c, 0x000b140d, 0x000c170f, 0x000d1810, 0x000e1810, 0x000f1911, 0x00111b13, 0x00141b13, 0x00161c14, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00161c17, 0x00161c17, 0x00141a14, 0x00141a14, 0x00161b15, 0x00141914, 0x00141914, 0x00141813, 0x00121712, 0x00121812, 0x00111711, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004d4e10, 0x00605911, 0x00c09a14, 0x00cca316, 0x00ae8e14, 0x005c5b12, 0x005c5c12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x007c7013, 0x00bf9b17, 0x00cca417, 0x00bc9916, 0x00847413, 0x00605d12, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005c5c12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x00786d13, 0x00b39317, 0x00cca418, 0x00cca418, 0x00bb9917, 0x00736a14, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5c12, 0x00595a12, 0x00887512, 0x00caa116, 0x00caa016, 0x007c6c11, 0x004d4e10, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0036370c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x000f130f, 0x00101610, 0x00101610, 0x00101710, 0x00101710, 0x00101710, 0x00101710, 0x00111611, 0x00121611, 0x00111711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00111711, 0x00111711, 0x00121812, 0x00121812, 0x00121810, 0x00121810, 0x00121810, 0x00121810, 0x00131910, 0x00151910, 0x00171810, 0x00191810, 0x00191810, 0x00191710, 0x001b1811, 0x001c1912, 0x001b1811, 0x00191810, 0x0018180f, 0x0018170e, 0x0018170e, 0x0018150c, 0x00141309, 0x00111309, 0x00111309, 0x00131309, 0x00141209, 0x00141209, 0x00141209, 0x0014100a, 0x00131009, 0x0013100a, 0x0013100a, 0x00111008, 0x00121108, 0x00121108, 0x00131109, 0x00141209, 0x0014130a, 0x0014130a, 0x0013120a, 0x0013120a, 0x0013120a, 0x0013120a, 0x00131209, 0x00131209, 0x00141208, 0x00141208, 0x00141207, 0x00151308, 0x00181309, 0x00181309, 0x001a140b, 0x001a140a, 0x001c140a, 0x001d1609, 0x001e160a, 0x0020160a, 0x00201609, 0x00201708, 0x00201708, 0x00201809, 0x00201808, 0x00221807, 0x00221807, 0x00241808, 0x00241809, 0x00241809, 0x00241809, 0x0024180c, 0x0024180c, 0x0024180c, 0x0024180c, 0x0024180d, 0x0024190e, 0x0025190e, 0x0023180c, 0x0021180c, 0x00211a0d, 0x00201a0f, 0x0020190e, 0x001f190e, 0x001b1409, 0x00181206, 0x00171508, 0x00171508, 0x00161407, 0x00171407, 0x001a150a, 0x001c140a, 0x001d1509, 0x001e1708, 0x0020180a, 0x00201809, 0x00241a09, 0x00281c08, 0x002c1c09, 0x00311e0a, 0x00352109, 0x003b2508, 0x0040290b, 0x00452f0c, 0x004a340c, 0x0054390a, 0x00644409, 0x00805e0d, 0x00ba9c2c, 0x00ccb421, 0x00ccb80c, 0x00cab90a, 0x00cab80c, 0x00c8b90c, 0x00c9b810, 0x00a88b09, 0x00755200, 0x005c3d00, 0x004b3407, 0x003a2a04, 0x00302400, 0x003d310a, 0x003d330a, 0x00342b08, 0x002c2207, 0x00241e08, 0x00201a08, 0x001b190b, 0x0014150b, 0x00101207, 0x000e1308, 0x0010150c, 0x000c1209, 0x00091006, 0x00071005, 0x00080f05, 0x00090d06, 0x000c0f07, 0x0010100b, 0x00101109, 0x0012110a, 0x00131008, 0x00151307, 0x00151305, 0x00181406, 0x001a1407, 0x001b1407, 0x001c1307, 0x001c1306, 0x001c1407, 0x00201408, 0x00201308, 0x00201308, 0x001e1307, 0x001f1207, 0x00211308, 0x00221208, 0x00201307, 0x00201406, 0x00221408, 0x00211407, 0x00211408, 0x001f1308, 0x001d1309, 0x001c1408, 0x00191308, 0x00191208, 0x00181208, 0x00181008, 0x00171008, 0x00151008, 0x00130f08, 0x00100f07, 0x00100f08, 0x000d0f05, 0x000d0f05, 0x00101308, 0x00111308, 0x00141208, 0x00161306, 0x00181306, 0x001c1408, 0x0022170b, 0x0027190b, 0x002c1d0a, 0x002e1c06, 0x00352405, 0x00402c06, 0x004e300a, 0x00644008, 0x00a27b28, 0x00c49e2c, 0x00c2a019, 0x00bf9f14, 0x00be9b13, 0x00c2941d, 0x009c6d0c, 0x006e4201, 0x00563400, 0x00493106, 0x00432e0b, 0x003d2907, 0x003b2208, 0x00382008, 0x00341e06, 0x00301c05, 0x00301c05, 0x002e1b06, 0x002b1908, 0x00281909, 0x00251808, 0x00251707, 0x00251607, 0x00241707, 0x00221508, 0x00201408, 0x001f150a, 0x001d160a, 0x001a1407, 0x00181206, 0x001b1305, 0x001d1407, 0x001e1508, 0x001e1406, 0x00231608, 0x00251808, 0x00251807, 0x00291a0b, 0x002c1c0c, 0x002e1c0c, 0x002f1d0b, 0x002f1d0a, 0x00301e0a, 0x00311e0b, 0x00321e0d, 0x00311e0c, 0x00301c08, 0x00301c08, 0x00311c09, 0x00321d0a, 0x00311d0a, 0x00301d0b, 0x00301d0c, 0x002e1c09, 0x002c1b08, 0x00291a07, 0x00281b08, 0x00271b08, 0x00241908, 0x00201608, 0x001d1408, 0x001e150b, 0x001c140a, 0x001a1208, 0x001a1208, 0x00191208, 0x0018120a, 0x0018130a, 0x0017130b, 0x0017130b, 0x0016130b, 0x00141008, 0x00111008, 0x00121008, 0x00121008, 0x00131009, 0x00131009, 0x00131009, 0x00131009, 0x00131009, 0x0013120b, 0x0013120b, 0x0012110a, 0x0013120b, 0x0013120a, 0x0012110a, 0x0013120b, 0x0013120a, 0x0014110a, 0x00141209, 0x0015140b, 0x0013140a, 0x0013140a, 0x0013140a, 0x0013140a, 0x0014140b, 0x0013140a, 0x0013140a, 0x0013140a, 0x0012150a, 0x00101409, 0x000d150b, 0x000c150c, 0x000c140c, 0x000c150c, 0x000c170d, 0x000e1810, 0x000f1910, 0x000e1810, 0x00121a11, 0x00151a11, 0x00171c12, 0x00191c14, 0x00191c14, 0x001b1c16, 0x00181c16, 0x00191c16, 0x00181d16, 0x00161c17, 0x00161c17, 0x00151c15, 0x00151c15, 0x00161b14, 0x00151a14, 0x00151a14, 0x00141813, 0x00131712, 0x00131712, 0x00131712, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280c, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x00494a0f, 0x004c4d0f, 0x00505010, 0x009e8213, 0x00cca316, 0x00c8a015, 0x007b6d12, 0x00595a12, 0x005c5c12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x00736a13, 0x00b49415, 0x00cba417, 0x00c9a318, 0x00b19216, 0x00897714, 0x00686212, 0x00605d11, 0x00605d12, 0x00605e12, 0x00636012, 0x007c7013, 0x00a68916, 0x00c6a118, 0x00cca418, 0x00cba418, 0x00b39317, 0x00706813, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5d12, 0x005b5b12, 0x00605c11, 0x00b49314, 0x00cca316, 0x00b69314, 0x00595510, 0x004d4e0f, 0x00494a10, 0x0045470e, 0x0043440e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0b, 0x00292b0a, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x00101711, 0x00101711, 0x00121812, 0x00121812, 0x00121812, 0x00111812, 0x00131712, 0x00121712, 0x00111611, 0x00111611, 0x00111611, 0x00121712, 0x00121712, 0x00111712, 0x00121712, 0x00121712, 0x00131712, 0x00141712, 0x00121611, 0x00141812, 0x00141812, 0x00141811, 0x00141811, 0x00141810, 0x00141810, 0x00161810, 0x00161810, 0x0016180e, 0x0017170e, 0x0018160e, 0x0018160e, 0x0017150c, 0x0016140c, 0x0016140b, 0x0016140b, 0x0015140b, 0x0018170e, 0x0018170e, 0x0016140b, 0x00131308, 0x00101208, 0x00101208, 0x00101006, 0x00121006, 0x00121008, 0x00131008, 0x00141009, 0x00130f08, 0x00130f09, 0x00111009, 0x00111008, 0x00111008, 0x00111108, 0x00131109, 0x0014120a, 0x0014120a, 0x0014120c, 0x0013120c, 0x0014120c, 0x0014120b, 0x0014130c, 0x0014130c, 0x0014130b, 0x00171108, 0x00181208, 0x00171005, 0x00181207, 0x00191208, 0x001a1209, 0x001b130a, 0x001c1308, 0x00201509, 0x00241609, 0x0024170b, 0x0024180b, 0x0024180a, 0x0025180b, 0x0026190c, 0x00271a0c, 0x00271b0a, 0x00281c08, 0x00281c08, 0x002a1c0a, 0x002a1c0a, 0x002a1c0a, 0x00281b09, 0x00271a0a, 0x00271a0a, 0x00271b0a, 0x00261a09, 0x00261a09, 0x00251a09, 0x0024190c, 0x0020180c, 0x001c1509, 0x001a1508, 0x00191508, 0x00181406, 0x00191407, 0x00191406, 0x001b1407, 0x001a1408, 0x001a1407, 0x00191407, 0x001a1407, 0x001d170a, 0x001f1709, 0x00201708, 0x00231808, 0x00241c09, 0x00241c08, 0x00271d09, 0x002c200a, 0x002f2008, 0x00342008, 0x00382408, 0x003e2706, 0x00442b0a, 0x0048300c, 0x004f350c, 0x00573a0b, 0x0064430a, 0x007c590d, 0x00b8992d, 0x00ccb423, 0x00ccb810, 0x00c9b80c, 0x00cab80c, 0x00c8ba0a, 0x00cbba11, 0x00ab8e0b, 0x00745400, 0x005b3e00, 0x00493204, 0x003b2a05, 0x002e2100, 0x00382c0a, 0x00392e0c, 0x0033280b, 0x002c240b, 0x00241c08, 0x001b1706, 0x00181609, 0x00111409, 0x000e1207, 0x000d1208, 0x000d140a, 0x000c1208, 0x00080f05, 0x00080e04, 0x00080e04, 0x00090d04, 0x00080c03, 0x000c0e06, 0x000c0f06, 0x00100f08, 0x00120f07, 0x00151108, 0x00171207, 0x00181407, 0x00191307, 0x00191307, 0x001b1307, 0x001b1207, 0x001b1207, 0x001c1308, 0x001c1107, 0x001c1107, 0x001c1207, 0x001c1107, 0x001e1108, 0x001e1108, 0x001e1108, 0x001e1108, 0x001e1107, 0x001d1107, 0x001e1408, 0x001c1308, 0x001b1409, 0x00191408, 0x00181308, 0x00181209, 0x00181108, 0x00171008, 0x00161008, 0x00130f08, 0x00110f07, 0x000f0e05, 0x000f0e06, 0x000c0f04, 0x000c1005, 0x000e1007, 0x00101207, 0x00131208, 0x00161208, 0x00181308, 0x00191308, 0x0020170b, 0x0025180a, 0x002a1b08, 0x002c1b05, 0x00352204, 0x00402a04, 0x004b2d09, 0x005b370a, 0x00724b08, 0x0088600b, 0x008a6102, 0x008b6303, 0x008b5f00, 0x00845300, 0x00754700, 0x005f3400, 0x00573406, 0x004a3008, 0x00442e0a, 0x00402a08, 0x003c2408, 0x00392207, 0x00361f06, 0x00341e06, 0x00321d04, 0x00311c05, 0x002e1c07, 0x002b1b07, 0x00281906, 0x00271804, 0x00271804, 0x00261804, 0x00261707, 0x00241809, 0x0024180b, 0x0023190b, 0x0020160a, 0x001c1406, 0x001b1204, 0x001c1104, 0x001c1305, 0x001c1304, 0x001d1101, 0x00201301, 0x00241404, 0x00271706, 0x002c1b08, 0x002f1c08, 0x00301d09, 0x0034200b, 0x0038220c, 0x0039230d, 0x003a230d, 0x003a230c, 0x0039210b, 0x003a210a, 0x0039210a, 0x00382009, 0x00382009, 0x00372009, 0x00352009, 0x00332009, 0x002f1f08, 0x002c1d07, 0x002b1c08, 0x002c1c08, 0x00291b08, 0x00261908, 0x00231608, 0x0022170a, 0x0022170b, 0x001f1408, 0x001d1206, 0x001c1108, 0x001a1208, 0x0019130a, 0x0017130b, 0x0016140b, 0x0014130a, 0x00111008, 0x00131209, 0x0014110a, 0x0012110a, 0x0012110a, 0x0013100a, 0x0013100a, 0x0012110a, 0x0012110a, 0x0013110b, 0x0013110b, 0x0012110a, 0x00101009, 0x00101008, 0x00121109, 0x0014120a, 0x00141109, 0x00141109, 0x00141008, 0x00131108, 0x00131108, 0x00121108, 0x00121108, 0x00121108, 0x00131208, 0x00141409, 0x0017140a, 0x0016140a, 0x0016150b, 0x0014150a, 0x0012160c, 0x0012170e, 0x0012180e, 0x0013180f, 0x00121810, 0x00121911, 0x00101810, 0x00101810, 0x00141911, 0x00181b12, 0x00191a12, 0x001a1b14, 0x001b1c14, 0x001b1c16, 0x00181b14, 0x001a1d17, 0x00191e17, 0x00161c17, 0x00161c17, 0x00151c15, 0x00151c15, 0x00161b14, 0x00151b14, 0x00141a13, 0x00141912, 0x00131812, 0x00131813, 0x00141813, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x001d200a, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x00393b0d, 0x003c3e0c, 0x0041420d, 0x0044450d, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00685f10, 0x00c39c15, 0x00cca316, 0x00b09014, 0x005e5c11, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x00636012, 0x00958014, 0x00c09d16, 0x00cba417, 0x00caa317, 0x00c6a117, 0x00bb9816, 0x00b49415, 0x00b69515, 0x00c19d17, 0x00c8a218, 0x00cca418, 0x00cba418, 0x00c19c18, 0x00978014, 0x00646213, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5c12, 0x00585912, 0x00887413, 0x00caa116, 0x00caa116, 0x00847012, 0x004f5010, 0x004c4d0f, 0x0048490f, 0x0045470e, 0x0041420e, 0x003e400c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x00292b0a, 0x0026280c, 0x0020230a, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00111812, 0x00111812, 0x00131812, 0x00131812, 0x00131812, 0x00131712, 0x00131812, 0x00131812, 0x00141813, 0x00141813, 0x00141814, 0x00141914, 0x00141a14, 0x00131914, 0x00141914, 0x00161814, 0x00171814, 0x00171711, 0x00151610, 0x0014150f, 0x0014150f, 0x0014140f, 0x0015140f, 0x0015140d, 0x0015140e, 0x0015150c, 0x0015150c, 0x0014140b, 0x0014140b, 0x0017150c, 0x0017150d, 0x0015140b, 0x0014130a, 0x0014120a, 0x00141109, 0x00141109, 0x0014130a, 0x0014130a, 0x00131209, 0x00101208, 0x00101108, 0x00101108, 0x00101008, 0x00101008, 0x00111008, 0x00121008, 0x00141109, 0x00110e07, 0x00101009, 0x00101009, 0x000f1008, 0x00101008, 0x00101008, 0x00101109, 0x0014100a, 0x0015100b, 0x0015100b, 0x0016100c, 0x0014120c, 0x0014120c, 0x0015120c, 0x0015120d, 0x0016120c, 0x001c1009, 0x001c1107, 0x001d1206, 0x001f1408, 0x00201408, 0x0020160b, 0x0023160b, 0x0024180b, 0x0026180a, 0x0027180a, 0x0029190b, 0x002b1b0c, 0x002c1c0c, 0x002c1c0f, 0x002d1d0e, 0x002e1d0d, 0x002d1e0b, 0x002d1c08, 0x002d1c08, 0x002d1e09, 0x002c1d08, 0x002b1c08, 0x00291a08, 0x00271805, 0x00251804, 0x00241704, 0x00201400, 0x001e1300, 0x001e1300, 0x001c1406, 0x001b1508, 0x00181507, 0x00161506, 0x00141505, 0x00151404, 0x00171304, 0x001c1404, 0x00201607, 0x00211708, 0x00211708, 0x00201605, 0x00201706, 0x00241908, 0x00281b0b, 0x00281a09, 0x002a1c08, 0x00281c06, 0x00281d05, 0x002c1f05, 0x00302008, 0x00332307, 0x00382506, 0x003b2704, 0x00402a04, 0x00442d06, 0x00482f08, 0x0050350c, 0x00583b0b, 0x0062420c, 0x00795510, 0x00b4902c, 0x00ccb228, 0x00ccb717, 0x00ccb610, 0x00ccb70c, 0x00c9b908, 0x00cab810, 0x00ae910d, 0x00725100, 0x00563a00, 0x00452d00, 0x00382802, 0x002d1e00, 0x00342509, 0x00362a10, 0x0030250c, 0x0029210a, 0x00211c09, 0x001e1909, 0x00181709, 0x00101207, 0x000e1105, 0x000e1208, 0x000f1308, 0x000e1007, 0x000b0e04, 0x000a0d03, 0x000a0d03, 0x000b0c02, 0x000b0c02, 0x000c0d04, 0x000e0f05, 0x00140f08, 0x00140e08, 0x00140e08, 0x00161009, 0x00181109, 0x00181006, 0x00171006, 0x00181006, 0x00181107, 0x001a1108, 0x001a1108, 0x00191007, 0x001a1007, 0x001b1007, 0x001b1007, 0x001c1108, 0x001b1108, 0x001b1108, 0x001b1108, 0x001a1108, 0x00191007, 0x00181107, 0x00181105, 0x00191306, 0x00191306, 0x00181108, 0x00181009, 0x00161008, 0x00151008, 0x00141008, 0x00120e07, 0x00110e06, 0x00100d05, 0x000f0d05, 0x000f0d05, 0x00100f05, 0x00101005, 0x00121108, 0x00131108, 0x00161108, 0x0019120c, 0x001a130b, 0x001f1508, 0x00241808, 0x00281a06, 0x00301c05, 0x00362004, 0x00402707, 0x004b2f09, 0x00523309, 0x005b3806, 0x00633c04, 0x00684005, 0x006b3f04, 0x006c4002, 0x00683c00, 0x00613b01, 0x00583502, 0x00543204, 0x004e3108, 0x00482d07, 0x00452c09, 0x0041290a, 0x003c2509, 0x00392209, 0x00382309, 0x00372108, 0x00341f07, 0x00321e05, 0x00301c05, 0x00301c05, 0x002d1c04, 0x002d1b05, 0x002c1b05, 0x002d1c08, 0x002e1d0c, 0x002e1d0d, 0x002e1d0d, 0x002b1d0d, 0x00271b0a, 0x00241807, 0x00231706, 0x00211407, 0x00211504, 0x00201401, 0x00221403, 0x00241504, 0x00281808, 0x002a1807, 0x002e1c08, 0x002e1c06, 0x00311d07, 0x00372008, 0x003c230c, 0x003e250a, 0x0040270b, 0x0042280d, 0x0042280d, 0x0042280f, 0x0042280e, 0x0040280d, 0x0040270b, 0x003d280c, 0x003c270e, 0x0038260f, 0x0033230a, 0x00302006, 0x00301e04, 0x00311c05, 0x002d1c08, 0x00281a08, 0x00271809, 0x0026180a, 0x00241608, 0x00211406, 0x001e1205, 0x001d1206, 0x001b1208, 0x00181309, 0x00161409, 0x0013140a, 0x00121108, 0x0013120a, 0x0013120b, 0x0012110a, 0x0012110a, 0x0012110a, 0x0012110a, 0x0012110a, 0x0012110a, 0x0013100a, 0x0013100a, 0x0013100a, 0x00121009, 0x00111009, 0x00101009, 0x00101009, 0x00111009, 0x00121009, 0x00131008, 0x00121008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00141109, 0x00161008, 0x00151108, 0x00151208, 0x00141308, 0x0016130b, 0x0016140b, 0x0016150c, 0x0016160d, 0x0017160f, 0x00181710, 0x0017160f, 0x0016160f, 0x00181710, 0x001c1910, 0x001c1910, 0x001a1811, 0x001a1710, 0x00191811, 0x001a1913, 0x001c1d18, 0x001b1e18, 0x00181d16, 0x00171d16, 0x00161c15, 0x00161c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00141b14, 0x00131a14, 0x00121a14, 0x00131b14, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x00515110, 0x00947c13, 0x00caa216, 0x00caa216, 0x00917c13, 0x00585912, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5d11, 0x006b6412, 0x00957f14, 0x00b59516, 0x00c7a117, 0x00cba418, 0x00cca418, 0x00cba418, 0x00cba418, 0x00c39e18, 0x00b19316, 0x00947f15, 0x006b6513, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5c12, 0x005b5b12, 0x00666011, 0x00bc9815, 0x00cca316, 0x00b08f14, 0x00565410, 0x004d4e10, 0x00494a0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0024250b, 0x00202309, 0x001d2008, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x00060c07, 0x00131914, 0x00131914, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00141a14, 0x00141a14, 0x00131914, 0x00141914, 0x00171813, 0x00171812, 0x00161510, 0x0014130d, 0x0014130c, 0x0014110b, 0x0014110b, 0x0014110b, 0x0014110b, 0x0014110b, 0x00141109, 0x00141109, 0x00121108, 0x00121108, 0x0014140b, 0x0015140c, 0x0013120a, 0x00101008, 0x00111008, 0x00121009, 0x00121009, 0x00121009, 0x00101009, 0x00101008, 0x00101108, 0x000f1007, 0x000f1007, 0x00101009, 0x00101009, 0x00100f08, 0x000f0e07, 0x0012110a, 0x000f1008, 0x000d1008, 0x000d1008, 0x000f1008, 0x00101008, 0x00121008, 0x00131008, 0x00141109, 0x0017100b, 0x00171009, 0x00181009, 0x0018110a, 0x0018110a, 0x0018130a, 0x0019140a, 0x001a130a, 0x001f1308, 0x001f1307, 0x00241808, 0x0028190a, 0x0028190a, 0x0029190b, 0x002a1a0c, 0x002c1b0b, 0x002c1b0b, 0x002d1c0c, 0x002e1d0b, 0x00301e0c, 0x00301f0d, 0x00301f0d, 0x0031200e, 0x0032200e, 0x00311f0a, 0x00301d06, 0x002f1c05, 0x002f1e08, 0x002d1d07, 0x002c1c06, 0x002b1a06, 0x00281805, 0x00281806, 0x00281808, 0x00241705, 0x00241506, 0x00221405, 0x00201404, 0x001f1506, 0x001d1606, 0x001d1807, 0x001c1805, 0x001f1906, 0x00231b08, 0x00271b08, 0x002b1c09, 0x002c1d0a, 0x002c1d0a, 0x002c1c08, 0x002c1c08, 0x002c1c08, 0x002c1c08, 0x002d1b06, 0x00301d04, 0x00302006, 0x00302104, 0x00342205, 0x00362508, 0x003b2a0d, 0x003e2d0d, 0x0041300c, 0x0046330c, 0x0048340d, 0x004a3610, 0x00503910, 0x00563c0c, 0x0061410e, 0x00784e10, 0x00a3791f, 0x00c8a126, 0x00c9a714, 0x00ccaa11, 0x00cbac0d, 0x00cbaf10, 0x00ccb018, 0x00ad8c14, 0x00704e00, 0x00553701, 0x00422800, 0x00362402, 0x002a1b00, 0x00312307, 0x0033270d, 0x002f240c, 0x0028200a, 0x00201b08, 0x001d1909, 0x00171608, 0x00121207, 0x00101106, 0x00101106, 0x00101106, 0x00101108, 0x000d0f05, 0x000e0f05, 0x000f0f06, 0x000f0d04, 0x000f0d04, 0x000e0d04, 0x00100f05, 0x00121008, 0x00140f08, 0x00120e06, 0x00140f08, 0x00141008, 0x00141007, 0x00141008, 0x00151108, 0x00151108, 0x00151108, 0x00151108, 0x00141007, 0x00141007, 0x00151007, 0x00151007, 0x00171008, 0x00171008, 0x00161008, 0x00151109, 0x00151009, 0x00141008, 0x00171108, 0x00181108, 0x00181209, 0x00181309, 0x00171109, 0x00171009, 0x00151008, 0x00141008, 0x00140f08, 0x00140f08, 0x00140f08, 0x00121008, 0x00121008, 0x00140f08, 0x00131008, 0x00131006, 0x00131107, 0x00151208, 0x00181108, 0x001c140c, 0x001c130c, 0x001e1508, 0x00241804, 0x002c1b05, 0x00352008, 0x0040280b, 0x004c310e, 0x004e3008, 0x00543407, 0x00593605, 0x005c3804, 0x005e3905, 0x005f3804, 0x00603804, 0x00603804, 0x005e3804, 0x00583504, 0x00543204, 0x00523206, 0x004d2e04, 0x00482c05, 0x00462d08, 0x00422a0c, 0x003f280b, 0x003f280c, 0x003d260c, 0x003c240b, 0x003a2309, 0x00392108, 0x00382108, 0x00372007, 0x00372007, 0x00342005, 0x00341f05, 0x00341e08, 0x00341d0a, 0x00341f0b, 0x00341f0a, 0x0032200a, 0x0030200b, 0x002f200c, 0x002d1c08, 0x002d1c07, 0x002c1b05, 0x002c1c06, 0x002c1904, 0x002f1c06, 0x002d1b04, 0x00301c04, 0x00331f05, 0x00372106, 0x00382306, 0x003b2408, 0x003d2707, 0x00402808, 0x00412b0a, 0x00412b0a, 0x00422c0c, 0x00432c0d, 0x00452c0c, 0x00462a0b, 0x0045290c, 0x0044290e, 0x0040290f, 0x00402b10, 0x003e290d, 0x003b250a, 0x00382409, 0x0033210a, 0x002e1d09, 0x002c1b0a, 0x002c190b, 0x00291809, 0x00261607, 0x00211404, 0x001f1304, 0x001d1306, 0x001a1208, 0x00191408, 0x0018140a, 0x00141308, 0x00141109, 0x00141109, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x00121009, 0x00121009, 0x00111009, 0x00101009, 0x00101009, 0x00101009, 0x00111009, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00140f08, 0x00140f08, 0x00131008, 0x00121108, 0x00141109, 0x00141109, 0x00141109, 0x0014120a, 0x0016110b, 0x0017120c, 0x0018130d, 0x001a140f, 0x001b140f, 0x001c140e, 0x001d150f, 0x001b1410, 0x0017100b, 0x0014130c, 0x00191812, 0x001b1c17, 0x001b1d17, 0x00181d16, 0x00181e17, 0x00171d16, 0x00171d16, 0x00151c16, 0x00151c15, 0x00151c15, 0x00151c15, 0x00131b14, 0x00121a14, 0x00131b14, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x0048490f, 0x004b4c0f, 0x004d4e10, 0x00595510, 0x00b79414, 0x00cca316, 0x00c39c15, 0x00786b12, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005c5d11, 0x00636011, 0x00706713, 0x00847413, 0x008d7a14, 0x00887714, 0x00786e13, 0x006c6514, 0x00626013, 0x005d5e13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5c11, 0x005b5b12, 0x005b5a11, 0x00a48714, 0x00cca316, 0x00c49d15, 0x00706410, 0x004f5010, 0x004b4c0f, 0x0048490f, 0x0045470e, 0x0041420e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0020230a, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00151a14, 0x00191c16, 0x00181712, 0x0013110b, 0x00110f08, 0x00141209, 0x00131008, 0x00151109, 0x00151109, 0x00151009, 0x00140f08, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00111008, 0x00101007, 0x00101008, 0x00110f08, 0x00110f08, 0x00121009, 0x00101009, 0x00101008, 0x00101108, 0x00101108, 0x00101108, 0x00101008, 0x00101008, 0x00100f08, 0x0012110a, 0x00121009, 0x00101009, 0x0010120a, 0x000f120a, 0x00131109, 0x00151109, 0x0018110a, 0x0018110a, 0x0018120a, 0x0018130a, 0x001b130a, 0x001c1309, 0x001e140b, 0x001e140b, 0x001f150b, 0x0023180d, 0x00241a0e, 0x00291c10, 0x002a1c0d, 0x002b1c0b, 0x002c1c08, 0x002d1c08, 0x002d1c08, 0x00301c0a, 0x00301c0a, 0x002f1c08, 0x00301c0a, 0x00301d09, 0x00301e09, 0x00301e09, 0x00301e09, 0x00301e07, 0x00301f07, 0x00321e06, 0x00321e04, 0x00321e04, 0x00322005, 0x00301f04, 0x00301e03, 0x002f1d02, 0x002f1e05, 0x002e1e06, 0x002e1e07, 0x002d1e08, 0x002c1d08, 0x002b1c08, 0x002a1b08, 0x00291c08, 0x00271c08, 0x00281e09, 0x002a210b, 0x002c210c, 0x002d2009, 0x002f1f09, 0x00301e08, 0x00342009, 0x0035210b, 0x0036230a, 0x0036220c, 0x0038240d, 0x0038230c, 0x0039230b, 0x003c2509, 0x003c2809, 0x003c2808, 0x003c2808, 0x00402a0c, 0x00422c0f, 0x00452f11, 0x00493110, 0x004a330f, 0x004d3610, 0x0050390f, 0x00543c0e, 0x0059400c, 0x0065440d, 0x00754809, 0x00885706, 0x00a06d07, 0x00a87803, 0x00af7c02, 0x00b18304, 0x00b28809, 0x00b38914, 0x00946e0e, 0x00664000, 0x00543404, 0x00422800, 0x003a2806, 0x002d1e01, 0x00302206, 0x002d2008, 0x002b2007, 0x00241c07, 0x001e1907, 0x001c1809, 0x00181509, 0x0015150b, 0x00141408, 0x00141409, 0x00141409, 0x0014130a, 0x0014130a, 0x00131209, 0x00131209, 0x00141109, 0x00141109, 0x0014130a, 0x00141109, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00111008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00101007, 0x00101007, 0x000f0f05, 0x000f0f05, 0x00100e05, 0x00110f07, 0x00121008, 0x00111008, 0x00101009, 0x00101009, 0x00101009, 0x00101009, 0x00140f08, 0x00140e08, 0x00151008, 0x00151008, 0x00151008, 0x00151008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00141109, 0x00151109, 0x00181108, 0x00181309, 0x00171408, 0x001a160b, 0x001a160a, 0x001e150a, 0x0020170c, 0x00241910, 0x00281d0c, 0x002a1d07, 0x002e1c04, 0x00412b10, 0x005b3d19, 0x00654519, 0x006a4816, 0x006c4711, 0x006f450e, 0x00724510, 0x00714610, 0x006c4410, 0x0068420d, 0x0064400b, 0x00603c08, 0x005c3704, 0x005b3704, 0x00583504, 0x00543204, 0x004f3004, 0x004c3007, 0x004b3008, 0x00472e07, 0x00462d08, 0x00462d08, 0x00462c09, 0x00432b0b, 0x00432b0b, 0x00452b0c, 0x00452b0c, 0x00462a0c, 0x00442809, 0x00422609, 0x0041250b, 0x0041240d, 0x0041250c, 0x003e240a, 0x003a2208, 0x00392409, 0x00382409, 0x00392308, 0x003a2308, 0x003a2308, 0x003b2409, 0x003c240a, 0x003d240c, 0x003c250b, 0x003c2609, 0x003f2708, 0x003f2707, 0x00412805, 0x00452c07, 0x004b3008, 0x0050340b, 0x0053360c, 0x0054360d, 0x0054360d, 0x0053350c, 0x00513109, 0x00513008, 0x004d2d06, 0x004c2d09, 0x00492d0c, 0x0045290d, 0x0043280d, 0x0041290d, 0x003d280b, 0x003a270c, 0x0038240e, 0x0034200d, 0x00301c0d, 0x002f1c0b, 0x002e1b09, 0x002a1908, 0x00251808, 0x0024180a, 0x0021160b, 0x001b1206, 0x00191208, 0x00181308, 0x00171209, 0x00161208, 0x0016120a, 0x0016120a, 0x00161209, 0x00151009, 0x00141008, 0x00141008, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0012110a, 0x0012110a, 0x0011110a, 0x00101009, 0x00111009, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00140f09, 0x00121009, 0x00101009, 0x00101009, 0x00101008, 0x00121008, 0x00141008, 0x00151109, 0x00161009, 0x0018110a, 0x0018110a, 0x001a120c, 0x001c140d, 0x001c130d, 0x001c120c, 0x0018100b, 0x00130c07, 0x0014120c, 0x001b1b14, 0x00191b14, 0x001b1e18, 0x001a2018, 0x00181f17, 0x00171d16, 0x00171d16, 0x00181e18, 0x00171d18, 0x00161c17, 0x00161c17, 0x00141c15, 0x00141c15, 0x00141c15, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x00141810, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a0f, 0x004c4d0f, 0x004f5010, 0x00726511, 0x00c39c15, 0x00cca316, 0x00b99615, 0x006a6312, 0x00595a12, 0x005b5b12, 0x005b5b11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x005c5c12, 0x005b5b12, 0x00585811, 0x008f7913, 0x00c9a116, 0x00c9a116, 0x00907812, 0x00505010, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0034350c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x000f130b, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00151a13, 0x00151a13, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00161a13, 0x00191b14, 0x0013120b, 0x000f0e07, 0x00100e05, 0x00100e05, 0x00131008, 0x00151109, 0x00151109, 0x00151009, 0x00140f08, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00110f07, 0x00100e05, 0x00100f05, 0x000f0f05, 0x00100f07, 0x00110f08, 0x00121009, 0x00121009, 0x00101009, 0x00101008, 0x00101108, 0x00101108, 0x00101008, 0x00101006, 0x00111006, 0x00131008, 0x00110f07, 0x00140d07, 0x00140f08, 0x0015120a, 0x0015130c, 0x0018120b, 0x001a120c, 0x001c130d, 0x001c130c, 0x001d140c, 0x001e140b, 0x0020160b, 0x0024180e, 0x0024190e, 0x00241a0d, 0x00251b0e, 0x00281a0c, 0x00291b0d, 0x00291b0d, 0x002a1b0c, 0x002b1909, 0x002c1906, 0x002c1a05, 0x002e1c06, 0x00301c06, 0x00321c06, 0x00301c05, 0x00311c06, 0x00331d08, 0x00352008, 0x00372108, 0x00382308, 0x00392408, 0x003a2608, 0x003b2608, 0x003b2608, 0x003c2708, 0x003c2809, 0x003c2807, 0x003b2706, 0x003a2605, 0x00382604, 0x00392605, 0x00382807, 0x00382709, 0x0036270a, 0x0035250b, 0x0035240a, 0x0036240c, 0x0032220a, 0x0032240c, 0x0033240c, 0x00322309, 0x00342209, 0x00352208, 0x00372108, 0x00392208, 0x003a2308, 0x003c2509, 0x003d280c, 0x003f280e, 0x00412910, 0x00432a0f, 0x00442c0d, 0x00452f0c, 0x00452f0b, 0x00462f0a, 0x004a300c, 0x004c330d, 0x0051350c, 0x0054380c, 0x0058390b, 0x005a3c0c, 0x005c3f0c, 0x0062430c, 0x0068480c, 0x00744f0f, 0x0082530c, 0x008a5504, 0x00975f04, 0x009a6401, 0x009d6201, 0x00945c00, 0x008d5800, 0x00865400, 0x00724800, 0x00603c08, 0x00503104, 0x00442c04, 0x003d2b0b, 0x00312005, 0x002f2006, 0x002b1d06, 0x002a1e08, 0x00241c08, 0x001f1808, 0x001d1809, 0x001a1609, 0x0018140b, 0x00171309, 0x0019160c, 0x0019150c, 0x0016120a, 0x0016120a, 0x00151109, 0x00151109, 0x00141008, 0x00141008, 0x00151109, 0x00141008, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00111008, 0x00101008, 0x00101008, 0x00101008, 0x00101108, 0x000f1008, 0x000f1008, 0x000c1007, 0x000d0f05, 0x000d0f05, 0x000f1007, 0x00101008, 0x00101108, 0x00101009, 0x00101009, 0x00101009, 0x00101009, 0x00110f08, 0x00120e08, 0x00140f09, 0x00140f09, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00131008, 0x00131008, 0x00141008, 0x00151109, 0x00161108, 0x00181309, 0x0019140b, 0x00191408, 0x001c150a, 0x001e1708, 0x00211608, 0x00241809, 0x00271b0d, 0x00291d0b, 0x002e1e07, 0x00342006, 0x00543b1c, 0x006d491e, 0x00724813, 0x00805418, 0x00845613, 0x0088550f, 0x008e5712, 0x008e5816, 0x008b5818, 0x00835518, 0x007a5314, 0x00765012, 0x00754c10, 0x006e450b, 0x00684008, 0x00623d08, 0x005a3805, 0x00583908, 0x00593908, 0x00573807, 0x00543504, 0x00543606, 0x0051350b, 0x004f340c, 0x004c310b, 0x004c300a, 0x004c300a, 0x004c300a, 0x004a2d08, 0x00482b0a, 0x0047290a, 0x0044270a, 0x0045280c, 0x0044280c, 0x0042280b, 0x0042280c, 0x0041280b, 0x00402609, 0x00412709, 0x00412709, 0x0043280c, 0x00452a0d, 0x00482c10, 0x004a2e0e, 0x004c2f0e, 0x0050310e, 0x00553511, 0x005e3c13, 0x00664312, 0x006c4715, 0x00744c18, 0x00784e1a, 0x00784e18, 0x00784e1a, 0x00784c18, 0x00744914, 0x006f4610, 0x006a430f, 0x00613d0d, 0x00553407, 0x004b2907, 0x00452705, 0x00402606, 0x003c2507, 0x00382306, 0x00372209, 0x0038230f, 0x0034200d, 0x00331f0a, 0x0033200b, 0x002e1d0b, 0x002a1b0a, 0x00291b0c, 0x0027190d, 0x00211509, 0x00201609, 0x0020170b, 0x001c140c, 0x001b130b, 0x001b130b, 0x001b130b, 0x0019130a, 0x00181209, 0x00151008, 0x00151008, 0x00141008, 0x00141008, 0x0014100a, 0x0013100a, 0x0013100a, 0x00101009, 0x00111109, 0x00101009, 0x00121009, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00131008, 0x00121009, 0x00101009, 0x00100f08, 0x00100f08, 0x00101008, 0x00101008, 0x00141008, 0x00151009, 0x00151108, 0x00161208, 0x0016130a, 0x0017120a, 0x0018130b, 0x0018120b, 0x0017120b, 0x00120d07, 0x000e0904, 0x00100f08, 0x00161810, 0x00191c15, 0x001b1f18, 0x00192018, 0x00181f17, 0x00181f17, 0x00181f17, 0x00181f18, 0x00171d18, 0x00161c17, 0x00161c17, 0x00151c16, 0x00151c15, 0x00151c15, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180c, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0041420d, 0x0044450e, 0x0048490f, 0x004b4c10, 0x004d4e0f, 0x004f4f10, 0x008b7512, 0x00c8a015, 0x00cca316, 0x00b39115, 0x00656011, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005d5e12, 0x005e5f13, 0x005d5e12, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5c12, 0x005b5b12, 0x00585811, 0x00867413, 0x00c59f15, 0x00cba216, 0x00a48614, 0x00535210, 0x004d4e0f, 0x004b4c10, 0x0048490f, 0x0044450e, 0x0041420e, 0x003e400c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a13, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00181a14, 0x00191a14, 0x0011120c, 0x000e0f07, 0x000c1007, 0x000c0f06, 0x000e1006, 0x00141109, 0x00151109, 0x00141008, 0x00141008, 0x00121006, 0x00121006, 0x00121006, 0x00121006, 0x00111007, 0x00110f06, 0x00110f07, 0x00130f08, 0x00121008, 0x00131008, 0x00131008, 0x00141209, 0x00121008, 0x00131107, 0x00131107, 0x00131208, 0x00131207, 0x00151307, 0x00141005, 0x00161006, 0x00191007, 0x00191007, 0x001a1108, 0x001e150c, 0x0020160f, 0x001e140d, 0x0021150e, 0x00231710, 0x00241610, 0x0024180e, 0x0025190d, 0x00261a0d, 0x0023160a, 0x0021180a, 0x00201708, 0x001f1607, 0x00211507, 0x00221608, 0x00211405, 0x00241405, 0x00271604, 0x002b1907, 0x00291a06, 0x002c1d08, 0x00301d08, 0x00342006, 0x00372206, 0x003b2609, 0x003e260c, 0x0043280e, 0x00462b0c, 0x00462c0a, 0x0048310a, 0x004a3308, 0x004b3308, 0x004b3308, 0x004c340a, 0x004c340c, 0x004c340b, 0x004d340b, 0x004d340c, 0x004e340c, 0x004b310b, 0x0049320d, 0x0044300c, 0x0041300c, 0x0040300c, 0x00402d0c, 0x0040290c, 0x003e270c, 0x003e260d, 0x003d240c, 0x003d250b, 0x003f250c, 0x0040250a, 0x00402609, 0x003f2708, 0x003f2708, 0x00422a09, 0x00442c0b, 0x00442c0c, 0x00482e11, 0x00452b0c, 0x004a300c, 0x004f340d, 0x004f350c, 0x0051370b, 0x00573b0c, 0x005c3c0c, 0x005e3b07, 0x00654009, 0x006c440a, 0x006e450a, 0x0074490c, 0x00794f0c, 0x007e540c, 0x008b5f11, 0x009b6912, 0x00a57416, 0x00af8017, 0x00bc8c1f, 0x00c08823, 0x00996109, 0x00824e04, 0x00784e04, 0x00633e00, 0x00553709, 0x00483205, 0x00403008, 0x003b2808, 0x00342207, 0x002e1e08, 0x00281b09, 0x0026190a, 0x00221809, 0x001f170a, 0x001d170a, 0x001a1509, 0x00191408, 0x00181309, 0x0018110a, 0x0018110a, 0x0018110a, 0x0018110a, 0x0017100b, 0x0017100b, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x0014100a, 0x0013100a, 0x00121009, 0x00121009, 0x00110f08, 0x00110e0a, 0x00110e0a, 0x00110e0a, 0x00110e0a, 0x00110d0a, 0x00100e0a, 0x000d0d08, 0x000c0d08, 0x000e0d06, 0x000f0e07, 0x00110f08, 0x00110f08, 0x00110f08, 0x00100f08, 0x00140f09, 0x00140f09, 0x00120f0b, 0x00120f0b, 0x0013100c, 0x0013100a, 0x00121109, 0x00121108, 0x00121108, 0x0013120a, 0x0014120b, 0x0014110b, 0x0014110a, 0x00141208, 0x00161208, 0x00181308, 0x00181308, 0x00191207, 0x001c1608, 0x00201608, 0x00221606, 0x00251706, 0x00291a08, 0x002c1d0c, 0x00311f0a, 0x003d2407, 0x00604016, 0x00744c17, 0x00845617, 0x00a77829, 0x00b38224, 0x00af7d1b, 0x00ac7716, 0x00a87314, 0x00a16c10, 0x009f6810, 0x0099630f, 0x00945d0d, 0x00905a11, 0x0088530c, 0x0085540c, 0x007c4e08, 0x00754908, 0x00714608, 0x006f440a, 0x006c410a, 0x0067400a, 0x0065400c, 0x00613f0d, 0x005b390a, 0x0058360a, 0x0058360c, 0x0057350a, 0x00543307, 0x00513306, 0x00503208, 0x00503208, 0x004b3108, 0x004a310b, 0x00462f0b, 0x00442c0a, 0x00472c0b, 0x00482c0c, 0x00492c0c, 0x00492d0f, 0x00492e10, 0x00492f0e, 0x004d300e, 0x00523410, 0x0054370c, 0x005b3d0c, 0x00694814, 0x006e4a14, 0x00785013, 0x00835412, 0x008a5915, 0x00935f19, 0x0099651b, 0x00986616, 0x00946413, 0x00936212, 0x00905f0f, 0x008e5a0c, 0x0088560e, 0x00815211, 0x00794c12, 0x006e400f, 0x005d3608, 0x004c2c05, 0x00402804, 0x003c2404, 0x00382208, 0x00341e08, 0x00301c05, 0x00301c04, 0x002e1c04, 0x002c1c07, 0x002b1c08, 0x002b1c0c, 0x00291c0e, 0x0025180c, 0x0024180e, 0x0024180e, 0x0022180e, 0x0021150c, 0x0021150c, 0x0020140c, 0x001e140b, 0x001c1409, 0x001b1309, 0x001a1208, 0x00181108, 0x00181108, 0x00181209, 0x00171009, 0x00141008, 0x00141008, 0x00140f08, 0x0014100a, 0x0014100a, 0x00140f09, 0x00140f09, 0x0014100a, 0x00141008, 0x00140f08, 0x00141006, 0x00141007, 0x00141007, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00130f09, 0x00140f09, 0x0014100b, 0x0015110a, 0x0017130a, 0x00171309, 0x0017140a, 0x0018140c, 0x0018140c, 0x00140f08, 0x000f0c04, 0x000c0c04, 0x000b0c04, 0x000c0e06, 0x0013150d, 0x00171c15, 0x00182017, 0x00192018, 0x00182018, 0x00192018, 0x00181f17, 0x00181f15, 0x00181f15, 0x00181f15, 0x00181f15, 0x00181e15, 0x00191e15, 0x00191e15, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x004d4e10, 0x00515110, 0x00967d12, 0x00c9a116, 0x00cca316, 0x00b29115, 0x006a6211, 0x00585912, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5c11, 0x005c5c12, 0x00595a12, 0x00585911, 0x00887513, 0x00c49e16, 0x00cca316, 0x00ac8b14, 0x00595510, 0x004d4e10, 0x004c4d0f, 0x0048490f, 0x0045470e, 0x0043440e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002d2f0b, 0x00292b0b, 0x0026280c, 0x0020230a, 0x00202308, 0x00191c08, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00151a11, 0x00151a11, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a13, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00181a14, 0x00191a14, 0x0011120c, 0x000d0f07, 0x000c1007, 0x000c0f06, 0x000c0f06, 0x0011110a, 0x0014110b, 0x00131008, 0x00121008, 0x00121008, 0x00121008, 0x00141006, 0x00141006, 0x00120f05, 0x00120f05, 0x00141006, 0x00161008, 0x00161007, 0x00151007, 0x00151007, 0x00151007, 0x00140f04, 0x00151005, 0x00151005, 0x00181206, 0x00181306, 0x00191408, 0x001e170b, 0x0021160a, 0x0022170b, 0x0020180b, 0x0020190c, 0x00221b0f, 0x0020190d, 0x0020190d, 0x0020180c, 0x001d150b, 0x001d140a, 0x001e1509, 0x001d1408, 0x001c1204, 0x001b1104, 0x001a1104, 0x00181202, 0x001a1203, 0x001c1203, 0x001e1204, 0x00231404, 0x00271804, 0x002b1906, 0x002f1c07, 0x00302008, 0x00332408, 0x003b280c, 0x003f2b0c, 0x00442f0c, 0x004a320e, 0x004e330f, 0x00533510, 0x00593810, 0x005c3c11, 0x00603f13, 0x00604010, 0x0061420d, 0x0061430b, 0x0062430b, 0x0060420a, 0x0060420b, 0x0061400c, 0x00613f0d, 0x005f3c0d, 0x005a390c, 0x0056370d, 0x0050340d, 0x004c340e, 0x004c340f, 0x004a330e, 0x0048300c, 0x00462c0c, 0x00452c0f, 0x00442a0e, 0x00442a0c, 0x00442a0c, 0x00442a0c, 0x00452c0b, 0x00452c09, 0x00452c08, 0x00482e0a, 0x004b300c, 0x004a300b, 0x004f330d, 0x0054340e, 0x00573810, 0x00593b13, 0x005a3c11, 0x00603f13, 0x00654212, 0x00704711, 0x0072470b, 0x007b4f0d, 0x0081540e, 0x0087590d, 0x00926414, 0x009c6f19, 0x00a6791f, 0x00b58c26, 0x00c39b25, 0x00c8a227, 0x00caa421, 0x00ccaa23, 0x00caa120, 0x009e7007, 0x007c4d00, 0x006c4600, 0x005f3f02, 0x00503407, 0x00443004, 0x003e2c07, 0x00372406, 0x00332108, 0x002e1c08, 0x00291b09, 0x00241809, 0x00211609, 0x001d1508, 0x001b1508, 0x001a1508, 0x00191409, 0x00181309, 0x0018110a, 0x0018110a, 0x0018110a, 0x0018110a, 0x0017100b, 0x0017100b, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x0014100a, 0x0013100a, 0x00121009, 0x00121009, 0x00110e0b, 0x00110e0c, 0x00110e0c, 0x00110e0c, 0x00110e0b, 0x00120d0a, 0x00110e0a, 0x000e0d08, 0x000c0d08, 0x000e0d06, 0x000f0e07, 0x00110f08, 0x00110f08, 0x00110f08, 0x00110f08, 0x00140f09, 0x00140f09, 0x00120f0b, 0x00120f0b, 0x0013100a, 0x00131009, 0x00121108, 0x00121108, 0x00121108, 0x0013120a, 0x0013110b, 0x0013100a, 0x00141109, 0x00141208, 0x00161307, 0x00181308, 0x00181308, 0x00191206, 0x001d1608, 0x00211609, 0x00241708, 0x00281808, 0x002c1c09, 0x002d1c0c, 0x0034200b, 0x00412709, 0x00644418, 0x00774f13, 0x008c6214, 0x00b8902d, 0x00cba32c, 0x00caa422, 0x00c99f1c, 0x00c89b1c, 0x00c5971b, 0x00c3921b, 0x00bd8c19, 0x00b88418, 0x00b07b16, 0x00a87312, 0x009d6a0b, 0x00976408, 0x00925f0a, 0x008e5c0c, 0x008b5a10, 0x00885710, 0x00855411, 0x00835414, 0x00805416, 0x007b5014, 0x00744b12, 0x00744912, 0x00714711, 0x006b430c, 0x00664008, 0x00603a04, 0x005b3803, 0x00543401, 0x00543604, 0x00523507, 0x00503308, 0x0050300b, 0x0051300c, 0x0052300d, 0x00502f0c, 0x0051320d, 0x0052330c, 0x005a3810, 0x005f3c10, 0x0068430c, 0x00734c0c, 0x00805911, 0x008c6416, 0x009c7118, 0x00aa7e1b, 0x00b48721, 0x00bb8d25, 0x00c29528, 0x00c19927, 0x00bd9724, 0x00bd9724, 0x00bc9423, 0x00b8841b, 0x00ad7a16, 0x009e6a10, 0x00915f0d, 0x0086560d, 0x00784d0d, 0x00674109, 0x00583707, 0x004b2c07, 0x00422509, 0x003a200a, 0x00301c05, 0x002c1a01, 0x002a1901, 0x00281804, 0x00261804, 0x00241706, 0x00231708, 0x0021180b, 0x0020180c, 0x0020180e, 0x0020180e, 0x00221a10, 0x00221a10, 0x0021180e, 0x0020160c, 0x0020150c, 0x0021180f, 0x0020170d, 0x001f150c, 0x001f150c, 0x001f160c, 0x001d140b, 0x001a1308, 0x001a1208, 0x00181208, 0x00181209, 0x00181209, 0x00181008, 0x00150f07, 0x00151008, 0x00161008, 0x00171008, 0x00171008, 0x00161007, 0x00151007, 0x00131008, 0x00121008, 0x00121008, 0x00121008, 0x00140f08, 0x00140f08, 0x0016120a, 0x0017130a, 0x00161208, 0x00181408, 0x001a160c, 0x00161209, 0x00120e06, 0x000f0d04, 0x000c0c03, 0x000b0c04, 0x00090c04, 0x000b0e05, 0x000e1109, 0x00171d16, 0x00182018, 0x00181e17, 0x001a2018, 0x001a2119, 0x00181f17, 0x00181f15, 0x00181f15, 0x00181f15, 0x00181f15, 0x00181e15, 0x00191e15, 0x00191e15, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0b, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003c3e0d, 0x0040400d, 0x0043440e, 0x0045470e, 0x00494a10, 0x004c4d0f, 0x004d4e10, 0x00525110, 0x00987e12, 0x00c8a016, 0x00cca316, 0x00b99615, 0x00786b12, 0x00585810, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5c11, 0x005c5d12, 0x005c5c12, 0x005b5b12, 0x00585912, 0x005e5c11, 0x00988013, 0x00c7a015, 0x00cba216, 0x00ac8b14, 0x005c5810, 0x004d4e10, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0043440e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x0024250c, 0x00202308, 0x001d2008, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00181b12, 0x00181b12, 0x00181a14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161b14, 0x00171c14, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00161711, 0x0011130b, 0x000f1008, 0x000d1008, 0x000b0e05, 0x000a0e05, 0x000d0e06, 0x00101009, 0x00141109, 0x00131107, 0x00131008, 0x00131008, 0x00131107, 0x00151308, 0x00181308, 0x00181208, 0x00191208, 0x001a1208, 0x001a1208, 0x001a1208, 0x001b1208, 0x001d140a, 0x001d140a, 0x001e1409, 0x001f1509, 0x001f170b, 0x0020190d, 0x00201a0c, 0x00201a0d, 0x0022180c, 0x00201509, 0x001c1508, 0x001c1608, 0x00191507, 0x00181406, 0x00171305, 0x00161104, 0x00141104, 0x00141104, 0x00151003, 0x00171002, 0x00181003, 0x001c1507, 0x00191404, 0x001b1605, 0x00201708, 0x0023180a, 0x00241808, 0x002a1c09, 0x00301e0a, 0x0034200a, 0x00382309, 0x003d280b, 0x00452f0e, 0x004a320d, 0x0050340f, 0x0057390c, 0x005d3c0c, 0x0064400c, 0x006b440c, 0x0072480d, 0x007a4e11, 0x00805415, 0x00835814, 0x00855a13, 0x00865c0f, 0x00865c0f, 0x00865c0f, 0x0083590c, 0x007f5708, 0x007b5308, 0x0079500a, 0x00714806, 0x006b430c, 0x00623c09, 0x005e3a0c, 0x0058370c, 0x0053360b, 0x004f340a, 0x004c320b, 0x004c320c, 0x004a300d, 0x00482f0d, 0x00482f0c, 0x004b300c, 0x004d330d, 0x004d330c, 0x004e330a, 0x0050340b, 0x0052360a, 0x00563709, 0x005c390c, 0x005f3b0c, 0x00643c0e, 0x00653f10, 0x00694310, 0x0070480e, 0x0078500f, 0x00845613, 0x008c5d13, 0x00986815, 0x00a4761a, 0x00b1851f, 0x00bb9121, 0x00c39b25, 0x00c9a429, 0x00ccaa24, 0x00ccad1b, 0x00ccb018, 0x00ccb215, 0x00ccb313, 0x00caac16, 0x00a17c04, 0x007d5300, 0x006e4803, 0x00593c00, 0x004c3305, 0x00442f04, 0x003d2804, 0x00362204, 0x00311f08, 0x002d1c08, 0x002a1908, 0x0027180b, 0x00211608, 0x001c1408, 0x001b1408, 0x00191407, 0x00181308, 0x00181108, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x0017100b, 0x0017100b, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x0015100b, 0x0015100b, 0x0014100a, 0x0014100a, 0x0014100c, 0x00120f0c, 0x00120f0c, 0x00120f0c, 0x00130f0c, 0x00140f0b, 0x00120f0b, 0x000f0e09, 0x000b0c06, 0x00100f08, 0x00100f08, 0x00121009, 0x00121009, 0x00140f0b, 0x00140f0b, 0x00140f0b, 0x00140f0b, 0x00110e0a, 0x00110f08, 0x00110f08, 0x00131108, 0x00131108, 0x00121108, 0x00111008, 0x00101008, 0x00111009, 0x00131008, 0x00131008, 0x00131107, 0x00171408, 0x00181107, 0x00181107, 0x001a1306, 0x001c1408, 0x00201408, 0x00241708, 0x00281808, 0x002c1c09, 0x002d1e0c, 0x00342009, 0x00422708, 0x00644418, 0x00795010, 0x00926710, 0x00bf9a26, 0x00ccad1f, 0x00ccb316, 0x00ccb011, 0x00ccae13, 0x00ccac14, 0x00ccaa16, 0x00cca819, 0x00cca61b, 0x00cba31e, 0x00c59c1c, 0x00c3991c, 0x00be9319, 0x00bb8c1a, 0x00b38216, 0x00ab7a14, 0x00a47311, 0x009f6c0e, 0x00a06a10, 0x009b6610, 0x0094600e, 0x00915d0f, 0x00905b10, 0x008d5810, 0x0088540e, 0x0083500a, 0x00804f0a, 0x007a4c0a, 0x0072490a, 0x006e470a, 0x00674107, 0x00623d06, 0x0060380c, 0x0060370c, 0x005e350b, 0x005c350a, 0x005c3708, 0x0064400e, 0x006d4512, 0x00744913, 0x0080530d, 0x00916410, 0x00a77d19, 0x00ba9322, 0x00c59f22, 0x00caa620, 0x00cca920, 0x00ccaa1e, 0x00ccac1d, 0x00ccaf1c, 0x00ccb01d, 0x00ccb01c, 0x00ccaf1c, 0x00cca81a, 0x00c9a019, 0x00c69a1d, 0x00b88a15, 0x00a67611, 0x00926309, 0x00885a0e, 0x00784c09, 0x00643c0a, 0x00532e09, 0x0046290a, 0x003b2407, 0x00332004, 0x002c1a02, 0x00281802, 0x00241602, 0x001f1201, 0x001b1102, 0x001a1104, 0x00161004, 0x00141005, 0x00141105, 0x00141206, 0x00171408, 0x0018160a, 0x001b140a, 0x001c140a, 0x001f160c, 0x0020180e, 0x0021180d, 0x0022180c, 0x0021180c, 0x0023180d, 0x0022180c, 0x0021160a, 0x00201509, 0x001e150a, 0x001c1308, 0x001c1308, 0x00191106, 0x00181206, 0x00181206, 0x00181008, 0x00181008, 0x00181107, 0x00171006, 0x00141007, 0x00141007, 0x00141007, 0x00141007, 0x00141008, 0x00141008, 0x0016120a, 0x00171309, 0x00181409, 0x00181408, 0x00171308, 0x00130f05, 0x000f0c04, 0x000d0c05, 0x000c0d05, 0x000b0e05, 0x000b0d07, 0x000b0d07, 0x000c0e08, 0x00161b14, 0x00161d15, 0x00181f17, 0x001a2018, 0x001a2119, 0x00181f17, 0x00171e14, 0x00182016, 0x00182016, 0x00182016, 0x00191f15, 0x00191e15, 0x00191e15, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0040400d, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x004d4e10, 0x00505010, 0x008f7812, 0x00c49e15, 0x00cca316, 0x00c49e16, 0x00947c14, 0x00605c10, 0x00585911, 0x00595a12, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5c11, 0x005c5c11, 0x005b5b12, 0x005b5b12, 0x00595a12, 0x00595911, 0x00756911, 0x00b09015, 0x00cba216, 0x00c9a116, 0x00a48614, 0x00585510, 0x004d4e10, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450e, 0x0041420d, 0x003e400c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0020230a, 0x001d2008, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181b12, 0x00181b12, 0x00181a14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161b14, 0x00161c14, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181b14, 0x00141510, 0x00101009, 0x000f1008, 0x000d1008, 0x000c0e08, 0x000a0d07, 0x000b0c04, 0x00100f08, 0x0017140c, 0x00151309, 0x00151308, 0x00151308, 0x00151308, 0x00181609, 0x001c1509, 0x001d1408, 0x0020150b, 0x0022170c, 0x0022170c, 0x0022170c, 0x0022170c, 0x0024180d, 0x0024180d, 0x0024180f, 0x0024180e, 0x0020140c, 0x001f150c, 0x001a170b, 0x001a170b, 0x00181309, 0x00181108, 0x00140e04, 0x00130f04, 0x00110f03, 0x00121004, 0x00141405, 0x00131304, 0x00141404, 0x00141504, 0x00151504, 0x00191404, 0x00191505, 0x001f1a09, 0x00201a09, 0x00211c09, 0x00241c0a, 0x002b200f, 0x002c200f, 0x0033230e, 0x0034220c, 0x003c280f, 0x00412910, 0x00492d0c, 0x0052340e, 0x005c3a11, 0x00643c11, 0x006b410a, 0x00754a0a, 0x00845811, 0x00906417, 0x009c6f16, 0x00aa7c19, 0x00b78924, 0x00bc9127, 0x00c09428, 0x00c09525, 0x00c09625, 0x00c09725, 0x00bc9421, 0x00b89020, 0x00b68c23, 0x00a67c1b, 0x0094690e, 0x00895f10, 0x007a500a, 0x0070470b, 0x00673f09, 0x005c3c0a, 0x0056390a, 0x0053370a, 0x0052370c, 0x0050350c, 0x004e340c, 0x004e340c, 0x0050340c, 0x0054370c, 0x0054380b, 0x0055380a, 0x005a3c0c, 0x005d3d0c, 0x00623f08, 0x00684009, 0x0070460c, 0x0073490e, 0x00784f0e, 0x00845912, 0x008c610e, 0x00996f13, 0x00a77c18, 0x00b48a1f, 0x00be951f, 0x00c8a220, 0x00ccaa20, 0x00ccac1e, 0x00ccb01c, 0x00ccb318, 0x00ccb314, 0x00ccb410, 0x00ccb50f, 0x00cbb60c, 0x00cbb70d, 0x00cab316, 0x00a38104, 0x007c5400, 0x006d4804, 0x00563900, 0x00493004, 0x00422c04, 0x003c2403, 0x00352005, 0x00301d06, 0x002b1908, 0x00281807, 0x00241608, 0x00201407, 0x001b1306, 0x001a1407, 0x00191407, 0x00181308, 0x00181108, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x0017100b, 0x0017100b, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x0017100b, 0x0017100b, 0x00150f0a, 0x00150f0a, 0x0014100a, 0x00130f0a, 0x00120e09, 0x00130f0a, 0x00130f0a, 0x00140f0b, 0x0012100b, 0x0011100b, 0x000c0d08, 0x0013120b, 0x0012110a, 0x00121009, 0x00121009, 0x00140f0b, 0x00140f0b, 0x00140f0b, 0x00140f0b, 0x00120f08, 0x00110e08, 0x00131007, 0x00131006, 0x00121008, 0x00121008, 0x00121008, 0x00111008, 0x00121008, 0x00131008, 0x00131008, 0x00131107, 0x00161307, 0x00181107, 0x00181107, 0x001a1306, 0x001c1408, 0x00201408, 0x00241608, 0x00291909, 0x002d1c0a, 0x002e1c0a, 0x00362009, 0x00432808, 0x00654518, 0x00805013, 0x00996810, 0x00c29a22, 0x00cbae16, 0x00ccb40c, 0x00cab30a, 0x00c9b20c, 0x00c9b20e, 0x00cab20f, 0x00cab110, 0x00cab114, 0x00cbb018, 0x00c9b01a, 0x00cab019, 0x00cbae1b, 0x00cca91d, 0x00c8a51d, 0x00c9a420, 0x00c79d1d, 0x00c4981b, 0x00c09018, 0x00be8a19, 0x00b98419, 0x00b37c15, 0x00af7714, 0x00aa7115, 0x00a36b15, 0x009c6510, 0x0098600e, 0x00935e0e, 0x00895c10, 0x00865810, 0x00825510, 0x007c5211, 0x00784b17, 0x00774a18, 0x00734615, 0x00704613, 0x006d440e, 0x006f450d, 0x00754a0f, 0x00885a1b, 0x00a07420, 0x00bd922b, 0x00c9a42c, 0x00ccad21, 0x00ccb116, 0x00ccb50f, 0x00cbb60d, 0x00cbb80d, 0x00c9b80d, 0x00cab710, 0x00cbb510, 0x00cbb511, 0x00cab510, 0x00cab40c, 0x00ccb411, 0x00ccb018, 0x00ccac1c, 0x00c89c1f, 0x00b98c1b, 0x00a07110, 0x008b5c09, 0x00805210, 0x0068400b, 0x0054340a, 0x00442c06, 0x003a2505, 0x00332208, 0x002e1f07, 0x00271a04, 0x00241705, 0x001e1404, 0x001c1405, 0x00181104, 0x00141105, 0x00101003, 0x000c0d00, 0x000d0f01, 0x000d0f02, 0x00101003, 0x00101003, 0x00101103, 0x00141407, 0x001c1408, 0x001f1309, 0x00201409, 0x0021170a, 0x0024180b, 0x0026180b, 0x0025190b, 0x0024190b, 0x00211709, 0x00211609, 0x001f1408, 0x001f1409, 0x001f150a, 0x001c1308, 0x001a1106, 0x00191006, 0x00191007, 0x00181106, 0x00181206, 0x00181106, 0x00171107, 0x00161208, 0x00161208, 0x00181309, 0x0018140a, 0x00191409, 0x00181408, 0x00161308, 0x00130f06, 0x000e0d04, 0x000c0d05, 0x000b0e05, 0x000b0e05, 0x000a0d07, 0x000c0e08, 0x000c0f08, 0x00161b14, 0x00151d15, 0x00181f17, 0x00182018, 0x00192018, 0x00181f17, 0x00171e14, 0x00182016, 0x00182016, 0x00182016, 0x00191e15, 0x00191e15, 0x00191e15, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180b, 0x0014180b, 0x00191c09, 0x001d2009, 0x001d2008, 0x0024250b, 0x0026280b, 0x00292b0a, 0x002d2f0b, 0x0030310c, 0x0034350c, 0x0036370c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x004d4e0f, 0x004d4e10, 0x00786911, 0x00bb9614, 0x00cba216, 0x00cba216, 0x00b49215, 0x007d6e12, 0x005c5a10, 0x00585810, 0x00585911, 0x00595a12, 0x00595a12, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x005c5c12, 0x005c5c12, 0x005c5c12, 0x005c5c12, 0x005b5b12, 0x00595a12, 0x00595a12, 0x00585912, 0x005c5b11, 0x00726811, 0x00a48713, 0x00c6a015, 0x00cca316, 0x00c49c15, 0x008f7812, 0x00535210, 0x004d4e10, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450e, 0x0041420e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002d2f0b, 0x002c2d0b, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x0014180e, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c16, 0x00181b17, 0x00191b17, 0x00191916, 0x00141510, 0x0010100b, 0x000f100a, 0x000d100a, 0x000a0f08, 0x000a0e07, 0x000c0c07, 0x000c0d05, 0x00141408, 0x0019170b, 0x0021180f, 0x0023180e, 0x0020180d, 0x001f180b, 0x0024170c, 0x0028160c, 0x0028180c, 0x0029180d, 0x0029180e, 0x0024170d, 0x0020160b, 0x001c170a, 0x00181408, 0x00181209, 0x0018130a, 0x00161108, 0x00120f04, 0x00100f04, 0x00100e04, 0x000f0e03, 0x00111006, 0x00151106, 0x00151005, 0x00141205, 0x00161408, 0x00181708, 0x00191709, 0x00191808, 0x001a1908, 0x001e1908, 0x00231807, 0x00241807, 0x00281c0a, 0x002b1f0c, 0x002b200b, 0x002b1f0a, 0x002d200a, 0x0034240b, 0x003f240c, 0x0042270d, 0x00442b0b, 0x00482f0b, 0x0050370b, 0x005f410f, 0x006c460c, 0x00805210, 0x00946314, 0x00a8781c, 0x00b48922, 0x00c19a28, 0x00c6a425, 0x00cbaa23, 0x00ccad22, 0x00ccaf20, 0x00ccb01e, 0x00ccb01c, 0x00ccb11a, 0x00ccb41a, 0x00ccb419, 0x00ccb419, 0x00ccb221, 0x00cbab26, 0x00c5a326, 0x00bc961f, 0x00a67f14, 0x00946810, 0x007d4d06, 0x006e4309, 0x00623c0b, 0x005a3a0c, 0x00583a0e, 0x0058390b, 0x00583809, 0x005b3a0b, 0x005f3f0c, 0x0060410b, 0x00614209, 0x0068450a, 0x00704a0e, 0x00754c0e, 0x007c4c09, 0x0084540d, 0x008c5c10, 0x00996a18, 0x00a5781b, 0x00b48823, 0x00be9424, 0x00c89f27, 0x00c6a423, 0x00c9ac24, 0x00ccb020, 0x00ccb11a, 0x00ccb315, 0x00ccb413, 0x00ccb413, 0x00ccb612, 0x00ccb70f, 0x00cab808, 0x00cab808, 0x00c9b808, 0x00ccb80c, 0x00ccb315, 0x00ab880b, 0x007d5600, 0x00694401, 0x00553804, 0x00462d05, 0x00402b08, 0x003a2404, 0x00342004, 0x002f1d07, 0x00291907, 0x00261706, 0x00221508, 0x001f1307, 0x001b1308, 0x00191207, 0x00181307, 0x00171309, 0x00171309, 0x00151108, 0x00151108, 0x0017100b, 0x0017100b, 0x00150f0a, 0x00150f0a, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x00160f08, 0x00170f08, 0x00151008, 0x00151008, 0x00141009, 0x0014100a, 0x0013100a, 0x0014140c, 0x000e1008, 0x00101109, 0x0012110a, 0x0013100a, 0x0014100a, 0x0014100a, 0x0014100a, 0x00150f0a, 0x00150f0a, 0x00151009, 0x00151008, 0x00151008, 0x00171009, 0x00151008, 0x00161108, 0x00161108, 0x00161108, 0x00161109, 0x00151109, 0x00151108, 0x00151108, 0x00161208, 0x00181207, 0x00191208, 0x001c1208, 0x001d1409, 0x00201408, 0x00241508, 0x00281808, 0x002d1c09, 0x002f1b09, 0x0037200a, 0x0044280a, 0x00674418, 0x007f5014, 0x009b6915, 0x00c59c26, 0x00cbac15, 0x00cbb10a, 0x00c8b209, 0x00c8b209, 0x00c9b30b, 0x00c9b30c, 0x00cab40f, 0x00cbb410, 0x00ccb410, 0x00ccb411, 0x00ccb40f, 0x00ccb40f, 0x00ccb310, 0x00ccb311, 0x00ccb211, 0x00ccb113, 0x00ccb012, 0x00ccaf13, 0x00ccac16, 0x00ccaa1a, 0x00caa61d, 0x00caa321, 0x00c9a023, 0x00c39820, 0x00be921c, 0x00b98c19, 0x00b48417, 0x00af7c18, 0x00a77211, 0x00a06c0f, 0x009a660b, 0x009a6412, 0x00925c14, 0x00895414, 0x00885414, 0x00845310, 0x00815010, 0x008b5a15, 0x00a87925, 0x00c4a02b, 0x00caad24, 0x00ccb11d, 0x00cab314, 0x00cab40f, 0x00c9b70c, 0x00c9b80b, 0x00c8b80c, 0x00c8b80c, 0x00c8b80c, 0x00c8b70c, 0x00c8b60c, 0x00c8b50c, 0x00cbb50c, 0x00cbb40d, 0x00c9b510, 0x00c9b412, 0x00ccb018, 0x00c9ac18, 0x00bf9d18, 0x00a87e0c, 0x00905f02, 0x00804f08, 0x00683c08, 0x004c3003, 0x00402a04, 0x003c2808, 0x00342307, 0x002e2008, 0x002b1d09, 0x00281a08, 0x00241606, 0x00201407, 0x001b1207, 0x00161207, 0x00121004, 0x00100f04, 0x000c0e02, 0x00090d01, 0x00080d01, 0x00060e01, 0x00081003, 0x000e1004, 0x00101005, 0x00101004, 0x00131405, 0x001b1408, 0x0021180b, 0x0023190c, 0x0024190d, 0x0024190c, 0x00261a0c, 0x00291c10, 0x0026180e, 0x0023160c, 0x0021180a, 0x0020180b, 0x001e140a, 0x001c1108, 0x001c1206, 0x001a1306, 0x00181406, 0x00181407, 0x00181508, 0x00181408, 0x001b1408, 0x001d1408, 0x001c1409, 0x00181308, 0x00140f07, 0x00100c04, 0x000d0c04, 0x000b0c03, 0x000a0d05, 0x000c0e08, 0x000c0e08, 0x000c1009, 0x000c0f08, 0x00121710, 0x001c2019, 0x00191e17, 0x001a1f18, 0x001b2018, 0x001a1f18, 0x00182018, 0x00182018, 0x001b2018, 0x001b2018, 0x001d211a, 0x001c1f18, 0x001c1e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250c, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004b4c10, 0x004c4d0f, 0x004f5010, 0x005d5810, 0x00a08413, 0x00c79f15, 0x00cca316, 0x00c9a116, 0x00b19015, 0x00887512, 0x00635e10, 0x005b5910, 0x00585810, 0x00595a11, 0x00585911, 0x00595a11, 0x00585911, 0x00585911, 0x00585911, 0x00595a11, 0x00595a11, 0x005c5a11, 0x00656010, 0x008a7613, 0x00ae8e14, 0x00c8a015, 0x00cca316, 0x00c9a116, 0x00b08f14, 0x00706410, 0x004f4f10, 0x004d4e10, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450e, 0x0041420e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c16, 0x00181b17, 0x00191b18, 0x00191a16, 0x0014150e, 0x00101009, 0x000f100a, 0x000d100a, 0x000a0f08, 0x00090e07, 0x000b0d07, 0x000b0c04, 0x000e0d02, 0x001c190d, 0x00281b12, 0x00271810, 0x0023160c, 0x0021160c, 0x0020140a, 0x00201409, 0x00201409, 0x00201409, 0x001e1408, 0x001a1305, 0x00151203, 0x00121201, 0x000d0f00, 0x000c0d02, 0x000e0d03, 0x000e0e01, 0x000f0f02, 0x00141105, 0x00131104, 0x00141205, 0x00181608, 0x001e180b, 0x001f180a, 0x00201809, 0x00221a0b, 0x00241c0d, 0x00241c0d, 0x00241d0c, 0x00271e0b, 0x002b1d0a, 0x00301c08, 0x00301c08, 0x00311e0a, 0x00331f0b, 0x0033200b, 0x00342209, 0x0037250a, 0x003c290c, 0x00492a10, 0x004e2f10, 0x0053320e, 0x005c3c11, 0x00664410, 0x007a5413, 0x00936917, 0x00b08422, 0x00c09728, 0x00c7a328, 0x00ccac24, 0x00ccaf1c, 0x00ccb216, 0x00ccb412, 0x00ccb512, 0x00ccb611, 0x00ccb811, 0x00ccb810, 0x00ccb80e, 0x00cbba0c, 0x00cbba0b, 0x00cbb90c, 0x00ccb911, 0x00ccb816, 0x00ccb619, 0x00ccb31c, 0x00cbae22, 0x00be9a21, 0x00a47a10, 0x00805703, 0x00704808, 0x00653f0a, 0x00613e0b, 0x00603d08, 0x00673f09, 0x006d440c, 0x0071480c, 0x00754c0a, 0x007e540d, 0x0084560e, 0x008d5f13, 0x00976717, 0x00a07115, 0x00ac801c, 0x00bc9026, 0x00c39929, 0x00cba427, 0x00cca824, 0x00ccac1e, 0x00ccad18, 0x00c9ae14, 0x00cbb314, 0x00ccb511, 0x00cbb50c, 0x00ccb60b, 0x00ccb60a, 0x00ccb70b, 0x00ccb80b, 0x00ccb80a, 0x00cab808, 0x00cab908, 0x00cab908, 0x00ccb80d, 0x00ccb718, 0x00af8c0d, 0x00825800, 0x00674000, 0x00563705, 0x00462d06, 0x003c2806, 0x00382201, 0x00332005, 0x002d1d07, 0x00291907, 0x00251707, 0x00221408, 0x001f1307, 0x001b1307, 0x00191207, 0x00181308, 0x00171309, 0x00171309, 0x00161208, 0x00151108, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x00161008, 0x00160f08, 0x00151008, 0x00151008, 0x00151009, 0x0014100a, 0x0012100a, 0x0014140c, 0x000e1008, 0x00101109, 0x0012110a, 0x0013100a, 0x0014100a, 0x0014100a, 0x0014100a, 0x0017100b, 0x0017100b, 0x00151008, 0x00151008, 0x00171009, 0x00171009, 0x00171008, 0x00171008, 0x00181209, 0x00181309, 0x00171209, 0x0016120a, 0x00151109, 0x00151108, 0x00151108, 0x00181207, 0x00191208, 0x001c1208, 0x001d1409, 0x00201408, 0x00231406, 0x00281808, 0x002e1b09, 0x00301a09, 0x0038200a, 0x0045290a, 0x00684619, 0x007f5014, 0x009a6916, 0x00c69d27, 0x00ccad18, 0x00c9b109, 0x00c8b308, 0x00c8b308, 0x00c9b408, 0x00c9b408, 0x00cab408, 0x00cbb509, 0x00cbb608, 0x00cbb708, 0x00cab707, 0x00c9b706, 0x00cab606, 0x00cab607, 0x00cab407, 0x00cab408, 0x00cbb408, 0x00cbb408, 0x00ccb40b, 0x00ccb20e, 0x00ccb011, 0x00ccaf13, 0x00cbad14, 0x00caac14, 0x00caab18, 0x00caab1b, 0x00cba81d, 0x00cca01c, 0x00c99d1c, 0x00c4981b, 0x00bf9217, 0x00b58716, 0x00b07f19, 0x00a36e15, 0x0096600d, 0x008d5b0c, 0x00905e13, 0x00aa7c27, 0x00c79f34, 0x00ccb025, 0x00ccb418, 0x00ccb512, 0x00ccb60c, 0x00ccb708, 0x00cbb708, 0x00cab509, 0x00cbb30b, 0x00cbb30a, 0x00cbb30a, 0x00ccb50c, 0x00ccb50c, 0x00ccb50b, 0x00ccb409, 0x00cbb509, 0x00c9b708, 0x00c9b707, 0x00ccb50e, 0x00cbb410, 0x00ccb318, 0x00c4a219, 0x00ae7f0d, 0x00935e02, 0x007c4c07, 0x00613a04, 0x004d3004, 0x00432906, 0x00392506, 0x00342408, 0x00312008, 0x00301e08, 0x002d1c09, 0x00291909, 0x0024170a, 0x0020170c, 0x001d150b, 0x001a1409, 0x00151006, 0x00101007, 0x000e0f06, 0x000c1006, 0x000a0f05, 0x000a0f04, 0x000b0f04, 0x000a0e04, 0x000a0e03, 0x000e0d03, 0x00140d03, 0x00161006, 0x00180f05, 0x00181004, 0x001b1207, 0x001e1409, 0x0020150a, 0x0022180c, 0x0024180e, 0x0024180d, 0x0024170c, 0x0022150b, 0x0022140b, 0x0021150b, 0x00201609, 0x001f1709, 0x001d1508, 0x001d1508, 0x001f1508, 0x00201508, 0x001c1408, 0x00141005, 0x00100c04, 0x000e0c04, 0x000c0c04, 0x00090d03, 0x00090c04, 0x000b0d07, 0x000c0f08, 0x000c1009, 0x000d100a, 0x000d120c, 0x001a1f18, 0x00191e17, 0x00191e17, 0x001a1f18, 0x001a1f18, 0x00182018, 0x00182018, 0x001b2018, 0x001b2018, 0x001d201a, 0x001c1f18, 0x001c1e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0045470e, 0x0048490f, 0x004b4c10, 0x004c4d0f, 0x004d4e0f, 0x00515010, 0x00726511, 0x00aa8a14, 0x00c8a015, 0x00cca216, 0x00c9a116, 0x00c49d15, 0x00af8f14, 0x009c8214, 0x008c7713, 0x007e6e12, 0x00786a12, 0x00726811, 0x00796c12, 0x00837212, 0x00907a13, 0x00a08514, 0x00b39114, 0x00c59e15, 0x00caa116, 0x00cca316, 0x00caa116, 0x00b89514, 0x00877312, 0x00565410, 0x004f5010, 0x004c4d0f, 0x004b4c10, 0x0048490f, 0x0047480e, 0x0044450e, 0x0041420e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0020230a, 0x001d2008, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x00141810, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x00181c15, 0x00181c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00191c16, 0x00191c16, 0x00181c15, 0x00181c16, 0x00191b17, 0x001b1c18, 0x00171813, 0x0013140c, 0x000f1008, 0x000f1008, 0x000d1008, 0x000b0f06, 0x000a0f06, 0x000c0e08, 0x000c1006, 0x000c0c01, 0x00181509, 0x0021150e, 0x001e0f09, 0x00190e07, 0x00180f07, 0x00161007, 0x00120f05, 0x00110f03, 0x00110e03, 0x00100e02, 0x000f0f01, 0x000d0f00, 0x000f1001, 0x000e1000, 0x00101204, 0x00141407, 0x00141405, 0x00141405, 0x001a1306, 0x001d1608, 0x00201708, 0x00241c0c, 0x00261c0c, 0x00271c09, 0x00261907, 0x00281b08, 0x002c1d09, 0x002d1e0a, 0x002e1e0a, 0x0030200a, 0x00332008, 0x00362008, 0x00372109, 0x00382209, 0x003c240c, 0x003c270d, 0x003c270b, 0x00402a0c, 0x00442d0c, 0x0050310f, 0x0055340c, 0x00603b08, 0x00724a11, 0x00875d14, 0x00a87f21, 0x00bf9924, 0x00c9a820, 0x00cbaf1c, 0x00cbb118, 0x00ccb413, 0x00ccb50f, 0x00ccb410, 0x00ccb10d, 0x00ccae0d, 0x00cbac0c, 0x00cbad0f, 0x00caae0f, 0x00c9af0d, 0x00cab10c, 0x00ccb50d, 0x00ccb50c, 0x00cbb70a, 0x00ccb809, 0x00ccbc09, 0x00ccba0e, 0x00ccb814, 0x00ccb41d, 0x00c4a718, 0x00a17d0b, 0x00785000, 0x00724704, 0x0072460a, 0x00764b0b, 0x0081540f, 0x008b5e12, 0x00926614, 0x009b6f13, 0x00a47814, 0x00af821d, 0x00bc9028, 0x00c49c2d, 0x00c6a023, 0x00cba824, 0x00cba81f, 0x00ccac1c, 0x00ccb014, 0x00ccb210, 0x00ccb40d, 0x00ccb409, 0x00cab608, 0x00c9b608, 0x00c9b707, 0x00c9b706, 0x00cab806, 0x00cab808, 0x00cbb808, 0x00ccb808, 0x00ccb808, 0x00ccb808, 0x00cab908, 0x00cbba0a, 0x00ccb80d, 0x00ccb518, 0x00b18e10, 0x00835a00, 0x00673f00, 0x00543403, 0x00452d06, 0x003c2805, 0x00362100, 0x00331f04, 0x002c1c08, 0x00281808, 0x00251607, 0x00221408, 0x001e1307, 0x001a1207, 0x00191207, 0x00181308, 0x00171309, 0x00171309, 0x00161208, 0x00161208, 0x0018110a, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00151109, 0x00171109, 0x0018110a, 0x0017110b, 0x0016110c, 0x0014120c, 0x0014140c, 0x000c0e06, 0x0012110a, 0x0013120b, 0x0014110b, 0x0015100b, 0x0017100b, 0x0017100b, 0x0017100b, 0x0017100b, 0x0018110a, 0x0018110a, 0x00171009, 0x00171009, 0x00181108, 0x00181108, 0x00181208, 0x00181208, 0x00171108, 0x00161208, 0x00151108, 0x00151108, 0x00161208, 0x00181207, 0x00191208, 0x001c1309, 0x001f140a, 0x00201408, 0x00231406, 0x00281707, 0x002c1a08, 0x00301b08, 0x00371f08, 0x00442707, 0x006a4819, 0x00805014, 0x009c6b18, 0x00c59c26, 0x00ccaf1a, 0x00cab30a, 0x00c9b407, 0x00c9b405, 0x00c9b405, 0x00c9b405, 0x00cab506, 0x00cab504, 0x00cbb605, 0x00c9b705, 0x00c9b707, 0x00c8b807, 0x00c9b707, 0x00c9b707, 0x00cbb607, 0x00cbb608, 0x00ccb508, 0x00ccb508, 0x00ccb507, 0x00ccb508, 0x00cbb408, 0x00cbb409, 0x00cab509, 0x00cbb50b, 0x00cbb40c, 0x00ccb410, 0x00ccb311, 0x00ccb212, 0x00ccb013, 0x00ccad14, 0x00ccac16, 0x00cba718, 0x00cba01d, 0x00c1901c, 0x00a06c06, 0x0099620a, 0x00a07017, 0x00c2982d, 0x00ccac27, 0x00cbb315, 0x00ccb60e, 0x00ccb70a, 0x00ccb805, 0x00cab504, 0x00ccb20c, 0x00cbaa0d, 0x00caa411, 0x00c8a010, 0x00c49d0c, 0x00c29c0a, 0x00c49f0c, 0x00c5a20d, 0x00c8a80e, 0x00ccb011, 0x00ccb410, 0x00ccb60c, 0x00ccb60d, 0x00ccb908, 0x00cbb707, 0x00ccb214, 0x00c8a218, 0x00ac7e08, 0x008e5c00, 0x00774903, 0x005e3805, 0x004e2f07, 0x00432804, 0x003c2608, 0x00382408, 0x00362006, 0x00331e07, 0x00301d08, 0x002c1c0a, 0x002a190e, 0x0028180d, 0x0026180e, 0x0024190e, 0x001e160b, 0x00181207, 0x00171409, 0x00131207, 0x00101105, 0x000c1003, 0x000c0f03, 0x000c0f03, 0x000d0c03, 0x00100c04, 0x00100c03, 0x00100c03, 0x000f0c02, 0x00100b01, 0x00120d02, 0x00151005, 0x001a1308, 0x001e1409, 0x001f1509, 0x0025180c, 0x0025190d, 0x0024180b, 0x0026190d, 0x0025170a, 0x00251609, 0x00241608, 0x00231608, 0x00231708, 0x001f1407, 0x00161002, 0x00100d02, 0x000e0c03, 0x000d0c04, 0x000a0d03, 0x00080e03, 0x00080d04, 0x00090e07, 0x000a0f09, 0x000d100a, 0x0010120c, 0x000e110b, 0x00151812, 0x00181d16, 0x00181d16, 0x00191e17, 0x00191e17, 0x00192018, 0x00192018, 0x001b2018, 0x001b2018, 0x001c2019, 0x001c1f18, 0x001c1e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0040400d, 0x0043440e, 0x0045470e, 0x0047480f, 0x00494a10, 0x004b4c0f, 0x004c4d0f, 0x004d4e10, 0x00525010, 0x00706311, 0x00a08413, 0x00be9815, 0x00cba116, 0x00cca216, 0x00cca216, 0x00caa116, 0x00c8a015, 0x00c7a015, 0x00c7a015, 0x00c8a015, 0x00c8a016, 0x00caa216, 0x00cca316, 0x00cca316, 0x00cca216, 0x00c8a015, 0x00af8e14, 0x00867111, 0x00595510, 0x004f5010, 0x004d4e0f, 0x004b4c0f, 0x00494a10, 0x0048490f, 0x0045470e, 0x0043440e, 0x0041420d, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c09, 0x00141809, 0x0014180b, 0x0014180e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c15, 0x00181c15, 0x001a1b15, 0x00181c15, 0x00181c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00191c16, 0x00191c16, 0x00181c15, 0x00181c16, 0x00191b17, 0x001c1c18, 0x00171812, 0x0013140c, 0x000f1007, 0x000f1007, 0x000d1007, 0x000c0f04, 0x00091006, 0x000a0f06, 0x000d1007, 0x00101005, 0x00151309, 0x001a120c, 0x00140d07, 0x00100b04, 0x000e0c04, 0x000c0d04, 0x000c0d04, 0x000e0f04, 0x00101005, 0x00101005, 0x00121205, 0x00131204, 0x00151405, 0x00161405, 0x001c180b, 0x00201a0c, 0x00201a0d, 0x00211a0c, 0x00241c09, 0x00281d0b, 0x00281f0c, 0x002b1f0c, 0x002c1e0b, 0x002d1e0a, 0x002f1e0a, 0x0030200a, 0x0033220a, 0x00342209, 0x00342209, 0x0037230a, 0x00382509, 0x003a270a, 0x003c280b, 0x003f290e, 0x00402a0f, 0x00412b0e, 0x00442c0c, 0x00482e0c, 0x004c320c, 0x0058380b, 0x00634009, 0x0078500d, 0x009c7224, 0x00b9902a, 0x00cba62e, 0x00caac1f, 0x00ccb313, 0x00cbb50c, 0x00cbb40a, 0x00ccb10c, 0x00cbac0a, 0x00caa30d, 0x00c49810, 0x00bd8f0a, 0x00b58906, 0x00b08405, 0x00b08406, 0x00af8604, 0x00b48c08, 0x00bc960d, 0x00c5a311, 0x00cbae14, 0x00cab50c, 0x00c9b806, 0x00cabb09, 0x00cbbb0e, 0x00c9b710, 0x00ccb616, 0x00c0a015, 0x008c6600, 0x00805104, 0x0081530c, 0x00966919, 0x00ad8328, 0x00b38b27, 0x00bb9527, 0x00c7a129, 0x00cba826, 0x00ccac28, 0x00ccae25, 0x00ccb122, 0x00cab01c, 0x00cbb418, 0x00ccb614, 0x00ccb710, 0x00cab70c, 0x00c9b608, 0x00cab607, 0x00c9b705, 0x00c8b807, 0x00c8b708, 0x00c9b608, 0x00c9b609, 0x00c9b709, 0x00c9b809, 0x00cbb80a, 0x00ccb80a, 0x00cab908, 0x00cab908, 0x00c8ba08, 0x00cabb0a, 0x00cbb90c, 0x00ccb618, 0x00b18e10, 0x00845b00, 0x00664000, 0x00543403, 0x00442d06, 0x00382603, 0x00331f00, 0x00311e04, 0x002c1c08, 0x00281708, 0x00241508, 0x00201307, 0x001c1206, 0x00191307, 0x00181307, 0x00171408, 0x00171309, 0x00171309, 0x00161208, 0x00161208, 0x00171008, 0x00171008, 0x00171008, 0x00171008, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00141109, 0x00141109, 0x0015110a, 0x0017120a, 0x0017110b, 0x0016110c, 0x0014120c, 0x0014140c, 0x000c0e06, 0x0012110b, 0x0013120b, 0x0014110b, 0x0015100b, 0x0017100b, 0x0017100b, 0x0018110c, 0x0018110c, 0x0018110a, 0x0018110a, 0x00171009, 0x00171009, 0x00181108, 0x00181108, 0x00171008, 0x00171008, 0x00161008, 0x00151108, 0x00151108, 0x00151108, 0x00161208, 0x00181207, 0x00191208, 0x001c1409, 0x001f140b, 0x00201408, 0x00231407, 0x00261706, 0x002c1908, 0x00301b08, 0x00381e08, 0x00442606, 0x006b491c, 0x00825417, 0x00a06e1b, 0x00c69c27, 0x00ccb01a, 0x00cab30a, 0x00c9b404, 0x00c9b404, 0x00c9b405, 0x00c9b405, 0x00cab506, 0x00cab506, 0x00ccb508, 0x00cbb508, 0x00cbb509, 0x00cbb50a, 0x00cbb50c, 0x00ccb40d, 0x00ccb40d, 0x00ccb40d, 0x00ccb40f, 0x00cbb40f, 0x00cbb40d, 0x00cab60c, 0x00c8b50a, 0x00c8b508, 0x00c9b508, 0x00cbb607, 0x00cbb609, 0x00cbb50c, 0x00cbb50c, 0x00cbb50c, 0x00cab40b, 0x00c9b30d, 0x00cbb210, 0x00ccad0d, 0x00cca710, 0x00c2910f, 0x00a46b00, 0x009c6504, 0x00b48720, 0x00cba82c, 0x00cbb217, 0x00cbb60c, 0x00ccb80c, 0x00ccb708, 0x00ccb805, 0x00cab109, 0x00c6a30e, 0x00b88c07, 0x00ae7902, 0x00a87002, 0x00a06d00, 0x00a06c00, 0x00a37000, 0x00a67402, 0x00b38308, 0x00bd900d, 0x00c79f14, 0x00ccaa18, 0x00cbb412, 0x00c8bb03, 0x00c9b900, 0x00ccb40b, 0x00ccb115, 0x00c4a014, 0x00a47804, 0x00815300, 0x00683f06, 0x00543306, 0x00482c04, 0x00422a07, 0x003f2707, 0x003b2305, 0x00372004, 0x00341f07, 0x00331e09, 0x00311c0c, 0x00301b0b, 0x002f1a0b, 0x002d1b0c, 0x00291a0d, 0x0026180c, 0x0024190c, 0x001f170b, 0x001b1709, 0x00181406, 0x00171306, 0x00141004, 0x00111004, 0x00101005, 0x000f0f04, 0x000c0c01, 0x000c0c01, 0x000e0c02, 0x000f0d03, 0x000d0c01, 0x00100d02, 0x00130f03, 0x00141002, 0x00191507, 0x001d1808, 0x001e1708, 0x00231809, 0x00281a0c, 0x0029190b, 0x0029180a, 0x0028180a, 0x00231707, 0x001c1101, 0x00130e00, 0x000e0c01, 0x000d0d03, 0x000c0d04, 0x000a0e04, 0x00070e03, 0x00080e04, 0x00090e07, 0x00090e07, 0x000c100a, 0x000f140c, 0x000e110b, 0x00151812, 0x00171c15, 0x00181d16, 0x00181d16, 0x00191e17, 0x00192018, 0x00192018, 0x001b2018, 0x001b2018, 0x001c2019, 0x001c1f18, 0x001c1e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0038380c, 0x00393b0d, 0x003c3e0d, 0x0040400d, 0x0041420e, 0x0044450e, 0x0045470e, 0x0048490f, 0x00494a10, 0x004b4c0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x005e5810, 0x007a6a11, 0x009c8013, 0x00b18f14, 0x00bc9815, 0x00c49c15, 0x00c8a015, 0x00c9a116, 0x00c8a015, 0x00c49d16, 0x00c09915, 0x00b69314, 0x00a98914, 0x008c7512, 0x006b6011, 0x00535110, 0x004d4e10, 0x004d4e0f, 0x004c4d0f, 0x004b4c10, 0x0048490f, 0x0047480e, 0x0044450e, 0x0043440e, 0x0040400d, 0x003c3e0c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1b15, 0x00151710, 0x00101208, 0x000f1006, 0x000f1007, 0x000d0f05, 0x000c0f04, 0x000c0f06, 0x000c1007, 0x000e0f08, 0x0015130c, 0x0014120c, 0x00141109, 0x000f0e07, 0x000e0d06, 0x000c0e06, 0x000c0e05, 0x000e1008, 0x00111108, 0x00151308, 0x00181408, 0x001d1809, 0x0021190b, 0x00241a0d, 0x0026190c, 0x002b1d0d, 0x002c1e0d, 0x002c1d0d, 0x002e1e0e, 0x002d1d0d, 0x002d1e0c, 0x00301f0c, 0x0033220d, 0x0034220c, 0x0035210c, 0x00352209, 0x0038240a, 0x0038270c, 0x003b290e, 0x003e2c11, 0x003f2d12, 0x00402e10, 0x00402f0f, 0x0040300c, 0x0044310d, 0x00473410, 0x00483310, 0x004b3410, 0x004f3610, 0x00543810, 0x0068400f, 0x00784f0f, 0x00a37823, 0x00c19530, 0x00c8ab26, 0x00ccb31d, 0x00ccb414, 0x00cab40f, 0x00ccb20f, 0x00c8a811, 0x00c29c13, 0x00b38708, 0x00a47300, 0x00976300, 0x00905a00, 0x00895400, 0x00885300, 0x00875100, 0x00855300, 0x00895700, 0x00906001, 0x009a6f07, 0x00af860e, 0x00c5a416, 0x00cbb416, 0x00cab60f, 0x00c8b80e, 0x00c8b80e, 0x00ccb80e, 0x00cbb017, 0x00a37c08, 0x00885902, 0x00916210, 0x00bb9030, 0x00cba732, 0x00c8ac26, 0x00cbb120, 0x00ccb319, 0x00ccb518, 0x00ccb618, 0x00cab715, 0x00cab813, 0x00c8b710, 0x00c8b80e, 0x00c9b80c, 0x00c9b80b, 0x00c9b809, 0x00c9b809, 0x00c9b809, 0x00c9b809, 0x00c9b80b, 0x00c9b80c, 0x00c9b80c, 0x00c9b70e, 0x00c9b70e, 0x00c9b80c, 0x00c9b80a, 0x00c8ba08, 0x00c8b908, 0x00c8b808, 0x00c8b809, 0x00cab90a, 0x00ccb90a, 0x00ccb713, 0x00b3900c, 0x00835c00, 0x00694500, 0x00543602, 0x00422c04, 0x00382504, 0x00321f00, 0x00301e08, 0x002c1a0b, 0x00251608, 0x00221406, 0x001f1406, 0x001c1205, 0x00181307, 0x00181307, 0x00171408, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x0018110a, 0x00171009, 0x00171009, 0x00171009, 0x00141208, 0x00141208, 0x00141108, 0x00161108, 0x00171109, 0x0016120a, 0x0016120a, 0x0016140b, 0x00131008, 0x00121108, 0x00141209, 0x00141109, 0x00141109, 0x00171009, 0x00171009, 0x0018100a, 0x0018100a, 0x00181108, 0x00161208, 0x00161208, 0x00161208, 0x00151108, 0x00151108, 0x00151108, 0x00151108, 0x00161108, 0x00171008, 0x00171008, 0x00171008, 0x00171309, 0x00171309, 0x00181309, 0x001c130c, 0x001d140b, 0x00201408, 0x00231407, 0x00261706, 0x002c1908, 0x00301b08, 0x00381f08, 0x00442608, 0x0069481e, 0x0085551a, 0x00a36f1c, 0x00c99e2c, 0x00ccaf1d, 0x00c8b20e, 0x00c8b408, 0x00c8b408, 0x00c8b40a, 0x00c8b40a, 0x00c8b509, 0x00cab409, 0x00cbb50b, 0x00cbb50c, 0x00cbb50c, 0x00cbb50c, 0x00cbb50c, 0x00cbb50c, 0x00ccb40d, 0x00ccb40d, 0x00ccb40c, 0x00ccb40c, 0x00cbb50a, 0x00cbb50a, 0x00cbb50a, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00cbb408, 0x00cbb408, 0x00cbb408, 0x00cbb409, 0x00ccb309, 0x00ccb008, 0x00cca80e, 0x00b78504, 0x00a16500, 0x00a1690e, 0x00c49a2c, 0x00ccb020, 0x00ccb90c, 0x00ccb90b, 0x00ccb80f, 0x00ccb810, 0x00cbb410, 0x00bc9c09, 0x00a97d03, 0x00976501, 0x00945e02, 0x008d5700, 0x008c5404, 0x008a5203, 0x008c5505, 0x008d5503, 0x00925d01, 0x009c6904, 0x00ab780a, 0x00c19018, 0x00cca619, 0x00ccb30d, 0x00cab804, 0x00ccb70a, 0x00ccb411, 0x00ccb014, 0x00c09a15, 0x00906001, 0x00744804, 0x005d3d04, 0x00503204, 0x00482e06, 0x00442b07, 0x00412909, 0x003d2507, 0x00382307, 0x00362008, 0x00341e08, 0x00321c08, 0x00321d09, 0x00301e0b, 0x002f1c0a, 0x002e1d0a, 0x002c1d09, 0x002a1d0a, 0x00251b0c, 0x0020180a, 0x00201709, 0x001d1409, 0x00191004, 0x00151004, 0x00141004, 0x00100f03, 0x00100e04, 0x00100f05, 0x000d0c04, 0x000d0c04, 0x000c0c02, 0x000c0c01, 0x000c0e00, 0x000d1002, 0x00101405, 0x00131405, 0x00171304, 0x001f1508, 0x0027190d, 0x00281c10, 0x0024190f, 0x001d1408, 0x00150f04, 0x000f0c01, 0x000e0e03, 0x000d0d04, 0x000c0c04, 0x000a0e04, 0x00080f05, 0x00080f05, 0x00080d04, 0x00080d06, 0x00090d05, 0x000a0d05, 0x000e1109, 0x0013160e, 0x00171c15, 0x00171c15, 0x00181d16, 0x00181d16, 0x00192018, 0x00192018, 0x00192018, 0x00192018, 0x001b2019, 0x001b201a, 0x001b201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0043440e, 0x0045470e, 0x0047480e, 0x0048490f, 0x00494a0f, 0x004b4c10, 0x004c4d0f, 0x004d4e0f, 0x004c4d0f, 0x004b4c10, 0x00515010, 0x00605810, 0x00685d11, 0x006d6011, 0x006f6110, 0x006c6010, 0x006a5f10, 0x00635b10, 0x00585410, 0x004c4d10, 0x004c4d10, 0x004d4e0f, 0x004c4d0f, 0x004b4c0f, 0x00494a0f, 0x0048490f, 0x0047480e, 0x0045470e, 0x0044450e, 0x0041420e, 0x0040400d, 0x003c3e0d, 0x00393b0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1c16, 0x00181812, 0x0012140c, 0x000f1007, 0x000f1005, 0x000d0f05, 0x000c0e04, 0x000c0f04, 0x000c0e04, 0x000d0f07, 0x00101009, 0x0016130c, 0x0017120c, 0x00121209, 0x000d1007, 0x000d1007, 0x000e1108, 0x00111208, 0x0015150c, 0x0019160b, 0x001d180a, 0x0021190a, 0x00281b0b, 0x002c1c0d, 0x002f1d10, 0x00301d0e, 0x00311f0c, 0x0032200b, 0x0033200b, 0x0034210c, 0x0035220e, 0x0035230f, 0x0035240c, 0x0039270e, 0x003b280e, 0x003b280c, 0x003d2a0d, 0x00402c0d, 0x00412f0d, 0x00453010, 0x00473311, 0x00463211, 0x00473311, 0x00473310, 0x00483510, 0x004c3910, 0x004e3c10, 0x00503b0d, 0x00523b0c, 0x00583c0d, 0x0060420f, 0x00744e0b, 0x009c7621, 0x00be9a2b, 0x00ccac28, 0x00ccb41a, 0x00ccb710, 0x00ccb611, 0x00c9ac0e, 0x00c29e10, 0x00ad8208, 0x00996902, 0x008a5800, 0x00815000, 0x007a4900, 0x00764500, 0x00724100, 0x00724201, 0x00744403, 0x00744401, 0x00774802, 0x007f5007, 0x00825504, 0x008f6001, 0x00ac840f, 0x00cbac1f, 0x00cbb511, 0x00c8b80b, 0x00c8bb08, 0x00cbb908, 0x00cbb514, 0x00a88204, 0x00906001, 0x00996a0d, 0x00c19926, 0x00ccb024, 0x00cab414, 0x00cbb60f, 0x00ccb70a, 0x00cab80c, 0x00cab80c, 0x00ccb80d, 0x00ccb80d, 0x00cab70c, 0x00cab70c, 0x00cbb70c, 0x00cbb70c, 0x00cab70c, 0x00cab70b, 0x00cab70b, 0x00cab809, 0x00cab809, 0x00cab70b, 0x00c9b80b, 0x00c9b80b, 0x00c9b80a, 0x00c9b809, 0x00c9b808, 0x00cab907, 0x00caba06, 0x00ccba08, 0x00ccb90a, 0x00ccb80a, 0x00ccb80d, 0x00ccb616, 0x00b38f0e, 0x00845d00, 0x006e4c03, 0x00513400, 0x003f2903, 0x00362606, 0x00321e04, 0x002f1c08, 0x00281809, 0x00241506, 0x00201305, 0x001d1204, 0x001a1305, 0x00181307, 0x00171407, 0x00161408, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x0016120a, 0x0016120a, 0x0016120a, 0x0016120a, 0x00141208, 0x00141106, 0x00161106, 0x00171006, 0x00181008, 0x00181108, 0x00181108, 0x00181309, 0x00141008, 0x00121107, 0x00141208, 0x00151108, 0x00151108, 0x00161208, 0x00171108, 0x00181108, 0x00181108, 0x00161307, 0x00161307, 0x00161307, 0x00161307, 0x00151208, 0x00151108, 0x00151108, 0x00151108, 0x00161108, 0x00181108, 0x00171008, 0x00181309, 0x00171309, 0x00171309, 0x00181309, 0x001c140c, 0x001d140b, 0x00201408, 0x00231406, 0x00261706, 0x002b1908, 0x00301c08, 0x00361f09, 0x00402408, 0x0065451d, 0x007c5013, 0x009a6712, 0x00c79927, 0x00cca91b, 0x00caaf0c, 0x00cab309, 0x00cab309, 0x00cab308, 0x00cab308, 0x00cbb408, 0x00cab408, 0x00cbb608, 0x00c9b608, 0x00c9b708, 0x00c9b708, 0x00c9b708, 0x00c9b707, 0x00cab608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00cbb408, 0x00cab307, 0x00cbb408, 0x00ccb408, 0x00ccb409, 0x00ccb20f, 0x00caa510, 0x00b07d02, 0x00a06301, 0x00ac7415, 0x00c7a02a, 0x00ccb31c, 0x00ccbb0a, 0x00ccbb0c, 0x00ccb810, 0x00ccb712, 0x00c4a60d, 0x00a88000, 0x00946500, 0x00885802, 0x00855405, 0x00815103, 0x0081500a, 0x00805008, 0x00804f08, 0x007f5007, 0x00835404, 0x00885802, 0x00916002, 0x00a06d08, 0x00b88c14, 0x00caa819, 0x00cbb212, 0x00ccb511, 0x00ccb510, 0x00ccb410, 0x00cbaa19, 0x00aa7c0f, 0x007d5300, 0x00664402, 0x00573804, 0x004d3306, 0x00482e07, 0x00462c09, 0x00442c0a, 0x003e2808, 0x00392306, 0x00392208, 0x00382108, 0x00362008, 0x00331f08, 0x00321e08, 0x00301e08, 0x002f1f08, 0x002f1f08, 0x002e1f0c, 0x002d1c0e, 0x002c1b0c, 0x002b190b, 0x0026180a, 0x0025180b, 0x00221809, 0x001e1707, 0x001b1408, 0x00161008, 0x00141007, 0x00121107, 0x00101006, 0x000f0f04, 0x000b0c01, 0x00090e00, 0x00081000, 0x00081000, 0x000b0f00, 0x00101001, 0x00171104, 0x001c140a, 0x001e170c, 0x0018140b, 0x00121006, 0x000f0d03, 0x000f0d03, 0x000e0d04, 0x000e0d04, 0x000c0e04, 0x00080f05, 0x00080f05, 0x00080d04, 0x00080d04, 0x00090c04, 0x00090c04, 0x000d1008, 0x0013160d, 0x00171c15, 0x00171c15, 0x00181d16, 0x00181d16, 0x00192018, 0x00192018, 0x00192018, 0x00192018, 0x001a2019, 0x001b201a, 0x001b201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x00393b0c, 0x003b3c0d, 0x003c3e0c, 0x0040400d, 0x0041420d, 0x0043440e, 0x0044450d, 0x0045470e, 0x0047480e, 0x0048490f, 0x00494a10, 0x00494a0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d10, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004c4d10, 0x004c4d0f, 0x004c4d0f, 0x004b4c10, 0x0048490f, 0x0048490f, 0x0047480e, 0x0045470e, 0x0044450e, 0x0041420e, 0x0040400d, 0x003e400c, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0026280b, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180b, 0x0014180e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00191b15, 0x001a1b15, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181c15, 0x00141710, 0x000d1008, 0x000d1008, 0x000d1007, 0x000c1005, 0x000c0e04, 0x000d1004, 0x000d0f05, 0x00101007, 0x0014120a, 0x0019130c, 0x0018110a, 0x00120e04, 0x00121007, 0x00141308, 0x0017140b, 0x001c180c, 0x00201c0e, 0x00261c0c, 0x00281d0c, 0x002c1f0c, 0x0030200c, 0x0032200c, 0x0036200d, 0x0038200c, 0x0039220c, 0x003c240c, 0x003c250b, 0x003d260b, 0x003c260b, 0x003c260b, 0x003c280b, 0x00402c0c, 0x00442e0e, 0x00442f0c, 0x0048310c, 0x0048330b, 0x004b340a, 0x0050380d, 0x0050380e, 0x00543810, 0x00543a0f, 0x00553b0e, 0x0059400f, 0x005b410f, 0x005d430b, 0x00604308, 0x005d4002, 0x00654404, 0x00704e0a, 0x008d6816, 0x00be9b32, 0x00caad27, 0x00cbb416, 0x00cab80c, 0x00ccb80c, 0x00cbb113, 0x00bc980c, 0x00a67603, 0x008f5b00, 0x00815003, 0x00784904, 0x00704402, 0x006a4202, 0x00684002, 0x00673e04, 0x00683f07, 0x00684008, 0x00684107, 0x006f4709, 0x00744c0b, 0x00794f08, 0x00855708, 0x009e710c, 0x00c3a01f, 0x00cbb414, 0x00c8b908, 0x00c8bc04, 0x00ccb907, 0x00cbb414, 0x00ab8304, 0x00926000, 0x00a06e0a, 0x00c49c1f, 0x00ccb219, 0x00cab40c, 0x00cab707, 0x00cbb704, 0x00c9b808, 0x00c9b808, 0x00ccb80a, 0x00ccb80a, 0x00ccb80c, 0x00ccb80c, 0x00ccb80c, 0x00ccb80c, 0x00ccb80c, 0x00ccb80c, 0x00ccb80a, 0x00ccb80a, 0x00ccb80a, 0x00ccb80a, 0x00ccb80a, 0x00cbb80a, 0x00ccb809, 0x00ccb808, 0x00ccb90b, 0x00ccb809, 0x00cbb408, 0x00cbb40b, 0x00ccb611, 0x00ccb312, 0x00ccb016, 0x00caac20, 0x00a98312, 0x00875f08, 0x00785512, 0x00513404, 0x003c2704, 0x00342307, 0x00301c05, 0x002c1906, 0x00271708, 0x00231407, 0x00201407, 0x001d1104, 0x001a1305, 0x00181307, 0x00161406, 0x00151308, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00181309, 0x00181309, 0x00161409, 0x00161409, 0x00161409, 0x00161409, 0x00161308, 0x00171205, 0x00181105, 0x00191105, 0x00191107, 0x00191208, 0x00191208, 0x001a1308, 0x00151106, 0x00141106, 0x00161307, 0x00161307, 0x00161307, 0x00161307, 0x00161307, 0x00171308, 0x00171308, 0x00171408, 0x00171408, 0x00171408, 0x00171408, 0x00161208, 0x00161208, 0x00161208, 0x00171309, 0x00171208, 0x00181108, 0x00181309, 0x00181309, 0x00171309, 0x00171309, 0x00181309, 0x001b130b, 0x001c140a, 0x00201408, 0x00211406, 0x00261607, 0x002a1a09, 0x002e1c0c, 0x00321d0a, 0x003a2008, 0x0060421c, 0x00724c11, 0x008d5f0e, 0x00ba8a21, 0x00c49a18, 0x00c8a313, 0x00caa711, 0x00ccaa10, 0x00cbab0c, 0x00cbac0c, 0x00ccb00e, 0x00ccb00e, 0x00ccb10d, 0x00cbb10c, 0x00c8b208, 0x00cab40b, 0x00cbb60a, 0x00cbb509, 0x00cbb509, 0x00ccb40a, 0x00ccb40a, 0x00cbb409, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00ccb508, 0x00cbb408, 0x00cbb408, 0x00ccb307, 0x00ccb308, 0x00ccb210, 0x00c9a410, 0x00ad7a02, 0x00a06402, 0x00b47c18, 0x00cba727, 0x00ccb418, 0x00cbb90d, 0x00cbbc0c, 0x00ccb80c, 0x00ccb310, 0x00ba9507, 0x009d6e00, 0x008c5b01, 0x00835107, 0x007f5008, 0x007a5006, 0x007a500c, 0x00794f0b, 0x00794f0b, 0x007b500d, 0x007c510c, 0x0080540a, 0x00875809, 0x008f600b, 0x009f6e0e, 0x00b98f19, 0x00caa81c, 0x00ccb61c, 0x00cab70e, 0x00ccb60b, 0x00ccb015, 0x00bc9612, 0x008b6200, 0x00704900, 0x00603c00, 0x00563506, 0x004f3005, 0x004c3007, 0x00482e08, 0x00452c08, 0x00402705, 0x00402506, 0x003e2508, 0x003c2509, 0x003a2409, 0x00362007, 0x00352007, 0x00342008, 0x00331f07, 0x00331e0a, 0x00341d0a, 0x00341c0b, 0x00341c0c, 0x00311a0a, 0x002f1b0a, 0x002c1c0c, 0x002b1c0c, 0x00281c0c, 0x00211809, 0x001d1508, 0x001b1408, 0x00161305, 0x00131004, 0x00100e02, 0x000c0e00, 0x00080e00, 0x00090f02, 0x000a1002, 0x000b0e02, 0x000d0e02, 0x00121004, 0x00181508, 0x0017150b, 0x00121006, 0x00100d02, 0x00100d01, 0x000f0e04, 0x000f0f05, 0x000c0f05, 0x00090f06, 0x00090f06, 0x00090e05, 0x00090e05, 0x000b0e05, 0x000b0e05, 0x000c1007, 0x0010130a, 0x00141810, 0x00191e17, 0x00171c15, 0x00171c17, 0x00182018, 0x00182018, 0x00192018, 0x00192018, 0x001b201a, 0x001c201b, 0x001c201b, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x0014180b, 0x00191c09, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x002d2f0a, 0x0030310c, 0x0032330c, 0x0036370c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x003e400c, 0x0040400d, 0x0041420d, 0x0043440e, 0x0044450e, 0x0045470e, 0x0045470e, 0x0047480e, 0x0048490f, 0x0048490f, 0x00494a0f, 0x00494a0f, 0x004b4c10, 0x00494a0f, 0x00494a0f, 0x004b4c10, 0x00494a0f, 0x00494a0f, 0x0048490f, 0x0047480e, 0x0047480e, 0x0045470e, 0x0044450e, 0x0043440e, 0x0041420e, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x00393b0d, 0x0038380c, 0x0036370c, 0x0032330c, 0x0030310c, 0x0030310b, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x001a1b15, 0x001a1b15, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x0013160f, 0x000c1008, 0x000d1008, 0x000d1007, 0x000c1005, 0x000d0f05, 0x000d1004, 0x000e0f04, 0x00141308, 0x0018130a, 0x001b1309, 0x00191007, 0x00180f04, 0x001c1207, 0x001f150a, 0x0022180d, 0x00241a0c, 0x00271d0c, 0x002c200d, 0x002e200b, 0x0030220a, 0x0033240a, 0x0034230a, 0x0038240c, 0x0039240b, 0x003c2509, 0x0040290c, 0x00422c0c, 0x00442d0d, 0x00442f0d, 0x00442f0c, 0x0046300a, 0x0049330c, 0x004d360f, 0x004e360e, 0x0051380d, 0x0052390a, 0x00543a0a, 0x0059400c, 0x005c400d, 0x005f420f, 0x00654610, 0x006b4b10, 0x006e4d0f, 0x0070500f, 0x0076540f, 0x007c5811, 0x00765006, 0x00714900, 0x007e5505, 0x00ac8629, 0x00cbaa34, 0x00ccb51e, 0x00caba09, 0x00c8bb04, 0x00ccb70b, 0x00c7a512, 0x00a67802, 0x008f5900, 0x00804c00, 0x00754804, 0x006a4602, 0x00664204, 0x00644008, 0x00643f08, 0x00643e07, 0x00653e08, 0x00653e08, 0x00664009, 0x006c460c, 0x00714b0d, 0x00784e0c, 0x00845510, 0x009d6f13, 0x00c39c22, 0x00cbb419, 0x00c8b909, 0x00c8bb05, 0x00ccb80c, 0x00cbb017, 0x00aa7d04, 0x00945e00, 0x00a87410, 0x00caa022, 0x00ccb118, 0x00cab40d, 0x00cab50c, 0x00cbb608, 0x00c9b80a, 0x00c9b80a, 0x00cbb80b, 0x00cbb909, 0x00cbb909, 0x00cbb909, 0x00cbb80a, 0x00cbb80b, 0x00cbb80b, 0x00cbb90a, 0x00ccb80a, 0x00ccb80b, 0x00ccb80c, 0x00ccb70d, 0x00ccb70d, 0x00ccb60c, 0x00cbb60a, 0x00cab50c, 0x00ccb50d, 0x00ccb20f, 0x00cbae10, 0x00c9aa12, 0x00c5a413, 0x00c09c12, 0x00b4900f, 0x009e7a09, 0x008c6004, 0x00825810, 0x006d4910, 0x004c2f04, 0x003b2604, 0x00332106, 0x002e1c04, 0x00281704, 0x00241406, 0x00231407, 0x001f1205, 0x001d1104, 0x001a1305, 0x00181306, 0x00151306, 0x00151308, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00181309, 0x00181309, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x00181407, 0x001a1405, 0x001a1305, 0x001a1204, 0x001b1206, 0x001a1206, 0x00191307, 0x001b1407, 0x00181105, 0x00161104, 0x00181306, 0x00181205, 0x00181205, 0x00171406, 0x00171406, 0x00171406, 0x00171406, 0x00171408, 0x00171408, 0x00171408, 0x00171408, 0x00161308, 0x00161208, 0x00171309, 0x00171309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00171309, 0x00171309, 0x00181309, 0x001b130b, 0x001c140a, 0x001f1308, 0x00211406, 0x00251507, 0x00291909, 0x002d1c0d, 0x00301c0c, 0x00351e08, 0x00513613, 0x006a4715, 0x007a4e0e, 0x00905e09, 0x00a06c04, 0x00a87403, 0x00ac7c08, 0x00b5860c, 0x00bb8d0d, 0x00c0940e, 0x00c49a10, 0x00c89f14, 0x00c9a115, 0x00cca717, 0x00caac12, 0x00ccb013, 0x00cbb012, 0x00cbb010, 0x00cbb010, 0x00ccb110, 0x00cab110, 0x00cbb30e, 0x00cbb50b, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00ccb508, 0x00cbb408, 0x00cbb408, 0x00ccb307, 0x00ccb307, 0x00ccb10c, 0x00c9a50c, 0x00ad7c00, 0x00a16600, 0x00b47e13, 0x00cca821, 0x00ccb614, 0x00cab80e, 0x00cbbb0e, 0x00ccb80c, 0x00ccad0c, 0x00ad8000, 0x00976300, 0x00885503, 0x007f5009, 0x007b5008, 0x00784f05, 0x007a4e0c, 0x007a4d0c, 0x007a4d0c, 0x007c5010, 0x007c5010, 0x007f5111, 0x00825210, 0x0085540f, 0x008d5b09, 0x009e6d09, 0x00c29a1b, 0x00ccb119, 0x00c9b709, 0x00cab806, 0x00ccb40f, 0x00c8a812, 0x009e7803, 0x007e5200, 0x006b4202, 0x00623d0a, 0x005a3809, 0x00533408, 0x00503208, 0x004c3008, 0x004a2e09, 0x00492c09, 0x00482d0b, 0x00452b0a, 0x0042280a, 0x0040270c, 0x003f270d, 0x003c250b, 0x00382108, 0x00382008, 0x00382008, 0x00381f09, 0x00371d09, 0x00361d09, 0x00311c08, 0x002e1c08, 0x002d1c0a, 0x002c1d0b, 0x002a1c0b, 0x00271c0a, 0x00251a0a, 0x00211808, 0x0021150b, 0x001d1409, 0x00160f03, 0x00100d01, 0x000e1003, 0x000c0f03, 0x000c0e04, 0x000c0f03, 0x000a0d00, 0x00131408, 0x0018150c, 0x00151208, 0x00130f04, 0x00131004, 0x00100f06, 0x000f0f05, 0x000c0f05, 0x000a0f06, 0x000a0f06, 0x00090e05, 0x00090e05, 0x000b0e05, 0x000b0e05, 0x000c1007, 0x000e1109, 0x0010160c, 0x00171b14, 0x00161b14, 0x00161b15, 0x00181f17, 0x00181f17, 0x00192018, 0x00192018, 0x001b201a, 0x001c201b, 0x001c201b, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0b, 0x00191c09, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0b, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x00393b0c, 0x00393b0d, 0x003b3c0d, 0x003c3e0c, 0x003e400c, 0x0041420d, 0x0041420e, 0x0043440e, 0x0044450e, 0x0044450e, 0x0044450d, 0x0045470e, 0x0047480e, 0x0047480e, 0x0045470e, 0x0045470e, 0x0047480e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0044450e, 0x0043440e, 0x0043440e, 0x0041420d, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0b, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c16, 0x00181c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181b14, 0x0012150f, 0x000d1009, 0x000d1008, 0x000c1007, 0x000c1005, 0x000e1005, 0x000f1004, 0x00101105, 0x0017140a, 0x0018140b, 0x001b1308, 0x001b1106, 0x00231508, 0x00251508, 0x00281809, 0x002b1c0b, 0x002c1e0c, 0x002f200c, 0x0033220c, 0x0034230a, 0x0035250a, 0x0037280b, 0x00382909, 0x003d2c0c, 0x003e2c0c, 0x00402c0c, 0x00442e0b, 0x0048300c, 0x004a300a, 0x004c320b, 0x004f340c, 0x004f3409, 0x0053370b, 0x00583c0f, 0x00583b0c, 0x005c400c, 0x005d440b, 0x0063450b, 0x006b490d, 0x00745011, 0x007a5412, 0x00815910, 0x008c6411, 0x00957016, 0x00a17e20, 0x00ac8a26, 0x00b5922b, 0x00966d0c, 0x007c4f00, 0x008b5f09, 0x00bc952e, 0x00cbaf28, 0x00ccb715, 0x00cab909, 0x00cbbb04, 0x00ccb60c, 0x00b79406, 0x00946600, 0x00834f00, 0x00764800, 0x006c4502, 0x00674502, 0x00644307, 0x0064400b, 0x00643f07, 0x00623d03, 0x00633e03, 0x00654006, 0x00684209, 0x006c440c, 0x00744b10, 0x0079500c, 0x0087590e, 0x00a77a1a, 0x00c9a428, 0x00ccb41a, 0x00c9b80d, 0x00c8b909, 0x00ccb70e, 0x00cba717, 0x00a47203, 0x00945f00, 0x00b4821b, 0x00cca523, 0x00ccb115, 0x00c9b40c, 0x00c8b608, 0x00c8b705, 0x00c8b70b, 0x00c9b80c, 0x00cbb80b, 0x00ccb90c, 0x00cbb809, 0x00cbb809, 0x00ccb809, 0x00ccb808, 0x00ccb806, 0x00ccb806, 0x00cbb809, 0x00cbb70c, 0x00ccb60d, 0x00ccb40d, 0x00ccb310, 0x00ccb010, 0x00ccae10, 0x00ccab11, 0x00cca817, 0x00c69f15, 0x00b9900f, 0x00ab8007, 0x00a07403, 0x00936801, 0x00855b00, 0x00775000, 0x006c4501, 0x0067430c, 0x00523305, 0x003f2500, 0x00362201, 0x00312004, 0x002c1c02, 0x00251804, 0x00241707, 0x00201406, 0x001d1307, 0x001b1205, 0x00191107, 0x00181207, 0x00171307, 0x00171308, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x0018140a, 0x0018140a, 0x00181309, 0x00181308, 0x001a1308, 0x001a1407, 0x001a1407, 0x001b1307, 0x001a1407, 0x001b1407, 0x001b1406, 0x001a1305, 0x001a1306, 0x001b1307, 0x001a1407, 0x001a1306, 0x00181004, 0x00161105, 0x00171307, 0x00171307, 0x00181307, 0x00181307, 0x00191207, 0x00191207, 0x00181307, 0x00181306, 0x00181307, 0x00181307, 0x00181307, 0x00181306, 0x00181208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191307, 0x001c1308, 0x001c1408, 0x001f1408, 0x00211407, 0x00241406, 0x00281809, 0x002c1c0d, 0x002e1c0c, 0x00321d08, 0x00392106, 0x0052320c, 0x0068400e, 0x0078490c, 0x00814f07, 0x00895406, 0x008c5607, 0x008f5904, 0x00925d00, 0x00986401, 0x009f6b01, 0x00a67004, 0x00ae7809, 0x00b47f0c, 0x00b8880b, 0x00ba8c0c, 0x00c39814, 0x00c89d17, 0x00cba016, 0x00cca415, 0x00cba612, 0x00ccab14, 0x00ccae0f, 0x00ccb00d, 0x00ccb10b, 0x00cab20a, 0x00c9b70b, 0x00c8b609, 0x00c8b409, 0x00cbb40b, 0x00c8b307, 0x00c8b406, 0x00cab406, 0x00ccb307, 0x00ccb208, 0x00ccb20c, 0x00c8a50c, 0x00af7f00, 0x00a16700, 0x00b78015, 0x00cca820, 0x00ccb513, 0x00cab80a, 0x00cabb0c, 0x00ccb80c, 0x00c9a80d, 0x00ad7c01, 0x00955d01, 0x00865405, 0x007a5008, 0x00765007, 0x00744e04, 0x00774c0b, 0x00794c0c, 0x007a4d0c, 0x007c500f, 0x007c500d, 0x007d5110, 0x00805110, 0x0080510f, 0x0084560c, 0x0093600c, 0x00ac7f11, 0x00c9a91b, 0x00c8b60b, 0x00c8b906, 0x00cbb60c, 0x00ccb114, 0x00b38c0c, 0x00885b00, 0x00784a06, 0x0073470e, 0x00684006, 0x00633e05, 0x005e3b09, 0x0057360a, 0x0055340c, 0x00513008, 0x004f2e08, 0x004d2e0b, 0x004a2c0c, 0x00492a0e, 0x00462a0e, 0x0042290c, 0x003f280b, 0x003d2608, 0x003d2407, 0x003c240a, 0x003a220a, 0x00382108, 0x00362108, 0x00332008, 0x002f1d07, 0x002e1c08, 0x002d1d08, 0x002d1c09, 0x002c1c0a, 0x002b1b09, 0x002b1a0c, 0x002a190c, 0x0024150a, 0x001c1005, 0x00151004, 0x00111005, 0x000f1106, 0x00091003, 0x00080e01, 0x00111407, 0x0018160c, 0x001a140a, 0x00181108, 0x00151006, 0x00121004, 0x00100f06, 0x000e1007, 0x000c1007, 0x000c1006, 0x000b0f06, 0x000a0f06, 0x000a0f04, 0x000c0f04, 0x000c1006, 0x000d1008, 0x0010150c, 0x00151a12, 0x00161b14, 0x00161b15, 0x00181d18, 0x00181e18, 0x00181f18, 0x00192019, 0x001b201a, 0x001b211a, 0x001b2019, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0b, 0x00191c09, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0024250b, 0x0026280b, 0x00292b0a, 0x002c2d0a, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x003c3e0d, 0x003c3e0c, 0x0040400d, 0x0040400d, 0x0040400d, 0x0041420e, 0x0041420e, 0x0043440e, 0x0043440e, 0x0044450e, 0x0044450e, 0x0043440e, 0x0043440e, 0x0041420e, 0x0041420d, 0x0040400d, 0x0040400d, 0x003e400c, 0x003c3e0c, 0x003c3e0d, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x002c2d0b, 0x0026280b, 0x0026280c, 0x0024250b, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x00191c16, 0x00171a14, 0x0011140d, 0x000d100a, 0x000c1008, 0x000c1007, 0x000d1008, 0x000f1005, 0x00101005, 0x00151408, 0x0018150a, 0x00181409, 0x001a1307, 0x00211609, 0x0029190b, 0x002c190a, 0x002d1c09, 0x00301f09, 0x0032220b, 0x0035240e, 0x003a270f, 0x003c280d, 0x003d2c0c, 0x003f2d0c, 0x0040300a, 0x0048330c, 0x0048340f, 0x00483410, 0x004c3410, 0x0050380f, 0x0050380b, 0x00533a0b, 0x00583d0c, 0x005c3d0b, 0x0061400d, 0x0065400a, 0x006a4409, 0x00704b0a, 0x0077530c, 0x00805910, 0x008c6416, 0x00987019, 0x00a77c20, 0x00b48b22, 0x00bf9824, 0x00c8a729, 0x00caad26, 0x00ccb529, 0x00cbb128, 0x00ae8810, 0x008b5f00, 0x0091670c, 0x00c29c29, 0x00caaf1c, 0x00ccb70f, 0x00ccb80d, 0x00ccb90a, 0x00ccb510, 0x00ba980d, 0x00946a00, 0x00815300, 0x00784b04, 0x00704708, 0x006c4609, 0x0068450d, 0x00674410, 0x0065420c, 0x00634008, 0x00624007, 0x0066450c, 0x0069470f, 0x006d4810, 0x00784f15, 0x007f540f, 0x00906712, 0x00b99224, 0x00ccad24, 0x00ccb711, 0x00cab909, 0x00ccb90c, 0x00ccb20d, 0x00bf920f, 0x00986400, 0x009c6806, 0x00c29424, 0x00cca920, 0x00ccb012, 0x00ccb10c, 0x00cbb404, 0x00c9b604, 0x00cab60b, 0x00cbb60c, 0x00ccb50c, 0x00ccb60c, 0x00cbb40c, 0x00cbb40c, 0x00cab40c, 0x00cbb40a, 0x00ccb509, 0x00ccb509, 0x00ccb30e, 0x00caae0e, 0x00ccac12, 0x00c8a40f, 0x00c49f10, 0x00c0980e, 0x00ba900b, 0x00b18407, 0x00a87804, 0x00986801, 0x008d5c00, 0x00825300, 0x007d5000, 0x00744901, 0x00704404, 0x00603900, 0x00533100, 0x004c2f03, 0x003f2700, 0x00382200, 0x00342103, 0x002e1f03, 0x002a1c02, 0x00241804, 0x00221807, 0x001e1508, 0x001c1407, 0x001a1107, 0x00191107, 0x00181107, 0x00171207, 0x00171308, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x0019140b, 0x0019140b, 0x00181309, 0x00181308, 0x001b1308, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001a1407, 0x001a1407, 0x001b1407, 0x001b1407, 0x00191306, 0x00181004, 0x00151106, 0x00161307, 0x00171408, 0x00181308, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00181306, 0x00181404, 0x00181404, 0x00181404, 0x00191305, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001b1206, 0x001b1206, 0x001c1305, 0x001c1407, 0x001f1408, 0x00221507, 0x00241406, 0x00281808, 0x002c1c0c, 0x002d1c0a, 0x00301b08, 0x00321c07, 0x00371c00, 0x00442402, 0x00532e06, 0x005d3405, 0x00683906, 0x006e3f06, 0x00724305, 0x00774804, 0x007d4d05, 0x00855206, 0x008c5506, 0x00925803, 0x00975d02, 0x009a6000, 0x009e6401, 0x00a46b04, 0x00a86f04, 0x00ad7405, 0x00b27904, 0x00b88508, 0x00be8e0c, 0x00c4940d, 0x00c89d11, 0x00cca515, 0x00cca814, 0x00cbab10, 0x00c8ad0c, 0x00caaf0e, 0x00ccb10f, 0x00ccb30c, 0x00ccb40c, 0x00ccb40a, 0x00cbb308, 0x00cbb309, 0x00ccb20f, 0x00c8a50e, 0x00b28204, 0x009f6500, 0x00b27c12, 0x00cba623, 0x00ccb414, 0x00c9b808, 0x00c9ba0a, 0x00ccb70f, 0x00caaa0f, 0x00ae8000, 0x00945f00, 0x00875406, 0x007c5108, 0x00755109, 0x00744f07, 0x00784e0b, 0x00784e0b, 0x00784f0c, 0x0079500c, 0x007b500a, 0x007c500b, 0x007c500b, 0x007d510c, 0x007d5409, 0x0089590c, 0x009f700e, 0x00c4a01c, 0x00c8b410, 0x00c8b809, 0x00cab60d, 0x00ccb312, 0x00c09b13, 0x00936400, 0x00804f04, 0x0080500e, 0x007c4d08, 0x00764804, 0x00724608, 0x006e430d, 0x00684010, 0x00633c0c, 0x005d3709, 0x0058330a, 0x0054300c, 0x0051300c, 0x004c2f0a, 0x00482e08, 0x00462e09, 0x00462e0a, 0x00452b09, 0x0043280a, 0x00402709, 0x003f2508, 0x003d260a, 0x003c250b, 0x0039230b, 0x00362008, 0x00352008, 0x00342009, 0x00321d0a, 0x00311b08, 0x00301c08, 0x00301c0a, 0x002c1909, 0x0028180a, 0x00201609, 0x00181306, 0x00141407, 0x000c1104, 0x000c1104, 0x00111206, 0x0019150b, 0x001e150c, 0x001c1409, 0x00161006, 0x00131005, 0x00100f08, 0x000f0f08, 0x000c1007, 0x000c1007, 0x000c0f06, 0x000a0f06, 0x000a1004, 0x000c0f04, 0x000c1005, 0x000c1006, 0x0010140c, 0x00141910, 0x00161b15, 0x00161b15, 0x00181e18, 0x00181e18, 0x00181e18, 0x0019201a, 0x001a2019, 0x001b2119, 0x001a2018, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x00202309, 0x0024250c, 0x0026280b, 0x00292b0b, 0x002c2d0b, 0x002c2d0a, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x0038380c, 0x0038380c, 0x003b3c0d, 0x003b3c0d, 0x003b3c0d, 0x003c3e0d, 0x003c3e0c, 0x003e400c, 0x003e400c, 0x0040400c, 0x003e400c, 0x003e400c, 0x0040400c, 0x003e400c, 0x003e400c, 0x003c3e0c, 0x003c3e0d, 0x003b3c0d, 0x003b3c0d, 0x00393b0c, 0x0038380c, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002d2f0b, 0x002c2d0a, 0x00292b0b, 0x0026280b, 0x0024250c, 0x0020230a, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180c, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x00161913, 0x0010140d, 0x000d110a, 0x000c1008, 0x000d1009, 0x000d1008, 0x000f1006, 0x00141307, 0x00181708, 0x00191509, 0x001a1509, 0x001e1507, 0x00261b0b, 0x002c1d0a, 0x002f1e0b, 0x00302009, 0x0033230b, 0x0037270c, 0x003c290d, 0x00412c10, 0x00452e0f, 0x0046310c, 0x0048340b, 0x004c340a, 0x0050380c, 0x0052390e, 0x0051380f, 0x00553b10, 0x005c3f10, 0x005d410e, 0x005e440d, 0x0064460c, 0x006c480b, 0x00744c0c, 0x007b500b, 0x0086590f, 0x00946512, 0x00a37319, 0x00ac821f, 0x00b89325, 0x00c29e27, 0x00c8a628, 0x00ccad25, 0x00ccb11e, 0x00ccb518, 0x00ccb812, 0x00ccbc12, 0x00cbb91c, 0x00b4950c, 0x008f6500, 0x008c6201, 0x00c09c24, 0x00caae18, 0x00ccb60c, 0x00ccb80d, 0x00ccb80d, 0x00ccb511, 0x00c8a918, 0x00a78209, 0x008e6200, 0x00845606, 0x00794f08, 0x00744b09, 0x00714a0d, 0x006f4812, 0x006c440e, 0x0069430c, 0x0068440c, 0x006b480f, 0x006d490e, 0x00744c10, 0x007c5312, 0x008d6313, 0x00ab8523, 0x00c7a828, 0x00ccb518, 0x00ccb90b, 0x00cab806, 0x00cbb30c, 0x00c8a30d, 0x00ab7b07, 0x00905d00, 0x00ac7c13, 0x00c89e24, 0x00cba81b, 0x00ccac12, 0x00ccb00f, 0x00ccb20a, 0x00cab309, 0x00cbb40c, 0x00ccb40c, 0x00cbb40c, 0x00cbb40c, 0x00cbb20e, 0x00ccb010, 0x00ccad11, 0x00c9a90f, 0x00c7a510, 0x00c4a00e, 0x00c09c10, 0x00b8900b, 0x00af8409, 0x00a67a05, 0x009c6d01, 0x00936400, 0x008d5c00, 0x00885901, 0x00845501, 0x007a4c00, 0x00704400, 0x00694004, 0x00643d05, 0x005b3704, 0x00543204, 0x004e3001, 0x00472a01, 0x00402703, 0x00382202, 0x00342004, 0x002f1e05, 0x002c1e08, 0x00281c06, 0x00231905, 0x00201705, 0x001d1407, 0x001b1406, 0x001a1107, 0x00191107, 0x00181208, 0x00171207, 0x00171308, 0x00181209, 0x00181209, 0x00181309, 0x00181309, 0x00181209, 0x00181209, 0x00181309, 0x00181309, 0x0019140b, 0x0019140b, 0x00181309, 0x00181308, 0x001b1308, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001a1306, 0x00181105, 0x00161207, 0x00181408, 0x00171408, 0x00181408, 0x001a1208, 0x001a1208, 0x001a1208, 0x001a1208, 0x00181306, 0x00181404, 0x00181404, 0x00181404, 0x00191305, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001b1206, 0x001b1206, 0x001c1305, 0x001c1406, 0x001f1408, 0x00231608, 0x00251508, 0x00271708, 0x002c1c0b, 0x002d1c0a, 0x00301b09, 0x00311c08, 0x00321d08, 0x00331d05, 0x00391d04, 0x00432206, 0x00492603, 0x004d2900, 0x00502d00, 0x00553101, 0x005c3704, 0x00653b05, 0x006b3d04, 0x00744406, 0x007c4905, 0x00834f04, 0x00875207, 0x008a5607, 0x008c5606, 0x008f5704, 0x00925a04, 0x00955d02, 0x009b6301, 0x009f6700, 0x00a66e02, 0x00ab7306, 0x00b27b0b, 0x00b9840c, 0x00be8d0a, 0x00c1940d, 0x00c59910, 0x00c9a111, 0x00caa50e, 0x00ccaa0f, 0x00ccad0e, 0x00ccb111, 0x00ccab14, 0x00caa316, 0x00b6850c, 0x009c6400, 0x00a97210, 0x00c8a124, 0x00cbb318, 0x00c9b70c, 0x00c9b80c, 0x00ccb70f, 0x00cbaf10, 0x00af8802, 0x00946300, 0x00885401, 0x007e5005, 0x00795009, 0x00755009, 0x00784e0a, 0x00784e0a, 0x00784f0b, 0x0079500b, 0x007b4f09, 0x007b500a, 0x007b500a, 0x007c510b, 0x007c5208, 0x0087560a, 0x00976709, 0x00bc9619, 0x00c9b114, 0x00c8b70c, 0x00cab70c, 0x00ccb411, 0x00c6a316, 0x009e7001, 0x008b5804, 0x009a6719, 0x00a16f1b, 0x0096650f, 0x00895806, 0x00865308, 0x0081510c, 0x007b4b0b, 0x00744609, 0x006e410a, 0x00683c08, 0x005f3807, 0x00593606, 0x00543407, 0x00503408, 0x00503409, 0x004c3107, 0x004c2f08, 0x004a2c08, 0x00452907, 0x00442807, 0x0044270a, 0x00412609, 0x003e2408, 0x003c2408, 0x003b240a, 0x003b230b, 0x00382008, 0x00362008, 0x00341f07, 0x00311d08, 0x002f1b09, 0x002c1a0c, 0x00261a0c, 0x001d1608, 0x00141205, 0x00141105, 0x00141004, 0x00191208, 0x0020160b, 0x001e150b, 0x00181206, 0x00151006, 0x00120f08, 0x000f0f08, 0x000e0e07, 0x000c0f07, 0x000c1006, 0x000a1006, 0x000a1004, 0x000c0f04, 0x000c1005, 0x000c0f04, 0x000d1309, 0x0012170f, 0x00151a14, 0x00161a16, 0x00171d18, 0x00181e18, 0x00181e18, 0x00181f19, 0x001a2019, 0x001b2119, 0x001a2018, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x0024250b, 0x0024250b, 0x0026280b, 0x00292b0b, 0x002c2d0a, 0x002d2f0a, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0032330c, 0x0036370c, 0x0036370c, 0x0036370b, 0x0038380c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x00393b0d, 0x00393b0d, 0x00393b0d, 0x00393b0d, 0x00393b0d, 0x003b3c0d, 0x00393b0d, 0x00393b0c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0034350c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0030310c, 0x002d2f0a, 0x002c2d0a, 0x002c2d0b, 0x0026280b, 0x0026280c, 0x0024250b, 0x00202309, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x001b1d17, 0x001a1c16, 0x00131610, 0x000d120b, 0x000d120b, 0x000c100a, 0x000d120b, 0x000e1108, 0x00121207, 0x00151407, 0x001a1809, 0x001b1608, 0x001d1507, 0x00241909, 0x002b1e0c, 0x0030200c, 0x0034240d, 0x0035250c, 0x0038280c, 0x003f2c0e, 0x00432f0f, 0x0048310f, 0x004c340f, 0x0050370e, 0x00533b0c, 0x00573d0c, 0x005c400c, 0x0061430f, 0x00654310, 0x006b4710, 0x00704b11, 0x00754f0f, 0x0078520c, 0x0080580c, 0x008f6611, 0x009a7015, 0x00a77c20, 0x00b68b28, 0x00c09826, 0x00c8a126, 0x00caa920, 0x00caae1b, 0x00cab219, 0x00cbb618, 0x00cbb817, 0x00ccb812, 0x00cbbb10, 0x00c9bd0d, 0x00cabd0e, 0x00cab814, 0x00b99a0c, 0x00956800, 0x00906001, 0x00b08816, 0x00cbae1a, 0x00cbb40c, 0x00cbb80d, 0x00cab80c, 0x00ccb80d, 0x00ccb417, 0x00c6a81b, 0x00ac880f, 0x009a7008, 0x00885f04, 0x00825704, 0x007e5208, 0x00794d09, 0x00764c09, 0x00764b0b, 0x00744b0a, 0x00754d08, 0x00785006, 0x00825708, 0x00916611, 0x00ae8724, 0x00c6a430, 0x00ccb424, 0x00c9b910, 0x00ccba0c, 0x00cbb50f, 0x00cbae1a, 0x00b6870c, 0x00945d00, 0x009b6408, 0x00bd8c24, 0x00c79921, 0x00c49914, 0x00c59b10, 0x00c8a011, 0x00cba513, 0x00cca913, 0x00ccaa14, 0x00cca912, 0x00cba811, 0x00cba711, 0x00c8a211, 0x00c49b10, 0x00bd930f, 0x00b08406, 0x00a47704, 0x009e6f04, 0x00946400, 0x008c5c00, 0x00895800, 0x00815200, 0x007c4c00, 0x007a4801, 0x00754403, 0x006f4104, 0x00694004, 0x00603c02, 0x00583801, 0x00533506, 0x00503307, 0x00492e07, 0x00432b04, 0x00402807, 0x003e2708, 0x003a2309, 0x00372008, 0x00301e08, 0x002c1e08, 0x00291c09, 0x00231908, 0x00221805, 0x00201604, 0x001c1407, 0x001a1306, 0x001a1107, 0x00191108, 0x001a1308, 0x00171207, 0x00161207, 0x00171008, 0x00181108, 0x00181309, 0x00181309, 0x00181108, 0x00181108, 0x00181309, 0x00181309, 0x0019140b, 0x0019140b, 0x00191209, 0x00191208, 0x001b1308, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1408, 0x00181206, 0x00171408, 0x0018150a, 0x00181408, 0x00181408, 0x001b1308, 0x001b1308, 0x001b1308, 0x001b1308, 0x00181306, 0x00181404, 0x00181404, 0x00181404, 0x00191305, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001c1307, 0x001c1307, 0x001c1305, 0x001c1305, 0x001f1408, 0x0023170a, 0x00251709, 0x0027170a, 0x0029190b, 0x002b1908, 0x002e1a09, 0x00301c0a, 0x002e1d09, 0x00301e0a, 0x00351e09, 0x003d210b, 0x00432408, 0x00462806, 0x00482908, 0x00482908, 0x00492c08, 0x004a2b07, 0x004d2b03, 0x00543003, 0x00593101, 0x005e3401, 0x00633804, 0x00663c04, 0x00683f04, 0x0074480d, 0x00794c0d, 0x007e4e0c, 0x0084510a, 0x008b5409, 0x008f5609, 0x00905607, 0x00955908, 0x00975c05, 0x00996002, 0x009d6604, 0x00a36c04, 0x00a87204, 0x00b07c08, 0x00b8840a, 0x00c08d0f, 0x00c59412, 0x00c79a17, 0x00c89c1d, 0x00c08c1d, 0x00a06708, 0x009a6404, 0x00b8911a, 0x00cab01c, 0x00c9b613, 0x00cbb80f, 0x00ccb80f, 0x00ccb411, 0x00bc9a0c, 0x009a6e00, 0x008e5a00, 0x00845004, 0x007e520b, 0x0079540d, 0x007a500c, 0x00784f0b, 0x0078500b, 0x0079500c, 0x007b500c, 0x007c510c, 0x007d520d, 0x0080540e, 0x007c5308, 0x0087560c, 0x0095650b, 0x00bc941e, 0x00cab11a, 0x00c9b70f, 0x00cab70c, 0x00ccb50f, 0x00c9a814, 0x00a77801, 0x00976202, 0x00b67f24, 0x00c7962f, 0x00c09222, 0x00b7881b, 0x00ab7910, 0x00a06c0a, 0x00935e07, 0x008b5705, 0x00875407, 0x00815006, 0x007a4b08, 0x00754809, 0x006f440c, 0x00623c05, 0x005c3c09, 0x00583908, 0x0055380a, 0x00523409, 0x004e3108, 0x004c3008, 0x004b2f0b, 0x00482d0c, 0x00462c0a, 0x00442b0a, 0x00432a0b, 0x0041250a, 0x00402408, 0x003e2408, 0x003b2306, 0x00382108, 0x00351f09, 0x00361c0e, 0x00311c0e, 0x0027170a, 0x00201608, 0x001e150b, 0x001e140b, 0x001c1208, 0x001f160b, 0x0020180c, 0x001c1408, 0x00181108, 0x0015110a, 0x0013100a, 0x00101008, 0x000f0e06, 0x000d0f06, 0x000b1006, 0x000a1004, 0x000c0f04, 0x000c0f04, 0x000c0f04, 0x000c1106, 0x0010140c, 0x00141914, 0x00151916, 0x00151b15, 0x00171d18, 0x00181e18, 0x00181f19, 0x001a2019, 0x001b2119, 0x00192018, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x00202309, 0x0024250b, 0x0024250b, 0x00292b0b, 0x00292b0b, 0x00292b0a, 0x002c2d0a, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0030310c, 0x0034350c, 0x0032330c, 0x0036370c, 0x0034350c, 0x0036370c, 0x0036370c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0036370c, 0x0036370c, 0x0034350c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x00292b0a, 0x00292b0a, 0x0026280b, 0x0026280c, 0x0024250c, 0x0020230a, 0x00202308, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x001b1e18, 0x00181c15, 0x0010140c, 0x000d120b, 0x000d120b, 0x000c110a, 0x000e1109, 0x00101208, 0x00141307, 0x00181407, 0x001c1809, 0x001a1405, 0x001f1606, 0x00281c09, 0x002f200b, 0x0035250c, 0x003a2a0f, 0x003e2c0e, 0x0042300e, 0x00483410, 0x004c3610, 0x00533811, 0x00583a10, 0x005f3f12, 0x00654611, 0x00694a0f, 0x006f4f0f, 0x0074500f, 0x007f520f, 0x0084570f, 0x00906214, 0x00986b15, 0x00a67a16, 0x00b08518, 0x00ba901c, 0x00c59d21, 0x00c8a527, 0x00c9aa24, 0x00ccb223, 0x00ccb418, 0x00ccb510, 0x00cbb80c, 0x00c9b90d, 0x00c8ba10, 0x00c9bb0f, 0x00cbbb0f, 0x00cabb10, 0x00c8bb10, 0x00c7ba10, 0x00c9b712, 0x00c1a010, 0x00a37402, 0x008c5800, 0x00966c06, 0x00bf9c19, 0x00ccb316, 0x00cbb80f, 0x00c8ba08, 0x00caba09, 0x00cbb90f, 0x00ccb514, 0x00cbae1c, 0x00c4a31f, 0x00b6911b, 0x00a67f11, 0x0099710c, 0x0092690c, 0x008c6208, 0x008a5f08, 0x008a6008, 0x0090650b, 0x00996e10, 0x00aa7e19, 0x00be9428, 0x00c6a42b, 0x00c9af24, 0x00cab818, 0x00c8bc0d, 0x00ccb90f, 0x00ccb218, 0x00b79014, 0x00996203, 0x008a4d00, 0x00955809, 0x00ab711b, 0x00a46c0d, 0x00a06704, 0x00a16803, 0x00a46d04, 0x00ab7608, 0x00b17d0c, 0x00b37e0c, 0x00b27d0b, 0x00ad7805, 0x00ad7807, 0x00a36e02, 0x00986400, 0x00905c00, 0x00895700, 0x00825100, 0x007c4c00, 0x00784901, 0x00734701, 0x006e4300, 0x00673d00, 0x00643b00, 0x00613802, 0x00603605, 0x005a3505, 0x00553404, 0x00513406, 0x004c3407, 0x00493307, 0x00473108, 0x00422e04, 0x003d2a04, 0x003b270c, 0x003b250d, 0x0036200a, 0x00331d0a, 0x002e1c0a, 0x00291a08, 0x00261a09, 0x00201807, 0x00201607, 0x001f1406, 0x001c1306, 0x001a1306, 0x00191107, 0x001a1208, 0x00191308, 0x00171307, 0x00161207, 0x00161008, 0x00171008, 0x00181208, 0x00181209, 0x00181208, 0x00181108, 0x00181209, 0x00181209, 0x0019140a, 0x0019140a, 0x00191208, 0x00191208, 0x001b1308, 0x001b1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001b1407, 0x001b1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001a1306, 0x00181207, 0x001a1409, 0x001a1408, 0x001a1408, 0x001c1308, 0x001c1208, 0x001c1208, 0x001c1308, 0x001a1304, 0x001a1304, 0x001a1304, 0x001a1304, 0x001a1305, 0x001a1207, 0x001a1307, 0x001a1307, 0x001a1307, 0x001a1306, 0x001a1306, 0x001a1306, 0x001b1206, 0x001c1308, 0x001c1308, 0x001c1306, 0x001d1306, 0x00201408, 0x0023160a, 0x00241608, 0x00251608, 0x00281608, 0x00281608, 0x002c1708, 0x002e1b08, 0x00301c06, 0x00301d06, 0x00341d05, 0x00381f04, 0x003d2106, 0x003f2408, 0x0043270b, 0x0044280c, 0x0044280c, 0x00452b0c, 0x00472c09, 0x004a2c07, 0x00492b03, 0x004b2b03, 0x004e2e06, 0x004f2f05, 0x004f3105, 0x004f3004, 0x00513003, 0x00583404, 0x005d3803, 0x00663c03, 0x006b3d04, 0x00744308, 0x0079470b, 0x007c4c0e, 0x007f500f, 0x00835310, 0x0085550c, 0x0089560a, 0x00905505, 0x00985b08, 0x009c5c03, 0x00a06302, 0x00a26c02, 0x00a8730a, 0x00a06a0c, 0x008e5600, 0x00915c04, 0x00a97d11, 0x00c8a71f, 0x00ccb418, 0x00ccb70f, 0x00ccb80b, 0x00ccb80c, 0x00c5aa11, 0x00a98207, 0x00966100, 0x00895402, 0x0084540b, 0x00805510, 0x007d5410, 0x007a510e, 0x0078500e, 0x0078500f, 0x007d5411, 0x007f530f, 0x0080540f, 0x0081560f, 0x007e5309, 0x0088570d, 0x0096640d, 0x00bf9421, 0x00cbb11c, 0x00c9b711, 0x00cab70c, 0x00ccb60c, 0x00ccac14, 0x00ae7d03, 0x009e6703, 0x00ba8320, 0x00ca9d26, 0x00cba61e, 0x00cca51c, 0x00caa01c, 0x00c59818, 0x00bd8c18, 0x00b07f10, 0x00a4730b, 0x00996805, 0x00925e05, 0x008c5805, 0x008a570d, 0x0081500c, 0x00754b0d, 0x006f480d, 0x0068440c, 0x00623f0c, 0x005c3a0b, 0x0058380b, 0x0054360c, 0x0050340c, 0x004d320b, 0x004c300b, 0x004c300c, 0x00482c0b, 0x00452908, 0x0044280a, 0x00422709, 0x003f2509, 0x003c2309, 0x003c210c, 0x0039200e, 0x00301a0a, 0x002a190a, 0x00281a0c, 0x0026190d, 0x0022170b, 0x001f1308, 0x0023180c, 0x0020160a, 0x001b1308, 0x0018130a, 0x0014120a, 0x00121008, 0x00101007, 0x000e1006, 0x000c1005, 0x000b1005, 0x000c0f04, 0x000c0f04, 0x000c0f03, 0x000a1004, 0x000e130a, 0x00141914, 0x00141815, 0x00141a15, 0x00161c17, 0x00181d18, 0x00181e19, 0x001a201b, 0x001a2019, 0x00192019, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x0024250b, 0x0024250c, 0x0024250b, 0x0026280b, 0x00292b0b, 0x00292b0a, 0x00292b0a, 0x002d2f0a, 0x002c2d0a, 0x0030310c, 0x0030310c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0030310c, 0x0030310c, 0x0030310c, 0x0030310c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x0026280a, 0x0026280b, 0x0026280c, 0x0024250c, 0x0020230a, 0x00202308, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c09, 0x00141809, 0x0014180b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x00191c16, 0x00191c16, 0x00191c16, 0x00171a14, 0x0010130c, 0x000f120a, 0x000f120a, 0x000e1109, 0x00101009, 0x00121107, 0x00171408, 0x001d170a, 0x00201809, 0x001c1304, 0x00281c0c, 0x002f210b, 0x0035260d, 0x003b2a0c, 0x00402e0c, 0x00443108, 0x004c350b, 0x00523a0c, 0x005c400f, 0x00644310, 0x006e4812, 0x00764d12, 0x007f5612, 0x00855d12, 0x008d6713, 0x009a7318, 0x00a8781b, 0x00b18420, 0x00ba9023, 0x00c09822, 0x00c7a21b, 0x00cba81a, 0x00ccac17, 0x00ccb018, 0x00ccb418, 0x00ccb817, 0x00ccb811, 0x00ccb80c, 0x00cab90a, 0x00cab90a, 0x00cbb90c, 0x00ccba0d, 0x00ccbb0e, 0x00cbbc0c, 0x00cbbc0c, 0x00cbbb0d, 0x00c9bc0d, 0x00c8ba0c, 0x00cbb317, 0x00b48d10, 0x00926100, 0x008a5a00, 0x009c7507, 0x00c1a11b, 0x00c9b116, 0x00cab80d, 0x00c8ba09, 0x00cabb08, 0x00cbbb07, 0x00ccb712, 0x00ccb51b, 0x00ccb31e, 0x00c9af21, 0x00c3a621, 0x00bc9f21, 0x00b8981c, 0x00b8961f, 0x00b89420, 0x00bb9621, 0x00c49e25, 0x00c9a425, 0x00ccaa24, 0x00ccb21b, 0x00ccb813, 0x00cab90b, 0x00c8ba0a, 0x00ccb410, 0x00bb9910, 0x00996a06, 0x00834b00, 0x00723e00, 0x00714000, 0x00754500, 0x00744200, 0x00713f00, 0x00743f02, 0x00754100, 0x007c4800, 0x00804b00, 0x00824c00, 0x00834c00, 0x00834c00, 0x00824b00, 0x00784400, 0x00724000, 0x00724202, 0x006c4003, 0x00663c00, 0x00633d03, 0x00603c04, 0x005a3a02, 0x00533600, 0x00513601, 0x00503404, 0x00503407, 0x00503407, 0x004c3006, 0x004b3008, 0x00472f09, 0x00422e0a, 0x00402c08, 0x003d2a06, 0x003c2905, 0x00382503, 0x00362106, 0x00342007, 0x00331d08, 0x002f1908, 0x002c1909, 0x00281908, 0x00221707, 0x00201806, 0x00201508, 0x001e1308, 0x001c1206, 0x001a1306, 0x00191207, 0x00181308, 0x00181308, 0x00151307, 0x00161207, 0x00171008, 0x00151007, 0x00151007, 0x00181108, 0x00181309, 0x00171008, 0x00181108, 0x00181108, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x001b1308, 0x001b1308, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1307, 0x00181105, 0x001c1509, 0x001c1408, 0x001c1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001c1104, 0x001c1104, 0x001c1107, 0x001b1108, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x00201408, 0x00211408, 0x00221407, 0x00241508, 0x00241409, 0x00271308, 0x00291607, 0x002d1807, 0x002f1b07, 0x002f1b05, 0x00311b03, 0x00331c01, 0x00341d04, 0x00372006, 0x003a2108, 0x003c230a, 0x0040240c, 0x00402508, 0x00402505, 0x00402504, 0x00412703, 0x00412804, 0x00422a07, 0x00442907, 0x00442908, 0x00472908, 0x004a2d0a, 0x004c2e09, 0x004e2e05, 0x00503003, 0x00533104, 0x00553004, 0x00573105, 0x00583205, 0x005d3508, 0x00613a09, 0x00643c0b, 0x006b3f0b, 0x00734005, 0x00784405, 0x00804a07, 0x00844f06, 0x00885306, 0x00885305, 0x00855004, 0x00814d02, 0x00885706, 0x009b680c, 0x00c29620, 0x00ccad1c, 0x00ccb510, 0x00ccb907, 0x00ccb907, 0x00cbb411, 0x00c09d14, 0x00a47503, 0x008f5e00, 0x00885704, 0x0084540c, 0x0080540e, 0x007c5210, 0x0079500f, 0x007a5112, 0x007d5211, 0x007f530f, 0x0080540d, 0x0083580e, 0x00835609, 0x008c5a0e, 0x009c6c11, 0x00c29a23, 0x00ccb21b, 0x00c9b611, 0x00cbb60c, 0x00ccb60b, 0x00ccac13, 0x00ae7c03, 0x009f6502, 0x00b98319, 0x00cca422, 0x00ccad14, 0x00cab010, 0x00ccb014, 0x00ccac14, 0x00cca814, 0x00c8a215, 0x00c69d19, 0x00c09418, 0x00bc8b19, 0x00b07b13, 0x00a97113, 0x009c650f, 0x00935c0d, 0x008b580d, 0x00865510, 0x00805110, 0x007c4c0f, 0x0076480f, 0x006f4410, 0x00674110, 0x00613d0e, 0x005b390a, 0x00553508, 0x00513208, 0x004c3008, 0x004c2e09, 0x004a2c0a, 0x00472a0c, 0x0044280b, 0x00422608, 0x0040240a, 0x00371e08, 0x00311c09, 0x002e1e0a, 0x002c1d0b, 0x00271a09, 0x00201404, 0x00211507, 0x0023180a, 0x001d1408, 0x001a1308, 0x00171209, 0x00131008, 0x00110f07, 0x00101006, 0x000c1005, 0x000c1007, 0x000c0f04, 0x000b0e02, 0x000b0e02, 0x000a1004, 0x000e130b, 0x00141813, 0x00141814, 0x00141815, 0x00161a17, 0x00181c19, 0x00191d1a, 0x00191f1a, 0x0019201a, 0x0019201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180b, 0x00141809, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x00202309, 0x0024250b, 0x0024250b, 0x0026280c, 0x0026280b, 0x00292b0b, 0x00292b0b, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x00292b0a, 0x00292b0b, 0x00292b0b, 0x0026280b, 0x0024250b, 0x0024250c, 0x0020230a, 0x00202308, 0x001d2008, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x00191c16, 0x00191c16, 0x00181c15, 0x00141710, 0x000f110b, 0x0010120a, 0x0010120a, 0x00101009, 0x00101008, 0x00141208, 0x001a140a, 0x0020180b, 0x00221808, 0x00241809, 0x002d200e, 0x0035260e, 0x003a2a0c, 0x00402e0c, 0x0048350c, 0x00543c0c, 0x005c3f0b, 0x00644408, 0x00714e0b, 0x007c560d, 0x00886011, 0x00986d14, 0x00a77c1b, 0x00b38821, 0x00bc9324, 0x00c49d28, 0x00c8a426, 0x00cba926, 0x00caab21, 0x00caad1c, 0x00cab011, 0x00ccb611, 0x00ccb810, 0x00ccb90f, 0x00ccba10, 0x00ccba0f, 0x00cbba0c, 0x00cab908, 0x00cab909, 0x00cab90a, 0x00cbba0b, 0x00cbba0b, 0x00cbba0b, 0x00cbbb0a, 0x00ccbb08, 0x00cbba08, 0x00cbbb06, 0x00cbbc08, 0x00ccb614, 0x00bf9e19, 0x00966a03, 0x007f4f00, 0x00835400, 0x009d7407, 0x00bc9a18, 0x00caad18, 0x00ccb416, 0x00ccb70e, 0x00cbba0a, 0x00ccbc0c, 0x00ccbc10, 0x00ccbc14, 0x00ccbc18, 0x00ccbb1b, 0x00ccb91c, 0x00cab61c, 0x00ccb41f, 0x00c9b21e, 0x00cab11d, 0x00ccb41d, 0x00ccb318, 0x00ccb414, 0x00ccb80a, 0x00ccb809, 0x00ccb60e, 0x00cab114, 0x00bc980f, 0x009c7002, 0x00805200, 0x00724100, 0x00603700, 0x005c3700, 0x005b3700, 0x005a3504, 0x005c340a, 0x005d3408, 0x005c3402, 0x005e3502, 0x00603802, 0x00633901, 0x00643a00, 0x00663b01, 0x00663c01, 0x00603800, 0x005b3500, 0x00593503, 0x00543403, 0x00533303, 0x00523404, 0x00513509, 0x004d3408, 0x00493407, 0x00483306, 0x00483207, 0x00483009, 0x0048300b, 0x00442d0a, 0x00412c0c, 0x003e2c0c, 0x003b290d, 0x003a280d, 0x0038250b, 0x0037240a, 0x00332005, 0x00321f06, 0x00321f08, 0x00301c08, 0x002c1808, 0x0029180b, 0x00251508, 0x00241508, 0x00201608, 0x00201508, 0x001e1308, 0x001c1206, 0x001a1306, 0x00191207, 0x00181308, 0x00181308, 0x00151307, 0x00161207, 0x00171008, 0x00171008, 0x00161008, 0x00181108, 0x00181209, 0x00171008, 0x00181108, 0x00181108, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x001b1308, 0x001b1308, 0x001b1407, 0x001b1407, 0x001c1307, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001b1407, 0x001e170b, 0x001d160a, 0x001e150a, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001c1104, 0x001c1104, 0x001c1108, 0x001b1108, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x00201408, 0x00211408, 0x00211507, 0x00221608, 0x00241409, 0x00261408, 0x00261504, 0x00291807, 0x002b1909, 0x002b190a, 0x002c1a08, 0x002d1b06, 0x002e1c06, 0x002f1c09, 0x00321d0b, 0x00341e0a, 0x0038200b, 0x00382108, 0x00392107, 0x003a2305, 0x003b2404, 0x003a2404, 0x003d2506, 0x00402607, 0x00422809, 0x00432809, 0x00442909, 0x00472a08, 0x00482b07, 0x00482c04, 0x00482c05, 0x00482c04, 0x004b2b05, 0x004c2c04, 0x004d2c03, 0x004d2c00, 0x004e2d00, 0x00502f00, 0x00542f01, 0x00583303, 0x005e3603, 0x00643803, 0x00653801, 0x006f4207, 0x0072460a, 0x00754a0b, 0x0080530c, 0x008d5e0f, 0x00ac7f1a, 0x00c5a422, 0x00cab218, 0x00ccb80d, 0x00ccb808, 0x00cbb40f, 0x00cbb11b, 0x00ba960f, 0x00a27703, 0x00946400, 0x008b5904, 0x00845408, 0x00805208, 0x007c5109, 0x007d510d, 0x0080520e, 0x0081530d, 0x0083540b, 0x0086580c, 0x00885908, 0x00915f0c, 0x00ab7d1a, 0x00c9a425, 0x00ccb417, 0x00cab70d, 0x00ccb60b, 0x00cbb70c, 0x00ccac13, 0x00b07b03, 0x009f6502, 0x00b9841b, 0x00cca520, 0x00cab30d, 0x00c8b708, 0x00c9b70e, 0x00ccb30e, 0x00ccb210, 0x00ccb114, 0x00ccae17, 0x00cbab18, 0x00cba117, 0x00c99e19, 0x00c8991c, 0x00c08f18, 0x00b78418, 0x00ac7814, 0x00a26e10, 0x009a640c, 0x00975f0c, 0x0091590d, 0x008c550e, 0x0084510e, 0x007d500c, 0x00774c0b, 0x006c4407, 0x00684009, 0x00613b07, 0x005c3705, 0x00583405, 0x00543108, 0x00502e0a, 0x004b2c07, 0x00472908, 0x003d2306, 0x00382108, 0x00362209, 0x0034210b, 0x002f1e09, 0x00281604, 0x00231403, 0x00241708, 0x00211708, 0x001c1408, 0x00181308, 0x00141007, 0x00110f05, 0x00101005, 0x000d0f05, 0x000c1005, 0x000c0f04, 0x000b0e02, 0x000c1001, 0x000a1004, 0x000e130b, 0x00131712, 0x00141814, 0x00141815, 0x00161a17, 0x00181c18, 0x00181d1a, 0x00191f1a, 0x0019201a, 0x0019201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x00202309, 0x0024250a, 0x0024250b, 0x0024250c, 0x0026280c, 0x0026280b, 0x0026280b, 0x00292b0b, 0x0026280a, 0x00292b0b, 0x0026280a, 0x0026280a, 0x00292b0b, 0x00292b0b, 0x0026280a, 0x0026280a, 0x00292b0b, 0x00292b0b, 0x00292b0b, 0x0026280b, 0x0026280b, 0x0024250b, 0x0024250b, 0x0024250b, 0x00202309, 0x00202309, 0x001d2008, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180e, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x00191e17, 0x00191d18, 0x00191d18, 0x001a1d18, 0x001a1d17, 0x001a1c16, 0x0013140e, 0x0010110b, 0x0012110a, 0x0012110a, 0x00121108, 0x00131008, 0x00181309, 0x001d160c, 0x0022180c, 0x00231808, 0x002c1e0e, 0x0034240f, 0x003b280f, 0x00402d0e, 0x0048340e, 0x00543d10, 0x00644510, 0x00745012, 0x00855d11, 0x00936b14, 0x00a17c18, 0x00b79124, 0x00c39e24, 0x00c9a823, 0x00ccac24, 0x00ccae20, 0x00ccb11e, 0x00ccb318, 0x00ccb516, 0x00ccb514, 0x00ccb610, 0x00ccb70c, 0x00ccb80b, 0x00ccb90c, 0x00cbba0c, 0x00ccb90c, 0x00ccb90c, 0x00ccb90c, 0x00ccb90c, 0x00cbba0c, 0x00cbba0c, 0x00cbba0c, 0x00cbba0c, 0x00cbba0b, 0x00cab908, 0x00cab908, 0x00c9b808, 0x00cab709, 0x00ccb30d, 0x00c6a814, 0x00b58d14, 0x008e6204, 0x00784a04, 0x007b4c07, 0x007f5200, 0x00946904, 0x00b48c13, 0x00c6a31c, 0x00cbaf18, 0x00ccb510, 0x00cbb90d, 0x00ccba0c, 0x00cbba0c, 0x00ccba0c, 0x00cbba0c, 0x00cbbb0c, 0x00cbba0f, 0x00ccba11, 0x00ccb911, 0x00ccb911, 0x00ccb810, 0x00ccb70d, 0x00ccb70b, 0x00ccb508, 0x00ccb10d, 0x00c8a614, 0x00b58e10, 0x009e6d05, 0x00805300, 0x00694101, 0x00583700, 0x00543305, 0x00533205, 0x00523104, 0x00503007, 0x00502f0a, 0x00522f07, 0x00523001, 0x00523004, 0x00523008, 0x00533003, 0x00533002, 0x00533003, 0x00543003, 0x00543104, 0x00533204, 0x00503205, 0x004c3004, 0x004a2e05, 0x00492e08, 0x00482e0b, 0x00462f0c, 0x00442e09, 0x00422b07, 0x00422a09, 0x00422a0a, 0x00422a0a, 0x003e2808, 0x003a2509, 0x0038250c, 0x0036260c, 0x0034240c, 0x00322009, 0x00312008, 0x00301d06, 0x002e1e07, 0x002d1c08, 0x002a1908, 0x00271508, 0x0028150b, 0x0026150b, 0x0024150c, 0x0020160b, 0x001f1409, 0x001d1207, 0x001c1206, 0x001a1306, 0x00191207, 0x00181308, 0x00181308, 0x00151307, 0x00171208, 0x00181108, 0x00181108, 0x00181309, 0x00171008, 0x00151007, 0x00181108, 0x00181309, 0x00181309, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x00191208, 0x00191208, 0x00191306, 0x00191306, 0x001b1307, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1307, 0x001c1307, 0x001e1409, 0x001c1408, 0x001b1408, 0x001e170b, 0x001d160a, 0x001d1409, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001c1104, 0x001c1104, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x00201408, 0x00201408, 0x00221407, 0x00221407, 0x00241409, 0x00241608, 0x00251607, 0x00271706, 0x00271706, 0x00281808, 0x00291807, 0x002c1906, 0x002c1a07, 0x002d1a07, 0x002e1b08, 0x00301b08, 0x00311c0a, 0x00331c09, 0x00331d08, 0x00351e06, 0x00351e05, 0x00351e05, 0x00351e05, 0x00382007, 0x003c230a, 0x003e230b, 0x0040240a, 0x00402409, 0x00402607, 0x003f2707, 0x003c2404, 0x003d2505, 0x00412909, 0x00442909, 0x00422806, 0x00442804, 0x00442802, 0x00422a00, 0x00442c03, 0x00482d07, 0x004b2c05, 0x00502f08, 0x00543008, 0x00553005, 0x00543302, 0x00593802, 0x00694305, 0x007f5214, 0x00946412, 0x00b48e1a, 0x00c7ac1d, 0x00c9b412, 0x00ccb80b, 0x00ccb70d, 0x00cab611, 0x00cab315, 0x00bf9b11, 0x00ab7a06, 0x00986401, 0x00905b08, 0x00885606, 0x00835305, 0x00815207, 0x0085540d, 0x0085540c, 0x0087570c, 0x008c5b0d, 0x00925f05, 0x00a37014, 0x00bd9426, 0x00ccac21, 0x00ccb510, 0x00cab808, 0x00ccb708, 0x00cab60b, 0x00c8a70f, 0x00ac7800, 0x00a46907, 0x00bc881e, 0x00cca61d, 0x00c8b40a, 0x00c6b804, 0x00c6b609, 0x00c9b60a, 0x00ccb60b, 0x00cbb60c, 0x00ccb40e, 0x00ccb30f, 0x00ccb00d, 0x00ccb00e, 0x00ccaf11, 0x00ccac13, 0x00cba819, 0x00c79e18, 0x00c29518, 0x00bd8c14, 0x00b88414, 0x00b17a12, 0x00a8700f, 0x00a0680c, 0x00976008, 0x00905c06, 0x00895808, 0x0085540c, 0x007d4e0a, 0x00764a08, 0x006f4408, 0x00683e0b, 0x00603709, 0x00553105, 0x004e2d04, 0x00472804, 0x00422706, 0x003f2508, 0x003b2108, 0x00392109, 0x00331d07, 0x00281502, 0x00241603, 0x00241807, 0x00201608, 0x001b1408, 0x00161008, 0x00141006, 0x00121006, 0x00101007, 0x000d1007, 0x000c1005, 0x000c0f03, 0x000c1001, 0x000b1004, 0x000c1109, 0x00101510, 0x00141814, 0x00141814, 0x00151916, 0x00161a17, 0x00171c18, 0x00181d18, 0x00181e18, 0x00181f19, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x001d200a, 0x001d2009, 0x001d2008, 0x001d2008, 0x00202308, 0x00202309, 0x00202309, 0x0024250b, 0x0024250b, 0x0024250b, 0x0024250c, 0x0024250c, 0x0026280c, 0x0026280c, 0x0026280c, 0x0026280c, 0x0026280c, 0x0026280c, 0x0024250c, 0x0024250c, 0x0024250b, 0x0024250b, 0x0020230a, 0x00202309, 0x00202309, 0x00202308, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x00191e17, 0x00191d18, 0x00191d18, 0x001a1d18, 0x001a1d17, 0x00191c16, 0x0011140d, 0x0012120c, 0x0014110b, 0x0013120a, 0x00121108, 0x00131008, 0x001b140b, 0x0020170c, 0x0024180a, 0x00251808, 0x00312310, 0x0038280e, 0x00402c0e, 0x0044300c, 0x00503910, 0x005f4211, 0x0079571a, 0x0090691f, 0x00a98220, 0x00bb9826, 0x00c6a82a, 0x00caae27, 0x00cbb41f, 0x00cab414, 0x00cbb613, 0x00ccb712, 0x00ccb910, 0x00cbb90d, 0x00ccbb0d, 0x00cbb90d, 0x00cbb90d, 0x00ccb80e, 0x00ccb80f, 0x00ccb810, 0x00ccb810, 0x00ccb80d, 0x00ccb80d, 0x00cbb90d, 0x00cbb90d, 0x00cbb90d, 0x00cbb90d, 0x00ccb80d, 0x00ccb80d, 0x00ccb80c, 0x00ccb80c, 0x00ccb70d, 0x00ccb510, 0x00cbb014, 0x00bf9810, 0x00a17802, 0x00895b00, 0x00764700, 0x00694005, 0x006c410a, 0x00704608, 0x007c5204, 0x008f6103, 0x00a07408, 0x00b79212, 0x00c6a717, 0x00cbaf13, 0x00cbb010, 0x00cbb10d, 0x00ccb40c, 0x00ccb60a, 0x00ccb509, 0x00ccb60b, 0x00ccb60c, 0x00ccb60d, 0x00ccb50d, 0x00ccb40e, 0x00ccb30e, 0x00ccb012, 0x00c7a412, 0x00be9812, 0x00aa7e0c, 0x008c5c00, 0x00804f01, 0x00704604, 0x00553802, 0x004b3607, 0x0048310e, 0x004a300f, 0x004a2f0a, 0x00492e0a, 0x00492d0c, 0x00492e08, 0x004a2e04, 0x004a2d09, 0x004a2c0d, 0x00492e0b, 0x00492e0b, 0x00492e0b, 0x00482d0a, 0x00472c08, 0x00472d08, 0x00462c07, 0x00452c06, 0x00442c06, 0x00442a08, 0x0043290a, 0x0042290c, 0x003f270a, 0x003e2509, 0x003e250b, 0x003e250b, 0x003e250a, 0x003c2307, 0x00382007, 0x00352008, 0x00342108, 0x00302007, 0x002d1d05, 0x002e1e06, 0x002d1d07, 0x002c1d08, 0x002b1c0a, 0x0028180a, 0x00251509, 0x0027140b, 0x0026150c, 0x0024150d, 0x0020150c, 0x001e1208, 0x001e1107, 0x001c1106, 0x001b1206, 0x00191207, 0x00181308, 0x00181308, 0x00161408, 0x00151308, 0x00181108, 0x00181209, 0x00181309, 0x00171008, 0x00151007, 0x00181108, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181308, 0x00191208, 0x00191208, 0x00191306, 0x00191306, 0x001b1307, 0x001c1307, 0x001c1408, 0x001c1407, 0x001c1407, 0x001c1307, 0x001c1307, 0x001e1409, 0x001e1409, 0x001b1407, 0x001c1509, 0x001b1407, 0x001d1409, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001c1104, 0x001c1104, 0x001c1206, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x00201408, 0x00201408, 0x00211507, 0x00211507, 0x00241409, 0x00241608, 0x00241607, 0x00271706, 0x00271706, 0x00281707, 0x002a1807, 0x002c1906, 0x002c1a05, 0x002e1a05, 0x002f1b06, 0x002f1b06, 0x002f1a08, 0x00301b08, 0x00301b08, 0x00311c08, 0x00311c06, 0x00311c06, 0x00311c06, 0x00341d08, 0x00351d08, 0x00371e09, 0x00381f08, 0x00392008, 0x00392207, 0x00382206, 0x00352105, 0x00362107, 0x00382309, 0x003a2408, 0x003b2408, 0x003b2407, 0x003c2404, 0x003c2404, 0x003e2606, 0x0042280b, 0x0044280b, 0x00492a0e, 0x004b2d0c, 0x004b2e08, 0x004f3408, 0x004e3202, 0x005a3704, 0x00704713, 0x00845610, 0x00946c09, 0x00b49415, 0x00c7ac18, 0x00ccb610, 0x00ccb80c, 0x00c8ba0b, 0x00c8b90c, 0x00ccb218, 0x00c9a01a, 0x00ba8813, 0x00a5700e, 0x00945f02, 0x00945f06, 0x00905c07, 0x00905c10, 0x00915c0f, 0x00935f0e, 0x0098630f, 0x00a6720f, 0x00b98a20, 0x00caa529, 0x00cbb11d, 0x00cab60c, 0x00cab805, 0x00ccb808, 0x00c8b107, 0x00c39e0a, 0x00a97200, 0x00a46c0a, 0x00bf8c20, 0x00cca91f, 0x00c9b408, 0x00c8b606, 0x00c8b40b, 0x00cbb50a, 0x00cbb50a, 0x00cbb50a, 0x00ccb40c, 0x00cbb50a, 0x00c9b608, 0x00c9b608, 0x00c8b508, 0x00cab50b, 0x00ccb50f, 0x00ccb413, 0x00ccae15, 0x00cba915, 0x00cba418, 0x00ca9e1c, 0x00c6981c, 0x00bf8d18, 0x00b98715, 0x00b27e14, 0x00a87410, 0x00a16c13, 0x00996611, 0x00925e0c, 0x008a560e, 0x00885619, 0x007c4c17, 0x00643c08, 0x00583706, 0x004d2f04, 0x00492c05, 0x00452808, 0x00432608, 0x003e2006, 0x00381f05, 0x002e1b04, 0x00231500, 0x00241806, 0x00221808, 0x001d1609, 0x00181208, 0x00141007, 0x00131008, 0x00101009, 0x000f1007, 0x000c1005, 0x000c0f04, 0x000c1004, 0x000c1004, 0x000d1008, 0x0011150f, 0x00141814, 0x00141814, 0x00151916, 0x00161a17, 0x00171c18, 0x00181d18, 0x00181e18, 0x00181f19, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x001d2008, 0x00202308, 0x00202308, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202308, 0x001d2008, 0x001d2008, 0x00202309, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180c, 0x0014180e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x001a1d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x001a1d18, 0x001a1d17, 0x00171a14, 0x0011140d, 0x0011130d, 0x0011120c, 0x00121309, 0x00131209, 0x0016120a, 0x001d140d, 0x0023170c, 0x00281a0a, 0x002c1d0c, 0x0035240e, 0x003a280c, 0x0044300d, 0x004c360c, 0x005c4010, 0x0076521f, 0x00956e28, 0x00b69530, 0x00c8ac26, 0x00ccb41e, 0x00cbb51c, 0x00cbb819, 0x00cbb914, 0x00cbbb0d, 0x00ccbb0d, 0x00ccbb0d, 0x00ccbc0a, 0x00cbbb07, 0x00cbba0a, 0x00cbba0c, 0x00cbb90d, 0x00cbb90f, 0x00cbb90f, 0x00cbb90d, 0x00ccb80d, 0x00ccb80c, 0x00ccb80c, 0x00cbba0c, 0x00cbba0c, 0x00ccb90b, 0x00ccb80c, 0x00ccb70e, 0x00ccb60f, 0x00cbb40c, 0x00cab00c, 0x00ccac13, 0x00c39d0f, 0x00b08609, 0x00956805, 0x007c5000, 0x006c4300, 0x00603902, 0x0059350a, 0x00583607, 0x005c3b06, 0x00614005, 0x00754b08, 0x007c5002, 0x00895c00, 0x009c7003, 0x00ad840b, 0x00b6900e, 0x00bf9911, 0x00c39e10, 0x00c6a10c, 0x00c7a20c, 0x00c7a20c, 0x00c7a10d, 0x00c7a00d, 0x00c49c0c, 0x00c1990e, 0x00b78e07, 0x00ad8104, 0x009d6c04, 0x008d5b00, 0x007a4c00, 0x006c4100, 0x00613b07, 0x00543204, 0x004c3007, 0x00452e09, 0x00442b0a, 0x0044290a, 0x0044280a, 0x0045270c, 0x0044260c, 0x0044260c, 0x0045270c, 0x0047270b, 0x0046280c, 0x0044290c, 0x0044290c, 0x00422a0c, 0x00412b0c, 0x00402a0b, 0x00402a0b, 0x0040290a, 0x003e2708, 0x003c2708, 0x003c2808, 0x003c280a, 0x003a2409, 0x0038220a, 0x0038220a, 0x0038200b, 0x00341e08, 0x0038200b, 0x00341e08, 0x00331c08, 0x00331d09, 0x00321d09, 0x00301d08, 0x002c1b07, 0x002c1b0a, 0x002c1c0c, 0x00281c0c, 0x00271a0a, 0x00241707, 0x00241607, 0x0026150a, 0x00241409, 0x00211308, 0x00201408, 0x00211308, 0x00201207, 0x001d1004, 0x001c1104, 0x001a1207, 0x00181308, 0x00181308, 0x00161408, 0x00151408, 0x0018140c, 0x0019130c, 0x0019110b, 0x0019110b, 0x00181108, 0x00181108, 0x00181108, 0x00181109, 0x0018110b, 0x0018110a, 0x0019130c, 0x0019140b, 0x00191208, 0x00191208, 0x00191306, 0x00191304, 0x001a1308, 0x001b1309, 0x001c1408, 0x001c1408, 0x001d1408, 0x001e1308, 0x001e1308, 0x001f1408, 0x001c1407, 0x00191407, 0x001c1509, 0x001e1409, 0x001e1409, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001e1407, 0x001c1407, 0x001c1406, 0x001c1407, 0x001d1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1408, 0x001f1409, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001e1308, 0x001e1308, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001f1206, 0x00201307, 0x00221509, 0x00231509, 0x00211407, 0x00241407, 0x00251709, 0x00261709, 0x00271809, 0x00291808, 0x00291808, 0x002c1909, 0x002c1a0a, 0x002c1a08, 0x002c1a08, 0x002c1a08, 0x002c1a08, 0x002c1b07, 0x002c1a07, 0x002f1a08, 0x00321c09, 0x00331c0a, 0x00311b06, 0x00331c09, 0x00331c09, 0x00321e08, 0x00321e06, 0x00341e07, 0x00341e07, 0x00341e07, 0x00351e07, 0x00361e07, 0x00381f08, 0x00381f06, 0x003c2105, 0x003e2408, 0x00402409, 0x0041270a, 0x00422808, 0x00422805, 0x00482e08, 0x00482e06, 0x00513007, 0x005e3807, 0x0074490e, 0x00835610, 0x009a6d0b, 0x00bf981c, 0x00cbad1c, 0x00ccb70f, 0x00c7ba06, 0x00c8b906, 0x00ccb80e, 0x00ccb414, 0x00cbad18, 0x00c69d18, 0x00bb8c0f, 0x00b9810e, 0x00b07509, 0x00ad7210, 0x00ac7310, 0x00b07710, 0x00b88117, 0x00c4981c, 0x00caa721, 0x00ccaf1c, 0x00c9b414, 0x00c9b80a, 0x00ccb806, 0x00ccb307, 0x00ccaf0c, 0x00bc8f06, 0x00a36a00, 0x00a87010, 0x00c39924, 0x00c8ad15, 0x00cbb407, 0x00cab40b, 0x00cbb50a, 0x00cbb608, 0x00ccb508, 0x00ccb508, 0x00ccb409, 0x00ccb40a, 0x00cbb50a, 0x00cbb50a, 0x00cbb50a, 0x00cbb50a, 0x00cab60a, 0x00c9b60b, 0x00c9b60b, 0x00c9b50b, 0x00cbb10a, 0x00ccad0f, 0x00ccac14, 0x00cca917, 0x00caa618, 0x00c9a319, 0x00c59c18, 0x00c0951a, 0x00be901b, 0x00ba8113, 0x00af7112, 0x00ac6f20, 0x00a06721, 0x0081500e, 0x00653f02, 0x00523600, 0x004c3306, 0x004a2e09, 0x00482908, 0x00432507, 0x003c2307, 0x00342008, 0x002a1a05, 0x00261704, 0x00251808, 0x0022180b, 0x001c140a, 0x00171008, 0x00141008, 0x00131009, 0x00101007, 0x00100f08, 0x000c0e08, 0x000e1008, 0x00101008, 0x00101006, 0x00111309, 0x00131610, 0x00141914, 0x00141914, 0x00151a14, 0x00161b15, 0x00161c17, 0x00181e18, 0x0019201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180a, 0x0014180a, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x00202309, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x00202309, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x00191c09, 0x001d200a, 0x00191c09, 0x00191c0a, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180c, 0x0014180e, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x001a1d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x001a1d18, 0x001a1d17, 0x00181914, 0x0011120c, 0x0012130d, 0x0013120c, 0x00131209, 0x0014130a, 0x00161208, 0x00211810, 0x00261a0e, 0x00281a09, 0x002e1e09, 0x0038250e, 0x003e2b0d, 0x0048320c, 0x00533c0e, 0x006a4b12, 0x00886420, 0x00ad892e, 0x00caad34, 0x00cbb81f, 0x00ccb914, 0x00cbb810, 0x00cbba0e, 0x00cbbb0b, 0x00ccbc09, 0x00cbbb07, 0x00ccbc08, 0x00ccbc06, 0x00cbbb06, 0x00cbba0a, 0x00cbba0c, 0x00cbba0b, 0x00cbba09, 0x00cbba08, 0x00cbba0b, 0x00cbba0a, 0x00ccb90a, 0x00ccb90a, 0x00ccb90c, 0x00cbb80b, 0x00ccb609, 0x00ccb30c, 0x00ccb011, 0x00c8aa12, 0x00c6a313, 0x00c09611, 0x00b2840f, 0x009f6e08, 0x00885700, 0x00744600, 0x00684001, 0x005c3703, 0x00553408, 0x0051340a, 0x00503408, 0x00503403, 0x00523401, 0x005a3807, 0x00643e09, 0x006e4606, 0x00754b03, 0x00784d00, 0x00815602, 0x00875b03, 0x008c5f04, 0x00906502, 0x00926701, 0x00936701, 0x00946601, 0x00946501, 0x00905f01, 0x008c5b00, 0x00855300, 0x007b4a00, 0x00744500, 0x00683c00, 0x00603700, 0x00573202, 0x00503005, 0x004b2c04, 0x00462c07, 0x00442c09, 0x00422808, 0x00412708, 0x00402608, 0x0041260a, 0x0040250b, 0x0040240b, 0x0040240a, 0x00402309, 0x00402308, 0x003f2308, 0x003d2408, 0x003c2409, 0x003a2509, 0x00392408, 0x00392409, 0x0039240a, 0x00382306, 0x00352206, 0x00352206, 0x00342006, 0x00332008, 0x00331f08, 0x00331e09, 0x00321d09, 0x002f1b06, 0x00321d09, 0x002f1b08, 0x00301b08, 0x00311e0b, 0x00301d0a, 0x002c1b07, 0x002a1907, 0x002b190b, 0x002a190c, 0x0027190c, 0x0024180a, 0x00241809, 0x00241809, 0x00241409, 0x00221408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x001d1104, 0x001c1204, 0x001a1207, 0x00181308, 0x00181308, 0x00161408, 0x00141308, 0x00151308, 0x00171208, 0x00181309, 0x00191209, 0x0018100a, 0x0018100a, 0x0018100a, 0x0018100a, 0x0018110a, 0x0018110a, 0x0019140b, 0x00191409, 0x00191208, 0x00191208, 0x00191306, 0x00191304, 0x001a1308, 0x001b1309, 0x001c1408, 0x001c1408, 0x001d1408, 0x001e1308, 0x001e1308, 0x001f1408, 0x001c1407, 0x00191407, 0x001c1509, 0x001e1409, 0x001f1409, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001e1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001d1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1408, 0x001f1409, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001e1308, 0x001e1308, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001e1205, 0x001e1205, 0x00201408, 0x00201408, 0x00201408, 0x00221509, 0x0023160a, 0x0023160a, 0x00241608, 0x00241506, 0x00251506, 0x00261708, 0x0028180a, 0x00281908, 0x00281908, 0x00281908, 0x00281908, 0x00291908, 0x002a1807, 0x002c1808, 0x002e1908, 0x00311c0b, 0x002f1a08, 0x002f1a08, 0x002f1a08, 0x00301b06, 0x00301a04, 0x00311b05, 0x00331b05, 0x00331b05, 0x00331b05, 0x00341b06, 0x00341b07, 0x00341c05, 0x00381c04, 0x00391e06, 0x003b2007, 0x003d2209, 0x003e230a, 0x003e2408, 0x00442b0c, 0x00452a09, 0x00492c08, 0x00523005, 0x00603704, 0x0075480e, 0x00815404, 0x009c700b, 0x00ba9318, 0x00cbac1a, 0x00cbb412, 0x00cab50c, 0x00ccb80e, 0x00ccb60d, 0x00cbb210, 0x00cbb018, 0x00cbaa17, 0x00cca618, 0x00caa31c, 0x00c89c18, 0x00c89c17, 0x00c9a017, 0x00cba519, 0x00ccac19, 0x00ccb116, 0x00cbb410, 0x00c9b70c, 0x00c8b908, 0x00cbb809, 0x00ccb30d, 0x00c4a40e, 0x00ae7f01, 0x00a06601, 0x00af7813, 0x00c89f23, 0x00c8b013, 0x00cab507, 0x00cab40b, 0x00cbb50a, 0x00cbb605, 0x00cbb503, 0x00cbb405, 0x00ccb507, 0x00ccb508, 0x00cbb608, 0x00cbb608, 0x00cbb50a, 0x00cbb50a, 0x00c9b60a, 0x00c9b60a, 0x00cbb50a, 0x00cbb609, 0x00cbb408, 0x00cbb208, 0x00ccb20c, 0x00ccb412, 0x00ccb313, 0x00ccb213, 0x00ccb116, 0x00c9ad16, 0x00c8a815, 0x00caa016, 0x00c38e13, 0x00c3871c, 0x00b47818, 0x009e6210, 0x00804d04, 0x00643c01, 0x00583704, 0x00503108, 0x004c2e0a, 0x00472b0b, 0x0040270a, 0x0039240c, 0x00301d08, 0x00281803, 0x00261806, 0x00251b0b, 0x001c1609, 0x00181308, 0x00161209, 0x00141109, 0x00101007, 0x00100f08, 0x000f100a, 0x000e1008, 0x000f0f05, 0x000f0f04, 0x00111309, 0x00131610, 0x00131712, 0x00131712, 0x00141813, 0x00141914, 0x00141a14, 0x00161c17, 0x00181e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180b, 0x00191c0b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x001d2009, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c18, 0x00191c18, 0x001a1d18, 0x00191d18, 0x00191d18, 0x00181e18, 0x00191d18, 0x00191d18, 0x00181c18, 0x00191d18, 0x00121510, 0x0010130c, 0x0013110c, 0x0014100b, 0x00141008, 0x00171208, 0x001d180c, 0x00241a0e, 0x00261a0c, 0x002c1c09, 0x0034240c, 0x003c280e, 0x00442d0e, 0x004d350d, 0x005c4313, 0x00775714, 0x009a771f, 0x00c2a42e, 0x00cbb721, 0x00ccc018, 0x00cbc010, 0x00cabc0b, 0x00cbbc07, 0x00cabc06, 0x00cbba07, 0x00cbba07, 0x00cbba07, 0x00cbbb05, 0x00cbbb06, 0x00cbba0a, 0x00cbba0c, 0x00cab908, 0x00caba06, 0x00cab907, 0x00ccb90c, 0x00cab70c, 0x00cbb50e, 0x00cbb20f, 0x00cab014, 0x00c9aa12, 0x00c6a50c, 0x00c09a07, 0x00b89008, 0x00ad8406, 0x00a07405, 0x00926403, 0x00875604, 0x00784703, 0x006c3c02, 0x00603a02, 0x00563400, 0x00513404, 0x004c3305, 0x00483008, 0x00473007, 0x00483106, 0x00483005, 0x004a3004, 0x004c2f03, 0x00543504, 0x005a3803, 0x005f3a04, 0x00613b03, 0x00643c03, 0x00643c01, 0x00653d00, 0x00673f00, 0x00684000, 0x00684000, 0x00684101, 0x00674002, 0x00623c01, 0x005d3701, 0x00593400, 0x00553200, 0x00502e00, 0x004e2b01, 0x00492a04, 0x00452908, 0x00432908, 0x00412808, 0x003f2708, 0x003e2407, 0x003c2306, 0x003c2107, 0x003d2209, 0x003c220a, 0x003c220a, 0x003b2109, 0x003a2009, 0x003a2009, 0x003b2009, 0x00392008, 0x00371f08, 0x00362008, 0x00341f09, 0x00341f09, 0x00341f08, 0x00341f08, 0x00331f07, 0x00331f07, 0x00321e09, 0x00311c09, 0x00301c08, 0x00301b08, 0x002e1b08, 0x002d1b08, 0x002d1b08, 0x002c1908, 0x002c1908, 0x002b1908, 0x002b1908, 0x00281806, 0x00261607, 0x00261608, 0x00251609, 0x0024170a, 0x00221509, 0x00221509, 0x00221509, 0x00241409, 0x00211408, 0x001f1407, 0x001d1407, 0x001d1205, 0x001e1205, 0x001d1205, 0x001c1305, 0x001b1308, 0x001a1408, 0x00181408, 0x00151307, 0x00141207, 0x00141308, 0x00151308, 0x00181309, 0x00181309, 0x00191209, 0x00181108, 0x00181108, 0x00191209, 0x0018120a, 0x00181309, 0x00191409, 0x00181307, 0x00191208, 0x00191208, 0x00191306, 0x00191304, 0x00191207, 0x00191208, 0x001a1307, 0x001b1407, 0x001c1207, 0x001c1106, 0x001c1106, 0x001e1407, 0x001f1508, 0x00181306, 0x001c1408, 0x001c1408, 0x001d1308, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1407, 0x001c1407, 0x001d1305, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201409, 0x00201409, 0x00201309, 0x00201308, 0x00201308, 0x00221407, 0x00221407, 0x00241508, 0x00241608, 0x00241707, 0x00241707, 0x00241707, 0x00241707, 0x00251706, 0x00261605, 0x00281707, 0x002b1808, 0x002c1a09, 0x002a1807, 0x002a1808, 0x002d1c09, 0x002c1a07, 0x002e1a05, 0x002e1a05, 0x002f1a05, 0x002f1a05, 0x002f1a05, 0x002f1a06, 0x00301b06, 0x00311a04, 0x00321b04, 0x00321b04, 0x00341c06, 0x00351e09, 0x00371f0a, 0x00372008, 0x003d260d, 0x003d260b, 0x00422809, 0x00492c08, 0x00502e04, 0x005d3507, 0x00704509, 0x007f5406, 0x00946807, 0x00b48915, 0x00c9a51d, 0x00ccb018, 0x00ccb214, 0x00ccb60d, 0x00ccb80c, 0x00cab710, 0x00cab610, 0x00cab410, 0x00cbb411, 0x00cbb311, 0x00cbb310, 0x00ccb40e, 0x00ccb40d, 0x00ccb60d, 0x00ccb70b, 0x00cab707, 0x00c9b804, 0x00c9b807, 0x00ccb80e, 0x00caac14, 0x00b48c08, 0x009f6c00, 0x00a06503, 0x00bd881c, 0x00cca823, 0x00cab210, 0x00cab507, 0x00cbb50c, 0x00cbb50a, 0x00cbb605, 0x00ccb604, 0x00ccb506, 0x00ccb508, 0x00ccb508, 0x00cbb608, 0x00cbb608, 0x00cbb50a, 0x00cbb50a, 0x00c9b60a, 0x00c9b60a, 0x00cbb50a, 0x00cbb609, 0x00cbb508, 0x00cbb406, 0x00cbb408, 0x00ccb509, 0x00ccb509, 0x00cbb50b, 0x00cbb50b, 0x00cab50c, 0x00ccb40f, 0x00ccaa0f, 0x00cc9d0e, 0x00cb9412, 0x00c48b12, 0x00bc8213, 0x00a66e0e, 0x00875408, 0x006d4306, 0x005d3b0a, 0x004f3308, 0x0048300c, 0x0043290c, 0x0040260e, 0x0038220b, 0x002e1b06, 0x00281704, 0x00261a09, 0x001c1708, 0x00161104, 0x00171208, 0x00141308, 0x00121208, 0x00101008, 0x000d0f08, 0x000c0f07, 0x00101007, 0x00101005, 0x00101108, 0x0011140e, 0x00101510, 0x00101510, 0x00131712, 0x00141813, 0x00141a14, 0x00151c16, 0x00151c16, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x00191c0b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x0014180f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c18, 0x00181c18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00181e18, 0x00191d18, 0x001a1f19, 0x00191e17, 0x00191e17, 0x0011150f, 0x0010120c, 0x0013100c, 0x0016100b, 0x00171009, 0x00181308, 0x001d170b, 0x00241a0c, 0x00271909, 0x002f200c, 0x0038260e, 0x00402c0e, 0x0048300c, 0x00563b10, 0x00654916, 0x00846214, 0x00b09027, 0x00cab025, 0x00cabc14, 0x00cbc210, 0x00cbc210, 0x00cabe0c, 0x00cbbc08, 0x00cbba07, 0x00cab909, 0x00cab90b, 0x00cbba0c, 0x00cbba08, 0x00cbbb06, 0x00cbbb09, 0x00ccb90c, 0x00cbb80b, 0x00cbb908, 0x00cbb70b, 0x00cab511, 0x00c8b014, 0x00c8a815, 0x00c39c11, 0x00b98f0e, 0x00ab7d04, 0x009e6f00, 0x00946400, 0x008e5d00, 0x00895700, 0x007d4e00, 0x00704700, 0x00674000, 0x005e3800, 0x005a3706, 0x0055350b, 0x004e3208, 0x00483207, 0x00453106, 0x00432f06, 0x00422e08, 0x00422d08, 0x00422d09, 0x00422d09, 0x00442e08, 0x00432a03, 0x00482e06, 0x004a2e04, 0x004c2e02, 0x004c2f03, 0x004c3003, 0x004c3002, 0x004d3203, 0x004d3403, 0x004d3403, 0x004f3403, 0x004e3401, 0x004c3101, 0x004c3105, 0x00492f04, 0x00482c04, 0x00472c05, 0x00462b0b, 0x0044290d, 0x0040260c, 0x003d260a, 0x003c2308, 0x003a2207, 0x00392106, 0x00381f05, 0x00361d05, 0x00361d07, 0x00351e08, 0x00341e08, 0x00341d08, 0x00331c08, 0x00341c07, 0x00341c07, 0x00341c08, 0x00341d09, 0x00321d09, 0x00311c0a, 0x00321d0b, 0x00301d0a, 0x00311d08, 0x00301d08, 0x00301d08, 0x00301c0a, 0x00301c0c, 0x002c1a08, 0x002c1a08, 0x002c1908, 0x002a1807, 0x002a1808, 0x00291809, 0x00281808, 0x00271708, 0x00261808, 0x00241606, 0x00241607, 0x00241608, 0x0024160a, 0x0023160c, 0x0021140a, 0x0021140a, 0x0021140a, 0x0022150b, 0x0020140a, 0x001d1408, 0x001c1408, 0x001c1305, 0x001d1205, 0x001c1205, 0x001c1305, 0x001b1407, 0x001a1308, 0x00181408, 0x00151207, 0x00141206, 0x00131306, 0x00141206, 0x00161307, 0x00181308, 0x00191307, 0x00191207, 0x00191307, 0x00191307, 0x00181308, 0x00181308, 0x00181307, 0x00181306, 0x00191307, 0x00191208, 0x00191306, 0x00191304, 0x00191207, 0x00191208, 0x001a1308, 0x001b1407, 0x001c1207, 0x001c1106, 0x001c1106, 0x001e1407, 0x001f1508, 0x00181306, 0x001c1408, 0x001c1408, 0x001d1408, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1407, 0x001c1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201208, 0x00201208, 0x00201208, 0x001e1208, 0x001d1208, 0x001d1207, 0x001c1106, 0x001f1207, 0x00201207, 0x00211308, 0x00221408, 0x00231509, 0x00221608, 0x00221708, 0x00221708, 0x00221708, 0x00241508, 0x00251508, 0x00261508, 0x00281408, 0x00281808, 0x00261606, 0x00261707, 0x00281908, 0x00281805, 0x00291806, 0x00291805, 0x00291805, 0x00291805, 0x00291805, 0x002a1806, 0x002a1806, 0x002b1905, 0x00301c08, 0x002f1c08, 0x002f1c08, 0x00301c08, 0x00301c0c, 0x00311e0b, 0x00341f0a, 0x00352008, 0x003c270c, 0x00442a0b, 0x00492b09, 0x004f2d08, 0x00583505, 0x00654104, 0x00795002, 0x008f6203, 0x00a87d0c, 0x00bf9918, 0x00cbab1b, 0x00ccb111, 0x00ccb50c, 0x00cab60c, 0x00cab70c, 0x00cab80c, 0x00cbb90d, 0x00cab90d, 0x00c8ba0b, 0x00c8b908, 0x00c8ba08, 0x00c9b908, 0x00c9b808, 0x00c9b806, 0x00cbb804, 0x00cab205, 0x00ccaf0f, 0x00bc9205, 0x00a57300, 0x009c6200, 0x00a16504, 0x00bf8b1b, 0x00caa41b, 0x00c9af0e, 0x00cbb40a, 0x00ccb40e, 0x00ccb50c, 0x00ccb508, 0x00ccb40a, 0x00ccb50a, 0x00ccb40a, 0x00ccb40a, 0x00cbb50a, 0x00c9b60a, 0x00c9b60a, 0x00c9b60a, 0x00c8b70a, 0x00c8b709, 0x00c9b609, 0x00c9b60a, 0x00cab509, 0x00cab408, 0x00cab509, 0x00cbb509, 0x00cbb50a, 0x00cbb50c, 0x00cbb50c, 0x00cbb50b, 0x00ccb40c, 0x00ccab0d, 0x00cba00c, 0x00c8980e, 0x00c99a14, 0x00cba315, 0x00bd8d12, 0x00a36f0e, 0x00855408, 0x00684108, 0x0057390a, 0x004a320a, 0x00472c0e, 0x0042280d, 0x003c260c, 0x00322007, 0x00291802, 0x00261b08, 0x00201908, 0x00191404, 0x00181206, 0x00141307, 0x00121108, 0x00100f08, 0x000d0f08, 0x000d0f07, 0x00101007, 0x00101005, 0x000f1108, 0x0012140e, 0x0010140f, 0x0010140f, 0x00111611, 0x00121712, 0x00131914, 0x00141a14, 0x00141a14, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180f, 0x000f130b, 0x0014180d, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130b, 0x000f130b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191d18, 0x00191d18, 0x00191d1a, 0x00181e18, 0x00181e18, 0x00181f17, 0x00171d18, 0x0019201a, 0x001b211a, 0x00141a13, 0x000f120c, 0x0010110c, 0x0011110b, 0x0014110a, 0x00161208, 0x001c170c, 0x0020190c, 0x00231809, 0x00281b0a, 0x0032230f, 0x0038260f, 0x00422e0c, 0x004c350c, 0x005b3f0c, 0x00724f14, 0x00906c17, 0x00c0a129, 0x00cbb41a, 0x00c9bc0e, 0x00cac110, 0x00cbc113, 0x00cbbf11, 0x00cbbc09, 0x00cbbb06, 0x00cabc09, 0x00c9bb09, 0x00c9bb07, 0x00cabb04, 0x00cbba04, 0x00ccb907, 0x00ccb80c, 0x00ccb40d, 0x00ccb110, 0x00caa910, 0x00c49f12, 0x00b8900c, 0x00a97a03, 0x009c6a00, 0x00925f00, 0x00855200, 0x007c4a00, 0x00774800, 0x00704400, 0x006b4000, 0x00643e02, 0x00593803, 0x00533502, 0x00503706, 0x004d3609, 0x0048330e, 0x0044300c, 0x00412f0a, 0x0040300a, 0x003e2c08, 0x003c2a05, 0x003d2808, 0x003d2808, 0x003d2808, 0x003e2909, 0x0040280a, 0x0041290b, 0x00402b0a, 0x00412b09, 0x00422b08, 0x00432a08, 0x00422a08, 0x00422a08, 0x00442b08, 0x00442b08, 0x00472c0a, 0x00482b0a, 0x00482b0c, 0x00482a0c, 0x00482a0c, 0x00472a09, 0x00452808, 0x00432509, 0x0040250c, 0x003c230b, 0x003a230a, 0x00382008, 0x00351e05, 0x00341d05, 0x00341d07, 0x00331c08, 0x00311c08, 0x00311c08, 0x00301c08, 0x00301c08, 0x00301c09, 0x00311c08, 0x00301b07, 0x00301a06, 0x00311b07, 0x00321d09, 0x00301c09, 0x002e1c08, 0x002c1c07, 0x002b1a06, 0x002c1b07, 0x002d1a07, 0x002d1a07, 0x002c1b07, 0x002a1906, 0x002a1907, 0x00281808, 0x00281809, 0x0028180b, 0x0027180a, 0x00241709, 0x00241608, 0x00231708, 0x00231708, 0x00231708, 0x00221608, 0x00221508, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1409, 0x001f1409, 0x001f1409, 0x001f1409, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001a1508, 0x001a1508, 0x00191408, 0x00181205, 0x00151204, 0x00151405, 0x00171305, 0x00181306, 0x00181306, 0x001b1407, 0x001b1407, 0x00191306, 0x00191306, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x001b1206, 0x001b1205, 0x001b1204, 0x001b1204, 0x001a1207, 0x00191208, 0x00191307, 0x00191306, 0x001c1206, 0x001d1207, 0x001d1207, 0x001d1205, 0x00201508, 0x001a1105, 0x001c1307, 0x001c1408, 0x001c1408, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1207, 0x001d1207, 0x001e1308, 0x001e1308, 0x001f140a, 0x001e130a, 0x001d1208, 0x001d1208, 0x001d130a, 0x001c140a, 0x001c1309, 0x001c1309, 0x001d1309, 0x001f1208, 0x001f1208, 0x00201409, 0x0020140a, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00221408, 0x00221408, 0x00231409, 0x0022160a, 0x0024150b, 0x00241509, 0x00251709, 0x00251708, 0x00261707, 0x00261607, 0x00271708, 0x00281708, 0x00281708, 0x00281708, 0x00281808, 0x00281809, 0x00281808, 0x002a1908, 0x002c1b09, 0x002f1c0a, 0x002f1c0a, 0x002d1c0a, 0x002f1c0b, 0x00321d09, 0x00341e08, 0x00372007, 0x003f250c, 0x0042270b, 0x00472a0b, 0x004a310a, 0x00503403, 0x005e3b00, 0x00754b06, 0x00845805, 0x00966a08, 0x00b08514, 0x00c49a14, 0x00cba814, 0x00cbb212, 0x00ccb411, 0x00ccb60e, 0x00ccb70c, 0x00ccb80b, 0x00cbb80b, 0x00cab80b, 0x00cab80b, 0x00cbb80a, 0x00cab409, 0x00cbb40b, 0x00ccb30c, 0x00cca810, 0x00bd8d08, 0x00aa7401, 0x009d6000, 0x00a16104, 0x00a16202, 0x00b47810, 0x00bc8910, 0x00c49511, 0x00c89f11, 0x00cca615, 0x00cca912, 0x00ccae13, 0x00ccb014, 0x00caaf0e, 0x00cab30c, 0x00cbb50a, 0x00cbb608, 0x00cbb608, 0x00cab608, 0x00c8b708, 0x00c8b708, 0x00c8b806, 0x00c9b707, 0x00c9b608, 0x00cbb509, 0x00cbb50a, 0x00cbb50c, 0x00cbb50c, 0x00cab50c, 0x00c9b50d, 0x00c9b60c, 0x00c9b60a, 0x00cbb508, 0x00ccac08, 0x00c8a108, 0x00c49c07, 0x00c8a80d, 0x00ccb416, 0x00caab18, 0x00be9318, 0x00a36e0c, 0x00875107, 0x006d4207, 0x00583809, 0x004c3007, 0x00432b08, 0x003f2a0b, 0x0038250b, 0x002f1d06, 0x00281805, 0x0027190a, 0x00201708, 0x00181305, 0x00161306, 0x00141008, 0x0014130c, 0x0010100b, 0x000e0e07, 0x00111008, 0x00101006, 0x0013120a, 0x0012140e, 0x000f140e, 0x00101610, 0x00101711, 0x000f1812, 0x00111914, 0x00121a15, 0x00131b16, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e1a, 0x00181e18, 0x00181e18, 0x00181f17, 0x00181f17, 0x001a2018, 0x001b2119, 0x00141a13, 0x0010110c, 0x0010100b, 0x0011110b, 0x0015130a, 0x00181209, 0x001e180c, 0x0021180a, 0x00241907, 0x002d200c, 0x00352710, 0x003c2911, 0x0046320d, 0x0053390d, 0x006a4812, 0x007f5a17, 0x00a58423, 0x00c9ad2c, 0x00ccb718, 0x00cbbd0e, 0x00cbc110, 0x00cbc111, 0x00ccc011, 0x00cbbd0b, 0x00cabc06, 0x00c9bc06, 0x00c8bb06, 0x00c8b805, 0x00c9b705, 0x00cab607, 0x00cbb40c, 0x00c8ab0c, 0x00c4a00a, 0x00bb8b07, 0x00ae7d04, 0x009c6d01, 0x008c5d00, 0x00835400, 0x00784c00, 0x006e4400, 0x00643d01, 0x00613c01, 0x005d3a01, 0x00583800, 0x00543400, 0x004f3303, 0x004f3309, 0x004c320a, 0x0049310c, 0x0046300e, 0x00412c0c, 0x003c2a09, 0x003b2807, 0x003a2807, 0x003a2707, 0x00382606, 0x00372405, 0x00362305, 0x00382307, 0x00382408, 0x00392409, 0x00392508, 0x00392709, 0x00392708, 0x00382606, 0x00372404, 0x00382406, 0x00382408, 0x003b2409, 0x003b240a, 0x00402509, 0x00412609, 0x0043270b, 0x0043260c, 0x0042250a, 0x00402406, 0x003f2306, 0x003c2108, 0x003a2108, 0x00371f08, 0x00351f08, 0x00331d06, 0x00321c05, 0x00301c05, 0x00301c06, 0x002f1a08, 0x002f1a09, 0x002e1a0a, 0x002e1b0a, 0x002e1b0a, 0x002e1b0a, 0x002e1b09, 0x002f1a08, 0x002e1908, 0x002e1907, 0x002f1b08, 0x002e1b0a, 0x002c1c0a, 0x00281a08, 0x00271908, 0x00281808, 0x00291808, 0x00291808, 0x00281807, 0x00281807, 0x00271808, 0x00251808, 0x00251709, 0x0024180a, 0x0024180b, 0x0024170b, 0x0023160a, 0x0023160a, 0x00231708, 0x00231708, 0x00221608, 0x00221608, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1409, 0x001f1409, 0x001f1409, 0x001f1409, 0x001e1407, 0x001e1407, 0x001d1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001b1407, 0x00181306, 0x00171305, 0x00181205, 0x00191306, 0x001a1306, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x001b1205, 0x001b1204, 0x001b1204, 0x001b1204, 0x001a1207, 0x00191208, 0x00191307, 0x00191306, 0x001c1206, 0x001d1207, 0x001d1207, 0x001d1205, 0x00201508, 0x001a1105, 0x001c1307, 0x001c1408, 0x001c1408, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1409, 0x001e1308, 0x001d1207, 0x001d1207, 0x001c1408, 0x001c1408, 0x001e1409, 0x001e1409, 0x001e1409, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201508, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201508, 0x00201408, 0x00211408, 0x00221608, 0x00221608, 0x00241508, 0x00241409, 0x0024150a, 0x0024160a, 0x0024160a, 0x0024160a, 0x0024160a, 0x0025170a, 0x00261608, 0x00281806, 0x00281807, 0x002b1908, 0x002c1b09, 0x002c1b09, 0x002d1c08, 0x00301c08, 0x00331d08, 0x00351d05, 0x00381f06, 0x003d2208, 0x0043290c, 0x00442e0c, 0x0048320a, 0x00503404, 0x005c3801, 0x006d4404, 0x007b4f01, 0x00895c00, 0x009d6d03, 0x00b0840c, 0x00bc9411, 0x00c7a015, 0x00cba814, 0x00ccad13, 0x00ccb00c, 0x00ccb00b, 0x00ccb00c, 0x00ccb10c, 0x00ccb00f, 0x00ccad0f, 0x00caa811, 0x00c49c0c, 0x00b78405, 0x00a87001, 0x009e6200, 0x00a96a0a, 0x00b57514, 0x00b0700c, 0x00ac6f05, 0x00a96d00, 0x00ac7200, 0x00b27a03, 0x00b98208, 0x00be890a, 0x00c59410, 0x00c39c10, 0x00c9a514, 0x00ccac14, 0x00ccb013, 0x00ccb40c, 0x00ccb40a, 0x00cbb508, 0x00cab608, 0x00cab707, 0x00cbb606, 0x00cbb607, 0x00cbb608, 0x00ccb409, 0x00ccb40b, 0x00ccb40c, 0x00cbb40d, 0x00cbb40d, 0x00cbb40d, 0x00cbb50c, 0x00c9b60a, 0x00cab508, 0x00ccae08, 0x00c8a309, 0x00c7a009, 0x00caac0f, 0x00cbb812, 0x00ccb514, 0x00cbad1d, 0x00bc8f14, 0x009c6a0c, 0x007f5208, 0x00644006, 0x00513303, 0x004a3008, 0x00402b0b, 0x003c280c, 0x00332108, 0x002a1a05, 0x00281908, 0x00241b09, 0x00191404, 0x00161304, 0x00151208, 0x00121109, 0x0011130b, 0x00101009, 0x00110f07, 0x00101006, 0x00101008, 0x0010120c, 0x000f140e, 0x00101610, 0x000f1811, 0x000f1912, 0x00101914, 0x00121a15, 0x00131b16, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e1a, 0x00181e1a, 0x00181e1a, 0x00181e18, 0x00181e18, 0x00182018, 0x00181f17, 0x001a2018, 0x001a1f18, 0x00141811, 0x0012140e, 0x0011110c, 0x0013100c, 0x00151209, 0x0019140a, 0x001e170b, 0x00221909, 0x00261a08, 0x0031220d, 0x00382710, 0x003e2b11, 0x004a330e, 0x00583c0d, 0x006f4c0e, 0x008a6417, 0x00b69628, 0x00c9b024, 0x00ccb814, 0x00cabc0d, 0x00c8be0d, 0x00c8c00c, 0x00cbc00e, 0x00ccc010, 0x00c8b60a, 0x00c8b309, 0x00c8af09, 0x00ccad0e, 0x00ccac11, 0x00caa815, 0x00c09c12, 0x00b08809, 0x00a17400, 0x00946000, 0x00885500, 0x00794c00, 0x00714800, 0x006a4403, 0x00603c02, 0x00583804, 0x00543708, 0x00513509, 0x004e3307, 0x004c3309, 0x004a330b, 0x0046320c, 0x0046300e, 0x00442c0d, 0x0042290e, 0x00402a0e, 0x003e290c, 0x003a2809, 0x00392608, 0x00372407, 0x00372407, 0x00362407, 0x00342107, 0x00342108, 0x00342007, 0x00342007, 0x00342107, 0x00342208, 0x00342208, 0x00322306, 0x00332206, 0x00342304, 0x00342204, 0x00342204, 0x00352204, 0x00372205, 0x00392307, 0x003c2308, 0x003c2408, 0x003c220b, 0x003c230a, 0x003b2307, 0x00382005, 0x00382008, 0x00372009, 0x00331d08, 0x00311d08, 0x00301c08, 0x002f1b06, 0x002d1c06, 0x002d1b08, 0x002c1a08, 0x002c180a, 0x002c180b, 0x002c180b, 0x002c180b, 0x002c180b, 0x002c180a, 0x002c1909, 0x002c1909, 0x002a1808, 0x002b1809, 0x00271708, 0x00261808, 0x00261a0a, 0x00271a0b, 0x0027180a, 0x0028180a, 0x00281809, 0x00271809, 0x00251808, 0x00251808, 0x00231709, 0x0023160a, 0x0023160c, 0x0023160c, 0x0023160c, 0x0023160b, 0x0023160a, 0x00221509, 0x00221608, 0x00211507, 0x00211507, 0x00221509, 0x00201408, 0x00201307, 0x00201307, 0x001f1409, 0x001f1409, 0x001f1409, 0x001f1409, 0x00201307, 0x00201307, 0x001e1407, 0x001d1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x00191306, 0x00181306, 0x00191306, 0x001c1307, 0x001c1307, 0x001d1207, 0x001d1207, 0x001e1308, 0x001c1206, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001b1204, 0x001b1204, 0x001b1204, 0x001b1204, 0x001b1308, 0x001b1309, 0x001a1308, 0x00191306, 0x001c1206, 0x001d1207, 0x001d1207, 0x001d1205, 0x00201508, 0x001b1206, 0x001c1307, 0x001e1409, 0x001e1409, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1409, 0x001e1308, 0x001d1207, 0x001d1207, 0x001c140a, 0x001c140a, 0x001c1309, 0x001c1208, 0x001c1209, 0x001e130a, 0x001e130a, 0x001e130a, 0x001e130a, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x00201409, 0x001f1409, 0x001e1409, 0x001d1409, 0x001e1407, 0x001e1407, 0x00201508, 0x00201508, 0x00211507, 0x00211506, 0x00211506, 0x00211506, 0x00211507, 0x00221607, 0x00221607, 0x00221607, 0x00241607, 0x00241607, 0x00251608, 0x00281709, 0x0028180a, 0x0028180a, 0x00291809, 0x002f1b0b, 0x00321d0b, 0x00341e0a, 0x00351d08, 0x00392009, 0x003e250c, 0x00402a0d, 0x00442c0d, 0x004a300a, 0x00503306, 0x005b3705, 0x00693f06, 0x007c4e08, 0x00885404, 0x00956004, 0x00a46e04, 0x00ad7807, 0x00b48008, 0x00bb8b08, 0x00c09206, 0x00c59a0c, 0x00c69a0c, 0x00c59b0c, 0x00c1980c, 0x00bb8f08, 0x00b58506, 0x00a77200, 0x00a16800, 0x00a66a06, 0x00b07510, 0x00c0891b, 0x00cb9b21, 0x00ca981b, 0x00c59114, 0x00bd880c, 0x00b57e05, 0x00af7501, 0x00ac7001, 0x00a96b00, 0x00a46800, 0x00a46f02, 0x00ae7c07, 0x00b6880d, 0x00c59b18, 0x00caa714, 0x00ccab14, 0x00cbac10, 0x00cbb00f, 0x00cbb10c, 0x00ccb30b, 0x00ccb30a, 0x00ccb40b, 0x00ccb40c, 0x00ccb40d, 0x00ccb40d, 0x00cbb40d, 0x00cbb40d, 0x00cbb40d, 0x00cab40b, 0x00c8b509, 0x00cab408, 0x00ccac08, 0x00c8a308, 0x00c9a30c, 0x00ccaf11, 0x00cab911, 0x00cbb90f, 0x00ccb814, 0x00c8aa13, 0x00a88007, 0x00895e00, 0x00734a04, 0x005c3a02, 0x004f3107, 0x00452c09, 0x0040290a, 0x003a250c, 0x002e1c05, 0x00261704, 0x00261b08, 0x001f1808, 0x00181404, 0x00161208, 0x00100e07, 0x0010120a, 0x00121108, 0x00101008, 0x00101006, 0x00101008, 0x0010110c, 0x000f140e, 0x00101510, 0x000f1611, 0x000e1813, 0x00101815, 0x00111816, 0x00121917, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e1a, 0x00181e1a, 0x00181e1a, 0x00181e18, 0x00181e18, 0x00182018, 0x00182018, 0x001a2018, 0x00191e17, 0x0010140d, 0x0010110c, 0x0012110c, 0x0013100b, 0x00161109, 0x0019140a, 0x0020180c, 0x00221808, 0x00271a07, 0x0031220a, 0x0039270f, 0x00402c10, 0x004d340e, 0x005c3d0d, 0x00704c08, 0x00986f1c, 0x00c4a72e, 0x00cab41e, 0x00ccba10, 0x00cabd0c, 0x00c8bd0d, 0x00c8bf09, 0x00cbbf0a, 0x00ccbc10, 0x00c5ac0d, 0x00bf9d08, 0x00bb9305, 0x00bc8c08, 0x00b88408, 0x00b37e0d, 0x00a07008, 0x008a5c00, 0x007c5000, 0x006f4500, 0x00684200, 0x005f3c00, 0x00593a00, 0x00573801, 0x00543605, 0x00513407, 0x004f3108, 0x004e3109, 0x004b300a, 0x00482f0c, 0x00442e0c, 0x00402c09, 0x003e2a09, 0x003e2708, 0x003d2409, 0x003c240a, 0x00392409, 0x00362407, 0x00342107, 0x00321e04, 0x00321e04, 0x00311d04, 0x002f1d05, 0x002f1c05, 0x00301d06, 0x00301d06, 0x00301d06, 0x00301d06, 0x00301d06, 0x00311d04, 0x00311d04, 0x00321c04, 0x00311d04, 0x00301e05, 0x00301e06, 0x00321e06, 0x00331e06, 0x00321e04, 0x00321d06, 0x00341d08, 0x00341e08, 0x00352006, 0x00341f05, 0x00341e08, 0x00331d09, 0x002f1b08, 0x002d1b08, 0x002c1c08, 0x002c1c08, 0x002c1b08, 0x002a1b0a, 0x00291809, 0x0028170a, 0x0028170b, 0x0028170b, 0x0028170b, 0x0028170b, 0x0028170a, 0x00281709, 0x00281709, 0x00281809, 0x0029190b, 0x00251709, 0x00241809, 0x00231809, 0x00231809, 0x00231708, 0x00241608, 0x00251709, 0x00241608, 0x00231708, 0x0023160a, 0x0020150a, 0x0020150a, 0x0020140b, 0x0021140c, 0x0021140c, 0x0021140c, 0x0021140a, 0x00221608, 0x00221608, 0x00211507, 0x00211507, 0x00221509, 0x00201408, 0x00201307, 0x00201307, 0x001f1409, 0x001f1409, 0x001f1409, 0x001f1409, 0x00201307, 0x00201307, 0x001e1407, 0x001d1407, 0x001d1308, 0x001e1308, 0x001e1308, 0x001d1308, 0x001a1206, 0x00181306, 0x001a1306, 0x001c1307, 0x001c1307, 0x001d1207, 0x001d1207, 0x001e1308, 0x001c1106, 0x001a1204, 0x00191304, 0x00191304, 0x00191304, 0x001b1204, 0x001b1204, 0x001b1204, 0x001b1204, 0x001b1308, 0x001b1309, 0x001a1307, 0x00191306, 0x001c1206, 0x001d1207, 0x001d1207, 0x001d1205, 0x00201508, 0x001b1206, 0x001c1307, 0x001e1409, 0x001e1409, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1304, 0x001d1304, 0x001e1405, 0x001e1406, 0x001f1408, 0x001d1205, 0x001d1205, 0x001d1205, 0x001c1409, 0x001c140a, 0x001c1309, 0x001c1208, 0x001c1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1508, 0x001d1508, 0x001c1508, 0x001c1405, 0x001c1405, 0x001f1608, 0x001f150a, 0x00201508, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00221608, 0x00221608, 0x00241608, 0x00241608, 0x00251709, 0x00251709, 0x00261808, 0x002b1809, 0x00301c0a, 0x00321c09, 0x00331c08, 0x00381f09, 0x003d240c, 0x0040280c, 0x00442a0d, 0x004c300d, 0x0052340c, 0x0059380c, 0x00613a08, 0x0073460c, 0x0084500d, 0x00a36a1b, 0x00b47817, 0x00ae730c, 0x00a86e04, 0x00a86e00, 0x00a66c00, 0x00a86d00, 0x00aa7000, 0x00a97000, 0x00a56e00, 0x00a46c00, 0x00a66c00, 0x00aa6c00, 0x00ac730c, 0x00bc871f, 0x00c69722, 0x00cca51d, 0x00ccae16, 0x00ccb013, 0x00ccb015, 0x00ccac15, 0x00cca515, 0x00c99c14, 0x00c38f16, 0x00ad730b, 0x009a5b00, 0x00975704, 0x00945600, 0x00975d00, 0x00a06c05, 0x00ad7e09, 0x00bb8e13, 0x00c09816, 0x00c7a318, 0x00caac13, 0x00ccb014, 0x00ccb113, 0x00ccb212, 0x00ccb211, 0x00ccb310, 0x00ccb40e, 0x00cbb40d, 0x00cbb40d, 0x00cbb40d, 0x00cab40b, 0x00c8b408, 0x00c9b407, 0x00cbac07, 0x00c8a208, 0x00c9a30c, 0x00cbb012, 0x00cab913, 0x00c9bb0e, 0x00cbb90d, 0x00c9b50f, 0x00b9980c, 0x00986e00, 0x00805403, 0x00684103, 0x00543407, 0x004a2f09, 0x00432a0a, 0x003d270c, 0x00321f07, 0x00281804, 0x00251906, 0x00231b0a, 0x001a1506, 0x00181408, 0x00111009, 0x00101208, 0x00121108, 0x0011110a, 0x00101007, 0x00101008, 0x0010110c, 0x0010130e, 0x00101510, 0x00101511, 0x000e1813, 0x00101816, 0x00121918, 0x00121918, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e18, 0x00182019, 0x00182019, 0x0019201a, 0x001b2018, 0x001c1f18, 0x00181a14, 0x0011130c, 0x0012110b, 0x0013120b, 0x0014110a, 0x00161108, 0x001b1309, 0x0020170b, 0x00231808, 0x002c1e0a, 0x0034240a, 0x003a280c, 0x00412c0c, 0x004e360e, 0x005c3e0e, 0x00744d0f, 0x00a27b21, 0x00c9ad2c, 0x00cbb818, 0x00ccbc0c, 0x00cabd0b, 0x00cabd0d, 0x00c9bc0a, 0x00cbbc0c, 0x00cab411, 0x00b8940c, 0x00a47503, 0x009f6b01, 0x00945d00, 0x008f5800, 0x00855600, 0x00795000, 0x006c4700, 0x00603f01, 0x005b3a05, 0x00583907, 0x00543806, 0x004e3405, 0x004d3507, 0x004b3407, 0x004c340b, 0x0048300b, 0x00442b08, 0x00442a0a, 0x0040270b, 0x003c2508, 0x003a2407, 0x00382408, 0x00382308, 0x00372008, 0x00351e08, 0x00331f08, 0x00331f08, 0x00331f08, 0x00311c06, 0x00311c08, 0x00301d08, 0x002d1c07, 0x002b1b06, 0x002c1b07, 0x002c1c08, 0x002c1c08, 0x002c1c08, 0x002e1b08, 0x002e1b08, 0x002d1b06, 0x002c1a05, 0x002c1a05, 0x002c1906, 0x002b1804, 0x002e1c06, 0x002f1c07, 0x00301d08, 0x00301d08, 0x00301c07, 0x00301c05, 0x002f1c04, 0x002e1904, 0x00301c08, 0x002f1c08, 0x002d1a09, 0x002c190a, 0x002c190a, 0x002b180a, 0x0028180c, 0x0028180c, 0x00261609, 0x0025150a, 0x0027150a, 0x0028150b, 0x0028150b, 0x0027160b, 0x0025170a, 0x00241608, 0x00241608, 0x00241608, 0x00241608, 0x0026180c, 0x0026180c, 0x0024170a, 0x00231409, 0x00221509, 0x00221509, 0x00221509, 0x0023160a, 0x0023160a, 0x0023160a, 0x00211408, 0x00201409, 0x00201409, 0x0020150a, 0x0020150a, 0x0020150a, 0x00201508, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00211408, 0x00201408, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201307, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001f1408, 0x001c1205, 0x001c1305, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1409, 0x001c1106, 0x001b1005, 0x001c1106, 0x001d1208, 0x001e1308, 0x001e1308, 0x001c1408, 0x001d1408, 0x001f1307, 0x001e1407, 0x001e1407, 0x001e1508, 0x001b1206, 0x001c1307, 0x0020150a, 0x001e1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001d1205, 0x001c1204, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1306, 0x001c1307, 0x001c1408, 0x001e1308, 0x001e1308, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001c1305, 0x001c1305, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1306, 0x001e1407, 0x001f1407, 0x00221509, 0x0024170b, 0x0024160a, 0x0024160a, 0x0024160a, 0x00241608, 0x00281809, 0x002b1b08, 0x002e1b08, 0x00311c08, 0x00341c08, 0x003a2108, 0x003f2608, 0x0040280b, 0x00462b0b, 0x004c3008, 0x00543505, 0x00643f0b, 0x00754a10, 0x008a5910, 0x00b88729, 0x00cb9e2a, 0x00cb9e20, 0x00c89918, 0x00c29117, 0x00b58211, 0x00b37f0a, 0x00b17c08, 0x00b17b0b, 0x00b17c0c, 0x00b27c0b, 0x00b7820d, 0x00c6921b, 0x00c89f1e, 0x00c9a81f, 0x00ccac1b, 0x00ccb014, 0x00ccb30e, 0x00ccb409, 0x00ccb409, 0x00cab40b, 0x00cbb410, 0x00ccb214, 0x00cca91a, 0x00b88913, 0x00945b00, 0x008b5107, 0x007f4800, 0x007d4902, 0x00804f01, 0x00875703, 0x00905f02, 0x009c6c05, 0x00a8780b, 0x00b4870c, 0x00c19515, 0x00c89e18, 0x00caa418, 0x00cba714, 0x00ccac13, 0x00ccaf10, 0x00ccb30f, 0x00ccb60f, 0x00cbb40c, 0x00cab40b, 0x00cab409, 0x00cab308, 0x00caab0c, 0x00c9a00b, 0x00c8a30f, 0x00cbb114, 0x00c9ba12, 0x00c8bb0b, 0x00c8bb07, 0x00c8ba0a, 0x00c9ad15, 0x00a67c04, 0x008a5c04, 0x00754c08, 0x005c3b03, 0x00503305, 0x00462c08, 0x003e270a, 0x00362309, 0x002b1c04, 0x00251804, 0x00221a09, 0x001a1506, 0x00181407, 0x00141407, 0x00121108, 0x00101108, 0x00101009, 0x000f1008, 0x0010120a, 0x0011120c, 0x0010130e, 0x00101411, 0x000f1411, 0x000d1712, 0x000f1816, 0x00101818, 0x00121918, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e18, 0x00182019, 0x00182019, 0x0019201a, 0x001c1f18, 0x001d1e18, 0x00181a14, 0x0010120c, 0x0012120c, 0x0014120c, 0x0014110b, 0x00181108, 0x001d160c, 0x0020160b, 0x00231707, 0x002e200a, 0x0037260a, 0x003c290d, 0x00442e0a, 0x0051390e, 0x00604010, 0x007e5817, 0x00af8828, 0x00cbb028, 0x00ccb918, 0x00ccbc0c, 0x00cbbe0b, 0x00cbbc0c, 0x00ccbb0c, 0x00ccb710, 0x00ba9b06, 0x009c7400, 0x00885802, 0x00835200, 0x007f4c04, 0x00784802, 0x006c4400, 0x00603e00, 0x005b3c02, 0x00543804, 0x00533607, 0x00503408, 0x004c3408, 0x00483006, 0x00452f06, 0x00412c04, 0x00432e08, 0x00402906, 0x003c2706, 0x003c2608, 0x003b2408, 0x00382108, 0x00342006, 0x00341f06, 0x00331f08, 0x00331d08, 0x00321d09, 0x00301d08, 0x00301d08, 0x002e1c06, 0x002c1904, 0x002c1906, 0x002c1a06, 0x002a1a06, 0x00281905, 0x00291808, 0x002b1909, 0x002b1909, 0x002b1909, 0x002c1808, 0x002c1808, 0x002a1807, 0x00291807, 0x00291806, 0x00281804, 0x00281603, 0x002a1806, 0x002c1a08, 0x002c1a08, 0x002c1a08, 0x002e1b08, 0x002f1c07, 0x002e1c04, 0x002c1904, 0x002c1a07, 0x002c1a08, 0x002c1808, 0x002c1809, 0x002c190c, 0x002b170c, 0x0028150b, 0x0027160b, 0x0025150a, 0x0025150a, 0x0027150b, 0x0028150b, 0x0027160b, 0x0025170b, 0x0024180a, 0x00231708, 0x00231708, 0x00231708, 0x00231708, 0x0024160a, 0x0024160a, 0x0025170b, 0x00231409, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00211408, 0x00211408, 0x00201508, 0x001f1608, 0x001f1608, 0x001f1608, 0x00201508, 0x00201408, 0x00211408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001e1407, 0x001d1407, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1308, 0x001d1207, 0x001d1207, 0x001d1207, 0x001f1208, 0x001f1308, 0x001e1308, 0x001d1308, 0x001f1308, 0x00201307, 0x001e1407, 0x001e1407, 0x001e1508, 0x001b1206, 0x001c1307, 0x001f1409, 0x0020150a, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1406, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1306, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x00201408, 0x00221509, 0x0024160a, 0x0024160a, 0x0024160a, 0x00241608, 0x00261708, 0x002a1a09, 0x002c1906, 0x00311c08, 0x00341c07, 0x00381f08, 0x003b2307, 0x003f2609, 0x00452a0c, 0x004b3008, 0x00533303, 0x00603c08, 0x0072480e, 0x00906314, 0x00c49b2e, 0x00ccaf22, 0x00ccb015, 0x00ccb011, 0x00ccac18, 0x00cba91e, 0x00caa718, 0x00caa517, 0x00caa419, 0x00cba51c, 0x00cba619, 0x00cba818, 0x00ccaa1a, 0x00ccad17, 0x00cbb016, 0x00cbb211, 0x00cbb30d, 0x00cbb40c, 0x00cbb50a, 0x00c8b706, 0x00c7b607, 0x00c8b70b, 0x00cbb40e, 0x00cbab14, 0x00b3840a, 0x00915b00, 0x007c4b02, 0x00704000, 0x006c3e01, 0x006f4302, 0x00714501, 0x007a4d03, 0x00845504, 0x00895800, 0x00905c00, 0x00986402, 0x009d6901, 0x00ac780a, 0x00b7840e, 0x00c08f12, 0x00c69614, 0x00cba017, 0x00cba615, 0x00cba910, 0x00ccab10, 0x00ccac0e, 0x00ccac0c, 0x00c9a60a, 0x00c89c07, 0x00c9a30a, 0x00cab310, 0x00cab911, 0x00cabb09, 0x00c8bb05, 0x00c8bb09, 0x00cbb314, 0x00b48e0c, 0x00906201, 0x0081560b, 0x00644004, 0x00533402, 0x00482d05, 0x0040290a, 0x0038240b, 0x002c1d05, 0x00241602, 0x00221808, 0x00211a0c, 0x00171404, 0x00151405, 0x00121106, 0x00101108, 0x00101009, 0x000f1008, 0x00101009, 0x0010100a, 0x000f120d, 0x00101410, 0x000f1410, 0x000e1613, 0x000f1816, 0x00101818, 0x00121918, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e18, 0x00181f19, 0x0019201a, 0x001b211b, 0x001c2019, 0x001c1d17, 0x00161711, 0x0014140e, 0x0014120c, 0x0014120c, 0x0015120b, 0x001b140c, 0x0020160c, 0x0021160b, 0x00271b0b, 0x0031230b, 0x00372708, 0x003f2b0c, 0x0048330c, 0x00543c10, 0x0062440f, 0x00866118, 0x00b9942a, 0x00ccb222, 0x00cbb916, 0x00ccbc0f, 0x00ccbc0c, 0x00ccbb0c, 0x00cbb70e, 0x00c7a911, 0x00a27d00, 0x00885f00, 0x00784e00, 0x00724b01, 0x00694402, 0x00603d00, 0x00573b00, 0x00513801, 0x004f3707, 0x004c3408, 0x004c3208, 0x004c320a, 0x0048310b, 0x00432e08, 0x003f2c07, 0x003c2805, 0x003c2808, 0x003a2507, 0x00382305, 0x00382206, 0x00372108, 0x00342008, 0x00321d07, 0x00301d06, 0x00301d08, 0x002f1c08, 0x002d1b08, 0x002e1b08, 0x002e1b08, 0x002c1a07, 0x002b1805, 0x00291807, 0x00281807, 0x00281907, 0x00281a07, 0x00281808, 0x00281809, 0x0028180a, 0x0028180a, 0x00291808, 0x00291808, 0x00281707, 0x00271706, 0x00271706, 0x00241504, 0x00241403, 0x00251605, 0x00281809, 0x0029190b, 0x002b1909, 0x002b1908, 0x002c1a07, 0x002d1c06, 0x002b1a06, 0x002c1a08, 0x002a1808, 0x00291808, 0x00291808, 0x002b180b, 0x0028170b, 0x0025150a, 0x0024160a, 0x00241509, 0x00241409, 0x0025150a, 0x0025150a, 0x0024160a, 0x0023160a, 0x0023160a, 0x00231708, 0x00231708, 0x00231708, 0x00231708, 0x00241409, 0x00241409, 0x00231408, 0x00221408, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00201408, 0x00201408, 0x001f1608, 0x001f1608, 0x001f1608, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001d1306, 0x001e1407, 0x00201508, 0x00201508, 0x00201508, 0x001e1407, 0x001d1306, 0x001f1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001d1207, 0x001d1207, 0x001d1207, 0x001f1208, 0x001f1308, 0x001e1308, 0x001d1308, 0x001f1308, 0x00201307, 0x001e1407, 0x001e1407, 0x001e1508, 0x001b1206, 0x001c1307, 0x0020140a, 0x0020160b, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1306, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1306, 0x001b1407, 0x001c1308, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x00201307, 0x00221509, 0x00241409, 0x00241409, 0x0024160a, 0x00241608, 0x00271709, 0x00281808, 0x002c1808, 0x00301b08, 0x00341c08, 0x00381f08, 0x003b2208, 0x003e240a, 0x0044290d, 0x00492e0a, 0x00533307, 0x005f3809, 0x006d4409, 0x00916414, 0x00c7a02c, 0x00c9b418, 0x00cab70c, 0x00cab808, 0x00cab60f, 0x00cbb412, 0x00cbb40e, 0x00ccb50f, 0x00ccb412, 0x00ccb514, 0x00ccb512, 0x00ccb50e, 0x00cbb40c, 0x00cbb40e, 0x00cab40e, 0x00cab40d, 0x00c9b50c, 0x00c8b60c, 0x00c8b708, 0x00c7b704, 0x00c8b708, 0x00cbb50c, 0x00ccb413, 0x00caa614, 0x00a87804, 0x00885200, 0x00734600, 0x00643700, 0x00603601, 0x005c3500, 0x005c3801, 0x00613c04, 0x00694204, 0x00714707, 0x00784b08, 0x0082510c, 0x0088540a, 0x008d5708, 0x00935a06, 0x00986008, 0x00a2690c, 0x00a9720d, 0x00af7c0c, 0x00b98b0c, 0x00c29510, 0x00c89c12, 0x00cba010, 0x00c5980d, 0x00c7940c, 0x00c8a00c, 0x00ccb512, 0x00cbb910, 0x00cbba09, 0x00cabc06, 0x00c8bb0a, 0x00ccb412, 0x00c19e12, 0x009c7003, 0x00875908, 0x006e4808, 0x00563501, 0x00482d02, 0x00402908, 0x00392508, 0x00301f08, 0x00271703, 0x00211507, 0x00241b0d, 0x00181505, 0x00141405, 0x00131107, 0x00121108, 0x00101008, 0x00101108, 0x00101108, 0x00101009, 0x0010110c, 0x00111310, 0x000f1412, 0x000e1514, 0x000e1716, 0x00101817, 0x00101818, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e18, 0x00181f19, 0x0019201a, 0x001b211a, 0x001f241c, 0x00181a14, 0x0014130c, 0x0014120c, 0x0014120c, 0x0014130a, 0x0018140c, 0x001d170d, 0x001f160b, 0x0020160b, 0x002b1d0d, 0x00322409, 0x00392808, 0x00422f0d, 0x004c380f, 0x00563d0e, 0x00684b11, 0x008d6919, 0x00c19e2b, 0x00cbb31c, 0x00cbba14, 0x00cabc0f, 0x00cbbc0b, 0x00cab90c, 0x00ccb410, 0x00b8970c, 0x00926600, 0x007f5304, 0x006e4a04, 0x00624201, 0x00583e03, 0x00503800, 0x004c3804, 0x00483504, 0x00483408, 0x00473008, 0x00482f0a, 0x00452c09, 0x00402b0a, 0x003c2808, 0x00382605, 0x00342304, 0x00342307, 0x00322006, 0x00301f05, 0x00301f04, 0x00311d08, 0x00301c08, 0x002e1c08, 0x002e1c08, 0x002c1c09, 0x002a1b0a, 0x002a1808, 0x002c1908, 0x002c1908, 0x00281805, 0x00281604, 0x00261605, 0x00251605, 0x00251705, 0x00241705, 0x00241604, 0x00241605, 0x00251706, 0x00261807, 0x00281809, 0x00281809, 0x00271708, 0x00251709, 0x00261709, 0x00231407, 0x00221406, 0x00221308, 0x00231408, 0x0025160a, 0x0028180b, 0x002b180b, 0x002b1909, 0x002a1b08, 0x00281806, 0x00281808, 0x00271708, 0x00281808, 0x00281809, 0x00261608, 0x0027160a, 0x0024160a, 0x0023160a, 0x00231509, 0x00221509, 0x0024150a, 0x0024160a, 0x0023160a, 0x0023160a, 0x0022170a, 0x00231708, 0x00231708, 0x00231708, 0x00231708, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00201408, 0x001f1407, 0x001c1407, 0x001e1508, 0x001c1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1408, 0x001e1407, 0x001f1408, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001d1207, 0x001c1106, 0x001d1207, 0x001f1208, 0x001f1308, 0x001e1308, 0x001d1308, 0x001f1308, 0x00201307, 0x001e1407, 0x001e1407, 0x001e1508, 0x001b1206, 0x001c1307, 0x0020150a, 0x0020150a, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001c1306, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1306, 0x001b1407, 0x001c1307, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x00211409, 0x00221509, 0x00241409, 0x00241409, 0x0024160a, 0x00241608, 0x0028180b, 0x00291808, 0x002c1a08, 0x00301b08, 0x00321c08, 0x00361e08, 0x003b220a, 0x003f250e, 0x00442810, 0x00482c0b, 0x00523209, 0x005e380c, 0x0070460c, 0x00986c19, 0x00cba530, 0x00c9b417, 0x00cab70b, 0x00cab808, 0x00cab70d, 0x00c8b60c, 0x00c8b709, 0x00c9b80a, 0x00c9b80c, 0x00cab80d, 0x00cab80c, 0x00c9b809, 0x00c8b807, 0x00c8b708, 0x00c9b608, 0x00c9b608, 0x00c8b708, 0x00c8b806, 0x00c8b704, 0x00c9b404, 0x00cbb10b, 0x00cbad0f, 0x00cba80f, 0x00c0950e, 0x009d6902, 0x00854f04, 0x006c4401, 0x005b3400, 0x00583306, 0x00523004, 0x004c3006, 0x004e3307, 0x00503205, 0x00543304, 0x00593705, 0x005d3a04, 0x00673d04, 0x0074460a, 0x007b4a09, 0x00814e0b, 0x0088530c, 0x008d5608, 0x008f5806, 0x00925c03, 0x00986300, 0x009c6900, 0x00a87402, 0x00b07708, 0x00b57b07, 0x00c49812, 0x00ccb319, 0x00cbb811, 0x00cbba09, 0x00cabc06, 0x00c9bc0b, 0x00ccb810, 0x00caaa14, 0x00a87d05, 0x00885800, 0x00714a08, 0x00593a02, 0x004b3003, 0x00432c09, 0x003c280b, 0x0036230b, 0x002c1b06, 0x00221405, 0x0021180b, 0x001c1908, 0x00141405, 0x00141207, 0x00121107, 0x00101008, 0x00101108, 0x00101108, 0x00101009, 0x0010110c, 0x0011140f, 0x00101412, 0x000e1514, 0x000e1716, 0x000f1817, 0x00101818, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181d18, 0x00182018, 0x00182018, 0x001a2018, 0x001d2119, 0x00161710, 0x0012120b, 0x0013120a, 0x0014120a, 0x0014130a, 0x0018150c, 0x001c170b, 0x001c1407, 0x00211907, 0x002c210b, 0x00322508, 0x003a2a06, 0x0043310d, 0x004c3a0e, 0x00583d0c, 0x00714f11, 0x0099731c, 0x00c8a62a, 0x00ccb518, 0x00caba11, 0x00c9bc0e, 0x00cbbc0b, 0x00ccb80b, 0x00c7ac0f, 0x00a78204, 0x00875b02, 0x00734b05, 0x00614204, 0x00573c03, 0x004f3907, 0x00483606, 0x00443408, 0x00423207, 0x00443008, 0x00432d08, 0x00422b08, 0x003f2808, 0x003a2507, 0x00362306, 0x00322104, 0x00312004, 0x002f1f03, 0x002e1e03, 0x002f1d06, 0x00301c09, 0x002e1c0a, 0x002c1b0a, 0x002b1a09, 0x00291908, 0x00281808, 0x00271808, 0x00271708, 0x00261605, 0x00261605, 0x00251504, 0x00241604, 0x00241507, 0x00241508, 0x00241508, 0x00241608, 0x00241608, 0x00241608, 0x00241608, 0x00251708, 0x00251608, 0x00261608, 0x0027160b, 0x0026160a, 0x00241609, 0x0023140a, 0x00201308, 0x001c1008, 0x0020140c, 0x0023140c, 0x0026150c, 0x0028180c, 0x0029180b, 0x00281708, 0x00281608, 0x00281709, 0x00251407, 0x00261608, 0x00261608, 0x00241408, 0x00251509, 0x00241509, 0x00241509, 0x00231409, 0x00231409, 0x00241409, 0x00231509, 0x00221609, 0x00211609, 0x00211609, 0x00201608, 0x00201608, 0x00211609, 0x00211609, 0x00211408, 0x00221408, 0x00211408, 0x00231509, 0x00211408, 0x00201408, 0x00211408, 0x00211408, 0x00201508, 0x00201508, 0x00201508, 0x00201408, 0x001e1306, 0x001d1306, 0x001d1306, 0x001d1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001d1205, 0x00201408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1307, 0x001e1306, 0x001e1306, 0x001d1205, 0x001e1306, 0x001e1306, 0x001e1306, 0x001e1306, 0x001d1306, 0x001d1306, 0x001f1406, 0x001f1407, 0x001d1304, 0x001d1304, 0x001d1208, 0x001e1308, 0x001d1208, 0x001d1208, 0x001f1208, 0x001f1308, 0x001e1308, 0x001e1409, 0x001e1408, 0x001e1406, 0x001e1406, 0x001d1407, 0x001c1407, 0x001c1306, 0x001c1307, 0x001f1409, 0x001f1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201407, 0x00201407, 0x001f1406, 0x001d1406, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1406, 0x001c1407, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1408, 0x001d1306, 0x001e1306, 0x001f1408, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001f1306, 0x001f1306, 0x00201307, 0x00201307, 0x001f1406, 0x001f1406, 0x001f1406, 0x001f1406, 0x001f1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00231409, 0x00231409, 0x00241409, 0x00241409, 0x0025150b, 0x0026160a, 0x0028180a, 0x00281809, 0x002b1908, 0x002f1b08, 0x00311b08, 0x00341c07, 0x0039210a, 0x003d250e, 0x00432810, 0x00482c0c, 0x0051320b, 0x005e390f, 0x006f470d, 0x009a6f1b, 0x00cba42f, 0x00cbb11b, 0x00ccb50e, 0x00ccb609, 0x00ccb50e, 0x00cbb50d, 0x00cbb608, 0x00cbb807, 0x00cbb709, 0x00cbb60c, 0x00cbb70b, 0x00cbb709, 0x00cab608, 0x00cab608, 0x00cbb708, 0x00cbb60a, 0x00cbb409, 0x00cbb208, 0x00ccaf08, 0x00cba80b, 0x00c6a00d, 0x00c0950f, 0x00b6860a, 0x00a57003, 0x008c5500, 0x007b4604, 0x00694004, 0x00593400, 0x00563206, 0x00503007, 0x004a3008, 0x004b3009, 0x004c3009, 0x004c2f0a, 0x004b2f06, 0x004b3003, 0x004f3000, 0x00523200, 0x00573500, 0x00603c03, 0x00664104, 0x006c4606, 0x0074480b, 0x00804c0f, 0x0083500c, 0x00845308, 0x00875604, 0x00915a02, 0x00a16607, 0x00bd8f18, 0x00cbb01c, 0x00ccb811, 0x00ccbb0a, 0x00cbbc08, 0x00cabc0b, 0x00ccb911, 0x00ccb016, 0x00b2880b, 0x008c5c00, 0x00744c04, 0x005c3c00, 0x004d3204, 0x00442f0b, 0x003d290c, 0x0038240b, 0x002e1e07, 0x00251806, 0x00201507, 0x001f1808, 0x00181306, 0x00141307, 0x00121207, 0x00111108, 0x00111108, 0x00101108, 0x000f1108, 0x000f110a, 0x000f110d, 0x000e120f, 0x000e1513, 0x000c1413, 0x000e1614, 0x00101815, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00191d18, 0x00192018, 0x00192018, 0x001a2018, 0x001d2119, 0x0016170e, 0x00121209, 0x00131209, 0x00141309, 0x00151309, 0x0018160b, 0x001c160b, 0x001c1404, 0x00261e09, 0x00291f05, 0x00342608, 0x003c2c08, 0x0044320d, 0x004e3a0c, 0x005c400c, 0x00775111, 0x00a88026, 0x00ccae2c, 0x00ccb714, 0x00c8bb0e, 0x00c9bc0c, 0x00ccbc09, 0x00ccb70c, 0x00c0a10c, 0x009a7301, 0x00805503, 0x00694604, 0x00583c01, 0x004f3602, 0x00493406, 0x0046340a, 0x0041310a, 0x003f2e08, 0x003f2a07, 0x003d2605, 0x003c2404, 0x00392304, 0x00352004, 0x00332005, 0x00301f05, 0x00301e06, 0x002f1d05, 0x002d1c04, 0x002c1b07, 0x002c1b08, 0x002c1a09, 0x00291908, 0x00281808, 0x00261706, 0x00261706, 0x00241406, 0x00251607, 0x00241706, 0x00231605, 0x00211404, 0x00211404, 0x00211407, 0x00211408, 0x00231508, 0x00231508, 0x00231509, 0x00231509, 0x00231509, 0x0024160a, 0x00241609, 0x00241609, 0x0025150b, 0x0024140a, 0x0023140a, 0x0023150b, 0x0020140a, 0x001a1007, 0x001d140b, 0x0020140b, 0x0024140b, 0x0025150a, 0x00261508, 0x00271609, 0x00261508, 0x00261508, 0x00261508, 0x00251508, 0x00241608, 0x00241608, 0x00241608, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00231409, 0x00211509, 0x00201609, 0x00201709, 0x00201508, 0x00201508, 0x00201609, 0x00201609, 0x00201508, 0x00201508, 0x00201508, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1306, 0x001d1306, 0x001e1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1104, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1306, 0x001e1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001f1406, 0x001f1406, 0x001d1304, 0x001d1304, 0x001d1207, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1208, 0x001f1308, 0x001f1409, 0x001f1409, 0x001e1408, 0x001e1405, 0x001e1405, 0x001c1407, 0x001c1407, 0x001c1305, 0x001c1407, 0x001f1409, 0x001f1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201406, 0x00201406, 0x001f1406, 0x001e1506, 0x001d1507, 0x001c1508, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001d1205, 0x001d1306, 0x00201508, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x001f1406, 0x001f1406, 0x001f1406, 0x001f1406, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x00201508, 0x00221509, 0x00211408, 0x00201408, 0x00201408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x0025140c, 0x0027160b, 0x00271609, 0x0028180a, 0x002a1908, 0x002e1b08, 0x00311c0c, 0x00331c0b, 0x00361f08, 0x003c240c, 0x0042280f, 0x00482d0c, 0x0050330b, 0x005d3b0f, 0x0070490f, 0x009d741d, 0x00cba72f, 0x00cbb019, 0x00ccb60c, 0x00ccb707, 0x00ccb60b, 0x00cbb60c, 0x00ccb707, 0x00ccb804, 0x00ccb707, 0x00ccb508, 0x00ccb506, 0x00cbb406, 0x00cbb306, 0x00ccb10c, 0x00ccac0c, 0x00ccab10, 0x00caa40f, 0x00c4990c, 0x00bc8c08, 0x00b28004, 0x00a67300, 0x009c6500, 0x009c6000, 0x00945800, 0x00885204, 0x00784908, 0x00603801, 0x00583401, 0x00533104, 0x004d2e04, 0x00482c04, 0x00462c05, 0x00462a07, 0x00472c0a, 0x00482b09, 0x00482b05, 0x00482b03, 0x00482b01, 0x00482c00, 0x004c3003, 0x004f3302, 0x00523603, 0x00583806, 0x00613909, 0x00643c07, 0x00694108, 0x00704806, 0x007d4f03, 0x00925d08, 0x00be9220, 0x00ccb320, 0x00ccb811, 0x00ccbb0a, 0x00cbbc08, 0x00ccbc0c, 0x00ccbc11, 0x00ccb414, 0x00bc960f, 0x00936200, 0x007a4f05, 0x005f3e02, 0x00503404, 0x00442f09, 0x003e2b0b, 0x00392508, 0x002f1f06, 0x00251804, 0x001f1504, 0x00201808, 0x001b1408, 0x00151407, 0x00121207, 0x00121109, 0x00121109, 0x00101008, 0x000e1108, 0x000e1109, 0x000e110b, 0x000d110e, 0x000e1612, 0x000a1410, 0x000d1512, 0x000f1714, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181f19, 0x001a1e19, 0x001a2018, 0x001a2018, 0x001b2118, 0x001b1f14, 0x0013150c, 0x00111109, 0x00121109, 0x00131208, 0x00151308, 0x001a170c, 0x001c150a, 0x00201606, 0x00281f08, 0x002d2208, 0x0035270a, 0x003d2d09, 0x0046330c, 0x00503b0c, 0x0064450c, 0x007e5812, 0x00b48f2d, 0x00ccaf25, 0x00ccb813, 0x00c8bb0d, 0x00c9bc0c, 0x00ccbc09, 0x00ccb411, 0x00b9960d, 0x00916801, 0x00774e01, 0x00614301, 0x004f3800, 0x00483300, 0x00443104, 0x00433008, 0x003f2d08, 0x003c2a06, 0x003c2605, 0x003b2304, 0x00392004, 0x00351f04, 0x00341e08, 0x00311d08, 0x00301d08, 0x002e1c08, 0x002d1c08, 0x002c1a08, 0x002a1906, 0x00281806, 0x00281806, 0x00281808, 0x00281807, 0x00251708, 0x00251608, 0x00241507, 0x00241608, 0x00221708, 0x00211607, 0x00201506, 0x00201406, 0x00211509, 0x00201509, 0x00201509, 0x0021160a, 0x00201409, 0x00201409, 0x00201409, 0x00211509, 0x0023150a, 0x0024160b, 0x0024150b, 0x00211309, 0x00201309, 0x0021140c, 0x0020150b, 0x00191208, 0x00191208, 0x001c1308, 0x001e1408, 0x00201408, 0x00221306, 0x00241408, 0x00231408, 0x00241408, 0x00251509, 0x00241509, 0x00241509, 0x00241509, 0x00241509, 0x00241409, 0x00241409, 0x00231409, 0x00231409, 0x00231409, 0x00221409, 0x00211508, 0x00201508, 0x001f1608, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x00201408, 0x00201408, 0x00201408, 0x00201308, 0x00201408, 0x001f1408, 0x001f1408, 0x001e1408, 0x001e1407, 0x001e1407, 0x001e1306, 0x001e1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001d1306, 0x001e1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001f1306, 0x001e1306, 0x001d1306, 0x001d1305, 0x001d1305, 0x001d1306, 0x001d1306, 0x001e1306, 0x001d1306, 0x001f1406, 0x001f1406, 0x001d1304, 0x001d1304, 0x001d1207, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1208, 0x001f1308, 0x001f1409, 0x001f1409, 0x001e1408, 0x001e1405, 0x001e1405, 0x001c1407, 0x001c1407, 0x001c1305, 0x001c1407, 0x001f1409, 0x001f1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201406, 0x00201406, 0x001f1406, 0x001d1405, 0x001c1406, 0x001c1406, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1306, 0x001e1306, 0x001f1408, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201308, 0x00211408, 0x00211408, 0x00201507, 0x00201506, 0x00201506, 0x00201506, 0x00201508, 0x00201508, 0x00211609, 0x0022170a, 0x0023170a, 0x0023160a, 0x00221509, 0x00211408, 0x00211408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x0025140c, 0x0027160b, 0x0027160a, 0x0028180a, 0x002a1908, 0x002e1b09, 0x00311c0c, 0x00331c0b, 0x00341e08, 0x0039210b, 0x0042280e, 0x00482d0a, 0x0050340b, 0x005e3c0e, 0x00714b0d, 0x00a37a20, 0x00caa82b, 0x00cbb114, 0x00c9b608, 0x00c9b804, 0x00c9b80b, 0x00c9b80c, 0x00cab607, 0x00ccb508, 0x00ccb20a, 0x00ccb008, 0x00ccaf07, 0x00cbab08, 0x00c8a707, 0x00c49e0a, 0x00bf9208, 0x00b98404, 0x00b37800, 0x00a86b00, 0x00a16600, 0x009c6400, 0x009c6603, 0x00a56c0b, 0x00ae710d, 0x009e6405, 0x00845202, 0x00774d0c, 0x005c3802, 0x00523001, 0x004f2f05, 0x004a2c05, 0x00452a04, 0x00442906, 0x00422707, 0x00432709, 0x00432708, 0x00432607, 0x00432607, 0x00432607, 0x00432608, 0x00452907, 0x00482c07, 0x004b3009, 0x004e310b, 0x0050320a, 0x00533508, 0x00573a08, 0x005f4006, 0x006e4804, 0x00855509, 0x00bc9327, 0x00ccb525, 0x00ccb813, 0x00ccba0a, 0x00ccbc08, 0x00ccbc0c, 0x00ccbc0e, 0x00ccb80e, 0x00c2a20f, 0x00976b00, 0x007c5003, 0x00623f00, 0x00513402, 0x00453008, 0x003e2c09, 0x003a2506, 0x00302004, 0x00271902, 0x00201402, 0x00201607, 0x001c1609, 0x00171408, 0x00131108, 0x00111009, 0x00101009, 0x000f1008, 0x000d1008, 0x000d1008, 0x000e100b, 0x000e110e, 0x000e1512, 0x000a1410, 0x000d1512, 0x000f1714, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181f19, 0x001a1f19, 0x001b2018, 0x001b2018, 0x001c2118, 0x00181c11, 0x0010140a, 0x00101109, 0x00101009, 0x00121009, 0x00151308, 0x001b140c, 0x001b1107, 0x00241809, 0x002c1f09, 0x00302208, 0x003a280c, 0x00422e0b, 0x0049340e, 0x00543c0c, 0x006a480c, 0x00876014, 0x00bf9c34, 0x00cbb121, 0x00cbb812, 0x00c9bb0d, 0x00cabc0b, 0x00ccbb0a, 0x00ccb014, 0x00ac8408, 0x00895d03, 0x006e4800, 0x00583f00, 0x00473800, 0x00423200, 0x00402e02, 0x003c2b04, 0x00382804, 0x00352503, 0x00362202, 0x00372004, 0x00351d04, 0x00321c06, 0x00301c08, 0x002c1908, 0x002b1908, 0x002b1a0a, 0x002a1908, 0x00281806, 0x00281806, 0x00261805, 0x00261804, 0x00261804, 0x00241605, 0x00231508, 0x00231508, 0x00231508, 0x00221608, 0x00201608, 0x001f1407, 0x00201508, 0x00201508, 0x001f1409, 0x0020150a, 0x001f1409, 0x0020160b, 0x001f1409, 0x0020140a, 0x0020150a, 0x0020150a, 0x00201409, 0x0021140a, 0x0022150b, 0x00201409, 0x001f1108, 0x001f1208, 0x001c1409, 0x00191307, 0x00151205, 0x00181307, 0x001b1407, 0x001e1407, 0x00201305, 0x00221408, 0x00221408, 0x00211408, 0x00211408, 0x00221509, 0x00211509, 0x00211509, 0x00211509, 0x00241409, 0x00241409, 0x00231408, 0x00221408, 0x00221408, 0x00221408, 0x00201408, 0x00201508, 0x001f1508, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201408, 0x00201307, 0x00201307, 0x001f1307, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1306, 0x001e1306, 0x001e1306, 0x001e1407, 0x001e1407, 0x001f1406, 0x001f1406, 0x001d1304, 0x001d1304, 0x001d1207, 0x001d1207, 0x001e1308, 0x001e1308, 0x001f1208, 0x001f1308, 0x001f1409, 0x001f1409, 0x001e1408, 0x001e1405, 0x001e1405, 0x001c1407, 0x001c1407, 0x001c1305, 0x001c1407, 0x001f1409, 0x001f1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201406, 0x00201406, 0x001e1405, 0x001c1405, 0x001c1405, 0x001b1405, 0x001c1406, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00201508, 0x00201508, 0x00201609, 0x0021170a, 0x0022160a, 0x00221509, 0x00211408, 0x00211408, 0x00211408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x0025140c, 0x0027160b, 0x0027160b, 0x0028180b, 0x002a180a, 0x002e1b09, 0x00311c0c, 0x00331c0b, 0x00341d08, 0x0039210b, 0x0041270e, 0x00482c0a, 0x00523409, 0x005e3c0c, 0x00734c0c, 0x00a88022, 0x00cba828, 0x00cbb113, 0x00cbb509, 0x00ccb70b, 0x00ccb712, 0x00cab410, 0x00cab10a, 0x00cbac0c, 0x00c9a40c, 0x00c89c0a, 0x00c49407, 0x00bb8b04, 0x00ae7d00, 0x00a87200, 0x00a56b00, 0x00a66800, 0x00a86802, 0x00ac6d0a, 0x00b17614, 0x00b38017, 0x00be8f20, 0x00c69824, 0x00ca9a26, 0x00b4801a, 0x00855402, 0x00744a0b, 0x00583603, 0x004d2e00, 0x004a2c04, 0x00442905, 0x00412805, 0x00402707, 0x003f2408, 0x003f2408, 0x003d2306, 0x003f2507, 0x00402609, 0x0040260c, 0x0040250c, 0x003f2508, 0x00412808, 0x00452c09, 0x00482f0c, 0x004a300c, 0x004a3108, 0x00503709, 0x00573c08, 0x0064440b, 0x007c520d, 0x00aa841f, 0x00c9b024, 0x00ccb611, 0x00ccb909, 0x00ccbc08, 0x00cbbc09, 0x00cabc0a, 0x00ccbb04, 0x00caae0e, 0x00a47c06, 0x007f5303, 0x00684201, 0x00553803, 0x00483308, 0x00412d08, 0x003c2604, 0x00332002, 0x002d1d04, 0x00231602, 0x001e1506, 0x001e170a, 0x00181409, 0x00141108, 0x0013100a, 0x0011100a, 0x000f1008, 0x000c1007, 0x000d1008, 0x000d100a, 0x000e120f, 0x000d1411, 0x000a1410, 0x000c1512, 0x000e1613, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181f19, 0x00191f19, 0x001b2019, 0x001b2019, 0x001c2118, 0x00171b11, 0x0010140a, 0x00101009, 0x00101009, 0x00121009, 0x00161309, 0x0019140a, 0x001d1108, 0x00271a0b, 0x002c1f0a, 0x00312108, 0x003c280c, 0x0043300c, 0x0049330c, 0x00573c0c, 0x006c480c, 0x008f6816, 0x00c2a332, 0x00cab420, 0x00cab912, 0x00c9bc0c, 0x00ccbd0a, 0x00ccba0c, 0x00c6a611, 0x00a07403, 0x00825602, 0x00684400, 0x00523c00, 0x00443600, 0x003f3000, 0x003c2c00, 0x00382804, 0x00362505, 0x00332303, 0x00332002, 0x00321e03, 0x00321c08, 0x00301c08, 0x002c1a08, 0x00281808, 0x00271809, 0x00271809, 0x00271808, 0x00261707, 0x00261807, 0x00241706, 0x00241605, 0x00241706, 0x00231606, 0x00221508, 0x00211407, 0x00211508, 0x00211508, 0x00201407, 0x00201407, 0x00201508, 0x00201508, 0x001c1206, 0x001f1408, 0x001e1308, 0x00201509, 0x001e1308, 0x00201509, 0x00201509, 0x001f1408, 0x001f1308, 0x00201408, 0x00201408, 0x00201408, 0x001f1208, 0x001e1207, 0x001c1408, 0x00181407, 0x00141104, 0x00161306, 0x00191407, 0x001c1407, 0x001e1307, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201609, 0x00201609, 0x00201609, 0x00201609, 0x00241409, 0x00241409, 0x00231409, 0x00221408, 0x00221408, 0x00221408, 0x00221409, 0x0022160a, 0x00221609, 0x00221409, 0x00211509, 0x00221609, 0x00211609, 0x00201508, 0x00201508, 0x00201609, 0x00201608, 0x00201408, 0x00201408, 0x001f1306, 0x001f1307, 0x001f1408, 0x001f1408, 0x001e1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001f1408, 0x001e1306, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201408, 0x00201307, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1406, 0x001f1406, 0x001d1304, 0x001d1305, 0x001d1205, 0x001d1206, 0x001e1308, 0x001f1308, 0x00201208, 0x00201308, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1406, 0x001f1406, 0x001d1407, 0x001d1407, 0x001c1305, 0x001c1306, 0x00201409, 0x001e1408, 0x001f1408, 0x00201508, 0x00211408, 0x00201408, 0x001f1305, 0x001f1305, 0x001e1406, 0x001d1405, 0x001c1306, 0x001c1306, 0x001c1307, 0x001d1408, 0x001d1408, 0x001d1408, 0x001f1308, 0x001f1308, 0x00201208, 0x00201208, 0x00201208, 0x00201208, 0x001f1208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1306, 0x001e1306, 0x001e1306, 0x001e1306, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001e1306, 0x001f1407, 0x001f1407, 0x001f1407, 0x001f1407, 0x001f1306, 0x001f1306, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00221508, 0x00221508, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221409, 0x00231509, 0x00221408, 0x00231408, 0x00241408, 0x00241408, 0x00241509, 0x0024150b, 0x0026160a, 0x0027160b, 0x0027180c, 0x0029180a, 0x002d1a0b, 0x00301c0c, 0x00321c0c, 0x00331d08, 0x0038210a, 0x0040270d, 0x00482c0a, 0x0051320a, 0x005e3c0c, 0x00734c0a, 0x00ac8423, 0x00cca92b, 0x00ccac14, 0x00ccac0d, 0x00ccaa0c, 0x00c8a40f, 0x00c69f0f, 0x00c3980b, 0x00bb8804, 0x00b37c01, 0x00b07301, 0x00a96a00, 0x00a46600, 0x00a56800, 0x00a86a02, 0x00ac7008, 0x00b37a10, 0x00be8919, 0x00c4941e, 0x00c99d20, 0x00cba61f, 0x00cbab1b, 0x00cbac1c, 0x00cca71f, 0x00b18213, 0x00885503, 0x00744408, 0x00533200, 0x004d2f02, 0x00452b04, 0x00412805, 0x00402508, 0x003f2409, 0x003c240b, 0x003c220c, 0x003c2309, 0x003b2108, 0x003b2309, 0x003d240c, 0x003e250c, 0x003e250b, 0x003f2608, 0x00402708, 0x00442a0a, 0x00452c0a, 0x00452d06, 0x004b3208, 0x00513809, 0x005e400c, 0x00744f0d, 0x00977414, 0x00c3a725, 0x00cbb415, 0x00ccb90c, 0x00ccbb08, 0x00cbbc08, 0x00cbbc08, 0x00ccbb05, 0x00cab00c, 0x00ae8909, 0x00845a01, 0x006c4404, 0x00583a04, 0x004c3607, 0x00423006, 0x003c2805, 0x00342203, 0x002f2006, 0x00261904, 0x001d1405, 0x001e170a, 0x00181409, 0x00141208, 0x0014110a, 0x0014130b, 0x00101008, 0x000c1007, 0x000d1008, 0x000d100a, 0x000e120c, 0x000c1410, 0x000a1410, 0x000c1512, 0x000d1512, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181f19, 0x00181f19, 0x00192018, 0x00192018, 0x001a2118, 0x00141910, 0x000e130c, 0x000f100a, 0x0011110a, 0x0014110a, 0x0017130a, 0x001a1409, 0x001e1308, 0x00281c0b, 0x002c1f0a, 0x00322208, 0x003d280d, 0x0042300b, 0x0049340c, 0x005b3f0e, 0x00714c0f, 0x009a741c, 0x00c8a930, 0x00cab51d, 0x00c8ba11, 0x00c8bc0a, 0x00cbbd09, 0x00cbb80d, 0x00be9c0d, 0x00946700, 0x007b5000, 0x00624100, 0x004c3701, 0x00413101, 0x003b2b00, 0x00382902, 0x00352604, 0x00342404, 0x00312204, 0x00311e04, 0x002d1b02, 0x002c1c07, 0x002b1a08, 0x00281807, 0x00261808, 0x00261909, 0x00241808, 0x00241607, 0x00241607, 0x00241507, 0x00231506, 0x00241607, 0x00241507, 0x00211407, 0x00221509, 0x001f1206, 0x00201408, 0x00211408, 0x00201407, 0x00201406, 0x00201406, 0x00211507, 0x001f1408, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x001f1208, 0x001c1408, 0x00191508, 0x00131003, 0x00141206, 0x00181306, 0x001b1408, 0x001c1208, 0x00201409, 0x00201409, 0x00211408, 0x00221608, 0x00201609, 0x00201609, 0x00201609, 0x00201609, 0x00241409, 0x00241409, 0x00241409, 0x00211308, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00201508, 0x00201408, 0x00201307, 0x00201508, 0x00201709, 0x00201508, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001e1205, 0x00201408, 0x00211408, 0x00201307, 0x00201307, 0x00201307, 0x001d1205, 0x001f1408, 0x00201508, 0x001f1408, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201307, 0x001e1407, 0x001c1205, 0x001c1205, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001e1306, 0x001d1306, 0x001e1407, 0x001e1306, 0x001d1206, 0x001d1207, 0x001e1308, 0x001e1308, 0x001f1308, 0x00201208, 0x00201208, 0x00201208, 0x00201208, 0x00211308, 0x00201105, 0x00201105, 0x001f1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001c1104, 0x001e1205, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001d1306, 0x001e1306, 0x001f1408, 0x00201508, 0x00201508, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241509, 0x00241409, 0x00221407, 0x00241508, 0x00241508, 0x00241608, 0x0023160a, 0x00231708, 0x0024180c, 0x0025180c, 0x0028170c, 0x002b180c, 0x002f1c0c, 0x00301b0a, 0x00321d08, 0x0037210b, 0x0040270c, 0x00482c09, 0x0052320c, 0x00633c10, 0x00744c0a, 0x00a2781c, 0x00c49824, 0x00c09410, 0x00b88908, 0x00b38000, 0x00af7700, 0x00ac7000, 0x00a76900, 0x00a66700, 0x00a46400, 0x00a66801, 0x00ad7106, 0x00b47c0d, 0x00ba8412, 0x00c38f19, 0x00c7981e, 0x00c9a220, 0x00ccaa20, 0x00ccaf1c, 0x00cbb214, 0x00cab40c, 0x00c8b608, 0x00c8b40c, 0x00cbab17, 0x00a97d08, 0x00885400, 0x00714002, 0x00523000, 0x004a2d02, 0x00422802, 0x003d2504, 0x003c2208, 0x003a1f08, 0x00361f0a, 0x00351f0d, 0x00351e0c, 0x00341c0c, 0x00341c08, 0x00351f08, 0x00392109, 0x003c240c, 0x003e250b, 0x003e260a, 0x0041290c, 0x00432c0b, 0x00432c08, 0x0048310c, 0x004e370c, 0x005e4010, 0x00705010, 0x008a670f, 0x00b5921f, 0x00ccb21d, 0x00ccb812, 0x00cbba0a, 0x00cabb08, 0x00cbba08, 0x00ccb80a, 0x00ccb412, 0x00b9980f, 0x008c6400, 0x006e4803, 0x00593b04, 0x004c3704, 0x00423004, 0x003c2805, 0x00372404, 0x00301f06, 0x00261803, 0x001c1404, 0x001d1609, 0x00181409, 0x00141208, 0x00141109, 0x00131209, 0x00101208, 0x000d1007, 0x000d1007, 0x000e1109, 0x000d110c, 0x000c140f, 0x000b1410, 0x000b1411, 0x000c1512, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181f19, 0x0019201a, 0x0019201a, 0x001b2119, 0x00192018, 0x00192017, 0x00131810, 0x000e130c, 0x000f1009, 0x0011100a, 0x0015120b, 0x0017130a, 0x00191309, 0x0020140a, 0x00281c0c, 0x002d200b, 0x00342409, 0x003e290e, 0x0044320d, 0x004b380e, 0x005d4110, 0x0074500f, 0x00a37f21, 0x00caac2d, 0x00cbb818, 0x00c8ba10, 0x00c8bc0a, 0x00cbba08, 0x00cab310, 0x00b18e0b, 0x008a5e00, 0x00764c03, 0x005d3f02, 0x00493402, 0x003f2f01, 0x00392800, 0x00352502, 0x00322402, 0x00312206, 0x00302005, 0x002c1c02, 0x00291900, 0x002b1a07, 0x00281807, 0x00241606, 0x00231707, 0x00241808, 0x00221606, 0x00211505, 0x00211505, 0x001f1305, 0x00211407, 0x00221608, 0x00211507, 0x00201408, 0x00221509, 0x001e1206, 0x00211408, 0x00221509, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x001f1308, 0x001c1408, 0x00191508, 0x00131003, 0x00131105, 0x00181308, 0x001b1308, 0x001c1208, 0x00201409, 0x00201409, 0x00221509, 0x00221608, 0x00201609, 0x00201609, 0x00201609, 0x00201609, 0x00241409, 0x00241409, 0x00241409, 0x00211308, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00201508, 0x00201408, 0x00201307, 0x00201508, 0x00201709, 0x00201508, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001e1205, 0x00201408, 0x00211408, 0x00201307, 0x00201307, 0x00201307, 0x001d1205, 0x001f1408, 0x00201508, 0x00201508, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001d1305, 0x001e1407, 0x001e1407, 0x00201307, 0x001e1205, 0x00201307, 0x00201307, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201307, 0x001e1407, 0x001c1205, 0x001c1204, 0x001e1306, 0x00201609, 0x001f1408, 0x001d1205, 0x001d1205, 0x001f1408, 0x00201508, 0x00201508, 0x00201609, 0x00201508, 0x001d1307, 0x001d1207, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x00201408, 0x001e1205, 0x001e1205, 0x001e1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1306, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201508, 0x00201508, 0x00201508, 0x00201508, 0x00201508, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241509, 0x0024160a, 0x00241409, 0x00221407, 0x00241508, 0x00241508, 0x00241608, 0x0023160a, 0x00231708, 0x0023170a, 0x0025180c, 0x0028170c, 0x002b180c, 0x002f1c0c, 0x00301b0a, 0x00321c07, 0x0037210b, 0x003f250b, 0x00472a07, 0x0055340a, 0x00673f0e, 0x0073460b, 0x00855408, 0x009c680b, 0x009a6200, 0x009a6100, 0x009c6300, 0x009c6300, 0x00a46902, 0x00aa7007, 0x00b2780a, 0x00ba8410, 0x00c39517, 0x00c79e1a, 0x00c8a31a, 0x00cca91c, 0x00ccac18, 0x00ccae14, 0x00ccb113, 0x00cab210, 0x00c8b30e, 0x00c6b40b, 0x00c6b706, 0x00c7b805, 0x00c9b60c, 0x00caa813, 0x00a47701, 0x00845300, 0x006d3e00, 0x00502d00, 0x00472a01, 0x003f2502, 0x003a2304, 0x00392007, 0x00371c07, 0x00341c09, 0x00321c0c, 0x00321c0c, 0x00331c0c, 0x00321c08, 0x00321c06, 0x00321d05, 0x00361f08, 0x00392209, 0x003a2308, 0x003c2609, 0x003f2809, 0x003f2907, 0x00422d0a, 0x0048340b, 0x00563e0f, 0x006b4c13, 0x00815d0e, 0x00a58018, 0x00caaf24, 0x00ccb718, 0x00ccb90d, 0x00cabb0a, 0x00cbba0a, 0x00ccb90a, 0x00ccb711, 0x00c0a212, 0x00936d01, 0x00734c03, 0x005c3d04, 0x004d3805, 0x00433005, 0x003d2a07, 0x00382404, 0x00312005, 0x00281904, 0x001c1404, 0x001b1406, 0x001a150a, 0x00141308, 0x00141109, 0x00131209, 0x00111309, 0x000e1107, 0x000d1007, 0x000e1109, 0x000d110c, 0x000c130e, 0x000b1410, 0x000b1411, 0x000b1411, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181f19, 0x0019201a, 0x0019201a, 0x001b2119, 0x00192018, 0x00171e14, 0x000f140b, 0x000e130b, 0x000d1009, 0x0011100b, 0x0015140c, 0x00171308, 0x00181208, 0x0020150b, 0x00281c0c, 0x002f200a, 0x0037250b, 0x003f2a0d, 0x00483611, 0x004e390f, 0x005f4310, 0x007c5810, 0x00ae8925, 0x00cbae2a, 0x00cbb814, 0x00c8bb0e, 0x00c8ba08, 0x00cab80c, 0x00c8af10, 0x00a07c03, 0x00825702, 0x00704807, 0x00573903, 0x00483404, 0x003e2d03, 0x003a2902, 0x00322201, 0x002e1f01, 0x002c1c03, 0x002a1c04, 0x00281a04, 0x00261802, 0x00261704, 0x00241505, 0x00211506, 0x00211508, 0x00201608, 0x001f1406, 0x001f1406, 0x001f1406, 0x00201408, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x0021140a, 0x00201208, 0x0021140a, 0x0021140a, 0x00201409, 0x00201409, 0x00201208, 0x00201208, 0x001d1205, 0x001d1205, 0x001c1104, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001f1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00211309, 0x001f1409, 0x00181407, 0x00141305, 0x00141005, 0x00181308, 0x001b1308, 0x001c1208, 0x00201309, 0x00201409, 0x00211408, 0x00221608, 0x00201609, 0x00201609, 0x00201508, 0x00201508, 0x00231409, 0x00241409, 0x00231408, 0x00221408, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00201508, 0x00211408, 0x00201307, 0x00201508, 0x001f1608, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001e1205, 0x00201408, 0x00201408, 0x001f1206, 0x001e1205, 0x001e1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x001e1205, 0x00201307, 0x00201307, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201307, 0x001e1407, 0x001c1205, 0x001c1204, 0x001f1408, 0x00201508, 0x001d1205, 0x001d1205, 0x001d1306, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201508, 0x001e1407, 0x001d1206, 0x001d1207, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201408, 0x001e1205, 0x001e1205, 0x001e1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x00201508, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1306, 0x001e1205, 0x001f1205, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x00201508, 0x00211408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00211406, 0x00221407, 0x00221407, 0x00241508, 0x0023160a, 0x00231708, 0x0023160a, 0x0024180c, 0x0027160c, 0x0028170b, 0x002c190a, 0x00301b0a, 0x00331c09, 0x0038210c, 0x0040270d, 0x004a2c08, 0x00593608, 0x006c410c, 0x00774609, 0x00804c01, 0x008e5500, 0x00985e01, 0x00a06803, 0x00ab760c, 0x00b68416, 0x00c19220, 0x00c89a22, 0x00caa01c, 0x00cca51a, 0x00ccab14, 0x00ccb013, 0x00cbb213, 0x00cab310, 0x00c9b30b, 0x00ccb509, 0x00cbb608, 0x00cab408, 0x00c8b60a, 0x00c8b708, 0x00c8b705, 0x00c8b605, 0x00cbb30e, 0x00c9a214, 0x009f7001, 0x00815000, 0x00693d03, 0x004f2c01, 0x00452803, 0x003d2404, 0x00392206, 0x00392008, 0x00361c08, 0x00341c0b, 0x00321c0e, 0x00301c0d, 0x00301c0c, 0x00301c0a, 0x00301b08, 0x00301c08, 0x00311d07, 0x00341f08, 0x00372108, 0x00382308, 0x003b2608, 0x003d2908, 0x003e2b07, 0x00422f08, 0x004d380c, 0x00614511, 0x0079540f, 0x009a6f14, 0x00c0a020, 0x00ccb41f, 0x00ccb912, 0x00cbbc0c, 0x00c9bc0c, 0x00cbbc0a, 0x00ccb80e, 0x00c3aa11, 0x009a7603, 0x00774f02, 0x00604006, 0x00503906, 0x00443006, 0x003e2a07, 0x00382405, 0x00342006, 0x002c1d07, 0x001d1405, 0x00191304, 0x001c170b, 0x0016140a, 0x00131008, 0x00121108, 0x00101208, 0x000e1208, 0x000d1007, 0x000d1008, 0x000d120b, 0x000a120e, 0x000a1410, 0x000b1310, 0x000b1411, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001b211b, 0x001b211b, 0x001b211b, 0x001c221b, 0x001b2119, 0x00141a10, 0x000c1108, 0x000b1008, 0x000d0f08, 0x0012110b, 0x0016140c, 0x00161408, 0x00191308, 0x0020180c, 0x00281c0c, 0x00302109, 0x0038270a, 0x003f2c0c, 0x00473710, 0x00513c11, 0x00634811, 0x00856114, 0x00b8952a, 0x00cab024, 0x00cbb910, 0x00cabb0c, 0x00c8ba07, 0x00c8b408, 0x00c4a811, 0x00967100, 0x00795003, 0x00664104, 0x00513603, 0x00423004, 0x003d2c05, 0x00372703, 0x00302001, 0x002c1c03, 0x002a1c05, 0x002a1c05, 0x00271a05, 0x00241704, 0x00241605, 0x00211506, 0x001f1305, 0x001e1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001e1407, 0x001e1308, 0x001d1308, 0x001f1409, 0x0020150a, 0x0021140c, 0x0020120a, 0x0021140c, 0x0021140c, 0x00201409, 0x00201409, 0x00201208, 0x00201208, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001f1408, 0x00201408, 0x00201409, 0x001f1409, 0x00191407, 0x00161305, 0x00141005, 0x00181308, 0x001b1308, 0x001c1208, 0x001f1208, 0x00201409, 0x00201408, 0x00221608, 0x00221509, 0x00221509, 0x00201408, 0x00201408, 0x00211308, 0x00211308, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00201508, 0x00211408, 0x00201307, 0x00201508, 0x001f1608, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001e1205, 0x00201408, 0x00201408, 0x001f1206, 0x001e1205, 0x001e1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x001e1205, 0x00201307, 0x00201307, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201307, 0x001e1407, 0x001c1205, 0x001c1105, 0x00201508, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1206, 0x001d1207, 0x001d1308, 0x001e1308, 0x001c1408, 0x001c1405, 0x001c1405, 0x001c1405, 0x001c1405, 0x001f1408, 0x001d1305, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x00201609, 0x00201508, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001e1205, 0x001f1206, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x00211408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00231409, 0x00211406, 0x00221407, 0x00221407, 0x00221407, 0x0023160a, 0x00231609, 0x0023160a, 0x0024170a, 0x0028180d, 0x00281608, 0x002b1808, 0x00301b0a, 0x00331d08, 0x0038220c, 0x00432810, 0x004c2e0e, 0x005c370a, 0x0070440c, 0x00845410, 0x00a26f1a, 0x00b17e18, 0x00bf8f1a, 0x00c89e23, 0x00caa11e, 0x00cba81f, 0x00ccac1f, 0x00ccaf1b, 0x00ccb015, 0x00cbb011, 0x00cab20d, 0x00cab50c, 0x00cab80a, 0x00cbba0a, 0x00ccb808, 0x00ccb709, 0x00ccb508, 0x00cbb409, 0x00cbb40a, 0x00cbb40a, 0x00ccb109, 0x00ccae0b, 0x00cca913, 0x00c09312, 0x00956100, 0x007e4d03, 0x00643804, 0x004c2b03, 0x00442502, 0x003b2204, 0x00382006, 0x00371d07, 0x00341a06, 0x00311908, 0x002f1a0b, 0x002c190a, 0x002c1a0a, 0x002c1908, 0x002c1808, 0x002d1a07, 0x002f1c08, 0x00301d06, 0x00331f08, 0x00352209, 0x00372407, 0x00382807, 0x003b2b06, 0x003c2c04, 0x0046360b, 0x00553b0b, 0x00714c0d, 0x008b600e, 0x00b28e19, 0x00ccb024, 0x00ccb715, 0x00cbbc0c, 0x00c8bc0b, 0x00cabc07, 0x00ccb908, 0x00c6b010, 0x009f7d04, 0x007b5200, 0x00644205, 0x00533b06, 0x00463206, 0x00402c09, 0x00392506, 0x00352206, 0x002d1d05, 0x001e1504, 0x00191304, 0x001a1709, 0x0018140a, 0x00131008, 0x00131008, 0x00111108, 0x000f1108, 0x000e1208, 0x000d1007, 0x000d120b, 0x000b130c, 0x000b140e, 0x000c1310, 0x000b1411, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001b211b, 0x001c221c, 0x001c211c, 0x001c211b, 0x001d221b, 0x0013170f, 0x000d1008, 0x000e1008, 0x00101109, 0x0013130c, 0x0016140c, 0x00151307, 0x00181408, 0x0020180c, 0x00291e0c, 0x00302209, 0x00392809, 0x003f2c09, 0x0046370d, 0x00523c11, 0x00684a10, 0x008a6610, 0x00c2a22c, 0x00ccb41d, 0x00ccba0d, 0x00c8bb0b, 0x00cbbc02, 0x00ccb80b, 0x00b8980c, 0x008c6500, 0x00754f04, 0x005f3f01, 0x004b3301, 0x00412f07, 0x003c2c09, 0x00352507, 0x002e1e04, 0x002a1c05, 0x00281a07, 0x00271a08, 0x00261808, 0x00231507, 0x00201408, 0x001e1407, 0x001c1406, 0x001c1305, 0x001d1207, 0x001c1307, 0x001c1408, 0x001c1408, 0x001c1409, 0x001c140a, 0x001c140a, 0x001c140a, 0x001d1409, 0x001e1409, 0x00201409, 0x00201409, 0x00201409, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1205, 0x001e1407, 0x00201508, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x001f1307, 0x001d1408, 0x001c1408, 0x001b1408, 0x00161003, 0x00141003, 0x00191208, 0x00191208, 0x001c1307, 0x001d1409, 0x001e1508, 0x00201607, 0x00231509, 0x00241409, 0x00201207, 0x00201207, 0x00211308, 0x00241409, 0x00241509, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00221509, 0x00201609, 0x00211408, 0x00211408, 0x001f1408, 0x001e1508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001f1408, 0x001f1408, 0x001d1205, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201406, 0x001f1204, 0x001e1204, 0x001e1204, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1205, 0x001e1205, 0x00201407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1608, 0x001d1408, 0x001c1407, 0x001c1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201207, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x00201709, 0x001d1207, 0x001b1005, 0x0020150a, 0x001f1409, 0x001d1207, 0x001d1207, 0x001e1308, 0x001e1308, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1306, 0x001b1204, 0x001b1205, 0x001c1407, 0x001c1407, 0x001c1405, 0x001c1405, 0x001c1405, 0x001c1405, 0x001e1407, 0x001e1407, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x00201609, 0x00201609, 0x001f1408, 0x00201408, 0x00241409, 0x00241409, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00211409, 0x00221509, 0x00221509, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x0021140a, 0x0024160a, 0x00271608, 0x00291808, 0x002c1a08, 0x00311b08, 0x00351e07, 0x0039210b, 0x00442811, 0x004a2c10, 0x005c360f, 0x0075480e, 0x00a17024, 0x00c89b32, 0x00cba624, 0x00cbad18, 0x00cbaf14, 0x00ccb110, 0x00ccb30e, 0x00cab40c, 0x00cab70d, 0x00c8b80b, 0x00c8b80a, 0x00c8b60a, 0x00c9b60a, 0x00c8b809, 0x00c8ba07, 0x00ccb808, 0x00ccb408, 0x00ccb108, 0x00ccb20a, 0x00cbaf09, 0x00caa90c, 0x00c8a311, 0x00c0940e, 0x00b6850b, 0x00a36c02, 0x008a5300, 0x00774604, 0x005e3501, 0x00482800, 0x00402401, 0x003a2104, 0x00361f06, 0x00361c08, 0x00331907, 0x002e1808, 0x002d1809, 0x002a1808, 0x00291808, 0x00281808, 0x00281808, 0x002b1908, 0x002c1a08, 0x002c1b07, 0x002d1c08, 0x002f1e09, 0x0034230a, 0x00342506, 0x00372805, 0x00392c03, 0x00423108, 0x00503808, 0x0068480c, 0x007d580a, 0x009c7610, 0x00c4a524, 0x00ccb519, 0x00cbba0f, 0x00c8bc06, 0x00c8bb03, 0x00c9b805, 0x00c9b40d, 0x00ae8d0a, 0x00805800, 0x006a4303, 0x00573904, 0x00483307, 0x00402c09, 0x003a2606, 0x00352304, 0x002e1e05, 0x00241908, 0x001a1102, 0x00191306, 0x0019150a, 0x0017130b, 0x00141109, 0x00121108, 0x00101108, 0x00101106, 0x000f1007, 0x000e1208, 0x000d1208, 0x000d120c, 0x000d130f, 0x000b1412, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001c221c, 0x001c221c, 0x001c211c, 0x001c201a, 0x00191e17, 0x0010140c, 0x000d1008, 0x00100f08, 0x00101109, 0x0014150c, 0x00141309, 0x00141306, 0x00191508, 0x00231b0c, 0x002c1f0c, 0x00332409, 0x003a2909, 0x003f2c09, 0x0048360c, 0x00574010, 0x006d4e0e, 0x00957217, 0x00c7a72c, 0x00ccb51e, 0x00cbba0d, 0x00c8bb0c, 0x00cbbb04, 0x00cab30b, 0x00ae8c08, 0x00825c00, 0x006e4a04, 0x00573a00, 0x00463000, 0x003d2c06, 0x00382807, 0x00322304, 0x002c1c03, 0x00281903, 0x00251606, 0x00241808, 0x00251809, 0x00231508, 0x00201409, 0x001c1408, 0x001c1408, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1508, 0x001c1408, 0x001c1408, 0x001c1308, 0x001c1307, 0x001c1408, 0x001e1508, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1305, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x001f1307, 0x001d1408, 0x001c1408, 0x001c1408, 0x00181004, 0x00140e01, 0x00181007, 0x00191208, 0x001c1307, 0x001c1408, 0x001e1508, 0x001f1507, 0x00231509, 0x00241409, 0x00201207, 0x00201207, 0x00211308, 0x00241409, 0x00241509, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00221509, 0x00201609, 0x00211408, 0x00211408, 0x001f1408, 0x001e1508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001f1408, 0x001f1408, 0x001d1205, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201406, 0x001f1204, 0x001e1204, 0x001e1204, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1205, 0x001e1205, 0x00201407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x00201508, 0x001f1608, 0x001d1408, 0x001c1407, 0x001c1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201207, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x00201709, 0x001d1207, 0x001b1005, 0x0020150a, 0x001f1409, 0x001d1207, 0x001d1207, 0x001e1308, 0x001e1308, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1307, 0x001b1206, 0x001b1207, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001e1407, 0x001e1407, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00211308, 0x00211308, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211409, 0x00221509, 0x00211408, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x0021140a, 0x0024170a, 0x00261708, 0x00291808, 0x002c1a08, 0x00311b08, 0x00351e07, 0x0039210b, 0x00442811, 0x004a2c0f, 0x005f380e, 0x00784b0f, 0x00ad8027, 0x00cca82d, 0x00cbaf18, 0x00ccb20d, 0x00ccb30a, 0x00ccb407, 0x00cbb408, 0x00c8b60b, 0x00c8b90d, 0x00c8ba10, 0x00caba0e, 0x00cbb809, 0x00cbb609, 0x00c8b408, 0x00c9b409, 0x00ccb10e, 0x00ccad0f, 0x00c8a60d, 0x00c09d09, 0x00ba9008, 0x00b27f04, 0x00a46f01, 0x009b6300, 0x00935a00, 0x008c5204, 0x00824807, 0x00704008, 0x00583102, 0x00482803, 0x00402303, 0x00382004, 0x00341e07, 0x00341c08, 0x00321a07, 0x002d1808, 0x002b170a, 0x00281809, 0x0028180b, 0x0028180b, 0x00281809, 0x00291909, 0x002c1a09, 0x002c1a08, 0x002c1a08, 0x002b1c08, 0x002e1f0a, 0x00322408, 0x00332605, 0x00372904, 0x003e2d07, 0x004b3408, 0x0060440c, 0x0075510a, 0x008f660b, 0x00b8941e, 0x00ccb41d, 0x00cbb911, 0x00c9bc0c, 0x00cabc06, 0x00ccb909, 0x00cab40c, 0x00b8980e, 0x00885f00, 0x006c4500, 0x00593c04, 0x00493405, 0x00412e09, 0x003b2707, 0x00362404, 0x002e1e04, 0x00241906, 0x001a1201, 0x001a1406, 0x001b180c, 0x0018140c, 0x00141109, 0x00131008, 0x00101108, 0x00101106, 0x000f1005, 0x000e1208, 0x000d1208, 0x000e130b, 0x000d130e, 0x000b1412, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001c221c, 0x001c221c, 0x001b211b, 0x001b2018, 0x00161b14, 0x000f120a, 0x000f0f08, 0x00100f08, 0x00111008, 0x0014150c, 0x00121108, 0x00141205, 0x00191608, 0x00231b0c, 0x002c1f0b, 0x00342408, 0x003c2809, 0x00442e0d, 0x004a340c, 0x005b400e, 0x0070500a, 0x00a07c1a, 0x00caac2c, 0x00ccb61c, 0x00ccbb0d, 0x00caba0d, 0x00ccb90a, 0x00c8ad0d, 0x00a17d01, 0x007d5704, 0x00674408, 0x00523704, 0x00412f01, 0x003c2c07, 0x00392808, 0x00332306, 0x002c1d04, 0x00251804, 0x00221608, 0x00211708, 0x00201409, 0x001f1409, 0x001c140a, 0x001c140a, 0x001c1409, 0x001a1408, 0x001b1407, 0x001b1407, 0x001a1407, 0x00181408, 0x001a1406, 0x001b1406, 0x001a1405, 0x00191304, 0x001a1304, 0x001c1305, 0x001e1206, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1308, 0x001c1106, 0x001c1206, 0x001c1106, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x00201508, 0x001e1407, 0x001e1407, 0x001f1407, 0x001f1307, 0x001d1408, 0x001c1408, 0x001c1408, 0x001b1206, 0x00160d01, 0x00181006, 0x001c1208, 0x001c1307, 0x001c1307, 0x001c1406, 0x001e1506, 0x00211408, 0x00221408, 0x00221408, 0x00211308, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00231409, 0x00211308, 0x00211308, 0x00211408, 0x00201508, 0x00211408, 0x00211408, 0x001f1408, 0x00201709, 0x00201508, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201406, 0x00201305, 0x00201305, 0x00201305, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x001f1206, 0x001f1206, 0x00201307, 0x00201407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201508, 0x001d1408, 0x001c1407, 0x001c1407, 0x001c1407, 0x001e1205, 0x001e1205, 0x001e1205, 0x001e1205, 0x001f1105, 0x001f1205, 0x001f1306, 0x001f1307, 0x001f1407, 0x00201307, 0x00201307, 0x001e1407, 0x001c1407, 0x001c1005, 0x001c1207, 0x001f1409, 0x001e1308, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001a1306, 0x00191306, 0x001a1407, 0x001b1407, 0x001a1307, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191306, 0x00191306, 0x001c1408, 0x001c1408, 0x001d1407, 0x001e1407, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001e1407, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001f1408, 0x0020150a, 0x0023170a, 0x0027180b, 0x00281808, 0x002e1908, 0x00321a08, 0x00371d07, 0x003a210b, 0x0042280e, 0x004c2d0a, 0x0060380a, 0x007c4f10, 0x00b08728, 0x00ccab27, 0x00ccb412, 0x00ccb508, 0x00ccb506, 0x00ccb605, 0x00cbb607, 0x00c9b50c, 0x00c8b60f, 0x00c9b510, 0x00cbb410, 0x00ccb10e, 0x00ccac0d, 0x00c9a710, 0x00c59e0e, 0x00be910c, 0x00b48406, 0x00a67501, 0x00a37000, 0x00a06700, 0x00a06100, 0x009f6100, 0x00a06504, 0x009e640b, 0x00885202, 0x00794402, 0x006c3e08, 0x00522d00, 0x00472804, 0x003e2204, 0x00382007, 0x00331d08, 0x00321c08, 0x002f1a08, 0x002b1909, 0x00271609, 0x0024180b, 0x0024180c, 0x0024180b, 0x0024180a, 0x00241708, 0x00261806, 0x00281908, 0x00291b0a, 0x002a1b0c, 0x002d1e0c, 0x0030220b, 0x00302408, 0x00342605, 0x003e2c08, 0x00463009, 0x00543b08, 0x006a4c0c, 0x00835809, 0x00a88218, 0x00cab023, 0x00cab715, 0x00c9bb10, 0x00cbbc0c, 0x00ccb80a, 0x00cab50c, 0x00bc9c0c, 0x008e6600, 0x006c4700, 0x005b3e02, 0x00493505, 0x00422f0a, 0x003c2506, 0x00362404, 0x002e2004, 0x00261a06, 0x001c1402, 0x00171102, 0x00191609, 0x0019150c, 0x00140f08, 0x00131008, 0x00111108, 0x00101106, 0x000f1005, 0x000e1208, 0x000d1208, 0x000e130b, 0x000d130e, 0x000c1312, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001c221c, 0x001c221c, 0x001b211b, 0x001c2019, 0x00161b14, 0x000f120a, 0x00100f08, 0x00110f08, 0x00121108, 0x0014140b, 0x00101005, 0x00141205, 0x001c1709, 0x00251c0c, 0x002e200c, 0x0036250a, 0x003e2a0c, 0x00493111, 0x00503710, 0x0060430f, 0x00755408, 0x00a8881e, 0x00ccb12c, 0x00ccb719, 0x00ccbb0d, 0x00c9b90c, 0x00ccb80b, 0x00c2a70d, 0x00946f00, 0x00744e04, 0x005d3d05, 0x004c3403, 0x00402e03, 0x003c2c08, 0x00392808, 0x00322305, 0x002a1b03, 0x00221601, 0x001e1405, 0x001d1407, 0x001c1409, 0x001c140b, 0x001c130c, 0x001c140c, 0x001b140c, 0x0019140a, 0x001b1407, 0x001b1407, 0x00191407, 0x00181407, 0x00181405, 0x00181404, 0x00181404, 0x00181404, 0x001a1404, 0x001c1404, 0x001e1304, 0x00201305, 0x001f1405, 0x00201507, 0x001f1406, 0x001e1405, 0x001e1406, 0x001c1107, 0x001e130a, 0x001f140b, 0x001d1208, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x00201508, 0x001e1407, 0x001e1407, 0x001e1306, 0x001f1307, 0x001e1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x00181004, 0x00191006, 0x001b1108, 0x001c1307, 0x001c1307, 0x001c1305, 0x001c1404, 0x00211408, 0x00221408, 0x00221408, 0x00211308, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00231409, 0x00211308, 0x00211308, 0x00211408, 0x00201508, 0x00211408, 0x00211408, 0x001f1408, 0x00201709, 0x00201508, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201406, 0x00201406, 0x00201305, 0x00201305, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x001f1206, 0x001f1206, 0x00201307, 0x00201407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001e1205, 0x001e1205, 0x001e1205, 0x001e1205, 0x001f1105, 0x001f1205, 0x001f1306, 0x001f1307, 0x001f1407, 0x00201307, 0x00201307, 0x001e1407, 0x001d1407, 0x001c1005, 0x001c1207, 0x001f1409, 0x001d1408, 0x001c1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001a1306, 0x00191306, 0x001a1407, 0x001b1407, 0x001a1307, 0x00191208, 0x00191208, 0x00191208, 0x00191308, 0x00191306, 0x00191306, 0x001b1508, 0x001c1408, 0x001d1407, 0x001e1407, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001e1407, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001f1408, 0x0020150a, 0x0023170a, 0x0027180a, 0x00291808, 0x002e1908, 0x00331a08, 0x00371d07, 0x003a2209, 0x00442a0c, 0x004c2f08, 0x00603807, 0x00805310, 0x00b88e2f, 0x00caab28, 0x00cbb414, 0x00ccb506, 0x00ccb506, 0x00ccb408, 0x00ccb308, 0x00cab00c, 0x00caaf10, 0x00c9a910, 0x00c6a00b, 0x00c09406, 0x00b88802, 0x00b07902, 0x00ab7101, 0x00a66800, 0x00a46600, 0x00a36400, 0x00a96c04, 0x00ac6e04, 0x00b6790d, 0x00bd8614, 0x00c4901a, 0x00c4941e, 0x009c6c05, 0x00804e00, 0x006c4004, 0x00502c00, 0x00442606, 0x003c2006, 0x00382008, 0x00331e09, 0x00301b08, 0x002c1a08, 0x00291909, 0x00241608, 0x0023160a, 0x0023160c, 0x0022170c, 0x0022170c, 0x00221608, 0x00221606, 0x00231607, 0x00261808, 0x0028190b, 0x002c1b0e, 0x002f200d, 0x00302009, 0x00332405, 0x003a2806, 0x0045300a, 0x004f380a, 0x00634910, 0x007d530e, 0x00987211, 0x00c5a825, 0x00c9b617, 0x00c9bb13, 0x00cbbb0f, 0x00cbb90d, 0x00ccb60c, 0x00c4a610, 0x00946d00, 0x006f4800, 0x005c3f01, 0x00483604, 0x00432f09, 0x003c2607, 0x00382505, 0x00302206, 0x00261b06, 0x001f1604, 0x00161001, 0x00171407, 0x001c180f, 0x0016110a, 0x00131008, 0x00111208, 0x00101106, 0x000f1005, 0x000e1208, 0x000e1208, 0x000e120c, 0x000d130e, 0x000c1311, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a221e, 0x001a221e, 0x001c211d, 0x001a211a, 0x00141810, 0x000e1108, 0x00101006, 0x00111006, 0x00131209, 0x00131409, 0x00101105, 0x00151307, 0x0021180c, 0x002a1b0d, 0x002f200c, 0x0036240a, 0x003e2a0b, 0x004a3210, 0x00543810, 0x00654512, 0x007c5a0d, 0x00b29224, 0x00ccb327, 0x00ccb716, 0x00cbb90d, 0x00c8b809, 0x00cab70c, 0x00b8990b, 0x00896100, 0x006d4802, 0x00583c04, 0x00483404, 0x003e2d04, 0x003c2a08, 0x00382608, 0x00312106, 0x00291c04, 0x00221703, 0x001c1405, 0x001c1407, 0x001b1309, 0x001b130c, 0x00191208, 0x00191208, 0x001a1108, 0x001b1007, 0x001b1206, 0x00191306, 0x00181306, 0x00181306, 0x00171406, 0x00171406, 0x00191608, 0x00181408, 0x001a1406, 0x001c1407, 0x001c1407, 0x001d1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001d1205, 0x001d1205, 0x00201307, 0x00201307, 0x001f1206, 0x00201408, 0x001d1205, 0x001e1306, 0x001f1408, 0x001f1408, 0x001e1508, 0x001d1409, 0x001c1408, 0x00191004, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1305, 0x001d1406, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00201307, 0x00201408, 0x001f1408, 0x00201609, 0x001f1408, 0x00201508, 0x00201508, 0x00201406, 0x00201406, 0x00201305, 0x00201305, 0x001e1407, 0x001e1407, 0x001d1205, 0x001f1408, 0x00211609, 0x001f1408, 0x001c1104, 0x001d1205, 0x001d1205, 0x001e1205, 0x001e1205, 0x001f1206, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201307, 0x00201408, 0x00201408, 0x001f1408, 0x001f1508, 0x001d1407, 0x001d1407, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1305, 0x00201508, 0x001c1104, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1107, 0x001e1107, 0x001e1107, 0x001e1107, 0x001e1206, 0x001e1205, 0x001f1306, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001e1205, 0x00201508, 0x001b1106, 0x001a1105, 0x001c1509, 0x001c1609, 0x001d1509, 0x001c1408, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1106, 0x001c1106, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1207, 0x001e1308, 0x001d1207, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1407, 0x001e1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00211408, 0x00211408, 0x00211408, 0x00221408, 0x00221408, 0x00211308, 0x00211308, 0x001f1408, 0x001f1408, 0x0020140a, 0x0023170a, 0x00261809, 0x002a1808, 0x002e1908, 0x00331a08, 0x00371d07, 0x003a2208, 0x00432a0b, 0x004d2e08, 0x00603908, 0x007c4f0a, 0x00bb912f, 0x00c9a827, 0x00ccb017, 0x00ccaf0b, 0x00ccab0b, 0x00caa50b, 0x00c59f09, 0x00be940c, 0x00b88a08, 0x00b07e02, 0x00ab7400, 0x00ad6b00, 0x00ab6800, 0x00a76700, 0x00aa6b04, 0x00ad710b, 0x00b37a10, 0x00bc8618, 0x00c59320, 0x00c89a20, 0x00cca520, 0x00ccab1c, 0x00ccac1c, 0x00c9a620, 0x00a47405, 0x00835101, 0x006a4002, 0x004f2b00, 0x00442509, 0x003c2008, 0x00371e08, 0x00321c08, 0x002f1b08, 0x002c1a08, 0x00281809, 0x00241609, 0x0023160a, 0x0023160a, 0x00211609, 0x00201608, 0x00201507, 0x00201606, 0x00211606, 0x00241808, 0x00251808, 0x00281a09, 0x002c1e09, 0x002c1d07, 0x00302005, 0x00382706, 0x0042300b, 0x004b360c, 0x00584010, 0x006f4d0c, 0x008a6411, 0x00bb9c26, 0x00cab61c, 0x00cbbb10, 0x00ccba0e, 0x00ccba0e, 0x00ccb80e, 0x00caad14, 0x009c7501, 0x00744d00, 0x005c4002, 0x00473704, 0x00433008, 0x003e2808, 0x00382606, 0x00312306, 0x00291c08, 0x00201705, 0x00181003, 0x00141005, 0x001c1910, 0x00161208, 0x00131107, 0x00101206, 0x000f1007, 0x000d0f05, 0x00101008, 0x00101109, 0x0010110c, 0x000e120f, 0x000b1210, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a221e, 0x001a221e, 0x001c221f, 0x00171d18, 0x000f140b, 0x000d1007, 0x00101006, 0x00131107, 0x0016140b, 0x00121208, 0x00101004, 0x00161408, 0x0023180d, 0x002d1c0f, 0x0030200c, 0x0038270c, 0x00402c0b, 0x004c330f, 0x00543810, 0x00664612, 0x00836111, 0x00b89928, 0x00ccb324, 0x00ccb813, 0x00cbba0c, 0x00c9b80b, 0x00cbb510, 0x00ad8d06, 0x00835a00, 0x006a4401, 0x00543804, 0x00443002, 0x003d2c04, 0x00392606, 0x00352305, 0x00301f04, 0x002a1c05, 0x00221703, 0x001c1404, 0x001c1407, 0x001b130a, 0x001b120c, 0x00181308, 0x00181308, 0x00191108, 0x001a1007, 0x001b1206, 0x00191306, 0x00181306, 0x00181306, 0x00171406, 0x00171406, 0x00191608, 0x00181408, 0x001a1406, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001d1205, 0x001d1205, 0x00201307, 0x00201307, 0x001f1206, 0x00201408, 0x001d1104, 0x001e1306, 0x00201508, 0x001f1408, 0x001f1608, 0x001f150a, 0x001e1409, 0x00180f04, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1306, 0x001f1507, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00201307, 0x00201408, 0x001f1408, 0x00201609, 0x001f1408, 0x00201508, 0x00201508, 0x00201406, 0x00201406, 0x00201305, 0x00201305, 0x001e1407, 0x001e1407, 0x001d1305, 0x001f1408, 0x0021170a, 0x001f1408, 0x001c1104, 0x001d1205, 0x001d1205, 0x001e1205, 0x001e1205, 0x00201408, 0x00221509, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201307, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1407, 0x001c1407, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1306, 0x00201508, 0x001c1104, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1206, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x00201508, 0x001a1106, 0x001b1105, 0x001c1509, 0x001b1609, 0x001c1509, 0x001c1408, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1106, 0x001c1106, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1207, 0x001c1106, 0x001d1208, 0x001d1408, 0x001c1407, 0x001e1508, 0x00201709, 0x00201608, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x001f1206, 0x001f1206, 0x001f1206, 0x001f1306, 0x00201307, 0x00201408, 0x00201308, 0x00211308, 0x00211308, 0x00211308, 0x00211308, 0x00201408, 0x00201408, 0x0021140a, 0x0024170a, 0x00261809, 0x002b1909, 0x002e1908, 0x00331a08, 0x00371e06, 0x003b2308, 0x00442b0d, 0x004e300b, 0x00603908, 0x00784a08, 0x00b5882d, 0x00c19824, 0x00c09816, 0x00bd8a0f, 0x00b58008, 0x00af7803, 0x00a77000, 0x00a26800, 0x00a36900, 0x00a46800, 0x00a56a01, 0x00a76c03, 0x00ab7408, 0x00b88416, 0x00c08f20, 0x00c59820, 0x00c9a221, 0x00cca820, 0x00ccac1c, 0x00cbad19, 0x00cab215, 0x00c8b313, 0x00c8b014, 0x00c8a61b, 0x009f7002, 0x00845104, 0x006b3f04, 0x004e2a00, 0x00442409, 0x003c2008, 0x00371e08, 0x00331c08, 0x002f1b08, 0x002b1908, 0x00281809, 0x00221509, 0x00221509, 0x00221509, 0x00201508, 0x001f1508, 0x001e1507, 0x001d1406, 0x001f1407, 0x00221809, 0x00241809, 0x00261a08, 0x00281c07, 0x00291c05, 0x002c1f03, 0x00352605, 0x003f2f09, 0x0048340b, 0x00533d0e, 0x006a4c0e, 0x007e5b0e, 0x00ae8d1e, 0x00c9b41c, 0x00cbb90d, 0x00cbba0c, 0x00cbb90d, 0x00ccb910, 0x00ccb217, 0x00a17c02, 0x007a5200, 0x005f4204, 0x004b3a05, 0x0047340b, 0x00422c0c, 0x003a2808, 0x00332407, 0x002b1d08, 0x00231807, 0x00181003, 0x00141005, 0x0018170d, 0x0018140b, 0x00121006, 0x000f1005, 0x00101108, 0x000f1007, 0x00101109, 0x0010120a, 0x0010110c, 0x000e120d, 0x000b120e, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a221e, 0x001a221e, 0x001d231f, 0x00151a14, 0x000f120a, 0x000f1007, 0x00121107, 0x0017140a, 0x00151308, 0x00101006, 0x00101104, 0x0019160a, 0x00251a0f, 0x002c1c0e, 0x0033210d, 0x0039260a, 0x00422e0b, 0x004b340c, 0x00543a0f, 0x00684710, 0x00896814, 0x00bfa12c, 0x00ccb31f, 0x00ccb810, 0x00cbba09, 0x00cab60c, 0x00cab116, 0x00a68205, 0x007e5500, 0x00654000, 0x00523504, 0x00443004, 0x003b2804, 0x00372204, 0x00321f02, 0x002f1d04, 0x002a1c06, 0x00221804, 0x001c1402, 0x001a1405, 0x00191208, 0x0019110b, 0x00171208, 0x00181207, 0x00181107, 0x00181006, 0x001b1206, 0x00191306, 0x00181306, 0x00181306, 0x00171406, 0x00171406, 0x00181408, 0x00181508, 0x00191306, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001d1205, 0x001e1306, 0x00201508, 0x001f1408, 0x001f1408, 0x001f1409, 0x001f1409, 0x001b1005, 0x001c1005, 0x001c1307, 0x001c1307, 0x001c1306, 0x001f1607, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00201307, 0x00201408, 0x001f1408, 0x00201508, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201406, 0x00201406, 0x00201406, 0x00201406, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x00201609, 0x001f1408, 0x001d1306, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201408, 0x00211409, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1306, 0x00201408, 0x00201408, 0x00201508, 0x001f1608, 0x001c1407, 0x001c1407, 0x001d1306, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001f1409, 0x001f1409, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1206, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001b1206, 0x001b1206, 0x001c1408, 0x001a1508, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1005, 0x001e1308, 0x001f1508, 0x001c1406, 0x001c1306, 0x001c1407, 0x001d1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00211308, 0x00211308, 0x00211308, 0x00211308, 0x00201408, 0x00201408, 0x0021140a, 0x0024160a, 0x00281709, 0x002b1909, 0x002f1a09, 0x00341b0a, 0x00381e06, 0x003c2409, 0x00462c10, 0x0053320e, 0x005f380c, 0x00703e08, 0x0088540b, 0x00925f02, 0x00945d00, 0x009c5a00, 0x009c5c00, 0x009b5c00, 0x009c6002, 0x00a56c03, 0x00aa7309, 0x00b37c11, 0x00be8c1c, 0x00c2951c, 0x00c8a020, 0x00caa720, 0x00ccac21, 0x00ccb01b, 0x00ccb116, 0x00cbb413, 0x00cbb60f, 0x00c9b70c, 0x00c8b808, 0x00c5b609, 0x00cab414, 0x00c4a014, 0x009e6e04, 0x00835006, 0x00663a03, 0x004d2802, 0x00422509, 0x003b2008, 0x00361d08, 0x00311b08, 0x002f1c0a, 0x00291808, 0x00271709, 0x00221509, 0x00211408, 0x001e1205, 0x001d1205, 0x001d1508, 0x001c1407, 0x001c1408, 0x001c1408, 0x001e1409, 0x00201609, 0x00231808, 0x00251b07, 0x00281d05, 0x002a1f04, 0x00322404, 0x003a2c05, 0x00433108, 0x004e3b0c, 0x0060440c, 0x0075520c, 0x00a07e16, 0x00c9af1f, 0x00ccba10, 0x00ccbb0c, 0x00cbb90d, 0x00ccba0e, 0x00ccb214, 0x00ac880b, 0x007c5400, 0x00604001, 0x004f3b05, 0x00463309, 0x00432b0b, 0x003c280a, 0x00322305, 0x002c1c08, 0x00241805, 0x00191104, 0x00130e04, 0x0017140b, 0x001a150c, 0x00141006, 0x000f1007, 0x000f1007, 0x000f1007, 0x00101009, 0x00101009, 0x000e1008, 0x0010140d, 0x000b120c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231c, 0x001a231c, 0x001d241e, 0x00151a13, 0x000f120a, 0x000f1007, 0x00111006, 0x00141108, 0x00141109, 0x00101007, 0x00111206, 0x001c190e, 0x00281c11, 0x002e1d0f, 0x0033220d, 0x003b280c, 0x00422f0c, 0x004b360d, 0x00573c0f, 0x006c4b10, 0x008c6c16, 0x00c5a830, 0x00cab41d, 0x00ccb90e, 0x00cbbb06, 0x00cbb60c, 0x00c7ac16, 0x009c7702, 0x00785000, 0x00623d02, 0x00503404, 0x00442f07, 0x003a2807, 0x00372205, 0x00331e03, 0x002d1d04, 0x00291d08, 0x00221805, 0x001c1404, 0x00191306, 0x00191208, 0x0019110b, 0x00171208, 0x00171307, 0x00181207, 0x00171106, 0x001b1206, 0x00191306, 0x00181306, 0x00181306, 0x00181406, 0x00171406, 0x00181408, 0x00181508, 0x00191306, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001d1205, 0x001e1306, 0x00201508, 0x001f1408, 0x001f1408, 0x001f1409, 0x001f1409, 0x001e1308, 0x001b1005, 0x001c1307, 0x001c1307, 0x001c1306, 0x001f1507, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00201307, 0x00201408, 0x001f1408, 0x00201508, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201406, 0x00201406, 0x00201406, 0x00201406, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x00201609, 0x001f1408, 0x001d1306, 0x001e1407, 0x001f1407, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1306, 0x00201307, 0x00201307, 0x001f1408, 0x001c1407, 0x001c1407, 0x001c1407, 0x001d1306, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1306, 0x001c1305, 0x001c1406, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001b1206, 0x001b1206, 0x001c1408, 0x001a1508, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001e1308, 0x001d1207, 0x001c1205, 0x001c1407, 0x001d1408, 0x001c1407, 0x001d1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201207, 0x00201207, 0x00211308, 0x00211308, 0x00201408, 0x00201408, 0x0021140a, 0x0024160a, 0x00281709, 0x002b1909, 0x00301b0a, 0x00341c0b, 0x00391f09, 0x003e260c, 0x00492f10, 0x00563612, 0x00643d0d, 0x00754408, 0x00865004, 0x00905800, 0x00985f01, 0x00a36608, 0x00aa710e, 0x00b17c14, 0x00ba891a, 0x00bd9218, 0x00c49c1c, 0x00cca925, 0x00ccac24, 0x00ccac1a, 0x00ccaf14, 0x00ccb10f, 0x00ccb50c, 0x00ccb507, 0x00ccb507, 0x00cab709, 0x00c9b80b, 0x00c8b807, 0x00c8b804, 0x00c8b708, 0x00ccb014, 0x00be9710, 0x00986500, 0x00804c04, 0x00623700, 0x004a2501, 0x0042240b, 0x003a2008, 0x00341e08, 0x00301b08, 0x002f1c0b, 0x00281808, 0x00261609, 0x00221509, 0x00201508, 0x001d1306, 0x001c1307, 0x001c1408, 0x00191408, 0x00191407, 0x001b1408, 0x001b1308, 0x001c1408, 0x00201806, 0x00231905, 0x00261d05, 0x00281f02, 0x00312404, 0x00382b05, 0x003e2f04, 0x00493809, 0x005a420c, 0x0070500e, 0x00967311, 0x00c6a81f, 0x00ccb811, 0x00ccbb0c, 0x00cbb90d, 0x00ccb90f, 0x00ccb414, 0x00af8c0c, 0x00805800, 0x00644200, 0x00513c07, 0x00463309, 0x00422a0a, 0x003c280a, 0x00332305, 0x002f1e09, 0x00271a08, 0x001c1507, 0x00140f04, 0x00141206, 0x001b150c, 0x00141006, 0x000f1007, 0x000f1007, 0x000f1007, 0x00101009, 0x00101009, 0x000e1008, 0x0010140c, 0x000b130c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231c, 0x001c221c, 0x001d211c, 0x00141710, 0x0010120a, 0x00101007, 0x00121108, 0x00131008, 0x000e0c03, 0x00131007, 0x00181409, 0x00201a0e, 0x00281c0e, 0x002f1d0c, 0x0034220c, 0x003b280c, 0x0041300d, 0x0049370f, 0x00583c0e, 0x00704c10, 0x00957417, 0x00c9ad2c, 0x00ccb617, 0x00cab909, 0x00ccb905, 0x00ccb80d, 0x00c2a312, 0x00946d00, 0x00744d00, 0x005d3c00, 0x004c3404, 0x00422e07, 0x003a2804, 0x00342302, 0x002e1f04, 0x002b1d06, 0x00281c08, 0x00201706, 0x00191304, 0x00181305, 0x00181207, 0x00161008, 0x00181207, 0x00181207, 0x00181207, 0x00171106, 0x00171106, 0x00171106, 0x00181308, 0x00191208, 0x00181207, 0x00181207, 0x00181308, 0x00191408, 0x001a1408, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001c1407, 0x001c1407, 0x00181304, 0x001b1405, 0x001c1508, 0x001b1204, 0x001d1205, 0x001e1407, 0x001f1307, 0x00211408, 0x00211408, 0x00201307, 0x001f1307, 0x001e1407, 0x001d1306, 0x001e1407, 0x001e1408, 0x001f1409, 0x0020150a, 0x001c1408, 0x00170e02, 0x001c140a, 0x001c140a, 0x001c1408, 0x001d1508, 0x00201408, 0x00211308, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00211408, 0x00211408, 0x00201508, 0x0022170a, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001d1207, 0x001e1308, 0x001d1307, 0x001f1508, 0x001f1608, 0x001c1406, 0x001c1104, 0x001d1205, 0x001d1205, 0x001f1408, 0x00201609, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1409, 0x001d1207, 0x001c1106, 0x001d1207, 0x001f1408, 0x00201508, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001c1104, 0x001a1003, 0x001b1105, 0x001c1308, 0x001b1206, 0x001b1206, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001d1408, 0x001e1308, 0x001d1208, 0x001c1005, 0x001c1106, 0x001a1105, 0x001a1105, 0x001b1407, 0x00191407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201507, 0x00211508, 0x00231409, 0x0025170b, 0x0028180a, 0x002c1a0a, 0x00301b0a, 0x00341c0b, 0x003b1f09, 0x0042240e, 0x004b2c10, 0x005c3b11, 0x006c4610, 0x008c5c18, 0x00a4711c, 0x00b4821b, 0x00b98d19, 0x00c49c1d, 0x00cba31f, 0x00cba61b, 0x00ccab19, 0x00ccae16, 0x00ccb014, 0x00ccb112, 0x00cbb310, 0x00cab410, 0x00c9b40d, 0x00ccb40b, 0x00ccb408, 0x00c8b807, 0x00c8b708, 0x00c8b40a, 0x00cab50d, 0x00ccb80e, 0x00ccb508, 0x00cab00c, 0x00ccac1b, 0x00b88910, 0x00915c00, 0x007f4d05, 0x005d3400, 0x00492603, 0x003e2308, 0x00371d06, 0x00341c09, 0x002f1b0a, 0x002c1c09, 0x00251808, 0x00211708, 0x001f1608, 0x001e140b, 0x001c140a, 0x001b1309, 0x00191209, 0x00181207, 0x00181308, 0x00181308, 0x00191408, 0x00191408, 0x001c1608, 0x00211908, 0x00231907, 0x00291e07, 0x00302306, 0x00372a07, 0x003b2d05, 0x0047380c, 0x00553e0d, 0x006c4d10, 0x008a6711, 0x00c2a122, 0x00ccb717, 0x00cbb90d, 0x00cbba0c, 0x00ccb90f, 0x00ccb413, 0x00b7930f, 0x00875e00, 0x00684401, 0x00543c06, 0x00473309, 0x00422b0b, 0x003c2709, 0x00342304, 0x002f1f05, 0x00271a04, 0x001e1604, 0x00151101, 0x00101002, 0x0017160a, 0x00151309, 0x00110f07, 0x000f1007, 0x000f1007, 0x000e1008, 0x000d1008, 0x000e110c, 0x000d130d, 0x000b130c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231b, 0x001c221b, 0x00181d16, 0x0010140b, 0x0010120a, 0x00101007, 0x00121108, 0x00111008, 0x000d0c02, 0x00141006, 0x001c1509, 0x00231b0e, 0x00281c0b, 0x002f1e0a, 0x0034220a, 0x003b2a0c, 0x0041310c, 0x004b3810, 0x005b3e0e, 0x00745111, 0x00a17f1d, 0x00ccb029, 0x00cbb813, 0x00cab908, 0x00ccb905, 0x00ccb40c, 0x00ba9b0f, 0x00886200, 0x006e4900, 0x00563800, 0x00483202, 0x003c2c04, 0x00352402, 0x00322001, 0x002d1e04, 0x00291c08, 0x00271c0a, 0x00201708, 0x00191306, 0x00181305, 0x00181207, 0x00161007, 0x00151108, 0x00151108, 0x00151107, 0x00141007, 0x00141005, 0x00141005, 0x00151106, 0x00181308, 0x00181207, 0x00181207, 0x00181308, 0x00181308, 0x00191308, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001a1507, 0x001a1507, 0x00191405, 0x001a1507, 0x001c1407, 0x001e1508, 0x00201609, 0x001e1407, 0x001d1104, 0x001f1306, 0x00201408, 0x00201307, 0x001f1407, 0x001e1306, 0x001d1306, 0x001e1407, 0x001e1408, 0x001f1409, 0x0020150a, 0x001f150a, 0x00180f03, 0x001b1108, 0x001c1208, 0x001b1407, 0x001c1407, 0x00201408, 0x00211308, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00211308, 0x00211308, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00211408, 0x00211408, 0x00201508, 0x0022170a, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1207, 0x001c1307, 0x001f1608, 0x001f1608, 0x001c1406, 0x001c1204, 0x001d1205, 0x001d1205, 0x001e1407, 0x00201508, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001e1308, 0x001e1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001c1004, 0x001a1105, 0x001c1308, 0x001b1206, 0x001b1206, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001b1206, 0x001c1307, 0x001a1105, 0x001a1105, 0x001b1407, 0x00191407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001c1408, 0x001c1408, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1308, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201507, 0x00211507, 0x0024150a, 0x0026180b, 0x0028180a, 0x002c190a, 0x00311c0c, 0x00351c0c, 0x003b1f0b, 0x00442610, 0x00502d0f, 0x005c3a0c, 0x00704609, 0x00ad7e2d, 0x00cb9e34, 0x00cca529, 0x00cba820, 0x00ccae18, 0x00ccaf14, 0x00ccb00f, 0x00ccb10c, 0x00ccb209, 0x00ccb309, 0x00ccb408, 0x00ccb608, 0x00c9b808, 0x00cab808, 0x00cbb605, 0x00cab604, 0x00c9b804, 0x00c9b707, 0x00cab409, 0x00cab00a, 0x00cbae10, 0x00caa913, 0x00c59f12, 0x00b78a0e, 0x00a06d04, 0x008b5300, 0x007c4c08, 0x00583000, 0x004a2805, 0x003e2308, 0x00361d06, 0x00311c0a, 0x002d1a0b, 0x00281a08, 0x00231705, 0x00201608, 0x001c1509, 0x001c140c, 0x001c140c, 0x001b130b, 0x00181108, 0x00181008, 0x00181309, 0x0018130a, 0x0019140b, 0x0019140b, 0x001c150b, 0x0021180b, 0x00231809, 0x002a1d0a, 0x00312208, 0x00372a08, 0x00392c05, 0x00423409, 0x00523b0c, 0x00684b12, 0x00846113, 0x00bb9820, 0x00ccb419, 0x00cbb90f, 0x00cbba0c, 0x00ccba0d, 0x00ccb613, 0x00ba970f, 0x008c6000, 0x006b4400, 0x00553a05, 0x00483408, 0x00432b0a, 0x003c2809, 0x00352404, 0x00302007, 0x00281c04, 0x00201604, 0x00161102, 0x00100f01, 0x00141408, 0x0018160e, 0x00121008, 0x00101007, 0x00101108, 0x000d1008, 0x000c1108, 0x000d110c, 0x000d130e, 0x000c130c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231b, 0x001c221b, 0x00131810, 0x00101009, 0x0011110a, 0x00110f07, 0x00121008, 0x00100f06, 0x000e0b02, 0x00141004, 0x001c1608, 0x00231a0c, 0x00291c0a, 0x002f1e06, 0x00352408, 0x003b2b09, 0x0041320b, 0x004c390d, 0x005d3f0d, 0x00795411, 0x00a98822, 0x00caaf22, 0x00cab910, 0x00c8ba08, 0x00cab805, 0x00cbb00c, 0x00b18e0b, 0x00835c00, 0x00694700, 0x00543901, 0x00443003, 0x00382805, 0x00312102, 0x002f1f01, 0x002c1c05, 0x00281b08, 0x00251909, 0x00201709, 0x001b1407, 0x00161205, 0x00151106, 0x00171008, 0x00141008, 0x00121008, 0x00121008, 0x00121008, 0x00141006, 0x00121006, 0x00131006, 0x00151108, 0x00161307, 0x00161307, 0x00181308, 0x00181308, 0x00191308, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x00191306, 0x00191306, 0x00191405, 0x00191405, 0x00191405, 0x001a1507, 0x001c1508, 0x001e1508, 0x001f1408, 0x001f1408, 0x00211408, 0x00211408, 0x00211408, 0x001f1306, 0x001d1105, 0x001e1407, 0x001e1407, 0x00201609, 0x0023180c, 0x0021160c, 0x0020150a, 0x001f160a, 0x00191004, 0x00191006, 0x001a1208, 0x001c1408, 0x001c1407, 0x00201408, 0x00211308, 0x00221408, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00241409, 0x00221509, 0x00201408, 0x00201609, 0x00211609, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1207, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1305, 0x001c1306, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1307, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001b1406, 0x001b1405, 0x001c1406, 0x001c1407, 0x001c1407, 0x001c1307, 0x001c1307, 0x001a1105, 0x001c1408, 0x001b1206, 0x001b1206, 0x001b1407, 0x00191407, 0x001b1407, 0x001b1405, 0x001b1405, 0x001b1405, 0x001e1409, 0x001c1408, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1207, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001a1306, 0x001a1306, 0x001a1306, 0x001a1306, 0x001b1204, 0x001b1204, 0x001c1305, 0x001c1305, 0x001c1307, 0x001c1307, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00201609, 0x00221608, 0x0024150a, 0x0028180b, 0x002c1a0b, 0x002c1a08, 0x00311c0c, 0x0036200d, 0x003b220a, 0x0044270d, 0x00543110, 0x00603b0c, 0x00784d0c, 0x00b88b2b, 0x00cca828, 0x00ccae1b, 0x00cab214, 0x00ccb40c, 0x00ccb40b, 0x00cbb408, 0x00cbb406, 0x00cbb406, 0x00cbb406, 0x00cab405, 0x00cab406, 0x00c9b407, 0x00cab307, 0x00ccb308, 0x00ccb006, 0x00caad08, 0x00cbab0b, 0x00caa70f, 0x00c09807, 0x00b78907, 0x00ac7a04, 0x00a47000, 0x00986100, 0x008f5600, 0x00844e04, 0x0077480b, 0x00512b00, 0x00442402, 0x003c2107, 0x00361d08, 0x00321c0a, 0x002f1d0d, 0x002a1b0a, 0x00231707, 0x00201508, 0x001c1409, 0x001c140a, 0x001b130b, 0x00191209, 0x00191209, 0x0018120a, 0x0018120b, 0x0018120b, 0x0018130c, 0x0019130c, 0x001a140c, 0x001e1409, 0x0022170a, 0x00291c0b, 0x00302108, 0x00342808, 0x00382b06, 0x00403008, 0x0051390c, 0x00644810, 0x00825d13, 0x00b28e1d, 0x00ccb31c, 0x00cab810, 0x00ccbb0b, 0x00ccbb0b, 0x00ccb70e, 0x00bf9d11, 0x00906400, 0x006d4400, 0x00583b04, 0x00493407, 0x00432c08, 0x003e2807, 0x00372403, 0x00322007, 0x002a1c04, 0x00241a08, 0x00171102, 0x000f0e00, 0x00121207, 0x0018160e, 0x0013100a, 0x00101007, 0x00101108, 0x000d1008, 0x000c1108, 0x000c100a, 0x000d110d, 0x000c120c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231b, 0x001c221b, 0x0010140d, 0x00101009, 0x00101009, 0x00121008, 0x00121008, 0x000f0d03, 0x00100d02, 0x00171206, 0x001f1808, 0x00241b0a, 0x00291c08, 0x002f1e04, 0x00352406, 0x003c2c09, 0x0042330a, 0x004c390c, 0x005f410d, 0x007e5811, 0x00b49127, 0x00ccb31f, 0x00c9b80b, 0x00c6b906, 0x00cab808, 0x00cbb010, 0x00ac880a, 0x007f5600, 0x00674402, 0x00523a04, 0x00403004, 0x00362907, 0x002f2204, 0x002d1f04, 0x002c1b07, 0x00271908, 0x0024180a, 0x001f160a, 0x001a1307, 0x00151104, 0x00141005, 0x00151007, 0x0015130a, 0x00131008, 0x00121008, 0x00111008, 0x00121008, 0x00121008, 0x00121008, 0x00131008, 0x00151106, 0x00161307, 0x00181308, 0x00181308, 0x00191308, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x00191306, 0x00191306, 0x00191405, 0x00191405, 0x00191405, 0x00191406, 0x001c1407, 0x001c1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00211408, 0x001f1206, 0x001e1206, 0x001e1407, 0x001d1205, 0x001f1408, 0x00201609, 0x001f1409, 0x001e1308, 0x0020170c, 0x001c1308, 0x00191006, 0x001b1309, 0x001c1408, 0x001c1407, 0x00201408, 0x00211308, 0x00221408, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00241409, 0x00221509, 0x00201408, 0x00201609, 0x00211609, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1207, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1307, 0x001c1407, 0x001c1406, 0x001c1305, 0x001c1306, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1307, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191405, 0x00191405, 0x001a1406, 0x001a1507, 0x001c1407, 0x001b1407, 0x001b1307, 0x00181105, 0x001c1408, 0x001b1205, 0x001a1105, 0x001c1408, 0x00191407, 0x001b1407, 0x001b1405, 0x001b1405, 0x001b1405, 0x001c1408, 0x001c1307, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1408, 0x001c1308, 0x001c1307, 0x001a1306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00181306, 0x00181306, 0x00191306, 0x00191306, 0x00191304, 0x00191304, 0x001b1204, 0x001b1204, 0x001c1307, 0x001c1307, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201609, 0x00221608, 0x0025170b, 0x0028180b, 0x002c1a0a, 0x002c1a08, 0x00311c0c, 0x0037200e, 0x003d260c, 0x00472c0d, 0x00583411, 0x00694011, 0x00845915, 0x00bf952e, 0x00ccac20, 0x00cab310, 0x00c7b50c, 0x00c9b708, 0x00c9b707, 0x00c8b606, 0x00cab507, 0x00cab408, 0x00cab408, 0x00cab20a, 0x00ccb10d, 0x00ccb00f, 0x00ccaa0d, 0x00caa50c, 0x00c69c08, 0x00c09007, 0x00b48001, 0x00ad7500, 0x00a56900, 0x00a46401, 0x00a26101, 0x009f6001, 0x00985804, 0x008a4c01, 0x00824c0a, 0x006f400b, 0x004d2800, 0x00462605, 0x003c2008, 0x00361d08, 0x00301a08, 0x002d1b0b, 0x00281908, 0x00221606, 0x00201508, 0x001c140a, 0x001b1308, 0x00191209, 0x00181109, 0x0018100a, 0x00181009, 0x0018110a, 0x0018110b, 0x0018120c, 0x0019130e, 0x001a130c, 0x001c140a, 0x0022170c, 0x0027190a, 0x002f2009, 0x00332508, 0x00382a08, 0x00403009, 0x004f380b, 0x00614410, 0x007d5813, 0x00ac881d, 0x00cbb120, 0x00cab812, 0x00ccbb0c, 0x00ccbc09, 0x00ccb90e, 0x00c1a312, 0x00936801, 0x006f4400, 0x00583b02, 0x004b3507, 0x00442d06, 0x003f2906, 0x00382403, 0x00342008, 0x002c1c05, 0x00251a08, 0x00181103, 0x00111004, 0x000f1004, 0x0017140c, 0x0015130c, 0x000f0f05, 0x000d0f05, 0x000d1008, 0x000c1108, 0x000b100a, 0x000d110d, 0x000c120c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00192219, 0x001a2018, 0x000f120c, 0x00101009, 0x00111009, 0x00141109, 0x00141109, 0x00100e04, 0x00120f04, 0x00181406, 0x00201808, 0x00241c07, 0x00291e06, 0x002e1d04, 0x00342305, 0x003c2c06, 0x00423408, 0x004e3b0b, 0x00654710, 0x00805910, 0x00ba992b, 0x00ccb41c, 0x00cab90a, 0x00c8bb09, 0x00cab80a, 0x00cab112, 0x00a48008, 0x007a5101, 0x00623f04, 0x00503806, 0x00413006, 0x00362708, 0x002d2104, 0x002b1f05, 0x002b1a08, 0x0027190a, 0x0024180b, 0x001f150a, 0x00181308, 0x00141005, 0x00141107, 0x00131008, 0x0017140d, 0x0014110a, 0x00100d06, 0x000f0e06, 0x00121008, 0x00131008, 0x00131007, 0x00131108, 0x00141208, 0x00151208, 0x00171208, 0x00181207, 0x00191207, 0x001a1306, 0x001a1306, 0x001b1407, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1307, 0x001b1307, 0x001b1406, 0x001a1406, 0x001a1406, 0x001a1406, 0x001b1405, 0x001c1305, 0x001e1407, 0x001e1407, 0x001d1104, 0x00201408, 0x00201408, 0x00201408, 0x001f1407, 0x001f1408, 0x001e1407, 0x001d1205, 0x001e1408, 0x001d1206, 0x001d1206, 0x0020160a, 0x001d1308, 0x001a1005, 0x001a1308, 0x001b1408, 0x001c1407, 0x00201509, 0x00221408, 0x00221408, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00211408, 0x00221408, 0x00231509, 0x00231509, 0x00231509, 0x00221509, 0x001f1306, 0x00201408, 0x001f1408, 0x001f1407, 0x001c1104, 0x001c1104, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001c1307, 0x001c1307, 0x001c1206, 0x001b1106, 0x001c1206, 0x001b1407, 0x001c1407, 0x001c1306, 0x001c1307, 0x001d1407, 0x001d1407, 0x001d1306, 0x001d1306, 0x001e1407, 0x001d1305, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1306, 0x001d1306, 0x001d1207, 0x001d1208, 0x001d1207, 0x001d1207, 0x001c1106, 0x001b1005, 0x001c1005, 0x001c1106, 0x001c1106, 0x001d1206, 0x001d1206, 0x001d1206, 0x001d1307, 0x001e1308, 0x001e1308, 0x001c1105, 0x001c1105, 0x001a1105, 0x001a1105, 0x001a1105, 0x001a1105, 0x00191105, 0x00191105, 0x00191105, 0x001a1206, 0x001b1306, 0x001b1407, 0x001b1407, 0x001b1407, 0x001a1406, 0x00191306, 0x00191306, 0x00181004, 0x00191306, 0x00191105, 0x00181105, 0x001c1408, 0x001a1405, 0x001b1406, 0x001c1406, 0x001c1406, 0x001c1406, 0x001c1408, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1308, 0x001c1307, 0x001c1307, 0x001a1306, 0x00191306, 0x00191306, 0x001a1306, 0x001a1306, 0x00191407, 0x001b1408, 0x001b1408, 0x001b1408, 0x001c1408, 0x001c1408, 0x001c1308, 0x001c1308, 0x001c1408, 0x001c1408, 0x001e1409, 0x001c1408, 0x001c1408, 0x001c1307, 0x001c1307, 0x001c1307, 0x001d1207, 0x001d1207, 0x001d1208, 0x001d1208, 0x001e1308, 0x001e1408, 0x001f1408, 0x001f1409, 0x001f1408, 0x001f1407, 0x001f1407, 0x001f1408, 0x00201509, 0x0021170a, 0x00231609, 0x0028190c, 0x002b1b0c, 0x002e1c0d, 0x00301c0b, 0x00331c0b, 0x0038200d, 0x003e270c, 0x00482d0e, 0x005a3513, 0x006d4414, 0x008c6214, 0x00c49c28, 0x00ccae18, 0x00cbb209, 0x00cab408, 0x00cbb608, 0x00cbb70b, 0x00cbb408, 0x00ccb208, 0x00ccb00e, 0x00ccac10, 0x00cca814, 0x00c7a010, 0x00c0940c, 0x00b58604, 0x00b17c01, 0x00ac7200, 0x00a66800, 0x00a66700, 0x00a66601, 0x00a76805, 0x00ab6d09, 0x00b57a11, 0x00be8418, 0x00b47918, 0x00915707, 0x00824d0b, 0x00683a06, 0x004c2700, 0x00422404, 0x003a2008, 0x00351c07, 0x002e1b08, 0x002b1809, 0x00281808, 0x00241707, 0x001e1405, 0x001b1206, 0x00191208, 0x00181208, 0x00181009, 0x0018100a, 0x0017100a, 0x00161009, 0x00171009, 0x0018110b, 0x0018120c, 0x0018120b, 0x001a1208, 0x001e1408, 0x00271b0c, 0x002e2008, 0x00322408, 0x00382808, 0x003f2f08, 0x004d360b, 0x005e400f, 0x007a5412, 0x00a5801b, 0x00caaf24, 0x00cbb615, 0x00ccbb0c, 0x00ccbb0a, 0x00ccba0f, 0x00c4a614, 0x00996e04, 0x00704400, 0x00593901, 0x004b3606, 0x00442e06, 0x003f2906, 0x00382404, 0x00342106, 0x002e1c05, 0x00281b0a, 0x001a1404, 0x00111005, 0x000d0c03, 0x0014140c, 0x0014130a, 0x00101007, 0x000e0f05, 0x000d1008, 0x000d1009, 0x000c0f09, 0x000c100c, 0x000c110c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001c251c, 0x00151c14, 0x000f110b, 0x00101009, 0x0013110b, 0x00141109, 0x00121008, 0x000f0c04, 0x00141007, 0x001b1708, 0x00211a07, 0x00251d05, 0x002a1f06, 0x00312008, 0x00372608, 0x003c2d06, 0x00433408, 0x004c3808, 0x0064440c, 0x00856013, 0x00c09f2e, 0x00ccb41c, 0x00cbba0c, 0x00c9bc0b, 0x00cbb80d, 0x00c8b011, 0x00a07c03, 0x00784f02, 0x00603e07, 0x004e3808, 0x00402f06, 0x00382608, 0x002e2105, 0x00291d06, 0x002a1909, 0x0026180b, 0x0022160a, 0x001d1409, 0x00181308, 0x00141004, 0x00101006, 0x000f1007, 0x00100f08, 0x00110e08, 0x0013100a, 0x0011100a, 0x00121007, 0x00110f07, 0x00131107, 0x00131107, 0x00131107, 0x00141107, 0x00171208, 0x00181107, 0x00181207, 0x00191306, 0x001a1306, 0x001b1407, 0x001b1407, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1405, 0x001c1305, 0x001e1407, 0x001e1407, 0x001e1205, 0x0023160a, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201508, 0x00201508, 0x0020150a, 0x001f1409, 0x00170e03, 0x00171004, 0x001b1508, 0x001d1407, 0x00201307, 0x00211308, 0x00211308, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00211408, 0x00211408, 0x00211408, 0x00221509, 0x00211408, 0x00211408, 0x00201408, 0x00221509, 0x00221509, 0x00201609, 0x00201508, 0x001d1305, 0x001d1305, 0x001d1306, 0x001e1306, 0x001d1306, 0x001d1306, 0x001c1308, 0x001c1308, 0x001b1206, 0x001b1206, 0x001a1306, 0x001b1407, 0x001c1408, 0x001c1308, 0x001c1408, 0x001d1407, 0x001d1407, 0x001d1306, 0x001d1306, 0x001d1306, 0x001d1306, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1306, 0x001d1306, 0x001d1306, 0x001d1208, 0x001d1208, 0x001d1207, 0x001d1207, 0x001d1208, 0x001e1308, 0x001f1409, 0x001f1409, 0x001f1409, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1106, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001a1306, 0x001b1407, 0x001b1408, 0x001c1408, 0x001c1408, 0x001b1408, 0x001a1306, 0x00191206, 0x001b1408, 0x00181105, 0x00181004, 0x001c1509, 0x001a1304, 0x001c1406, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001a1306, 0x00191306, 0x00191306, 0x00191306, 0x00191206, 0x00181105, 0x00181105, 0x00181105, 0x00181105, 0x001b1206, 0x001b1206, 0x001a1105, 0x001a1105, 0x001a1105, 0x001a1105, 0x001b1206, 0x001c1307, 0x001c1307, 0x001e1409, 0x001e1409, 0x001f150a, 0x001f1409, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001c1106, 0x001d1207, 0x001d1205, 0x001e1407, 0x001e1407, 0x00201609, 0x0022170a, 0x00221509, 0x00241608, 0x00281809, 0x002e1a0b, 0x002f1a09, 0x00331c0b, 0x0039200d, 0x003f270c, 0x00492c0e, 0x005c3814, 0x00714617, 0x00936618, 0x00c7a02b, 0x00ccac19, 0x00ccae0e, 0x00cbad0f, 0x00caa912, 0x00c8a70f, 0x00c8a20c, 0x00c39b08, 0x00ba8f07, 0x00b18303, 0x00ac7801, 0x00a67100, 0x00a36c00, 0x00a36a01, 0x00a36702, 0x00a76804, 0x00ab6d08, 0x00b0770f, 0x00b98417, 0x00c2901d, 0x00c89c24, 0x00cca324, 0x00cca421, 0x00bd8c17, 0x00925e04, 0x00804c08, 0x00643804, 0x004a2700, 0x00402202, 0x00371d04, 0x00301a04, 0x00301c08, 0x002a1909, 0x00261704, 0x00231504, 0x001f1305, 0x001b1106, 0x00191208, 0x00181308, 0x0017110a, 0x0017100b, 0x0017100b, 0x0017110a, 0x0017110a, 0x0017110a, 0x0018120c, 0x0017130b, 0x001a1308, 0x001c1408, 0x00291d0d, 0x002e2008, 0x00312407, 0x00382807, 0x003f2f08, 0x004e360c, 0x005c3f0e, 0x00785213, 0x00a27c1a, 0x00c9ad26, 0x00ccb717, 0x00ccbb0d, 0x00ccbb0d, 0x00cbba10, 0x00c4a813, 0x009d7005, 0x00744800, 0x00593c03, 0x004b3508, 0x00442e06, 0x003f2906, 0x00382405, 0x00342006, 0x00301c05, 0x002a1c0c, 0x001f1809, 0x00101005, 0x000d0c04, 0x0014130c, 0x0014130a, 0x00101007, 0x00101007, 0x000f1008, 0x000e110a, 0x000e100c, 0x000e110d, 0x000e130e, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00222922, 0x001b2018, 0x00151811, 0x00171610, 0x001a1812, 0x001c1810, 0x0017140c, 0x0016130b, 0x001e1910, 0x00231d10, 0x0027200d, 0x002c210b, 0x0030250c, 0x00382810, 0x003d2c0f, 0x0044350f, 0x004c3c10, 0x00554011, 0x006b4c13, 0x00906b1c, 0x00c5a534, 0x00ccb41e, 0x00cbbb0d, 0x00c9bb0c, 0x00cbb80f, 0x00c8ae11, 0x009e7901, 0x007b5004, 0x00624008, 0x00513c0d, 0x0045330b, 0x00402c0e, 0x0035280d, 0x0030240c, 0x002d1c0d, 0x00281b0e, 0x0025180d, 0x0020180c, 0x001e180d, 0x0019160b, 0x0016150b, 0x0014160c, 0x0016150e, 0x001b1812, 0x0017140e, 0x0015140e, 0x0018160d, 0x0018160e, 0x0018160c, 0x0019170d, 0x0018180d, 0x001a170d, 0x001d180e, 0x001f180e, 0x0020180d, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0021180c, 0x0021180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020190b, 0x00221a0c, 0x00241a0e, 0x00241a0e, 0x0025190d, 0x002a1e12, 0x00281b0f, 0x0025180c, 0x0024180c, 0x0024190d, 0x0024190c, 0x0024180c, 0x0024190c, 0x00271c10, 0x00281d10, 0x00281d12, 0x00281d12, 0x0020170c, 0x0020190c, 0x0020190d, 0x00231a0c, 0x00251a0d, 0x00281a0f, 0x0027190d, 0x0026190d, 0x0026180c, 0x0027180c, 0x0027180c, 0x0027180d, 0x0026190d, 0x00261a0e, 0x00281b0f, 0x00281b10, 0x00271a0e, 0x00281b0f, 0x00281b10, 0x00271a0e, 0x0025190d, 0x0024180c, 0x0024180c, 0x00251a0d, 0x0024190c, 0x0024190c, 0x0023180c, 0x0024190c, 0x0024190c, 0x00231a0e, 0x00231a0e, 0x0022190d, 0x0022190d, 0x0021190d, 0x0020190d, 0x0021190e, 0x0022190e, 0x0022190d, 0x00231a0d, 0x00241a0d, 0x0024190c, 0x0024190c, 0x0024190c, 0x0024190c, 0x00251b0e, 0x00251b0f, 0x00251b0e, 0x00261c0f, 0x00251b0e, 0x00251b0e, 0x00251a10, 0x00251a10, 0x0024190f, 0x0024190f, 0x0024190f, 0x0024180e, 0x0024190f, 0x0024190f, 0x0024190f, 0x0024190f, 0x0024190e, 0x0024190e, 0x0024190e, 0x0024190e, 0x0024190e, 0x0022180c, 0x0022180c, 0x0021180d, 0x0021180d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0021180d, 0x0022190d, 0x00221a0e, 0x00221b0f, 0x00211a0e, 0x0020190e, 0x00211a0e, 0x00211a0e, 0x00211a0e, 0x00211a0f, 0x00231c10, 0x0020190d, 0x00201a0e, 0x00241c11, 0x00231c0f, 0x00221b0d, 0x0020190a, 0x00211a0c, 0x00221b0c, 0x00231a0e, 0x00231a0e, 0x00221a0e, 0x0022190e, 0x0022190e, 0x0022190e, 0x0022190e, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190e, 0x0022190e, 0x0022190e, 0x0022190e, 0x0021180d, 0x0021180d, 0x0020190d, 0x0020190d, 0x0020190d, 0x0020190d, 0x0020190d, 0x0020190d, 0x00201a0e, 0x00201a0e, 0x00211a0e, 0x00231a0f, 0x00231a0f, 0x0022190e, 0x0022190e, 0x0022190e, 0x0022190e, 0x00231a0f, 0x00231a0e, 0x00231a10, 0x00231a0f, 0x00221a0f, 0x00221a0f, 0x0024190f, 0x0024190f, 0x0024190f, 0x0024190e, 0x0024190e, 0x0024180e, 0x0024180e, 0x0024190e, 0x0024190e, 0x00251c0f, 0x00251c0f, 0x00241a0d, 0x00261c10, 0x00271c10, 0x00281b10, 0x002c1e10, 0x00302010, 0x00342112, 0x0036210f, 0x00382110, 0x003d2512, 0x00442c12, 0x004e3113, 0x00623d1b, 0x00744819, 0x0092641b, 0x00c4982e, 0x00c39c17, 0x00bf9a0b, 0x00b89208, 0x00b08506, 0x00aa7d02, 0x00a47400, 0x009f6c00, 0x009c6800, 0x009c6601, 0x00a16704, 0x00a46709, 0x00ac6c14, 0x00b3741b, 0x00ba7c21, 0x00c48928, 0x00c6942a, 0x00c89d2b, 0x00cca42a, 0x00cca827, 0x00ccac22, 0x00cbad1c, 0x00ccad1b, 0x00b99210, 0x008f6000, 0x007f4e08, 0x00623804, 0x004c2c04, 0x00432606, 0x003e240c, 0x0038220c, 0x0034210f, 0x00301e0f, 0x002c1d0b, 0x00291c0c, 0x0024180b, 0x0021180c, 0x0020180d, 0x001f190e, 0x001f1811, 0x001f1812, 0x001e1811, 0x001d1810, 0x001e1811, 0x001f1811, 0x001f1812, 0x001e1911, 0x0020180f, 0x0022180d, 0x002e2313, 0x0032240d, 0x0034280b, 0x003c2c0b, 0x0044320c, 0x00513a11, 0x00604212, 0x00785212, 0x00a37c1b, 0x00c8ac25, 0x00ccb719, 0x00ccbb0f, 0x00ccbb0e, 0x00cbba10, 0x00c6a814, 0x00a27508, 0x007b4e04, 0x005f400b, 0x00503b0e, 0x0049330c, 0x00442e0d, 0x003f2a0c, 0x003b270d, 0x0036220c, 0x00302111, 0x00261e10, 0x0017160c, 0x0014130c, 0x00191811, 0x001b1b11, 0x00191810, 0x0017170e, 0x0014160e, 0x00141610, 0x00141510, 0x00131611, 0x00141813, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07}; \ No newline at end of file diff --git a/include/subsystems/screen.h b/include/subsystems/screen.h new file mode 100644 index 0000000..4f0a876 --- /dev/null +++ b/include/subsystems/screen.h @@ -0,0 +1,22 @@ +#pragma once +#include "vex.h" +#include + +/// @brief the type of function that the screen controller expects +/// @param screen a reference to the screen to draw on +/// @param x the x position this widget has been told to start at +/// @param y the y position this widget has been told to start at + +typedef void (*screenFunc)(vex::brain::lcd &screen, int x, int y, int width, int height, bool first_run); + +void draw_mot_header(vex::brain::lcd &screen, int x, int y, int width); +// name should be no longer than 15 characters +void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char *name, vex::motor &motor); +void draw_battery_stats(vex::brain::lcd &screen, int x, int y, double voltage, double percentage); + + + +void draw_lr_arrows(vex::brain::lcd &screen, int bar_width, int width, int height); + +int HandleScreen(vex::brain::lcd &screen, std::vector pages); +void StartScreen(vex::brain::lcd &screen, std::vector pages); \ No newline at end of file diff --git a/src/subsystems/screen.cpp b/src/subsystems/screen.cpp new file mode 100644 index 0000000..2b963c1 --- /dev/null +++ b/src/subsystems/screen.cpp @@ -0,0 +1,202 @@ +#include "../core/include/subsystems/screen.h" + +void draw_battery_stats(vex::brain::lcd &screen, int x, int y, double voltage, double percentage) +{ + double low_pct = 70.0; + double med_pct = 85.0; + + vex::color low_col = vex::color(120, 0, 0); + vex::color med_col = vex::color(140, 100, 0); + vex::color high_col = vex::black; + + vex::color bg_col = vex::black; + if (percentage < low_pct) + { + bg_col = low_col; + } + else if (percentage < med_pct) + { + bg_col = med_col; + } + else + { + bg_col = high_col; + } + + screen.setFillColor(bg_col); + screen.setPenColor(vex::white); + screen.setFont(vex::mono15); + + screen.drawRectangle(x, y, 200, 20); + screen.printAt(x + 2, y + 15, "battery: %.1fv %d%%", voltage, (int)percentage); +} + +void draw_mot_header(vex::brain::lcd &screen, int x, int y, int width) +{ + vex::color bg_col = vex::black; + vex::color border_col = vex::white; + screen.setFillColor(bg_col); + screen.setPenColor(border_col); + screen.setFont(vex::mono15); + + screen.drawRectangle(x, y, width, 20); + screen.printAt(x + 5, y + 15, "motor name"); + int name_width = 110; + + screen.printAt(x + name_width + 7, y + 15, "temp"); + + screen.drawLine(x + name_width, y, x + name_width, y + 20); + + screen.drawLine(x + name_width + 50, y, x + name_width + 50, y + 20); + + screen.printAt(x + name_width + 55, y + 15, "port"); +} + +void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char *name, vex::motor &motor) +{ + double tempC = motor.temperature(vex::celsius); + bool pluggedin = motor.installed(); + int port = motor.index() + 1; + + // used for flashing + static int count = 0; + vex::color bg_col = vex::black; + vex::color hot_col = vex::color(120, 0, 0); + vex::color med_col = vex::color(140, 100, 0); + vex::color low_col = vex::black; // color(0,100,0); + vex::color not_plugged_in_col = vex::color(255, 0, 0); + + double lowtemp = 40; + double hightemp = 50; + if (tempC < lowtemp) + { + bg_col = low_col; + } + else if (tempC >= lowtemp && tempC < hightemp) + { + bg_col = med_col; + } + else if (tempC > hightemp) + { + bg_col = hot_col; + } + + if (!pluggedin) + { + if ((count / 16) % 2 == 0) + { + bg_col = not_plugged_in_col; + } + else + { + bg_col = bg_col; + } + } + + vex::color border_col = vex::white; + screen.setFillColor(bg_col); + screen.setPenColor(border_col); + screen.setFont(vex::mono15); + + screen.drawRectangle(x, y, width, 20); + + // name + screen.printAt(x + 5, y + 15, name); + int name_width = 110; + + // temp + screen.drawLine(x + name_width, y, x + name_width, y + 20); + screen.printAt(x + name_width + 10, y + 15, "%dC", (int)tempC); + + // PORT + screen.drawLine(x + name_width + 50, y, x + name_width + 50, y + 20); + char *warning = "!"; + if (pluggedin) + { + warning = ""; + } + screen.printAt(x + name_width + 60, y + 15, "%d%s", port, warning); + count++; +} + +void draw_lr_arrows(vex::brain::lcd &screen, int bar_width, int width, int height) +{ + auto bar_col = vex::color(40, 40, 40); + auto arrow_col = vex::color(255, 255, 255); + // draw touch zones + screen.setFillColor(bar_col); + screen.setPenColor(bar_col); + + screen.drawRectangle(0, 0, bar_width, height); + screen.drawRectangle(width - bar_width, 0, width, height); + + // draw arrows + screen.setPenColor(arrow_col); + screen.drawLine(bar_width / 3, height / 2, 2 * bar_width / 3, height / 2 - 20); + screen.drawLine(bar_width / 3, height / 2, 2 * bar_width / 3, height / 2 + 20); + + screen.drawLine(width - bar_width / 3, height / 2, width - 2 * bar_width / 3, height / 2 - 20); + screen.drawLine(width - bar_width / 3, height / 2, width - 2 * bar_width / 3, height / 2 + 20); +} + +int HandleScreen(vex::brain::lcd &screen, std::vector pages) +{ + unsigned int num_pages = pages.size(); + unsigned int current_page = 0; + + int width = 480; + int height = 240; + + int bar_width = 40; + + bool was_pressing = false; + bool first_draw = true; + while (true) + { + draw_lr_arrows(screen, bar_width, width, height); + + pages[current_page](screen, bar_width, 0, width - bar_width * 2, height, first_draw); + + first_draw = false; + // handle presses + if (screen.pressing() && !was_pressing) + { + + int x = screen.xPosition(); + int y = screen.yPosition(); + + if (x < bar_width) + { + if (current_page == 0) + { + current_page = num_pages; + } + current_page--; + first_draw = true; + } + + if (x > width - bar_width * 2) + { + current_page++; + current_page %= num_pages; + first_draw = true; + } + } + was_pressing = screen.pressing(); + screen.render(); + vexDelay(100); + } + + return 0; +} + +void StartScreen(vex::brain::lcd &screen, std::vector pages) +{ + static std::vector my_pages = pages; + ; // hold onto it here so we don't lose it and can use it in the lambda down there. capture semantics are fun + static vex::brain::lcd my_screen = screen; + vex::task screenTask([]() + { + HandleScreen(my_screen, my_pages); + return 0; }); +} \ No newline at end of file diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index 14be25e..691664c 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -50,6 +50,8 @@ void CommandController::run() { printf("Running Auto. Commands 1 to %d\n", command_queue.size()); fflush(stdout); int command_count = 1; + vex::timer tmr; + tmr.reset(); while(!command_queue.empty()) { // retrieve and remove command at the front of the queue @@ -86,6 +88,7 @@ void CommandController::run() { fflush(stdout); command_count++; } + printf("Finished commands in %f seconds\n", tmr.time(vex::sec)); } bool CommandController::last_command_timed_out(){ From 294952e67cb4c1959bade24aeb1c0d0490242628 Mon Sep 17 00:00:00 2001 From: cowsed Date: Thu, 23 Feb 2023 21:58:17 -0500 Subject: [PATCH 180/243] pre purdue auto --- include/utils/command_structure/auto_command.h | 2 +- include/utils/command_structure/drive_commands.h | 5 ----- src/subsystems/flywheel.cpp | 2 +- src/subsystems/screen.cpp | 2 +- src/subsystems/tank_drive.cpp | 1 + 5 files changed, 4 insertions(+), 8 deletions(-) diff --git a/include/utils/command_structure/auto_command.h b/include/utils/command_structure/auto_command.h index c8f1cbf..fd44850 100644 --- a/include/utils/command_structure/auto_command.h +++ b/include/utils/command_structure/auto_command.h @@ -21,7 +21,7 @@ class AutoCommand { */ virtual void on_timeout(){} AutoCommand* withTimeout(double t_seconds){ - timeout_seconds = t_seconds; + this->timeout_seconds = t_seconds; return this; } /** diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index 3419a18..8e4ff04 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -176,11 +176,6 @@ class DriveStopCommand: public AutoCommand { * @returns true when execution is complete, false otherwise */ bool run() override; - /** - * Cleans up drive system if we time out before finishing - */ - void on_timeout() override; - private: // drive system to run the function on diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 2c41114..01a2c2a 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -22,7 +22,7 @@ using namespace vex; -const int FlywheelWindowSize = 1; +const int FlywheelWindowSize = 20; /********************************************************* * CONSTRUCTOR, GETTERS, SETTERS diff --git a/src/subsystems/screen.cpp b/src/subsystems/screen.cpp index 2b963c1..38fd56e 100644 --- a/src/subsystems/screen.cpp +++ b/src/subsystems/screen.cpp @@ -76,7 +76,7 @@ void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char { bg_col = med_col; } - else if (tempC > hightemp) + else if (tempC >= hightemp) { bg_col = hot_col; } diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 370173a..812f6bd 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -303,6 +303,7 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb { stop(); func_initialized = false; + stop(); return true; } From f0ee99db778aa31e169a4da5ebd743fce0ffae60 Mon Sep 17 00:00:00 2001 From: cowsed Date: Thu, 2 Mar 2023 19:03:47 -0500 Subject: [PATCH 181/243] Vision Chooser: Vision options in robot_config screen four allows picking between these options VisionCommand stops if vision is disabled and only red or blue targets will be targeted --- include/subsystems/screen.h | 4 ++-- src/subsystems/screen.cpp | 15 +++++++-------- 2 files changed, 9 insertions(+), 10 deletions(-) diff --git a/include/subsystems/screen.h b/include/subsystems/screen.h index 4f0a876..891c57d 100644 --- a/include/subsystems/screen.h +++ b/include/subsystems/screen.h @@ -18,5 +18,5 @@ void draw_battery_stats(vex::brain::lcd &screen, int x, int y, double voltage, d void draw_lr_arrows(vex::brain::lcd &screen, int bar_width, int width, int height); -int HandleScreen(vex::brain::lcd &screen, std::vector pages); -void StartScreen(vex::brain::lcd &screen, std::vector pages); \ No newline at end of file +int handle_screen_thread(vex::brain::lcd &screen, std::vector pages, int first_page); +void StartScreen(vex::brain::lcd &screen, std::vector pages, int first_page = 0); \ No newline at end of file diff --git a/src/subsystems/screen.cpp b/src/subsystems/screen.cpp index 38fd56e..85ca0ba 100644 --- a/src/subsystems/screen.cpp +++ b/src/subsystems/screen.cpp @@ -139,10 +139,10 @@ void draw_lr_arrows(vex::brain::lcd &screen, int bar_width, int width, int heigh screen.drawLine(width - bar_width / 3, height / 2, width - 2 * bar_width / 3, height / 2 + 20); } -int HandleScreen(vex::brain::lcd &screen, std::vector pages) +int handle_screen_thread(vex::brain::lcd &screen, std::vector pages, int first_page) { unsigned int num_pages = pages.size(); - unsigned int current_page = 0; + unsigned int current_page = first_page; int width = 480; int height = 240; @@ -184,19 +184,18 @@ int HandleScreen(vex::brain::lcd &screen, std::vector pages) } was_pressing = screen.pressing(); screen.render(); - vexDelay(100); + vexDelay(40); } return 0; } -void StartScreen(vex::brain::lcd &screen, std::vector pages) +void StartScreen(vex::brain::lcd &screen, std::vector pages, int first_page) { + // hold onto arguments here so we don't lose them and can use then in the lambda down there. capture semantics are not fun static std::vector my_pages = pages; - ; // hold onto it here so we don't lose it and can use it in the lambda down there. capture semantics are fun static vex::brain::lcd my_screen = screen; + static int my_first_page = first_page; vex::task screenTask([]() - { - HandleScreen(my_screen, my_pages); - return 0; }); + { return handle_screen_thread(my_screen, my_pages, my_first_page); }); } \ No newline at end of file From 750cef61f7ab3c12bdc72a123d3a1cefcc36042f Mon Sep 17 00:00:00 2001 From: cowsed Date: Fri, 3 Mar 2023 21:43:31 -0500 Subject: [PATCH 182/243] Screen Arrows Drawn after --- src/subsystems/screen.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/subsystems/screen.cpp b/src/subsystems/screen.cpp index 85ca0ba..fd06524 100644 --- a/src/subsystems/screen.cpp +++ b/src/subsystems/screen.cpp @@ -153,8 +153,6 @@ int handle_screen_thread(vex::brain::lcd &screen, std::vector pages, bool first_draw = true; while (true) { - draw_lr_arrows(screen, bar_width, width, height); - pages[current_page](screen, bar_width, 0, width - bar_width * 2, height, first_draw); first_draw = false; @@ -181,6 +179,7 @@ int handle_screen_thread(vex::brain::lcd &screen, std::vector pages, current_page %= num_pages; first_draw = true; } + draw_lr_arrows(screen, bar_width, width, height); } was_pressing = screen.pressing(); screen.render(); From 49a46d12e860541f1d446fac1722a5043bfeb909 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 12 Mar 2023 20:04:19 -0400 Subject: [PATCH 183/243] Experimental gh pages documentation --- .github/workflows/main.yml | 39 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 39 insertions(+) create mode 100644 .github/workflows/main.yml diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml new file mode 100644 index 0000000..c033af1 --- /dev/null +++ b/.github/workflows/main.yml @@ -0,0 +1,39 @@ +# This is a basic workflow to help you get started with Actions + +name: Doxygen Action + +# Controls when the action will run. Triggers the workflow on push or pull request +# events but only for the master branch +on: + push: + branches: [ master ] + + + +# A workflow run is made up of one or more jobs that can run sequentially or in parallel +jobs: + # This workflow contains a single job called "build" + build: + # The type of runner that the job will run on + runs-on: ubuntu-latest + + # Steps represent a sequence of tasks that will be executed as part of the job + steps: + # Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it + - uses: actions/checkout@v2 + + - name: Doxygen Action + uses: mattnotmitt/doxygen-action@v1.1.0 + with: + # Path to Doxyfile + doxyfile-path: "./Doxyfile" # default is ./Doxyfile + # Working directory + working-directory: "." # default is . + + - name: Deploy + uses: peaceiris/actions-gh-pages@v3 + with: + github_token: ${{ secrets.GITHUB_TOKEN }} + # Default Doxyfile build documentation to html directory. + # Change the directory if changes in Doxyfile + publish_dir: ./documentation/html From 89baed4b9d781618b1813b64925b507d722f1982 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 12 Mar 2023 20:08:22 -0400 Subject: [PATCH 184/243] gh pages for real --- Doxyfile | 2736 +++++++++++++++++ documentation/html/annotated.html | 132 + .../html/auto__chooser_8h_source.html | 130 + .../html/auto__command_8h_source.html | 109 + documentation/html/bc_s.png | Bin 0 -> 676 bytes documentation/html/bc_sd.png | Bin 0 -> 635 bytes documentation/html/bdwn.png | Bin 0 -> 147 bytes .../html/classAutoChooser-members.html | 91 + documentation/html/classAutoChooser.html | 296 ++ .../html/classAutoCommand-members.html | 88 + documentation/html/classAutoCommand.html | 205 ++ documentation/html/classAutoCommand.png | Bin 0 -> 5628 bytes .../html/classCommandController-members.html | 89 + .../html/classCommandController.html | 233 ++ .../html/classCustomEncoder-members.html | 90 + documentation/html/classCustomEncoder.html | 296 ++ documentation/html/classCustomEncoder.png | Bin 0 -> 494 bytes .../html/classDelayCommand-members.html | 89 + documentation/html/classDelayCommand.html | 184 ++ documentation/html/classDelayCommand.png | Bin 0 -> 508 bytes .../classDriveForwardCommand-members.html | 89 + .../html/classDriveForwardCommand.html | 252 ++ .../html/classDriveForwardCommand.png | Bin 0 -> 613 bytes .../html/classDriveStopCommand-members.html | 89 + documentation/html/classDriveStopCommand.html | 178 ++ documentation/html/classDriveStopCommand.png | Bin 0 -> 549 bytes .../classDriveToPointCommand-members.html | 89 + .../html/classDriveToPointCommand.html | 274 ++ .../html/classDriveToPointCommand.png | Bin 0 -> 595 bytes .../html/classFeedForward-members.html | 86 + documentation/html/classFeedForward.html | 199 ++ documentation/html/classFeedback-members.html | 94 + documentation/html/classFeedback.html | 315 ++ documentation/html/classFeedback.png | Bin 0 -> 792 bytes documentation/html/classFlywheel-members.html | 105 + documentation/html/classFlywheel.html | 684 +++++ .../classFlywheelStopCommand-members.html | 89 + .../html/classFlywheelStopCommand.html | 177 ++ .../html/classFlywheelStopCommand.png | Bin 0 -> 621 bytes ...lassFlywheelStopMotorsCommand-members.html | 89 + .../html/classFlywheelStopMotorsCommand.html | 177 ++ .../html/classFlywheelStopMotorsCommand.png | Bin 0 -> 678 bytes ...ssFlywheelStopNonTasksCommand-members.html | 87 + .../classFlywheelStopNonTasksCommand.html | 115 + .../html/classFlywheelStopNonTasksCommand.png | Bin 0 -> 718 bytes .../html/classGenericAuto-members.html | 88 + documentation/html/classGenericAuto.html | 204 ++ .../html/classGraphDrawer-members.html | 87 + documentation/html/classGraphDrawer.html | 277 ++ documentation/html/classLift-members.html | 97 + documentation/html/classLift.html | 630 ++++ .../html/classMecanumDrive-members.html | 89 + documentation/html/classMecanumDrive.html | 389 +++ .../html/classMotionController-members.html | 97 + documentation/html/classMotionController.html | 477 +++ documentation/html/classMotionController.png | Bin 0 -> 474 bytes .../html/classMovingAverage-members.html | 89 + documentation/html/classMovingAverage.html | 233 ++ .../html/classOdomSetPosition-members.html | 89 + documentation/html/classOdomSetPosition.html | 195 ++ documentation/html/classOdomSetPosition.png | Bin 0 -> 525 bytes .../html/classOdometry3Wheel-members.html | 108 + documentation/html/classOdometry3Wheel.html | 303 ++ documentation/html/classOdometry3Wheel.png | Bin 0 -> 548 bytes .../html/classOdometryBase-members.html | 106 + documentation/html/classOdometryBase.html | 725 +++++ documentation/html/classOdometryBase.png | Bin 0 -> 776 bytes .../html/classOdometryTank-members.html | 108 + documentation/html/classOdometryTank.html | 345 +++ documentation/html/classOdometryTank.png | Bin 0 -> 541 bytes documentation/html/classPID-members.html | 103 + documentation/html/classPID.html | 509 +++ documentation/html/classPID.png | Bin 0 -> 362 bytes documentation/html/classPIDFF-members.html | 98 + documentation/html/classPIDFF.html | 401 +++ documentation/html/classPIDFF.png | Bin 0 -> 377 bytes .../html/classSpinRPMCommand-members.html | 89 + documentation/html/classSpinRPMCommand.html | 189 ++ documentation/html/classSpinRPMCommand.png | Bin 0 -> 543 bytes .../html/classTankDrive-members.html | 99 + documentation/html/classTankDrive.html | 877 ++++++ .../html/classTrapezoidProfile-members.html | 90 + documentation/html/classTrapezoidProfile.html | 290 ++ .../html/classTurnDegreesCommand-members.html | 89 + .../html/classTurnDegreesCommand.html | 233 ++ .../html/classTurnDegreesCommand.png | Bin 0 -> 614 bytes .../classTurnToHeadingCommand-members.html | 89 + .../html/classTurnToHeadingCommand.html | 233 ++ .../html/classTurnToHeadingCommand.png | Bin 0 -> 624 bytes documentation/html/classVector2D-members.html | 95 + documentation/html/classVector2D.html | 378 +++ ...lassWaitUntilUpToSpeedCommand-members.html | 89 + .../html/classWaitUntilUpToSpeedCommand.html | 188 ++ .../html/classWaitUntilUpToSpeedCommand.png | Bin 0 -> 660 bytes documentation/html/classes.html | 132 + documentation/html/closed.png | Bin 0 -> 132 bytes .../html/command__controller_8h_source.html | 113 + .../html/custom__encoder_8h_source.html | 115 + .../html/delay__command_8h_source.html | 107 + .../dir_313caf1132e152dd9b58bea13a4052ca.html | 91 + .../dir_42a35307dcefecb9f25978d1dedb502f.html | 91 + .../dir_68267d1309a1af8e8297ef4c3efbcdba.html | 93 + .../dir_821002d4f10779a80d4fb17bc32f21f1.html | 120 + .../dir_883d6c53cd62ec60a5d421a7bc1a2629.html | 95 + .../dir_8e84b5daa2b3f33b7b3fb9ecedbe5637.html | 106 + .../dir_ca1fd9fa48e5fdc0ddfbf442e09c4dab.html | 85 + .../dir_d44c64559bbebec7f509842c48db8b23.html | 98 + .../dir_d9631e0f4b8929605c336e8f080acaa3.html | 85 + .../dir_e0729c835bcfebced7012c88d9b3a1d3.html | 99 + documentation/html/doc.png | Bin 0 -> 746 bytes documentation/html/docd.png | Bin 0 -> 756 bytes documentation/html/doxygen.css | 2007 ++++++++++++ documentation/html/doxygen.svg | 26 + .../html/drive__commands_8h_source.html | 229 ++ documentation/html/dynsections.js | 123 + .../html/feedback__base_8h_source.html | 118 + documentation/html/feedforward_8h_source.html | 135 + documentation/html/files.html | 118 + documentation/html/flywheel_8h_source.html | 197 ++ .../html/flywheel__commands_8h_source.html | 161 + documentation/html/folderclosed.png | Bin 0 -> 616 bytes documentation/html/folderopen.png | Bin 0 -> 597 bytes documentation/html/functions.html | 93 + documentation/html/functions_b.html | 84 + documentation/html/functions_c.html | 91 + documentation/html/functions_d.html | 99 + documentation/html/functions_e.html | 86 + documentation/html/functions_enum.html | 81 + documentation/html/functions_f.html | 87 + documentation/html/functions_func.html | 282 ++ documentation/html/functions_g.html | 109 + documentation/html/functions_h.html | 86 + documentation/html/functions_i.html | 86 + documentation/html/functions_k.html | 86 + documentation/html/functions_l.html | 85 + documentation/html/functions_m.html | 89 + documentation/html/functions_n.html | 84 + documentation/html/functions_o.html | 94 + documentation/html/functions_p.html | 90 + documentation/html/functions_r.html | 90 + documentation/html/functions_s.html | 104 + documentation/html/functions_t.html | 92 + documentation/html/functions_u.html | 84 + documentation/html/functions_v.html | 85 + documentation/html/functions_vars.html | 212 ++ documentation/html/functions_w.html | 86 + documentation/html/functions_x.html | 83 + documentation/html/functions_y.html | 83 + documentation/html/functions_z.html | 83 + .../html/generic__auto_8h_source.html | 116 + .../html/graph__drawer_8h_source.html | 199 ++ documentation/html/hierarchy.html | 132 + documentation/html/index.html | 81 + documentation/html/jquery.js | 34 + documentation/html/lift_8h_source.html | 344 +++ documentation/html/math__util_8h_source.html | 128 + documentation/html/md_README.html | 109 + .../html/mecanum__drive_8h_source.html | 151 + documentation/html/menu.js | 136 + documentation/html/menudata.js | 104 + .../html/motion__controller_8h_source.html | 158 + .../html/moving__average_8h_source.html | 129 + documentation/html/nav_f.png | Bin 0 -> 153 bytes documentation/html/nav_fd.png | Bin 0 -> 169 bytes documentation/html/nav_g.png | Bin 0 -> 95 bytes documentation/html/nav_h.png | Bin 0 -> 98 bytes documentation/html/nav_hd.png | Bin 0 -> 114 bytes .../html/odometry__3wheel_8h_source.html | 127 + .../html/odometry__base_8h_source.html | 173 ++ .../html/odometry__tank_8h_source.html | 127 + documentation/html/open.png | Bin 0 -> 123 bytes documentation/html/pages.html | 86 + documentation/html/pid_8h_source.html | 177 ++ documentation/html/pidff_8h_source.html | 135 + .../html/pure__pursuit_8h_source.html | 133 + .../html/robot__specs_8h_source.html | 115 + documentation/html/screen_8h_source.html | 103 + documentation/html/search/all_0.js | 15 + documentation/html/search/all_1.js | 5 + documentation/html/search/all_10.js | 26 + documentation/html/search/all_11.js | 13 + documentation/html/search/all_12.js | 5 + documentation/html/search/all_13.js | 6 + documentation/html/search/all_14.js | 7 + documentation/html/search/all_15.js | 4 + documentation/html/search/all_16.js | 4 + documentation/html/search/all_17.js | 4 + documentation/html/search/all_2.js | 14 + documentation/html/search/all_3.js | 20 + documentation/html/search/all_4.js | 8 + documentation/html/search/all_5.js | 11 + documentation/html/search/all_6.js | 31 + documentation/html/search/all_7.js | 8 + documentation/html/search/all_8.js | 7 + documentation/html/search/all_9.js | 7 + documentation/html/search/all_a.js | 7 + documentation/html/search/all_b.js | 13 + documentation/html/search/all_c.js | 5 + documentation/html/search/all_d.js | 16 + documentation/html/search/all_e.js | 15 + documentation/html/search/all_f.js | 12 + documentation/html/search/classes_0.js | 5 + documentation/html/search/classes_1.js | 5 + documentation/html/search/classes_2.js | 7 + documentation/html/search/classes_3.js | 4 + documentation/html/search/classes_4.js | 10 + documentation/html/search/classes_5.js | 5 + documentation/html/search/classes_6.js | 4 + documentation/html/search/classes_7.js | 5 + documentation/html/search/classes_8.js | 9 + documentation/html/search/classes_9.js | 8 + documentation/html/search/classes_a.js | 8 + documentation/html/search/classes_b.js | 4 + documentation/html/search/classes_c.js | 5 + documentation/html/search/classes_d.js | 7 + documentation/html/search/classes_e.js | 4 + documentation/html/search/classes_f.js | 4 + documentation/html/search/close.svg | 31 + documentation/html/search/enums_0.js | 4 + documentation/html/search/functions_0.js | 11 + documentation/html/search/functions_1.js | 4 + documentation/html/search/functions_10.js | 11 + documentation/html/search/functions_11.js | 5 + documentation/html/search/functions_12.js | 5 + documentation/html/search/functions_13.js | 4 + documentation/html/search/functions_2.js | 8 + documentation/html/search/functions_3.js | 15 + documentation/html/search/functions_4.js | 4 + documentation/html/search/functions_5.js | 7 + documentation/html/search/functions_6.js | 30 + documentation/html/search/functions_7.js | 5 + documentation/html/search/functions_8.js | 6 + documentation/html/search/functions_9.js | 5 + documentation/html/search/functions_a.js | 8 + documentation/html/search/functions_b.js | 4 + documentation/html/search/functions_c.js | 11 + documentation/html/search/functions_d.js | 8 + documentation/html/search/functions_e.js | 9 + documentation/html/search/functions_f.js | 24 + documentation/html/search/mag.svg | 37 + documentation/html/search/mag_d.svg | 37 + documentation/html/search/mag_sel.svg | 74 + documentation/html/search/mag_seld.svg | 74 + documentation/html/search/pages_0.js | 4 + documentation/html/search/search.css | 291 ++ documentation/html/search/search.js | 816 +++++ documentation/html/search/searchdata.js | 30 + documentation/html/search/variables_0.js | 6 + documentation/html/search/variables_1.js | 4 + documentation/html/search/variables_10.js | 5 + documentation/html/search/variables_11.js | 4 + documentation/html/search/variables_12.js | 6 + documentation/html/search/variables_13.js | 4 + documentation/html/search/variables_14.js | 4 + documentation/html/search/variables_15.js | 4 + documentation/html/search/variables_2.js | 7 + documentation/html/search/variables_3.js | 8 + documentation/html/search/variables_4.js | 5 + documentation/html/search/variables_5.js | 4 + documentation/html/search/variables_6.js | 5 + documentation/html/search/variables_7.js | 4 + documentation/html/search/variables_8.js | 7 + documentation/html/search/variables_9.js | 4 + documentation/html/search/variables_a.js | 5 + documentation/html/search/variables_b.js | 4 + documentation/html/search/variables_c.js | 7 + documentation/html/search/variables_d.js | 6 + documentation/html/search/variables_e.js | 5 + documentation/html/search/variables_f.js | 4 + documentation/html/splitbar.png | Bin 0 -> 314 bytes documentation/html/splitbard.png | Bin 0 -> 282 bytes ...structAutoChooser_1_1entry__t-members.html | 93 + .../html/structAutoChooser_1_1entry__t.html | 185 ++ ...tFeedForward_1_1ff__config__t-members.html | 92 + .../structFeedForward_1_1ff__config__t.html | 172 ++ .../structLift_1_1lift__cfg__t-members.html | 93 + .../html/structLift_1_1lift__cfg__t.html | 118 + ...ve_1_1mecanumdrive__config__t-members.html | 94 + ...canumDrive_1_1mecanumdrive__config__t.html | 117 + ...troller_1_1m__profile__cfg__t-members.html | 92 + ...otionController_1_1m__profile__cfg__t.html | 115 + ...eel_1_1odometry3wheel__cfg__t-members.html | 91 + ...metry3Wheel_1_1odometry3wheel__cfg__t.html | 151 + .../structPID_1_1pid__config__t-members.html | 94 + .../html/structPID_1_1pid__config__t.html | 126 + ...PurePursuit_1_1hermite__point-members.html | 94 + .../structPurePursuit_1_1hermite__point.html | 121 + .../structPurePursuit_1_1spline-members.html | 95 + .../html/structPurePursuit_1_1spline.html | 124 + .../structVector2D_1_1point__t-members.html | 93 + .../html/structVector2D_1_1point__t.html | 217 ++ .../html/structmotion__t-members.html | 87 + documentation/html/structmotion__t.html | 107 + .../html/structposition__t-members.html | 87 + documentation/html/structposition__t.html | 107 + .../html/structrobot__specs__t-members.html | 92 + documentation/html/structrobot__specs__t.html | 127 + documentation/html/sync_off.png | Bin 0 -> 853 bytes documentation/html/sync_on.png | Bin 0 -> 845 bytes documentation/html/tab_a.png | Bin 0 -> 142 bytes documentation/html/tab_ad.png | Bin 0 -> 135 bytes documentation/html/tab_b.png | Bin 0 -> 169 bytes documentation/html/tab_bd.png | Bin 0 -> 173 bytes documentation/html/tab_h.png | Bin 0 -> 177 bytes documentation/html/tab_hd.png | Bin 0 -> 180 bytes documentation/html/tab_s.png | Bin 0 -> 184 bytes documentation/html/tab_sd.png | Bin 0 -> 188 bytes documentation/html/tabs.css | 1 + documentation/html/tank__drive_8h_source.html | 165 + .../html/trapezoid__profile_8h_source.html | 129 + documentation/html/vector2d_8h_source.html | 173 ++ 311 files changed, 32589 insertions(+) create mode 100644 Doxyfile create mode 100644 documentation/html/annotated.html create mode 100644 documentation/html/auto__chooser_8h_source.html create mode 100644 documentation/html/auto__command_8h_source.html create mode 100644 documentation/html/bc_s.png create mode 100644 documentation/html/bc_sd.png create mode 100644 documentation/html/bdwn.png create mode 100644 documentation/html/classAutoChooser-members.html create mode 100644 documentation/html/classAutoChooser.html create mode 100644 documentation/html/classAutoCommand-members.html create mode 100644 documentation/html/classAutoCommand.html create mode 100644 documentation/html/classAutoCommand.png create mode 100644 documentation/html/classCommandController-members.html create mode 100644 documentation/html/classCommandController.html create mode 100644 documentation/html/classCustomEncoder-members.html create mode 100644 documentation/html/classCustomEncoder.html create mode 100644 documentation/html/classCustomEncoder.png create mode 100644 documentation/html/classDelayCommand-members.html create mode 100644 documentation/html/classDelayCommand.html create mode 100644 documentation/html/classDelayCommand.png create mode 100644 documentation/html/classDriveForwardCommand-members.html create mode 100644 documentation/html/classDriveForwardCommand.html create mode 100644 documentation/html/classDriveForwardCommand.png create mode 100644 documentation/html/classDriveStopCommand-members.html create mode 100644 documentation/html/classDriveStopCommand.html create mode 100644 documentation/html/classDriveStopCommand.png create mode 100644 documentation/html/classDriveToPointCommand-members.html create mode 100644 documentation/html/classDriveToPointCommand.html create mode 100644 documentation/html/classDriveToPointCommand.png create mode 100644 documentation/html/classFeedForward-members.html create mode 100644 documentation/html/classFeedForward.html create mode 100644 documentation/html/classFeedback-members.html create mode 100644 documentation/html/classFeedback.html create mode 100644 documentation/html/classFeedback.png create mode 100644 documentation/html/classFlywheel-members.html create mode 100644 documentation/html/classFlywheel.html create mode 100644 documentation/html/classFlywheelStopCommand-members.html create mode 100644 documentation/html/classFlywheelStopCommand.html create mode 100644 documentation/html/classFlywheelStopCommand.png create mode 100644 documentation/html/classFlywheelStopMotorsCommand-members.html create mode 100644 documentation/html/classFlywheelStopMotorsCommand.html create mode 100644 documentation/html/classFlywheelStopMotorsCommand.png create mode 100644 documentation/html/classFlywheelStopNonTasksCommand-members.html create mode 100644 documentation/html/classFlywheelStopNonTasksCommand.html create mode 100644 documentation/html/classFlywheelStopNonTasksCommand.png create mode 100644 documentation/html/classGenericAuto-members.html create mode 100644 documentation/html/classGenericAuto.html create mode 100644 documentation/html/classGraphDrawer-members.html create mode 100644 documentation/html/classGraphDrawer.html create mode 100644 documentation/html/classLift-members.html create mode 100644 documentation/html/classLift.html create mode 100644 documentation/html/classMecanumDrive-members.html create mode 100644 documentation/html/classMecanumDrive.html create mode 100644 documentation/html/classMotionController-members.html create mode 100644 documentation/html/classMotionController.html create mode 100644 documentation/html/classMotionController.png create mode 100644 documentation/html/classMovingAverage-members.html create mode 100644 documentation/html/classMovingAverage.html create mode 100644 documentation/html/classOdomSetPosition-members.html create mode 100644 documentation/html/classOdomSetPosition.html create mode 100644 documentation/html/classOdomSetPosition.png create mode 100644 documentation/html/classOdometry3Wheel-members.html create mode 100644 documentation/html/classOdometry3Wheel.html create mode 100644 documentation/html/classOdometry3Wheel.png create mode 100644 documentation/html/classOdometryBase-members.html create mode 100644 documentation/html/classOdometryBase.html create mode 100644 documentation/html/classOdometryBase.png create mode 100644 documentation/html/classOdometryTank-members.html create mode 100644 documentation/html/classOdometryTank.html create mode 100644 documentation/html/classOdometryTank.png create mode 100644 documentation/html/classPID-members.html create mode 100644 documentation/html/classPID.html create mode 100644 documentation/html/classPID.png create mode 100644 documentation/html/classPIDFF-members.html create mode 100644 documentation/html/classPIDFF.html create mode 100644 documentation/html/classPIDFF.png create mode 100644 documentation/html/classSpinRPMCommand-members.html create mode 100644 documentation/html/classSpinRPMCommand.html create mode 100644 documentation/html/classSpinRPMCommand.png create mode 100644 documentation/html/classTankDrive-members.html create mode 100644 documentation/html/classTankDrive.html create mode 100644 documentation/html/classTrapezoidProfile-members.html create mode 100644 documentation/html/classTrapezoidProfile.html create mode 100644 documentation/html/classTurnDegreesCommand-members.html create mode 100644 documentation/html/classTurnDegreesCommand.html create mode 100644 documentation/html/classTurnDegreesCommand.png create mode 100644 documentation/html/classTurnToHeadingCommand-members.html create mode 100644 documentation/html/classTurnToHeadingCommand.html create mode 100644 documentation/html/classTurnToHeadingCommand.png create mode 100644 documentation/html/classVector2D-members.html create mode 100644 documentation/html/classVector2D.html create mode 100644 documentation/html/classWaitUntilUpToSpeedCommand-members.html create mode 100644 documentation/html/classWaitUntilUpToSpeedCommand.html create mode 100644 documentation/html/classWaitUntilUpToSpeedCommand.png create mode 100644 documentation/html/classes.html create mode 100644 documentation/html/closed.png create mode 100644 documentation/html/command__controller_8h_source.html create mode 100644 documentation/html/custom__encoder_8h_source.html create mode 100644 documentation/html/delay__command_8h_source.html create mode 100644 documentation/html/dir_313caf1132e152dd9b58bea13a4052ca.html create mode 100644 documentation/html/dir_42a35307dcefecb9f25978d1dedb502f.html create mode 100644 documentation/html/dir_68267d1309a1af8e8297ef4c3efbcdba.html create mode 100644 documentation/html/dir_821002d4f10779a80d4fb17bc32f21f1.html create mode 100644 documentation/html/dir_883d6c53cd62ec60a5d421a7bc1a2629.html create mode 100644 documentation/html/dir_8e84b5daa2b3f33b7b3fb9ecedbe5637.html create mode 100644 documentation/html/dir_ca1fd9fa48e5fdc0ddfbf442e09c4dab.html create mode 100644 documentation/html/dir_d44c64559bbebec7f509842c48db8b23.html create mode 100644 documentation/html/dir_d9631e0f4b8929605c336e8f080acaa3.html create mode 100644 documentation/html/dir_e0729c835bcfebced7012c88d9b3a1d3.html create mode 100644 documentation/html/doc.png create mode 100644 documentation/html/docd.png create mode 100644 documentation/html/doxygen.css create mode 100644 documentation/html/doxygen.svg create mode 100644 documentation/html/drive__commands_8h_source.html create mode 100644 documentation/html/dynsections.js create mode 100644 documentation/html/feedback__base_8h_source.html create mode 100644 documentation/html/feedforward_8h_source.html create mode 100644 documentation/html/files.html create mode 100644 documentation/html/flywheel_8h_source.html create mode 100644 documentation/html/flywheel__commands_8h_source.html create mode 100644 documentation/html/folderclosed.png create mode 100644 documentation/html/folderopen.png create mode 100644 documentation/html/functions.html create mode 100644 documentation/html/functions_b.html create mode 100644 documentation/html/functions_c.html create mode 100644 documentation/html/functions_d.html create mode 100644 documentation/html/functions_e.html create mode 100644 documentation/html/functions_enum.html create mode 100644 documentation/html/functions_f.html create mode 100644 documentation/html/functions_func.html create mode 100644 documentation/html/functions_g.html create mode 100644 documentation/html/functions_h.html create mode 100644 documentation/html/functions_i.html create mode 100644 documentation/html/functions_k.html create mode 100644 documentation/html/functions_l.html create mode 100644 documentation/html/functions_m.html create mode 100644 documentation/html/functions_n.html create mode 100644 documentation/html/functions_o.html create mode 100644 documentation/html/functions_p.html create mode 100644 documentation/html/functions_r.html create mode 100644 documentation/html/functions_s.html create mode 100644 documentation/html/functions_t.html create mode 100644 documentation/html/functions_u.html create mode 100644 documentation/html/functions_v.html create mode 100644 documentation/html/functions_vars.html create mode 100644 documentation/html/functions_w.html create mode 100644 documentation/html/functions_x.html create mode 100644 documentation/html/functions_y.html create mode 100644 documentation/html/functions_z.html create mode 100644 documentation/html/generic__auto_8h_source.html create mode 100644 documentation/html/graph__drawer_8h_source.html create mode 100644 documentation/html/hierarchy.html create mode 100644 documentation/html/index.html create mode 100644 documentation/html/jquery.js create mode 100644 documentation/html/lift_8h_source.html create mode 100644 documentation/html/math__util_8h_source.html create mode 100644 documentation/html/md_README.html create mode 100644 documentation/html/mecanum__drive_8h_source.html create mode 100644 documentation/html/menu.js create mode 100644 documentation/html/menudata.js create mode 100644 documentation/html/motion__controller_8h_source.html create mode 100644 documentation/html/moving__average_8h_source.html create mode 100644 documentation/html/nav_f.png create mode 100644 documentation/html/nav_fd.png create mode 100644 documentation/html/nav_g.png create mode 100644 documentation/html/nav_h.png create mode 100644 documentation/html/nav_hd.png create mode 100644 documentation/html/odometry__3wheel_8h_source.html create mode 100644 documentation/html/odometry__base_8h_source.html create mode 100644 documentation/html/odometry__tank_8h_source.html create mode 100644 documentation/html/open.png create mode 100644 documentation/html/pages.html create mode 100644 documentation/html/pid_8h_source.html create mode 100644 documentation/html/pidff_8h_source.html create mode 100644 documentation/html/pure__pursuit_8h_source.html create mode 100644 documentation/html/robot__specs_8h_source.html create mode 100644 documentation/html/screen_8h_source.html create mode 100644 documentation/html/search/all_0.js create mode 100644 documentation/html/search/all_1.js create mode 100644 documentation/html/search/all_10.js create mode 100644 documentation/html/search/all_11.js create mode 100644 documentation/html/search/all_12.js create mode 100644 documentation/html/search/all_13.js create mode 100644 documentation/html/search/all_14.js create mode 100644 documentation/html/search/all_15.js create mode 100644 documentation/html/search/all_16.js create mode 100644 documentation/html/search/all_17.js create mode 100644 documentation/html/search/all_2.js create mode 100644 documentation/html/search/all_3.js create mode 100644 documentation/html/search/all_4.js create mode 100644 documentation/html/search/all_5.js create mode 100644 documentation/html/search/all_6.js create mode 100644 documentation/html/search/all_7.js create mode 100644 documentation/html/search/all_8.js create mode 100644 documentation/html/search/all_9.js create mode 100644 documentation/html/search/all_a.js create mode 100644 documentation/html/search/all_b.js create mode 100644 documentation/html/search/all_c.js create mode 100644 documentation/html/search/all_d.js create mode 100644 documentation/html/search/all_e.js create mode 100644 documentation/html/search/all_f.js create mode 100644 documentation/html/search/classes_0.js create mode 100644 documentation/html/search/classes_1.js create mode 100644 documentation/html/search/classes_2.js create mode 100644 documentation/html/search/classes_3.js create mode 100644 documentation/html/search/classes_4.js create mode 100644 documentation/html/search/classes_5.js create mode 100644 documentation/html/search/classes_6.js create mode 100644 documentation/html/search/classes_7.js create mode 100644 documentation/html/search/classes_8.js create mode 100644 documentation/html/search/classes_9.js create mode 100644 documentation/html/search/classes_a.js create mode 100644 documentation/html/search/classes_b.js create mode 100644 documentation/html/search/classes_c.js create mode 100644 documentation/html/search/classes_d.js create mode 100644 documentation/html/search/classes_e.js create mode 100644 documentation/html/search/classes_f.js create mode 100644 documentation/html/search/close.svg create mode 100644 documentation/html/search/enums_0.js create mode 100644 documentation/html/search/functions_0.js create mode 100644 documentation/html/search/functions_1.js create mode 100644 documentation/html/search/functions_10.js create mode 100644 documentation/html/search/functions_11.js create mode 100644 documentation/html/search/functions_12.js create mode 100644 documentation/html/search/functions_13.js create mode 100644 documentation/html/search/functions_2.js create mode 100644 documentation/html/search/functions_3.js create mode 100644 documentation/html/search/functions_4.js create mode 100644 documentation/html/search/functions_5.js create mode 100644 documentation/html/search/functions_6.js create mode 100644 documentation/html/search/functions_7.js create mode 100644 documentation/html/search/functions_8.js create mode 100644 documentation/html/search/functions_9.js create mode 100644 documentation/html/search/functions_a.js create mode 100644 documentation/html/search/functions_b.js create mode 100644 documentation/html/search/functions_c.js create mode 100644 documentation/html/search/functions_d.js create mode 100644 documentation/html/search/functions_e.js create mode 100644 documentation/html/search/functions_f.js create mode 100644 documentation/html/search/mag.svg create mode 100644 documentation/html/search/mag_d.svg create mode 100644 documentation/html/search/mag_sel.svg create mode 100644 documentation/html/search/mag_seld.svg create mode 100644 documentation/html/search/pages_0.js create mode 100644 documentation/html/search/search.css create mode 100644 documentation/html/search/search.js create mode 100644 documentation/html/search/searchdata.js create mode 100644 documentation/html/search/variables_0.js create mode 100644 documentation/html/search/variables_1.js create mode 100644 documentation/html/search/variables_10.js create mode 100644 documentation/html/search/variables_11.js create mode 100644 documentation/html/search/variables_12.js create mode 100644 documentation/html/search/variables_13.js create mode 100644 documentation/html/search/variables_14.js create mode 100644 documentation/html/search/variables_15.js create mode 100644 documentation/html/search/variables_2.js create mode 100644 documentation/html/search/variables_3.js create mode 100644 documentation/html/search/variables_4.js create mode 100644 documentation/html/search/variables_5.js create mode 100644 documentation/html/search/variables_6.js create mode 100644 documentation/html/search/variables_7.js create mode 100644 documentation/html/search/variables_8.js create mode 100644 documentation/html/search/variables_9.js create mode 100644 documentation/html/search/variables_a.js create mode 100644 documentation/html/search/variables_b.js create mode 100644 documentation/html/search/variables_c.js create mode 100644 documentation/html/search/variables_d.js create mode 100644 documentation/html/search/variables_e.js create mode 100644 documentation/html/search/variables_f.js create mode 100644 documentation/html/splitbar.png create mode 100644 documentation/html/splitbard.png create mode 100644 documentation/html/structAutoChooser_1_1entry__t-members.html create mode 100644 documentation/html/structAutoChooser_1_1entry__t.html create mode 100644 documentation/html/structFeedForward_1_1ff__config__t-members.html create mode 100644 documentation/html/structFeedForward_1_1ff__config__t.html create mode 100644 documentation/html/structLift_1_1lift__cfg__t-members.html create mode 100644 documentation/html/structLift_1_1lift__cfg__t.html create mode 100644 documentation/html/structMecanumDrive_1_1mecanumdrive__config__t-members.html create mode 100644 documentation/html/structMecanumDrive_1_1mecanumdrive__config__t.html create mode 100644 documentation/html/structMotionController_1_1m__profile__cfg__t-members.html create mode 100644 documentation/html/structMotionController_1_1m__profile__cfg__t.html create mode 100644 documentation/html/structOdometry3Wheel_1_1odometry3wheel__cfg__t-members.html create mode 100644 documentation/html/structOdometry3Wheel_1_1odometry3wheel__cfg__t.html create mode 100644 documentation/html/structPID_1_1pid__config__t-members.html create mode 100644 documentation/html/structPID_1_1pid__config__t.html create mode 100644 documentation/html/structPurePursuit_1_1hermite__point-members.html create mode 100644 documentation/html/structPurePursuit_1_1hermite__point.html create mode 100644 documentation/html/structPurePursuit_1_1spline-members.html create mode 100644 documentation/html/structPurePursuit_1_1spline.html create mode 100644 documentation/html/structVector2D_1_1point__t-members.html create mode 100644 documentation/html/structVector2D_1_1point__t.html create mode 100644 documentation/html/structmotion__t-members.html create mode 100644 documentation/html/structmotion__t.html create mode 100644 documentation/html/structposition__t-members.html create mode 100644 documentation/html/structposition__t.html create mode 100644 documentation/html/structrobot__specs__t-members.html create mode 100644 documentation/html/structrobot__specs__t.html create mode 100644 documentation/html/sync_off.png create mode 100644 documentation/html/sync_on.png create mode 100644 documentation/html/tab_a.png create mode 100644 documentation/html/tab_ad.png create mode 100644 documentation/html/tab_b.png create mode 100644 documentation/html/tab_bd.png create mode 100644 documentation/html/tab_h.png create mode 100644 documentation/html/tab_hd.png create mode 100644 documentation/html/tab_s.png create mode 100644 documentation/html/tab_sd.png create mode 100644 documentation/html/tabs.css create mode 100644 documentation/html/tank__drive_8h_source.html create mode 100644 documentation/html/trapezoid__profile_8h_source.html create mode 100644 documentation/html/vector2d_8h_source.html diff --git a/Doxyfile b/Doxyfile new file mode 100644 index 0000000..7aa3d2c --- /dev/null +++ b/Doxyfile @@ -0,0 +1,2736 @@ +# Doxyfile 1.9.6 + +# This file describes the settings to be used by the documentation system +# doxygen (www.doxygen.org) for a project. +# +# All text after a double hash (##) is considered a comment and is placed in +# front of the TAG it is preceding. +# +# All text after a single hash (#) is considered a comment and will be ignored. +# The format is: +# TAG = value [value, ...] +# For lists, items can also be appended using: +# TAG += value [value, ...] +# Values that contain spaces should be placed between quotes (\" \"). +# +# Note: +# +# Use doxygen to compare the used configuration file with the template +# configuration file: +# doxygen -x [configFile] +# Use doxygen to compare the used configuration file with the template +# configuration file without replacing the environment variables or CMake type +# replacement variables: +# doxygen -x_noenv [configFile] + +#--------------------------------------------------------------------------- +# Project related configuration options +#--------------------------------------------------------------------------- + +# This tag specifies the encoding used for all characters in the configuration +# file that follow. The default is UTF-8 which is also the encoding used for all +# text before the first occurrence of this tag. Doxygen uses libiconv (or the +# iconv built into libc) for the transcoding. See +# https://www.gnu.org/software/libiconv/ for the list of possible encodings. +# The default value is: UTF-8. + +DOXYFILE_ENCODING = UTF-8 + +# The PROJECT_NAME tag is a single word (or a sequence of words surrounded by +# double-quotes, unless you are using Doxywizard) that should identify the +# project for which the documentation is generated. This name is used in the +# title of most generated pages and in a few other places. +# The default value is: My Project. + +PROJECT_NAME = "RIT VEXU Core API" + +# The PROJECT_NUMBER tag can be used to enter a project or revision number. This +# could be handy for archiving the generated documentation or if some version +# control system is used. + +PROJECT_NUMBER = + +# Using the PROJECT_BRIEF tag one can provide an optional one line description +# for a project that appears at the top of each page and should give viewer a +# quick idea about the purpose of the project. Keep the description short. + +PROJECT_BRIEF = + +# With the PROJECT_LOGO tag one can specify a logo or an icon that is included +# in the documentation. The maximum height of the logo should not exceed 55 +# pixels and the maximum width should not exceed 200 pixels. Doxygen will copy +# the logo to the output directory. + +PROJECT_LOGO = + +# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) path +# into which the generated documentation will be written. If a relative path is +# entered, it will be relative to the location where doxygen was started. If +# left blank the current directory will be used. + +OUTPUT_DIRECTORY = documentation/ + +# If the CREATE_SUBDIRS tag is set to YES then doxygen will create up to 4096 +# sub-directories (in 2 levels) under the output directory of each output format +# and will distribute the generated files over these directories. Enabling this +# option can be useful when feeding doxygen a huge amount of source files, where +# putting all generated files in the same directory would otherwise causes +# performance problems for the file system. Adapt CREATE_SUBDIRS_LEVEL to +# control the number of sub-directories. +# The default value is: NO. + +CREATE_SUBDIRS = NO + +# Controls the number of sub-directories that will be created when +# CREATE_SUBDIRS tag is set to YES. Level 0 represents 16 directories, and every +# level increment doubles the number of directories, resulting in 4096 +# directories at level 8 which is the default and also the maximum value. The +# sub-directories are organized in 2 levels, the first level always has a fixed +# number of 16 directories. +# Minimum value: 0, maximum value: 8, default value: 8. +# This tag requires that the tag CREATE_SUBDIRS is set to YES. + +CREATE_SUBDIRS_LEVEL = 8 + +# If the ALLOW_UNICODE_NAMES tag is set to YES, doxygen will allow non-ASCII +# characters to appear in the names of generated files. If set to NO, non-ASCII +# characters will be escaped, for example _xE3_x81_x84 will be used for Unicode +# U+3044. +# The default value is: NO. + +ALLOW_UNICODE_NAMES = NO + +# The OUTPUT_LANGUAGE tag is used to specify the language in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all constant output in the proper language. +# Possible values are: Afrikaans, Arabic, Armenian, Brazilian, Bulgarian, +# Catalan, Chinese, Chinese-Traditional, Croatian, Czech, Danish, Dutch, English +# (United States), Esperanto, Farsi (Persian), Finnish, French, German, Greek, +# Hindi, Hungarian, Indonesian, Italian, Japanese, Japanese-en (Japanese with +# English messages), Korean, Korean-en (Korean with English messages), Latvian, +# Lithuanian, Macedonian, Norwegian, Persian (Farsi), Polish, Portuguese, +# Romanian, Russian, Serbian, Serbian-Cyrillic, Slovak, Slovene, Spanish, +# Swedish, Turkish, Ukrainian and Vietnamese. +# The default value is: English. + +OUTPUT_LANGUAGE = English + +# If the BRIEF_MEMBER_DESC tag is set to YES, doxygen will include brief member +# descriptions after the members that are listed in the file and class +# documentation (similar to Javadoc). Set to NO to disable this. +# The default value is: YES. + +BRIEF_MEMBER_DESC = YES + +# If the REPEAT_BRIEF tag is set to YES, doxygen will prepend the brief +# description of a member or function before the detailed description +# +# Note: If both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the +# brief descriptions will be completely suppressed. +# The default value is: YES. + +REPEAT_BRIEF = YES + +# This tag implements a quasi-intelligent brief description abbreviator that is +# used to form the text in various listings. Each string in this list, if found +# as the leading text of the brief description, will be stripped from the text +# and the result, after processing the whole list, is used as the annotated +# text. Otherwise, the brief description is used as-is. If left blank, the +# following values are used ($name is automatically replaced with the name of +# the entity):The $name class, The $name widget, The $name file, is, provides, +# specifies, contains, represents, a, an and the. + +ABBREVIATE_BRIEF = "The $name class" \ + "The $name widget" \ + "The $name file" \ + is \ + provides \ + specifies \ + contains \ + represents \ + a \ + an \ + the + +# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then +# doxygen will generate a detailed section even if there is only a brief +# description. +# The default value is: NO. + +ALWAYS_DETAILED_SEC = NO + +# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all +# inherited members of a class in the documentation of that class as if those +# members were ordinary class members. Constructors, destructors and assignment +# operators of the base classes will not be shown. +# The default value is: NO. + +INLINE_INHERITED_MEMB = NO + +# If the FULL_PATH_NAMES tag is set to YES, doxygen will prepend the full path +# before files name in the file list and in the header files. If set to NO the +# shortest path that makes the file name unique will be used +# The default value is: YES. + +FULL_PATH_NAMES = YES + +# The STRIP_FROM_PATH tag can be used to strip a user-defined part of the path. +# Stripping is only done if one of the specified strings matches the left-hand +# part of the path. The tag can be used to show relative paths in the file list. +# If left blank the directory from which doxygen is run is used as the path to +# strip. +# +# Note that you can specify absolute paths here, but also relative paths, which +# will be relative from the directory where doxygen is started. +# This tag requires that the tag FULL_PATH_NAMES is set to YES. + +STRIP_FROM_PATH = + +# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of the +# path mentioned in the documentation of a class, which tells the reader which +# header file to include in order to use a class. If left blank only the name of +# the header file containing the class definition is used. Otherwise one should +# specify the list of include paths that are normally passed to the compiler +# using the -I flag. + +STRIP_FROM_INC_PATH = + +# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter (but +# less readable) file names. This can be useful is your file systems doesn't +# support long names like on DOS, Mac, or CD-ROM. +# The default value is: NO. + +SHORT_NAMES = NO + +# If the JAVADOC_AUTOBRIEF tag is set to YES then doxygen will interpret the +# first line (until the first dot) of a Javadoc-style comment as the brief +# description. If set to NO, the Javadoc-style will behave just like regular Qt- +# style comments (thus requiring an explicit @brief command for a brief +# description.) +# The default value is: NO. + +JAVADOC_AUTOBRIEF = NO + +# If the JAVADOC_BANNER tag is set to YES then doxygen will interpret a line +# such as +# /*************** +# as being the beginning of a Javadoc-style comment "banner". If set to NO, the +# Javadoc-style will behave just like regular comments and it will not be +# interpreted by doxygen. +# The default value is: NO. + +JAVADOC_BANNER = NO + +# If the QT_AUTOBRIEF tag is set to YES then doxygen will interpret the first +# line (until the first dot) of a Qt-style comment as the brief description. If +# set to NO, the Qt-style will behave just like regular Qt-style comments (thus +# requiring an explicit \brief command for a brief description.) +# The default value is: NO. + +QT_AUTOBRIEF = NO + +# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make doxygen treat a +# multi-line C++ special comment block (i.e. a block of //! or /// comments) as +# a brief description. This used to be the default behavior. The new default is +# to treat a multi-line C++ comment block as a detailed description. Set this +# tag to YES if you prefer the old behavior instead. +# +# Note that setting this tag to YES also means that rational rose comments are +# not recognized any more. +# The default value is: NO. + +MULTILINE_CPP_IS_BRIEF = NO + +# By default Python docstrings are displayed as preformatted text and doxygen's +# special commands cannot be used. By setting PYTHON_DOCSTRING to NO the +# doxygen's special commands can be used and the contents of the docstring +# documentation blocks is shown as doxygen documentation. +# The default value is: YES. + +PYTHON_DOCSTRING = YES + +# If the INHERIT_DOCS tag is set to YES then an undocumented member inherits the +# documentation from any documented member that it re-implements. +# The default value is: YES. + +INHERIT_DOCS = YES + +# If the SEPARATE_MEMBER_PAGES tag is set to YES then doxygen will produce a new +# page for each member. If set to NO, the documentation of a member will be part +# of the file/class/namespace that contains it. +# The default value is: NO. + +SEPARATE_MEMBER_PAGES = NO + +# The TAB_SIZE tag can be used to set the number of spaces in a tab. Doxygen +# uses this value to replace tabs by spaces in code fragments. +# Minimum value: 1, maximum value: 16, default value: 4. + +TAB_SIZE = 4 + +# This tag can be used to specify a number of aliases that act as commands in +# the documentation. An alias has the form: +# name=value +# For example adding +# "sideeffect=@par Side Effects:^^" +# will allow you to put the command \sideeffect (or @sideeffect) in the +# documentation, which will result in a user-defined paragraph with heading +# "Side Effects:". Note that you cannot put \n's in the value part of an alias +# to insert newlines (in the resulting output). You can put ^^ in the value part +# of an alias to insert a newline as if a physical newline was in the original +# file. When you need a literal { or } or , in the value part of an alias you +# have to escape them by means of a backslash (\), this can lead to conflicts +# with the commands \{ and \} for these it is advised to use the version @{ and +# @} or use a double escape (\\{ and \\}) + +ALIASES = + +# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C sources +# only. Doxygen will then generate output that is more tailored for C. For +# instance, some of the names that are used will be different. The list of all +# members will be omitted, etc. +# The default value is: NO. + +OPTIMIZE_OUTPUT_FOR_C = NO + +# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java or +# Python sources only. Doxygen will then generate output that is more tailored +# for that language. For instance, namespaces will be presented as packages, +# qualified scopes will look different, etc. +# The default value is: NO. + +OPTIMIZE_OUTPUT_JAVA = NO + +# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran +# sources. Doxygen will then generate output that is tailored for Fortran. +# The default value is: NO. + +OPTIMIZE_FOR_FORTRAN = NO + +# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL +# sources. Doxygen will then generate output that is tailored for VHDL. +# The default value is: NO. + +OPTIMIZE_OUTPUT_VHDL = NO + +# Set the OPTIMIZE_OUTPUT_SLICE tag to YES if your project consists of Slice +# sources only. Doxygen will then generate output that is more tailored for that +# language. For instance, namespaces will be presented as modules, types will be +# separated into more groups, etc. +# The default value is: NO. + +OPTIMIZE_OUTPUT_SLICE = NO + +# Doxygen selects the parser to use depending on the extension of the files it +# parses. With this tag you can assign which parser to use for a given +# extension. Doxygen has a built-in mapping, but you can override or extend it +# using this tag. The format is ext=language, where ext is a file extension, and +# language is one of the parsers supported by doxygen: IDL, Java, JavaScript, +# Csharp (C#), C, C++, Lex, D, PHP, md (Markdown), Objective-C, Python, Slice, +# VHDL, Fortran (fixed format Fortran: FortranFixed, free formatted Fortran: +# FortranFree, unknown formatted Fortran: Fortran. In the later case the parser +# tries to guess whether the code is fixed or free formatted code, this is the +# default for Fortran type files). For instance to make doxygen treat .inc files +# as Fortran files (default is PHP), and .f files as C (default is Fortran), +# use: inc=Fortran f=C. +# +# Note: For files without extension you can use no_extension as a placeholder. +# +# Note that for custom extensions you also need to set FILE_PATTERNS otherwise +# the files are not read by doxygen. When specifying no_extension you should add +# * to the FILE_PATTERNS. +# +# Note see also the list of default file extension mappings. + +EXTENSION_MAPPING = + +# If the MARKDOWN_SUPPORT tag is enabled then doxygen pre-processes all comments +# according to the Markdown format, which allows for more readable +# documentation. See https://daringfireball.net/projects/markdown/ for details. +# The output of markdown processing is further processed by doxygen, so you can +# mix doxygen, HTML, and XML commands with Markdown formatting. Disable only in +# case of backward compatibilities issues. +# The default value is: YES. + +MARKDOWN_SUPPORT = YES + +# When the TOC_INCLUDE_HEADINGS tag is set to a non-zero value, all headings up +# to that level are automatically included in the table of contents, even if +# they do not have an id attribute. +# Note: This feature currently applies only to Markdown headings. +# Minimum value: 0, maximum value: 99, default value: 5. +# This tag requires that the tag MARKDOWN_SUPPORT is set to YES. + +TOC_INCLUDE_HEADINGS = 5 + +# When enabled doxygen tries to link words that correspond to documented +# classes, or namespaces to their corresponding documentation. Such a link can +# be prevented in individual cases by putting a % sign in front of the word or +# globally by setting AUTOLINK_SUPPORT to NO. +# The default value is: YES. + +AUTOLINK_SUPPORT = YES + +# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want +# to include (a tag file for) the STL sources as input, then you should set this +# tag to YES in order to let doxygen match functions declarations and +# definitions whose arguments contain STL classes (e.g. func(std::string); +# versus func(std::string) {}). This also make the inheritance and collaboration +# diagrams that involve STL classes more complete and accurate. +# The default value is: NO. + +BUILTIN_STL_SUPPORT = NO + +# If you use Microsoft's C++/CLI language, you should set this option to YES to +# enable parsing support. +# The default value is: NO. + +CPP_CLI_SUPPORT = NO + +# Set the SIP_SUPPORT tag to YES if your project consists of sip (see: +# https://www.riverbankcomputing.com/software/sip/intro) sources only. Doxygen +# will parse them like normal C++ but will assume all classes use public instead +# of private inheritance when no explicit protection keyword is present. +# The default value is: NO. + +SIP_SUPPORT = NO + +# For Microsoft's IDL there are propget and propput attributes to indicate +# getter and setter methods for a property. Setting this option to YES will make +# doxygen to replace the get and set methods by a property in the documentation. +# This will only work if the methods are indeed getting or setting a simple +# type. If this is not the case, or you want to show the methods anyway, you +# should set this option to NO. +# The default value is: YES. + +IDL_PROPERTY_SUPPORT = YES + +# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC +# tag is set to YES then doxygen will reuse the documentation of the first +# member in the group (if any) for the other members of the group. By default +# all members of a group must be documented explicitly. +# The default value is: NO. + +DISTRIBUTE_GROUP_DOC = NO + +# If one adds a struct or class to a group and this option is enabled, then also +# any nested class or struct is added to the same group. By default this option +# is disabled and one has to add nested compounds explicitly via \ingroup. +# The default value is: NO. + +GROUP_NESTED_COMPOUNDS = NO + +# Set the SUBGROUPING tag to YES to allow class member groups of the same type +# (for instance a group of public functions) to be put as a subgroup of that +# type (e.g. under the Public Functions section). Set it to NO to prevent +# subgrouping. Alternatively, this can be done per class using the +# \nosubgrouping command. +# The default value is: YES. + +SUBGROUPING = YES + +# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and unions +# are shown inside the group in which they are included (e.g. using \ingroup) +# instead of on a separate page (for HTML and Man pages) or section (for LaTeX +# and RTF). +# +# Note that this feature does not work in combination with +# SEPARATE_MEMBER_PAGES. +# The default value is: NO. + +INLINE_GROUPED_CLASSES = NO + +# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and unions +# with only public data fields or simple typedef fields will be shown inline in +# the documentation of the scope in which they are defined (i.e. file, +# namespace, or group documentation), provided this scope is documented. If set +# to NO, structs, classes, and unions are shown on a separate page (for HTML and +# Man pages) or section (for LaTeX and RTF). +# The default value is: NO. + +INLINE_SIMPLE_STRUCTS = NO + +# When TYPEDEF_HIDES_STRUCT tag is enabled, a typedef of a struct, union, or +# enum is documented as struct, union, or enum with the name of the typedef. So +# typedef struct TypeS {} TypeT, will appear in the documentation as a struct +# with name TypeT. When disabled the typedef will appear as a member of a file, +# namespace, or class. And the struct will be named TypeS. This can typically be +# useful for C code in case the coding convention dictates that all compound +# types are typedef'ed and only the typedef is referenced, never the tag name. +# The default value is: NO. + +TYPEDEF_HIDES_STRUCT = NO + +# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This +# cache is used to resolve symbols given their name and scope. Since this can be +# an expensive process and often the same symbol appears multiple times in the +# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small +# doxygen will become slower. If the cache is too large, memory is wasted. The +# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range +# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536 +# symbols. At the end of a run doxygen will report the cache usage and suggest +# the optimal cache size from a speed point of view. +# Minimum value: 0, maximum value: 9, default value: 0. + +LOOKUP_CACHE_SIZE = 0 + +# The NUM_PROC_THREADS specifies the number of threads doxygen is allowed to use +# during processing. When set to 0 doxygen will based this on the number of +# cores available in the system. You can set it explicitly to a value larger +# than 0 to get more control over the balance between CPU load and processing +# speed. At this moment only the input processing can be done using multiple +# threads. Since this is still an experimental feature the default is set to 1, +# which effectively disables parallel processing. Please report any issues you +# encounter. Generating dot graphs in parallel is controlled by the +# DOT_NUM_THREADS setting. +# Minimum value: 0, maximum value: 32, default value: 1. + +NUM_PROC_THREADS = 1 + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- + +# If the EXTRACT_ALL tag is set to YES, doxygen will assume all entities in +# documentation are documented, even if no documentation was available. Private +# class members and static file members will be hidden unless the +# EXTRACT_PRIVATE respectively EXTRACT_STATIC tags are set to YES. +# Note: This will also disable the warnings about undocumented members that are +# normally produced when WARNINGS is set to YES. +# The default value is: NO. + +EXTRACT_ALL = NO + +# If the EXTRACT_PRIVATE tag is set to YES, all private members of a class will +# be included in the documentation. +# The default value is: NO. + +EXTRACT_PRIVATE = NO + +# If the EXTRACT_PRIV_VIRTUAL tag is set to YES, documented private virtual +# methods of a class will be included in the documentation. +# The default value is: NO. + +EXTRACT_PRIV_VIRTUAL = NO + +# If the EXTRACT_PACKAGE tag is set to YES, all members with package or internal +# scope will be included in the documentation. +# The default value is: NO. + +EXTRACT_PACKAGE = NO + +# If the EXTRACT_STATIC tag is set to YES, all static members of a file will be +# included in the documentation. +# The default value is: NO. + +EXTRACT_STATIC = NO + +# If the EXTRACT_LOCAL_CLASSES tag is set to YES, classes (and structs) defined +# locally in source files will be included in the documentation. If set to NO, +# only classes defined in header files are included. Does not have any effect +# for Java sources. +# The default value is: YES. + +EXTRACT_LOCAL_CLASSES = YES + +# This flag is only useful for Objective-C code. If set to YES, local methods, +# which are defined in the implementation section but not in the interface are +# included in the documentation. If set to NO, only methods in the interface are +# included. +# The default value is: NO. + +EXTRACT_LOCAL_METHODS = NO + +# If this flag is set to YES, the members of anonymous namespaces will be +# extracted and appear in the documentation as a namespace called +# 'anonymous_namespace{file}', where file will be replaced with the base name of +# the file that contains the anonymous namespace. By default anonymous namespace +# are hidden. +# The default value is: NO. + +EXTRACT_ANON_NSPACES = NO + +# If this flag is set to YES, the name of an unnamed parameter in a declaration +# will be determined by the corresponding definition. By default unnamed +# parameters remain unnamed in the output. +# The default value is: YES. + +RESOLVE_UNNAMED_PARAMS = YES + +# If the HIDE_UNDOC_MEMBERS tag is set to YES, doxygen will hide all +# undocumented members inside documented classes or files. If set to NO these +# members will be included in the various overviews, but no documentation +# section is generated. This option has no effect if EXTRACT_ALL is enabled. +# The default value is: NO. + +HIDE_UNDOC_MEMBERS = NO + +# If the HIDE_UNDOC_CLASSES tag is set to YES, doxygen will hide all +# undocumented classes that are normally visible in the class hierarchy. If set +# to NO, these classes will be included in the various overviews. This option +# will also hide undocumented C++ concepts if enabled. This option has no effect +# if EXTRACT_ALL is enabled. +# The default value is: NO. + +HIDE_UNDOC_CLASSES = NO + +# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, doxygen will hide all friend +# declarations. If set to NO, these declarations will be included in the +# documentation. +# The default value is: NO. + +HIDE_FRIEND_COMPOUNDS = NO + +# If the HIDE_IN_BODY_DOCS tag is set to YES, doxygen will hide any +# documentation blocks found inside the body of a function. If set to NO, these +# blocks will be appended to the function's detailed documentation block. +# The default value is: NO. + +HIDE_IN_BODY_DOCS = NO + +# The INTERNAL_DOCS tag determines if documentation that is typed after a +# \internal command is included. If the tag is set to NO then the documentation +# will be excluded. Set it to YES to include the internal documentation. +# The default value is: NO. + +INTERNAL_DOCS = NO + +# With the correct setting of option CASE_SENSE_NAMES doxygen will better be +# able to match the capabilities of the underlying filesystem. In case the +# filesystem is case sensitive (i.e. it supports files in the same directory +# whose names only differ in casing), the option must be set to YES to properly +# deal with such files in case they appear in the input. For filesystems that +# are not case sensitive the option should be set to NO to properly deal with +# output files written for symbols that only differ in casing, such as for two +# classes, one named CLASS and the other named Class, and to also support +# references to files without having to specify the exact matching casing. On +# Windows (including Cygwin) and MacOS, users should typically set this option +# to NO, whereas on Linux or other Unix flavors it should typically be set to +# YES. +# Possible values are: SYSTEM, NO and YES. +# The default value is: SYSTEM. + +CASE_SENSE_NAMES = SYSTEM + +# If the HIDE_SCOPE_NAMES tag is set to NO then doxygen will show members with +# their full class and namespace scopes in the documentation. If set to YES, the +# scope will be hidden. +# The default value is: NO. + +HIDE_SCOPE_NAMES = NO + +# If the HIDE_COMPOUND_REFERENCE tag is set to NO (default) then doxygen will +# append additional text to a page's title, such as Class Reference. If set to +# YES the compound reference will be hidden. +# The default value is: NO. + +HIDE_COMPOUND_REFERENCE= NO + +# If the SHOW_HEADERFILE tag is set to YES then the documentation for a class +# will show which file needs to be included to use the class. +# The default value is: YES. + +SHOW_HEADERFILE = YES + +# If the SHOW_INCLUDE_FILES tag is set to YES then doxygen will put a list of +# the files that are included by a file in the documentation of that file. +# The default value is: YES. + +SHOW_INCLUDE_FILES = YES + +# If the SHOW_GROUPED_MEMB_INC tag is set to YES then Doxygen will add for each +# grouped member an include statement to the documentation, telling the reader +# which file to include in order to use the member. +# The default value is: NO. + +SHOW_GROUPED_MEMB_INC = NO + +# If the FORCE_LOCAL_INCLUDES tag is set to YES then doxygen will list include +# files with double quotes in the documentation rather than with sharp brackets. +# The default value is: NO. + +FORCE_LOCAL_INCLUDES = NO + +# If the INLINE_INFO tag is set to YES then a tag [inline] is inserted in the +# documentation for inline members. +# The default value is: YES. + +INLINE_INFO = YES + +# If the SORT_MEMBER_DOCS tag is set to YES then doxygen will sort the +# (detailed) documentation of file and class members alphabetically by member +# name. If set to NO, the members will appear in declaration order. +# The default value is: YES. + +SORT_MEMBER_DOCS = YES + +# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the brief +# descriptions of file, namespace and class members alphabetically by member +# name. If set to NO, the members will appear in declaration order. Note that +# this will also influence the order of the classes in the class list. +# The default value is: NO. + +SORT_BRIEF_DOCS = NO + +# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the +# (brief and detailed) documentation of class members so that constructors and +# destructors are listed first. If set to NO the constructors will appear in the +# respective orders defined by SORT_BRIEF_DOCS and SORT_MEMBER_DOCS. +# Note: If SORT_BRIEF_DOCS is set to NO this option is ignored for sorting brief +# member documentation. +# Note: If SORT_MEMBER_DOCS is set to NO this option is ignored for sorting +# detailed member documentation. +# The default value is: NO. + +SORT_MEMBERS_CTORS_1ST = NO + +# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the hierarchy +# of group names into alphabetical order. If set to NO the group names will +# appear in their defined order. +# The default value is: NO. + +SORT_GROUP_NAMES = NO + +# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be sorted by +# fully-qualified names, including namespaces. If set to NO, the class list will +# be sorted only by class name, not including the namespace part. +# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. +# Note: This option applies only to the class list, not to the alphabetical +# list. +# The default value is: NO. + +SORT_BY_SCOPE_NAME = NO + +# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to do proper +# type resolution of all parameters of a function it will reject a match between +# the prototype and the implementation of a member function even if there is +# only one candidate or it is obvious which candidate to choose by doing a +# simple string match. By disabling STRICT_PROTO_MATCHING doxygen will still +# accept a match between prototype and implementation in such cases. +# The default value is: NO. + +STRICT_PROTO_MATCHING = NO + +# The GENERATE_TODOLIST tag can be used to enable (YES) or disable (NO) the todo +# list. This list is created by putting \todo commands in the documentation. +# The default value is: YES. + +GENERATE_TODOLIST = YES + +# The GENERATE_TESTLIST tag can be used to enable (YES) or disable (NO) the test +# list. This list is created by putting \test commands in the documentation. +# The default value is: YES. + +GENERATE_TESTLIST = YES + +# The GENERATE_BUGLIST tag can be used to enable (YES) or disable (NO) the bug +# list. This list is created by putting \bug commands in the documentation. +# The default value is: YES. + +GENERATE_BUGLIST = YES + +# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or disable (NO) +# the deprecated list. This list is created by putting \deprecated commands in +# the documentation. +# The default value is: YES. + +GENERATE_DEPRECATEDLIST= YES + +# The ENABLED_SECTIONS tag can be used to enable conditional documentation +# sections, marked by \if ... \endif and \cond +# ... \endcond blocks. + +ENABLED_SECTIONS = + +# The MAX_INITIALIZER_LINES tag determines the maximum number of lines that the +# initial value of a variable or macro / define can have for it to appear in the +# documentation. If the initializer consists of more lines than specified here +# it will be hidden. Use a value of 0 to hide initializers completely. The +# appearance of the value of individual variables and macros / defines can be +# controlled using \showinitializer or \hideinitializer command in the +# documentation regardless of this setting. +# Minimum value: 0, maximum value: 10000, default value: 30. + +MAX_INITIALIZER_LINES = 30 + +# Set the SHOW_USED_FILES tag to NO to disable the list of files generated at +# the bottom of the documentation of classes and structs. If set to YES, the +# list will mention the files that were used to generate the documentation. +# The default value is: YES. + +SHOW_USED_FILES = YES + +# Set the SHOW_FILES tag to NO to disable the generation of the Files page. This +# will remove the Files entry from the Quick Index and from the Folder Tree View +# (if specified). +# The default value is: YES. + +SHOW_FILES = YES + +# Set the SHOW_NAMESPACES tag to NO to disable the generation of the Namespaces +# page. This will remove the Namespaces entry from the Quick Index and from the +# Folder Tree View (if specified). +# The default value is: YES. + +SHOW_NAMESPACES = YES + +# The FILE_VERSION_FILTER tag can be used to specify a program or script that +# doxygen should invoke to get the current version for each file (typically from +# the version control system). Doxygen will invoke the program by executing (via +# popen()) the command command input-file, where command is the value of the +# FILE_VERSION_FILTER tag, and input-file is the name of an input file provided +# by doxygen. Whatever the program writes to standard output is used as the file +# version. For an example see the documentation. + +FILE_VERSION_FILTER = + +# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed +# by doxygen. The layout file controls the global structure of the generated +# output files in an output format independent way. To create the layout file +# that represents doxygen's defaults, run doxygen with the -l option. You can +# optionally specify a file name after the option, if omitted DoxygenLayout.xml +# will be used as the name of the layout file. See also section "Changing the +# layout of pages" for information. +# +# Note that if you run doxygen from a directory containing a file called +# DoxygenLayout.xml, doxygen will parse it automatically even if the LAYOUT_FILE +# tag is left empty. + +LAYOUT_FILE = + +# The CITE_BIB_FILES tag can be used to specify one or more bib files containing +# the reference definitions. This must be a list of .bib files. The .bib +# extension is automatically appended if omitted. This requires the bibtex tool +# to be installed. See also https://en.wikipedia.org/wiki/BibTeX for more info. +# For LaTeX the style of the bibliography can be controlled using +# LATEX_BIB_STYLE. To use this feature you need bibtex and perl available in the +# search path. See also \cite for info how to create references. + +CITE_BIB_FILES = + +#--------------------------------------------------------------------------- +# Configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +# The QUIET tag can be used to turn on/off the messages that are generated to +# standard output by doxygen. If QUIET is set to YES this implies that the +# messages are off. +# The default value is: NO. + +QUIET = NO + +# The WARNINGS tag can be used to turn on/off the warning messages that are +# generated to standard error (stderr) by doxygen. If WARNINGS is set to YES +# this implies that the warnings are on. +# +# Tip: Turn warnings on while writing the documentation. +# The default value is: YES. + +WARNINGS = YES + +# If the WARN_IF_UNDOCUMENTED tag is set to YES then doxygen will generate +# warnings for undocumented members. If EXTRACT_ALL is set to YES then this flag +# will automatically be disabled. +# The default value is: YES. + +WARN_IF_UNDOCUMENTED = YES + +# If the WARN_IF_DOC_ERROR tag is set to YES, doxygen will generate warnings for +# potential errors in the documentation, such as documenting some parameters in +# a documented function twice, or documenting parameters that don't exist or +# using markup commands wrongly. +# The default value is: YES. + +WARN_IF_DOC_ERROR = YES + +# If WARN_IF_INCOMPLETE_DOC is set to YES, doxygen will warn about incomplete +# function parameter documentation. If set to NO, doxygen will accept that some +# parameters have no documentation without warning. +# The default value is: YES. + +WARN_IF_INCOMPLETE_DOC = YES + +# This WARN_NO_PARAMDOC option can be enabled to get warnings for functions that +# are documented, but have no documentation for their parameters or return +# value. If set to NO, doxygen will only warn about wrong parameter +# documentation, but not about the absence of documentation. If EXTRACT_ALL is +# set to YES then this flag will automatically be disabled. See also +# WARN_IF_INCOMPLETE_DOC +# The default value is: NO. + +WARN_NO_PARAMDOC = NO + +# If WARN_IF_UNDOC_ENUM_VAL option is set to YES, doxygen will warn about +# undocumented enumeration values. If set to NO, doxygen will accept +# undocumented enumeration values. If EXTRACT_ALL is set to YES then this flag +# will automatically be disabled. +# The default value is: NO. + +WARN_IF_UNDOC_ENUM_VAL = NO + +# If the WARN_AS_ERROR tag is set to YES then doxygen will immediately stop when +# a warning is encountered. If the WARN_AS_ERROR tag is set to FAIL_ON_WARNINGS +# then doxygen will continue running as if WARN_AS_ERROR tag is set to NO, but +# at the end of the doxygen process doxygen will return with a non-zero status. +# Possible values are: NO, YES and FAIL_ON_WARNINGS. +# The default value is: NO. + +WARN_AS_ERROR = NO + +# The WARN_FORMAT tag determines the format of the warning messages that doxygen +# can produce. The string should contain the $file, $line, and $text tags, which +# will be replaced by the file and line number from which the warning originated +# and the warning text. Optionally the format may contain $version, which will +# be replaced by the version of the file (if it could be obtained via +# FILE_VERSION_FILTER) +# See also: WARN_LINE_FORMAT +# The default value is: $file:$line: $text. + +WARN_FORMAT = "$file:$line: $text" + +# In the $text part of the WARN_FORMAT command it is possible that a reference +# to a more specific place is given. To make it easier to jump to this place +# (outside of doxygen) the user can define a custom "cut" / "paste" string. +# Example: +# WARN_LINE_FORMAT = "'vi $file +$line'" +# See also: WARN_FORMAT +# The default value is: at line $line of file $file. + +WARN_LINE_FORMAT = "at line $line of file $file" + +# The WARN_LOGFILE tag can be used to specify a file to which warning and error +# messages should be written. If left blank the output is written to standard +# error (stderr). In case the file specified cannot be opened for writing the +# warning and error messages are written to standard error. When as file - is +# specified the warning and error messages are written to standard output +# (stdout). + +WARN_LOGFILE = + +#--------------------------------------------------------------------------- +# Configuration options related to the input files +#--------------------------------------------------------------------------- + +# The INPUT tag is used to specify the files and/or directories that contain +# documented source files. You may enter file names like myfile.cpp or +# directories like /usr/src/myproject. Separate the files or directories with +# spaces. See also FILE_PATTERNS and EXTENSION_MAPPING +# Note: If this tag is empty the current directory is searched. + +INPUT = + +# This tag can be used to specify the character encoding of the source files +# that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses +# libiconv (or the iconv built into libc) for the transcoding. See the libiconv +# documentation (see: +# https://www.gnu.org/software/libiconv/) for the list of possible encodings. +# See also: INPUT_FILE_ENCODING +# The default value is: UTF-8. + +INPUT_ENCODING = UTF-8 + +# This tag can be used to specify the character encoding of the source files +# that doxygen parses The INPUT_FILE_ENCODING tag can be used to specify +# character encoding on a per file pattern basis. Doxygen will compare the file +# name with each pattern and apply the encoding instead of the default +# INPUT_ENCODING) if there is a match. The character encodings are a list of the +# form: pattern=encoding (like *.php=ISO-8859-1). See cfg_input_encoding +# "INPUT_ENCODING" for further information on supported encodings. + +INPUT_FILE_ENCODING = + +# If the value of the INPUT tag contains directories, you can use the +# FILE_PATTERNS tag to specify one or more wildcard patterns (like *.cpp and +# *.h) to filter out the source-files in the directories. +# +# Note that for custom extensions or not directly supported extensions you also +# need to set EXTENSION_MAPPING for the extension otherwise the files are not +# read by doxygen. +# +# Note the list of default checked file patterns might differ from the list of +# default file extension mappings. +# +# If left blank the following patterns are tested:*.c, *.cc, *.cxx, *.cpp, +# *.c++, *.java, *.ii, *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h, +# *.hh, *.hxx, *.hpp, *.h++, *.l, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, +# *.inc, *.m, *.markdown, *.md, *.mm, *.dox (to be provided as doxygen C +# comment), *.py, *.pyw, *.f90, *.f95, *.f03, *.f08, *.f18, *.f, *.for, *.vhd, +# *.vhdl, *.ucf, *.qsf and *.ice. + +FILE_PATTERNS = *.c \ + *.cc \ + *.cxx \ + *.cpp \ + *.c++ \ + *.java \ + *.ii \ + *.ixx \ + *.ipp \ + *.i++ \ + *.inl \ + *.idl \ + *.ddl \ + *.odl \ + *.h \ + *.hh \ + *.hxx \ + *.hpp \ + *.h++ \ + *.l \ + *.cs \ + *.d \ + *.php \ + *.php4 \ + *.php5 \ + *.phtml \ + *.inc \ + *.m \ + *.markdown \ + *.md \ + *.mm \ + *.dox \ + *.py \ + *.pyw \ + *.f90 \ + *.f95 \ + *.f03 \ + *.f08 \ + *.f18 \ + *.f \ + *.for \ + *.vhd \ + *.vhdl \ + *.ucf \ + *.qsf \ + *.ice + +# The RECURSIVE tag can be used to specify whether or not subdirectories should +# be searched for input files as well. +# The default value is: NO. + +RECURSIVE = YES + +# The EXCLUDE tag can be used to specify files and/or directories that should be +# excluded from the INPUT source files. This way you can easily exclude a +# subdirectory from a directory tree whose root is specified with the INPUT tag. +# +# Note that relative paths are relative to the directory from which doxygen is +# run. + +EXCLUDE = + +# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or +# directories that are symbolic links (a Unix file system feature) are excluded +# from the input. +# The default value is: NO. + +EXCLUDE_SYMLINKS = NO + +# If the value of the INPUT tag contains directories, you can use the +# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude +# certain files from those directories. +# +# Note that the wildcards are matched against the file with absolute path, so to +# exclude all test directories for example use the pattern */test/* + +EXCLUDE_PATTERNS = + +# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names +# (namespaces, classes, functions, etc.) that should be excluded from the +# output. The symbol name can be a fully qualified name, a word, or if the +# wildcard * is used, a substring. Examples: ANamespace, AClass, +# ANamespace::AClass, ANamespace::*Test +# +# Note that the wildcards are matched against the file with absolute path, so to +# exclude all test directories use the pattern */test/* + +EXCLUDE_SYMBOLS = + +# The EXAMPLE_PATH tag can be used to specify one or more files or directories +# that contain example code fragments that are included (see the \include +# command). + +EXAMPLE_PATH = + +# If the value of the EXAMPLE_PATH tag contains directories, you can use the +# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp and +# *.h) to filter out the source-files in the directories. If left blank all +# files are included. + +EXAMPLE_PATTERNS = * + +# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be +# searched for input files to be used with the \include or \dontinclude commands +# irrespective of the value of the RECURSIVE tag. +# The default value is: NO. + +EXAMPLE_RECURSIVE = NO + +# The IMAGE_PATH tag can be used to specify one or more files or directories +# that contain images that are to be included in the documentation (see the +# \image command). + +IMAGE_PATH = + +# The INPUT_FILTER tag can be used to specify a program that doxygen should +# invoke to filter for each input file. Doxygen will invoke the filter program +# by executing (via popen()) the command: +# +# +# +# where is the value of the INPUT_FILTER tag, and is the +# name of an input file. Doxygen will then use the output that the filter +# program writes to standard output. If FILTER_PATTERNS is specified, this tag +# will be ignored. +# +# Note that the filter must not add or remove lines; it is applied before the +# code is scanned, but not when the output code is generated. If lines are added +# or removed, the anchors will not be placed correctly. +# +# Note that doxygen will use the data processed and written to standard output +# for further processing, therefore nothing else, like debug statements or used +# commands (so in case of a Windows batch file always use @echo OFF), should be +# written to standard output. +# +# Note that for custom extensions or not directly supported extensions you also +# need to set EXTENSION_MAPPING for the extension otherwise the files are not +# properly processed by doxygen. + +INPUT_FILTER = + +# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern +# basis. Doxygen will compare the file name with each pattern and apply the +# filter if there is a match. The filters are a list of the form: pattern=filter +# (like *.cpp=my_cpp_filter). See INPUT_FILTER for further information on how +# filters are used. If the FILTER_PATTERNS tag is empty or if none of the +# patterns match the file name, INPUT_FILTER is applied. +# +# Note that for custom extensions or not directly supported extensions you also +# need to set EXTENSION_MAPPING for the extension otherwise the files are not +# properly processed by doxygen. + +FILTER_PATTERNS = + +# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using +# INPUT_FILTER) will also be used to filter the input files that are used for +# producing the source files to browse (i.e. when SOURCE_BROWSER is set to YES). +# The default value is: NO. + +FILTER_SOURCE_FILES = NO + +# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file +# pattern. A pattern will override the setting for FILTER_PATTERN (if any) and +# it is also possible to disable source filtering for a specific pattern using +# *.ext= (so without naming a filter). +# This tag requires that the tag FILTER_SOURCE_FILES is set to YES. + +FILTER_SOURCE_PATTERNS = + +# If the USE_MDFILE_AS_MAINPAGE tag refers to the name of a markdown file that +# is part of the input, its contents will be placed on the main page +# (index.html). This can be useful if you have a project on for instance GitHub +# and want to reuse the introduction page also for the doxygen output. + +USE_MDFILE_AS_MAINPAGE = + +# The Fortran standard specifies that for fixed formatted Fortran code all +# characters from position 72 are to be considered as comment. A common +# extension is to allow longer lines before the automatic comment starts. The +# setting FORTRAN_COMMENT_AFTER will also make it possible that longer lines can +# be processed before the automatic comment starts. +# Minimum value: 7, maximum value: 10000, default value: 72. + +FORTRAN_COMMENT_AFTER = 72 + +#--------------------------------------------------------------------------- +# Configuration options related to source browsing +#--------------------------------------------------------------------------- + +# If the SOURCE_BROWSER tag is set to YES then a list of source files will be +# generated. Documented entities will be cross-referenced with these sources. +# +# Note: To get rid of all source code in the generated output, make sure that +# also VERBATIM_HEADERS is set to NO. +# The default value is: NO. + +SOURCE_BROWSER = NO + +# Setting the INLINE_SOURCES tag to YES will include the body of functions, +# classes and enums directly into the documentation. +# The default value is: NO. + +INLINE_SOURCES = NO + +# Setting the STRIP_CODE_COMMENTS tag to YES will instruct doxygen to hide any +# special comment blocks from generated source code fragments. Normal C, C++ and +# Fortran comments will always remain visible. +# The default value is: YES. + +STRIP_CODE_COMMENTS = YES + +# If the REFERENCED_BY_RELATION tag is set to YES then for each documented +# entity all documented functions referencing it will be listed. +# The default value is: NO. + +REFERENCED_BY_RELATION = NO + +# If the REFERENCES_RELATION tag is set to YES then for each documented function +# all documented entities called/used by that function will be listed. +# The default value is: NO. + +REFERENCES_RELATION = NO + +# If the REFERENCES_LINK_SOURCE tag is set to YES and SOURCE_BROWSER tag is set +# to YES then the hyperlinks from functions in REFERENCES_RELATION and +# REFERENCED_BY_RELATION lists will link to the source code. Otherwise they will +# link to the documentation. +# The default value is: YES. + +REFERENCES_LINK_SOURCE = YES + +# If SOURCE_TOOLTIPS is enabled (the default) then hovering a hyperlink in the +# source code will show a tooltip with additional information such as prototype, +# brief description and links to the definition and documentation. Since this +# will make the HTML file larger and loading of large files a bit slower, you +# can opt to disable this feature. +# The default value is: YES. +# This tag requires that the tag SOURCE_BROWSER is set to YES. + +SOURCE_TOOLTIPS = YES + +# If the USE_HTAGS tag is set to YES then the references to source code will +# point to the HTML generated by the htags(1) tool instead of doxygen built-in +# source browser. The htags tool is part of GNU's global source tagging system +# (see https://www.gnu.org/software/global/global.html). You will need version +# 4.8.6 or higher. +# +# To use it do the following: +# - Install the latest version of global +# - Enable SOURCE_BROWSER and USE_HTAGS in the configuration file +# - Make sure the INPUT points to the root of the source tree +# - Run doxygen as normal +# +# Doxygen will invoke htags (and that will in turn invoke gtags), so these +# tools must be available from the command line (i.e. in the search path). +# +# The result: instead of the source browser generated by doxygen, the links to +# source code will now point to the output of htags. +# The default value is: NO. +# This tag requires that the tag SOURCE_BROWSER is set to YES. + +USE_HTAGS = NO + +# If the VERBATIM_HEADERS tag is set the YES then doxygen will generate a +# verbatim copy of the header file for each class for which an include is +# specified. Set to NO to disable this. +# See also: Section \class. +# The default value is: YES. + +VERBATIM_HEADERS = YES + +#--------------------------------------------------------------------------- +# Configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- + +# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index of all +# compounds will be generated. Enable this if the project contains a lot of +# classes, structs, unions or interfaces. +# The default value is: YES. + +ALPHABETICAL_INDEX = YES + +# The IGNORE_PREFIX tag can be used to specify a prefix (or a list of prefixes) +# that should be ignored while generating the index headers. The IGNORE_PREFIX +# tag works for classes, function and member names. The entity will be placed in +# the alphabetical list under the first letter of the entity name that remains +# after removing the prefix. +# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. + +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the HTML output +#--------------------------------------------------------------------------- + +# If the GENERATE_HTML tag is set to YES, doxygen will generate HTML output +# The default value is: YES. + +GENERATE_HTML = YES + +# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. If a +# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of +# it. +# The default directory is: html. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_OUTPUT = html + +# The HTML_FILE_EXTENSION tag can be used to specify the file extension for each +# generated HTML page (for example: .htm, .php, .asp). +# The default value is: .html. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_FILE_EXTENSION = .html + +# The HTML_HEADER tag can be used to specify a user-defined HTML header file for +# each generated HTML page. If the tag is left blank doxygen will generate a +# standard header. +# +# To get valid HTML the header file that includes any scripts and style sheets +# that doxygen needs, which is dependent on the configuration options used (e.g. +# the setting GENERATE_TREEVIEW). It is highly recommended to start with a +# default header using +# doxygen -w html new_header.html new_footer.html new_stylesheet.css +# YourConfigFile +# and then modify the file new_header.html. See also section "Doxygen usage" +# for information on how to generate the default header that doxygen normally +# uses. +# Note: The header is subject to change so you typically have to regenerate the +# default header when upgrading to a newer version of doxygen. For a description +# of the possible markers and block names see the documentation. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_HEADER = + +# The HTML_FOOTER tag can be used to specify a user-defined HTML footer for each +# generated HTML page. If the tag is left blank doxygen will generate a standard +# footer. See HTML_HEADER for more information on how to generate a default +# footer and what special commands can be used inside the footer. See also +# section "Doxygen usage" for information on how to generate the default footer +# that doxygen normally uses. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_FOOTER = + +# The HTML_STYLESHEET tag can be used to specify a user-defined cascading style +# sheet that is used by each HTML page. It can be used to fine-tune the look of +# the HTML output. If left blank doxygen will generate a default style sheet. +# See also section "Doxygen usage" for information on how to generate the style +# sheet that doxygen normally uses. +# Note: It is recommended to use HTML_EXTRA_STYLESHEET instead of this tag, as +# it is more robust and this tag (HTML_STYLESHEET) will in the future become +# obsolete. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_STYLESHEET = + +# The HTML_EXTRA_STYLESHEET tag can be used to specify additional user-defined +# cascading style sheets that are included after the standard style sheets +# created by doxygen. Using this option one can overrule certain style aspects. +# This is preferred over using HTML_STYLESHEET since it does not replace the +# standard style sheet and is therefore more robust against future updates. +# Doxygen will copy the style sheet files to the output directory. +# Note: The order of the extra style sheet files is of importance (e.g. the last +# style sheet in the list overrules the setting of the previous ones in the +# list). +# Note: Since the styling of scrollbars can currently not be overruled in +# Webkit/Chromium, the styling will be left out of the default doxygen.css if +# one or more extra stylesheets have been specified. So if scrollbar +# customization is desired it has to be added explicitly. For an example see the +# documentation. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_EXTRA_STYLESHEET = + +# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or +# other source files which should be copied to the HTML output directory. Note +# that these files will be copied to the base HTML output directory. Use the +# $relpath^ marker in the HTML_HEADER and/or HTML_FOOTER files to load these +# files. In the HTML_STYLESHEET file, use the file name only. Also note that the +# files will be copied as-is; there are no commands or markers available. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_EXTRA_FILES = + +# The HTML_COLORSTYLE tag can be used to specify if the generated HTML output +# should be rendered with a dark or light theme. +# Possible values are: LIGHT always generate light mode output, DARK always +# generate dark mode output, AUTO_LIGHT automatically set the mode according to +# the user preference, use light mode if no preference is set (the default), +# AUTO_DARK automatically set the mode according to the user preference, use +# dark mode if no preference is set and TOGGLE allow to user to switch between +# light and dark mode via a button. +# The default value is: AUTO_LIGHT. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE = AUTO_LIGHT + +# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen +# will adjust the colors in the style sheet and background images according to +# this color. Hue is specified as an angle on a color-wheel, see +# https://en.wikipedia.org/wiki/Hue for more information. For instance the value +# 0 represents red, 60 is yellow, 120 is green, 180 is cyan, 240 is blue, 300 +# purple, and 360 is red again. +# Minimum value: 0, maximum value: 359, default value: 220. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_HUE = 220 + +# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of the colors +# in the HTML output. For a value of 0 the output will use gray-scales only. A +# value of 255 will produce the most vivid colors. +# Minimum value: 0, maximum value: 255, default value: 100. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_SAT = 100 + +# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to the +# luminance component of the colors in the HTML output. Values below 100 +# gradually make the output lighter, whereas values above 100 make the output +# darker. The value divided by 100 is the actual gamma applied, so 80 represents +# a gamma of 0.8, The value 220 represents a gamma of 2.2, and 100 does not +# change the gamma. +# Minimum value: 40, maximum value: 240, default value: 80. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_GAMMA = 80 + +# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML +# page will contain the date and time when the page was generated. Setting this +# to YES can help to show when doxygen was last run and thus if the +# documentation is up to date. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_TIMESTAMP = NO + +# If the HTML_DYNAMIC_MENUS tag is set to YES then the generated HTML +# documentation will contain a main index with vertical navigation menus that +# are dynamically created via JavaScript. If disabled, the navigation index will +# consists of multiple levels of tabs that are statically embedded in every HTML +# page. Disable this option to support browsers that do not have JavaScript, +# like the Qt help browser. +# The default value is: YES. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_DYNAMIC_MENUS = YES + +# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML +# documentation will contain sections that can be hidden and shown after the +# page has loaded. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_DYNAMIC_SECTIONS = NO + +# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of entries +# shown in the various tree structured indices initially; the user can expand +# and collapse entries dynamically later on. Doxygen will expand the tree to +# such a level that at most the specified number of entries are visible (unless +# a fully collapsed tree already exceeds this amount). So setting the number of +# entries 1 will produce a full collapsed tree by default. 0 is a special value +# representing an infinite number of entries and will result in a full expanded +# tree by default. +# Minimum value: 0, maximum value: 9999, default value: 100. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_INDEX_NUM_ENTRIES = 100 + +# If the GENERATE_DOCSET tag is set to YES, additional index files will be +# generated that can be used as input for Apple's Xcode 3 integrated development +# environment (see: +# https://developer.apple.com/xcode/), introduced with OSX 10.5 (Leopard). To +# create a documentation set, doxygen will generate a Makefile in the HTML +# output directory. Running make will produce the docset in that directory and +# running make install will install the docset in +# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find it at +# startup. See https://developer.apple.com/library/archive/featuredarticles/Doxy +# genXcode/_index.html for more information. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_DOCSET = NO + +# This tag determines the name of the docset feed. A documentation feed provides +# an umbrella under which multiple documentation sets from a single provider +# (such as a company or product suite) can be grouped. +# The default value is: Doxygen generated docs. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_FEEDNAME = "Doxygen generated docs" + +# This tag determines the URL of the docset feed. A documentation feed provides +# an umbrella under which multiple documentation sets from a single provider +# (such as a company or product suite) can be grouped. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_FEEDURL = + +# This tag specifies a string that should uniquely identify the documentation +# set bundle. This should be a reverse domain-name style string, e.g. +# com.mycompany.MyDocSet. Doxygen will append .docset to the name. +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_BUNDLE_ID = org.doxygen.Project + +# The DOCSET_PUBLISHER_ID tag specifies a string that should uniquely identify +# the documentation publisher. This should be a reverse domain-name style +# string, e.g. com.mycompany.MyDocSet.documentation. +# The default value is: org.doxygen.Publisher. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_PUBLISHER_ID = org.doxygen.Publisher + +# The DOCSET_PUBLISHER_NAME tag identifies the documentation publisher. +# The default value is: Publisher. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_PUBLISHER_NAME = Publisher + +# If the GENERATE_HTMLHELP tag is set to YES then doxygen generates three +# additional HTML index files: index.hhp, index.hhc, and index.hhk. The +# index.hhp is a project file that can be read by Microsoft's HTML Help Workshop +# on Windows. In the beginning of 2021 Microsoft took the original page, with +# a.o. the download links, offline the HTML help workshop was already many years +# in maintenance mode). You can download the HTML help workshop from the web +# archives at Installation executable (see: +# http://web.archive.org/web/20160201063255/http://download.microsoft.com/downlo +# ad/0/A/9/0A939EF6-E31C-430F-A3DF-DFAE7960D564/htmlhelp.exe). +# +# The HTML Help Workshop contains a compiler that can convert all HTML output +# generated by doxygen into a single compiled HTML file (.chm). Compiled HTML +# files are now used as the Windows 98 help format, and will replace the old +# Windows help format (.hlp) on all Windows platforms in the future. Compressed +# HTML files also contain an index, a table of contents, and you can search for +# words in the documentation. The HTML workshop also contains a viewer for +# compressed HTML files. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_HTMLHELP = NO + +# The CHM_FILE tag can be used to specify the file name of the resulting .chm +# file. You can add a path in front of the file if the result should not be +# written to the html output directory. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +CHM_FILE = + +# The HHC_LOCATION tag can be used to specify the location (absolute path +# including file name) of the HTML help compiler (hhc.exe). If non-empty, +# doxygen will try to run the HTML help compiler on the generated index.hhp. +# The file has to be specified with full path. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +HHC_LOCATION = + +# The GENERATE_CHI flag controls if a separate .chi index file is generated +# (YES) or that it should be included in the main .chm file (NO). +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +GENERATE_CHI = NO + +# The CHM_INDEX_ENCODING is used to encode HtmlHelp index (hhk), content (hhc) +# and project file content. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +CHM_INDEX_ENCODING = + +# The BINARY_TOC flag controls whether a binary table of contents is generated +# (YES) or a normal table of contents (NO) in the .chm file. Furthermore it +# enables the Previous and Next buttons. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +BINARY_TOC = NO + +# The TOC_EXPAND flag can be set to YES to add extra items for group members to +# the table of contents of the HTML help documentation and to the tree view. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +TOC_EXPAND = NO + +# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and +# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated that +# can be used as input for Qt's qhelpgenerator to generate a Qt Compressed Help +# (.qch) of the generated HTML documentation. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_QHP = NO + +# If the QHG_LOCATION tag is specified, the QCH_FILE tag can be used to specify +# the file name of the resulting .qch file. The path specified is relative to +# the HTML output folder. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QCH_FILE = + +# The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help +# Project output. For more information please see Qt Help Project / Namespace +# (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#namespace). +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_NAMESPACE = org.doxygen.Project + +# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt +# Help Project output. For more information please see Qt Help Project / Virtual +# Folders (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#virtual-folders). +# The default value is: doc. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_VIRTUAL_FOLDER = doc + +# If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom +# filter to add. For more information please see Qt Help Project / Custom +# Filters (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom-filters). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_CUST_FILTER_NAME = + +# The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the +# custom filter to add. For more information please see Qt Help Project / Custom +# Filters (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom-filters). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_CUST_FILTER_ATTRS = + +# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this +# project's filter section matches. Qt Help Project / Filter Attributes (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#filter-attributes). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_SECT_FILTER_ATTRS = + +# The QHG_LOCATION tag can be used to specify the location (absolute path +# including file name) of Qt's qhelpgenerator. If non-empty doxygen will try to +# run qhelpgenerator on the generated .qhp file. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHG_LOCATION = + +# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files will be +# generated, together with the HTML files, they form an Eclipse help plugin. To +# install this plugin and make it available under the help contents menu in +# Eclipse, the contents of the directory containing the HTML and XML files needs +# to be copied into the plugins directory of eclipse. The name of the directory +# within the plugins directory should be the same as the ECLIPSE_DOC_ID value. +# After copying Eclipse needs to be restarted before the help appears. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_ECLIPSEHELP = NO + +# A unique identifier for the Eclipse help plugin. When installing the plugin +# the directory name containing the HTML and XML files should also have this +# name. Each documentation set should have its own identifier. +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_ECLIPSEHELP is set to YES. + +ECLIPSE_DOC_ID = org.doxygen.Project + +# If you want full control over the layout of the generated HTML pages it might +# be necessary to disable the index and replace it with your own. The +# DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) at top +# of each HTML page. A value of NO enables the index and the value YES disables +# it. Since the tabs in the index contain the same information as the navigation +# tree, you can set this option to YES if you also set GENERATE_TREEVIEW to YES. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +DISABLE_INDEX = NO + +# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index +# structure should be generated to display hierarchical information. If the tag +# value is set to YES, a side panel will be generated containing a tree-like +# index structure (just like the one that is generated for HTML Help). For this +# to work a browser that supports JavaScript, DHTML, CSS and frames is required +# (i.e. any modern browser). Windows users are probably better off using the +# HTML help feature. Via custom style sheets (see HTML_EXTRA_STYLESHEET) one can +# further fine tune the look of the index (see "Fine-tuning the output"). As an +# example, the default style sheet generated by doxygen has an example that +# shows how to put an image at the root of the tree instead of the PROJECT_NAME. +# Since the tree basically has the same information as the tab index, you could +# consider setting DISABLE_INDEX to YES when enabling this option. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_TREEVIEW = NO + +# When both GENERATE_TREEVIEW and DISABLE_INDEX are set to YES, then the +# FULL_SIDEBAR option determines if the side bar is limited to only the treeview +# area (value NO) or if it should extend to the full height of the window (value +# YES). Setting this to YES gives a layout similar to +# https://docs.readthedocs.io with more room for contents, but less room for the +# project logo, title, and description. If either GENERATE_TREEVIEW or +# DISABLE_INDEX is set to NO, this option has no effect. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +FULL_SIDEBAR = NO + +# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values that +# doxygen will group on one line in the generated HTML documentation. +# +# Note that a value of 0 will completely suppress the enum values from appearing +# in the overview section. +# Minimum value: 0, maximum value: 20, default value: 4. +# This tag requires that the tag GENERATE_HTML is set to YES. + +ENUM_VALUES_PER_LINE = 4 + +# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be used +# to set the initial width (in pixels) of the frame in which the tree is shown. +# Minimum value: 0, maximum value: 1500, default value: 250. +# This tag requires that the tag GENERATE_HTML is set to YES. + +TREEVIEW_WIDTH = 250 + +# If the EXT_LINKS_IN_WINDOW option is set to YES, doxygen will open links to +# external symbols imported via tag files in a separate window. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +EXT_LINKS_IN_WINDOW = NO + +# If the OBFUSCATE_EMAILS tag is set to YES, doxygen will obfuscate email +# addresses. +# The default value is: YES. +# This tag requires that the tag GENERATE_HTML is set to YES. + +OBFUSCATE_EMAILS = YES + +# If the HTML_FORMULA_FORMAT option is set to svg, doxygen will use the pdf2svg +# tool (see https://github.com/dawbarton/pdf2svg) or inkscape (see +# https://inkscape.org) to generate formulas as SVG images instead of PNGs for +# the HTML output. These images will generally look nicer at scaled resolutions. +# Possible values are: png (the default) and svg (looks nicer but requires the +# pdf2svg or inkscape tool). +# The default value is: png. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_FORMULA_FORMAT = png + +# Use this tag to change the font size of LaTeX formulas included as images in +# the HTML documentation. When you change the font size after a successful +# doxygen run you need to manually remove any form_*.png images from the HTML +# output directory to force them to be regenerated. +# Minimum value: 8, maximum value: 50, default value: 10. +# This tag requires that the tag GENERATE_HTML is set to YES. + +FORMULA_FONTSIZE = 10 + +# The FORMULA_MACROFILE can contain LaTeX \newcommand and \renewcommand commands +# to create new LaTeX commands to be used in formulas as building blocks. See +# the section "Including formulas" for details. + +FORMULA_MACROFILE = + +# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see +# https://www.mathjax.org) which uses client side JavaScript for the rendering +# instead of using pre-rendered bitmaps. Use this if you do not have LaTeX +# installed or if you want to formulas look prettier in the HTML output. When +# enabled you may also need to install MathJax separately and configure the path +# to it using the MATHJAX_RELPATH option. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +USE_MATHJAX = NO + +# With MATHJAX_VERSION it is possible to specify the MathJax version to be used. +# Note that the different versions of MathJax have different requirements with +# regards to the different settings, so it is possible that also other MathJax +# settings have to be changed when switching between the different MathJax +# versions. +# Possible values are: MathJax_2 and MathJax_3. +# The default value is: MathJax_2. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_VERSION = MathJax_2 + +# When MathJax is enabled you can set the default output format to be used for +# the MathJax output. For more details about the output format see MathJax +# version 2 (see: +# http://docs.mathjax.org/en/v2.7-latest/output.html) and MathJax version 3 +# (see: +# http://docs.mathjax.org/en/latest/web/components/output.html). +# Possible values are: HTML-CSS (which is slower, but has the best +# compatibility. This is the name for Mathjax version 2, for MathJax version 3 +# this will be translated into chtml), NativeMML (i.e. MathML. Only supported +# for NathJax 2. For MathJax version 3 chtml will be used instead.), chtml (This +# is the name for Mathjax version 3, for MathJax version 2 this will be +# translated into HTML-CSS) and SVG. +# The default value is: HTML-CSS. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_FORMAT = HTML-CSS + +# When MathJax is enabled you need to specify the location relative to the HTML +# output directory using the MATHJAX_RELPATH option. The destination directory +# should contain the MathJax.js script. For instance, if the mathjax directory +# is located at the same level as the HTML output directory, then +# MATHJAX_RELPATH should be ../mathjax. The default value points to the MathJax +# Content Delivery Network so you can quickly see the result without installing +# MathJax. However, it is strongly recommended to install a local copy of +# MathJax from https://www.mathjax.org before deployment. The default value is: +# - in case of MathJax version 2: https://cdn.jsdelivr.net/npm/mathjax@2 +# - in case of MathJax version 3: https://cdn.jsdelivr.net/npm/mathjax@3 +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_RELPATH = + +# The MATHJAX_EXTENSIONS tag can be used to specify one or more MathJax +# extension names that should be enabled during MathJax rendering. For example +# for MathJax version 2 (see +# https://docs.mathjax.org/en/v2.7-latest/tex.html#tex-and-latex-extensions): +# MATHJAX_EXTENSIONS = TeX/AMSmath TeX/AMSsymbols +# For example for MathJax version 3 (see +# http://docs.mathjax.org/en/latest/input/tex/extensions/index.html): +# MATHJAX_EXTENSIONS = ams +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_EXTENSIONS = + +# The MATHJAX_CODEFILE tag can be used to specify a file with javascript pieces +# of code that will be used on startup of the MathJax code. See the MathJax site +# (see: +# http://docs.mathjax.org/en/v2.7-latest/output.html) for more details. For an +# example see the documentation. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_CODEFILE = + +# When the SEARCHENGINE tag is enabled doxygen will generate a search box for +# the HTML output. The underlying search engine uses javascript and DHTML and +# should work on any modern browser. Note that when using HTML help +# (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets (GENERATE_DOCSET) +# there is already a search function so this one should typically be disabled. +# For large projects the javascript based search engine can be slow, then +# enabling SERVER_BASED_SEARCH may provide a better solution. It is possible to +# search using the keyboard; to jump to the search box use + S +# (what the is depends on the OS and browser, but it is typically +# , /Node, +# Edge and Graph Attributes specification You need to make sure dot is able +# to find the font, which can be done by putting it in a standard location or by +# setting the DOTFONTPATH environment variable or by setting DOT_FONTPATH to the +# directory containing the font. Default graphviz fontsize is 14. +# The default value is: fontname=Helvetica,fontsize=10. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_COMMON_ATTR = "fontname=Helvetica,fontsize=10" + +# DOT_EDGE_ATTR is concatenated with DOT_COMMON_ATTR. For elegant style you can +# add 'arrowhead=open, arrowtail=open, arrowsize=0.5'. Complete documentation about +# arrows shapes. +# The default value is: labelfontname=Helvetica,labelfontsize=10. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_EDGE_ATTR = "labelfontname=Helvetica,labelfontsize=10" + +# DOT_NODE_ATTR is concatenated with DOT_COMMON_ATTR. For view without boxes +# around nodes set 'shape=plain' or 'shape=plaintext' Shapes specification +# The default value is: shape=box,height=0.2,width=0.4. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_NODE_ATTR = "shape=box,height=0.2,width=0.4" + +# You can set the path where dot can find font specified with fontname in +# DOT_COMMON_ATTR and others dot attributes. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_FONTPATH = + +# If the CLASS_GRAPH tag is set to YES (or GRAPH) then doxygen will generate a +# graph for each documented class showing the direct and indirect inheritance +# relations. In case HAVE_DOT is set as well dot will be used to draw the graph, +# otherwise the built-in generator will be used. If the CLASS_GRAPH tag is set +# to TEXT the direct and indirect inheritance relations will be shown as texts / +# links. +# Possible values are: NO, YES, TEXT and GRAPH. +# The default value is: YES. + +CLASS_GRAPH = YES + +# If the COLLABORATION_GRAPH tag is set to YES then doxygen will generate a +# graph for each documented class showing the direct and indirect implementation +# dependencies (inheritance, containment, and class references variables) of the +# class with other documented classes. +# The default value is: YES. +# This tag requires that the tag HAVE_DOT is set to YES. + +COLLABORATION_GRAPH = YES + +# If the GROUP_GRAPHS tag is set to YES then doxygen will generate a graph for +# groups, showing the direct groups dependencies. See also the chapter Grouping +# in the manual. +# The default value is: YES. +# This tag requires that the tag HAVE_DOT is set to YES. + +GROUP_GRAPHS = YES + +# If the UML_LOOK tag is set to YES, doxygen will generate inheritance and +# collaboration diagrams in a style similar to the OMG's Unified Modeling +# Language. +# The default value is: NO. +# This tag requires that the tag HAVE_DOT is set to YES. + +UML_LOOK = NO + +# If the UML_LOOK tag is enabled, the fields and methods are shown inside the +# class node. If there are many fields or methods and many nodes the graph may +# become too big to be useful. The UML_LIMIT_NUM_FIELDS threshold limits the +# number of items for each type to make the size more manageable. Set this to 0 +# for no limit. Note that the threshold may be exceeded by 50% before the limit +# is enforced. So when you set the threshold to 10, up to 15 fields may appear, +# but if the number exceeds 15, the total amount of fields shown is limited to +# 10. +# Minimum value: 0, maximum value: 100, default value: 10. +# This tag requires that the tag UML_LOOK is set to YES. + +UML_LIMIT_NUM_FIELDS = 10 + +# If the DOT_UML_DETAILS tag is set to NO, doxygen will show attributes and +# methods without types and arguments in the UML graphs. If the DOT_UML_DETAILS +# tag is set to YES, doxygen will add type and arguments for attributes and +# methods in the UML graphs. If the DOT_UML_DETAILS tag is set to NONE, doxygen +# will not generate fields with class member information in the UML graphs. The +# class diagrams will look similar to the default class diagrams but using UML +# notation for the relationships. +# Possible values are: NO, YES and NONE. +# The default value is: NO. +# This tag requires that the tag UML_LOOK is set to YES. + +DOT_UML_DETAILS = NO + +# The DOT_WRAP_THRESHOLD tag can be used to set the maximum number of characters +# to display on a single line. If the actual line length exceeds this threshold +# significantly it will wrapped across multiple lines. Some heuristics are apply +# to avoid ugly line breaks. +# Minimum value: 0, maximum value: 1000, default value: 17. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_WRAP_THRESHOLD = 17 + +# If the TEMPLATE_RELATIONS tag is set to YES then the inheritance and +# collaboration graphs will show the relations between templates and their +# instances. +# The default value is: NO. +# This tag requires that the tag HAVE_DOT is set to YES. + +TEMPLATE_RELATIONS = NO + +# If the INCLUDE_GRAPH, ENABLE_PREPROCESSING and SEARCH_INCLUDES tags are set to +# YES then doxygen will generate a graph for each documented file showing the +# direct and indirect include dependencies of the file with other documented +# files. +# The default value is: YES. +# This tag requires that the tag HAVE_DOT is set to YES. + +INCLUDE_GRAPH = YES + +# If the INCLUDED_BY_GRAPH, ENABLE_PREPROCESSING and SEARCH_INCLUDES tags are +# set to YES then doxygen will generate a graph for each documented file showing +# the direct and indirect include dependencies of the file with other documented +# files. +# The default value is: YES. +# This tag requires that the tag HAVE_DOT is set to YES. + +INCLUDED_BY_GRAPH = YES + +# If the CALL_GRAPH tag is set to YES then doxygen will generate a call +# dependency graph for every global function or class method. +# +# Note that enabling this option will significantly increase the time of a run. +# So in most cases it will be better to enable call graphs for selected +# functions only using the \callgraph command. Disabling a call graph can be +# accomplished by means of the command \hidecallgraph. +# The default value is: NO. +# This tag requires that the tag HAVE_DOT is set to YES. + +CALL_GRAPH = NO + +# If the CALLER_GRAPH tag is set to YES then doxygen will generate a caller +# dependency graph for every global function or class method. +# +# Note that enabling this option will significantly increase the time of a run. +# So in most cases it will be better to enable caller graphs for selected +# functions only using the \callergraph command. Disabling a caller graph can be +# accomplished by means of the command \hidecallergraph. +# The default value is: NO. +# This tag requires that the tag HAVE_DOT is set to YES. + +CALLER_GRAPH = NO + +# If the GRAPHICAL_HIERARCHY tag is set to YES then doxygen will graphical +# hierarchy of all classes instead of a textual one. +# The default value is: YES. +# This tag requires that the tag HAVE_DOT is set to YES. + +GRAPHICAL_HIERARCHY = YES + +# If the DIRECTORY_GRAPH tag is set to YES then doxygen will show the +# dependencies a directory has on other directories in a graphical way. The +# dependency relations are determined by the #include relations between the +# files in the directories. +# The default value is: YES. +# This tag requires that the tag HAVE_DOT is set to YES. + +DIRECTORY_GRAPH = YES + +# The DIR_GRAPH_MAX_DEPTH tag can be used to limit the maximum number of levels +# of child directories generated in directory dependency graphs by dot. +# Minimum value: 1, maximum value: 25, default value: 1. +# This tag requires that the tag DIRECTORY_GRAPH is set to YES. + +DIR_GRAPH_MAX_DEPTH = 1 + +# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images +# generated by dot. For an explanation of the image formats see the section +# output formats in the documentation of the dot tool (Graphviz (see: +# http://www.graphviz.org/)). +# Note: If you choose svg you need to set HTML_FILE_EXTENSION to xhtml in order +# to make the SVG files visible in IE 9+ (other browsers do not have this +# requirement). +# Possible values are: png, jpg, gif, svg, png:gd, png:gd:gd, png:cairo, +# png:cairo:gd, png:cairo:cairo, png:cairo:gdiplus, png:gdiplus and +# png:gdiplus:gdiplus. +# The default value is: png. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_IMAGE_FORMAT = png + +# If DOT_IMAGE_FORMAT is set to svg, then this option can be set to YES to +# enable generation of interactive SVG images that allow zooming and panning. +# +# Note that this requires a modern browser other than Internet Explorer. Tested +# and working are Firefox, Chrome, Safari, and Opera. +# Note: For IE 9+ you need to set HTML_FILE_EXTENSION to xhtml in order to make +# the SVG files visible. Older versions of IE do not have SVG support. +# The default value is: NO. +# This tag requires that the tag HAVE_DOT is set to YES. + +INTERACTIVE_SVG = NO + +# The DOT_PATH tag can be used to specify the path where the dot tool can be +# found. If left blank, it is assumed the dot tool can be found in the path. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_PATH = + +# The DOTFILE_DIRS tag can be used to specify one or more directories that +# contain dot files that are included in the documentation (see the \dotfile +# command). +# This tag requires that the tag HAVE_DOT is set to YES. + +DOTFILE_DIRS = + +# The MSCFILE_DIRS tag can be used to specify one or more directories that +# contain msc files that are included in the documentation (see the \mscfile +# command). + +MSCFILE_DIRS = + +# The DIAFILE_DIRS tag can be used to specify one or more directories that +# contain dia files that are included in the documentation (see the \diafile +# command). + +DIAFILE_DIRS = + +# When using plantuml, the PLANTUML_JAR_PATH tag should be used to specify the +# path where java can find the plantuml.jar file or to the filename of jar file +# to be used. If left blank, it is assumed PlantUML is not used or called during +# a preprocessing step. Doxygen will generate a warning when it encounters a +# \startuml command in this case and will not generate output for the diagram. + +PLANTUML_JAR_PATH = + +# When using plantuml, the PLANTUML_CFG_FILE tag can be used to specify a +# configuration file for plantuml. + +PLANTUML_CFG_FILE = + +# When using plantuml, the specified paths are searched for files specified by +# the !include statement in a plantuml block. + +PLANTUML_INCLUDE_PATH = + +# The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of nodes +# that will be shown in the graph. If the number of nodes in a graph becomes +# larger than this value, doxygen will truncate the graph, which is visualized +# by representing a node as a red box. Note that doxygen if the number of direct +# children of the root node in a graph is already larger than +# DOT_GRAPH_MAX_NODES then the graph will not be shown at all. Also note that +# the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH. +# Minimum value: 0, maximum value: 10000, default value: 50. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_GRAPH_MAX_NODES = 50 + +# The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the graphs +# generated by dot. A depth value of 3 means that only nodes reachable from the +# root by following a path via at most 3 edges will be shown. Nodes that lay +# further from the root node will be omitted. Note that setting this option to 1 +# or 2 may greatly reduce the computation time needed for large code bases. Also +# note that the size of a graph can be further restricted by +# DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction. +# Minimum value: 0, maximum value: 1000, default value: 0. +# This tag requires that the tag HAVE_DOT is set to YES. + +MAX_DOT_GRAPH_DEPTH = 0 + +# Set the DOT_MULTI_TARGETS tag to YES to allow dot to generate multiple output +# files in one run (i.e. multiple -o and -T options on the command line). This +# makes dot run faster, but since only newer versions of dot (>1.8.10) support +# this, this feature is disabled by default. +# The default value is: NO. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_MULTI_TARGETS = NO + +# If the GENERATE_LEGEND tag is set to YES doxygen will generate a legend page +# explaining the meaning of the various boxes and arrows in the dot generated +# graphs. +# Note: This tag requires that UML_LOOK isn't set, i.e. the doxygen internal +# graphical representation for inheritance and collaboration diagrams is used. +# The default value is: YES. +# This tag requires that the tag HAVE_DOT is set to YES. + +GENERATE_LEGEND = YES + +# If the DOT_CLEANUP tag is set to YES, doxygen will remove the intermediate +# files that are used to generate the various graphs. +# +# Note: This setting is not only used for dot files but also for msc temporary +# files. +# The default value is: YES. + +DOT_CLEANUP = YES diff --git a/documentation/html/annotated.html b/documentation/html/annotated.html new file mode 100644 index 0000000..55c9901 --- /dev/null +++ b/documentation/html/annotated.html @@ -0,0 +1,132 @@ + + + + + + + +RIT VEXU Core API: Class List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Class List
+
+ + + + + diff --git a/documentation/html/auto__chooser_8h_source.html b/documentation/html/auto__chooser_8h_source.html new file mode 100644 index 0000000..3fe6516 --- /dev/null +++ b/documentation/html/auto__chooser_8h_source.html @@ -0,0 +1,130 @@ + + + + + + + +RIT VEXU Core API: include/utils/auto_chooser.h Source File + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
auto_chooser.h
+
+
+
1#pragma once
+
2#include "vex.h"
+
3#include <string>
+
4#include <vector>
+
5
+
6
+ +
16{
+
17 public:
+
23 AutoChooser(vex::brain &brain);
+
24
+
29 void add(std::string name);
+
30
+
35 std::string get_choice();
+
36
+
37 protected:
+
38
+
42 struct entry_t
+
43 {
+
44 int x;
+
45 int y;
+
46 int width;
+
47 int height;
+
48 std::string name;
+
49 };
+
50
+
51 void render(entry_t *selected);
+
52
+
53 std::string choice;
+
54 std::vector<entry_t> list ;
+
55 vex::brain &brain;
+
58};
+
Definition: auto_chooser.h:16
+
std::string choice
Definition: auto_chooser.h:53
+
std::vector< entry_t > list
Definition: auto_chooser.h:54
+
void add(std::string name)
Definition: auto_chooser.cpp:66
+
void render(entry_t *selected)
Definition: auto_chooser.cpp:47
+
vex::brain & brain
Definition: auto_chooser.h:55
+
std::string get_choice()
Definition: auto_chooser.cpp:85
+
Definition: auto_chooser.h:43
+
int width
Definition: auto_chooser.h:46
+
int y
Definition: auto_chooser.h:45
+
int x
Definition: auto_chooser.h:44
+
int height
Definition: auto_chooser.h:47
+
std::string name
Definition: auto_chooser.h:48
+
+ + + + diff --git a/documentation/html/auto__command_8h_source.html b/documentation/html/auto__command_8h_source.html new file mode 100644 index 0000000..a8c192c --- /dev/null +++ b/documentation/html/auto__command_8h_source.html @@ -0,0 +1,109 @@ + + + + + + + +RIT VEXU Core API: include/utils/command_structure/auto_command.h Source File + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
auto_command.h
+
+
+
1
+
7#pragma once
+
8
+
9#include "vex.h"
+
10
+ +
12 public:
+
18 virtual bool run() { return true; }
+
22 virtual void on_timeout(){}
+
23 AutoCommand* withTimeout(double t_seconds){
+
24<<<<<<< HEAD
+
25 this->timeout_seconds = t_seconds;
+
26=======
+
27 timeout_seconds = t_seconds;
+
28>>>>>>> refs/subrepo/core/fetch
+
29 return this;
+
30 }
+
40 double timeout_seconds = 10.0;
+
41
+
42};
+
Definition: auto_command.h:11
+
virtual void on_timeout()
Definition: auto_command.h:22
+
virtual bool run()
Definition: auto_command.h:18
+
double timeout_seconds
Definition: auto_command.h:40
+
+ + + + diff --git a/documentation/html/bc_s.png b/documentation/html/bc_s.png new file mode 100644 index 0000000000000000000000000000000000000000..224b29aa9847d5a4b3902efd602b7ddf7d33e6c2 GIT binary patch literal 676 zcmV;V0$crwP)y__>=_9%My z{n931IS})GlGUF8K#6VIbs%684A^L3@%PlP2>_sk`UWPq@f;rU*V%rPy_ekbhXT&s z(GN{DxFv}*vZp`F>S!r||M`I*nOwwKX+BC~3P5N3-)Y{65c;ywYiAh-1*hZcToLHK ztpl1xomJ+Yb}K(cfbJr2=GNOnT!UFA7Vy~fBz8?J>XHsbZoDad^8PxfSa0GDgENZS zuLCEqzb*xWX2CG*b&5IiO#NzrW*;`VC9455M`o1NBh+(k8~`XCEEoC1Ybwf;vr4K3 zg|EB<07?SOqHp9DhLpS&bzgo70I+ghB_#)K7H%AMU3v}xuyQq9&Bm~++VYhF09a+U zl7>n7Jjm$K#b*FONz~fj;I->Bf;ule1prFN9FovcDGBkpg>)O*-}eLnC{6oZHZ$o% zXKW$;0_{8hxHQ>l;_*HATI(`7t#^{$(zLe}h*mqwOc*nRY9=?Sx4OOeVIfI|0V(V2 zBrW#G7Ss9wvzr@>H*`r>zE z+e8bOBgqIgldUJlG(YUDviMB`9+DH8n-s9SXRLyJHO1!=wY^79WYZMTa(wiZ!zP66 zA~!21vmF3H2{ngD;+`6j#~6j;$*f*G_2ZD1E;9(yaw7d-QnSCpK(cR1zU3qU0000< KMNUMnLSTYoA~SLT literal 0 HcmV?d00001 diff --git a/documentation/html/bc_sd.png b/documentation/html/bc_sd.png new file mode 100644 index 0000000000000000000000000000000000000000..31ca888dc71049713b35c351933a8d0f36180bf1 GIT binary patch literal 635 zcmV->0)+jEP)Jwi0r1~gdSq#w{Bu1q z`craw(p2!hu$4C_$Oc3X(sI6e=9QSTwPt{G) z=htT&^~&c~L2~e{r5_5SYe7#Is-$ln>~Kd%$F#tC65?{LvQ}8O`A~RBB0N~`2M+waajO;5>3B&-viHGJeEK2TQOiPRa zfDKyqwMc4wfaEh4jt>H`nW_Zidwk@Bowp`}(VUaj-pSI(-1L>FJVsX}Yl9~JsqgsZ zUD9(rMwf23Gez6KPa|wwInZodP-2}9@fK0Ga_9{8SOjU&4l`pH4@qlQp83>>HT$xW zER^U>)MyV%t(Lu=`d=Y?{k1@}&r7ZGkFQ%z%N+sE9BtYjovzxyxCPxN6&@wLK{soQ zSmkj$aLI}miuE^p@~4}mg9OjDfGEkgY4~^XzLRUBB*O{+&vq<3v(E%+k_i%=`~j%{ Vj14gnt9}3g002ovPDHLkV1n!oC4m3{ literal 0 HcmV?d00001 diff --git a/documentation/html/bdwn.png b/documentation/html/bdwn.png new file mode 100644 index 0000000000000000000000000000000000000000..940a0b950443a0bb1b216ac03c45b8a16c955452 GIT binary patch literal 147 zcmeAS@N?(olHy`uVBq!ia0vp^>_E)H!3HEvS)PKZC{Gv1kP61Pb5HX&C2wk~_T + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
AutoChooser Member List
+
+
+ +

This is the complete list of members for AutoChooser, including all inherited members.

+ + + + + + + + +
add(std::string name)AutoChooser
AutoChooser(vex::brain &brain)AutoChooser
brainAutoChooserprotected
choiceAutoChooserprotected
get_choice()AutoChooser
listAutoChooserprotected
render(entry_t *selected)AutoChooserprotected
+ + + + diff --git a/documentation/html/classAutoChooser.html b/documentation/html/classAutoChooser.html new file mode 100644 index 0000000..834a586 --- /dev/null +++ b/documentation/html/classAutoChooser.html @@ -0,0 +1,296 @@ + + + + + + + +RIT VEXU Core API: AutoChooser Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
+ +

#include <auto_chooser.h>

+ + + + +

+Classes

struct  entry_t
 
+ + + + + + + +

+Public Member Functions

 AutoChooser (vex::brain &brain)
 
void add (std::string name)
 
std::string get_choice ()
 
+ + + +

+Protected Member Functions

void render (entry_t *selected)
 
+ + + + + + + +

+Protected Attributes

std::string choice
 
std::vector< entry_tlist
 
vex::brain & brain
 
+

Detailed Description

+

Autochooser is a utility to make selecting robot autonomous programs easier source: RIT VexU Wiki During a season, we usually code between 4 and 6 autonomous programs. Most teams will change their entire robot program as a way of choosing autonomi but this may cause issues if you have an emergency patch to upload during a competition. This class was built as a way of using the robot screen to list autonomous programs, and the touchscreen to select them.

+

Constructor & Destructor Documentation

+ +

◆ AutoChooser()

+ +
+
+ + + + + + + + +
AutoChooser::AutoChooser (vex::brain & brain)
+
+

Initialize the auto-chooser. This class places a choice menu on the brain screen, so the driver can choose which autonomous to run.

Parameters
+ + +
brainthe brain on which to draw the selection boxes
+
+
+ +
+
+

Member Function Documentation

+ +

◆ add()

+ +
+
+ + + + + + + + +
void AutoChooser::add (std::string name)
+
+

Add an auto path to the chooser

Parameters
+ + +
nameThe name of the path. This should be used as an human readable identifier to the auto path
+
+
+

Add a new autonomous option. There are 3 options per row.

+ +
+
+ +

◆ get_choice()

+ +
+
+ + + + + + + +
std::string AutoChooser::get_choice ()
+
+

Get the currently selected auto choice

Returns
the identifier to the auto path
+

Return the selected autonomous

+ +
+
+ +

◆ render()

+ +
+
+ + + + + +
+ + + + + + + + +
void AutoChooser::render (entry_tselected)
+
+protected
+
+

Place all the autonomous choices on the screen. If one is selected, change it's color

Parameters
+ + +
selectedthe choice that is currently selected
+
+
+ +
+
+

Member Data Documentation

+ +

◆ brain

+ +
+
+ + + + + +
+ + + + +
vex::brain& AutoChooser::brain
+
+protected
+
+

the brain to show the choices on

+ +
+
+ +

◆ choice

+ +
+
+ + + + + +
+ + + + +
std::string AutoChooser::choice
+
+protected
+
+

the current choice of auto

+ +
+
+ +

◆ list

+ +
+
+ + + + + +
+ + + + +
std::vector<entry_t> AutoChooser::list
+
+protected
+
+

< a list of all possible auto choices

+ +
+
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/documentation/html/classAutoCommand-members.html b/documentation/html/classAutoCommand-members.html new file mode 100644 index 0000000..daf0d0e --- /dev/null +++ b/documentation/html/classAutoCommand-members.html @@ -0,0 +1,88 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
AutoCommand Member List
+
+
+ +

This is the complete list of members for AutoCommand, including all inherited members.

+ + + + + +
on_timeout()AutoCommandinlinevirtual
run()AutoCommandinlinevirtual
timeout_secondsAutoCommand
withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
+ + + + diff --git a/documentation/html/classAutoCommand.html b/documentation/html/classAutoCommand.html new file mode 100644 index 0000000..9c9139f --- /dev/null +++ b/documentation/html/classAutoCommand.html @@ -0,0 +1,205 @@ + + + + + + + +RIT VEXU Core API: AutoCommand Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
AutoCommand Class Reference
+
+
+ +

#include <auto_command.h>

+
+Inheritance diagram for AutoCommand:
+
+
+ + +DelayCommand +DriveForwardCommand +DriveStopCommand +DriveToPointCommand +FlywheelStopCommand +FlywheelStopMotorsCommand +FlywheelStopNonTasksCommand +OdomSetPosition +SpinRPMCommand +TurnDegreesCommand +TurnToHeadingCommand +WaitUntilUpToSpeedCommand + +
+ + + + + + + + +

+Public Member Functions

virtual bool run ()
 
virtual void on_timeout ()
 
+AutoCommandwithTimeout (double t_seconds)
 
+ + + +

+Public Attributes

double timeout_seconds = 10.0
 
+

Detailed Description

+

File: auto_command.h Desc: Interface for module-specifc commands

+

Member Function Documentation

+ +

◆ on_timeout()

+ +
+
+ + + + + +
+ + + + + + + +
virtual void AutoCommand::on_timeout ()
+
+inlinevirtual
+
+

What to do if we timeout instead of finishing. timeout is specified by the timeout seconds in the constructor

+ +

Reimplemented in DriveForwardCommand, TurnDegreesCommand, and TurnToHeadingCommand.

+ +
+
+ +

◆ run()

+ +
+
+ + + + + +
+ + + + + + + +
virtual bool AutoCommand::run ()
+
+inlinevirtual
+
+

Executes the command Overridden by child classes

Returns
true when the command is finished, false otherwise
+ +

Reimplemented in DelayCommand, DriveForwardCommand, TurnDegreesCommand, DriveToPointCommand, TurnToHeadingCommand, DriveStopCommand, OdomSetPosition, SpinRPMCommand, WaitUntilUpToSpeedCommand, FlywheelStopCommand, and FlywheelStopMotorsCommand.

+ +
+
+

Member Data Documentation

+ +

◆ timeout_seconds

+ +
+
+ + + + +
double AutoCommand::timeout_seconds = 10.0
+
+

How long to run until we cancel this command. If the command is cancelled, on_timeout() is called to allow any cleanup from the function. If the timeout_seconds <= 0, no timeout will be applied and this command will run forever A timeout can come in handy for some commands that can not reach the end due to some physical limitation such as

    +
  • a drive command hitting a wall and not being able to reach its target
  • +
  • a command that waits until something is up to speed that never gets up to speed because of battery voltage
  • +
  • something else...
  • +
+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/documentation/html/classAutoCommand.png b/documentation/html/classAutoCommand.png new file mode 100644 index 0000000000000000000000000000000000000000..dbc2ae9af026460a51e9ecb20c4ae5ea5939c1a3 GIT binary patch literal 5628 zcmdT|cT`hZzl|s|mQhDEj!IFmj3YNl88FfuMFD9FQRLEfLI;(OkVNGhkUp00f`kBq z5C{SS2?2zlg9FMXv=~B>Zi0jsM5L2<;puzdxZZnf-dgkhVg5)?ZdvP`-#+`d_dbzl z%?!R>ziT}Th5FXWP~QTDS_Pp{5~bg)My@!z9ws3_yU&{7PKm{0WcY4m%0K>h>d_;I zu700T|L)ndXUKKSyPRy~-a0=EGfNcmf90boL4J)wZI3Y0{}~swYLqhU(|>HsT5`a4 z{xqq-xR>l{Qo65iW1phCr^miRtM8>6zp6ESct( zX@WzX>(D$)*?|6m&_m~reC!jAbEXL-y`I^K>vvky(-3%uu=`h zNs@D{@l*v6`G&s(2tCvM+YoDf-sk^XM#8{mcdX2&2&U8?)SJfd_MmVIAc}TPyJo|2 zm2}CpUE;?tHXH|#(VjaJXX9K~{a`>x-B$!rb>9If{%!OPAN>u-vB+(i=D*{1tue#T zj#sINs$zREvRPWq>0q4eIlzFP4Jm>+WKo>Kt8?^5numrW?uw{aF{OEYAC56&!I1ITe1-wd4if>a z4XXg(b~F6xtJDaudZ);h6f-!lb*aukL8zEUG`HG$~2lGuCBlmT_FM`#+FEBpeb|K52>CBjw;C5IF$6GTZoTV}=Iv+e%^O8-i^ z3Y;;|ziWQAsI%fiwD74kKtq_w_4z#Y)I9#xIVE%2;TjR%F)F+J)yZl-TbMVS^t%>I z&diUV-Cg?|?cp9X(!glh_mD}7d{&C-Y<(B3no%6EFr)?I#?zZsANkhLUUJ!WL=tj} zZT4-IQk-N5EL;w;r>k$p&|}&wzOi*}t}gfTbe5inAg3M2}S?V$q;a>L76pa9XQO>yF49z3`lz;qQwUZ#irf{kiX+c+y{UB9d zY>Fj_=iSe^Y;1^*)iibtjY4zn5I%hrgfhoToHDs$6EL7$C1^!i)bE|I+Q;>=frCQT z!3%+hf$JBU8>l(R8yNaVa)VE~0}h@9!}lAzW98y&6CPdY^h?pGgIq%Ol<27OH+bF8~xbe4feeyZ{>(}$$u+!s7$qKYUWK-@?2gBDV z3VZ!DE9Nds*6&v}+Zp9K^5%Zyo36*@;4h#mh*O?D12^$rCSs}|W%=$b8}U2&iAy>m z-L)w|=L?4^mCPldx_q?G@v7a9Hp)DBF{sN$*~ z>Aa`Pdd_t23t7z9%fT~W;;Ql+Z<<>KK_sn;^!+Z;!u@&BP;Z;+TW{U4 z8j9<0DgkjrvWjq9SjnhNV$}PJ6ZC8%TNZ0k+1nmWW6t^k<}R8bYHV;X(0FiV@Z8jd zA@_y;PDriDvkoH9#thV&8#aHd`2Rn;U{DT}KU_X7)yoXdLvsTUezED6Dxm7w$#Gh_ zGu7jrjI(VGHE#ctr!OjQ2q~W7VgkUE4l;$yNR4k3hY#@QU!|gvUbVSZ755A$MSZ&W z`9Q8t!po!hABqZnOVvT>o%*7-za4&ZL{Mv0_0ysc9YLLSy2fuOr^?SvQPbLcEQu@F zrd%BHLRpiH@03_bE5?&&a&@zk?aj*a@I)yL{hd>nMvER%y7Pd0kR`R!H8do!woz7V z0}yF<`{o%ab$!eou+YM#MT2KZ4^MaPzogHOW&o$a0dnDy=+y}|<} z+Zq%>-EmL10=T>Cl3`uw+E|zYQF)7d2Z zDNG85I=4+elRq?adc!kjX+D4U?ebv8UD}ec;a|MTvg#qeaHu>#Bm_kyC%CWr2F3i_ z&E8+cd%^;+r?78SNIH=edV%{j(y%**voXp4QA6enwrtZz(5EgWl>xVrgD+9}4C zuT=hY&%sVJ+1_Ql&UW$p)^)2boXq8e?hT9ak7oPUA%XN)EP3@{)zGyOnW)~LY4u-* zk`%n6BD$SyLyFgQOyQ~&!0#eptp8-owNRz3SR8r4Q@AFmtCmGq@u#OvU z(J1}Y)Q{6Ck~BRddbYhw2M6b1_=O-W$DpOOWq-h2_6IrW8>p+%|L%i}|4qx3xyvDc z2?_ZH-1NDz&k^mjBX)7aZj|SKOMZE^SX1=6j6=d(a}S4N7Y1nj>lz&|c_5CLtR+9W z6?nQ%=BSvlHJnKt+L`Ofis7oVle8e(P9BBixbW&wlZj>5U^OH8uExRq$a*kou(@`w zrTz*vl~YyzU^QEvOVF(Z(XC)shVvmxEMuAUm*sSozCqt01K6$DdTelT60iNc)%bjA zQ>npEoXs62*KUrgb9HphqJ@p`@x=3~dq7;OK(P1W+?wX}IqiY&%(;7CRN||090VXD zyv)V*DP?%6T4Wv0*i73U-mbYeC%=7@SRW| zox3i;uL%eN1^o$n7O*Igzp=f%gpXSRl=472n8GazEU}d{OmKm%4wHTw zz063~hm!wQRe=~N3dTroQun>QBNH(4l(9}j~GPPNf9pD%srw#+2YMGc(I8CUD uoNei(OZL_-`@@C%Xs$T+f3^}SViZ*3XE+t8(vO_eqKrF1wty!9X6E{rz- literal 0 HcmV?d00001 diff --git a/documentation/html/classCommandController-members.html b/documentation/html/classCommandController-members.html new file mode 100644 index 0000000..a530d84 --- /dev/null +++ b/documentation/html/classCommandController-members.html @@ -0,0 +1,89 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
CommandController Member List
+
+
+ +

This is the complete list of members for CommandController, including all inherited members.

+ + + + + + +
add(AutoCommand *cmd, double timeout_seconds=10.0)CommandController
add(std::vector< AutoCommand * > cmds)CommandController
add_delay(int ms)CommandController
last_command_timed_out()CommandController
run()CommandController
+ + + + diff --git a/documentation/html/classCommandController.html b/documentation/html/classCommandController.html new file mode 100644 index 0000000..d377e9e --- /dev/null +++ b/documentation/html/classCommandController.html @@ -0,0 +1,233 @@ + + + + + + + +RIT VEXU Core API: CommandController Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
CommandController Class Reference
+
+
+ +

#include <command_controller.h>

+ + + + + + + + + + + + +

+Public Member Functions

void add (AutoCommand *cmd, double timeout_seconds=10.0)
 
void add (std::vector< AutoCommand * > cmds)
 
void add_delay (int ms)
 
void run ()
 
bool last_command_timed_out ()
 
+

Detailed Description

+

File: command_controller.h Desc: A CommandController manages the AutoCommands that make up an autonomous route. The AutoCommands are kept in a queue and get executed and removed from the queue in FIFO order.

+

Member Function Documentation

+ +

◆ add() [1/2]

+ +
+
+ + + + + + + + + + + + + + + + + + +
void CommandController::add (AutoCommandcmd,
double timeout_seconds = 10.0 
)
+
+

Adds a command to the queue

Parameters
+ + + +
cmdthe AutoCommand we want to add to our list
timeout_secondsthe number of seconds we will let the command run for. If it exceeds this, we cancel it and run on_timeout. if it is <= 0 no time out will be applied
+
+
+

File: command_controller.cpp Desc: A CommandController manages the AutoCommands that make up an autonomous route. The AutoCommands are kept in a queue and get executed and removed from the queue in FIFO order. Adds a command to the queue

Parameters
+ + + +
cmdthe AutoCommand we want to add to our list
timeout_secondsthe number of seconds we will let the command run for. If it exceeds this, we cancel it and run on_timeout
+
+
+ +
+
+ +

◆ add() [2/2]

+ +
+
+ + + + + + + + +
void CommandController::add (std::vector< AutoCommand * > cmds)
+
+

Add multiple commands to the queue. No timeout here.

Parameters
+ + +
cmdsthe AutoCommands we want to add to our list
+
+
+ +
+
+ +

◆ add_delay()

+ +
+
+ + + + + + + + +
void CommandController::add_delay (int ms)
+
+

Adds a command that will delay progression of the queue

Parameters
+ + +
ms- number of milliseconds to wait before continuing execution of autonomous
+
+
+ +
+
+ +

◆ last_command_timed_out()

+ +
+
+ + + + + + + +
bool CommandController::last_command_timed_out ()
+
+

last_command_timed_out tells how the last command ended Use this if you want to make decisions based on the end of the last command

Returns
true if the last command timed out. false if it finished regularly
+ +
+
+ +

◆ run()

+ +
+
+ + + + + + + +
void CommandController::run ()
+
+

Begin execution of the queue Execute and remove commands in FIFO order

+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/utils/command_structure/command_controller.h
  • +
  • src/utils/command_structure/command_controller.cpp
  • +
+
+ + + + diff --git a/documentation/html/classCustomEncoder-members.html b/documentation/html/classCustomEncoder-members.html new file mode 100644 index 0000000..fa936ea --- /dev/null +++ b/documentation/html/classCustomEncoder-members.html @@ -0,0 +1,90 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
CustomEncoder Member List
+
+
+ +

This is the complete list of members for CustomEncoder, including all inherited members.

+ + + + + + + +
CustomEncoder(vex::triport::port &port, double ticks_per_rev)CustomEncoder
position(vex::rotationUnits units)CustomEncoder
rotation(vex::rotationUnits units)CustomEncoder
setPosition(double val, vex::rotationUnits units)CustomEncoder
setRotation(double val, vex::rotationUnits units)CustomEncoder
velocity(vex::velocityUnits units)CustomEncoder
+ + + + diff --git a/documentation/html/classCustomEncoder.html b/documentation/html/classCustomEncoder.html new file mode 100644 index 0000000..dfb1463 --- /dev/null +++ b/documentation/html/classCustomEncoder.html @@ -0,0 +1,296 @@ + + + + + + + +RIT VEXU Core API: CustomEncoder Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
CustomEncoder Class Reference
+
+
+ +

#include <custom_encoder.h>

+
+Inheritance diagram for CustomEncoder:
+
+
+ +
+ + + + + + + + + + + + + + +

+Public Member Functions

 CustomEncoder (vex::triport::port &port, double ticks_per_rev)
 
void setRotation (double val, vex::rotationUnits units)
 
void setPosition (double val, vex::rotationUnits units)
 
double rotation (vex::rotationUnits units)
 
double position (vex::rotationUnits units)
 
double velocity (vex::velocityUnits units)
 
+

Detailed Description

+

A wrapper class for the vex encoder that allows the use of 3rd party encoders with different tick-per-revolution values.

+

Constructor & Destructor Documentation

+ +

◆ CustomEncoder()

+ +
+
+ + + + + + + + + + + + + + + + + + +
CustomEncoder::CustomEncoder (vex::triport::port & port,
double ticks_per_rev 
)
+
+

Construct an encoder with a custom number of ticks

Parameters
+ + + +
portthe triport port on the brain the encoder is plugged into
ticks_per_revthe number of ticks the encoder will report for one revolution
+
+
+ +
+
+

Member Function Documentation

+ +

◆ position()

+ +
+
+ + + + + + + + +
double CustomEncoder::position (vex::rotationUnits units)
+
+

get the position that the encoder is at

Parameters
+ + +
unitsthe unit we want the return value to be in
+
+
+
Returns
the position of the encoder in the units specified
+ +
+
+ +

◆ rotation()

+ +
+
+ + + + + + + + +
double CustomEncoder::rotation (vex::rotationUnits units)
+
+

get the rotation that the encoder is at

Parameters
+ + +
unitsthe unit we want the return value to be in
+
+
+
Returns
the rotation of the encoder in the units specified
+ +
+
+ +

◆ setPosition()

+ +
+
+ + + + + + + + + + + + + + + + + + +
void CustomEncoder::setPosition (double val,
vex::rotationUnits units 
)
+
+

sets the stored position of the encoder. Any further movements will be from this value

Parameters
+ + + +
valthe numerical value of the position we are setting to
unitsthe unit of val
+
+
+ +
+
+ +

◆ setRotation()

+ +
+
+ + + + + + + + + + + + + + + + + + +
void CustomEncoder::setRotation (double val,
vex::rotationUnits units 
)
+
+

sets the stored rotation of the encoder. Any further movements will be from this value

Parameters
+ + + +
valthe numerical value of the angle we are setting to
unitsthe unit of val
+
+
+ +
+
+ +

◆ velocity()

+ +
+
+ + + + + + + + +
double CustomEncoder::velocity (vex::velocityUnits units)
+
+

get the velocity that the encoder is moving at

Parameters
+ + +
unitsthe unit we want the return value to be in
+
+
+
Returns
the velocity of the encoder in the units specified
+ +
+
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/documentation/html/classCustomEncoder.png b/documentation/html/classCustomEncoder.png new file mode 100644 index 0000000000000000000000000000000000000000..88e06a2b60fc27308a74888eecee5a5b25fb0f4d GIT binary patch literal 494 zcmeAS@N?(olHy`uVBq!ia0vp^sX!dS!3-qLMZF&bDd_;85ZC|z{{xvX-h3_XKeXJ! zK(jz%`k5C84jcfA2T!`Z0w~8>666=m0OW&#In(Sb3=E8wo-U3d6^w7^9-P#oz~f>) z{pG*^`f=<60gW?d3bJEYT?$G##H~`*HuGl5L64$MVy!B+zlx_EbldMz>EE1F-Bx~6 zQ78AZ!IDTxuaFOlk!##FopTc{&UMAlTxzp#*_D6OYj1b&K300tz5jb~;G;_uHn~q+ zv)23M>?xaKzP*+G!0n}3xhhfimX^nAJ(cX&fqb^xjz7P>;`YkB$tv2>^%9f5WCVI# zTHGFZ=1dwl!<;I{10{EzD)+uSaL4JUf_cKbg*K~>i?K4qM2Rqb$OvROu-KK6p&uw< z0~h%3XJ|ZIZ-$ERwM8D2+_wkc+pF+0p;sj7vPY2n+8I8ak8ds(RrFNu)p+W$dz-t5 zRa)Nrqkm(+bgO%@pLXW*^K^f&w{)99OYCKvx8eKs0z=JypY79_{$q>xn$rj0b6L-; zu1NOv(w=RsYI-95)X!rvQ-YOas@KH4y*{Nb_Sb#yyve&R?kfFxA^EkvnrEGEmrCUq fgRYr3bN({?VyYD8Oskp&j2Q+`S3j3^P6 + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
DelayCommand Member List
+
+
+ +

This is the complete list of members for DelayCommand, including all inherited members.

+ + + + + + +
DelayCommand(int ms)DelayCommandinline
on_timeout()AutoCommandinlinevirtual
run() overrideDelayCommandinlinevirtual
timeout_secondsAutoCommand
withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
+ + + + diff --git a/documentation/html/classDelayCommand.html b/documentation/html/classDelayCommand.html new file mode 100644 index 0000000..5ac6f9b --- /dev/null +++ b/documentation/html/classDelayCommand.html @@ -0,0 +1,184 @@ + + + + + + + +RIT VEXU Core API: DelayCommand Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
DelayCommand Class Reference
+
+
+ +

#include <delay_command.h>

+
+Inheritance diagram for DelayCommand:
+
+
+ + +AutoCommand + +
+ + + + + + + + + + + + + +

+Public Member Functions

 DelayCommand (int ms)
 
bool run () override
 
- Public Member Functions inherited from AutoCommand
virtual bool run ()
 
virtual void on_timeout ()
 
+AutoCommandwithTimeout (double t_seconds)
 
+ + + + +

+Additional Inherited Members

- Public Attributes inherited from AutoCommand
double timeout_seconds = 10.0
 
+

Detailed Description

+

File: delay_command.h Desc: A DelayCommand will make the robot wait the set amount of milliseconds before continuing execution of the autonomous route

+

Constructor & Destructor Documentation

+ +

◆ DelayCommand()

+ +
+
+ + + + + +
+ + + + + + + + +
DelayCommand::DelayCommand (int ms)
+
+inline
+
+

Construct a delay command

Parameters
+ + +
msthe number of milliseconds to delay for
+
+
+ +
+
+

Member Function Documentation

+ +

◆ run()

+ +
+
+ + + + + +
+ + + + + + + +
bool DelayCommand::run ()
+
+inlineoverridevirtual
+
+

Delays for the amount of milliseconds stored in the command Overrides run from AutoCommand

Returns
true when complete
+ +

Reimplemented from AutoCommand.

+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/documentation/html/classDelayCommand.png b/documentation/html/classDelayCommand.png new file mode 100644 index 0000000000000000000000000000000000000000..0275ee5a7ae92b1f70e62ff0c92d7724de5dfdcb GIT binary patch literal 508 zcmeAS@N?(olHy`uVBq!ia0vp^DL@>+!3-pCTvxaYq@)9ULR|m<{|{uoc=NTi|Il&^ z1I+@7>1SRXIB)4W!G&`m#=`8|>vJ_XWT6eW=#j0Ij#RViwpZp9C{d#)I zc7e>^-OtjeNInU*oxOhRasCy;MgK)N^-6i{RaE({D!SN8@jL(KWr0kU&q_O1ZBb?Q z{UTBBd5P=TggYsCG)a&nS8Ae`W76LYsvJ{E42A< z*~(RQYj^`gOJA>6P;A){!SG?B9K(jFatFD7X^nD+c|BjJL@UIX>^5Uz_;X8up&;9t z;lNs6MuzP`fje-4dR{@nNL>z3pcf`AiT>`?7oEVYa&y&bg_E6|${S10rSG@4TX%V;ipR=76F$$JQtw#3`%P1jo2S5~X;b3U=kIG#ao_bzqe5Z2 ryd3+JUyrxVubNZ>^pcWN_g7}wM?qm8e_p=<#uJ05tDnm{r-UW|$HeC2 literal 0 HcmV?d00001 diff --git a/documentation/html/classDriveForwardCommand-members.html b/documentation/html/classDriveForwardCommand-members.html new file mode 100644 index 0000000..375c415 --- /dev/null +++ b/documentation/html/classDriveForwardCommand-members.html @@ -0,0 +1,89 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
DriveForwardCommand Member List
+
+
+ +

This is the complete list of members for DriveForwardCommand, including all inherited members.

+ + + + + + +
DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed=1)DriveForwardCommand
on_timeout() overrideDriveForwardCommandvirtual
run() overrideDriveForwardCommandvirtual
timeout_secondsAutoCommand
withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
+ + + + diff --git a/documentation/html/classDriveForwardCommand.html b/documentation/html/classDriveForwardCommand.html new file mode 100644 index 0000000..25ba864 --- /dev/null +++ b/documentation/html/classDriveForwardCommand.html @@ -0,0 +1,252 @@ + + + + + + + +RIT VEXU Core API: DriveForwardCommand Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
DriveForwardCommand Class Reference
+
+
+ +

#include <drive_commands.h>

+
+Inheritance diagram for DriveForwardCommand:
+
+
+ + +AutoCommand + +
+ + + + + + + + + + + + + + + +

+Public Member Functions

 DriveForwardCommand (TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed=1)
 
bool run () override
 
void on_timeout () override
 
- Public Member Functions inherited from AutoCommand
virtual bool run ()
 
virtual void on_timeout ()
 
+AutoCommandwithTimeout (double t_seconds)
 
+ + + + +

+Additional Inherited Members

- Public Attributes inherited from AutoCommand
double timeout_seconds = 10.0
 
+

Detailed Description

+

AutoCommand wrapper class for the drive_forward function in the TankDrive class

+

Constructor & Destructor Documentation

+ +

◆ DriveForwardCommand()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
DriveForwardCommand::DriveForwardCommand (TankDrivedrive_sys,
Feedbackfeedback,
double inches,
directionType dir,
double max_speed = 1 
)
+
+

File: drive_commands.h Desc: Holds all the AutoCommand subclasses that wrap (currently) TankDrive functions

+

Currently includes:

    +
  • drive_forward
  • +
  • turn_degrees
  • +
  • drive_to_point
  • +
  • turn_to_heading
  • +
  • stop
  • +
+

Also holds AutoCommand subclasses that wrap OdometryBase functions

+

Currently includes:

    +
  • set_position Construct a DriveForward Command
    Parameters
    + + + + + + +
    drive_systhe drive system we are commanding
    feedbackthe feedback controller we are using to execute the drive
    incheshow far forward to drive
    dirthe direction to drive
    max_speed0 -> 1 percentage of the drive systems speed to drive at
    +
    +
    +
  • +
+ +
+
+

Member Function Documentation

+ +

◆ on_timeout()

+ +
+
+ + + + + +
+ + + + + + + +
void DriveForwardCommand::on_timeout ()
+
+overridevirtual
+
+

Cleans up drive system if we time out before finishing

+

reset the drive system if we timeout

+ +

Reimplemented from AutoCommand.

+ +
+
+ +

◆ run()

+ +
+
+ + + + + +
+ + + + + + + +
bool DriveForwardCommand::run ()
+
+overridevirtual
+
+

Run drive_forward Overrides run from AutoCommand

Returns
true when execution is complete, false otherwise
+ +

Reimplemented from AutoCommand.

+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/utils/command_structure/drive_commands.h
  • +
  • src/utils/command_structure/drive_commands.cpp
  • +
+
+ + + + diff --git a/documentation/html/classDriveForwardCommand.png b/documentation/html/classDriveForwardCommand.png new file mode 100644 index 0000000000000000000000000000000000000000..fc8d72471098ed76d0e31fd1ac25e1e6eecfa68b GIT binary patch literal 613 zcmeAS@N?(olHy`uVBq!ia0vp^lYlsYgBeI3ZM_4cqyv0HT>t<74`jZ0^R=}9&~gg{ z%>s$(XI>mQZ~!PCJn8ZZpd4pOkY6wZkPimtOtY^rFfe}bba4!+V0=6GcHV0P9+v6a z3OD}$fAqL}U7xH~Yqf$%j_FzvuPYIPlf#!xxfG)?@rh51kY^PL-wEEdx>46&rBc5B zm#(U`Dc{}qbLNFc{nxqsHRjvl%$KJtc)!jSJF&QZ%BgoVcjbD=AG>|cc{$suQ~%ex z+`3V;VfOzCLHmx_2i}@)w|0xVq|p5^sn|N#m9bsZ{%d5X+~@n4KK0h!v#nR`roXZV z^0ys`OVefatW($*;BiTL3IZnwdTB0Q$BZzr`q1u((}O$m>?KDUHx3vIVCg! E0BqtSOaK4? literal 0 HcmV?d00001 diff --git a/documentation/html/classDriveStopCommand-members.html b/documentation/html/classDriveStopCommand-members.html new file mode 100644 index 0000000..877cc5e --- /dev/null +++ b/documentation/html/classDriveStopCommand-members.html @@ -0,0 +1,89 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
DriveStopCommand Member List
+
+
+ +

This is the complete list of members for DriveStopCommand, including all inherited members.

+ + + + + + +
DriveStopCommand(TankDrive &drive_sys)DriveStopCommand
on_timeout()AutoCommandinlinevirtual
run() overrideDriveStopCommandvirtual
timeout_secondsAutoCommand
withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
+ + + + diff --git a/documentation/html/classDriveStopCommand.html b/documentation/html/classDriveStopCommand.html new file mode 100644 index 0000000..0691bb1 --- /dev/null +++ b/documentation/html/classDriveStopCommand.html @@ -0,0 +1,178 @@ + + + + + + + +RIT VEXU Core API: DriveStopCommand Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
DriveStopCommand Class Reference
+
+
+ +

#include <drive_commands.h>

+
+Inheritance diagram for DriveStopCommand:
+
+
+ + +AutoCommand + +
+ + + + + + + + + + + + + +

+Public Member Functions

 DriveStopCommand (TankDrive &drive_sys)
 
bool run () override
 
- Public Member Functions inherited from AutoCommand
virtual bool run ()
 
virtual void on_timeout ()
 
+AutoCommandwithTimeout (double t_seconds)
 
+ + + + +

+Additional Inherited Members

- Public Attributes inherited from AutoCommand
double timeout_seconds = 10.0
 
+

Detailed Description

+

AutoCommand wrapper class for the stop() function in the TankDrive class

+

Constructor & Destructor Documentation

+ +

◆ DriveStopCommand()

+ +
+
+ + + + + + + + +
DriveStopCommand::DriveStopCommand (TankDrivedrive_sys)
+
+

Construct a DriveStop Command

Parameters
+ + +
drive_systhe drive system we are commanding
+
+
+ +
+
+

Member Function Documentation

+ +

◆ run()

+ +
+
+ + + + + +
+ + + + + + + +
bool DriveStopCommand::run ()
+
+overridevirtual
+
+

Stop the drive system Overrides run from AutoCommand

Returns
true when execution is complete, false otherwise
+

Stop the drive train Overrides run from AutoCommand

Returns
true when execution is complete, false otherwise
+ +

Reimplemented from AutoCommand.

+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/utils/command_structure/drive_commands.h
  • +
  • src/utils/command_structure/drive_commands.cpp
  • +
+
+ + + + diff --git a/documentation/html/classDriveStopCommand.png b/documentation/html/classDriveStopCommand.png new file mode 100644 index 0000000000000000000000000000000000000000..535e91ddba4db331b47fc65da562e61ce3605bda GIT binary patch literal 549 zcmeAS@N?(olHy`uVBq!ia0vp^)j%A;!3-q%ihk_?QqloFA+G=b{|7Q(y!l$%e`vXd zfo6fk^fNCG95?_J51w>+1yGK&B*-tA0mugfbEer>7#J8gc)B=-R4~4so85O{+ z+_qWQdDb7y-}F6C`kl4yw%L!5{LIs0zbTLwep66*%A@BNh3_Pcl3~Z?oUTcr2{>{MS$a=!s30hXe0e zGI*Lr-4B^0v-+so$&J5`=RBV?TbW_UdUgh%OD^9Y8}i#t+`Dl3!Sqf4bLZ-tG4NbV zVm=U|YsS!X6)Pik=1gB9pGnIyHmYW>`NwiwJg!d1b86Gh$(dUNCf(Cg65idv=FawY zldrsPopfc@>2G^~)=T`#6@B+x#V(Ui$@W~LQ_|A^_x2~qXFENZ<5beo_9kq}TW9$j zCK-PpYrlH8`#7JsUz>3Brd_6*`z=2|y0A*>jqC~bH_C@(zpcEsZqxj^$?MNe-a4oB zM(P5sZJxf_Z`8}IZqJfkWpelZwsSyliyvCDsnXf*h~HfAORBa1ZDVpgrB)xEwq)b1 eGiJuK7t3=pqz0CJK6Vcnp$wj`elF{r5}E*In+j3@ literal 0 HcmV?d00001 diff --git a/documentation/html/classDriveToPointCommand-members.html b/documentation/html/classDriveToPointCommand-members.html new file mode 100644 index 0000000..8765c93 --- /dev/null +++ b/documentation/html/classDriveToPointCommand-members.html @@ -0,0 +1,89 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
DriveToPointCommand Member List
+
+
+ +

This is the complete list of members for DriveToPointCommand, including all inherited members.

+ + + + + + +
DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed=1)DriveToPointCommand
DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, Vector2D::point_t point, directionType dir, double max_speed=1)DriveToPointCommand
run() overrideDriveToPointCommandvirtual
timeout_secondsAutoCommand
withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
+ + + + diff --git a/documentation/html/classDriveToPointCommand.html b/documentation/html/classDriveToPointCommand.html new file mode 100644 index 0000000..6037c14 --- /dev/null +++ b/documentation/html/classDriveToPointCommand.html @@ -0,0 +1,274 @@ + + + + + + + +RIT VEXU Core API: DriveToPointCommand Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
DriveToPointCommand Class Reference
+
+
+ +

#include <drive_commands.h>

+
+Inheritance diagram for DriveToPointCommand:
+
+
+ + +AutoCommand + +
+ + + + + + + + + + + + + + + +

+Public Member Functions

 DriveToPointCommand (TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed=1)
 
 DriveToPointCommand (TankDrive &drive_sys, Feedback &feedback, Vector2D::point_t point, directionType dir, double max_speed=1)
 
bool run () override
 
- Public Member Functions inherited from AutoCommand
virtual bool run ()
 
virtual void on_timeout ()
 
+AutoCommandwithTimeout (double t_seconds)
 
+ + + + +

+Additional Inherited Members

- Public Attributes inherited from AutoCommand
double timeout_seconds = 10.0
 
+

Detailed Description

+

AutoCommand wrapper class for the drive_to_point function in the TankDrive class

+

Constructor & Destructor Documentation

+ +

◆ DriveToPointCommand() [1/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
DriveToPointCommand::DriveToPointCommand (TankDrivedrive_sys,
Feedbackfeedback,
double x,
double y,
directionType dir,
double max_speed = 1 
)
+
+

Construct a DriveForward Command

Parameters
+ + + + + + + +
drive_systhe drive system we are commanding
feedbackthe feedback controller we are using to execute the drive
xwhere to drive in the x dimension
ywhere to drive in the y dimension
dirthe direction to drive
max_speed0 -> 1 percentage of the drive systems speed to drive at
+
+
+ +
+
+ +

◆ DriveToPointCommand() [2/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
DriveToPointCommand::DriveToPointCommand (TankDrivedrive_sys,
Feedbackfeedback,
Vector2D::point_t point,
directionType dir,
double max_speed = 1 
)
+
+

Construct a DriveForward Command

Parameters
+ + + + + + +
drive_systhe drive system we are commanding
feedbackthe feedback controller we are using to execute the drive
pointthe point to drive to
dirthe direction to drive
max_speed0 -> 1 percentage of the drive systems speed to drive at
+
+
+ +
+
+

Member Function Documentation

+ +

◆ run()

+ +
+
+ + + + + +
+ + + + + + + +
bool DriveToPointCommand::run ()
+
+overridevirtual
+
+

Run drive_to_point Overrides run from AutoCommand

Returns
true when execution is complete, false otherwise
+ +

Reimplemented from AutoCommand.

+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/utils/command_structure/drive_commands.h
  • +
  • src/utils/command_structure/drive_commands.cpp
  • +
+
+ + + + diff --git a/documentation/html/classDriveToPointCommand.png b/documentation/html/classDriveToPointCommand.png new file mode 100644 index 0000000000000000000000000000000000000000..690e372fedbe6424ef275b37e2ee92c4dd0933b1 GIT binary patch literal 595 zcmeAS@N?(olHy`uVBq!ia0vp^JwP15!3-q-Jj#s#QqloFA+G=b{|7Q(y!l$%e`vXd zfo6fk^fNCG95?_J51w>+1yGK&B*-tA0mugfbEer>7#JAudAc};R4~4sd%JIqf`Dsz z?xb`7{_EStP3WGs_Hu683D2(^cp{j*HRgmbnQ}=(Vd4{s79P(k5WX{EDw zAANk?=oi-#=4R@|E=Yfuq=h``=;G|c6JKq>jTl%GqG+28X{+&0>K^srIs=hr8yeU)!->b6%6-fS#C>DOG% z-x(><(+*U%ykbzPbo*ni;MqSx5rI9`mQG<~WRQEn%COjA(wWz$6V7@VO+Ia5=6v!< zCKJQ_35*Q=#Nz*f$Ij%4Bup}4Q&jep17X*+lh3N6gQAPJm7i6+b^X@@mDr7zB9iA1 zzWng-;m>_2;=Q2mhLxzJ51H>2b lliMU47 + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
FeedForward Member List
+
+
+ +

This is the complete list of members for FeedForward, including all inherited members.

+ + + +
calculate(double v, double a, double pid_ref=0.0)FeedForwardinline
FeedForward(ff_config_t &cfg)FeedForwardinline
+ + + + diff --git a/documentation/html/classFeedForward.html b/documentation/html/classFeedForward.html new file mode 100644 index 0000000..687b0e0 --- /dev/null +++ b/documentation/html/classFeedForward.html @@ -0,0 +1,199 @@ + + + + + + + +RIT VEXU Core API: FeedForward Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
FeedForward Class Reference
+
+
+ +

#include <feedforward.h>

+ + + + +

+Classes

struct  ff_config_t
 
+ + + + + + +

+Public Member Functions

 FeedForward (ff_config_t &cfg)
 
double calculate (double v, double a, double pid_ref=0.0)
 Perform the feedforward calculation.
 
+

Detailed Description

+

FeedForward

+

Stores the feedfoward constants, and allows for quick computation. Feedfoward should be used in systems that require smooth precise movements and have high inertia, such as drivetrains and lifts.

+

This is best used alongside a PID loop, with the form: output = pid.get() + feedforward.calculate(v, a);

+

In this case, the feedforward does the majority of the heavy lifting, and the pid loop only corrects for inconsistencies

+

For information about tuning feedforward, I reccommend looking at this post: https://www.chiefdelphi.com/t/paper-frc-drivetrain-characterization/160915 (yes I know it's for FRC but trust me, it's useful)

+
Author
Ryan McGee
+
Date
6/13/2022
+

Constructor & Destructor Documentation

+ +

◆ FeedForward()

+ +
+
+ + + + + +
+ + + + + + + + +
FeedForward::FeedForward (ff_config_tcfg)
+
+inline
+
+

Creates a FeedForward object.

Parameters
+ + +
cfgConfiguration Struct for tuning
+
+
+ +
+
+

Member Function Documentation

+ +

◆ calculate()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + +
double FeedForward::calculate (double v,
double a,
double pid_ref = 0.0 
)
+
+inline
+
+ +

Perform the feedforward calculation.

+

This calculation is the equation: F = kG + kS*sgn(v) + kV*v + kA*a

+
Parameters
+ + + +
vRequested velocity of system
aRequested acceleration of system
+
+
+
Returns
A feedforward that should closely represent the system if tuned correctly
+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/documentation/html/classFeedback-members.html b/documentation/html/classFeedback-members.html new file mode 100644 index 0000000..fc5a22e --- /dev/null +++ b/documentation/html/classFeedback-members.html @@ -0,0 +1,94 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
Feedback Member List
+
+
+ +

This is the complete list of members for Feedback, including all inherited members.

+ + + + + + + + + + + +
FeedbackType enum name (defined in Feedback)Feedback
FeedforwardType enum value (defined in Feedback)Feedback
get()=0Feedbackpure virtual
get_type() (defined in Feedback)Feedbackinlinevirtual
init(double start_pt, double set_pt)=0Feedbackpure virtual
is_on_target()=0Feedbackpure virtual
OtherType enum value (defined in Feedback)Feedback
PIDType enum value (defined in Feedback)Feedback
set_limits(double lower, double upper)=0Feedbackpure virtual
update(double val)=0Feedbackpure virtual
+ + + + diff --git a/documentation/html/classFeedback.html b/documentation/html/classFeedback.html new file mode 100644 index 0000000..9412358 --- /dev/null +++ b/documentation/html/classFeedback.html @@ -0,0 +1,315 @@ + + + + + + + +RIT VEXU Core API: Feedback Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
Feedback Class Referenceabstract
+
+
+ +

#include <feedback_base.h>

+
+Inheritance diagram for Feedback:
+
+
+ + +MotionController +PID +PIDFF + +
+ + + + +

+Public Types

enum  FeedbackType { PIDType +, FeedforwardType +, OtherType + }
 
+ + + + + + + + + + + + + +

+Public Member Functions

virtual void init (double start_pt, double set_pt)=0
 
virtual double update (double val)=0
 
virtual double get ()=0
 
virtual void set_limits (double lower, double upper)=0
 
virtual bool is_on_target ()=0
 
+virtual Feedback::FeedbackType get_type ()
 
+

Detailed Description

+

Interface so that subsystems can easily switch between feedback loops

+
Author
Ryan McGee
+
Date
9/25/2022
+

Member Function Documentation

+ +

◆ get()

+ +
+
+ + + + + +
+ + + + + + + +
virtual double Feedback::get ()
+
+pure virtual
+
+
Returns
the last saved result from the feedback controller
+ +

Implemented in MotionController, PID, and PIDFF.

+ +
+
+ +

◆ init()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
virtual void Feedback::init (double start_pt,
double set_pt 
)
+
+pure virtual
+
+

Initialize the feedback controller for a movement

+
Parameters
+ + + +
start_ptthe current sensor value
set_ptwhere the sensor value should be
+
+
+ +

Implemented in MotionController, PID, and PIDFF.

+ +
+
+ +

◆ is_on_target()

+ +
+
+ + + + + +
+ + + + + + + +
virtual bool Feedback::is_on_target ()
+
+pure virtual
+
+
Returns
true if the feedback controller has reached it's setpoint
+ +

Implemented in MotionController, PID, and PIDFF.

+ +
+
+ +

◆ set_limits()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
virtual void Feedback::set_limits (double lower,
double upper 
)
+
+pure virtual
+
+

Clamp the upper and lower limits of the output. If both are 0, no limits should be applied.

+
Parameters
+ + + +
lowerUpper limit
upperLower limit
+
+
+ +

Implemented in MotionController, PID, and PIDFF.

+ +
+
+ +

◆ update()

+ +
+
+ + + + + +
+ + + + + + + + +
virtual double Feedback::update (double val)
+
+pure virtual
+
+

Iterate the feedback loop once with an updated sensor value

+
Parameters
+ + +
valvalue from the sensor
+
+
+
Returns
feedback loop result
+ +

Implemented in MotionController, PID, and PIDFF.

+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/documentation/html/classFeedback.png b/documentation/html/classFeedback.png new file mode 100644 index 0000000000000000000000000000000000000000..fe590a2623212573b01ca6e3a12913cdb44220a5 GIT binary patch literal 792 zcmeAS@N?(olHy`uVBq!ia0y~yU<6`@01jp#S+j*V2}nr?_=LFr|NkGzeDUUMY5$?+ z76zIH64TGTIB?(qP&|0jhFmGyEx<8m9GZw3fwip zlqbB_TyFpGg?@`mY`niu(QEr^xS{@&+sovsd|AsA*Ou_Py)5ScS9N3U&D)`Je?DzC zdAoAiWB%obbnb7H@5HbcUErtE(%9>z%NYb1zP(^%au5yV3h=ytT+=}j$T)d4V-C|5 z!KDmGT{IjtfdXDrn5GCVWmxK>iNXE9^U}Wezt=N7kg*Fi{9k!agH=P-i_xnys3B;P z$bu=vaQiaWZe9K|I{R(pKDG48ON=A*{3o4zU~IWKWD-|rkf)Zam+HzX8dH}9z4O{_ zXwbWT_0PjHd-teh9#z{^|GfM3ZnZt<%I21s?^Kcfm~w7!%=T{053}EFzVz^V_w2HK z`Ar^Cd+)C*nOA5JQn2RI+?f8YYM%BRR+rqGns}=4{<62T&A-UW)!Dy$yQbvUvybbP zmik-%U3@9EaLhtzt7A3{>@xVzqjsN6Ef-E>25F8m#KD>je$O&0P^{w zkV(KGMG6X#z)p?awOfNDbk=XZ=J!z8@;_tHp-#5TCys3greOw8S3j3^P6 + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
Flywheel Member List
+
+
+ +

This is the complete list of members for Flywheel, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + +
Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio)Flywheel
Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio)Flywheel
Flywheel(motor_group &motors, double tbh_gain, const double ratio)Flywheel
Flywheel(motor_group &motors, const double ratio)Flywheel
getDesiredRPM()Flywheel
getFeedforwardValue()Flywheel
getMotors()Flywheel
getPID()Flywheel
getPIDValue()Flywheel
getRPM()Flywheel
getTBHGain()Flywheel
isTaskRunning()Flywheel
measureRPM()Flywheel
setPIDTarget(double value)Flywheel
spin_manual(double speed, directionType dir=fwd)Flywheel
spin_raw(double speed, directionType dir=fwd)Flywheel
spinRPM(int rpm)Flywheel
stop()Flywheel
stopMotors()Flywheel
stopNonTasks()Flywheel
updatePID(double value)Flywheel
+ + + + diff --git a/documentation/html/classFlywheel.html b/documentation/html/classFlywheel.html new file mode 100644 index 0000000..4112a90 --- /dev/null +++ b/documentation/html/classFlywheel.html @@ -0,0 +1,684 @@ + + + + + + + +RIT VEXU Core API: Flywheel Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
Flywheel Class Reference
+
+
+ +

#include <flywheel.h>

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

 Flywheel (motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio)
 
 Flywheel (motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio)
 
 Flywheel (motor_group &motors, double tbh_gain, const double ratio)
 
 Flywheel (motor_group &motors, const double ratio)
 
double getDesiredRPM ()
 
bool isTaskRunning ()
 
motor_group * getMotors ()
 
double measureRPM ()
 
double getRPM ()
 
PIDgetPID ()
 
double getPIDValue ()
 
double getFeedforwardValue ()
 
double getTBHGain ()
 
void setPIDTarget (double value)
 
void updatePID (double value)
 
void spin_raw (double speed, directionType dir=fwd)
 
void spin_manual (double speed, directionType dir=fwd)
 
void spinRPM (int rpm)
 
void stop ()
 
void stopMotors ()
 
void stopNonTasks ()
 
+

Detailed Description

+

a Flywheel class that handles all control of a high inertia spinning disk It gives multiple options for what control system to use in order to control wheel velocity and functions alerting the user when the flywheel is up to speed. Flywheel is a set and forget class. Once you create it you can call spinRPM or stop on it at any time and it will take all necessary steps to accomplish this

+

Constructor & Destructor Documentation

+ +

◆ Flywheel() [1/4]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Flywheel::Flywheel (motor_group & motors,
PID::pid_config_tpid_config,
FeedForward::ff_config_tff_config,
const double ratio 
)
+
+

Create the Flywheel object using PID + feedforward for control.

Parameters
+ + + + + +
motorspointer to the motors on the fly wheel
pid_configpointer the pid config to use
ff_configthe feedforward config to use
ratioratio of the whatever just multiplies the velocity
+
+
+

Create the Flywheel object using PID + feedforward for control.

+ +
+
+ +

◆ Flywheel() [2/4]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
Flywheel::Flywheel (motor_group & motors,
FeedForward::ff_config_tff_config,
const double ratio 
)
+
+

Create the Flywheel object using only feedforward for control

Parameters
+ + + + +
motorsthe motors on the fly wheel
ff_configthe feedforward config to use
ratioratio of the whatever just multiplies the velocity
+
+
+

Create the Flywheel object using only feedforward for control

+ +
+
+ +

◆ Flywheel() [3/4]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
Flywheel::Flywheel (motor_group & motors,
double tbh_gain,
const double ratio 
)
+
+

Create the Flywheel object using Take Back Half for control

Parameters
+ + + + +
motorsthe motors on the fly wheel
tbh_gainthe TBH control paramater
ratioratio of the whatever just multiplies the velocity
+
+
+

Create the Flywheel object using Take Back Half for control

+ +
+
+ +

◆ Flywheel() [4/4]

+ +
+
+ + + + + + + + + + + + + + + + + + +
Flywheel::Flywheel (motor_group & motors,
const double ratio 
)
+
+

Create the Flywheel object using Bang Bang for control

Parameters
+ + + +
motorsthe motors on the fly wheel
ratioratio of the whatever just multiplies the velocity
+
+
+

Create the Flywheel object using Bang Bang for control

+ +
+
+

Member Function Documentation

+ +

◆ getDesiredRPM()

+ +
+
+ + + + + + + +
double Flywheel::getDesiredRPM ()
+
+

Return the RPM that the flywheel is currently trying to achieve

Returns
RPM the target rpm
+

Return the current value that the RPM should be set to

+ +
+
+ +

◆ getFeedforwardValue()

+ +
+
+ + + + + + + +
double Flywheel::getFeedforwardValue ()
+
+

returns the current OUT value of the PID - the value that the PID would set the motors to

+

returns the current OUT value of the Feedforward - the value that the Feedforward would set the motors to

Returns
the voltage that feedforward wants the motors at to achieve the target RPM
+ +
+
+ +

◆ getMotors()

+ +
+
+ + + + + + + +
motor_group * Flywheel::getMotors ()
+
+

Returns a POINTER to the motors

+

Returns a POINTER TO the motors; not currently used.

Returns
motorPointer -pointer to the motors
+ +
+
+ +

◆ getPID()

+ +
+
+ + + + + + + +
PID * Flywheel::getPID ()
+
+

Returns a POINTER to the PID.

+

Returns a POINTER TO the PID; not currently used.

Returns
pidPointer -pointer to the PID
+ +
+
+ +

◆ getPIDValue()

+ +
+
+ + + + + + + +
double Flywheel::getPIDValue ()
+
+

returns the current OUT value of the PID - the value that the PID would set the motors to

+

returns the current OUT value of the PID - the value that the PID would set the motors to

Returns
the voltage that PID wants the motors at to achieve the target RPM
+ +
+
+ +

◆ getRPM()

+ +
+
+ + + + + + + +
double Flywheel::getRPM ()
+
+

return the current smoothed velocity of the flywheel motors, in RPM

+ +
+
+ +

◆ getTBHGain()

+ +
+
+ + + + + + + +
double Flywheel::getTBHGain ()
+
+

get the gain used for TBH control

+

get the gain used for TBH control

Returns
the gain used in TBH control
+ +
+
+ +

◆ isTaskRunning()

+ +
+
+ + + + + + + +
bool Flywheel::isTaskRunning ()
+
+

Checks if the background RPM controlling task is running

Returns
true if the task is running
+

Checks if the background RPM controlling task is running

Returns
taskRunning - If the task is running
+ +
+
+ +

◆ measureRPM()

+ +
+
+ + + + + + + +
double Flywheel::measureRPM ()
+
+

make a measurement of the current RPM of the flywheel motor and return a smoothed version

+

return the current velocity of the flywheel motors, in RPM

Returns
the measured velocity of the flywheel
+ +
+
+ +

◆ setPIDTarget()

+ +
+
+ + + + + + + + +
void Flywheel::setPIDTarget (double value)
+
+

Sets the value of the PID target

Parameters
+ + +
value- desired value of the PID
+
+
+ +
+
+ +

◆ spin_manual()

+ +
+
+ + + + + + + + + + + + + + + + + + +
void Flywheel::spin_manual (double speed,
directionType dir = fwd 
)
+
+

Spin motors using voltage; defaults forward at 12 volts FOR USE BY OPCONTROL AND AUTONOMOUS - this only applies if the RPM thread is not running

Parameters
+ + + +
speed- speed (between -1 and 1) to set the motor
dir- direction that the motor moves in; defaults to forward
+
+
+ +
+
+ +

◆ spin_raw()

+ +
+
+ + + + + + + + + + + + + + + + + + +
void Flywheel::spin_raw (double speed,
directionType dir = fwd 
)
+
+

Spin motors using voltage; defaults forward at 12 volts FOR USE BY TASKS ONLY

Parameters
+ + + +
speed- speed (between -1 and 1) to set the motor
dir- direction that the motor moves in; defaults to forward
+
+
+ +
+
+ +

◆ spinRPM()

+ +
+
+ + + + + + + + +
void Flywheel::spinRPM (int inputRPM)
+
+

starts or sets the RPM thread at new value what control scheme is dependent on control_style

Parameters
+ + +
rpm- the RPM we want to spin at
+
+
+

starts or sets the RPM thread at new value what control scheme is dependent on control_style

Parameters
+ + +
inputRPM- set the current RPM
+
+
+ +
+
+ +

◆ stop()

+ +
+
+ + + + + + + +
void Flywheel::stop ()
+
+

stop the RPM thread and the wheel

+ +
+
+ +

◆ stopMotors()

+ +
+
+ + + + + + + +
void Flywheel::stopMotors ()
+
+

stop only the motors; exclusively for BANG BANG use

+ +
+
+ +

◆ stopNonTasks()

+ +
+
+ + + + + + + +
void Flywheel::stopNonTasks ()
+
+

Stop the motors if the task isn't running - stop manual control

+ +
+
+ +

◆ updatePID()

+ +
+
+ + + + + + + + +
void Flywheel::updatePID (double value)
+
+

updates the value of the PID

Parameters
+ + +
value- value to update the PID with
+
+
+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/subsystems/flywheel.h
  • +
  • src/subsystems/flywheel.cpp
  • +
+
+ + + + diff --git a/documentation/html/classFlywheelStopCommand-members.html b/documentation/html/classFlywheelStopCommand-members.html new file mode 100644 index 0000000..0fa5c63 --- /dev/null +++ b/documentation/html/classFlywheelStopCommand-members.html @@ -0,0 +1,89 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
FlywheelStopCommand Member List
+
+
+ +

This is the complete list of members for FlywheelStopCommand, including all inherited members.

+ + + + + + +
FlywheelStopCommand(Flywheel &flywheel)FlywheelStopCommand
on_timeout()AutoCommandinlinevirtual
run() overrideFlywheelStopCommandvirtual
timeout_secondsAutoCommand
withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
+ + + + diff --git a/documentation/html/classFlywheelStopCommand.html b/documentation/html/classFlywheelStopCommand.html new file mode 100644 index 0000000..d0bb13c --- /dev/null +++ b/documentation/html/classFlywheelStopCommand.html @@ -0,0 +1,177 @@ + + + + + + + +RIT VEXU Core API: FlywheelStopCommand Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
FlywheelStopCommand Class Reference
+
+
+ +

#include <flywheel_commands.h>

+
+Inheritance diagram for FlywheelStopCommand:
+
+
+ + +AutoCommand + +
+ + + + + + + + + + + + + +

+Public Member Functions

 FlywheelStopCommand (Flywheel &flywheel)
 
bool run () override
 
- Public Member Functions inherited from AutoCommand
virtual bool run ()
 
virtual void on_timeout ()
 
+AutoCommandwithTimeout (double t_seconds)
 
+ + + + +

+Additional Inherited Members

- Public Attributes inherited from AutoCommand
double timeout_seconds = 10.0
 
+

Detailed Description

+

AutoCommand wrapper class for the stop function in the Flywheel class

+

Constructor & Destructor Documentation

+ +

◆ FlywheelStopCommand()

+ +
+
+ + + + + + + + +
FlywheelStopCommand::FlywheelStopCommand (Flywheelflywheel)
+
+

Construct a FlywheelStopCommand

Parameters
+ + +
flywheelthe flywheel system we are commanding
+
+
+ +
+
+

Member Function Documentation

+ +

◆ run()

+ +
+
+ + + + + +
+ + + + + + + +
bool FlywheelStopCommand::run ()
+
+overridevirtual
+
+

Run stop Overrides run from AutoCommand

Returns
true when execution is complete, false otherwise
+ +

Reimplemented from AutoCommand.

+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/utils/command_structure/flywheel_commands.h
  • +
  • src/utils/command_structure/flywheel_commands.cpp
  • +
+
+ + + + diff --git a/documentation/html/classFlywheelStopCommand.png b/documentation/html/classFlywheelStopCommand.png new file mode 100644 index 0000000000000000000000000000000000000000..3c321f66210de7d5a34627551a35b1ad207189a8 GIT binary patch literal 621 zcmeAS@N?(olHy`uVBq!ia0vp^{XiVR!3-qDuU?A=QqloFA+G=b{|7Q(y!l$%e`vXd zfo6fk^fNCG95?_J51w>+1yGK&B*-tA0mugfbEer>7#J9Tc)B=-R4~4sd%Nhdf`H5H zWv8zG|9@0lvd~mmGb+_N*Z0sy!H$OoU$v8Z3Ka!BizM%~tK@>P-cOd-iaGTvm2)>= zU;m@!UgC*5{}+z)|0bV)XFO@y(qre&SBK7CDSG^}u-(qr&6m=9=gzraAm)&cFTJ&C}&X0RiIe(X6)`yEG6LO_q$$wcn`>Tc7*MFMa zQYXyzYF}EoiqYfJk$QcPOUG&vIPG(%;jvPN2K5TY15P^6K3A<(-7@3+vdvR2WZBj2 zV|bu_hn*pZSo|+~zJOB%2a9JE+xLko(m*`>(d4r4-*i1~gCFlT*gC_^({xhF#5I96 zZ_eq?FaKG>vD0mm-ltZ7sbaaG^SqmFkHx4hJ(r^^qqauGJaD&y<&*6-L6ON5_XjOr zwqakSxM}J15U;cvd;R?V^~dCVC*FCUK6z!o$S)I~$0d7@Ib?EFrrxT}*PQ?3io$cd z)Qy+^U+}iyHQVlTrtQbfvI{oHjx6W3i?2NVy!d~O+*O5@$rkZX|4E(?-&=pn)^c5V zb(-Dz=}Tt4yLYp`{ + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
FlywheelStopMotorsCommand Member List
+
+
+ +

This is the complete list of members for FlywheelStopMotorsCommand, including all inherited members.

+ + + + + + +
FlywheelStopMotorsCommand(Flywheel &flywheel)FlywheelStopMotorsCommand
on_timeout()AutoCommandinlinevirtual
run() overrideFlywheelStopMotorsCommandvirtual
timeout_secondsAutoCommand
withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
+ + + + diff --git a/documentation/html/classFlywheelStopMotorsCommand.html b/documentation/html/classFlywheelStopMotorsCommand.html new file mode 100644 index 0000000..3962966 --- /dev/null +++ b/documentation/html/classFlywheelStopMotorsCommand.html @@ -0,0 +1,177 @@ + + + + + + + +RIT VEXU Core API: FlywheelStopMotorsCommand Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
FlywheelStopMotorsCommand Class Reference
+
+
+ +

#include <flywheel_commands.h>

+
+Inheritance diagram for FlywheelStopMotorsCommand:
+
+
+ + +AutoCommand + +
+ + + + + + + + + + + + + +

+Public Member Functions

 FlywheelStopMotorsCommand (Flywheel &flywheel)
 
bool run () override
 
- Public Member Functions inherited from AutoCommand
virtual bool run ()
 
virtual void on_timeout ()
 
+AutoCommandwithTimeout (double t_seconds)
 
+ + + + +

+Additional Inherited Members

- Public Attributes inherited from AutoCommand
double timeout_seconds = 10.0
 
+

Detailed Description

+

AutoCommand wrapper class for the stopMotors function in the Flywheel class

+

Constructor & Destructor Documentation

+ +

◆ FlywheelStopMotorsCommand()

+ +
+
+ + + + + + + + +
FlywheelStopMotorsCommand::FlywheelStopMotorsCommand (Flywheelflywheel)
+
+

Construct a FlywheeStopMotors Command

Parameters
+ + +
flywheelthe flywheel system we are commanding
+
+
+ +
+
+

Member Function Documentation

+ +

◆ run()

+ +
+
+ + + + + +
+ + + + + + + +
bool FlywheelStopMotorsCommand::run ()
+
+overridevirtual
+
+

Run stop Overrides run from AutoCommand

Returns
true when execution is complete, false otherwise
+ +

Reimplemented from AutoCommand.

+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/utils/command_structure/flywheel_commands.h
  • +
  • src/utils/command_structure/flywheel_commands.cpp
  • +
+
+ + + + diff --git a/documentation/html/classFlywheelStopMotorsCommand.png b/documentation/html/classFlywheelStopMotorsCommand.png new file mode 100644 index 0000000000000000000000000000000000000000..1d73925219da75f2122ab845b0a56ba24386722f GIT binary patch literal 678 zcmeAS@N?(olHy`uVBq!ia0vp^+kiNLgBeIR8`rM{QqloFA+G=b{|7Q(y!l$%e`vXd zfo6fk^fNCG95?_J51w>+1yGK&B*-tA0mugfbEer>7#NrgJzX3_Dj46+jpbWxz|*4M z9CG%r|DFpI>TfWuE|oqRx~zrexO`u7+(w<#M)NmJc#>0;Gil4D&P!_FJbS}G zk59Yu?EdNBSm^q8*LR0E8@KP@y8Ea(+fIcgzjIf;o6`CBoPf39yHgpgig)*aoaHyq zW7_@>-?nXUCtv;CcH{TK>Lyv={f)A+rswpNx9^ERtmhde@k^X5NiFAzA**9 zDm%Bx;o4hU!PD-M4J!F3?cb?nsvcMK)V4J9j5@i|^OBeLw@o^yOPCt|FBNAvv)poH z{Cdru&yU2dOn)*@x+JV!e;cn`ccC5cl+MXF-f(+da#g+6 zQ~T}#&u`nhFUzdGTT6JRi%nS4{foP-C!y={wQh#$jG~Uyc2f^ltlV%q$Ebexw%t?K zYCrE?|Kz7wnat{h%c;k;n_r&nTl6Y)b?TcW*@Iroqs{UYX5Y5Gp_%{5a#qc;bB0nI zmR{JVry)OiNxa6s%v-O2y_mNrGRf}PyGc)EcK`U*6YILVJEB%&mU5-|Zwt>Q23uZV zytnapuC3R?MCYnQmsKdDgT6)Mev!Je<8jK!AQdA@pO5GLfg z)b?-DtlC2Ujq=t1wZ0WUzu&t}?YzL>B-6 literal 0 HcmV?d00001 diff --git a/documentation/html/classFlywheelStopNonTasksCommand-members.html b/documentation/html/classFlywheelStopNonTasksCommand-members.html new file mode 100644 index 0000000..69e1e10 --- /dev/null +++ b/documentation/html/classFlywheelStopNonTasksCommand-members.html @@ -0,0 +1,87 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
FlywheelStopNonTasksCommand Member List
+
+
+ +

This is the complete list of members for FlywheelStopNonTasksCommand, including all inherited members.

+ + + + +
on_timeout()AutoCommandinlinevirtual
timeout_secondsAutoCommand
withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
+ + + + diff --git a/documentation/html/classFlywheelStopNonTasksCommand.html b/documentation/html/classFlywheelStopNonTasksCommand.html new file mode 100644 index 0000000..d69510f --- /dev/null +++ b/documentation/html/classFlywheelStopNonTasksCommand.html @@ -0,0 +1,115 @@ + + + + + + + +RIT VEXU Core API: FlywheelStopNonTasksCommand Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
FlywheelStopNonTasksCommand Class Reference
+
+
+ +

#include <flywheel_commands.h>

+
+Inheritance diagram for FlywheelStopNonTasksCommand:
+
+
+ + +AutoCommand + +
+ + + + + + + + + + + + +

+Additional Inherited Members

- Public Member Functions inherited from AutoCommand
virtual bool run ()
 
virtual void on_timeout ()
 
+AutoCommandwithTimeout (double t_seconds)
 
- Public Attributes inherited from AutoCommand
double timeout_seconds = 10.0
 
+

Detailed Description

+

AutoCommand wrapper class for the stopNonTasks function in the Flywheel class

+

The documentation for this class was generated from the following files:
    +
  • include/utils/command_structure/flywheel_commands.h
  • +
  • src/utils/command_structure/flywheel_commands.cpp
  • +
+
+ + + + diff --git a/documentation/html/classFlywheelStopNonTasksCommand.png b/documentation/html/classFlywheelStopNonTasksCommand.png new file mode 100644 index 0000000000000000000000000000000000000000..9db847fdcf55b7adcb4600473b7bff95d1a87a3a GIT binary patch literal 718 zcmeAS@N?(olHy`uVBq!ia0vp^$ACD1gBeJcR{b&rQqloFA+G=b{|7Q(y!l$%e`vXd zfo6fk^fNCG95?_J51w>+1yGK&B*-tA0mugfbEer>7#Nr$JzX3_Dj46+eYkG5ff7E>kcS*>T~f-`m)I1@X{N_ zwf2*0V)OU;ZJNq&7?fYTqxSrb?}ppzU%%b<&ywS8Q02W@Z+x?F%-`1$DD!?**zBdB zYPR3Ld!_BtXD*49SEuh~-21O|tZu^jgeU9d3_cy1J9D~W)&D$$TWb09+zzwmj5Y0bUjE|uV4$B&nJ{_;Lrdvr$iyu>@N`%i41KHcqA zR@z;a%tiJFpSY%%-g{RT|LxM7=L+wpKE3ql>Z#MxjQx><`d-GN)hWZ%tCI4qR zJg4vFu}Y2^nH5bFmn&GX+TFX=DoD7@9H-SauE#?^V!x}~6S0SAz%^3o}K>+8S1Ud*@U T=LZg8%46_!^>bP0l+XkKIon$W literal 0 HcmV?d00001 diff --git a/documentation/html/classGenericAuto-members.html b/documentation/html/classGenericAuto-members.html new file mode 100644 index 0000000..685b6a4 --- /dev/null +++ b/documentation/html/classGenericAuto-members.html @@ -0,0 +1,88 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
GenericAuto Member List
+
+
+ +

This is the complete list of members for GenericAuto, including all inherited members.

+ + + + + +
add(state_ptr new_state)GenericAuto
add_async(state_ptr async_state)GenericAuto
add_delay(int ms)GenericAuto
run(bool blocking)GenericAuto
+ + + + diff --git a/documentation/html/classGenericAuto.html b/documentation/html/classGenericAuto.html new file mode 100644 index 0000000..c843843 --- /dev/null +++ b/documentation/html/classGenericAuto.html @@ -0,0 +1,204 @@ + + + + + + + +RIT VEXU Core API: GenericAuto Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
GenericAuto Class Reference
+
+
+ +

#include <generic_auto.h>

+ + + + + + + + + + +

+Public Member Functions

bool run (bool blocking)
 
void add (state_ptr new_state)
 
void add_async (state_ptr async_state)
 
void add_delay (int ms)
 
+

Detailed Description

+

GenericAuto provides a pleasant interface for organizing an auto path steps of the path can be added with add() and when ready, calling run() will begin executing the path

+

Member Function Documentation

+ +

◆ add()

+ +
+
+ + + + + + + + +
void GenericAuto::add (state_ptr new_state)
+
+

Add a new state to the autonomous via function point of type "bool (ptr*)()"

Parameters
+ + +
new_statethe function to run
+
+
+ +
+
+ +

◆ add_async()

+ +
+
+ + + + + + + + +
void GenericAuto::add_async (state_ptr async_state)
+
+

Add a new state to the autonomous via function point of type "bool (ptr*)()" that will run asynchronously

Parameters
+ + +
async_statethe function to run
+
+
+ +
+
+ +

◆ add_delay()

+ +
+
+ + + + + + + + +
void GenericAuto::add_delay (int ms)
+
+

add_delay adds a period where the auto system will simply wait for the specified time

Parameters
+ + +
mshow long to wait in milliseconds
+
+
+ +
+
+ +

◆ run()

+ +
+
+ + + + + + + + +
bool GenericAuto::run (bool blocking)
+
+

The method that runs the autonomous. If 'blocking' is true, then this method will run through every state until it finished.

+

If blocking is false, then assuming every state is also non-blocking, the method will run through the current state in the list and return immediately.

+
Parameters
+ + +
blockingWhether or not to block the thread until all states have run
+
+
+
Returns
true after all states have finished.
+ +
+
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/documentation/html/classGraphDrawer-members.html b/documentation/html/classGraphDrawer-members.html new file mode 100644 index 0000000..1afa5d4 --- /dev/null +++ b/documentation/html/classGraphDrawer-members.html @@ -0,0 +1,87 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
GraphDrawer Member List
+
+
+ +

This is the complete list of members for GraphDrawer, including all inherited members.

+ + + + +
add_sample(Vector2D::point_t sample)GraphDrawerinline
draw(int x, int y, int width, int height)GraphDrawerinline
GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound)GraphDrawerinline
+ + + + diff --git a/documentation/html/classGraphDrawer.html b/documentation/html/classGraphDrawer.html new file mode 100644 index 0000000..20307e4 --- /dev/null +++ b/documentation/html/classGraphDrawer.html @@ -0,0 +1,277 @@ + + + + + + + +RIT VEXU Core API: GraphDrawer Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
GraphDrawer Class Reference
+
+
+ + + + + + + + + +

+Public Member Functions

 GraphDrawer (vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound)
 a helper class to graph values on the brain screen
 
void add_sample (Vector2D::point_t sample)
 
void draw (int x, int y, int width, int height)
 
+

Constructor & Destructor Documentation

+ +

◆ GraphDrawer()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
GraphDrawer::GraphDrawer (vex::brain::lcd & screen,
int num_samples,
std::string x_label,
std::string y_label,
vex::color col,
bool draw_border,
double lower_bound,
double upper_bound 
)
+
+inline
+
+ +

a helper class to graph values on the brain screen

+

Construct a GraphDrawer

Parameters
+ + + + + + + + +
screena reference to Brain.screen we can save for later
num_samplesthe graph works on a fixed window and will plot the last num_samples before the history is forgotten. Larger values give more context but may slow down if you have many graphs or an exceptionally high
x_labelthe name of the x axis (currently unused)
y_labelthe name of the y axis (currently unused)
draw_borderwhether to draw the border around the graph. can be turned off if there are multiple graphs in the same space ie. a graph of error and output
lower_boundthe bottom of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints
+
upper_boundthe top of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints
+
+
+
+ +
+
+

Member Function Documentation

+ +

◆ add_sample()

+ +
+
+ + + + + +
+ + + + + + + + +
void GraphDrawer::add_sample (Vector2D::point_t sample)
+
+inline
+
+

add_sample adds a point to the graph, removing one from the back

Parameters
+ + +
samplean x, y coordinate of the next point to graph
+
+
+ +
+
+ +

◆ draw()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void GraphDrawer::draw (int x,
int y,
int width,
int height 
)
+
+inline
+
+

draws the graph to the screen in the constructor

Parameters
+ + + + + +
xx position of the top left of the graphed region
yy position of the top left of the graphed region
widththe width of the graphed region
heightthe height of the graphed region
+
+
+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/documentation/html/classLift-members.html b/documentation/html/classLift-members.html new file mode 100644 index 0000000..dbb6aea --- /dev/null +++ b/documentation/html/classLift-members.html @@ -0,0 +1,97 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
Lift< T > Member List
+
+
+ +

This is the complete list of members for Lift< T >, including all inherited members.

+ + + + + + + + + + + + + + +
control_continuous(bool up_ctrl, bool down_ctrl)Lift< T >inline
control_manual(bool up_btn, bool down_btn, int volt_up, int volt_down)Lift< T >inline
control_setpoints(bool up_step, bool down_step, vector< T > pos_list)Lift< T >inline
get_async()Lift< T >inline
get_setpoint()Lift< T >inline
hold()Lift< T >inline
home()Lift< T >inline
Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map< T, double > &setpoint_map, limit *homing_switch=NULL)Lift< T >inline
set_async(bool val)Lift< T >inline
set_position(T pos)Lift< T >inline
set_sensor_function(double(*fn_ptr)(void))Lift< T >inline
set_sensor_reset(void(*fn_ptr)(void))Lift< T >inline
set_setpoint(double val)Lift< T >inline
+ + + + diff --git a/documentation/html/classLift.html b/documentation/html/classLift.html new file mode 100644 index 0000000..747497d --- /dev/null +++ b/documentation/html/classLift.html @@ -0,0 +1,630 @@ + + + + + + + +RIT VEXU Core API: Lift< T > Class Template Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
Lift< T > Class Template Reference
+
+
+ +

#include <lift.h>

+ + + + +

+Classes

struct  lift_cfg_t
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

 Lift (motor_group &lift_motors, lift_cfg_t &lift_cfg, map< T, double > &setpoint_map, limit *homing_switch=NULL)
 
void control_continuous (bool up_ctrl, bool down_ctrl)
 
void control_manual (bool up_btn, bool down_btn, int volt_up, int volt_down)
 
void control_setpoints (bool up_step, bool down_step, vector< T > pos_list)
 
bool set_position (T pos)
 
bool set_setpoint (double val)
 
double get_setpoint ()
 
void hold ()
 
void home ()
 
bool get_async ()
 
void set_async (bool val)
 
void set_sensor_function (double(*fn_ptr)(void))
 
void set_sensor_reset (void(*fn_ptr)(void))
 
+

Detailed Description

+
template<typename T>
+class Lift< T >

LIFT A general class for lifts (e.g. 4bar, dr4bar, linear, etc) Uses a PID to hold the lift at a certain height under load, and to move the lift to different heights

+
Author
Ryan McGee
+

Constructor & Destructor Documentation

+ +

◆ Lift()

+ +
+
+
+template<typename T >
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Lift< T >::Lift (motor_group & lift_motors,
lift_cfg_tlift_cfg,
map< T, double > & setpoint_map,
limit * homing_switch = NULL 
)
+
+inline
+
+

Construct the Lift object and begin the background task that controls the lift.

+

Usage example: /code{.cpp} enum Positions {UP, MID, DOWN}; map<Positions, double> setpt_map { {DOWN, 0.0}, {MID, 0.5}, {UP, 1.0} }; Lift<Positions> my_lift(motors, lift_cfg, setpt_map); /endcode

+
Parameters
+ + + + +
lift_motorsA set of motors, all set that positive rotation correlates with the lift going up
lift_cfgLift characterization information; PID tunings and movement speeds
setpoint_mapA map of enum type T, in which each enum entry corresponds to a different lift height
+
+
+ +
+
+

Member Function Documentation

+ +

◆ control_continuous()

+ +
+
+
+template<typename T >
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
void Lift< T >::control_continuous (bool up_ctrl,
bool down_ctrl 
)
+
+inline
+
+

Control the lift with an "up" button and a "down" button. Use PID to hold the lift when letting go.

Parameters
+ + + +
up_ctrlButton controlling the "UP" motion
down_ctrlButton controlling the "DOWN" motion
+
+
+ +
+
+ +

◆ control_manual()

+ +
+
+
+template<typename T >
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void Lift< T >::control_manual (bool up_btn,
bool down_btn,
int volt_up,
int volt_down 
)
+
+inline
+
+

Control the lift with manual controls (no holding voltage)

+
Parameters
+ + + + + +
up_btnRaise the lift when true
down_btnLower the lift when true
volt_upMotor voltage when raising the lift
volt_downMotor voltage when lowering the lift
+
+
+ +
+
+ +

◆ control_setpoints()

+ +
+
+
+template<typename T >
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + +
void Lift< T >::control_setpoints (bool up_step,
bool down_step,
vector< T > pos_list 
)
+
+inline
+
+

Control the lift in "steps". When the "up" button is pressed, the lift will go to the next position as defined by pos_list. Order matters!

+
Parameters
+ + + + +
up_stepA button that increments the position of the lift.
down_stepA button that decrements the position of the lift.
pos_listA list of positions for the lift to go through. The higher the index, the higher the lift should be (generally).
+
+
+ +
+
+ +

◆ get_async()

+ +
+
+
+template<typename T >
+ + + + + +
+ + + + + + + +
bool Lift< T >::get_async ()
+
+inline
+
+
Returns
whether or not the background thread is running the lift
+ +
+
+ +

◆ get_setpoint()

+ +
+
+
+template<typename T >
+ + + + + +
+ + + + + + + +
double Lift< T >::get_setpoint ()
+
+inline
+
+
Returns
The current setpoint for the lift
+ +
+
+ +

◆ hold()

+ +
+
+
+template<typename T >
+ + + + + +
+ + + + + + + +
void Lift< T >::hold ()
+
+inline
+
+

Target the class's setpoint. Calculate the PID output and set the lift motors accordingly.

+ +
+
+ +

◆ home()

+ +
+
+
+template<typename T >
+ + + + + +
+ + + + + + + +
void Lift< T >::home ()
+
+inline
+
+

A blocking function that automatically homes the lift based on a sensor or hard stop, and sets the position to 0. A watchdog times out after 3 seconds, to avoid damage.

+ +
+
+ +

◆ set_async()

+ +
+
+
+template<typename T >
+ + + + + +
+ + + + + + + + +
void Lift< T >::set_async (bool val)
+
+inline
+
+

Enables or disables the background task. Note that running the control functions, or set_position functions will immediately re-enable the task for autonomous use.

Parameters
+ + +
Whetheror not the background thread should run the lift
+
+
+ +
+
+ +

◆ set_position()

+ +
+
+
+template<typename T >
+ + + + + +
+ + + + + + + + +
bool Lift< T >::set_position (pos)
+
+inline
+
+

Enable the background task, and send the lift to a position, specified by the setpoint map from the constructor.

+
Parameters
+ + +
posA lift position enum type
+
+
+
Returns
True if the pid has reached the setpoint
+ +
+
+ +

◆ set_sensor_function()

+ +
+
+
+template<typename T >
+ + + + + +
+ + + + + + + + +
void Lift< T >::set_sensor_function (double(*)(void) fn_ptr)
+
+inline
+
+

Creates a custom hook for any other type of sensor to be used on the lift. Example: /code{.cpp} my_lift.set_sensor_function( [](){return my_sensor.position();} ); /endcode

+
Parameters
+ + +
fn_ptrPointer to custom sensor function
+
+
+ +
+
+ +

◆ set_sensor_reset()

+ +
+
+
+template<typename T >
+ + + + + +
+ + + + + + + + +
void Lift< T >::set_sensor_reset (void(*)(void) fn_ptr)
+
+inline
+
+

Creates a custom hook to reset the sensor used in set_sensor_function(). Example: /code{.cpp} my_lift.set_sensor_reset( my_sensor.resetPosition ); /endcode

+ +
+
+ +

◆ set_setpoint()

+ +
+
+
+template<typename T >
+ + + + + +
+ + + + + + + + +
bool Lift< T >::set_setpoint (double val)
+
+inline
+
+

Manually set a setpoint value for the lift PID to go to.

Parameters
+ + +
valLift setpoint, in motor revolutions or sensor units defined by get_sensor. Cannot be outside the softstops.
+
+
+
Returns
True if the pid has reached the setpoint
+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/documentation/html/classMecanumDrive-members.html b/documentation/html/classMecanumDrive-members.html new file mode 100644 index 0000000..cabe2a6 --- /dev/null +++ b/documentation/html/classMecanumDrive-members.html @@ -0,0 +1,89 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
MecanumDrive Member List
+
+
+ +

This is the complete list of members for MecanumDrive, including all inherited members.

+ + + + + + +
auto_drive(double inches, double direction, double speed, bool gyro_correction=true)MecanumDrive
auto_turn(double degrees, double speed, bool ignore_imu=false)MecanumDrive
drive(double left_y, double left_x, double right_x, int power=2)MecanumDrive
drive_raw(double direction_deg, double magnitude, double rotation)MecanumDrive
MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear, vex::rotation *lateral_wheel=NULL, vex::inertial *imu=NULL, mecanumdrive_config_t *config=NULL)MecanumDrive
+ + + + diff --git a/documentation/html/classMecanumDrive.html b/documentation/html/classMecanumDrive.html new file mode 100644 index 0000000..a6cfd10 --- /dev/null +++ b/documentation/html/classMecanumDrive.html @@ -0,0 +1,389 @@ + + + + + + + +RIT VEXU Core API: MecanumDrive Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
MecanumDrive Class Reference
+
+
+ +

#include <mecanum_drive.h>

+ + + + +

+Classes

struct  mecanumdrive_config_t
 
+ + + + + + + + + + + +

+Public Member Functions

 MecanumDrive (vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear, vex::rotation *lateral_wheel=NULL, vex::inertial *imu=NULL, mecanumdrive_config_t *config=NULL)
 
void drive_raw (double direction_deg, double magnitude, double rotation)
 
void drive (double left_y, double left_x, double right_x, int power=2)
 
bool auto_drive (double inches, double direction, double speed, bool gyro_correction=true)
 
bool auto_turn (double degrees, double speed, bool ignore_imu=false)
 
+

Detailed Description

+

A class representing the Mecanum drivetrain. Contains 4 motors, a possible IMU (intertial), and a possible undriven perpendicular wheel.

+

Constructor & Destructor Documentation

+ +

◆ MecanumDrive()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
MecanumDrive::MecanumDrive (vex::motor & left_front,
vex::motor & right_front,
vex::motor & left_rear,
vex::motor & right_rear,
vex::rotation * lateral_wheel = NULL,
vex::inertial * imu = NULL,
mecanumdrive_config_tconfig = NULL 
)
+
+

Create the Mecanum drivetrain object

+ +
+
+

Member Function Documentation

+ +

◆ auto_drive()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
bool MecanumDrive::auto_drive (double inches,
double direction,
double speed,
bool gyro_correction = true 
)
+
+

Drive the robot in a straight line automatically. If the inertial was declared in the constructor, use it to correct while driving. If the lateral wheel was declared in the constructor, use it for more accurate positioning while strafing.

+
Parameters
+ + + + + +
inchesHow far the robot should drive, in inches
directionWhat direction the robot should travel in, in degrees. 0 is forward, +/-180 is reverse, clockwise is positive.
speedThe maximum speed the robot should travel, in percent: -1.0->+1.0
gyro_correction=true Whether or not to use the gyro to help correct while driving. Will always be false if no gyro was declared in the constructor.
+
+
+

Drive the robot in a straight line automatically. If the inertial was declared in the constructor, use it to correct while driving. If the lateral wheel was declared in the constructor, use it for more accurate positioning while strafing.

+
Parameters
+ + + + + +
inchesHow far the robot should drive, in inches
directionWhat direction the robot should travel in, in degrees. 0 is forward, +/-180 is reverse, clockwise is positive.
speedThe maximum speed the robot should travel, in percent: -1.0->+1.0
gyro_correction= true Whether or not to use the gyro to help correct while driving. Will always be false if no gyro was declared in the constructor.
+
+
+
Returns
Whether or not the maneuver is complete.
+ +
+
+ +

◆ auto_turn()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
bool MecanumDrive::auto_turn (double degrees,
double speed,
bool ignore_imu = false 
)
+
+

Autonomously turn the robot X degrees over it's center point. Uses a closed loop for control.

Parameters
+ + + + +
degreesHow many degrees to rotate the robot. Clockwise postive.
speedWhat percentage to run the motors at: 0.0 -> 1.0
ignore_imu=false Whether or not to use the Inertial for determining angle. Will instead use circumference formula + robot's wheelbase + encoders to determine.
+
+
+
Returns
whether or not the robot has finished the maneuver
+

Autonomously turn the robot X degrees over it's center point. Uses a closed loop for control.

Parameters
+ + + + +
degreesHow many degrees to rotate the robot. Clockwise postive.
speedWhat percentage to run the motors at: 0.0 -> 1.0
ignore_imu= false Whether or not to use the Inertial for determining angle. Will instead use circumference formula + robot's wheelbase + encoders to determine.
+
+
+
Returns
whether or not the robot has finished the maneuver
+ +
+
+ +

◆ drive()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void MecanumDrive::drive (double left_y,
double left_x,
double right_x,
int power = 2 
)
+
+

Drive the robot with a mecanum-style / arcade drive. Inputs are in percent (-100.0 -> 100.0) straight from the controller. Controls are mixed, so the robot can drive forward / strafe / rotate all at the same time.

+
Parameters
+ + + + + +
left_yleft joystick, Y axis (forward / backwards)
left_xleft joystick, X axis (strafe left / right)
right_xright joystick, X axis (rotation left / right)
power=2 how much of a "curve" there should be on drive controls; better for low speed maneuvers. Leave blank for a default curve of 2 (higher means more fidelity)
+
+
+

Drive the robot with a mecanum-style / arcade drive. Inputs are in percent (-100.0 -> 100.0) straight from the controller. Controls are mixed, so the robot can drive forward / strafe / rotate all at the same time.

+
Parameters
+ + + + + +
left_yleft joystick, Y axis (forward / backwards)
left_xleft joystick, X axis (strafe left / right)
right_xright joystick, X axis (rotation left / right)
power= 2 how much of a "curve" there should be on drive controls; better for low speed maneuvers. Leave blank for a default curve of 2 (higher means more fidelity)
+
+
+ +
+
+ +

◆ drive_raw()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
void MecanumDrive::drive_raw (double direction_deg,
double magnitude,
double rotation 
)
+
+

Drive the robot using vectors. This handles all the math required for mecanum control.

+
Parameters
+ + + + +
direction_degthe direction to drive the robot, in degrees. 0 is forward, 180 is back, clockwise is positive, counterclockwise is negative.
magnitudeHow fast the robot should drive, in percent: 0.0->1.0
rotationHow fast the robot should rotate, in percent: -1.0->+1.0
+
+
+ +
+
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/documentation/html/classMotionController-members.html b/documentation/html/classMotionController-members.html new file mode 100644 index 0000000..8d8a6a6 --- /dev/null +++ b/documentation/html/classMotionController-members.html @@ -0,0 +1,97 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
MotionController Member List
+
+
+ +

This is the complete list of members for MotionController, including all inherited members.

+ + + + + + + + + + + + + + +
FeedbackType enum name (defined in Feedback)Feedback
FeedforwardType enum value (defined in Feedback)Feedback
get() overrideMotionControllervirtual
get_motion()MotionController
get_type() (defined in Feedback)Feedbackinlinevirtual
init(double start_pt, double end_pt) overrideMotionControllervirtual
is_on_target() overrideMotionControllervirtual
MotionController(m_profile_cfg_t &config)MotionController
OtherType enum value (defined in Feedback)Feedback
PIDType enum value (defined in Feedback)Feedback
set_limits(double lower, double upper) overrideMotionControllervirtual
tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct=0.6, double duration=2)MotionControllerstatic
update(double sensor_val) overrideMotionControllervirtual
+ + + + diff --git a/documentation/html/classMotionController.html b/documentation/html/classMotionController.html new file mode 100644 index 0000000..9ceaa44 --- /dev/null +++ b/documentation/html/classMotionController.html @@ -0,0 +1,477 @@ + + + + + + + +RIT VEXU Core API: MotionController Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
MotionController Class Reference
+
+
+ +

#include <motion_controller.h>

+
+Inheritance diagram for MotionController:
+
+
+ + +Feedback + +
+ + + + +

+Classes

struct  m_profile_cfg_t
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

 MotionController (m_profile_cfg_t &config)
 Construct a new Motion Controller object.
 
void init (double start_pt, double end_pt) override
 Initialize the motion profile for a new movement This will also reset the PID and profile timers.
 
double update (double sensor_val) override
 Update the motion profile with a new sensor value.
 
double get () override
 
void set_limits (double lower, double upper) override
 
bool is_on_target () override
 
motion_t get_motion ()
 
- Public Member Functions inherited from Feedback
virtual void init (double start_pt, double set_pt)=0
 
virtual double update (double val)=0
 
virtual double get ()=0
 
virtual void set_limits (double lower, double upper)=0
 
virtual bool is_on_target ()=0
 
+virtual Feedback::FeedbackType get_type ()
 
+ + + +

+Static Public Member Functions

static FeedForward::ff_config_t tune_feedforward (TankDrive &drive, OdometryTank &odometry, double pct=0.6, double duration=2)
 
+ + + + +

+Additional Inherited Members

- Public Types inherited from Feedback
enum  FeedbackType { PIDType +, FeedforwardType +, OtherType + }
 
+

Detailed Description

+

Motion Controller class

+

This class defines a top-level motion profile, which can act as an intermediate between a subsystem class and the motors themselves

+

This takes the constants kS, kV, kA, kP, kI, kD, max_v and acceleration and wraps around a feedforward, PID and trapezoid profile. It does so with the following formula:

+

out = feedfoward.calculate(motion_profile.get(time_s)) + pid.get(motion_profile.get(time_s))

+

For PID and Feedforward specific formulae, see pid.h, feedforward.h, and trapezoid_profile.h

+
Author
Ryan McGee
+
Date
7/13/2022
+

Constructor & Destructor Documentation

+ +

◆ MotionController()

+ +
+
+ + + + + + + + +
MotionController::MotionController (m_profile_cfg_tconfig)
+
+ +

Construct a new Motion Controller object.

+
Parameters
+ + +
configThe definition of how the robot is able to move max_v Maximum velocity the movement is capable of accel Acceleration / deceleration of the movement pid_cfg Definitions of kP, kI, and kD ff_cfg Definitions of kS, kV, and kA
+
+
+
Parameters
+ + +
configThe definition of how the robot is able to move max_v Maximum velocity the movement is capable of accel Acceleration / deceleration of the movement pid_cfg Definitions of kP, kI, and kD ff_cfg Definitions of kS, kV, and kA
+
+
+ +
+
+

Member Function Documentation

+ +

◆ get()

+ +
+
+ + + + + +
+ + + + + + + +
double MotionController::get ()
+
+overridevirtual
+
+
Returns
the last saved result from the feedback controller
+ +

Implements Feedback.

+ +
+
+ +

◆ get_motion()

+ +
+
+ + + + + + + +
motion_t MotionController::get_motion ()
+
+
Returns
The current postion, velocity and acceleration setpoints
+ +
+
+ +

◆ init()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
void MotionController::init (double start_pt,
double end_pt 
)
+
+overridevirtual
+
+ +

Initialize the motion profile for a new movement This will also reset the PID and profile timers.

+
Parameters
+ + + +
start_ptMovement starting position
end_ptMovement ending posiiton
+
+
+ +

Implements Feedback.

+ +
+
+ +

◆ is_on_target()

+ +
+
+ + + + + +
+ + + + + + + +
bool MotionController::is_on_target ()
+
+overridevirtual
+
+
Returns
Whether or not the movement has finished, and the PID confirms it is on target
+ +

Implements Feedback.

+ +
+
+ +

◆ set_limits()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
void MotionController::set_limits (double lower,
double upper 
)
+
+overridevirtual
+
+

Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. if limits are applied, the controller will not target any value below lower or above upper

+
Parameters
+ + + +
lowerupper limit
upperlower limiet
+
+
+

Clamp the upper and lower limits of the output. If both are 0, no limits should be applied.

+
Parameters
+ + + +
lowerUpper limit
upperLower limit
+
+
+ +

Implements Feedback.

+ +
+
+ +

◆ tune_feedforward()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
FeedForward::ff_config_t MotionController::tune_feedforward (TankDrivedrive,
OdometryTankodometry,
double pct = 0.6,
double duration = 2 
)
+
+static
+
+

This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. It does this by first calculating the kS (voltage to overcome static friction) by slowly increasing the voltage until it moves.

+

Next is kV (voltage to sustain a certain velocity), where the robot will record it's steady-state velocity at 'pct' speed.

+

Finally, kA (voltage needed to accelerate by a certain rate), where the robot will record the entire movement's velocity and acceleration, record a plot of [X=(pct-kV*V-kS), Y=(Acceleration)] along the movement, and since kA*Accel = pct-kV*V-kS, the reciprocal of the linear regression is the kA value.

+
Parameters
+ + + + + +
driveThe tankdrive to operate on
odometryThe robot's odometry subsystem
pctMaximum velocity in percent (0->1.0)
durationAmount of time the robot should be moving for the test
+
+
+
Returns
A tuned feedforward object
+ +
+
+ +

◆ update()

+ +
+
+ + + + + +
+ + + + + + + + +
double MotionController::update (double sensor_val)
+
+overridevirtual
+
+ +

Update the motion profile with a new sensor value.

+
Parameters
+ + +
sensor_valValue from the sensor
+
+
+
Returns
the motor input generated from the motion profile
+
Parameters
+ + +
sensor_valValue from the sensor
+
+
+
Returns
the motor input generated from the motion profile
+ +

Implements Feedback.

+ +
+
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/documentation/html/classMotionController.png b/documentation/html/classMotionController.png new file mode 100644 index 0000000000000000000000000000000000000000..3063bd77d06358dd6d7a19e19db2307972f03c03 GIT binary patch literal 474 zcmeAS@N?(olHy`uVBq!ia0vp^SwI}X!3-pi$qD2EDd_;85ZC|z{{xvX-h3_XKeXJ! zK(jz%`k5C84jcfA2T!`Z0w~8>666=m0OW&#In(Sb3=E8^o-U3d6^w7^zRf$Vz~ibf zuKDS={YN1?A*PhrN9Sg1h1;5%HXd%DdcVWaOxoZB~A5vd#Xa(-TPK?^{yvk>!y834mI}VyS=4z%1@kz&iX3wC;)gD0ykFQGVxyZt><2)0C*^QOc zj-E+f9_1UR=X|w2Y{6;HtqPV{CSV} z+%SxtCG_OSJK60acX#%@Z1XeK?0!`_eO1VW)>W%#25;nl{Cx7+@PgM2v%7V!-waE* zdSzGE<*h1uS{Lp&Dk){fs46XbkQ}Pml5j|TB~N&F^`dVzz*u1LboFyt=akR{0DXGg AH~;_u literal 0 HcmV?d00001 diff --git a/documentation/html/classMovingAverage-members.html b/documentation/html/classMovingAverage-members.html new file mode 100644 index 0000000..f3476cc --- /dev/null +++ b/documentation/html/classMovingAverage-members.html @@ -0,0 +1,89 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
MovingAverage Member List
+
+
+ +

This is the complete list of members for MovingAverage, including all inherited members.

+ + + + + + +
add_entry(double n)MovingAverage
get_average()MovingAverage
get_size()MovingAverage
MovingAverage(int buffer_size)MovingAverage
MovingAverage(int buffer_size, double starting_value)MovingAverage
+ + + + diff --git a/documentation/html/classMovingAverage.html b/documentation/html/classMovingAverage.html new file mode 100644 index 0000000..2d74470 --- /dev/null +++ b/documentation/html/classMovingAverage.html @@ -0,0 +1,233 @@ + + + + + + + +RIT VEXU Core API: MovingAverage Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
MovingAverage Class Reference
+
+
+ +

#include <moving_average.h>

+ + + + + + + + + + + + +

+Public Member Functions

 MovingAverage (int buffer_size)
 
 MovingAverage (int buffer_size, double starting_value)
 
void add_entry (double n)
 
double get_average ()
 
int get_size ()
 
+

Detailed Description

+

MovingAverage

+

A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. This means that if you collect enough samples those that are too high are cancelled out by the samples that are too low leaving the real value.

+

The MovingAverage class provides a simple interface to do this smoothing from our noisy sensor values.

+

WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' behind the actual value that the sensor is reading. Using a MovingAverage is thus a tradeoff between accuracy and lag time (more samples) vs. less accuracy and faster updating (less samples).
+

+

Constructor & Destructor Documentation

+ +

◆ MovingAverage() [1/2]

+ +
+
+ + + + + + + + +
MovingAverage::MovingAverage (int buffer_size)
+
+

Create a moving average calculator with 0 as the default value

+
Parameters
+ + +
buffer_sizeThe size of the buffer. The number of samples that constitute a valid reading
+
+
+ +
+
+ +

◆ MovingAverage() [2/2]

+ +
+
+ + + + + + + + + + + + + + + + + + +
MovingAverage::MovingAverage (int buffer_size,
double starting_value 
)
+
+

Create a moving average calculator with a specified default value

Parameters
+ + + +
buffer_sizeThe size of the buffer. The number of samples that constitute a valid reading
starting_valueThe value that the average will be before any data is added
+
+
+ +
+
+

Member Function Documentation

+ +

◆ add_entry()

+ +
+
+ + + + + + + + +
void MovingAverage::add_entry (double n)
+
+

Add a reading to the buffer Before: [ 1 1 2 2 3 3] => 2 ^ After: [ 2 1 2 2 3 3] => 2.16 ^

Parameters
+ + +
nthe sample that will be added to the moving average.
+
+
+ +
+
+ +

◆ get_average()

+ +
+
+ + + + + + + +
double MovingAverage::get_average ()
+
+

Returns the average based off of all the samples collected so far

Returns
the calculated average. sum(samples)/numsamples
+

How many samples the average is made from

Returns
the number of samples used to calculate this average
+ +
+
+ +

◆ get_size()

+ +
+
+ + + + + + + +
int MovingAverage::get_size ()
+
+

How many samples the average is made from

Returns
the number of samples used to calculate this average
+ +
+
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/documentation/html/classOdomSetPosition-members.html b/documentation/html/classOdomSetPosition-members.html new file mode 100644 index 0000000..1da2f8e --- /dev/null +++ b/documentation/html/classOdomSetPosition-members.html @@ -0,0 +1,89 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
OdomSetPosition Member List
+
+
+ +

This is the complete list of members for OdomSetPosition, including all inherited members.

+ + + + + + +
OdomSetPosition(OdometryBase &odom, const position_t &newpos=OdometryBase::zero_pos)OdomSetPosition
on_timeout()AutoCommandinlinevirtual
run() overrideOdomSetPositionvirtual
timeout_secondsAutoCommand
withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
+ + + + diff --git a/documentation/html/classOdomSetPosition.html b/documentation/html/classOdomSetPosition.html new file mode 100644 index 0000000..1c0897d --- /dev/null +++ b/documentation/html/classOdomSetPosition.html @@ -0,0 +1,195 @@ + + + + + + + +RIT VEXU Core API: OdomSetPosition Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
OdomSetPosition Class Reference
+
+
+ +

#include <drive_commands.h>

+
+Inheritance diagram for OdomSetPosition:
+
+
+ + +AutoCommand + +
+ + + + + + + + + + + + + +

+Public Member Functions

 OdomSetPosition (OdometryBase &odom, const position_t &newpos=OdometryBase::zero_pos)
 
bool run () override
 
- Public Member Functions inherited from AutoCommand
virtual bool run ()
 
virtual void on_timeout ()
 
+AutoCommandwithTimeout (double t_seconds)
 
+ + + + +

+Additional Inherited Members

- Public Attributes inherited from AutoCommand
double timeout_seconds = 10.0
 
+

Detailed Description

+

AutoCommand wrapper class for the set_position function in the Odometry class

+

Constructor & Destructor Documentation

+ +

◆ OdomSetPosition()

+ +
+
+ + + + + + + + + + + + + + + + + + +
OdomSetPosition::OdomSetPosition (OdometryBaseodom,
const position_tnewpos = OdometryBase::zero_pos 
)
+
+

constructs a new OdomSetPosition command

Parameters
+ + + +
odomthe odometry system we are setting
newposthe position we are telling the odometry to take. defaults to (0, 0), angle = 90
+
+
+

Construct an Odometry set pos

Parameters
+ + + +
odomthe odometry system we are setting
newposthe now position to set the odometry to
+
+
+ +
+
+

Member Function Documentation

+ +

◆ run()

+ +
+
+ + + + + +
+ + + + + + + +
bool OdomSetPosition::run ()
+
+overridevirtual
+
+

Run set_position Overrides run from AutoCommand

Returns
true when execution is complete, false otherwise
+ +

Reimplemented from AutoCommand.

+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/utils/command_structure/drive_commands.h
  • +
  • src/utils/command_structure/drive_commands.cpp
  • +
+
+ + + + diff --git a/documentation/html/classOdomSetPosition.png b/documentation/html/classOdomSetPosition.png new file mode 100644 index 0000000000000000000000000000000000000000..7d9b7504e42e4fe77173907be2d266d77bafb305 GIT binary patch literal 525 zcmeAS@N?(olHy`uVBq!ia0vp^*+3k?!3-od?^Fi>Dd_;85ZC|z{{xvX-h3_XKeXJ! zK(jz%`k5C84jcfA2T!`Z0w~8>666=m0OW&#In(Sb3=E7jJY5_^Dj46+jqN+Ez|(Tv zZPl}X>i1e$axymgPScyJ6+Vx_@Z0hJ%jrv|TvAb7xymnaLrCcHFNxFU@TUA+xhgK) z`tMBD+<)t;`O7A5wVU>C*W_GlvG8N7PnVzB*dMpi>sGAk{G(F~&)qCpwb*4}?^3O` zZ~e^wi)OEH*uP=hh0|-!-gb#e+d83I$GU?1O}OH!dshElr^Wt>i~Cl4)mbbw|K>)~ z`KlfNokOo~*Nj-TD*0DZn3v{RL54fmnHkhFm0o|G!9M#$RKVo~QS~ z+s`&E*?cUY^L*N*l;x+2&ThJ~_T>3VSKrrHhg{pY*JywLdg+R^r#`0tr6Q7YP0#L| zWqz+_Rq(Yyw&)#eSLob5|1whVyX-XeE&92S^AmpxXIJUXopA45#Jgp;fB*VgHZT8! z(CK~i*Y#z&=$ePG37h$jXZH_gG0%Uin_MR)bBTHOWg2oJbA-|1vc+3>a|? Mp00i_>zopr06Kp56951J literal 0 HcmV?d00001 diff --git a/documentation/html/classOdometry3Wheel-members.html b/documentation/html/classOdometry3Wheel-members.html new file mode 100644 index 0000000..f722eb7 --- /dev/null +++ b/documentation/html/classOdometry3Wheel-members.html @@ -0,0 +1,108 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
Odometry3Wheel Member List
+
+
+ +

This is the complete list of members for Odometry3Wheel, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + +
accelOdometryBaseprotected
ang_accel_degOdometryBaseprotected
ang_speed_degOdometryBaseprotected
background_task(void *ptr)OdometryBasestatic
current_posOdometryBaseprotected
end_async()OdometryBase
end_taskOdometryBase
get_accel()OdometryBase
get_angular_accel_deg()OdometryBase
get_angular_speed_deg()OdometryBase
get_position(void)OdometryBase
get_speed()OdometryBase
handleOdometryBaseprotected
mutOdometryBaseprotected
Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, odometry3wheel_cfg_t &cfg, bool is_async=true)Odometry3Wheel
OdometryBase(bool is_async)OdometryBase
pos_diff(position_t start_pos, position_t end_pos)OdometryBasestatic
rot_diff(position_t pos1, position_t pos2)OdometryBasestatic
set_position(const position_t &newpos=zero_pos)OdometryBasevirtual
smallest_angle(double start_deg, double end_deg)OdometryBasestatic
speedOdometryBaseprotected
tune(vex::controller &con, TankDrive &drive)Odometry3Wheel
update() overrideOdometry3Wheelvirtual
zero_posOdometryBaseinlinestatic
+ + + + diff --git a/documentation/html/classOdometry3Wheel.html b/documentation/html/classOdometry3Wheel.html new file mode 100644 index 0000000..b566fbb --- /dev/null +++ b/documentation/html/classOdometry3Wheel.html @@ -0,0 +1,303 @@ + + + + + + + +RIT VEXU Core API: Odometry3Wheel Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
Odometry3Wheel Class Reference
+
+
+ +

#include <odometry_3wheel.h>

+
+Inheritance diagram for Odometry3Wheel:
+
+
+ + +OdometryBase + +
+ + + + +

+Classes

struct  odometry3wheel_cfg_t
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

 Odometry3Wheel (CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, odometry3wheel_cfg_t &cfg, bool is_async=true)
 
position_t update () override
 
void tune (vex::controller &con, TankDrive &drive)
 
- Public Member Functions inherited from OdometryBase
 OdometryBase (bool is_async)
 
position_t get_position (void)
 
virtual void set_position (const position_t &newpos=zero_pos)
 
virtual position_t update ()=0
 
void end_async ()
 
double get_speed ()
 
double get_accel ()
 
double get_angular_speed_deg ()
 
double get_angular_accel_deg ()
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Additional Inherited Members

- Static Public Member Functions inherited from OdometryBase
static int background_task (void *ptr)
 
static double pos_diff (position_t start_pos, position_t end_pos)
 
static double rot_diff (position_t pos1, position_t pos2)
 
static double smallest_angle (double start_deg, double end_deg)
 
- Public Attributes inherited from OdometryBase
+bool end_task = false
 end_task is true if we instruct the odometry thread to shut down
 
- Static Public Attributes inherited from OdometryBase
static constexpr position_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}
 
- Protected Attributes inherited from OdometryBase
vex::task * handle
 
vex::mutex mut
 
position_t current_pos
 
double speed
 
double accel
 
double ang_speed_deg
 
double ang_accel_deg
 
+

Detailed Description

+

Odometry3Wheel

+

This class handles the code for a standard 3-pod odometry setup, where there are 3 "pods" made up of undriven (dead) wheels connected to encoders in the following configuration:

+

+Y ------------— ^ | | | | | | | || O || | | | | | | === | | ------------— | +----------------—> + X

+

Where O is the center of rotation. The robot will monitor the changes in rotation of these wheels and calculate the robot's X, Y and rotation on the field.

+

This is a "set and forget" class, meaning once the object is created, the robot will immediately begin tracking it's movement in the background.

+
Author
Ryan McGee
+
Date
Oct 31 2022
+

Constructor & Destructor Documentation

+ +

◆ Odometry3Wheel()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Odometry3Wheel::Odometry3Wheel (CustomEncoderlside_fwd,
CustomEncoderrside_fwd,
CustomEncoderoff_axis,
odometry3wheel_cfg_tcfg,
bool is_async = true 
)
+
+

Construct a new Odometry 3 Wheel object

+
Parameters
+ + + + + + +
lside_fwdleft-side encoder reference
rside_fwdright-side encoder reference
off_axisoff-axis (perpendicular) encoder reference
cfgrobot odometry configuration
is_asynctrue to constantly run in the background
+
+
+ +
+
+

Member Function Documentation

+ +

◆ tune()

+ +
+
+ + + + + + + + + + + + + + + + + + +
void Odometry3Wheel::tune (vex::controller & con,
TankDrivedrive 
)
+
+

A guided tuning process to automatically find tuning parameters. This method is blocking, and returns when tuning has finished. Follow the instructions on the controller to complete the tuning process

+
Parameters
+ + + +
conController reference, for screen and button control
driveDrivetrain reference for robot control
+
+
+

A guided tuning process to automatically find tuning parameters. This method is blocking, and returns when tuning has finished. Follow the instructions on the controller to complete the tuning process

+

It is assumed the gear ratio and encoder PPR have been set correctly

+ +
+
+ +

◆ update()

+ +
+
+ + + + + +
+ + + + + + + +
position_t Odometry3Wheel::update ()
+
+overridevirtual
+
+

Update the current position of the robot once, using the current state of the encoders and the previous known location

+
Returns
the robot's updated position
+ +

Implements OdometryBase.

+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/subsystems/odometry/odometry_3wheel.h
  • +
  • src/subsystems/odometry/odometry_3wheel.cpp
  • +
+
+ + + + diff --git a/documentation/html/classOdometry3Wheel.png b/documentation/html/classOdometry3Wheel.png new file mode 100644 index 0000000000000000000000000000000000000000..e1b39c48649336e03dde2ef7a4e4da634399f51f GIT binary patch literal 548 zcmV+<0^9wGP)vTJr#LVva2S`&=)l0h|Ns9}lGCUF000SeQchC<|NsC0|NsC0Hv*f~00056 zNklfGV!(xIAk_jYlT zecI@~neWZjq}GP55G_h;?SIoreJu^(%anfaa`7@yOg_#V?9 m+15V}GjoJ~oR(5bv-Ahx;#s6>)d8mf0000 + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
OdometryBase Member List
+
+
+ +

This is the complete list of members for OdometryBase, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + +
accelOdometryBaseprotected
ang_accel_degOdometryBaseprotected
ang_speed_degOdometryBaseprotected
background_task(void *ptr)OdometryBasestatic
current_posOdometryBaseprotected
end_async()OdometryBase
end_taskOdometryBase
get_accel()OdometryBase
get_angular_accel_deg()OdometryBase
get_angular_speed_deg()OdometryBase
get_position(void)OdometryBase
get_speed()OdometryBase
handleOdometryBaseprotected
mutOdometryBaseprotected
OdometryBase(bool is_async)OdometryBase
pos_diff(position_t start_pos, position_t end_pos)OdometryBasestatic
rot_diff(position_t pos1, position_t pos2)OdometryBasestatic
set_position(const position_t &newpos=zero_pos)OdometryBasevirtual
smallest_angle(double start_deg, double end_deg)OdometryBasestatic
speedOdometryBaseprotected
update()=0OdometryBasepure virtual
zero_posOdometryBaseinlinestatic
+ + + + diff --git a/documentation/html/classOdometryBase.html b/documentation/html/classOdometryBase.html new file mode 100644 index 0000000..f0cab51 --- /dev/null +++ b/documentation/html/classOdometryBase.html @@ -0,0 +1,725 @@ + + + + + + + +RIT VEXU Core API: OdometryBase Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
+ +

#include <odometry_base.h>

+
+Inheritance diagram for OdometryBase:
+
+
+ + +Odometry3Wheel +OdometryTank + +
+ + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

 OdometryBase (bool is_async)
 
position_t get_position (void)
 
virtual void set_position (const position_t &newpos=zero_pos)
 
virtual position_t update ()=0
 
void end_async ()
 
double get_speed ()
 
double get_accel ()
 
double get_angular_speed_deg ()
 
double get_angular_accel_deg ()
 
+ + + + + + + + + +

+Static Public Member Functions

static int background_task (void *ptr)
 
static double pos_diff (position_t start_pos, position_t end_pos)
 
static double rot_diff (position_t pos1, position_t pos2)
 
static double smallest_angle (double start_deg, double end_deg)
 
+ + + + +

+Public Attributes

+bool end_task = false
 end_task is true if we instruct the odometry thread to shut down
 
+ + + +

+Static Public Attributes

static constexpr position_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}
 
+ + + + + + + + + + + + + + + +

+Protected Attributes

vex::task * handle
 
vex::mutex mut
 
position_t current_pos
 
double speed
 
double accel
 
double ang_speed_deg
 
double ang_accel_deg
 
+

Detailed Description

+

OdometryBase

+

This base class contains all the shared code between different implementations of odometry. It handles the asynchronous management, position input/output and basic math functions, and holds positional types specific to field orientation.

+

All future odometry implementations should extend this file and redefine update() function.

+
Author
Ryan McGee
+
Date
Aug 11 2021
+

Constructor & Destructor Documentation

+ +

◆ OdometryBase()

+ +
+
+ + + + + + + + +
OdometryBase::OdometryBase (bool is_async)
+
+

Construct a new Odometry Base object

+
Parameters
+ + +
is_asyncTrue to run constantly in the background, false to call update() manually
+
+
+ +
+
+

Member Function Documentation

+ +

◆ background_task()

+ +
+
+ + + + + +
+ + + + + + + + +
int OdometryBase::background_task (void * ptr)
+
+static
+
+

Function that runs in the background task. This function pointer is passed to the vex::task constructor.

+
Parameters
+ + +
ptrPointer to OdometryBase object
+
+
+
Returns
Required integer return code. Unused.
+ +
+
+ +

◆ end_async()

+ +
+
+ + + + + + + +
void OdometryBase::end_async ()
+
+

End the background task. Cannot be restarted. If the user wants to end the thread but keep the data up to date, they must run the update() function manually from then on.

+ +
+
+ +

◆ get_accel()

+ +
+
+ + + + + + + +
double OdometryBase::get_accel ()
+
+

Get the current acceleration

Returns
the acceleration rate of the robot (inch/s^2)
+ +
+
+ +

◆ get_angular_accel_deg()

+ +
+
+ + + + + + + +
double OdometryBase::get_angular_accel_deg ()
+
+

Get the current angular acceleration in degrees

Returns
the angular acceleration at which we are turning (deg/s^2)
+ +
+
+ +

◆ get_angular_speed_deg()

+ +
+
+ + + + + + + +
double OdometryBase::get_angular_speed_deg ()
+
+

Get the current angular speed in degrees

Returns
the angular velocity at which we are turning (deg/s)
+ +
+
+ +

◆ get_position()

+ +
+
+ + + + + + + + +
position_t OdometryBase::get_position (void )
+
+

Gets the current position and rotation

Returns
the position that the odometry believes the robot is at
+

Gets the current position and rotation

+ +
+
+ +

◆ get_speed()

+ +
+
+ + + + + + + +
double OdometryBase::get_speed ()
+
+

Get the current speed

Returns
the speed at which the robot is moving and grooving (inch/s)
+ +
+
+ +

◆ pos_diff()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
double OdometryBase::pos_diff (position_t start_pos,
position_t end_pos 
)
+
+static
+
+

Get the distance between two points

Parameters
+ + + +
start_posdistance from this point
end_posto this point
+
+
+
Returns
the euclidean distance between start_pos and end_pos
+ +
+
+ +

◆ rot_diff()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
double OdometryBase::rot_diff (position_t pos1,
position_t pos2 
)
+
+static
+
+

Get the change in rotation between two points

Parameters
+ + + +
pos1position with initial rotation
pos2position with final rotation
+
+
+
Returns
change in rotation between pos1 and pos2
+

Get the change in rotation between two points

+ +
+
+ +

◆ set_position()

+ +
+
+ + + + + +
+ + + + + + + + +
void OdometryBase::set_position (const position_tnewpos = zero_pos)
+
+virtual
+
+

Sets the current position of the robot

Parameters
+ + +
newposthe new position that the odometry will believe it is at
+
+
+

Sets the current position of the robot

+ +

Reimplemented in OdometryTank.

+ +
+
+ +

◆ smallest_angle()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
double OdometryBase::smallest_angle (double start_deg,
double end_deg 
)
+
+static
+
+

Get the smallest difference in angle between a start heading and end heading. Returns the difference between -180 degrees and +180 degrees, representing the robot turning left or right, respectively.

Parameters
+ + + +
start_degintitial angle (degrees)
end_degfinal angle (degrees)
+
+
+
Returns
the smallest angle from the initial to the final angle. This takes into account the wrapping of rotations around 360 degrees
+

Get the smallest difference in angle between a start heading and end heading. Returns the difference between -180 degrees and +180 degrees, representing the robot turning left or right, respectively.

+ +
+
+ +

◆ update()

+ +
+
+ + + + + +
+ + + + + + + +
virtual position_t OdometryBase::update ()
+
+pure virtual
+
+

Update the current position on the field based on the sensors

Returns
the location that the robot is at after the odometry does its calculations
+ +

Implemented in Odometry3Wheel, and OdometryTank.

+ +
+
+

Member Data Documentation

+ +

◆ accel

+ +
+
+ + + + + +
+ + + + +
double OdometryBase::accel
+
+protected
+
+

the rate at which we are accelerating (inch/s^2)

+ +
+
+ +

◆ ang_accel_deg

+ +
+
+ + + + + +
+ + + + +
double OdometryBase::ang_accel_deg
+
+protected
+
+

the rate at which we are accelerating our turn (deg/s^2)

+ +
+
+ +

◆ ang_speed_deg

+ +
+
+ + + + + +
+ + + + +
double OdometryBase::ang_speed_deg
+
+protected
+
+

the speed at which we are turning (deg/s)

+ +
+
+ +

◆ current_pos

+ +
+
+ + + + + +
+ + + + +
position_t OdometryBase::current_pos
+
+protected
+
+

Current position of the robot in terms of x,y,rotation

+ +
+
+ +

◆ handle

+ +
+
+ + + + + +
+ + + + +
vex::task* OdometryBase::handle
+
+protected
+
+

handle to the vex task that is running the odometry code

+ +
+
+ +

◆ mut

+ +
+
+ + + + + +
+ + + + +
vex::mutex OdometryBase::mut
+
+protected
+
+

Mutex to control multithreading

+ +
+
+ +

◆ speed

+ +
+
+ + + + + +
+ + + + +
double OdometryBase::speed
+
+protected
+
+

the speed at which we are travelling (inch/s)

+ +
+
+ +

◆ zero_pos

+ +
+
+ + + + + +
+ + + + +
constexpr position_t OdometryBase::zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}
+
+inlinestaticconstexpr
+
+

Zeroed position. X=0, Y=0, Rotation= 90 degrees

+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/subsystems/odometry/odometry_base.h
  • +
  • src/subsystems/odometry/odometry_base.cpp
  • +
+
+ + + + diff --git a/documentation/html/classOdometryBase.png b/documentation/html/classOdometryBase.png new file mode 100644 index 0000000000000000000000000000000000000000..ad76095914622330d748df91defd2bc7f2f459c3 GIT binary patch literal 776 zcmV+j1NZ!iP)vTJr#LVva2S`&=)l0h|Ns9}lGCUF000SeQchC<|NsC0|NsC0Hv*f~0007$ zNkl zb<~W%t7O&in@ZM=zHPdSi0nlr0pKW9QbeR9DhU8bVT>`S0RZ=50D!0S2FYP~f#n+{ z{~e!i`3gy`t^n{1R1yH5fJy?u6HrM2cmgU30GDAHhT#_gz-jzwJ5&+?x}uT*a11I5 z09{c@05}Gf1c0unBmf+PN&-MvR1yG=K_vm8D>sw0*4laoYpt#4S79wlowTfUQIk-WzZiYN~C4>u%RqK{*uVXLEqa?Jn+VG$xUBYwMRd?DUpob96UwdAYpM18&*DY$yHlW?9=PSra`z$B`?^=u;u-&UoSUl_mY_Vbph$ zE76y9?If90nmH?yB~5bY6p?ZOk)*ZOp2Z)$N^&*WVI4030000 + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
OdometryTank Member List
+
+
+ +

This is the complete list of members for OdometryTank, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + + +
accelOdometryBaseprotected
ang_accel_degOdometryBaseprotected
ang_speed_degOdometryBaseprotected
background_task(void *ptr)OdometryBasestatic
current_posOdometryBaseprotected
end_async()OdometryBase
end_taskOdometryBase
get_accel()OdometryBase
get_angular_accel_deg()OdometryBase
get_angular_speed_deg()OdometryBase
get_position(void)OdometryBase
get_speed()OdometryBase
handleOdometryBaseprotected
mutOdometryBaseprotected
OdometryBase(bool is_async)OdometryBase
OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true)OdometryTank
OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true)OdometryTank
pos_diff(position_t start_pos, position_t end_pos)OdometryBasestatic
rot_diff(position_t pos1, position_t pos2)OdometryBasestatic
set_position(const position_t &newpos=zero_pos) overrideOdometryTankvirtual
smallest_angle(double start_deg, double end_deg)OdometryBasestatic
speedOdometryBaseprotected
update() overrideOdometryTankvirtual
zero_posOdometryBaseinlinestatic
+ + + + diff --git a/documentation/html/classOdometryTank.html b/documentation/html/classOdometryTank.html new file mode 100644 index 0000000..57a3165 --- /dev/null +++ b/documentation/html/classOdometryTank.html @@ -0,0 +1,345 @@ + + + + + + + +RIT VEXU Core API: OdometryTank Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
OdometryTank Class Reference
+
+
+ +

#include <odometry_tank.h>

+
+Inheritance diagram for OdometryTank:
+
+
+ + +OdometryBase + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

 OdometryTank (vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true)
 
 OdometryTank (CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true)
 
position_t update () override
 
void set_position (const position_t &newpos=zero_pos) override
 
- Public Member Functions inherited from OdometryBase
 OdometryBase (bool is_async)
 
position_t get_position (void)
 
virtual void set_position (const position_t &newpos=zero_pos)
 
virtual position_t update ()=0
 
void end_async ()
 
double get_speed ()
 
double get_accel ()
 
double get_angular_speed_deg ()
 
double get_angular_accel_deg ()
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Additional Inherited Members

- Static Public Member Functions inherited from OdometryBase
static int background_task (void *ptr)
 
static double pos_diff (position_t start_pos, position_t end_pos)
 
static double rot_diff (position_t pos1, position_t pos2)
 
static double smallest_angle (double start_deg, double end_deg)
 
- Public Attributes inherited from OdometryBase
+bool end_task = false
 end_task is true if we instruct the odometry thread to shut down
 
- Static Public Attributes inherited from OdometryBase
static constexpr position_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}
 
- Protected Attributes inherited from OdometryBase
vex::task * handle
 
vex::mutex mut
 
position_t current_pos
 
double speed
 
double accel
 
double ang_speed_deg
 
double ang_accel_deg
 
+

Detailed Description

+

OdometryTank defines an odometry system for a tank drivetrain This requires encoders in the same orientation as the drive wheels Odometry is a "start and forget" subsystem, which means once it's created and configured, it will constantly run in the background and track the robot's X, Y and rotation coordinates.

+

Constructor & Destructor Documentation

+ +

◆ OdometryTank() [1/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
OdometryTank::OdometryTank (vex::motor_group & left_side,
vex::motor_group & right_side,
robot_specs_tconfig,
vex::inertial * imu = NULL,
bool is_async = true 
)
+
+

Initialize the Odometry module, calculating position from the drive motors.

Parameters
+ + + + + + +
left_sideThe left motors
right_sideThe right motors
configthe specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained
imuThe robot's inertial sensor. If not included, rotation is calculated from the encoders.
is_asyncIf true, position will be updated in the background continuously. If false, the programmer will have to manually call update().
+
+
+ +
+
+ +

◆ OdometryTank() [2/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
OdometryTank::OdometryTank (CustomEncoderleft_enc,
CustomEncoderright_enc,
robot_specs_tconfig,
vex::inertial * imu = NULL,
bool is_async = true 
)
+
+

Initialize the Odometry module, calculating position from the drive motors.

Parameters
+ + + + + + +
left_encThe left motors
right_encThe right motors
configthe specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained
imuThe robot's inertial sensor. If not included, rotation is calculated from the encoders.
is_asyncIf true, position will be updated in the background continuously. If false, the programmer will have to manually call update().
+
+
+ +
+
+

Member Function Documentation

+ +

◆ set_position()

+ +
+
+ + + + + +
+ + + + + + + + +
void OdometryTank::set_position (const position_tnewpos = zero_pos)
+
+overridevirtual
+
+

set_position tells the odometry to place itself at a position

Parameters
+ + +
newposthe position the odometry will take
+
+
+

Resets the position and rotational data to the input.

+ +

Reimplemented from OdometryBase.

+ +
+
+ +

◆ update()

+ +
+
+ + + + + +
+ + + + + + + +
position_t OdometryTank::update ()
+
+overridevirtual
+
+

Update the current position on the field based on the sensors

Returns
the position that odometry has calculated itself to be at
+

Update, store and return the current position of the robot. Only use if not initializing with a separate thread.

+ +

Implements OdometryBase.

+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/subsystems/odometry/odometry_tank.h
  • +
  • src/subsystems/odometry/odometry_tank.cpp
  • +
+
+ + + + diff --git a/documentation/html/classOdometryTank.png b/documentation/html/classOdometryTank.png new file mode 100644 index 0000000000000000000000000000000000000000..84c96799bab641858ec7d9a0c377dff4274a1c77 GIT binary patch literal 541 zcmV+&0^vTJr#LVva2S`&=)l0h|Ns9}lGCUF000SeQchC<|NsC0|NsC0Hv*f~0004~ zNklo8_LGO=^j`cnwo-y7C3@BApCh-jcM;Kvx_JORKRy#QdM zCi7pfxeg}tH~drwv-y9%e-%zV=6q;s{$H`5l6O#7JD;ydkS zkheCZayh>*fu8w0C3_NQ#m6z})(mPV-Us}8Dvz1k_-h+Y&<(y6(y()8Omn=&HwBV~ z;kP#D{Pgn3fvd;nXUsp>*YtnWKU!5=+v*>Z!_rhGhPQsdmkgituh~83Uo>0aXJ%$! fU%(F`gn9Y_VW3V+flA{300000NkvXXu0mjfwf_-5 literal 0 HcmV?d00001 diff --git a/documentation/html/classPID-members.html b/documentation/html/classPID-members.html new file mode 100644 index 0000000..ba81b0f --- /dev/null +++ b/documentation/html/classPID-members.html @@ -0,0 +1,103 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
PID Member List
+
+
+ +

This is the complete list of members for PID, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + +
ANGULAR enum value (defined in PID)PID
configPID
ERROR_TYPE enum namePID
FeedbackType enum name (defined in Feedback)Feedback
FeedforwardType enum value (defined in Feedback)Feedback
get() overridePIDvirtual
get_error()PID
get_target()PID
get_type() override (defined in PID)PIDvirtual
init(double start_pt, double set_pt) overridePIDvirtual
is_on_target() overridePIDvirtual
LINEAR enum value (defined in PID)PID
OtherType enum value (defined in Feedback)Feedback
PID(pid_config_t &config)PID
PIDType enum value (defined in Feedback)Feedback
reset()PID
set_limits(double lower, double upper) overridePIDvirtual
set_target(double target)PID
update(double sensor_val) overridePIDvirtual
+ + + + diff --git a/documentation/html/classPID.html b/documentation/html/classPID.html new file mode 100644 index 0000000..f418f70 --- /dev/null +++ b/documentation/html/classPID.html @@ -0,0 +1,509 @@ + + + + + + + +RIT VEXU Core API: PID Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
+ +

#include <pid.h>

+
+Inheritance diagram for PID:
+
+
+ + +Feedback + +
+ + + + +

+Classes

struct  pid_config_t
 
+ + + + + + +

+Public Types

enum  ERROR_TYPE { LINEAR +, ANGULAR + }
 
- Public Types inherited from Feedback
enum  FeedbackType { PIDType +, FeedforwardType +, OtherType + }
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

 PID (pid_config_t &config)
 
void init (double start_pt, double set_pt) override
 
double update (double sensor_val) override
 
double get () override
 
void set_limits (double lower, double upper) override
 
bool is_on_target () override
 
void reset ()
 
double get_error ()
 
double get_target ()
 
void set_target (double target)
 
Feedback::FeedbackType get_type () override
 
virtual void init (double start_pt, double set_pt)=0
 
virtual double update (double val)=0
 
virtual double get ()=0
 
virtual void set_limits (double lower, double upper)=0
 
virtual bool is_on_target ()=0
 
+virtual Feedback::FeedbackType get_type ()
 
+ + + + +

+Public Attributes

+pid_config_tconfig
 configuration struct for this controller. see pid_config_t for information about what this contains
 
+

Detailed Description

+

PID Class

+

Defines a standard feedback loop using the constants kP, kI, kD, deadband, and on_target_time. The formula is:

+

out = kP*error + kI*integral(d Error) + kD*(dError/dt)

+

The PID object will determine it is "on target" when the error is within the deadband, for a duration of on_target_time

+
Author
Ryan McGee
+
Date
4/3/2020
+

Member Enumeration Documentation

+ +

◆ ERROR_TYPE

+ +
+
+ + + + +
enum PID::ERROR_TYPE
+
+

An enum to distinguish between a linear and angular caluclation of PID error.

+ +
+
+

Constructor & Destructor Documentation

+ +

◆ PID()

+ +
+
+ + + + + + + + +
PID::PID (pid_config_tconfig)
+
+

Create the PID object

Parameters
+ + +
configthe configuration data for this controller
+
+
+

Create the PID object

+ +
+
+

Member Function Documentation

+ +

◆ get()

+ +
+
+ + + + + +
+ + + + + + + +
double PID::get ()
+
+overridevirtual
+
+

Gets the current PID out value, from when update() was last run

Returns
the Out value of the controller (voltage, RPM, whatever the PID controller is controlling)
+

Gets the current PID out value, from when update() was last run

+ +

Implements Feedback.

+ +
+
+ +

◆ get_error()

+ +
+
+ + + + + + + +
double PID::get_error ()
+
+

Get the delta between the current sensor data and the target

Returns
the error calculated. how it is calculated depends on error_method specified in pid_config_t
+

Get the delta between the current sensor data and the target

+ +
+
+ +

◆ get_target()

+ +
+
+ + + + + + + +
double PID::get_target ()
+
+

Get the PID's target

Returns
the target the PID controller is trying to achieve
+ +
+
+ +

◆ get_type()

+ +
+
+ + + + + +
+ + + + + + + +
Feedback::FeedbackType PID::get_type ()
+
+overridevirtual
+
+ +

Reimplemented from Feedback.

+ +
+
+ +

◆ init()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
void PID::init (double start_pt,
double set_pt 
)
+
+overridevirtual
+
+

Inherited from Feedback for interoperability. Update the setpoint and reset integral accumulation

+

start_pt can be safely ignored in this feedback controller

Parameters
+ + + +
start_ptcommpletely ignored for PID. necessary to satisfy Feedback base
set_ptsets the target of the PID controller
+
+
+ +

Implements Feedback.

+ +
+
+ +

◆ is_on_target()

+ +
+
+ + + + + +
+ + + + + + + +
bool PID::is_on_target ()
+
+overridevirtual
+
+

Checks if the PID controller is on target.
+

Returns
true if the loop is within [deadband] for [on_target_time] seconds
+

Returns true if the loop is within [deadband] for [on_target_time] seconds

+ +

Implements Feedback.

+ +
+
+ +

◆ reset()

+ +
+
+ + + + + + + +
void PID::reset ()
+
+

Reset the PID loop by resetting time since 0 and accumulated error.

+ +
+
+ +

◆ set_limits()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
void PID::set_limits (double lower,
double upper 
)
+
+overridevirtual
+
+

Set the limits on the PID out. The PID out will "clip" itself to be between the limits.

Parameters
+ + + +
lowerthe lower limit. the PID controller will never command the output go below lower
upperthe upper limit. the PID controller will never command the output go higher than upper
+
+
+

Set the limits on the PID out. The PID out will "clip" itself to be between the limits.

+ +

Implements Feedback.

+ +
+
+ +

◆ set_target()

+ +
+
+ + + + + + + + +
void PID::set_target (double target)
+
+

Set the target for the PID loop, where the robot is trying to end up

Parameters
+ + +
targetthe sensor reading we would like to achieve
+
+
+

Set the target for the PID loop, where the robot is trying to end up

+ +
+
+ +

◆ update()

+ +
+
+ + + + + +
+ + + + + + + + +
double PID::update (double sensor_val)
+
+overridevirtual
+
+

Update the PID loop by taking the time difference from last update, and running the PID formula with the new sensor data

Parameters
+ + +
sensor_valthe distance, angle, encoder position or whatever it is we are measuring
+
+
+
Returns
the new output. What would be returned by PID::get()
+ +

Implements Feedback.

+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/utils/pid.h
  • +
  • src/utils/pid.cpp
  • +
+
+ + + + diff --git a/documentation/html/classPID.png b/documentation/html/classPID.png new file mode 100644 index 0000000000000000000000000000000000000000..364123b3e5af956757c94b478945a17461604170 GIT binary patch literal 362 zcmeAS@N?(olHy`uVBq!ia0vp^E!3-p)cPaA%Dd_;85ZC|z{{xvX-h3_XKeXJ! zK(jz%`k5C84jcfA2T!`Z0w~8>666=m0OW&#In(SbK*6t`E{-7;jBn>&>}xjQVYx2N z`SySPN5+M`Y60tJcwL<Q?H&B`eAmq>>KTso7_K4nr1VxBysz?%4_-0 zo&5QvtE;R^*S{_O$vi2=9cZSpmzSn02g4i#28SuuDu)Z2pYol2(Gi_DvF75-B`geP zKy0JQ$l&kAaA2|!!-qfioiigvW~dzX=v1kU^LVz;f1|HzW_$Rg)D_>2Jc5o(Pf9+0 zTy^!lBU(SbPJX@IS*Jefi*=Ba=e+&uhQ{2Vn59{)CSGgUvIQ6b44$rjF6*2UngHFh Bn3w + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
PIDFF Member List
+
+
+ +

This is the complete list of members for PIDFF, including all inherited members.

+ + + + + + + + + + + + + + + +
FeedbackType enum name (defined in Feedback)Feedback
FeedforwardType enum value (defined in Feedback)Feedback
get() overridePIDFFvirtual
get_type() (defined in Feedback)Feedbackinlinevirtual
init(double start_pt, double set_pt) overridePIDFFvirtual
is_on_target() overridePIDFFvirtual
OtherType enum value (defined in Feedback)Feedback
pid (defined in PIDFF)PIDFF
PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg) (defined in PIDFF)PIDFF
PIDType enum value (defined in Feedback)Feedback
set_limits(double lower, double upper) overridePIDFFvirtual
set_target(double set_pt)PIDFF
update(double val) overridePIDFFvirtual
update(double val, double vel_setpt, double a_setpt=0)PIDFF
+ + + + diff --git a/documentation/html/classPIDFF.html b/documentation/html/classPIDFF.html new file mode 100644 index 0000000..131cf69 --- /dev/null +++ b/documentation/html/classPIDFF.html @@ -0,0 +1,401 @@ + + + + + + + +RIT VEXU Core API: PIDFF Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
+
+Inheritance diagram for PIDFF:
+
+
+ + +Feedback + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

PIDFF (PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg)
 
void init (double start_pt, double set_pt) override
 
void set_target (double set_pt)
 
double update (double val) override
 
double update (double val, double vel_setpt, double a_setpt=0)
 
double get () override
 
void set_limits (double lower, double upper) override
 
bool is_on_target () override
 
- Public Member Functions inherited from Feedback
virtual void init (double start_pt, double set_pt)=0
 
virtual double update (double val)=0
 
virtual double get ()=0
 
virtual void set_limits (double lower, double upper)=0
 
virtual bool is_on_target ()=0
 
+virtual Feedback::FeedbackType get_type ()
 
+ + + +

+Public Attributes

+PID pid
 
+ + + + +

+Additional Inherited Members

- Public Types inherited from Feedback
enum  FeedbackType { PIDType +, FeedforwardType +, OtherType + }
 
+

Member Function Documentation

+ +

◆ get()

+ +
+
+ + + + + +
+ + + + + + + +
double PIDFF::get ()
+
+overridevirtual
+
+
Returns
the last saved result from the feedback controller
+ +

Implements Feedback.

+ +
+
+ +

◆ init()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
void PIDFF::init (double start_pt,
double set_pt 
)
+
+overridevirtual
+
+

Initialize the feedback controller for a movement

+
Parameters
+ + + +
start_ptthe current sensor value
set_ptwhere the sensor value should be
+
+
+ +

Implements Feedback.

+ +
+
+ +

◆ is_on_target()

+ +
+
+ + + + + +
+ + + + + + + +
bool PIDFF::is_on_target ()
+
+overridevirtual
+
+
Returns
true if the feedback controller has reached it's setpoint
+ +

Implements Feedback.

+ +
+
+ +

◆ set_limits()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
void PIDFF::set_limits (double lower,
double upper 
)
+
+overridevirtual
+
+

Clamp the upper and lower limits of the output. If both are 0, no limits should be applied.

+
Parameters
+ + + +
lowerUpper limit
upperLower limit
+
+
+ +

Implements Feedback.

+ +
+
+ +

◆ set_target()

+ +
+
+ + + + + + + + +
void PIDFF::set_target (double set_pt)
+
+

Set the target of the PID loop

Parameters
+ + +
set_ptSetpoint / target value
+
+
+ +
+
+ +

◆ update() [1/2]

+ +
+
+ + + + + +
+ + + + + + + + +
double PIDFF::update (double val)
+
+overridevirtual
+
+

Iterate the feedback loop once with an updated sensor value. Only kS for feedfoward will be applied.

+
Parameters
+ + +
valvalue from the sensor
+
+
+
Returns
feedback loop result
+ +

Implements Feedback.

+ +
+
+ +

◆ update() [2/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
double PIDFF::update (double val,
double vel_setpt,
double a_setpt = 0 
)
+
+

Iterate the feedback loop once with an updated sensor value

+
Parameters
+ + + + +
valvalue from the sensor
vel_setptVelocity for feedforward
a_setptAcceleration for feedfoward
+
+
+
Returns
feedback loop result
+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/utils/pidff.h
  • +
  • src/utils/pidff.cpp
  • +
+
+ + + + diff --git a/documentation/html/classPIDFF.png b/documentation/html/classPIDFF.png new file mode 100644 index 0000000000000000000000000000000000000000..6d05d23a375c177db25840a37677290b0377730c GIT binary patch literal 377 zcmeAS@N?(olHy`uVBq!ia0vp^E!3-p)cPaA%Dd_;85ZC|z{{xvX-h3_XKeXJ! zK(jz%`k5C84jcfA2T!`Z0w~8>666=m0OW&#In(Sb3=E7co-U3d6^w7^UhHd8;Bn2* z7ry-e|D#aJBTUCaPo!;*Ha>0^dTxr*XTH#@feTbD-8?)l6?>%Y_t=!C8+TQj)3dBn z`RAA77L}D<(HfuJimK)u+Lo}qcG~qHGry=Te_$T2cB5=kie-hT<~@&D7v5%{zx8&{ zjFV3j^8MA{Zmo&^!|1t5QAOotr0S|w%?t;4xfyzloHywR>lmx7PQGL0`l;JbU4A6}3k!pdA|r#p2g8BS|5cQf7CW3dbBv>N=FH{FH=pl4I%%1T_$^V{lh3Ewy_^>R zYWrVaPtUrTqFE;uPj0>Ep=Z5Pb^SKu=uiJjUfn+#+&S~6u~Smov!B&Mf)gG0F_^bm VPMv)uApsaj44$rjF6*2UngHUNr7Hjc literal 0 HcmV?d00001 diff --git a/documentation/html/classSpinRPMCommand-members.html b/documentation/html/classSpinRPMCommand-members.html new file mode 100644 index 0000000..6f34ef6 --- /dev/null +++ b/documentation/html/classSpinRPMCommand-members.html @@ -0,0 +1,89 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
SpinRPMCommand Member List
+
+
+ +

This is the complete list of members for SpinRPMCommand, including all inherited members.

+ + + + + + +
on_timeout()AutoCommandinlinevirtual
run() overrideSpinRPMCommandvirtual
SpinRPMCommand(Flywheel &flywheel, int rpm)SpinRPMCommand
timeout_secondsAutoCommand
withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
+ + + + diff --git a/documentation/html/classSpinRPMCommand.html b/documentation/html/classSpinRPMCommand.html new file mode 100644 index 0000000..72ab14c --- /dev/null +++ b/documentation/html/classSpinRPMCommand.html @@ -0,0 +1,189 @@ + + + + + + + +RIT VEXU Core API: SpinRPMCommand Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
SpinRPMCommand Class Reference
+
+
+ +

#include <flywheel_commands.h>

+
+Inheritance diagram for SpinRPMCommand:
+
+
+ + +AutoCommand + +
+ + + + + + + + + + + + + +

+Public Member Functions

 SpinRPMCommand (Flywheel &flywheel, int rpm)
 
bool run () override
 
- Public Member Functions inherited from AutoCommand
virtual bool run ()
 
virtual void on_timeout ()
 
+AutoCommandwithTimeout (double t_seconds)
 
+ + + + +

+Additional Inherited Members

- Public Attributes inherited from AutoCommand
double timeout_seconds = 10.0
 
+

Detailed Description

+

File: flywheel_commands.h Desc: [insert meaningful desc] AutoCommand wrapper class for the spinRPM function in the Flywheel class

+

Constructor & Destructor Documentation

+ +

◆ SpinRPMCommand()

+ +
+
+ + + + + + + + + + + + + + + + + + +
SpinRPMCommand::SpinRPMCommand (Flywheelflywheel,
int rpm 
)
+
+

Construct a SpinRPM Command

Parameters
+ + + +
flywheelthe flywheel sys to command
rpmthe rpm that we should spin at
+
+
+

File: flywheel_commands.cpp Desc: [insert meaningful desc]

+ +
+
+

Member Function Documentation

+ +

◆ run()

+ +
+
+ + + + + +
+ + + + + + + +
bool SpinRPMCommand::run ()
+
+overridevirtual
+
+

Run spin_manual Overrides run from AutoCommand

Returns
true when execution is complete, false otherwise
+ +

Reimplemented from AutoCommand.

+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/utils/command_structure/flywheel_commands.h
  • +
  • src/utils/command_structure/flywheel_commands.cpp
  • +
+
+ + + + diff --git a/documentation/html/classSpinRPMCommand.png b/documentation/html/classSpinRPMCommand.png new file mode 100644 index 0000000000000000000000000000000000000000..1d9f067b838fa3b50907740b084fe8b767e50efe GIT binary patch literal 543 zcmeAS@N?(olHy`uVBq!ia0vp^{mhF42Mz$mgC|{H0hHq`3GxeO0P?}WoN4wI1_s7eo-U3d6^w7^#`Yan;AuJD z9CG%r|DN0*h8IfAJ6$4HhWHq6{P>(j{XBmNm(es!k!0r#Ej_b=DnP2A&qe&Tig@Z25BYtI!JE3JI;O{Q}1)BK)CC#>5GJhR=4 z!ak<&SXsTU;PEx@I}$hF*qzC3yuPz8VBV7TCr(tA{Ns+vpLJ!~zkk!34K~TmRyNzH zu5i-rwYBG@$6%}DPw*aj2i0@BiiStc(5dSsGG+~=L^)mE?DJyj-ko$@W;NnfT1RXjXqGUg@N|8mMH>*f&qx(>$Y4HFJ+z(b+TauJbn?OWd_N Tb{`KgDj7Uo{an^LB{Ts5AD|31 literal 0 HcmV?d00001 diff --git a/documentation/html/classTankDrive-members.html b/documentation/html/classTankDrive-members.html new file mode 100644 index 0000000..d42c75b --- /dev/null +++ b/documentation/html/classTankDrive-members.html @@ -0,0 +1,99 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
TankDrive Member List
+
+
+ +

This is the complete list of members for TankDrive, including all inherited members.

+ + + + + + + + + + + + + + + + +
drive_arcade(double forward_back, double left_right, int power=1)TankDrive
drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed=1)TankDrive
drive_forward(double inches, directionType dir, double max_speed=1)TankDrive
drive_tank(double left, double right, int power=1, bool isdriver=false)TankDrive
drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed=1)TankDrive
drive_to_point(double x, double y, vex::directionType dir, double max_speed=1)TankDrive
modify_inputs(double input, int power=2)TankDrivestatic
pure_pursuit(std::vector< PurePursuit::hermite_point > path, directionType dir, double radius, double res, Feedback &feedback, double max_speed=1)TankDrive
reset_auto()TankDrive
stop()TankDrive
TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom=NULL)TankDrive
turn_degrees(double degrees, Feedback &feedback, double max_speed=1)TankDrive
turn_degrees(double degrees, double max_speed=1)TankDrive
turn_to_heading(double heading_deg, Feedback &feedback, double max_speed=1)TankDrive
turn_to_heading(double heading_deg, double max_speed=1)TankDrive
+ + + + diff --git a/documentation/html/classTankDrive.html b/documentation/html/classTankDrive.html new file mode 100644 index 0000000..12429bc --- /dev/null +++ b/documentation/html/classTankDrive.html @@ -0,0 +1,877 @@ + + + + + + + +RIT VEXU Core API: TankDrive Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
+ +

#include <tank_drive.h>

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

 TankDrive (motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom=NULL)
 
void stop ()
 
void drive_tank (double left, double right, int power=1, bool isdriver=false)
 
void drive_arcade (double forward_back, double left_right, int power=1)
 
bool drive_forward (double inches, directionType dir, Feedback &feedback, double max_speed=1)
 
bool drive_forward (double inches, directionType dir, double max_speed=1)
 
bool turn_degrees (double degrees, Feedback &feedback, double max_speed=1)
 
bool turn_degrees (double degrees, double max_speed=1)
 
bool drive_to_point (double x, double y, vex::directionType dir, Feedback &feedback, double max_speed=1)
 
bool drive_to_point (double x, double y, vex::directionType dir, double max_speed=1)
 
bool turn_to_heading (double heading_deg, Feedback &feedback, double max_speed=1)
 
bool turn_to_heading (double heading_deg, double max_speed=1)
 
void reset_auto ()
 
bool pure_pursuit (std::vector< PurePursuit::hermite_point > path, directionType dir, double radius, double res, Feedback &feedback, double max_speed=1)
 
+ + + +

+Static Public Member Functions

static double modify_inputs (double input, int power=2)
 
+

Detailed Description

+

TankDrive is a class to run a tank drive system. A tank drive system, sometimes called differential drive, has a motor (or group of synchronized motors) on the left and right side

+

Constructor & Destructor Documentation

+ +

◆ TankDrive()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
TankDrive::TankDrive (motor_group & left_motors,
motor_group & right_motors,
robot_specs_tconfig,
OdometryBaseodom = NULL 
)
+
+

Create the TankDrive object

Parameters
+ + + + + +
left_motorsleft side drive motors
right_motorsright side drive motors
configthe configuration specification defining physical dimensions about the robot. See robot_specs_t for more info
odoman odometry system to track position and rotation. this is necessary to execute autonomous paths
+
+
+ +
+
+

Member Function Documentation

+ +

◆ drive_arcade()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
void TankDrive::drive_arcade (double forward_back,
double left_right,
int power = 1 
)
+
+

Drive the robot using arcade style controls. forward_back controls the linear motion, left_right controls the turning.

+

forward_back and left_right are in "percent": -1.0 -> 1.0

+
Parameters
+ + + + +
forward_backthe percent to move forward or backward
left_rightthe percent to turn left or right
powermodifies the input velocities left^power, right^power
+
+
+

Drive the robot using arcade style controls. forward_back controls the linear motion, left_right controls the turning.

+

left_motors and right_motors are in "percent": -1.0 -> 1.0

+ +
+
+ +

◆ drive_forward() [1/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
bool TankDrive::drive_forward (double inches,
directionType dir,
double max_speed = 1 
)
+
+

Autonomously drive the robot forward a certain distance

+
Parameters
+ + + + +
inchesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
dirthe direction we want to travel forward and backward
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
+
+
+

Autonomously drive the robot forward a certain distance

+
Parameters
+ + + + +
inchesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
dirthe direction we want to travel forward and backward
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
+
+
+
Returns
true if we have finished driving to our point
+ +
+
+ +

◆ drive_forward() [2/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
bool TankDrive::drive_forward (double inches,
directionType dir,
Feedbackfeedback,
double max_speed = 1 
)
+
+

Use odometry to drive forward a certain distance using a custom feedback controller

+

Returns whether or not the robot has reached it's destination.

Parameters
+ + + + + +
inchesthe distance to drive forward
dirthe direction we want to travel forward and backward
feedbackthe custom feedback controller we will use to travel. controls the rate at which we accelerate and drive.
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
+
+
+
Returns
true when we have reached our target distance
+

Use odometry to drive forward a certain distance using a custom feedback controller

+

Returns whether or not the robot has reached it's destination.

Parameters
+ + + + + +
inchesthe distance to drive forward
dirthe direction we want to travel forward and backward
feedbackthe custom feedback controller we will use to travel. controls the rate at which we accelerate and drive.
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
+
+
+ +
+
+ +

◆ drive_tank()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void TankDrive::drive_tank (double left,
double right,
int power = 1,
bool isdriver = false 
)
+
+

Drive the robot using differential style controls. left_motors controls the left motors, right_motors controls the right motors.

+

left_motors and right_motors are in "percent": -1.0 -> 1.0

Parameters
+ + + + + +
leftthe percent to run the left motors
rightthe percent to run the right motors
powermodifies the input velocities left^power, right^power
isdriverdefault false. if true uses motor percentage. if false uses plain percentage of maximum voltage
+
+
+

Drive the robot using differential style controls. left_motors controls the left motors, right_motors controls the right motors.

+

left_motors and right_motors are in "percent": -1.0 -> 1.0

+ +
+
+ +

◆ drive_to_point() [1/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
bool TankDrive::drive_to_point (double x,
double y,
vex::directionType dir,
double max_speed = 1 
)
+
+

Use odometry to automatically drive the robot to a point on the field. X and Y is the final point we want the robot. Here we use the default feedback controller from the drive_sys

+

Returns whether or not the robot has reached it's destination.

Parameters
+ + + + + +
xthe x position of the target
ythe y position of the target
dirthe direction we want to travel forward and backward
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
+
+
+

Use odometry to automatically drive the robot to a point on the field. X and Y is the final point we want the robot. Here we use the default feedback controller from the drive_sys

+

Returns whether or not the robot has reached it's destination.

Parameters
+ + + + + +
xthe x position of the target
ythe y position of the target
dirthe direction we want to travel forward and backward
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
+
+
+
Returns
true if we have reached our target point
+ +
+
+ +

◆ drive_to_point() [2/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
bool TankDrive::drive_to_point (double x,
double y,
vex::directionType dir,
Feedbackfeedback,
double max_speed = 1 
)
+
+

Use odometry to automatically drive the robot to a point on the field. X and Y is the final point we want the robot.

+

Returns whether or not the robot has reached it's destination.

Parameters
+ + + + + + +
xthe x position of the target
ythe y position of the target
dirthe direction we want to travel forward and backward
feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
+
+
+

Use odometry to automatically drive the robot to a point on the field. X and Y is the final point we want the robot.

+

Returns whether or not the robot has reached it's destination.

Parameters
+ + + + + + +
xthe x position of the target
ythe y position of the target
dirthe direction we want to travel forward and backward
feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
+
+
+
Returns
true if we have reached our target point
+ +
+
+ +

◆ modify_inputs()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
double TankDrive::modify_inputs (double input,
int power = 2 
)
+
+static
+
+

Create a curve for the inputs, so that drivers have more control at lower speeds. Curves are exponential, with the default being squaring the inputs.

+
Parameters
+ + + +
inputthe input before modification
powerthe power to raise input to
+
+
+
Returns
input ^ power (accounts for negative inputs and odd numbered powers)
+

Modify the inputs from the controller by squaring / cubing, etc Allows for better control of the robot at slower speeds

Parameters
+ + + +
inputthe input signal -1 -> 1
powerthe power to raise the signal to
+
+
+
Returns
input^power accounting for any sign issues that would arise with this naive solution
+ +
+
+ +

◆ pure_pursuit()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
bool TankDrive::pure_pursuit (std::vector< PurePursuit::hermite_pointpath,
directionType dir,
double radius,
double res,
Feedbackfeedback,
double max_speed = 1 
)
+
+

Follow a hermite curve using the pure pursuit algorithm.

+
Parameters
+ + + + + + + +
pathThe hermite curve for the robot to take. Must have 2 or more points.
dirWhether the robot should move forward or backwards
radiusHow the pure pursuit radius, in inches, for finding the lookahead point
resThe number of points to use along the path; the hermite curve is split up into "res" individual points.
feedbackThe feedback controller to use
max_speedRobot's maximum speed throughout the path, between 0 and 1.0
+
+
+
Returns
true when we reach the end of the path
+ +
+
+ +

◆ reset_auto()

+ +
+
+ + + + + + + +
void TankDrive::reset_auto ()
+
+

Reset the initialization for autonomous drive functions

+ +
+
+ +

◆ stop()

+ +
+
+ + + + + + + +
void TankDrive::stop ()
+
+

Stops rotation of all the motors using their "brake mode"

+ +
+
+ +

◆ turn_degrees() [1/2]

+ +
+
+ + + + + + + + + + + + + + + + + + +
bool TankDrive::turn_degrees (double degrees,
double max_speed = 1 
)
+
+

Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed of percent_speed (-1.0 -> 1.0)

+

Uses the defualt turning feedback of the drive system.

+
Parameters
+ + + +
degreesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
+
+
+

Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed of percent_speed (-1.0 -> 1.0)

+

Uses the defualt turning feedback of the drive system.

+
Parameters
+ + + +
degreesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
+
+
+
Returns
true if we turned te target number of degrees
+ +
+
+ +

◆ turn_degrees() [2/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
bool TankDrive::turn_degrees (double degrees,
Feedbackfeedback,
double max_speed = 1 
)
+
+

Autonomously turn the robot X degrees counterclockwise (negative for clockwise), with a maximum motor speed of percent_speed (-1.0 -> 1.0)

+

Uses PID + Feedforward for it's control.

+
Parameters
+ + + + +
degreesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
+
+
+

Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed of percent_speed (-1.0 -> 1.0)

+

Uses the specified feedback for it's control.

+
Parameters
+ + + + +
degreesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
+
+
+
Returns
true if we have turned our target number of degrees
+ +
+
+ +

◆ turn_to_heading() [1/2]

+ +
+
+ + + + + + + + + + + + + + + + + + +
bool TankDrive::turn_to_heading (double heading_deg,
double max_speed = 1 
)
+
+

Turn the robot in place to an exact heading relative to the field. 0 is forward. Uses the defualt turn feedback of the drive system

+
Parameters
+ + + +
heading_degthe heading to which we will turn
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
+
+
+

Turn the robot in place to an exact heading relative to the field. 0 is forward. Uses the defualt turn feedback of the drive system

+
Parameters
+ + + +
heading_degthe heading to which we will turn
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
+
+
+
Returns
true if we have reached our target heading
+ +
+
+ +

◆ turn_to_heading() [2/2]

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
bool TankDrive::turn_to_heading (double heading_deg,
Feedbackfeedback,
double max_speed = 1 
)
+
+

Turn the robot in place to an exact heading relative to the field. 0 is forward.

+
Parameters
+ + + + +
heading_degthe heading to which we will turn
feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
+
+
+

Turn the robot in place to an exact heading relative to the field. 0 is forward.

+
Parameters
+ + + + +
heading_degthe heading to which we will turn
feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
+
+
+
Returns
true if we have reached our target heading
+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/subsystems/tank_drive.h
  • +
  • src/subsystems/tank_drive.cpp
  • +
+
+ + + + diff --git a/documentation/html/classTrapezoidProfile-members.html b/documentation/html/classTrapezoidProfile-members.html new file mode 100644 index 0000000..6e7caba --- /dev/null +++ b/documentation/html/classTrapezoidProfile-members.html @@ -0,0 +1,90 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
TrapezoidProfile Member List
+
+
+ +

This is the complete list of members for TrapezoidProfile, including all inherited members.

+ + + + + + + +
calculate(double time_s)TrapezoidProfile
get_movement_time()TrapezoidProfile
set_accel(double accel)TrapezoidProfile
set_endpts(double start, double end)TrapezoidProfile
set_max_v(double max_v)TrapezoidProfile
TrapezoidProfile(double max_v, double accel)TrapezoidProfile
+ + + + diff --git a/documentation/html/classTrapezoidProfile.html b/documentation/html/classTrapezoidProfile.html new file mode 100644 index 0000000..0847ad1 --- /dev/null +++ b/documentation/html/classTrapezoidProfile.html @@ -0,0 +1,290 @@ + + + + + + + +RIT VEXU Core API: TrapezoidProfile Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
TrapezoidProfile Class Reference
+
+
+ +

#include <trapezoid_profile.h>

+ + + + + + + + + + + + + + + + +

+Public Member Functions

 TrapezoidProfile (double max_v, double accel)
 Construct a new Trapezoid Profile object.
 
motion_t calculate (double time_s)
 Run the trapezoidal profile based on the time that's ellapsed.
 
void set_endpts (double start, double end)
 
void set_accel (double accel)
 
void set_max_v (double max_v)
 
double get_movement_time ()
 
+

Detailed Description

+

Trapezoid Profile

+

This is a motion profile defined by an acceleration, maximum velocity, start point and end point. Using this information, a parametric function is generated, with a period of acceleration, constant velocity, and deceleration. The velocity graph looks like a trapezoid, giving it it's name.

+

If the maximum velocity is set high enough, this will become a S-curve profile, with only acceleration and deceleration.

+

This class is designed for use in properly modelling the motion of the robots to create a feedfoward and target for PID. Acceleration and Maximum velocity should be measured on the robot and tuned down slightly to account for battery drop.

+

Here are the equations graphed for ease of understanding: https://www.desmos.com/calculator/rkm3ivu1yk

+
Author
Ryan McGee
+
Date
7/12/2022
+

Constructor & Destructor Documentation

+ +

◆ TrapezoidProfile()

+ +
+
+ + + + + + + + + + + + + + + + + + +
TrapezoidProfile::TrapezoidProfile (double max_v,
double accel 
)
+
+ +

Construct a new Trapezoid Profile object.

+
Parameters
+ + + +
max_vMaximum velocity the robot can run at
accelMaximum acceleration of the robot
+
+
+ +
+
+

Member Function Documentation

+ +

◆ calculate()

+ +
+
+ + + + + + + + +
motion_t TrapezoidProfile::calculate (double time_s)
+
+ +

Run the trapezoidal profile based on the time that's ellapsed.

+
Parameters
+ + +
time_sTime since start of movement
+
+
+
Returns
motion_t Position, velocity and acceleration
+
Parameters
+ + +
time_sTime since start of movement
+
+
+
Returns
motion_t Position, velocity and acceleration
+ +
+
+ +

◆ get_movement_time()

+ +
+
+ + + + + + + +
double TrapezoidProfile::get_movement_time ()
+
+

uses the kinematic equations to and specified accel and max_v to figure out how long moving along the profile would take

Returns
the time the path will take to travel
+ +
+
+ +

◆ set_accel()

+ +
+
+ + + + + + + + +
void TrapezoidProfile::set_accel (double accel)
+
+

set_accel sets the acceleration this profile will use (the left and right legs of the trapezoid)

Parameters
+ + +
accelthe acceleration amount to use
+
+
+ +
+
+ +

◆ set_endpts()

+ +
+
+ + + + + + + + + + + + + + + + + + +
void TrapezoidProfile::set_endpts (double start,
double end 
)
+
+

set_endpts defines a start and end position

Parameters
+ + + +
startthe starting position of the path
endthe ending position of the path
+
+
+ +
+
+ +

◆ set_max_v()

+ +
+
+ + + + + + + + +
void TrapezoidProfile::set_max_v (double max_v)
+
+

sets the maximum velocity for the profile (the height of the top of the trapezoid)

Parameters
+ + +
max_vthe maximum velocity the robot can travel at
+
+
+ +
+
+
The documentation for this class was generated from the following files: +
+ + + + diff --git a/documentation/html/classTurnDegreesCommand-members.html b/documentation/html/classTurnDegreesCommand-members.html new file mode 100644 index 0000000..70f2a65 --- /dev/null +++ b/documentation/html/classTurnDegreesCommand-members.html @@ -0,0 +1,89 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
TurnDegreesCommand Member List
+
+
+ +

This is the complete list of members for TurnDegreesCommand, including all inherited members.

+ + + + + + +
on_timeout() overrideTurnDegreesCommandvirtual
run() overrideTurnDegreesCommandvirtual
timeout_secondsAutoCommand
TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed=1)TurnDegreesCommand
withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
+ + + + diff --git a/documentation/html/classTurnDegreesCommand.html b/documentation/html/classTurnDegreesCommand.html new file mode 100644 index 0000000..79bf994 --- /dev/null +++ b/documentation/html/classTurnDegreesCommand.html @@ -0,0 +1,233 @@ + + + + + + + +RIT VEXU Core API: TurnDegreesCommand Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
TurnDegreesCommand Class Reference
+
+
+ +

#include <drive_commands.h>

+
+Inheritance diagram for TurnDegreesCommand:
+
+
+ + +AutoCommand + +
+ + + + + + + + + + + + + + + +

+Public Member Functions

 TurnDegreesCommand (TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed=1)
 
bool run () override
 
void on_timeout () override
 
- Public Member Functions inherited from AutoCommand
virtual bool run ()
 
virtual void on_timeout ()
 
+AutoCommandwithTimeout (double t_seconds)
 
+ + + + +

+Additional Inherited Members

- Public Attributes inherited from AutoCommand
double timeout_seconds = 10.0
 
+

Detailed Description

+

AutoCommand wrapper class for the turn_degrees function in the TankDrive class

+

Constructor & Destructor Documentation

+ +

◆ TurnDegreesCommand()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
TurnDegreesCommand::TurnDegreesCommand (TankDrivedrive_sys,
Feedbackfeedback,
double degrees,
double max_speed = 1 
)
+
+

Construct a TurnDegreesCommand Command

Parameters
+ + + + + +
drive_systhe drive system we are commanding
feedbackthe feedback controller we are using to execute the turn
degreeshow many degrees to rotate
max_speed0 -> 1 percentage of the drive systems speed to drive at
+
+
+ +
+
+

Member Function Documentation

+ +

◆ on_timeout()

+ +
+
+ + + + + +
+ + + + + + + +
void TurnDegreesCommand::on_timeout ()
+
+overridevirtual
+
+

Cleans up drive system if we time out before finishing

+

reset the drive system if we timeout

+ +

Reimplemented from AutoCommand.

+ +
+
+ +

◆ run()

+ +
+
+ + + + + +
+ + + + + + + +
bool TurnDegreesCommand::run ()
+
+overridevirtual
+
+

Run turn_degrees Overrides run from AutoCommand

Returns
true when execution is complete, false otherwise
+ +

Reimplemented from AutoCommand.

+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/utils/command_structure/drive_commands.h
  • +
  • src/utils/command_structure/drive_commands.cpp
  • +
+
+ + + + diff --git a/documentation/html/classTurnDegreesCommand.png b/documentation/html/classTurnDegreesCommand.png new file mode 100644 index 0000000000000000000000000000000000000000..fff51ee3c144b350062b9ba92a57f7b716a5cfbe GIT binary patch literal 614 zcmeAS@N?(olHy`uVBq!ia0vp^y+9nm!3-pY71+{%lyrbki0l9V|AEXGZ@!lHA6jl< zpjjX>{mhF42Mz$mgC|{H0hHq`3GxeO0P?}WoN4wI1_s8Do-U3d6^w7^Ud(%}AmFMm zuDR>~|D&Zm6348!l)Z{wcy)`Nn1R6@0fqG^ET5-3sGW4>ke>8~6Nq;vO-`G-NhTfbG$HYqNi(4_n*&R5}0swWa1;PrL|>^4<^hbn?FUIp1b}`;-`*Y&r z7k8fh$mlK|{e9Pr&O3Kaw$FS!yDp*a?6r0MpJz(V{x$Q}cVBBOFQfBv63;%Ko1zl? zR6q8C{EZvdu9M^*Pu{w-_PzHd)ko$rlWGpRO{$r;*;8|A=ntkC-V%?01`n12Qv`#j LtDnm{r-UW|-_Ij= literal 0 HcmV?d00001 diff --git a/documentation/html/classTurnToHeadingCommand-members.html b/documentation/html/classTurnToHeadingCommand-members.html new file mode 100644 index 0000000..acb092b --- /dev/null +++ b/documentation/html/classTurnToHeadingCommand-members.html @@ -0,0 +1,89 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
TurnToHeadingCommand Member List
+
+
+ +

This is the complete list of members for TurnToHeadingCommand, including all inherited members.

+ + + + + + +
on_timeout() overrideTurnToHeadingCommandvirtual
run() overrideTurnToHeadingCommandvirtual
timeout_secondsAutoCommand
TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed=1)TurnToHeadingCommand
withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
+ + + + diff --git a/documentation/html/classTurnToHeadingCommand.html b/documentation/html/classTurnToHeadingCommand.html new file mode 100644 index 0000000..0e0896b --- /dev/null +++ b/documentation/html/classTurnToHeadingCommand.html @@ -0,0 +1,233 @@ + + + + + + + +RIT VEXU Core API: TurnToHeadingCommand Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
TurnToHeadingCommand Class Reference
+
+
+ +

#include <drive_commands.h>

+
+Inheritance diagram for TurnToHeadingCommand:
+
+
+ + +AutoCommand + +
+ + + + + + + + + + + + + + + +

+Public Member Functions

 TurnToHeadingCommand (TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed=1)
 
bool run () override
 
void on_timeout () override
 
- Public Member Functions inherited from AutoCommand
virtual bool run ()
 
virtual void on_timeout ()
 
+AutoCommandwithTimeout (double t_seconds)
 
+ + + + +

+Additional Inherited Members

- Public Attributes inherited from AutoCommand
double timeout_seconds = 10.0
 
+

Detailed Description

+

AutoCommand wrapper class for the turn_to_heading() function in the TankDrive class

+

Constructor & Destructor Documentation

+ +

◆ TurnToHeadingCommand()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
TurnToHeadingCommand::TurnToHeadingCommand (TankDrivedrive_sys,
Feedbackfeedback,
double heading_deg,
double max_speed = 1 
)
+
+

Construct a TurnToHeadingCommand Command

Parameters
+ + + + + +
drive_systhe drive system we are commanding
feedbackthe feedback controller we are using to execute the drive
heading_degthe heading to turn to in degrees
max_speed0 -> 1 percentage of the drive systems speed to drive at
+
+
+ +
+
+

Member Function Documentation

+ +

◆ on_timeout()

+ +
+
+ + + + + +
+ + + + + + + +
void TurnToHeadingCommand::on_timeout ()
+
+overridevirtual
+
+

Cleans up drive system if we time out before finishing

+

reset the drive system if we don't hit our target

+ +

Reimplemented from AutoCommand.

+ +
+
+ +

◆ run()

+ +
+
+ + + + + +
+ + + + + + + +
bool TurnToHeadingCommand::run ()
+
+overridevirtual
+
+

Run turn_to_heading Overrides run from AutoCommand

Returns
true when execution is complete, false otherwise
+ +

Reimplemented from AutoCommand.

+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/utils/command_structure/drive_commands.h
  • +
  • src/utils/command_structure/drive_commands.cpp
  • +
+
+ + + + diff --git a/documentation/html/classTurnToHeadingCommand.png b/documentation/html/classTurnToHeadingCommand.png new file mode 100644 index 0000000000000000000000000000000000000000..5bb95c50a13fe6406ea6055259fd4067906bdb1f GIT binary patch literal 624 zcmV-$0+0QPP)54J0000RP)t-s|Ns90 z008Lh^>vTJr#LVva2S`&=)l0h|Ns9}lGCUF000SeQchC<|NsC0|NsC0Hv*f~0005| zNklhD_lj|Z|XTVOwybpVq50e?}Eq!m{qNh_{Kl2%-eB&{rJF~&G00PsCt05B)> zs=Z#*y3MP$n9b@ov6`Py0I=g~0AR({0Kkf?0e}@(0{|vH2|>U zY5-ux)d0YXs{w$O|3)o@5at9yl4iu!B*}`aNs^VUmJWp^4GfXgU6MwY#t-cW!%ETt zse7|(#{;yHb2Ulo*&1zb2WsnOXZveK_NT8cX*J4MTD6>28tUq$amxg0${c9YPSw`L zlH5d!T63SA`mZLxP2Uu{N(nS+=c`uf)$-P>OE?(5nRjYZ=*!0^y{A^jO8dJLy`we` z@CCJT%A0EM{g2hkZvR>B<6i3;>Zq61j`mtUA@6EuCp2yA?z!_(%fD+SJxFay1B_`8 zzYTsj^kZtxrjeu@Jhy7*_miZq`~$CdNtz5-lO!v1tA!B4l>7m49De7pStqgp0000< KMNUMnLSTa4eJz~; literal 0 HcmV?d00001 diff --git a/documentation/html/classVector2D-members.html b/documentation/html/classVector2D-members.html new file mode 100644 index 0000000..dae6379 --- /dev/null +++ b/documentation/html/classVector2D-members.html @@ -0,0 +1,95 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
Vector2D Member List
+
+
+ +

This is the complete list of members for Vector2D, including all inherited members.

+ + + + + + + + + + + + +
get_dir() constVector2D
get_mag() constVector2D
get_x() constVector2D
get_y() constVector2D
normalize()Vector2D
operator*(const double &x)Vector2D
operator+(const Vector2D &other)Vector2D
operator-(const Vector2D &other)Vector2D
point()Vector2D
Vector2D(double dir, double mag)Vector2D
Vector2D(point_t p)Vector2D
+ + + + diff --git a/documentation/html/classVector2D.html b/documentation/html/classVector2D.html new file mode 100644 index 0000000..8ed6b49 --- /dev/null +++ b/documentation/html/classVector2D.html @@ -0,0 +1,378 @@ + + + + + + + +RIT VEXU Core API: Vector2D Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
Vector2D Class Reference
+
+
+ +

#include <vector2d.h>

+ + + + +

+Classes

struct  point_t
 
+ + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

 Vector2D (double dir, double mag)
 
 Vector2D (point_t p)
 
double get_dir () const
 
double get_mag () const
 
double get_x () const
 
double get_y () const
 
Vector2D normalize ()
 
Vector2D::point_t point ()
 
Vector2D operator* (const double &x)
 
Vector2D operator+ (const Vector2D &other)
 
Vector2D operator- (const Vector2D &other)
 
+

Detailed Description

+

Vector2D is an x,y pair Used to represent 2D locations on the field. It can also be treated as a direction and magnitude

+

Constructor & Destructor Documentation

+ +

◆ Vector2D() [1/2]

+ +
+
+ + + + + + + + + + + + + + + + + + +
Vector2D::Vector2D (double dir,
double mag 
)
+
+

Construct a vector object.

+
Parameters
+ + + +
dirDirection, in radians. 'foward' is 0, clockwise positive when viewed from the top.
magMagnitude.
+
+
+ +
+
+ +

◆ Vector2D() [2/2]

+ +
+
+ + + + + + + + +
Vector2D::Vector2D (point_t p)
+
+

Construct a vector object from a cartesian point.

+
Parameters
+ + +
ppoint_t.x , point_t.y
+
+
+ +
+
+

Member Function Documentation

+ +

◆ get_dir()

+ +
+
+ + + + + + + +
double Vector2D::get_dir () const
+
+

Get the direction of the vector, in radians. '0' is forward, clockwise positive when viewed from the top.

+

Use r2d() to convert.

Returns
the direction of the vetctor in radians
+

Get the direction of the vector, in radians. '0' is forward, clockwise positive when viewed from the top.

+

Use r2d() to convert.

+ +
+
+ +

◆ get_mag()

+ +
+
+ + + + + + + +
double Vector2D::get_mag () const
+
+
Returns
the magnitude of the vector
+

Get the magnitude of the vector

+ +
+
+ +

◆ get_x()

+ +
+
+ + + + + + + +
double Vector2D::get_x () const
+
+
Returns
the X component of the vector; positive to the right.
+

Get the X component of the vector; positive to the right.

+ +
+
+ +

◆ get_y()

+ +
+
+ + + + + + + +
double Vector2D::get_y () const
+
+
Returns
the Y component of the vector, positive forward.
+

Get the Y component of the vector, positive forward.

+ +
+
+ +

◆ normalize()

+ +
+
+ + + + + + + +
Vector2D Vector2D::normalize ()
+
+

Changes the magnitude of the vector to 1

Returns
the normalized vector
+

Changes the magnetude of the vector to 1

+ +
+
+ +

◆ operator*()

+ +
+
+ + + + + + + + +
Vector2D Vector2D::operator* (const double & x)
+
+

Scales a Vector2D by a scalar with the * operator

Parameters
+ + +
xthe value to scale the vector by
+
+
+
Returns
the this Vector2D scaled by x
+ +
+
+ +

◆ operator+()

+ +
+
+ + + + + + + + +
Vector2D Vector2D::operator+ (const Vector2Dother)
+
+

Add the components of two vectors together Vector2D + Vector2D = (this.x + other.x, this.y + other.y)

Parameters
+ + +
otherthe vector to add to this
+
+
+
Returns
the sum of the vectors
+ +
+
+ +

◆ operator-()

+ +
+
+ + + + + + + + +
Vector2D Vector2D::operator- (const Vector2Dother)
+
+

Subtract the components of two vectors together Vector2D - Vector2D = (this.x - other.x, this.y - other.y)

Parameters
+ + +
otherthe vector to subtract from this
+
+
+
Returns
the difference of the vectors
+ +
+
+ +

◆ point()

+ +
+
+ + + + + + + +
Vector2D::point_t Vector2D::point ()
+
+

Returns a point from the vector

Returns
the point represented by the vector
+

Convert a direction and magnitude representation to an x, y representation

Returns
the x, y representation of the vector
+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/utils/vector2d.h
  • +
  • src/utils/vector2d.cpp
  • +
+
+ + + + diff --git a/documentation/html/classWaitUntilUpToSpeedCommand-members.html b/documentation/html/classWaitUntilUpToSpeedCommand-members.html new file mode 100644 index 0000000..e4ef8cb --- /dev/null +++ b/documentation/html/classWaitUntilUpToSpeedCommand-members.html @@ -0,0 +1,89 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
WaitUntilUpToSpeedCommand Member List
+
+
+ +

This is the complete list of members for WaitUntilUpToSpeedCommand, including all inherited members.

+ + + + + + +
on_timeout()AutoCommandinlinevirtual
run() overrideWaitUntilUpToSpeedCommandvirtual
timeout_secondsAutoCommand
WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshold_rpm)WaitUntilUpToSpeedCommand
withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
+ + + + diff --git a/documentation/html/classWaitUntilUpToSpeedCommand.html b/documentation/html/classWaitUntilUpToSpeedCommand.html new file mode 100644 index 0000000..157edc8 --- /dev/null +++ b/documentation/html/classWaitUntilUpToSpeedCommand.html @@ -0,0 +1,188 @@ + + + + + + + +RIT VEXU Core API: WaitUntilUpToSpeedCommand Class Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+ +
WaitUntilUpToSpeedCommand Class Reference
+
+
+ +

#include <flywheel_commands.h>

+
+Inheritance diagram for WaitUntilUpToSpeedCommand:
+
+
+ + +AutoCommand + +
+ + + + + + + + + + + + + +

+Public Member Functions

 WaitUntilUpToSpeedCommand (Flywheel &flywheel, int threshold_rpm)
 
bool run () override
 
- Public Member Functions inherited from AutoCommand
virtual bool run ()
 
virtual void on_timeout ()
 
+AutoCommandwithTimeout (double t_seconds)
 
+ + + + +

+Additional Inherited Members

- Public Attributes inherited from AutoCommand
double timeout_seconds = 10.0
 
+

Detailed Description

+

AutoCommand that listens to the Flywheel and waits until it is at its target speed +/- the specified threshold

+

Constructor & Destructor Documentation

+ +

◆ WaitUntilUpToSpeedCommand()

+ +
+
+ + + + + + + + + + + + + + + + + + +
WaitUntilUpToSpeedCommand::WaitUntilUpToSpeedCommand (Flywheelflywheel,
int threshold_rpm 
)
+
+

Creat a WaitUntilUpToSpeedCommand

Parameters
+ + + +
flywheelthe flywheel system we are commanding
threshold_rpmthe threshold over and under the flywheel target RPM that we define to be acceptable
+
+
+ +
+
+

Member Function Documentation

+ +

◆ run()

+ +
+
+ + + + + +
+ + + + + + + +
bool WaitUntilUpToSpeedCommand::run ()
+
+overridevirtual
+
+

Run spin_manual Overrides run from AutoCommand

Returns
true when execution is complete, false otherwise
+ +

Reimplemented from AutoCommand.

+ +
+
+
The documentation for this class was generated from the following files:
    +
  • include/utils/command_structure/flywheel_commands.h
  • +
  • src/utils/command_structure/flywheel_commands.cpp
  • +
+
+ + + + diff --git a/documentation/html/classWaitUntilUpToSpeedCommand.png b/documentation/html/classWaitUntilUpToSpeedCommand.png new file mode 100644 index 0000000000000000000000000000000000000000..0783fa1dbb2baf02213f965b941a9170b40144f3 GIT binary patch literal 660 zcmeAS@N?(olHy`uVBq!ia0vp^TYxx#gBeJ+A6q{KNJ$6ygt-3y{~ySF@#br3|Doj; z2ATyD)6cv(aNqz?Jb2RO6+k)8k|4ie1|S~{%$a6iVPIgA_jGX#sbG9N_jcZE1p(LZ zIo=ol{nxki+mWo^d%4VS;GS!exgv8nT{qdY^u2ubw|(0(8)rLc-gmBD##(gJch`^9RT07(PuuTISlM{# z^Lx+9X3J#W+}iE={PDNWl2@!V}R)>2o0VD=hK6)I34WlfUdG&}l~*8sZV0+$#bIC?NQuq*O1$Pp4);GLGXnsM@ytsI%2pA?p;o@~~t ztryAi^;$kPxz_IL+Q|3`OFFOo?sl7G5)?DvJN&5UuPy&n{(G%BS912()RHL1YMav+ zz6W*nXwQ9h`}LD`sTV}fct^>XHZ1gCmviyi#a+GCyLP6iSx#Pd<$AgN%dMOJ>@&>s z^kY}a7dbyO_}p3YtA11YbMu+6)L+^hJXlu6b7@lVOM}lhy~1CXIPFunEjh(}t?>R7 zyDjz}{g>iw7+Oa|D{PKbJy29tGrC-%=DD{vHH@aC%zuulh_q?J>}k9N=xhh a$Y1h(^5L01H*W*e4}+(xpUXO@geCx{3_%6} literal 0 HcmV?d00001 diff --git a/documentation/html/classes.html b/documentation/html/classes.html new file mode 100644 index 0000000..b8374fd --- /dev/null +++ b/documentation/html/classes.html @@ -0,0 +1,132 @@ + + + + + + + +RIT VEXU Core API: Class Index + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Class Index
+
+ + + + + diff --git a/documentation/html/closed.png b/documentation/html/closed.png new file mode 100644 index 0000000000000000000000000000000000000000..98cc2c909da37a6df914fbf67780eebd99c597f5 GIT binary patch literal 132 zcmeAS@N?(olHy`uVBq!ia0vp^oFL4>1|%O$WD@{V-kvUwAr*{o@8{^CZMh(5KoB^r_<4^zF@3)Cp&&t3hdujKf f*?bjBoY!V+E))@{xMcbjXe@)LtDnm{r-UW|*e5JT literal 0 HcmV?d00001 diff --git a/documentation/html/command__controller_8h_source.html b/documentation/html/command__controller_8h_source.html new file mode 100644 index 0000000..553e9c3 --- /dev/null +++ b/documentation/html/command__controller_8h_source.html @@ -0,0 +1,113 @@ + + + + + + + +RIT VEXU Core API: include/utils/command_structure/command_controller.h Source File + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
command_controller.h
+
+
+
1
+
10#pragma once
+
11
+
12#include <queue>
+
13#include "../core/include/utils/command_structure/auto_command.h"
+
14
+ +
16 public:
+
17
+
23 void add(AutoCommand *cmd, double timeout_seconds = 10.0);
+
24
+
29 void add(std::vector<AutoCommand *> cmds);
+
30
+
37 void add_delay(int ms);
+
38
+
43 void run();
+ +
50
+
51 private:
+
52 std::queue<AutoCommand*> command_queue;
+
53 bool command_timed_out = false;
+
54};
+
Definition: auto_command.h:11
+
Definition: command_controller.h:15
+
void run()
Definition: command_controller.cpp:48
+
bool last_command_timed_out()
Definition: command_controller.cpp:94
+
void add(AutoCommand *cmd, double timeout_seconds=10.0)
Definition: command_controller.cpp:18
+
void add_delay(int ms)
Definition: command_controller.cpp:39
+
+ + + + diff --git a/documentation/html/custom__encoder_8h_source.html b/documentation/html/custom__encoder_8h_source.html new file mode 100644 index 0000000..e3d7ae4 --- /dev/null +++ b/documentation/html/custom__encoder_8h_source.html @@ -0,0 +1,115 @@ + + + + + + + +RIT VEXU Core API: include/subsystems/custom_encoder.h Source File + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
custom_encoder.h
+
+
+
1#pragma once
+
2#include "vex.h"
+
3
+
8class CustomEncoder : public vex::encoder
+
9{
+
10 typedef vex::encoder super;
+
11
+
12 public:
+
18 CustomEncoder(vex::triport::port &port, double ticks_per_rev);
+
19
+
25 void setRotation(double val, vex::rotationUnits units);
+
26
+
32 void setPosition(double val, vex::rotationUnits units);
+
33
+
39 double rotation(vex::rotationUnits units);
+
40
+
46 double position(vex::rotationUnits units);
+
47
+
53 double velocity(vex::velocityUnits units);
+
54
+
55
+
56 private:
+
57 double tick_scalar;
+
58};
+
Definition: custom_encoder.h:9
+
void setPosition(double val, vex::rotationUnits units)
Definition: custom_encoder.cpp:15
+
double rotation(vex::rotationUnits units)
Definition: custom_encoder.cpp:20
+
double velocity(vex::velocityUnits units)
Definition: custom_encoder.cpp:36
+
double position(vex::rotationUnits units)
Definition: custom_encoder.cpp:28
+
void setRotation(double val, vex::rotationUnits units)
Definition: custom_encoder.cpp:10
+
+ + + + diff --git a/documentation/html/delay__command_8h_source.html b/documentation/html/delay__command_8h_source.html new file mode 100644 index 0000000..19814a4 --- /dev/null +++ b/documentation/html/delay__command_8h_source.html @@ -0,0 +1,107 @@ + + + + + + + +RIT VEXU Core API: include/utils/command_structure/delay_command.h Source File + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
delay_command.h
+
+
+
1
+
8#pragma once
+
9
+
10#include "../core/include/utils/command_structure/auto_command.h"
+
11
+ +
13 public:
+
18 DelayCommand(int ms): ms(ms) {}
+
19
+
25 bool run() override {
+
26 vexDelay(ms);
+
27 return true;
+
28 }
+
29
+
30 private:
+
31 // amount of milliseconds to wait
+
32 int ms;
+
33};
+
Definition: auto_command.h:11
+
Definition: delay_command.h:12
+
bool run() override
Definition: delay_command.h:25
+
DelayCommand(int ms)
Definition: delay_command.h:18
+
+ + + + diff --git a/documentation/html/dir_313caf1132e152dd9b58bea13a4052ca.html b/documentation/html/dir_313caf1132e152dd9b58bea13a4052ca.html new file mode 100644 index 0000000..5ca5097 --- /dev/null +++ b/documentation/html/dir_313caf1132e152dd9b58bea13a4052ca.html @@ -0,0 +1,91 @@ + + + + + + + +RIT VEXU Core API: src/utils Directory Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
utils Directory Reference
+
+
+ + + + +

+Directories

directory  command_structure
 
+
+ + + + diff --git a/documentation/html/dir_42a35307dcefecb9f25978d1dedb502f.html b/documentation/html/dir_42a35307dcefecb9f25978d1dedb502f.html new file mode 100644 index 0000000..68dae65 --- /dev/null +++ b/documentation/html/dir_42a35307dcefecb9f25978d1dedb502f.html @@ -0,0 +1,91 @@ + + + + + + + +RIT VEXU Core API: src/subsystems Directory Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
subsystems Directory Reference
+
+
+ + + + +

+Directories

directory  odometry
 
+
+ + + + diff --git a/documentation/html/dir_68267d1309a1af8e8297ef4c3efbcdba.html b/documentation/html/dir_68267d1309a1af8e8297ef4c3efbcdba.html new file mode 100644 index 0000000..3971108 --- /dev/null +++ b/documentation/html/dir_68267d1309a1af8e8297ef4c3efbcdba.html @@ -0,0 +1,93 @@ + + + + + + + +RIT VEXU Core API: src Directory Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
src Directory Reference
+
+
+ + + + + + +

+Directories

directory  subsystems
 
directory  utils
 
+
+ + + + diff --git a/documentation/html/dir_821002d4f10779a80d4fb17bc32f21f1.html b/documentation/html/dir_821002d4f10779a80d4fb17bc32f21f1.html new file mode 100644 index 0000000..04d997a --- /dev/null +++ b/documentation/html/dir_821002d4f10779a80d4fb17bc32f21f1.html @@ -0,0 +1,120 @@ + + + + + + + +RIT VEXU Core API: include/utils Directory Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
utils Directory Reference
+
+
+ + + + +

+Directories

directory  command_structure
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Files

file  auto_chooser.h [code]
 
file  feedback_base.h [code]
 
file  feedforward.h [code]
 
file  generic_auto.h [code]
 
file  graph_drawer.h [code]
 
file  math_util.h [code]
 
file  motion_controller.h [code]
 
file  moving_average.h [code]
 
file  pid.h [code]
 
file  pidff.h [code]
 
file  pure_pursuit.h [code]
 
file  trapezoid_profile.h [code]
 
file  vector2d.h [code]
 
+
+ + + + diff --git a/documentation/html/dir_883d6c53cd62ec60a5d421a7bc1a2629.html b/documentation/html/dir_883d6c53cd62ec60a5d421a7bc1a2629.html new file mode 100644 index 0000000..fe41ce4 --- /dev/null +++ b/documentation/html/dir_883d6c53cd62ec60a5d421a7bc1a2629.html @@ -0,0 +1,95 @@ + + + + + + + +RIT VEXU Core API: include/subsystems/odometry Directory Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
odometry Directory Reference
+
+
+ + + + + + + + +

+Files

file  odometry_3wheel.h [code]
 
file  odometry_base.h [code]
 
file  odometry_tank.h [code]
 
+
+ + + + diff --git a/documentation/html/dir_8e84b5daa2b3f33b7b3fb9ecedbe5637.html b/documentation/html/dir_8e84b5daa2b3f33b7b3fb9ecedbe5637.html new file mode 100644 index 0000000..121f259 --- /dev/null +++ b/documentation/html/dir_8e84b5daa2b3f33b7b3fb9ecedbe5637.html @@ -0,0 +1,106 @@ + + + + + + + +RIT VEXU Core API: include/subsystems Directory Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
subsystems Directory Reference
+
+
+ + + + +

+Directories

directory  odometry
 
+ + + + + + + + + + + + + +

+Files

file  custom_encoder.h [code]
 
file  flywheel.h [code]
 
file  lift.h [code]
 
file  mecanum_drive.h [code]
 
file  screen.h [code]
 
file  tank_drive.h [code]
 
+
+ + + + diff --git a/documentation/html/dir_ca1fd9fa48e5fdc0ddfbf442e09c4dab.html b/documentation/html/dir_ca1fd9fa48e5fdc0ddfbf442e09c4dab.html new file mode 100644 index 0000000..fbc5eaf --- /dev/null +++ b/documentation/html/dir_ca1fd9fa48e5fdc0ddfbf442e09c4dab.html @@ -0,0 +1,85 @@ + + + + + + + +RIT VEXU Core API: src/subsystems/odometry Directory Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
odometry Directory Reference
+
+
+
+ + + + diff --git a/documentation/html/dir_d44c64559bbebec7f509842c48db8b23.html b/documentation/html/dir_d44c64559bbebec7f509842c48db8b23.html new file mode 100644 index 0000000..b8ee575 --- /dev/null +++ b/documentation/html/dir_d44c64559bbebec7f509842c48db8b23.html @@ -0,0 +1,98 @@ + + + + + + + +RIT VEXU Core API: include Directory Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
include Directory Reference
+
+
+ + + + + + +

+Directories

directory  subsystems
 
directory  utils
 
+ + + +

+Files

file  robot_specs.h [code]
 
+
+ + + + diff --git a/documentation/html/dir_d9631e0f4b8929605c336e8f080acaa3.html b/documentation/html/dir_d9631e0f4b8929605c336e8f080acaa3.html new file mode 100644 index 0000000..00b6a4b --- /dev/null +++ b/documentation/html/dir_d9631e0f4b8929605c336e8f080acaa3.html @@ -0,0 +1,85 @@ + + + + + + + +RIT VEXU Core API: src/utils/command_structure Directory Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
command_structure Directory Reference
+
+
+
+ + + + diff --git a/documentation/html/dir_e0729c835bcfebced7012c88d9b3a1d3.html b/documentation/html/dir_e0729c835bcfebced7012c88d9b3a1d3.html new file mode 100644 index 0000000..c393732 --- /dev/null +++ b/documentation/html/dir_e0729c835bcfebced7012c88d9b3a1d3.html @@ -0,0 +1,99 @@ + + + + + + + +RIT VEXU Core API: include/utils/command_structure Directory Reference + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
command_structure Directory Reference
+
+
+ + + + + + + + + + + + +

+Files

file  auto_command.h [code]
 
file  command_controller.h [code]
 
file  delay_command.h [code]
 
file  drive_commands.h [code]
 
file  flywheel_commands.h [code]
 
+
+ + + + diff --git a/documentation/html/doc.png b/documentation/html/doc.png new file mode 100644 index 0000000000000000000000000000000000000000..17edabff95f7b8da13c9516a04efe05493c29501 GIT binary patch literal 746 zcmV7=@pnbNXRFEm&G8P!&WHG=d)>K?YZ1bzou)2{$)) zumDct!>4SyxL;zgaG>wy`^Hv*+}0kUfCrz~BCOViSb$_*&;{TGGn2^x9K*!Sf0=lV zpP=7O;GA0*Jm*tTYj$IoXvimpnV4S1Z5f$p*f$Db2iq2zrVGQUz~yq`ahn7ck(|CE z7Gz;%OP~J6)tEZWDzjhL9h2hdfoU2)Nd%T<5Kt;Y0XLt&<@6pQx!nw*5`@bq#?l*?3z{Hlzoc=Pr>oB5(9i6~_&-}A(4{Q$>c>%rV&E|a(r&;?i5cQB=} zYSDU5nXG)NS4HEs0it2AHe2>shCyr7`6@4*6{r@8fXRbTA?=IFVWAQJL&H5H{)DpM#{W(GL+Idzf^)uRV@oB8u$ z8v{MfJbTiiRg4bza<41NAzrl{=3fl_D+$t+^!xlQ8S}{UtY`e z;;&9UhyZqQRN%2pot{*Ei0*4~hSF_3AH2@fKU!$NSflS>{@tZpDT4`M2WRTTVH+D? z)GFlEGGHe?koB}i|1w45!BF}N_q&^HJ&-tyR{(afC6H7|aml|tBBbv}55C5DNP8p3 z)~jLEO4Z&2hZmP^i-e%(@d!(E|KRafiU8Q5u(wU((j8un3OR*Hvj+t literal 0 HcmV?d00001 diff --git a/documentation/html/docd.png b/documentation/html/docd.png new file mode 100644 index 0000000000000000000000000000000000000000..d7c94fda9bf08ecc02c7190d968452b7a2dbf04b GIT binary patch literal 756 zcmV1wr-rhpn+wxm%q2)IkAYsr{iGq<}_z5JCD4J;FN?6Qh;@TCubdp(_XdD-^ zG_#)IP7_z6hKNdx5^+FGArwLWTWCG!j+oKji?U!hxA#d-ljgkN`+e^@-P+RWG{Bx= z2iQyYTtEf*o~ySWrIVW}HWHi0_hd4~$E6Jx1U`>Owo}EYJ1O>iZvS?!z8}B}QwLMA zC3Keqf1c}K@?C`X>68b(EUzYUYAS&OH^VPteZLPr{S&|nQvp@6W4GH-1U8!u&7l~A zx~RUSNH+>7@q38W6!BzirtjLFCzc|XGx)EF#G%^pWION*k@?vP<2O>|XkCD3ujl%1 z{55JSVkw{~HbX>iEZ2%yJ2eHj5Yh8OTpzs0A2;tZ^x!#5D+y-es{k1&0|Ns9-|+Xt ziGiTsZ8(^nUo#wdTpIDkb-Zp(3|A*FzW}GZ5SQD-r^R`&X@`26E3W|GyrwDIZjtQ& z$g5f8Sv=VgVtDien@J(!^BK+#l;s-LgP--p7C;7;E!ysXcXK6?+9D>_-B(?Wm(U zQbNm-5TyYxIU=rs0+)!ixqzhuxw(AqKc3?KKX32{D~Qibp*r0x&Wux5-9WCMMRi3U zTd6dOCQlj>a;gr;gLwRKulT&(m@^L{&HkSC(qH05HSSf$YEhynGvH zWNez``Z8FJXE+BSg=%ak{OR z+Nylcb{?evLYLuE1_HngYw0g%LC#=$a@?4~Tx>F9295Q>9UJ|_6v-KMw;!YZSgGj@ zR8fRov=hJ#QvsO@xw*{0%zH@OKVEUrsummary { + list-style-type: none; +} + +details > summary::-webkit-details-marker { + display: none; +} + +details>summary::before { + content: "\25ba"; + padding-right:4px; + font-size: 80%; +} + +details[open]>summary::before { + content: "\25bc"; + padding-right:4px; + font-size: 80%; +} + +body { + scrollbar-color: var(--scrollbar-thumb-color) var(--scrollbar-background-color); +} + +::-webkit-scrollbar { + background-color: var(--scrollbar-background-color); + height: 12px; + width: 12px; +} +::-webkit-scrollbar-thumb { + border-radius: 6px; + box-shadow: inset 0 0 12px 12px var(--scrollbar-thumb-color); + border: solid 2px transparent; +} +::-webkit-scrollbar-corner { + background-color: var(--scrollbar-background-color); +} + diff --git a/documentation/html/doxygen.svg b/documentation/html/doxygen.svg new file mode 100644 index 0000000..d42dad5 --- /dev/null +++ b/documentation/html/doxygen.svg @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/documentation/html/drive__commands_8h_source.html b/documentation/html/drive__commands_8h_source.html new file mode 100644 index 0000000..9f3d850 --- /dev/null +++ b/documentation/html/drive__commands_8h_source.html @@ -0,0 +1,229 @@ + + + + + + + +RIT VEXU Core API: include/utils/command_structure/drive_commands.h Source File + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
drive_commands.h
+
+
+
1
+
19#pragma once
+
20
+
21#include "vex.h"
+
22#include "../core/include/utils/command_structure/auto_command.h"
+
23#include "../core/include/subsystems/tank_drive.h"
+
24
+
25using namespace vex;
+
26
+
27
+
28// ==== DRIVING ====
+
29
+ +
36 public:
+
37 DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed=1);
+
38
+
44 bool run() override;
+
48 void on_timeout() override;
+
49
+
50 private:
+
51 // drive system to run the function on
+
52 TankDrive &drive_sys;
+
53
+
54 // feedback controller to use
+
55 Feedback &feedback;
+
56
+
57 // parameters for drive_forward
+
58 double inches;
+
59 directionType dir;
+
60 double max_speed;
+
61};
+
62
+ +
68 public:
+
69 TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed = 1);
+
70
+
76 bool run() override;
+
80 void on_timeout() override;
+
81
+
82
+
83 private:
+
84 // drive system to run the function on
+
85 TankDrive &drive_sys;
+
86
+
87 // feedback controller to use
+
88 Feedback &feedback;
+
89
+
90 // parameters for turn_degrees
+
91 double degrees;
+
92 double max_speed;
+
93};
+
94
+ +
100 public:
+
101 DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed = 1);
+
102 DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, Vector2D::point_t point, directionType dir, double max_speed=1);
+
103
+
109 bool run() override;
+
110
+
111 private:
+
112 // drive system to run the function on
+
113 TankDrive &drive_sys;
+
114
+
118 void on_timeout() override;
+
119
+
120
+
121 // feedback controller to use
+
122 Feedback &feedback;
+
123
+
124 // parameters for drive_to_point
+
125 double x;
+
126 double y;
+
127 directionType dir;
+
128 double max_speed;
+
129
+
130};
+
131
+ +
138 public:
+
139 TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed = 1);
+
140
+
146 bool run() override;
+
150 void on_timeout() override;
+
151
+
152
+
153 private:
+
154 // drive system to run the function on
+
155 TankDrive &drive_sys;
+
156
+
157 // feedback controller to use
+
158 Feedback &feedback;
+
159
+
160 // parameters for turn_to_heading
+
161 double heading_deg;
+
162 double max_speed;
+
163};
+
164
+ +
170 public:
+
171 DriveStopCommand(TankDrive &drive_sys);
+
172
+
178 bool run() override;
+
179
+
180 private:
+
181 // drive system to run the function on
+
182 TankDrive &drive_sys;
+
183};
+
184
+
185
+
186// ==== ODOMETRY ====
+
187
+ +
193 public:
+ +
200
+
206 bool run() override;
+
207
+
208 private:
+
209 // drive system with an odometry config
+
210 OdometryBase &odom;
+
211 position_t newpos;
+
212};
+
Definition: auto_command.h:11
+
Definition: drive_commands.h:35
+
void on_timeout() override
Definition: drive_commands.cpp:47
+
bool run() override
Definition: drive_commands.cpp:40
+
Definition: drive_commands.h:169
+
bool run() override
Definition: drive_commands.cpp:164
+
Definition: drive_commands.h:99
+
bool run() override
Definition: drive_commands.cpp:108
+
Definition: feedback_base.h:11
+
Definition: drive_commands.h:192
+
bool run() override
Definition: drive_commands.cpp:178
+
Definition: odometry_base.h:33
+
static constexpr position_t zero_pos
Definition: odometry_base.h:133
+
Definition: tank_drive.h:23
+
Definition: drive_commands.h:67
+
bool run() override
Definition: drive_commands.cpp:68
+
void on_timeout() override
Definition: drive_commands.cpp:74
+
Definition: drive_commands.h:137
+
void on_timeout() override
Definition: drive_commands.cpp:141
+
bool run() override
Definition: drive_commands.cpp:135
+
Definition: vector2d.h:21
+
Definition: odometry_base.h:14
+
+ + + + diff --git a/documentation/html/dynsections.js b/documentation/html/dynsections.js new file mode 100644 index 0000000..f579fbf --- /dev/null +++ b/documentation/html/dynsections.js @@ -0,0 +1,123 @@ +/* + @licstart The following is the entire license notice for the JavaScript code in this file. + + The MIT License (MIT) + + Copyright (C) 1997-2020 by Dimitri van Heesch + + Permission is hereby granted, free of charge, to any person obtaining a copy of this software + and associated documentation files (the "Software"), to deal in the Software without restriction, + including without limitation the rights to use, copy, modify, merge, publish, distribute, + sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in all copies or + substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING + BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, + DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + @licend The above is the entire license notice for the JavaScript code in this file + */ +function toggleVisibility(linkObj) +{ + var base = $(linkObj).attr('id'); + var summary = $('#'+base+'-summary'); + var content = $('#'+base+'-content'); + var trigger = $('#'+base+'-trigger'); + var src=$(trigger).attr('src'); + if (content.is(':visible')===true) { + content.hide(); + summary.show(); + $(linkObj).addClass('closed').removeClass('opened'); + $(trigger).attr('src',src.substring(0,src.length-8)+'closed.png'); + } else { + content.show(); + summary.hide(); + $(linkObj).removeClass('closed').addClass('opened'); + $(trigger).attr('src',src.substring(0,src.length-10)+'open.png'); + } + return false; +} + +function updateStripes() +{ + $('table.directory tr'). + removeClass('even').filter(':visible:even').addClass('even'); + $('table.directory tr'). + removeClass('odd').filter(':visible:odd').addClass('odd'); +} + +function toggleLevel(level) +{ + $('table.directory tr').each(function() { + var l = this.id.split('_').length-1; + var i = $('#img'+this.id.substring(3)); + var a = $('#arr'+this.id.substring(3)); + if (l + + + + + + +RIT VEXU Core API: include/utils/feedback_base.h Source File + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
feedback_base.h
+
+
+
1#pragma once
+
2
+ +
11{
+
12public:
+
13 enum FeedbackType
+
14 {
+
15 PIDType,
+
16 FeedforwardType,
+
17 OtherType,
+
18 };
+
19
+
26 virtual void init(double start_pt, double set_pt) = 0;
+
27
+
34 virtual double update(double val) = 0;
+
35
+
39 virtual double get() = 0;
+
40
+
47 virtual void set_limits(double lower, double upper) = 0;
+
48
+
52 virtual bool is_on_target() = 0;
+
53
+
54 virtual Feedback::FeedbackType get_type()
+
55 {
+
56 return FeedbackType::OtherType;
+
57 }
+
58};
+
Definition: feedback_base.h:11
+
virtual void init(double start_pt, double set_pt)=0
+
virtual void set_limits(double lower, double upper)=0
+
virtual double get()=0
+
virtual double update(double val)=0
+
virtual bool is_on_target()=0
+
+ + + + diff --git a/documentation/html/feedforward_8h_source.html b/documentation/html/feedforward_8h_source.html new file mode 100644 index 0000000..4b70867 --- /dev/null +++ b/documentation/html/feedforward_8h_source.html @@ -0,0 +1,135 @@ + + + + + + + +RIT VEXU Core API: include/utils/feedforward.h Source File + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
feedforward.h
+
+
+
1#pragma once
+
2
+
3#include <math.h>
+
4#include <vector>
+
5#include "../core/include/utils/math_util.h"
+
6#include "../core/include/utils/moving_average.h"
+
7#include "vex.h"
+
8
+ +
30{
+
31 public:
+
32
+
41 typedef struct
+
42 {
+
43 double kS;
+
44 double kV;
+
45 double kA;
+
46 double kG;
+ +
48
+
49
+
54 FeedForward(ff_config_t &cfg) : cfg(cfg) {}
+
55
+
66 double calculate(double v, double a, double pid_ref=0.0)
+
67 {
+
68 double ks_sign = 0;
+
69 if(v != 0)
+
70 ks_sign = sign(v);
+
71 else if(pid_ref != 0)
+
72 ks_sign = sign(pid_ref);
+
73
+
74 return (cfg.kS * ks_sign) + (cfg.kV * v) + (cfg.kA * a) + cfg.kG;
+
75 }
+
76
+
77 private:
+
78
+
79 ff_config_t &cfg;
+
80
+
81};
+
82
+
83
+
91FeedForward::ff_config_t tune_feedforward(vex::motor_group &motor, double pct, double duration);
+
Definition: feedforward.h:30
+
double calculate(double v, double a, double pid_ref=0.0)
Perform the feedforward calculation.
Definition: feedforward.h:66
+
FeedForward(ff_config_t &cfg)
Definition: feedforward.h:54
+
Definition: feedforward.h:42
+
double kG
Definition: feedforward.h:46
+
double kA
Definition: feedforward.h:45
+
double kS
Definition: feedforward.h:43
+
double kV
Definition: feedforward.h:44
+
+ + + + diff --git a/documentation/html/files.html b/documentation/html/files.html new file mode 100644 index 0000000..f100989 --- /dev/null +++ b/documentation/html/files.html @@ -0,0 +1,118 @@ + + + + + + + +RIT VEXU Core API: File List + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
File List
+
+
+
Here is a list of all documented files with brief descriptions:
+
[detail level 1234]
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
  include
  subsystems
  odometry
 odometry_3wheel.h
 odometry_base.h
 odometry_tank.h
 custom_encoder.h
 flywheel.h
 lift.h
 mecanum_drive.h
 screen.h
 tank_drive.h
  utils
  command_structure
 auto_command.h
 command_controller.h
 delay_command.h
 drive_commands.h
 flywheel_commands.h
 auto_chooser.h
 feedback_base.h
 feedforward.h
 generic_auto.h
 graph_drawer.h
 math_util.h
 motion_controller.h
 moving_average.h
 pid.h
 pidff.h
 pure_pursuit.h
 trapezoid_profile.h
 vector2d.h
 robot_specs.h
+
+
+ + + + diff --git a/documentation/html/flywheel_8h_source.html b/documentation/html/flywheel_8h_source.html new file mode 100644 index 0000000..e2532f6 --- /dev/null +++ b/documentation/html/flywheel_8h_source.html @@ -0,0 +1,197 @@ + + + + + + + +RIT VEXU Core API: include/subsystems/flywheel.h Source File + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
flywheel.h
+
+
+
1#pragma once
+
2/*********************************************************
+
3*
+
4* File: Flywheel.h
+
5* Purpose: Generalized flywheel class for Core.
+
6* Author: Chris Nokes
+
7*
+
8**********************************************************
+
9* EDIT HISTORY
+
10**********************************************************
+
11* 09/23/2022 <CRN> Reorganized, added documentation.
+
12* 09/23/2022 <CRN> Added functions elaborated on in .cpp.
+
13*********************************************************/
+
14#include "../core/include/utils/feedforward.h"
+
15#include "vex.h"
+
16#include "../core/include/robot_specs.h"
+
17#include "../core/include/utils/pid.h"
+
18#include <atomic>
+
19
+
20using namespace vex;
+
21
+ +
30 enum FlywheelControlStyle{
+
31 PID_Feedforward,
+
32 Feedforward,
+
33 Take_Back_Half,
+
34 Bang_Bang,
+
35 };
+
36 public:
+
37
+
38 // CONSTRUCTORS, GETTERS, AND SETTERS
+
46 Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio);
+
47
+
54 Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio);
+
55
+
62 Flywheel(motor_group &motors, double tbh_gain, const double ratio);
+
63
+
69 Flywheel(motor_group &motors, const double ratio);
+
70
+
75 double getDesiredRPM();
+
76
+
81 bool isTaskRunning();
+
82
+
86 motor_group* getMotors();
+
87
+
91 double measureRPM();
+
92
+
96 double getRPM();
+
100 PID* getPID();
+
101
+
105 double getPIDValue();
+
106
+
110 double getFeedforwardValue();
+
111
+
115 double getTBHGain();
+
116
+
121 void setPIDTarget(double value);
+
122
+
127 void updatePID(double value);
+
128
+
129 // SPINNERS AND STOPPERS
+
130
+
137 void spin_raw(double speed, directionType dir=fwd);
+
138
+
145 void spin_manual(double speed, directionType dir=fwd);
+
146
+
152 void spinRPM(int rpm);
+
153
+
157 void stop();
+
158
+
159
+
163 void stopMotors();
+
164
+
168 void stopNonTasks();
+
169
+
170 private:
+
171
+
172 motor_group &motors; // motors that make up the flywheel
+
173 bool taskRunning = false; // is the task (thread but not) currently running?
+
174 PID pid; // PID on the flywheel
+
175 FeedForward ff; // FF constants for the flywheel
+
176 double TBH_gain; // TBH gain parameter for the flywheel
+
177 double ratio; // multiplies the velocity by this value
+
178 std::atomic<double> RPM; // Desired RPM of the flywheel.
+
179 task rpmTask; // task (thread but not) that handles spinning the wheel at a given RPM
+
180 FlywheelControlStyle control_style; // how the flywheel should be controlled
+
181 double smoothedRPM;
+
182 MovingAverage RPM_avger;
+
183 };
+
Definition: feedforward.h:30
+
Definition: flywheel.h:29
+
double getRPM()
Definition: flywheel.cpp:91
+
void spin_manual(double speed, directionType dir=fwd)
Definition: flywheel.cpp:250
+
double getPIDValue()
Definition: flywheel.cpp:104
+
motor_group * getMotors()
Definition: flywheel.cpp:78
+
double getDesiredRPM()
Definition: flywheel.cpp:66
+
void setPIDTarget(double value)
Definition: flywheel.cpp:127
+
void spin_raw(double speed, directionType dir=fwd)
Definition: flywheel.cpp:240
+
void stopNonTasks()
Definition: flywheel.cpp:311
+
void stop()
Definition: flywheel.cpp:295
+
void stopMotors()
Definition: flywheel.cpp:306
+
double getTBHGain()
Definition: flywheel.cpp:119
+
bool isTaskRunning()
Definition: flywheel.cpp:72
+
void spinRPM(int rpm)
Definition: flywheel.cpp:259
+
void updatePID(double value)
Definition: flywheel.cpp:133
+
PID * getPID()
Definition: flywheel.cpp:98
+
double measureRPM()
Definition: flywheel.cpp:84
+
double getFeedforwardValue()
Definition: flywheel.cpp:110
+
Definition: moving_average.h:15
+
Definition: pid.h:24
+
Definition: feedforward.h:42
+
Definition: pid.h:41
+
+ + + + diff --git a/documentation/html/flywheel__commands_8h_source.html b/documentation/html/flywheel__commands_8h_source.html new file mode 100644 index 0000000..67e2001 --- /dev/null +++ b/documentation/html/flywheel__commands_8h_source.html @@ -0,0 +1,161 @@ + + + + + + + +RIT VEXU Core API: include/utils/command_structure/flywheel_commands.h Source File + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
flywheel_commands.h
+
+
+
1
+
7#pragma once
+
8
+
9#include "../core/include/subsystems/flywheel.h"
+
10#include "../core/include/utils/command_structure/auto_command.h"
+
11
+ +
18 public:
+
24 SpinRPMCommand(Flywheel &flywheel, int rpm);
+
25
+
31 bool run() override;
+
32
+
33 private:
+
34 // Flywheel instance to run the function on
+
35 Flywheel &flywheel;
+
36
+
37 // parameters for spinRPM
+
38 int rpm;
+
39};
+
40
+ +
46 public:
+
52 WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshold_rpm);
+
53
+
59 bool run() override;
+
60
+
61 private:
+
62 // Flywheel instance to run the function on
+
63 Flywheel &flywheel;
+
64
+
65 // if the actual speed is equal to the desired speed +/- this value, we are ready to fire
+
66 int threshold_rpm;
+
67};
+
68
+ +
75 public:
+ +
81
+
87 bool run() override;
+
88
+
89 private:
+
90 // Flywheel instance to run the function on
+
91 Flywheel &flywheel;
+
92};
+
93
+ +
100 public:
+ +
106
+
112 bool run() override;
+
113
+
114 private:
+
115 // Flywheel instance to run the function on
+
116 Flywheel &flywheel;
+
117};
+
118
+ + +
126
+
132 bool run() override;
+
133
+
134 private:
+
135 // Flywheel instance to run the function on
+
136 Flywheel &flywheel;
+
137};
+
Definition: auto_command.h:11
+
Definition: flywheel_commands.h:74
+
bool run() override
Definition: flywheel_commands.cpp:35
+
Definition: flywheel_commands.h:99
+
bool run() override
Definition: flywheel_commands.cpp:44
+
Definition: flywheel_commands.h:124
+
Definition: flywheel.h:29
+
Definition: flywheel_commands.h:17
+
bool run() override
Definition: flywheel_commands.cpp:13
+
Definition: flywheel_commands.h:45
+
bool run() override
Definition: flywheel_commands.cpp:21
+
+ + + + diff --git a/documentation/html/folderclosed.png b/documentation/html/folderclosed.png new file mode 100644 index 0000000000000000000000000000000000000000..bb8ab35edce8e97554e360005ee9fc5bffb36e66 GIT binary patch literal 616 zcmV-u0+;=XP)a9#ETzayK)T~Jw&MMH>OIr#&;dC}is*2Mqdf&akCc=O@`qC+4i z5Iu3w#1M@KqXCz8TIZd1wli&kkl2HVcAiZ8PUn5z_kG@-y;?yK06=cA0U%H0PH+kU zl6dp}OR(|r8-RG+YLu`zbI}5TlOU6ToR41{9=uz^?dGTNL;wIMf|V3`d1Wj3y!#6` zBLZ?xpKR~^2x}?~zA(_NUu3IaDB$tKma*XUdOZN~c=dLt_h_k!dbxm_*ibDM zlFX`g{k$X}yIe%$N)cn1LNu=q9_CS)*>A zsX_mM4L@`(cSNQKMFc$RtYbx{79#j-J7hk*>*+ZZhM4Hw?I?rsXCi#mRWJ=-0LGV5a-WR0Qgt<|Nqf)C-@80`5gIz45^_20000IqP)X=#(TiCT&PiIIVc55T}TU}EUh*{q$|`3@{d>{Tc9Bo>e= zfmF3!f>fbI9#GoEHh0f`i5)wkLpva0ztf%HpZneK?w-7AK@b4Itw{y|Zd3k!fH?q2 zlhckHd_V2M_X7+)U&_Xcfvtw60l;--DgZmLSw-Y?S>)zIqMyJ1#FwLU*%bl38ok+! zh78H87n`ZTS;uhzAR$M`zZ`bVhq=+%u9^$5jDplgxd44}9;IRqUH1YHH|@6oFe%z( zo4)_>E$F&^P-f(#)>(TrnbE>Pefs9~@iN=|)Rz|V`sGfHNrJ)0gJb8xx+SBmRf@1l zvuzt=vGfI)<-F9!o&3l?>9~0QbUDT(wFdnQPv%xdD)m*g%!20>Bc9iYmGAp<9YAa( z0QgYgTWqf1qN++Gqp z8@AYPTB3E|6s=WLG?xw0tm|U!o=&zd+H0oRYE;Dbx+Na9s^STqX|Gnq%H8s(nGDGJ j8vwW|`Ts`)fSK|Kx=IK@RG@g200000NkvXXu0mjfauFEA literal 0 HcmV?d00001 diff --git a/documentation/html/functions.html b/documentation/html/functions.html new file mode 100644 index 0000000..a2547a0 --- /dev/null +++ b/documentation/html/functions.html @@ -0,0 +1,93 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- a -

+
+ + + + diff --git a/documentation/html/functions_b.html b/documentation/html/functions_b.html new file mode 100644 index 0000000..2bce74c --- /dev/null +++ b/documentation/html/functions_b.html @@ -0,0 +1,84 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- b -

+
+ + + + diff --git a/documentation/html/functions_c.html b/documentation/html/functions_c.html new file mode 100644 index 0000000..f7095bf --- /dev/null +++ b/documentation/html/functions_c.html @@ -0,0 +1,91 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- c -

+
+ + + + diff --git a/documentation/html/functions_d.html b/documentation/html/functions_d.html new file mode 100644 index 0000000..13767b6 --- /dev/null +++ b/documentation/html/functions_d.html @@ -0,0 +1,99 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- d -

+
+ + + + diff --git a/documentation/html/functions_e.html b/documentation/html/functions_e.html new file mode 100644 index 0000000..bc84988 --- /dev/null +++ b/documentation/html/functions_e.html @@ -0,0 +1,86 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- e -

+
+ + + + diff --git a/documentation/html/functions_enum.html b/documentation/html/functions_enum.html new file mode 100644 index 0000000..4081f5f --- /dev/null +++ b/documentation/html/functions_enum.html @@ -0,0 +1,81 @@ + + + + + + + +RIT VEXU Core API: Class Members - Enumerations + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
    +
  • ERROR_TYPE : PID
  • +
+
+ + + + diff --git a/documentation/html/functions_f.html b/documentation/html/functions_f.html new file mode 100644 index 0000000..9ccef83 --- /dev/null +++ b/documentation/html/functions_f.html @@ -0,0 +1,87 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- f -

+
+ + + + diff --git a/documentation/html/functions_func.html b/documentation/html/functions_func.html new file mode 100644 index 0000000..2bb052d --- /dev/null +++ b/documentation/html/functions_func.html @@ -0,0 +1,282 @@ + + + + + + + +RIT VEXU Core API: Class Members - Functions + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+  + +

- a -

+ + +

- b -

+ + +

- c -

+ + +

- d -

+ + +

- e -

+ + +

- f -

+ + +

- g -

+ + +

- h -

+ + +

- i -

+ + +

- l -

+ + +

- m -

+ + +

- n -

+ + +

- o -

+ + +

- p -

+ + +

- r -

+ + +

- s -

+ + +

- t -

+ + +

- u -

+ + +

- v -

+ + +

- w -

+
+ + + + diff --git a/documentation/html/functions_g.html b/documentation/html/functions_g.html new file mode 100644 index 0000000..4e74ecb --- /dev/null +++ b/documentation/html/functions_g.html @@ -0,0 +1,109 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- g -

+
+ + + + diff --git a/documentation/html/functions_h.html b/documentation/html/functions_h.html new file mode 100644 index 0000000..3a9d1b7 --- /dev/null +++ b/documentation/html/functions_h.html @@ -0,0 +1,86 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- h -

+
+ + + + diff --git a/documentation/html/functions_i.html b/documentation/html/functions_i.html new file mode 100644 index 0000000..4983d51 --- /dev/null +++ b/documentation/html/functions_i.html @@ -0,0 +1,86 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- i -

+
+ + + + diff --git a/documentation/html/functions_k.html b/documentation/html/functions_k.html new file mode 100644 index 0000000..c7ff6db --- /dev/null +++ b/documentation/html/functions_k.html @@ -0,0 +1,86 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- k -

+
+ + + + diff --git a/documentation/html/functions_l.html b/documentation/html/functions_l.html new file mode 100644 index 0000000..eea2f87 --- /dev/null +++ b/documentation/html/functions_l.html @@ -0,0 +1,85 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- l -

+
+ + + + diff --git a/documentation/html/functions_m.html b/documentation/html/functions_m.html new file mode 100644 index 0000000..efed15c --- /dev/null +++ b/documentation/html/functions_m.html @@ -0,0 +1,89 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- m -

+
+ + + + diff --git a/documentation/html/functions_n.html b/documentation/html/functions_n.html new file mode 100644 index 0000000..fa9a804 --- /dev/null +++ b/documentation/html/functions_n.html @@ -0,0 +1,84 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- n -

+
+ + + + diff --git a/documentation/html/functions_o.html b/documentation/html/functions_o.html new file mode 100644 index 0000000..7e48198 --- /dev/null +++ b/documentation/html/functions_o.html @@ -0,0 +1,94 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- o -

+
+ + + + diff --git a/documentation/html/functions_p.html b/documentation/html/functions_p.html new file mode 100644 index 0000000..28d8b87 --- /dev/null +++ b/documentation/html/functions_p.html @@ -0,0 +1,90 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- p -

+
+ + + + diff --git a/documentation/html/functions_r.html b/documentation/html/functions_r.html new file mode 100644 index 0000000..1a4754f --- /dev/null +++ b/documentation/html/functions_r.html @@ -0,0 +1,90 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- r -

+
+ + + + diff --git a/documentation/html/functions_s.html b/documentation/html/functions_s.html new file mode 100644 index 0000000..3e4d6ba --- /dev/null +++ b/documentation/html/functions_s.html @@ -0,0 +1,104 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- s -

+
+ + + + diff --git a/documentation/html/functions_t.html b/documentation/html/functions_t.html new file mode 100644 index 0000000..6a24775 --- /dev/null +++ b/documentation/html/functions_t.html @@ -0,0 +1,92 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- t -

+
+ + + + diff --git a/documentation/html/functions_u.html b/documentation/html/functions_u.html new file mode 100644 index 0000000..c40b5c9 --- /dev/null +++ b/documentation/html/functions_u.html @@ -0,0 +1,84 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- u -

+
+ + + + diff --git a/documentation/html/functions_v.html b/documentation/html/functions_v.html new file mode 100644 index 0000000..c4fefd4 --- /dev/null +++ b/documentation/html/functions_v.html @@ -0,0 +1,85 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- v -

+
+ + + + diff --git a/documentation/html/functions_vars.html b/documentation/html/functions_vars.html new file mode 100644 index 0000000..0e6ecfb --- /dev/null +++ b/documentation/html/functions_vars.html @@ -0,0 +1,212 @@ + + + + + + + +RIT VEXU Core API: Class Members - Variables + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+  + +

- a -

+ + +

- b -

+ + +

- c -

+ + +

- d -

+ + +

- e -

+ + +

- f -

+ + +

- h -

+ + +

- i -

+ + +

- k -

+ + +

- l -

+ + +

- m -

+ + +

- n -

+ + +

- o -

+ + +

- p -

+ + +

- r -

+ + +

- s -

+ + +

- t -

+ + +

- v -

+ + +

- w -

+ + +

- x -

+ + +

- y -

+ + +

- z -

+
+ + + + diff --git a/documentation/html/functions_w.html b/documentation/html/functions_w.html new file mode 100644 index 0000000..b6cc523 --- /dev/null +++ b/documentation/html/functions_w.html @@ -0,0 +1,86 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- w -

+
+ + + + diff --git a/documentation/html/functions_x.html b/documentation/html/functions_x.html new file mode 100644 index 0000000..abf1351 --- /dev/null +++ b/documentation/html/functions_x.html @@ -0,0 +1,83 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- x -

+
+ + + + diff --git a/documentation/html/functions_y.html b/documentation/html/functions_y.html new file mode 100644 index 0000000..f44bc19 --- /dev/null +++ b/documentation/html/functions_y.html @@ -0,0 +1,83 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- y -

+
+ + + + diff --git a/documentation/html/functions_z.html b/documentation/html/functions_z.html new file mode 100644 index 0000000..f76fdf7 --- /dev/null +++ b/documentation/html/functions_z.html @@ -0,0 +1,83 @@ + + + + + + + +RIT VEXU Core API: Class Members + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- z -

+
+ + + + diff --git a/documentation/html/generic__auto_8h_source.html b/documentation/html/generic__auto_8h_source.html new file mode 100644 index 0000000..f361c3e --- /dev/null +++ b/documentation/html/generic__auto_8h_source.html @@ -0,0 +1,116 @@ + + + + + + + +RIT VEXU Core API: include/utils/generic_auto.h Source File + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
generic_auto.h
+
+
+
1#pragma once
+
2
+
3#include <queue>
+
4#include <map>
+
5#include "vex.h"
+
6#include <functional>
+
7
+
8typedef std::function<bool(void)> state_ptr;
+
9
+ +
15{
+
16 public:
+
17
+
31 bool run(bool blocking);
+
32
+
37 void add(state_ptr new_state);
+
38
+
43 void add_async(state_ptr async_state);
+
44
+
49 void add_delay(int ms);
+
50
+
51 private:
+
52
+
53 std::queue<state_ptr> state_list;
+
54
+
55};
+
Definition: generic_auto.h:15
+
void add_async(state_ptr async_state)
Definition: generic_auto.cpp:41
+
void add_delay(int ms)
Definition: generic_auto.cpp:56
+
bool run(bool blocking)
Definition: generic_auto.cpp:16
+
void add(state_ptr new_state)
Definition: generic_auto.cpp:36
+
+ + + + diff --git a/documentation/html/graph__drawer_8h_source.html b/documentation/html/graph__drawer_8h_source.html new file mode 100644 index 0000000..2a6f2eb --- /dev/null +++ b/documentation/html/graph__drawer_8h_source.html @@ -0,0 +1,199 @@ + + + + + + + +RIT VEXU Core API: include/utils/graph_drawer.h Source File + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
graph_drawer.h
+
+
+
1#pragma once
+
2
+
3#include <string>
+
4#include <stdio.h>
+
5#include <vector>
+
6#include "vex.h"
+
7#include "../core/include/utils/vector2d.h"
+
8
+ +
10{
+
11public:
+
23 GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound) : Screen(screen), sample_index(0), xlabel(x_label), ylabel(y_label), col(col), border(draw_border), upper(upper_bound), lower(lower_bound)
+
24 {
+
25 std::vector<Vector2D::point_t> temp(num_samples, Vector2D::point_t{.x = 0.0, .y = 0.0});
+
26 samples = temp;
+
27 }
+
28
+ +
34 {
+
35 samples[sample_index] = sample;
+
36 sample_index++;
+
37 sample_index %= samples.size();
+
38 }
+
46 void draw(int x, int y, int width, int height)
+
47 {
+
48 if (samples.size() < 1)
+
49 {
+
50 return;
+
51 }
+
52
+
53 double current_min = samples[0].y;
+
54 double current_max = samples[0].y;
+
55 double earliest_time = samples[0].x;
+
56 double latest_time = samples[0].x;
+
57 // collect data
+
58 for (int i = 0; i < samples.size(); i++)
+
59 {
+
60 Vector2D::point_t p = samples[i];
+
61 if (p.x < earliest_time)
+
62 {
+
63 earliest_time = p.x;
+
64 }
+
65 else if (p.x > latest_time)
+
66 {
+
67 latest_time = p.x;
+
68 }
+
69
+
70 if (p.y < current_min)
+
71 {
+
72 current_min = p.y;
+
73 }
+
74 else if (p.y > current_max)
+
75 {
+
76 current_max = p.y;
+
77 }
+
78 }
+
79 if (fabs(latest_time - earliest_time) < 0.001)
+
80 {
+
81 Screen.printAt(width / 2, height / 2, "Not enough Data");
+
82 return;
+
83 }
+
84 if (upper != lower)
+
85 {
+
86 current_min = lower;
+
87 current_max = upper;
+
88 }
+
89
+
90 if (border)
+
91 {
+
92 Screen.setPenWidth(1);
+
93 Screen.setPenColor(vex::white);
+
94 Screen.setFillColor(bgcol);
+
95 Screen.drawRectangle(x, y, width, height);
+
96 }
+
97
+
98 double time_range = latest_time - earliest_time;
+
99 double sample_range = current_max - current_min;
+
100 double x_s = (double)x;
+
101 double y_s = (double)y + (double)height;
+
102 Screen.setPenWidth(4);
+
103 Screen.setPenColor(col);
+
104 for (int i = sample_index; i < samples.size() + sample_index - 1; i++)
+
105 {
+
106 Vector2D::point_t p = samples[i % samples.size()];
+
107 double x_pos = x_s + ((p.x - earliest_time) / time_range) * (double)width;
+
108 double y_pos = y_s + ((p.y - current_min) / sample_range) * (double)(-height);
+
109
+
110 Vector2D::point_t p2 = samples[(i + 1) % samples.size()];
+
111 double x_pos2 = x_s + ((p2.x - earliest_time) / time_range) * (double)width;
+
112 double y_pos2 = y_s + ((p2.y - current_min) / sample_range) * (double)(-height);
+
113
+
114 Screen.drawLine((int)x_pos, (int)y_pos, (int)x_pos2, (int)y_pos2);
+
115 }
+
116 }
+
117
+
118private:
+
119 vex::brain::lcd &Screen;
+
120 std::vector<Vector2D::point_t> samples;
+
121 int sample_index = 0;
+
122 std::string xlabel;
+
123 std::string ylabel;
+
124 vex::color col = vex::red;
+
125 vex::color bgcol = vex::transparent;
+
126 bool border;
+
127 double upper;
+
128 double lower;
+
129};
+
Definition: graph_drawer.h:10
+
void add_sample(Vector2D::point_t sample)
Definition: graph_drawer.h:33
+
void draw(int x, int y, int width, int height)
Definition: graph_drawer.h:46
+
GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound)
a helper class to graph values on the brain screen
Definition: graph_drawer.h:23
+
Definition: vector2d.h:21
+
double y
the y position in space
Definition: vector2d.h:23
+
double x
the x position in space
Definition: vector2d.h:22
+
+ + + + diff --git a/documentation/html/hierarchy.html b/documentation/html/hierarchy.html new file mode 100644 index 0000000..656e20b --- /dev/null +++ b/documentation/html/hierarchy.html @@ -0,0 +1,132 @@ + + + + + + + +RIT VEXU Core API: Class Hierarchy + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Class Hierarchy
+
+ + + + + diff --git a/documentation/html/index.html b/documentation/html/index.html new file mode 100644 index 0000000..98612e5 --- /dev/null +++ b/documentation/html/index.html @@ -0,0 +1,81 @@ + + + + + + + +RIT VEXU Core API: Main Page + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
RIT VEXU Core API Documentation
+
+
+
+ + + + diff --git a/documentation/html/jquery.js b/documentation/html/jquery.js new file mode 100644 index 0000000..1dffb65 --- /dev/null +++ b/documentation/html/jquery.js @@ -0,0 +1,34 @@ +/*! jQuery v3.6.0 | (c) OpenJS Foundation and other contributors | jquery.org/license */ +!function(e,t){"use strict";"object"==typeof module&&"object"==typeof module.exports?module.exports=e.document?t(e,!0):function(e){if(!e.document)throw new Error("jQuery requires a window with a document");return t(e)}:t(e)}("undefined"!=typeof window?window:this,function(C,e){"use strict";var t=[],r=Object.getPrototypeOf,s=t.slice,g=t.flat?function(e){return t.flat.call(e)}:function(e){return t.concat.apply([],e)},u=t.push,i=t.indexOf,n={},o=n.toString,v=n.hasOwnProperty,a=v.toString,l=a.call(Object),y={},m=function(e){return"function"==typeof e&&"number"!=typeof e.nodeType&&"function"!=typeof e.item},x=function(e){return null!=e&&e===e.window},E=C.document,c={type:!0,src:!0,nonce:!0,noModule:!0};function b(e,t,n){var r,i,o=(n=n||E).createElement("script");if(o.text=e,t)for(r in c)(i=t[r]||t.getAttribute&&t.getAttribute(r))&&o.setAttribute(r,i);n.head.appendChild(o).parentNode.removeChild(o)}function w(e){return null==e?e+"":"object"==typeof e||"function"==typeof e?n[o.call(e)]||"object":typeof e}var f="3.6.0",S=function(e,t){return new S.fn.init(e,t)};function p(e){var t=!!e&&"length"in e&&e.length,n=w(e);return!m(e)&&!x(e)&&("array"===n||0===t||"number"==typeof t&&0+~]|"+M+")"+M+"*"),U=new RegExp(M+"|>"),X=new RegExp(F),V=new RegExp("^"+I+"$"),G={ID:new RegExp("^#("+I+")"),CLASS:new RegExp("^\\.("+I+")"),TAG:new RegExp("^("+I+"|[*])"),ATTR:new RegExp("^"+W),PSEUDO:new RegExp("^"+F),CHILD:new RegExp("^:(only|first|last|nth|nth-last)-(child|of-type)(?:\\("+M+"*(even|odd|(([+-]|)(\\d*)n|)"+M+"*(?:([+-]|)"+M+"*(\\d+)|))"+M+"*\\)|)","i"),bool:new RegExp("^(?:"+R+")$","i"),needsContext:new RegExp("^"+M+"*[>+~]|:(even|odd|eq|gt|lt|nth|first|last)(?:\\("+M+"*((?:-\\d)?\\d*)"+M+"*\\)|)(?=[^-]|$)","i")},Y=/HTML$/i,Q=/^(?:input|select|textarea|button)$/i,J=/^h\d$/i,K=/^[^{]+\{\s*\[native \w/,Z=/^(?:#([\w-]+)|(\w+)|\.([\w-]+))$/,ee=/[+~]/,te=new RegExp("\\\\[\\da-fA-F]{1,6}"+M+"?|\\\\([^\\r\\n\\f])","g"),ne=function(e,t){var n="0x"+e.slice(1)-65536;return t||(n<0?String.fromCharCode(n+65536):String.fromCharCode(n>>10|55296,1023&n|56320))},re=/([\0-\x1f\x7f]|^-?\d)|^-$|[^\0-\x1f\x7f-\uFFFF\w-]/g,ie=function(e,t){return t?"\0"===e?"\ufffd":e.slice(0,-1)+"\\"+e.charCodeAt(e.length-1).toString(16)+" ":"\\"+e},oe=function(){T()},ae=be(function(e){return!0===e.disabled&&"fieldset"===e.nodeName.toLowerCase()},{dir:"parentNode",next:"legend"});try{H.apply(t=O.call(p.childNodes),p.childNodes),t[p.childNodes.length].nodeType}catch(e){H={apply:t.length?function(e,t){L.apply(e,O.call(t))}:function(e,t){var n=e.length,r=0;while(e[n++]=t[r++]);e.length=n-1}}}function se(t,e,n,r){var i,o,a,s,u,l,c,f=e&&e.ownerDocument,p=e?e.nodeType:9;if(n=n||[],"string"!=typeof t||!t||1!==p&&9!==p&&11!==p)return n;if(!r&&(T(e),e=e||C,E)){if(11!==p&&(u=Z.exec(t)))if(i=u[1]){if(9===p){if(!(a=e.getElementById(i)))return n;if(a.id===i)return n.push(a),n}else if(f&&(a=f.getElementById(i))&&y(e,a)&&a.id===i)return n.push(a),n}else{if(u[2])return H.apply(n,e.getElementsByTagName(t)),n;if((i=u[3])&&d.getElementsByClassName&&e.getElementsByClassName)return H.apply(n,e.getElementsByClassName(i)),n}if(d.qsa&&!N[t+" "]&&(!v||!v.test(t))&&(1!==p||"object"!==e.nodeName.toLowerCase())){if(c=t,f=e,1===p&&(U.test(t)||z.test(t))){(f=ee.test(t)&&ye(e.parentNode)||e)===e&&d.scope||((s=e.getAttribute("id"))?s=s.replace(re,ie):e.setAttribute("id",s=S)),o=(l=h(t)).length;while(o--)l[o]=(s?"#"+s:":scope")+" "+xe(l[o]);c=l.join(",")}try{return H.apply(n,f.querySelectorAll(c)),n}catch(e){N(t,!0)}finally{s===S&&e.removeAttribute("id")}}}return g(t.replace($,"$1"),e,n,r)}function ue(){var r=[];return function e(t,n){return r.push(t+" ")>b.cacheLength&&delete e[r.shift()],e[t+" "]=n}}function le(e){return e[S]=!0,e}function ce(e){var t=C.createElement("fieldset");try{return!!e(t)}catch(e){return!1}finally{t.parentNode&&t.parentNode.removeChild(t),t=null}}function fe(e,t){var n=e.split("|"),r=n.length;while(r--)b.attrHandle[n[r]]=t}function pe(e,t){var n=t&&e,r=n&&1===e.nodeType&&1===t.nodeType&&e.sourceIndex-t.sourceIndex;if(r)return r;if(n)while(n=n.nextSibling)if(n===t)return-1;return e?1:-1}function de(t){return function(e){return"input"===e.nodeName.toLowerCase()&&e.type===t}}function he(n){return function(e){var t=e.nodeName.toLowerCase();return("input"===t||"button"===t)&&e.type===n}}function ge(t){return function(e){return"form"in e?e.parentNode&&!1===e.disabled?"label"in e?"label"in e.parentNode?e.parentNode.disabled===t:e.disabled===t:e.isDisabled===t||e.isDisabled!==!t&&ae(e)===t:e.disabled===t:"label"in e&&e.disabled===t}}function ve(a){return le(function(o){return o=+o,le(function(e,t){var n,r=a([],e.length,o),i=r.length;while(i--)e[n=r[i]]&&(e[n]=!(t[n]=e[n]))})})}function ye(e){return e&&"undefined"!=typeof e.getElementsByTagName&&e}for(e in d=se.support={},i=se.isXML=function(e){var t=e&&e.namespaceURI,n=e&&(e.ownerDocument||e).documentElement;return!Y.test(t||n&&n.nodeName||"HTML")},T=se.setDocument=function(e){var t,n,r=e?e.ownerDocument||e:p;return r!=C&&9===r.nodeType&&r.documentElement&&(a=(C=r).documentElement,E=!i(C),p!=C&&(n=C.defaultView)&&n.top!==n&&(n.addEventListener?n.addEventListener("unload",oe,!1):n.attachEvent&&n.attachEvent("onunload",oe)),d.scope=ce(function(e){return a.appendChild(e).appendChild(C.createElement("div")),"undefined"!=typeof e.querySelectorAll&&!e.querySelectorAll(":scope fieldset div").length}),d.attributes=ce(function(e){return e.className="i",!e.getAttribute("className")}),d.getElementsByTagName=ce(function(e){return e.appendChild(C.createComment("")),!e.getElementsByTagName("*").length}),d.getElementsByClassName=K.test(C.getElementsByClassName),d.getById=ce(function(e){return a.appendChild(e).id=S,!C.getElementsByName||!C.getElementsByName(S).length}),d.getById?(b.filter.ID=function(e){var t=e.replace(te,ne);return function(e){return e.getAttribute("id")===t}},b.find.ID=function(e,t){if("undefined"!=typeof t.getElementById&&E){var n=t.getElementById(e);return n?[n]:[]}}):(b.filter.ID=function(e){var n=e.replace(te,ne);return function(e){var t="undefined"!=typeof e.getAttributeNode&&e.getAttributeNode("id");return t&&t.value===n}},b.find.ID=function(e,t){if("undefined"!=typeof t.getElementById&&E){var n,r,i,o=t.getElementById(e);if(o){if((n=o.getAttributeNode("id"))&&n.value===e)return[o];i=t.getElementsByName(e),r=0;while(o=i[r++])if((n=o.getAttributeNode("id"))&&n.value===e)return[o]}return[]}}),b.find.TAG=d.getElementsByTagName?function(e,t){return"undefined"!=typeof t.getElementsByTagName?t.getElementsByTagName(e):d.qsa?t.querySelectorAll(e):void 0}:function(e,t){var n,r=[],i=0,o=t.getElementsByTagName(e);if("*"===e){while(n=o[i++])1===n.nodeType&&r.push(n);return r}return o},b.find.CLASS=d.getElementsByClassName&&function(e,t){if("undefined"!=typeof t.getElementsByClassName&&E)return t.getElementsByClassName(e)},s=[],v=[],(d.qsa=K.test(C.querySelectorAll))&&(ce(function(e){var t;a.appendChild(e).innerHTML="",e.querySelectorAll("[msallowcapture^='']").length&&v.push("[*^$]="+M+"*(?:''|\"\")"),e.querySelectorAll("[selected]").length||v.push("\\["+M+"*(?:value|"+R+")"),e.querySelectorAll("[id~="+S+"-]").length||v.push("~="),(t=C.createElement("input")).setAttribute("name",""),e.appendChild(t),e.querySelectorAll("[name='']").length||v.push("\\["+M+"*name"+M+"*="+M+"*(?:''|\"\")"),e.querySelectorAll(":checked").length||v.push(":checked"),e.querySelectorAll("a#"+S+"+*").length||v.push(".#.+[+~]"),e.querySelectorAll("\\\f"),v.push("[\\r\\n\\f]")}),ce(function(e){e.innerHTML="";var t=C.createElement("input");t.setAttribute("type","hidden"),e.appendChild(t).setAttribute("name","D"),e.querySelectorAll("[name=d]").length&&v.push("name"+M+"*[*^$|!~]?="),2!==e.querySelectorAll(":enabled").length&&v.push(":enabled",":disabled"),a.appendChild(e).disabled=!0,2!==e.querySelectorAll(":disabled").length&&v.push(":enabled",":disabled"),e.querySelectorAll("*,:x"),v.push(",.*:")})),(d.matchesSelector=K.test(c=a.matches||a.webkitMatchesSelector||a.mozMatchesSelector||a.oMatchesSelector||a.msMatchesSelector))&&ce(function(e){d.disconnectedMatch=c.call(e,"*"),c.call(e,"[s!='']:x"),s.push("!=",F)}),v=v.length&&new RegExp(v.join("|")),s=s.length&&new RegExp(s.join("|")),t=K.test(a.compareDocumentPosition),y=t||K.test(a.contains)?function(e,t){var n=9===e.nodeType?e.documentElement:e,r=t&&t.parentNode;return e===r||!(!r||1!==r.nodeType||!(n.contains?n.contains(r):e.compareDocumentPosition&&16&e.compareDocumentPosition(r)))}:function(e,t){if(t)while(t=t.parentNode)if(t===e)return!0;return!1},j=t?function(e,t){if(e===t)return l=!0,0;var n=!e.compareDocumentPosition-!t.compareDocumentPosition;return n||(1&(n=(e.ownerDocument||e)==(t.ownerDocument||t)?e.compareDocumentPosition(t):1)||!d.sortDetached&&t.compareDocumentPosition(e)===n?e==C||e.ownerDocument==p&&y(p,e)?-1:t==C||t.ownerDocument==p&&y(p,t)?1:u?P(u,e)-P(u,t):0:4&n?-1:1)}:function(e,t){if(e===t)return l=!0,0;var n,r=0,i=e.parentNode,o=t.parentNode,a=[e],s=[t];if(!i||!o)return e==C?-1:t==C?1:i?-1:o?1:u?P(u,e)-P(u,t):0;if(i===o)return pe(e,t);n=e;while(n=n.parentNode)a.unshift(n);n=t;while(n=n.parentNode)s.unshift(n);while(a[r]===s[r])r++;return r?pe(a[r],s[r]):a[r]==p?-1:s[r]==p?1:0}),C},se.matches=function(e,t){return se(e,null,null,t)},se.matchesSelector=function(e,t){if(T(e),d.matchesSelector&&E&&!N[t+" "]&&(!s||!s.test(t))&&(!v||!v.test(t)))try{var n=c.call(e,t);if(n||d.disconnectedMatch||e.document&&11!==e.document.nodeType)return n}catch(e){N(t,!0)}return 0":{dir:"parentNode",first:!0}," ":{dir:"parentNode"},"+":{dir:"previousSibling",first:!0},"~":{dir:"previousSibling"}},preFilter:{ATTR:function(e){return e[1]=e[1].replace(te,ne),e[3]=(e[3]||e[4]||e[5]||"").replace(te,ne),"~="===e[2]&&(e[3]=" "+e[3]+" "),e.slice(0,4)},CHILD:function(e){return e[1]=e[1].toLowerCase(),"nth"===e[1].slice(0,3)?(e[3]||se.error(e[0]),e[4]=+(e[4]?e[5]+(e[6]||1):2*("even"===e[3]||"odd"===e[3])),e[5]=+(e[7]+e[8]||"odd"===e[3])):e[3]&&se.error(e[0]),e},PSEUDO:function(e){var t,n=!e[6]&&e[2];return G.CHILD.test(e[0])?null:(e[3]?e[2]=e[4]||e[5]||"":n&&X.test(n)&&(t=h(n,!0))&&(t=n.indexOf(")",n.length-t)-n.length)&&(e[0]=e[0].slice(0,t),e[2]=n.slice(0,t)),e.slice(0,3))}},filter:{TAG:function(e){var t=e.replace(te,ne).toLowerCase();return"*"===e?function(){return!0}:function(e){return e.nodeName&&e.nodeName.toLowerCase()===t}},CLASS:function(e){var t=m[e+" "];return t||(t=new RegExp("(^|"+M+")"+e+"("+M+"|$)"))&&m(e,function(e){return t.test("string"==typeof e.className&&e.className||"undefined"!=typeof e.getAttribute&&e.getAttribute("class")||"")})},ATTR:function(n,r,i){return function(e){var t=se.attr(e,n);return null==t?"!="===r:!r||(t+="","="===r?t===i:"!="===r?t!==i:"^="===r?i&&0===t.indexOf(i):"*="===r?i&&-1:\x20\t\r\n\f]*)[\x20\t\r\n\f]*\/?>(?:<\/\1>|)$/i;function j(e,n,r){return m(n)?S.grep(e,function(e,t){return!!n.call(e,t,e)!==r}):n.nodeType?S.grep(e,function(e){return e===n!==r}):"string"!=typeof n?S.grep(e,function(e){return-1)[^>]*|#([\w-]+))$/;(S.fn.init=function(e,t,n){var r,i;if(!e)return this;if(n=n||D,"string"==typeof e){if(!(r="<"===e[0]&&">"===e[e.length-1]&&3<=e.length?[null,e,null]:q.exec(e))||!r[1]&&t)return!t||t.jquery?(t||n).find(e):this.constructor(t).find(e);if(r[1]){if(t=t instanceof S?t[0]:t,S.merge(this,S.parseHTML(r[1],t&&t.nodeType?t.ownerDocument||t:E,!0)),N.test(r[1])&&S.isPlainObject(t))for(r in t)m(this[r])?this[r](t[r]):this.attr(r,t[r]);return this}return(i=E.getElementById(r[2]))&&(this[0]=i,this.length=1),this}return e.nodeType?(this[0]=e,this.length=1,this):m(e)?void 0!==n.ready?n.ready(e):e(S):S.makeArray(e,this)}).prototype=S.fn,D=S(E);var L=/^(?:parents|prev(?:Until|All))/,H={children:!0,contents:!0,next:!0,prev:!0};function O(e,t){while((e=e[t])&&1!==e.nodeType);return e}S.fn.extend({has:function(e){var t=S(e,this),n=t.length;return this.filter(function(){for(var e=0;e\x20\t\r\n\f]*)/i,he=/^$|^module$|\/(?:java|ecma)script/i;ce=E.createDocumentFragment().appendChild(E.createElement("div")),(fe=E.createElement("input")).setAttribute("type","radio"),fe.setAttribute("checked","checked"),fe.setAttribute("name","t"),ce.appendChild(fe),y.checkClone=ce.cloneNode(!0).cloneNode(!0).lastChild.checked,ce.innerHTML="",y.noCloneChecked=!!ce.cloneNode(!0).lastChild.defaultValue,ce.innerHTML="",y.option=!!ce.lastChild;var ge={thead:[1,"","
"],col:[2,"","
"],tr:[2,"","
"],td:[3,"","
"],_default:[0,"",""]};function ve(e,t){var n;return n="undefined"!=typeof e.getElementsByTagName?e.getElementsByTagName(t||"*"):"undefined"!=typeof e.querySelectorAll?e.querySelectorAll(t||"*"):[],void 0===t||t&&A(e,t)?S.merge([e],n):n}function ye(e,t){for(var n=0,r=e.length;n",""]);var me=/<|&#?\w+;/;function xe(e,t,n,r,i){for(var o,a,s,u,l,c,f=t.createDocumentFragment(),p=[],d=0,h=e.length;d\s*$/g;function je(e,t){return A(e,"table")&&A(11!==t.nodeType?t:t.firstChild,"tr")&&S(e).children("tbody")[0]||e}function De(e){return e.type=(null!==e.getAttribute("type"))+"/"+e.type,e}function qe(e){return"true/"===(e.type||"").slice(0,5)?e.type=e.type.slice(5):e.removeAttribute("type"),e}function Le(e,t){var n,r,i,o,a,s;if(1===t.nodeType){if(Y.hasData(e)&&(s=Y.get(e).events))for(i in Y.remove(t,"handle events"),s)for(n=0,r=s[i].length;n").attr(n.scriptAttrs||{}).prop({charset:n.scriptCharset,src:n.url}).on("load error",i=function(e){r.remove(),i=null,e&&t("error"===e.type?404:200,e.type)}),E.head.appendChild(r[0])},abort:function(){i&&i()}}});var _t,zt=[],Ut=/(=)\?(?=&|$)|\?\?/;S.ajaxSetup({jsonp:"callback",jsonpCallback:function(){var e=zt.pop()||S.expando+"_"+wt.guid++;return this[e]=!0,e}}),S.ajaxPrefilter("json jsonp",function(e,t,n){var r,i,o,a=!1!==e.jsonp&&(Ut.test(e.url)?"url":"string"==typeof e.data&&0===(e.contentType||"").indexOf("application/x-www-form-urlencoded")&&Ut.test(e.data)&&"data");if(a||"jsonp"===e.dataTypes[0])return r=e.jsonpCallback=m(e.jsonpCallback)?e.jsonpCallback():e.jsonpCallback,a?e[a]=e[a].replace(Ut,"$1"+r):!1!==e.jsonp&&(e.url+=(Tt.test(e.url)?"&":"?")+e.jsonp+"="+r),e.converters["script json"]=function(){return o||S.error(r+" was not called"),o[0]},e.dataTypes[0]="json",i=C[r],C[r]=function(){o=arguments},n.always(function(){void 0===i?S(C).removeProp(r):C[r]=i,e[r]&&(e.jsonpCallback=t.jsonpCallback,zt.push(r)),o&&m(i)&&i(o[0]),o=i=void 0}),"script"}),y.createHTMLDocument=((_t=E.implementation.createHTMLDocument("").body).innerHTML="
",2===_t.childNodes.length),S.parseHTML=function(e,t,n){return"string"!=typeof e?[]:("boolean"==typeof t&&(n=t,t=!1),t||(y.createHTMLDocument?((r=(t=E.implementation.createHTMLDocument("")).createElement("base")).href=E.location.href,t.head.appendChild(r)):t=E),o=!n&&[],(i=N.exec(e))?[t.createElement(i[1])]:(i=xe([e],t,o),o&&o.length&&S(o).remove(),S.merge([],i.childNodes)));var r,i,o},S.fn.load=function(e,t,n){var r,i,o,a=this,s=e.indexOf(" ");return-1").append(S.parseHTML(e)).find(r):e)}).always(n&&function(e,t){a.each(function(){n.apply(this,o||[e.responseText,t,e])})}),this},S.expr.pseudos.animated=function(t){return S.grep(S.timers,function(e){return t===e.elem}).length},S.offset={setOffset:function(e,t,n){var r,i,o,a,s,u,l=S.css(e,"position"),c=S(e),f={};"static"===l&&(e.style.position="relative"),s=c.offset(),o=S.css(e,"top"),u=S.css(e,"left"),("absolute"===l||"fixed"===l)&&-1<(o+u).indexOf("auto")?(a=(r=c.position()).top,i=r.left):(a=parseFloat(o)||0,i=parseFloat(u)||0),m(t)&&(t=t.call(e,n,S.extend({},s))),null!=t.top&&(f.top=t.top-s.top+a),null!=t.left&&(f.left=t.left-s.left+i),"using"in t?t.using.call(e,f):c.css(f)}},S.fn.extend({offset:function(t){if(arguments.length)return void 0===t?this:this.each(function(e){S.offset.setOffset(this,t,e)});var e,n,r=this[0];return r?r.getClientRects().length?(e=r.getBoundingClientRect(),n=r.ownerDocument.defaultView,{top:e.top+n.pageYOffset,left:e.left+n.pageXOffset}):{top:0,left:0}:void 0},position:function(){if(this[0]){var e,t,n,r=this[0],i={top:0,left:0};if("fixed"===S.css(r,"position"))t=r.getBoundingClientRect();else{t=this.offset(),n=r.ownerDocument,e=r.offsetParent||n.documentElement;while(e&&(e===n.body||e===n.documentElement)&&"static"===S.css(e,"position"))e=e.parentNode;e&&e!==r&&1===e.nodeType&&((i=S(e).offset()).top+=S.css(e,"borderTopWidth",!0),i.left+=S.css(e,"borderLeftWidth",!0))}return{top:t.top-i.top-S.css(r,"marginTop",!0),left:t.left-i.left-S.css(r,"marginLeft",!0)}}},offsetParent:function(){return this.map(function(){var e=this.offsetParent;while(e&&"static"===S.css(e,"position"))e=e.offsetParent;return e||re})}}),S.each({scrollLeft:"pageXOffset",scrollTop:"pageYOffset"},function(t,i){var o="pageYOffset"===i;S.fn[t]=function(e){return $(this,function(e,t,n){var r;if(x(e)?r=e:9===e.nodeType&&(r=e.defaultView),void 0===n)return r?r[i]:e[t];r?r.scrollTo(o?r.pageXOffset:n,o?n:r.pageYOffset):e[t]=n},t,e,arguments.length)}}),S.each(["top","left"],function(e,n){S.cssHooks[n]=Fe(y.pixelPosition,function(e,t){if(t)return t=We(e,n),Pe.test(t)?S(e).position()[n]+"px":t})}),S.each({Height:"height",Width:"width"},function(a,s){S.each({padding:"inner"+a,content:s,"":"outer"+a},function(r,o){S.fn[o]=function(e,t){var n=arguments.length&&(r||"boolean"!=typeof e),i=r||(!0===e||!0===t?"margin":"border");return $(this,function(e,t,n){var r;return x(e)?0===o.indexOf("outer")?e["inner"+a]:e.document.documentElement["client"+a]:9===e.nodeType?(r=e.documentElement,Math.max(e.body["scroll"+a],r["scroll"+a],e.body["offset"+a],r["offset"+a],r["client"+a])):void 0===n?S.css(e,t,i):S.style(e,t,n,i)},s,n?e:void 0,n)}})}),S.each(["ajaxStart","ajaxStop","ajaxComplete","ajaxError","ajaxSuccess","ajaxSend"],function(e,t){S.fn[t]=function(e){return this.on(t,e)}}),S.fn.extend({bind:function(e,t,n){return this.on(e,null,t,n)},unbind:function(e,t){return this.off(e,null,t)},delegate:function(e,t,n,r){return this.on(t,e,n,r)},undelegate:function(e,t,n){return 1===arguments.length?this.off(e,"**"):this.off(t,e||"**",n)},hover:function(e,t){return this.mouseenter(e).mouseleave(t||e)}}),S.each("blur focus focusin focusout resize scroll click dblclick mousedown mouseup mousemove mouseover mouseout mouseenter mouseleave change select submit keydown keypress keyup contextmenu".split(" "),function(e,n){S.fn[n]=function(e,t){return 0",options:{classes:{},disabled:!1,create:null},_createWidget:function(t,e){e=y(e||this.defaultElement||this)[0],this.element=y(e),this.uuid=i++,this.eventNamespace="."+this.widgetName+this.uuid,this.bindings=y(),this.hoverable=y(),this.focusable=y(),this.classesElementLookup={},e!==this&&(y.data(e,this.widgetFullName,this),this._on(!0,this.element,{remove:function(t){t.target===e&&this.destroy()}}),this.document=y(e.style?e.ownerDocument:e.document||e),this.window=y(this.document[0].defaultView||this.document[0].parentWindow)),this.options=y.widget.extend({},this.options,this._getCreateOptions(),t),this._create(),this.options.disabled&&this._setOptionDisabled(this.options.disabled),this._trigger("create",null,this._getCreateEventData()),this._init()},_getCreateOptions:function(){return{}},_getCreateEventData:y.noop,_create:y.noop,_init:y.noop,destroy:function(){var i=this;this._destroy(),y.each(this.classesElementLookup,function(t,e){i._removeClass(e,t)}),this.element.off(this.eventNamespace).removeData(this.widgetFullName),this.widget().off(this.eventNamespace).removeAttr("aria-disabled"),this.bindings.off(this.eventNamespace)},_destroy:y.noop,widget:function(){return this.element},option:function(t,e){var i,s,n,o=t;if(0===arguments.length)return y.widget.extend({},this.options);if("string"==typeof t)if(o={},t=(i=t.split(".")).shift(),i.length){for(s=o[t]=y.widget.extend({},this.options[t]),n=0;n
"),i=e.children()[0];return y("body").append(e),t=i.offsetWidth,e.css("overflow","scroll"),t===(i=i.offsetWidth)&&(i=e[0].clientWidth),e.remove(),s=t-i},getScrollInfo:function(t){var e=t.isWindow||t.isDocument?"":t.element.css("overflow-x"),i=t.isWindow||t.isDocument?"":t.element.css("overflow-y"),e="scroll"===e||"auto"===e&&t.widthx(D(s),D(n))?o.important="horizontal":o.important="vertical",p.using.call(this,t,o)}),h.offset(y.extend(l,{using:t}))})},y.ui.position={fit:{left:function(t,e){var i=e.within,s=i.isWindow?i.scrollLeft:i.offset.left,n=i.width,o=t.left-e.collisionPosition.marginLeft,h=s-o,a=o+e.collisionWidth-n-s;e.collisionWidth>n?0n?0=this.options.distance},_mouseDelayMet:function(){return this.mouseDelayMet},_mouseStart:function(){},_mouseDrag:function(){},_mouseStop:function(){},_mouseCapture:function(){return!0}}),y.ui.plugin={add:function(t,e,i){var s,n=y.ui[t].prototype;for(s in i)n.plugins[s]=n.plugins[s]||[],n.plugins[s].push([e,i[s]])},call:function(t,e,i,s){var n,o=t.plugins[e];if(o&&(s||t.element[0].parentNode&&11!==t.element[0].parentNode.nodeType))for(n=0;n").css({overflow:"hidden",position:this.element.css("position"),width:this.element.outerWidth(),height:this.element.outerHeight(),top:this.element.css("top"),left:this.element.css("left")})),this.element=this.element.parent().data("ui-resizable",this.element.resizable("instance")),this.elementIsWrapper=!0,t={marginTop:this.originalElement.css("marginTop"),marginRight:this.originalElement.css("marginRight"),marginBottom:this.originalElement.css("marginBottom"),marginLeft:this.originalElement.css("marginLeft")},this.element.css(t),this.originalElement.css("margin",0),this.originalResizeStyle=this.originalElement.css("resize"),this.originalElement.css("resize","none"),this._proportionallyResizeElements.push(this.originalElement.css({position:"static",zoom:1,display:"block"})),this.originalElement.css(t),this._proportionallyResize()),this._setupHandles(),e.autoHide&&y(this.element).on("mouseenter",function(){e.disabled||(i._removeClass("ui-resizable-autohide"),i._handles.show())}).on("mouseleave",function(){e.disabled||i.resizing||(i._addClass("ui-resizable-autohide"),i._handles.hide())}),this._mouseInit()},_destroy:function(){this._mouseDestroy(),this._addedHandles.remove();function t(t){y(t).removeData("resizable").removeData("ui-resizable").off(".resizable")}var e;return this.elementIsWrapper&&(t(this.element),e=this.element,this.originalElement.css({position:e.css("position"),width:e.outerWidth(),height:e.outerHeight(),top:e.css("top"),left:e.css("left")}).insertAfter(e),e.remove()),this.originalElement.css("resize",this.originalResizeStyle),t(this.originalElement),this},_setOption:function(t,e){switch(this._super(t,e),t){case"handles":this._removeHandles(),this._setupHandles();break;case"aspectRatio":this._aspectRatio=!!e}},_setupHandles:function(){var t,e,i,s,n,o=this.options,h=this;if(this.handles=o.handles||(y(".ui-resizable-handle",this.element).length?{n:".ui-resizable-n",e:".ui-resizable-e",s:".ui-resizable-s",w:".ui-resizable-w",se:".ui-resizable-se",sw:".ui-resizable-sw",ne:".ui-resizable-ne",nw:".ui-resizable-nw"}:"e,s,se"),this._handles=y(),this._addedHandles=y(),this.handles.constructor===String)for("all"===this.handles&&(this.handles="n,e,s,w,se,sw,ne,nw"),i=this.handles.split(","),this.handles={},e=0;e"),this._addClass(n,"ui-resizable-handle "+s),n.css({zIndex:o.zIndex}),this.handles[t]=".ui-resizable-"+t,this.element.children(this.handles[t]).length||(this.element.append(n),this._addedHandles=this._addedHandles.add(n));this._renderAxis=function(t){var e,i,s;for(e in t=t||this.element,this.handles)this.handles[e].constructor===String?this.handles[e]=this.element.children(this.handles[e]).first().show():(this.handles[e].jquery||this.handles[e].nodeType)&&(this.handles[e]=y(this.handles[e]),this._on(this.handles[e],{mousedown:h._mouseDown})),this.elementIsWrapper&&this.originalElement[0].nodeName.match(/^(textarea|input|select|button)$/i)&&(i=y(this.handles[e],this.element),s=/sw|ne|nw|se|n|s/.test(e)?i.outerHeight():i.outerWidth(),i=["padding",/ne|nw|n/.test(e)?"Top":/se|sw|s/.test(e)?"Bottom":/^e$/.test(e)?"Right":"Left"].join(""),t.css(i,s),this._proportionallyResize()),this._handles=this._handles.add(this.handles[e])},this._renderAxis(this.element),this._handles=this._handles.add(this.element.find(".ui-resizable-handle")),this._handles.disableSelection(),this._handles.on("mouseover",function(){h.resizing||(this.className&&(n=this.className.match(/ui-resizable-(se|sw|ne|nw|n|e|s|w)/i)),h.axis=n&&n[1]?n[1]:"se")}),o.autoHide&&(this._handles.hide(),this._addClass("ui-resizable-autohide"))},_removeHandles:function(){this._addedHandles.remove()},_mouseCapture:function(t){var e,i,s=!1;for(e in this.handles)(i=y(this.handles[e])[0])!==t.target&&!y.contains(i,t.target)||(s=!0);return!this.options.disabled&&s},_mouseStart:function(t){var e,i,s=this.options,n=this.element;return this.resizing=!0,this._renderProxy(),e=this._num(this.helper.css("left")),i=this._num(this.helper.css("top")),s.containment&&(e+=y(s.containment).scrollLeft()||0,i+=y(s.containment).scrollTop()||0),this.offset=this.helper.offset(),this.position={left:e,top:i},this.size=this._helper?{width:this.helper.width(),height:this.helper.height()}:{width:n.width(),height:n.height()},this.originalSize=this._helper?{width:n.outerWidth(),height:n.outerHeight()}:{width:n.width(),height:n.height()},this.sizeDiff={width:n.outerWidth()-n.width(),height:n.outerHeight()-n.height()},this.originalPosition={left:e,top:i},this.originalMousePosition={left:t.pageX,top:t.pageY},this.aspectRatio="number"==typeof s.aspectRatio?s.aspectRatio:this.originalSize.width/this.originalSize.height||1,s=y(".ui-resizable-"+this.axis).css("cursor"),y("body").css("cursor","auto"===s?this.axis+"-resize":s),this._addClass("ui-resizable-resizing"),this._propagate("start",t),!0},_mouseDrag:function(t){var e=this.originalMousePosition,i=this.axis,s=t.pageX-e.left||0,e=t.pageY-e.top||0,i=this._change[i];return this._updatePrevProperties(),i&&(e=i.apply(this,[t,s,e]),this._updateVirtualBoundaries(t.shiftKey),(this._aspectRatio||t.shiftKey)&&(e=this._updateRatio(e,t)),e=this._respectSize(e,t),this._updateCache(e),this._propagate("resize",t),e=this._applyChanges(),!this._helper&&this._proportionallyResizeElements.length&&this._proportionallyResize(),y.isEmptyObject(e)||(this._updatePrevProperties(),this._trigger("resize",t,this.ui()),this._applyChanges())),!1},_mouseStop:function(t){this.resizing=!1;var e,i,s,n=this.options,o=this;return this._helper&&(s=(e=(i=this._proportionallyResizeElements).length&&/textarea/i.test(i[0].nodeName))&&this._hasScroll(i[0],"left")?0:o.sizeDiff.height,i=e?0:o.sizeDiff.width,e={width:o.helper.width()-i,height:o.helper.height()-s},i=parseFloat(o.element.css("left"))+(o.position.left-o.originalPosition.left)||null,s=parseFloat(o.element.css("top"))+(o.position.top-o.originalPosition.top)||null,n.animate||this.element.css(y.extend(e,{top:s,left:i})),o.helper.height(o.size.height),o.helper.width(o.size.width),this._helper&&!n.animate&&this._proportionallyResize()),y("body").css("cursor","auto"),this._removeClass("ui-resizable-resizing"),this._propagate("stop",t),this._helper&&this.helper.remove(),!1},_updatePrevProperties:function(){this.prevPosition={top:this.position.top,left:this.position.left},this.prevSize={width:this.size.width,height:this.size.height}},_applyChanges:function(){var t={};return this.position.top!==this.prevPosition.top&&(t.top=this.position.top+"px"),this.position.left!==this.prevPosition.left&&(t.left=this.position.left+"px"),this.size.width!==this.prevSize.width&&(t.width=this.size.width+"px"),this.size.height!==this.prevSize.height&&(t.height=this.size.height+"px"),this.helper.css(t),t},_updateVirtualBoundaries:function(t){var e,i,s=this.options,n={minWidth:this._isNumber(s.minWidth)?s.minWidth:0,maxWidth:this._isNumber(s.maxWidth)?s.maxWidth:1/0,minHeight:this._isNumber(s.minHeight)?s.minHeight:0,maxHeight:this._isNumber(s.maxHeight)?s.maxHeight:1/0};(this._aspectRatio||t)&&(e=n.minHeight*this.aspectRatio,i=n.minWidth/this.aspectRatio,s=n.maxHeight*this.aspectRatio,t=n.maxWidth/this.aspectRatio,e>n.minWidth&&(n.minWidth=e),i>n.minHeight&&(n.minHeight=i),st.width,h=this._isNumber(t.height)&&e.minHeight&&e.minHeight>t.height,a=this.originalPosition.left+this.originalSize.width,r=this.originalPosition.top+this.originalSize.height,l=/sw|nw|w/.test(i),i=/nw|ne|n/.test(i);return o&&(t.width=e.minWidth),h&&(t.height=e.minHeight),s&&(t.width=e.maxWidth),n&&(t.height=e.maxHeight),o&&l&&(t.left=a-e.minWidth),s&&l&&(t.left=a-e.maxWidth),h&&i&&(t.top=r-e.minHeight),n&&i&&(t.top=r-e.maxHeight),t.width||t.height||t.left||!t.top?t.width||t.height||t.top||!t.left||(t.left=null):t.top=null,t},_getPaddingPlusBorderDimensions:function(t){for(var e=0,i=[],s=[t.css("borderTopWidth"),t.css("borderRightWidth"),t.css("borderBottomWidth"),t.css("borderLeftWidth")],n=[t.css("paddingTop"),t.css("paddingRight"),t.css("paddingBottom"),t.css("paddingLeft")];e<4;e++)i[e]=parseFloat(s[e])||0,i[e]+=parseFloat(n[e])||0;return{height:i[0]+i[2],width:i[1]+i[3]}},_proportionallyResize:function(){if(this._proportionallyResizeElements.length)for(var t,e=0,i=this.helper||this.element;e").css({overflow:"hidden"}),this._addClass(this.helper,this._helper),this.helper.css({width:this.element.outerWidth(),height:this.element.outerHeight(),position:"absolute",left:this.elementOffset.left+"px",top:this.elementOffset.top+"px",zIndex:++e.zIndex}),this.helper.appendTo("body").disableSelection()):this.helper=this.element},_change:{e:function(t,e){return{width:this.originalSize.width+e}},w:function(t,e){var i=this.originalSize;return{left:this.originalPosition.left+e,width:i.width-e}},n:function(t,e,i){var s=this.originalSize;return{top:this.originalPosition.top+i,height:s.height-i}},s:function(t,e,i){return{height:this.originalSize.height+i}},se:function(t,e,i){return y.extend(this._change.s.apply(this,arguments),this._change.e.apply(this,[t,e,i]))},sw:function(t,e,i){return y.extend(this._change.s.apply(this,arguments),this._change.w.apply(this,[t,e,i]))},ne:function(t,e,i){return y.extend(this._change.n.apply(this,arguments),this._change.e.apply(this,[t,e,i]))},nw:function(t,e,i){return y.extend(this._change.n.apply(this,arguments),this._change.w.apply(this,[t,e,i]))}},_propagate:function(t,e){y.ui.plugin.call(this,t,[e,this.ui()]),"resize"!==t&&this._trigger(t,e,this.ui())},plugins:{},ui:function(){return{originalElement:this.originalElement,element:this.element,helper:this.helper,position:this.position,size:this.size,originalSize:this.originalSize,originalPosition:this.originalPosition}}}),y.ui.plugin.add("resizable","animate",{stop:function(e){var i=y(this).resizable("instance"),t=i.options,s=i._proportionallyResizeElements,n=s.length&&/textarea/i.test(s[0].nodeName),o=n&&i._hasScroll(s[0],"left")?0:i.sizeDiff.height,h=n?0:i.sizeDiff.width,n={width:i.size.width-h,height:i.size.height-o},h=parseFloat(i.element.css("left"))+(i.position.left-i.originalPosition.left)||null,o=parseFloat(i.element.css("top"))+(i.position.top-i.originalPosition.top)||null;i.element.animate(y.extend(n,o&&h?{top:o,left:h}:{}),{duration:t.animateDuration,easing:t.animateEasing,step:function(){var t={width:parseFloat(i.element.css("width")),height:parseFloat(i.element.css("height")),top:parseFloat(i.element.css("top")),left:parseFloat(i.element.css("left"))};s&&s.length&&y(s[0]).css({width:t.width,height:t.height}),i._updateCache(t),i._propagate("resize",e)}})}}),y.ui.plugin.add("resizable","containment",{start:function(){var i,s,n=y(this).resizable("instance"),t=n.options,e=n.element,o=t.containment,h=o instanceof y?o.get(0):/parent/.test(o)?e.parent().get(0):o;h&&(n.containerElement=y(h),/document/.test(o)||o===document?(n.containerOffset={left:0,top:0},n.containerPosition={left:0,top:0},n.parentData={element:y(document),left:0,top:0,width:y(document).width(),height:y(document).height()||document.body.parentNode.scrollHeight}):(i=y(h),s=[],y(["Top","Right","Left","Bottom"]).each(function(t,e){s[t]=n._num(i.css("padding"+e))}),n.containerOffset=i.offset(),n.containerPosition=i.position(),n.containerSize={height:i.innerHeight()-s[3],width:i.innerWidth()-s[1]},t=n.containerOffset,e=n.containerSize.height,o=n.containerSize.width,o=n._hasScroll(h,"left")?h.scrollWidth:o,e=n._hasScroll(h)?h.scrollHeight:e,n.parentData={element:h,left:t.left,top:t.top,width:o,height:e}))},resize:function(t){var e=y(this).resizable("instance"),i=e.options,s=e.containerOffset,n=e.position,o=e._aspectRatio||t.shiftKey,h={top:0,left:0},a=e.containerElement,t=!0;a[0]!==document&&/static/.test(a.css("position"))&&(h=s),n.left<(e._helper?s.left:0)&&(e.size.width=e.size.width+(e._helper?e.position.left-s.left:e.position.left-h.left),o&&(e.size.height=e.size.width/e.aspectRatio,t=!1),e.position.left=i.helper?s.left:0),n.top<(e._helper?s.top:0)&&(e.size.height=e.size.height+(e._helper?e.position.top-s.top:e.position.top),o&&(e.size.width=e.size.height*e.aspectRatio,t=!1),e.position.top=e._helper?s.top:0),i=e.containerElement.get(0)===e.element.parent().get(0),n=/relative|absolute/.test(e.containerElement.css("position")),i&&n?(e.offset.left=e.parentData.left+e.position.left,e.offset.top=e.parentData.top+e.position.top):(e.offset.left=e.element.offset().left,e.offset.top=e.element.offset().top),n=Math.abs(e.sizeDiff.width+(e._helper?e.offset.left-h.left:e.offset.left-s.left)),s=Math.abs(e.sizeDiff.height+(e._helper?e.offset.top-h.top:e.offset.top-s.top)),n+e.size.width>=e.parentData.width&&(e.size.width=e.parentData.width-n,o&&(e.size.height=e.size.width/e.aspectRatio,t=!1)),s+e.size.height>=e.parentData.height&&(e.size.height=e.parentData.height-s,o&&(e.size.width=e.size.height*e.aspectRatio,t=!1)),t||(e.position.left=e.prevPosition.left,e.position.top=e.prevPosition.top,e.size.width=e.prevSize.width,e.size.height=e.prevSize.height)},stop:function(){var t=y(this).resizable("instance"),e=t.options,i=t.containerOffset,s=t.containerPosition,n=t.containerElement,o=y(t.helper),h=o.offset(),a=o.outerWidth()-t.sizeDiff.width,o=o.outerHeight()-t.sizeDiff.height;t._helper&&!e.animate&&/relative/.test(n.css("position"))&&y(this).css({left:h.left-s.left-i.left,width:a,height:o}),t._helper&&!e.animate&&/static/.test(n.css("position"))&&y(this).css({left:h.left-s.left-i.left,width:a,height:o})}}),y.ui.plugin.add("resizable","alsoResize",{start:function(){var t=y(this).resizable("instance").options;y(t.alsoResize).each(function(){var t=y(this);t.data("ui-resizable-alsoresize",{width:parseFloat(t.width()),height:parseFloat(t.height()),left:parseFloat(t.css("left")),top:parseFloat(t.css("top"))})})},resize:function(t,i){var e=y(this).resizable("instance"),s=e.options,n=e.originalSize,o=e.originalPosition,h={height:e.size.height-n.height||0,width:e.size.width-n.width||0,top:e.position.top-o.top||0,left:e.position.left-o.left||0};y(s.alsoResize).each(function(){var t=y(this),s=y(this).data("ui-resizable-alsoresize"),n={},e=t.parents(i.originalElement[0]).length?["width","height"]:["width","height","top","left"];y.each(e,function(t,e){var i=(s[e]||0)+(h[e]||0);i&&0<=i&&(n[e]=i||null)}),t.css(n)})},stop:function(){y(this).removeData("ui-resizable-alsoresize")}}),y.ui.plugin.add("resizable","ghost",{start:function(){var t=y(this).resizable("instance"),e=t.size;t.ghost=t.originalElement.clone(),t.ghost.css({opacity:.25,display:"block",position:"relative",height:e.height,width:e.width,margin:0,left:0,top:0}),t._addClass(t.ghost,"ui-resizable-ghost"),!1!==y.uiBackCompat&&"string"==typeof t.options.ghost&&t.ghost.addClass(this.options.ghost),t.ghost.appendTo(t.helper)},resize:function(){var t=y(this).resizable("instance");t.ghost&&t.ghost.css({position:"relative",height:t.size.height,width:t.size.width})},stop:function(){var t=y(this).resizable("instance");t.ghost&&t.helper&&t.helper.get(0).removeChild(t.ghost.get(0))}}),y.ui.plugin.add("resizable","grid",{resize:function(){var t,e=y(this).resizable("instance"),i=e.options,s=e.size,n=e.originalSize,o=e.originalPosition,h=e.axis,a="number"==typeof i.grid?[i.grid,i.grid]:i.grid,r=a[0]||1,l=a[1]||1,u=Math.round((s.width-n.width)/r)*r,p=Math.round((s.height-n.height)/l)*l,d=n.width+u,c=n.height+p,f=i.maxWidth&&i.maxWidthd,s=i.minHeight&&i.minHeight>c;i.grid=a,m&&(d+=r),s&&(c+=l),f&&(d-=r),g&&(c-=l),/^(se|s|e)$/.test(h)?(e.size.width=d,e.size.height=c):/^(ne)$/.test(h)?(e.size.width=d,e.size.height=c,e.position.top=o.top-p):/^(sw)$/.test(h)?(e.size.width=d,e.size.height=c,e.position.left=o.left-u):((c-l<=0||d-r<=0)&&(t=e._getPaddingPlusBorderDimensions(this)),0=f[g]?0:Math.min(f[g],n));!a&&1-1){targetElements.on(evt+EVENT_NAMESPACE,function elementToggle(event){$.powerTip.toggle(this,event)})}else{targetElements.on(evt+EVENT_NAMESPACE,function elementOpen(event){$.powerTip.show(this,event)})}});$.each(options.closeEvents,function(idx,evt){if($.inArray(evt,options.openEvents)<0){targetElements.on(evt+EVENT_NAMESPACE,function elementClose(event){$.powerTip.hide(this,!isMouseEvent(event))})}});targetElements.on("keydown"+EVENT_NAMESPACE,function elementKeyDown(event){if(event.keyCode===27){$.powerTip.hide(this,true)}})}return targetElements};$.fn.powerTip.defaults={fadeInTime:200,fadeOutTime:100,followMouse:false,popupId:"powerTip",popupClass:null,intentSensitivity:7,intentPollInterval:100,closeDelay:100,placement:"n",smartPlacement:false,offset:10,mouseOnToPopup:false,manual:false,openEvents:["mouseenter","focus"],closeEvents:["mouseleave","blur"]};$.fn.powerTip.smartPlacementLists={n:["n","ne","nw","s"],e:["e","ne","se","w","nw","sw","n","s","e"],s:["s","se","sw","n"],w:["w","nw","sw","e","ne","se","n","s","w"],nw:["nw","w","sw","n","s","se","nw"],ne:["ne","e","se","n","s","sw","ne"],sw:["sw","w","nw","s","n","ne","sw"],se:["se","e","ne","s","n","nw","se"],"nw-alt":["nw-alt","n","ne-alt","sw-alt","s","se-alt","w","e"],"ne-alt":["ne-alt","n","nw-alt","se-alt","s","sw-alt","e","w"],"sw-alt":["sw-alt","s","se-alt","nw-alt","n","ne-alt","w","e"],"se-alt":["se-alt","s","sw-alt","ne-alt","n","nw-alt","e","w"]};$.powerTip={show:function apiShowTip(element,event){if(isMouseEvent(event)){trackMouse(event);session.previousX=event.pageX;session.previousY=event.pageY;$(element).data(DATA_DISPLAYCONTROLLER).show()}else{$(element).first().data(DATA_DISPLAYCONTROLLER).show(true,true)}return element},reposition:function apiResetPosition(element){$(element).first().data(DATA_DISPLAYCONTROLLER).resetPosition();return element},hide:function apiCloseTip(element,immediate){var displayController;immediate=element?immediate:true;if(element){displayController=$(element).first().data(DATA_DISPLAYCONTROLLER)}else if(session.activeHover){displayController=session.activeHover.data(DATA_DISPLAYCONTROLLER)}if(displayController){displayController.hide(immediate)}return element},toggle:function apiToggle(element,event){if(session.activeHover&&session.activeHover.is(element)){$.powerTip.hide(element,!isMouseEvent(event))}else{$.powerTip.show(element,event)}return element}};$.powerTip.showTip=$.powerTip.show;$.powerTip.closeTip=$.powerTip.hide;function CSSCoordinates(){var me=this;me.top="auto";me.left="auto";me.right="auto";me.bottom="auto";me.set=function(property,value){if($.isNumeric(value)){me[property]=Math.round(value)}}}function DisplayController(element,options,tipController){var hoverTimer=null,myCloseDelay=null;function openTooltip(immediate,forceOpen){cancelTimer();if(!element.data(DATA_HASACTIVEHOVER)){if(!immediate){session.tipOpenImminent=true;hoverTimer=setTimeout(function intentDelay(){hoverTimer=null;checkForIntent()},options.intentPollInterval)}else{if(forceOpen){element.data(DATA_FORCEDOPEN,true)}closeAnyDelayed();tipController.showTip(element)}}else{cancelClose()}}function closeTooltip(disableDelay){if(myCloseDelay){myCloseDelay=session.closeDelayTimeout=clearTimeout(myCloseDelay);session.delayInProgress=false}cancelTimer();session.tipOpenImminent=false;if(element.data(DATA_HASACTIVEHOVER)){element.data(DATA_FORCEDOPEN,false);if(!disableDelay){session.delayInProgress=true;session.closeDelayTimeout=setTimeout(function closeDelay(){session.closeDelayTimeout=null;tipController.hideTip(element);session.delayInProgress=false;myCloseDelay=null},options.closeDelay);myCloseDelay=session.closeDelayTimeout}else{tipController.hideTip(element)}}}function checkForIntent(){var xDifference=Math.abs(session.previousX-session.currentX),yDifference=Math.abs(session.previousY-session.currentY),totalDifference=xDifference+yDifference;if(totalDifference",{id:options.popupId});if($body.length===0){$body=$("body")}$body.append(tipElement);session.tooltips=session.tooltips?session.tooltips.add(tipElement):tipElement}if(options.followMouse){if(!tipElement.data(DATA_HASMOUSEMOVE)){$document.on("mousemove"+EVENT_NAMESPACE,positionTipOnCursor);$window.on("scroll"+EVENT_NAMESPACE,positionTipOnCursor);tipElement.data(DATA_HASMOUSEMOVE,true)}}function beginShowTip(element){element.data(DATA_HASACTIVEHOVER,true);tipElement.queue(function queueTipInit(next){showTip(element);next()})}function showTip(element){var tipContent;if(!element.data(DATA_HASACTIVEHOVER)){return}if(session.isTipOpen){if(!session.isClosing){hideTip(session.activeHover)}tipElement.delay(100).queue(function queueTipAgain(next){showTip(element);next()});return}element.trigger("powerTipPreRender");tipContent=getTooltipContent(element);if(tipContent){tipElement.empty().append(tipContent)}else{return}element.trigger("powerTipRender");session.activeHover=element;session.isTipOpen=true;tipElement.data(DATA_MOUSEONTOTIP,options.mouseOnToPopup);tipElement.addClass(options.popupClass);if(!options.followMouse||element.data(DATA_FORCEDOPEN)){positionTipOnElement(element);session.isFixedTipOpen=true}else{positionTipOnCursor()}if(!element.data(DATA_FORCEDOPEN)&&!options.followMouse){$document.on("click"+EVENT_NAMESPACE,function documentClick(event){var target=event.target;if(target!==element[0]){if(options.mouseOnToPopup){if(target!==tipElement[0]&&!$.contains(tipElement[0],target)){$.powerTip.hide()}}else{$.powerTip.hide()}}})}if(options.mouseOnToPopup&&!options.manual){tipElement.on("mouseenter"+EVENT_NAMESPACE,function tipMouseEnter(){if(session.activeHover){session.activeHover.data(DATA_DISPLAYCONTROLLER).cancel()}});tipElement.on("mouseleave"+EVENT_NAMESPACE,function tipMouseLeave(){if(session.activeHover){session.activeHover.data(DATA_DISPLAYCONTROLLER).hide()}})}tipElement.fadeIn(options.fadeInTime,function fadeInCallback(){if(!session.desyncTimeout){session.desyncTimeout=setInterval(closeDesyncedTip,500)}element.trigger("powerTipOpen")})}function hideTip(element){session.isClosing=true;session.isTipOpen=false;session.desyncTimeout=clearInterval(session.desyncTimeout);element.data(DATA_HASACTIVEHOVER,false);element.data(DATA_FORCEDOPEN,false);$document.off("click"+EVENT_NAMESPACE);tipElement.off(EVENT_NAMESPACE);tipElement.fadeOut(options.fadeOutTime,function fadeOutCallback(){var coords=new CSSCoordinates;session.activeHover=null;session.isClosing=false;session.isFixedTipOpen=false;tipElement.removeClass();coords.set("top",session.currentY+options.offset);coords.set("left",session.currentX+options.offset);tipElement.css(coords);element.trigger("powerTipClose")})}function positionTipOnCursor(){var tipWidth,tipHeight,coords,collisions,collisionCount;if(!session.isFixedTipOpen&&(session.isTipOpen||session.tipOpenImminent&&tipElement.data(DATA_HASMOUSEMOVE))){tipWidth=tipElement.outerWidth();tipHeight=tipElement.outerHeight();coords=new CSSCoordinates;coords.set("top",session.currentY+options.offset);coords.set("left",session.currentX+options.offset);collisions=getViewportCollisions(coords,tipWidth,tipHeight);if(collisions!==Collision.none){collisionCount=countFlags(collisions);if(collisionCount===1){if(collisions===Collision.right){coords.set("left",session.scrollLeft+session.windowWidth-tipWidth)}else if(collisions===Collision.bottom){coords.set("top",session.scrollTop+session.windowHeight-tipHeight)}}else{coords.set("left",session.currentX-tipWidth-options.offset);coords.set("top",session.currentY-tipHeight-options.offset)}}tipElement.css(coords)}}function positionTipOnElement(element){var priorityList,finalPlacement;if(options.smartPlacement||options.followMouse&&element.data(DATA_FORCEDOPEN)){priorityList=$.fn.powerTip.smartPlacementLists[options.placement];$.each(priorityList,function(idx,pos){var collisions=getViewportCollisions(placeTooltip(element,pos),tipElement.outerWidth(),tipElement.outerHeight());finalPlacement=pos;return collisions!==Collision.none})}else{placeTooltip(element,options.placement);finalPlacement=options.placement}tipElement.removeClass("w nw sw e ne se n s w se-alt sw-alt ne-alt nw-alt");tipElement.addClass(finalPlacement)}function placeTooltip(element,placement){var iterationCount=0,tipWidth,tipHeight,coords=new CSSCoordinates;coords.set("top",0);coords.set("left",0);tipElement.css(coords);do{tipWidth=tipElement.outerWidth();tipHeight=tipElement.outerHeight();coords=placementCalculator.compute(element,placement,tipWidth,tipHeight,options.offset);tipElement.css(coords)}while(++iterationCount<=5&&(tipWidth!==tipElement.outerWidth()||tipHeight!==tipElement.outerHeight()));return coords}function closeDesyncedTip(){var isDesynced=false,hasDesyncableCloseEvent=$.grep(["mouseleave","mouseout","blur","focusout"],function(eventType){return $.inArray(eventType,options.closeEvents)!==-1}).length>0;if(session.isTipOpen&&!session.isClosing&&!session.delayInProgress&&hasDesyncableCloseEvent){if(session.activeHover.data(DATA_HASACTIVEHOVER)===false||session.activeHover.is(":disabled")){isDesynced=true}else if(!isMouseOver(session.activeHover)&&!session.activeHover.is(":focus")&&!session.activeHover.data(DATA_FORCEDOPEN)){if(tipElement.data(DATA_MOUSEONTOTIP)){if(!isMouseOver(tipElement)){isDesynced=true}}else{isDesynced=true}}if(isDesynced){hideTip(session.activeHover)}}}this.showTip=beginShowTip;this.hideTip=hideTip;this.resetPosition=positionTipOnElement}function isSvgElement(element){return Boolean(window.SVGElement&&element[0]instanceof SVGElement)}function isMouseEvent(event){return Boolean(event&&$.inArray(event.type,MOUSE_EVENTS)>-1&&typeof event.pageX==="number")}function initTracking(){if(!session.mouseTrackingActive){session.mouseTrackingActive=true;getViewportDimensions();$(getViewportDimensions);$document.on("mousemove"+EVENT_NAMESPACE,trackMouse);$window.on("resize"+EVENT_NAMESPACE,trackResize);$window.on("scroll"+EVENT_NAMESPACE,trackScroll)}}function getViewportDimensions(){session.scrollLeft=$window.scrollLeft();session.scrollTop=$window.scrollTop();session.windowWidth=$window.width();session.windowHeight=$window.height()}function trackResize(){session.windowWidth=$window.width();session.windowHeight=$window.height()}function trackScroll(){var x=$window.scrollLeft(),y=$window.scrollTop();if(x!==session.scrollLeft){session.currentX+=x-session.scrollLeft;session.scrollLeft=x}if(y!==session.scrollTop){session.currentY+=y-session.scrollTop;session.scrollTop=y}}function trackMouse(event){session.currentX=event.pageX;session.currentY=event.pageY}function isMouseOver(element){var elementPosition=element.offset(),elementBox=element[0].getBoundingClientRect(),elementWidth=elementBox.right-elementBox.left,elementHeight=elementBox.bottom-elementBox.top;return session.currentX>=elementPosition.left&&session.currentX<=elementPosition.left+elementWidth&&session.currentY>=elementPosition.top&&session.currentY<=elementPosition.top+elementHeight}function getTooltipContent(element){var tipText=element.data(DATA_POWERTIP),tipObject=element.data(DATA_POWERTIPJQ),tipTarget=element.data(DATA_POWERTIPTARGET),targetElement,content;if(tipText){if($.isFunction(tipText)){tipText=tipText.call(element[0])}content=tipText}else if(tipObject){if($.isFunction(tipObject)){tipObject=tipObject.call(element[0])}if(tipObject.length>0){content=tipObject.clone(true,true)}}else if(tipTarget){targetElement=$("#"+tipTarget);if(targetElement.length>0){content=targetElement.html()}}return content}function getViewportCollisions(coords,elementWidth,elementHeight){var viewportTop=session.scrollTop,viewportLeft=session.scrollLeft,viewportBottom=viewportTop+session.windowHeight,viewportRight=viewportLeft+session.windowWidth,collisions=Collision.none;if(coords.topviewportBottom||Math.abs(coords.bottom-session.windowHeight)>viewportBottom){collisions|=Collision.bottom}if(coords.leftviewportRight){collisions|=Collision.left}if(coords.left+elementWidth>viewportRight||coords.right1)){a.preventDefault();var c=a.originalEvent.changedTouches[0],d=document.createEvent("MouseEvents");d.initMouseEvent(b,!0,!0,window,1,c.screenX,c.screenY,c.clientX,c.clientY,!1,!1,!1,!1,0,null),a.target.dispatchEvent(d)}}if(a.support.touch="ontouchend"in document,a.support.touch){var e,b=a.ui.mouse.prototype,c=b._mouseInit,d=b._mouseDestroy;b._touchStart=function(a){var b=this;!e&&b._mouseCapture(a.originalEvent.changedTouches[0])&&(e=!0,b._touchMoved=!1,f(a,"mouseover"),f(a,"mousemove"),f(a,"mousedown"))},b._touchMove=function(a){e&&(this._touchMoved=!0,f(a,"mousemove"))},b._touchEnd=function(a){e&&(f(a,"mouseup"),f(a,"mouseout"),this._touchMoved||f(a,"click"),e=!1)},b._mouseInit=function(){var b=this;b.element.bind({touchstart:a.proxy(b,"_touchStart"),touchmove:a.proxy(b,"_touchMove"),touchend:a.proxy(b,"_touchEnd")}),c.call(b)},b._mouseDestroy=function(){var b=this;b.element.unbind({touchstart:a.proxy(b,"_touchStart"),touchmove:a.proxy(b,"_touchMove"),touchend:a.proxy(b,"_touchEnd")}),d.call(b)}}}(jQuery);/*! SmartMenus jQuery Plugin - v1.1.0 - September 17, 2017 + * http://www.smartmenus.org/ + * Copyright Vasil Dinkov, Vadikom Web Ltd. http://vadikom.com; Licensed MIT */(function(t){"function"==typeof define&&define.amd?define(["jquery"],t):"object"==typeof module&&"object"==typeof module.exports?module.exports=t(require("jquery")):t(jQuery)})(function($){function initMouseDetection(t){var e=".smartmenus_mouse";if(mouseDetectionEnabled||t)mouseDetectionEnabled&&t&&($(document).off(e),mouseDetectionEnabled=!1);else{var i=!0,s=null,o={mousemove:function(t){var e={x:t.pageX,y:t.pageY,timeStamp:(new Date).getTime()};if(s){var o=Math.abs(s.x-e.x),a=Math.abs(s.y-e.y);if((o>0||a>0)&&2>=o&&2>=a&&300>=e.timeStamp-s.timeStamp&&(mouse=!0,i)){var n=$(t.target).closest("a");n.is("a")&&$.each(menuTrees,function(){return $.contains(this.$root[0],n[0])?(this.itemEnter({currentTarget:n[0]}),!1):void 0}),i=!1}}s=e}};o[touchEvents?"touchstart":"pointerover pointermove pointerout MSPointerOver MSPointerMove MSPointerOut"]=function(t){isTouchEvent(t.originalEvent)&&(mouse=!1)},$(document).on(getEventsNS(o,e)),mouseDetectionEnabled=!0}}function isTouchEvent(t){return!/^(4|mouse)$/.test(t.pointerType)}function getEventsNS(t,e){e||(e="");var i={};for(var s in t)i[s.split(" ").join(e+" ")+e]=t[s];return i}var menuTrees=[],mouse=!1,touchEvents="ontouchstart"in window,mouseDetectionEnabled=!1,requestAnimationFrame=window.requestAnimationFrame||function(t){return setTimeout(t,1e3/60)},cancelAnimationFrame=window.cancelAnimationFrame||function(t){clearTimeout(t)},canAnimate=!!$.fn.animate;return $.SmartMenus=function(t,e){this.$root=$(t),this.opts=e,this.rootId="",this.accessIdPrefix="",this.$subArrow=null,this.activatedItems=[],this.visibleSubMenus=[],this.showTimeout=0,this.hideTimeout=0,this.scrollTimeout=0,this.clickActivated=!1,this.focusActivated=!1,this.zIndexInc=0,this.idInc=0,this.$firstLink=null,this.$firstSub=null,this.disabled=!1,this.$disableOverlay=null,this.$touchScrollingSub=null,this.cssTransforms3d="perspective"in t.style||"webkitPerspective"in t.style,this.wasCollapsible=!1,this.init()},$.extend($.SmartMenus,{hideAll:function(){$.each(menuTrees,function(){this.menuHideAll()})},destroy:function(){for(;menuTrees.length;)menuTrees[0].destroy();initMouseDetection(!0)},prototype:{init:function(t){var e=this;if(!t){menuTrees.push(this),this.rootId=((new Date).getTime()+Math.random()+"").replace(/\D/g,""),this.accessIdPrefix="sm-"+this.rootId+"-",this.$root.hasClass("sm-rtl")&&(this.opts.rightToLeftSubMenus=!0);var i=".smartmenus";this.$root.data("smartmenus",this).attr("data-smartmenus-id",this.rootId).dataSM("level",1).on(getEventsNS({"mouseover focusin":$.proxy(this.rootOver,this),"mouseout focusout":$.proxy(this.rootOut,this),keydown:$.proxy(this.rootKeyDown,this)},i)).on(getEventsNS({mouseenter:$.proxy(this.itemEnter,this),mouseleave:$.proxy(this.itemLeave,this),mousedown:$.proxy(this.itemDown,this),focus:$.proxy(this.itemFocus,this),blur:$.proxy(this.itemBlur,this),click:$.proxy(this.itemClick,this)},i),"a"),i+=this.rootId,this.opts.hideOnClick&&$(document).on(getEventsNS({touchstart:$.proxy(this.docTouchStart,this),touchmove:$.proxy(this.docTouchMove,this),touchend:$.proxy(this.docTouchEnd,this),click:$.proxy(this.docClick,this)},i)),$(window).on(getEventsNS({"resize orientationchange":$.proxy(this.winResize,this)},i)),this.opts.subIndicators&&(this.$subArrow=$("").addClass("sub-arrow"),this.opts.subIndicatorsText&&this.$subArrow.html(this.opts.subIndicatorsText)),initMouseDetection()}if(this.$firstSub=this.$root.find("ul").each(function(){e.menuInit($(this))}).eq(0),this.$firstLink=this.$root.find("a").eq(0),this.opts.markCurrentItem){var s=/(index|default)\.[^#\?\/]*/i,o=/#.*/,a=window.location.href.replace(s,""),n=a.replace(o,"");this.$root.find("a").each(function(){var t=this.href.replace(s,""),i=$(this);(t==a||t==n)&&(i.addClass("current"),e.opts.markCurrentTree&&i.parentsUntil("[data-smartmenus-id]","ul").each(function(){$(this).dataSM("parent-a").addClass("current")}))})}this.wasCollapsible=this.isCollapsible()},destroy:function(t){if(!t){var e=".smartmenus";this.$root.removeData("smartmenus").removeAttr("data-smartmenus-id").removeDataSM("level").off(e),e+=this.rootId,$(document).off(e),$(window).off(e),this.opts.subIndicators&&(this.$subArrow=null)}this.menuHideAll();var i=this;this.$root.find("ul").each(function(){var t=$(this);t.dataSM("scroll-arrows")&&t.dataSM("scroll-arrows").remove(),t.dataSM("shown-before")&&((i.opts.subMenusMinWidth||i.opts.subMenusMaxWidth)&&t.css({width:"",minWidth:"",maxWidth:""}).removeClass("sm-nowrap"),t.dataSM("scroll-arrows")&&t.dataSM("scroll-arrows").remove(),t.css({zIndex:"",top:"",left:"",marginLeft:"",marginTop:"",display:""})),0==(t.attr("id")||"").indexOf(i.accessIdPrefix)&&t.removeAttr("id")}).removeDataSM("in-mega").removeDataSM("shown-before").removeDataSM("scroll-arrows").removeDataSM("parent-a").removeDataSM("level").removeDataSM("beforefirstshowfired").removeAttr("role").removeAttr("aria-hidden").removeAttr("aria-labelledby").removeAttr("aria-expanded"),this.$root.find("a.has-submenu").each(function(){var t=$(this);0==t.attr("id").indexOf(i.accessIdPrefix)&&t.removeAttr("id")}).removeClass("has-submenu").removeDataSM("sub").removeAttr("aria-haspopup").removeAttr("aria-controls").removeAttr("aria-expanded").closest("li").removeDataSM("sub"),this.opts.subIndicators&&this.$root.find("span.sub-arrow").remove(),this.opts.markCurrentItem&&this.$root.find("a.current").removeClass("current"),t||(this.$root=null,this.$firstLink=null,this.$firstSub=null,this.$disableOverlay&&(this.$disableOverlay.remove(),this.$disableOverlay=null),menuTrees.splice($.inArray(this,menuTrees),1))},disable:function(t){if(!this.disabled){if(this.menuHideAll(),!t&&!this.opts.isPopup&&this.$root.is(":visible")){var e=this.$root.offset();this.$disableOverlay=$('
').css({position:"absolute",top:e.top,left:e.left,width:this.$root.outerWidth(),height:this.$root.outerHeight(),zIndex:this.getStartZIndex(!0),opacity:0}).appendTo(document.body)}this.disabled=!0}},docClick:function(t){return this.$touchScrollingSub?(this.$touchScrollingSub=null,void 0):((this.visibleSubMenus.length&&!$.contains(this.$root[0],t.target)||$(t.target).closest("a").length)&&this.menuHideAll(),void 0)},docTouchEnd:function(){if(this.lastTouch){if(!(!this.visibleSubMenus.length||void 0!==this.lastTouch.x2&&this.lastTouch.x1!=this.lastTouch.x2||void 0!==this.lastTouch.y2&&this.lastTouch.y1!=this.lastTouch.y2||this.lastTouch.target&&$.contains(this.$root[0],this.lastTouch.target))){this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0);var t=this;this.hideTimeout=setTimeout(function(){t.menuHideAll()},350)}this.lastTouch=null}},docTouchMove:function(t){if(this.lastTouch){var e=t.originalEvent.touches[0];this.lastTouch.x2=e.pageX,this.lastTouch.y2=e.pageY}},docTouchStart:function(t){var e=t.originalEvent.touches[0];this.lastTouch={x1:e.pageX,y1:e.pageY,target:e.target}},enable:function(){this.disabled&&(this.$disableOverlay&&(this.$disableOverlay.remove(),this.$disableOverlay=null),this.disabled=!1)},getClosestMenu:function(t){for(var e=$(t).closest("ul");e.dataSM("in-mega");)e=e.parent().closest("ul");return e[0]||null},getHeight:function(t){return this.getOffset(t,!0)},getOffset:function(t,e){var i;"none"==t.css("display")&&(i={position:t[0].style.position,visibility:t[0].style.visibility},t.css({position:"absolute",visibility:"hidden"}).show());var s=t[0].getBoundingClientRect&&t[0].getBoundingClientRect(),o=s&&(e?s.height||s.bottom-s.top:s.width||s.right-s.left);return o||0===o||(o=e?t[0].offsetHeight:t[0].offsetWidth),i&&t.hide().css(i),o},getStartZIndex:function(t){var e=parseInt(this[t?"$root":"$firstSub"].css("z-index"));return!t&&isNaN(e)&&(e=parseInt(this.$root.css("z-index"))),isNaN(e)?1:e},getTouchPoint:function(t){return t.touches&&t.touches[0]||t.changedTouches&&t.changedTouches[0]||t},getViewport:function(t){var e=t?"Height":"Width",i=document.documentElement["client"+e],s=window["inner"+e];return s&&(i=Math.min(i,s)),i},getViewportHeight:function(){return this.getViewport(!0)},getViewportWidth:function(){return this.getViewport()},getWidth:function(t){return this.getOffset(t)},handleEvents:function(){return!this.disabled&&this.isCSSOn()},handleItemEvents:function(t){return this.handleEvents()&&!this.isLinkInMegaMenu(t)},isCollapsible:function(){return"static"==this.$firstSub.css("position")},isCSSOn:function(){return"inline"!=this.$firstLink.css("display")},isFixed:function(){var t="fixed"==this.$root.css("position");return t||this.$root.parentsUntil("body").each(function(){return"fixed"==$(this).css("position")?(t=!0,!1):void 0}),t},isLinkInMegaMenu:function(t){return $(this.getClosestMenu(t[0])).hasClass("mega-menu")},isTouchMode:function(){return!mouse||this.opts.noMouseOver||this.isCollapsible()},itemActivate:function(t,e){var i=t.closest("ul"),s=i.dataSM("level");if(s>1&&(!this.activatedItems[s-2]||this.activatedItems[s-2][0]!=i.dataSM("parent-a")[0])){var o=this;$(i.parentsUntil("[data-smartmenus-id]","ul").get().reverse()).add(i).each(function(){o.itemActivate($(this).dataSM("parent-a"))})}if((!this.isCollapsible()||e)&&this.menuHideSubMenus(this.activatedItems[s-1]&&this.activatedItems[s-1][0]==t[0]?s:s-1),this.activatedItems[s-1]=t,this.$root.triggerHandler("activate.smapi",t[0])!==!1){var a=t.dataSM("sub");a&&(this.isTouchMode()||!this.opts.showOnClick||this.clickActivated)&&this.menuShow(a)}},itemBlur:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&this.$root.triggerHandler("blur.smapi",e[0])},itemClick:function(t){var e=$(t.currentTarget);if(this.handleItemEvents(e)){if(this.$touchScrollingSub&&this.$touchScrollingSub[0]==e.closest("ul")[0])return this.$touchScrollingSub=null,t.stopPropagation(),!1;if(this.$root.triggerHandler("click.smapi",e[0])===!1)return!1;var i=$(t.target).is(".sub-arrow"),s=e.dataSM("sub"),o=s?2==s.dataSM("level"):!1,a=this.isCollapsible(),n=/toggle$/.test(this.opts.collapsibleBehavior),r=/link$/.test(this.opts.collapsibleBehavior),h=/^accordion/.test(this.opts.collapsibleBehavior);if(s&&!s.is(":visible")){if((!r||!a||i)&&(this.opts.showOnClick&&o&&(this.clickActivated=!0),this.itemActivate(e,h),s.is(":visible")))return this.focusActivated=!0,!1}else if(a&&(n||i))return this.itemActivate(e,h),this.menuHide(s),n&&(this.focusActivated=!1),!1;return this.opts.showOnClick&&o||e.hasClass("disabled")||this.$root.triggerHandler("select.smapi",e[0])===!1?!1:void 0}},itemDown:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&e.dataSM("mousedown",!0)},itemEnter:function(t){var e=$(t.currentTarget);if(this.handleItemEvents(e)){if(!this.isTouchMode()){this.showTimeout&&(clearTimeout(this.showTimeout),this.showTimeout=0);var i=this;this.showTimeout=setTimeout(function(){i.itemActivate(e)},this.opts.showOnClick&&1==e.closest("ul").dataSM("level")?1:this.opts.showTimeout)}this.$root.triggerHandler("mouseenter.smapi",e[0])}},itemFocus:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&(!this.focusActivated||this.isTouchMode()&&e.dataSM("mousedown")||this.activatedItems.length&&this.activatedItems[this.activatedItems.length-1][0]==e[0]||this.itemActivate(e,!0),this.$root.triggerHandler("focus.smapi",e[0]))},itemLeave:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&(this.isTouchMode()||(e[0].blur(),this.showTimeout&&(clearTimeout(this.showTimeout),this.showTimeout=0)),e.removeDataSM("mousedown"),this.$root.triggerHandler("mouseleave.smapi",e[0]))},menuHide:function(t){if(this.$root.triggerHandler("beforehide.smapi",t[0])!==!1&&(canAnimate&&t.stop(!0,!0),"none"!=t.css("display"))){var e=function(){t.css("z-index","")};this.isCollapsible()?canAnimate&&this.opts.collapsibleHideFunction?this.opts.collapsibleHideFunction.call(this,t,e):t.hide(this.opts.collapsibleHideDuration,e):canAnimate&&this.opts.hideFunction?this.opts.hideFunction.call(this,t,e):t.hide(this.opts.hideDuration,e),t.dataSM("scroll")&&(this.menuScrollStop(t),t.css({"touch-action":"","-ms-touch-action":"","-webkit-transform":"",transform:""}).off(".smartmenus_scroll").removeDataSM("scroll").dataSM("scroll-arrows").hide()),t.dataSM("parent-a").removeClass("highlighted").attr("aria-expanded","false"),t.attr({"aria-expanded":"false","aria-hidden":"true"});var i=t.dataSM("level");this.activatedItems.splice(i-1,1),this.visibleSubMenus.splice($.inArray(t,this.visibleSubMenus),1),this.$root.triggerHandler("hide.smapi",t[0])}},menuHideAll:function(){this.showTimeout&&(clearTimeout(this.showTimeout),this.showTimeout=0);for(var t=this.opts.isPopup?1:0,e=this.visibleSubMenus.length-1;e>=t;e--)this.menuHide(this.visibleSubMenus[e]);this.opts.isPopup&&(canAnimate&&this.$root.stop(!0,!0),this.$root.is(":visible")&&(canAnimate&&this.opts.hideFunction?this.opts.hideFunction.call(this,this.$root):this.$root.hide(this.opts.hideDuration))),this.activatedItems=[],this.visibleSubMenus=[],this.clickActivated=!1,this.focusActivated=!1,this.zIndexInc=0,this.$root.triggerHandler("hideAll.smapi")},menuHideSubMenus:function(t){for(var e=this.activatedItems.length-1;e>=t;e--){var i=this.activatedItems[e].dataSM("sub");i&&this.menuHide(i)}},menuInit:function(t){if(!t.dataSM("in-mega")){t.hasClass("mega-menu")&&t.find("ul").dataSM("in-mega",!0);for(var e=2,i=t[0];(i=i.parentNode.parentNode)!=this.$root[0];)e++;var s=t.prevAll("a").eq(-1);s.length||(s=t.prevAll().find("a").eq(-1)),s.addClass("has-submenu").dataSM("sub",t),t.dataSM("parent-a",s).dataSM("level",e).parent().dataSM("sub",t);var o=s.attr("id")||this.accessIdPrefix+ ++this.idInc,a=t.attr("id")||this.accessIdPrefix+ ++this.idInc;s.attr({id:o,"aria-haspopup":"true","aria-controls":a,"aria-expanded":"false"}),t.attr({id:a,role:"group","aria-hidden":"true","aria-labelledby":o,"aria-expanded":"false"}),this.opts.subIndicators&&s[this.opts.subIndicatorsPos](this.$subArrow.clone())}},menuPosition:function(t){var e,i,s=t.dataSM("parent-a"),o=s.closest("li"),a=o.parent(),n=t.dataSM("level"),r=this.getWidth(t),h=this.getHeight(t),u=s.offset(),l=u.left,c=u.top,d=this.getWidth(s),m=this.getHeight(s),p=$(window),f=p.scrollLeft(),v=p.scrollTop(),b=this.getViewportWidth(),S=this.getViewportHeight(),g=a.parent().is("[data-sm-horizontal-sub]")||2==n&&!a.hasClass("sm-vertical"),M=this.opts.rightToLeftSubMenus&&!o.is("[data-sm-reverse]")||!this.opts.rightToLeftSubMenus&&o.is("[data-sm-reverse]"),w=2==n?this.opts.mainMenuSubOffsetX:this.opts.subMenusSubOffsetX,T=2==n?this.opts.mainMenuSubOffsetY:this.opts.subMenusSubOffsetY;if(g?(e=M?d-r-w:w,i=this.opts.bottomToTopSubMenus?-h-T:m+T):(e=M?w-r:d-w,i=this.opts.bottomToTopSubMenus?m-T-h:T),this.opts.keepInViewport){var y=l+e,I=c+i;if(M&&f>y?e=g?f-y+e:d-w:!M&&y+r>f+b&&(e=g?f+b-r-y+e:w-r),g||(S>h&&I+h>v+S?i+=v+S-h-I:(h>=S||v>I)&&(i+=v-I)),g&&(I+h>v+S+.49||v>I)||!g&&h>S+.49){var x=this;t.dataSM("scroll-arrows")||t.dataSM("scroll-arrows",$([$('')[0],$('')[0]]).on({mouseenter:function(){t.dataSM("scroll").up=$(this).hasClass("scroll-up"),x.menuScroll(t)},mouseleave:function(e){x.menuScrollStop(t),x.menuScrollOut(t,e)},"mousewheel DOMMouseScroll":function(t){t.preventDefault()}}).insertAfter(t));var A=".smartmenus_scroll";if(t.dataSM("scroll",{y:this.cssTransforms3d?0:i-m,step:1,itemH:m,subH:h,arrowDownH:this.getHeight(t.dataSM("scroll-arrows").eq(1))}).on(getEventsNS({mouseover:function(e){x.menuScrollOver(t,e)},mouseout:function(e){x.menuScrollOut(t,e)},"mousewheel DOMMouseScroll":function(e){x.menuScrollMousewheel(t,e)}},A)).dataSM("scroll-arrows").css({top:"auto",left:"0",marginLeft:e+(parseInt(t.css("border-left-width"))||0),width:r-(parseInt(t.css("border-left-width"))||0)-(parseInt(t.css("border-right-width"))||0),zIndex:t.css("z-index")}).eq(g&&this.opts.bottomToTopSubMenus?0:1).show(),this.isFixed()){var C={};C[touchEvents?"touchstart touchmove touchend":"pointerdown pointermove pointerup MSPointerDown MSPointerMove MSPointerUp"]=function(e){x.menuScrollTouch(t,e)},t.css({"touch-action":"none","-ms-touch-action":"none"}).on(getEventsNS(C,A))}}}t.css({top:"auto",left:"0",marginLeft:e,marginTop:i-m})},menuScroll:function(t,e,i){var s,o=t.dataSM("scroll"),a=t.dataSM("scroll-arrows"),n=o.up?o.upEnd:o.downEnd;if(!e&&o.momentum){if(o.momentum*=.92,s=o.momentum,.5>s)return this.menuScrollStop(t),void 0}else s=i||(e||!this.opts.scrollAccelerate?this.opts.scrollStep:Math.floor(o.step));var r=t.dataSM("level");if(this.activatedItems[r-1]&&this.activatedItems[r-1].dataSM("sub")&&this.activatedItems[r-1].dataSM("sub").is(":visible")&&this.menuHideSubMenus(r-1),o.y=o.up&&o.y>=n||!o.up&&n>=o.y?o.y:Math.abs(n-o.y)>s?o.y+(o.up?s:-s):n,t.css(this.cssTransforms3d?{"-webkit-transform":"translate3d(0, "+o.y+"px, 0)",transform:"translate3d(0, "+o.y+"px, 0)"}:{marginTop:o.y}),mouse&&(o.up&&o.y>o.downEnd||!o.up&&o.y0;t.dataSM("scroll-arrows").eq(i?0:1).is(":visible")&&(t.dataSM("scroll").up=i,this.menuScroll(t,!0))}e.preventDefault()},menuScrollOut:function(t,e){mouse&&(/^scroll-(up|down)/.test((e.relatedTarget||"").className)||(t[0]==e.relatedTarget||$.contains(t[0],e.relatedTarget))&&this.getClosestMenu(e.relatedTarget)==t[0]||t.dataSM("scroll-arrows").css("visibility","hidden"))},menuScrollOver:function(t,e){if(mouse&&!/^scroll-(up|down)/.test(e.target.className)&&this.getClosestMenu(e.target)==t[0]){this.menuScrollRefreshData(t);var i=t.dataSM("scroll"),s=$(window).scrollTop()-t.dataSM("parent-a").offset().top-i.itemH;t.dataSM("scroll-arrows").eq(0).css("margin-top",s).end().eq(1).css("margin-top",s+this.getViewportHeight()-i.arrowDownH).end().css("visibility","visible")}},menuScrollRefreshData:function(t){var e=t.dataSM("scroll"),i=$(window).scrollTop()-t.dataSM("parent-a").offset().top-e.itemH;this.cssTransforms3d&&(i=-(parseFloat(t.css("margin-top"))-i)),$.extend(e,{upEnd:i,downEnd:i+this.getViewportHeight()-e.subH})},menuScrollStop:function(t){return this.scrollTimeout?(cancelAnimationFrame(this.scrollTimeout),this.scrollTimeout=0,t.dataSM("scroll").step=1,!0):void 0},menuScrollTouch:function(t,e){if(e=e.originalEvent,isTouchEvent(e)){var i=this.getTouchPoint(e);if(this.getClosestMenu(i.target)==t[0]){var s=t.dataSM("scroll");if(/(start|down)$/i.test(e.type))this.menuScrollStop(t)?(e.preventDefault(),this.$touchScrollingSub=t):this.$touchScrollingSub=null,this.menuScrollRefreshData(t),$.extend(s,{touchStartY:i.pageY,touchStartTime:e.timeStamp});else if(/move$/i.test(e.type)){var o=void 0!==s.touchY?s.touchY:s.touchStartY;if(void 0!==o&&o!=i.pageY){this.$touchScrollingSub=t;var a=i.pageY>o;void 0!==s.up&&s.up!=a&&$.extend(s,{touchStartY:i.pageY,touchStartTime:e.timeStamp}),$.extend(s,{up:a,touchY:i.pageY}),this.menuScroll(t,!0,Math.abs(i.pageY-o))}e.preventDefault()}else void 0!==s.touchY&&((s.momentum=15*Math.pow(Math.abs(i.pageY-s.touchStartY)/(e.timeStamp-s.touchStartTime),2))&&(this.menuScrollStop(t),this.menuScroll(t),e.preventDefault()),delete s.touchY)}}},menuShow:function(t){if((t.dataSM("beforefirstshowfired")||(t.dataSM("beforefirstshowfired",!0),this.$root.triggerHandler("beforefirstshow.smapi",t[0])!==!1))&&this.$root.triggerHandler("beforeshow.smapi",t[0])!==!1&&(t.dataSM("shown-before",!0),canAnimate&&t.stop(!0,!0),!t.is(":visible"))){var e=t.dataSM("parent-a"),i=this.isCollapsible();if((this.opts.keepHighlighted||i)&&e.addClass("highlighted"),i)t.removeClass("sm-nowrap").css({zIndex:"",width:"auto",minWidth:"",maxWidth:"",top:"",left:"",marginLeft:"",marginTop:""});else{if(t.css("z-index",this.zIndexInc=(this.zIndexInc||this.getStartZIndex())+1),(this.opts.subMenusMinWidth||this.opts.subMenusMaxWidth)&&(t.css({width:"auto",minWidth:"",maxWidth:""}).addClass("sm-nowrap"),this.opts.subMenusMinWidth&&t.css("min-width",this.opts.subMenusMinWidth),this.opts.subMenusMaxWidth)){var s=this.getWidth(t);t.css("max-width",this.opts.subMenusMaxWidth),s>this.getWidth(t)&&t.removeClass("sm-nowrap").css("width",this.opts.subMenusMaxWidth)}this.menuPosition(t)}var o=function(){t.css("overflow","")};i?canAnimate&&this.opts.collapsibleShowFunction?this.opts.collapsibleShowFunction.call(this,t,o):t.show(this.opts.collapsibleShowDuration,o):canAnimate&&this.opts.showFunction?this.opts.showFunction.call(this,t,o):t.show(this.opts.showDuration,o),e.attr("aria-expanded","true"),t.attr({"aria-expanded":"true","aria-hidden":"false"}),this.visibleSubMenus.push(t),this.$root.triggerHandler("show.smapi",t[0])}},popupHide:function(t){this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0);var e=this;this.hideTimeout=setTimeout(function(){e.menuHideAll()},t?1:this.opts.hideTimeout)},popupShow:function(t,e){if(!this.opts.isPopup)return alert('SmartMenus jQuery Error:\n\nIf you want to show this menu via the "popupShow" method, set the isPopup:true option.'),void 0;if(this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0),this.$root.dataSM("shown-before",!0),canAnimate&&this.$root.stop(!0,!0),!this.$root.is(":visible")){this.$root.css({left:t,top:e});var i=this,s=function(){i.$root.css("overflow","")};canAnimate&&this.opts.showFunction?this.opts.showFunction.call(this,this.$root,s):this.$root.show(this.opts.showDuration,s),this.visibleSubMenus[0]=this.$root}},refresh:function(){this.destroy(!0),this.init(!0)},rootKeyDown:function(t){if(this.handleEvents())switch(t.keyCode){case 27:var e=this.activatedItems[0];if(e){this.menuHideAll(),e[0].focus();var i=e.dataSM("sub");i&&this.menuHide(i)}break;case 32:var s=$(t.target);if(s.is("a")&&this.handleItemEvents(s)){var i=s.dataSM("sub");i&&!i.is(":visible")&&(this.itemClick({currentTarget:t.target}),t.preventDefault())}}},rootOut:function(t){if(this.handleEvents()&&!this.isTouchMode()&&t.target!=this.$root[0]&&(this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0),!this.opts.showOnClick||!this.opts.hideOnClick)){var e=this;this.hideTimeout=setTimeout(function(){e.menuHideAll()},this.opts.hideTimeout)}},rootOver:function(t){this.handleEvents()&&!this.isTouchMode()&&t.target!=this.$root[0]&&this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0)},winResize:function(t){if(this.handleEvents()){if(!("onorientationchange"in window)||"orientationchange"==t.type){var e=this.isCollapsible();this.wasCollapsible&&e||(this.activatedItems.length&&this.activatedItems[this.activatedItems.length-1][0].blur(),this.menuHideAll()),this.wasCollapsible=e}}else if(this.$disableOverlay){var i=this.$root.offset();this.$disableOverlay.css({top:i.top,left:i.left,width:this.$root.outerWidth(),height:this.$root.outerHeight()})}}}}),$.fn.dataSM=function(t,e){return e?this.data(t+"_smartmenus",e):this.data(t+"_smartmenus")},$.fn.removeDataSM=function(t){return this.removeData(t+"_smartmenus")},$.fn.smartmenus=function(options){if("string"==typeof options){var args=arguments,method=options;return Array.prototype.shift.call(args),this.each(function(){var t=$(this).data("smartmenus");t&&t[method]&&t[method].apply(t,args)})}return this.each(function(){var dataOpts=$(this).data("sm-options")||null;if(dataOpts)try{dataOpts=eval("("+dataOpts+")")}catch(e){dataOpts=null,alert('ERROR\n\nSmartMenus jQuery init:\nInvalid "data-sm-options" attribute value syntax.')}new $.SmartMenus(this,$.extend({},$.fn.smartmenus.defaults,options,dataOpts))})},$.fn.smartmenus.defaults={isPopup:!1,mainMenuSubOffsetX:0,mainMenuSubOffsetY:0,subMenusSubOffsetX:0,subMenusSubOffsetY:0,subMenusMinWidth:"10em",subMenusMaxWidth:"20em",subIndicators:!0,subIndicatorsPos:"append",subIndicatorsText:"",scrollStep:30,scrollAccelerate:!0,showTimeout:250,hideTimeout:500,showDuration:0,showFunction:null,hideDuration:0,hideFunction:function(t,e){t.fadeOut(200,e)},collapsibleShowDuration:0,collapsibleShowFunction:function(t,e){t.slideDown(200,e)},collapsibleHideDuration:0,collapsibleHideFunction:function(t,e){t.slideUp(200,e)},showOnClick:!1,hideOnClick:!0,noMouseOver:!1,keepInViewport:!0,keepHighlighted:!0,markCurrentItem:!1,markCurrentTree:!0,rightToLeftSubMenus:!1,bottomToTopSubMenus:!1,collapsibleBehavior:"default"},$}); \ No newline at end of file diff --git a/documentation/html/lift_8h_source.html b/documentation/html/lift_8h_source.html new file mode 100644 index 0000000..5f4ded0 --- /dev/null +++ b/documentation/html/lift_8h_source.html @@ -0,0 +1,344 @@ + + + + + + + +RIT VEXU Core API: include/subsystems/lift.h Source File + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
lift.h
+
+
+
1#pragma once
+
2
+
3#include "vex.h"
+
4#include "../core/include/utils/pid.h"
+
5#include <iostream>
+
6#include <map>
+
7#include <atomic>
+
8#include <vector>
+
9
+
10using namespace vex;
+
11using namespace std;
+
12
+
20template <typename T>
+
21class Lift
+
22{
+
23 public:
+
24
+ +
32 {
+
33 double up_speed, down_speed;
+
34 double softstop_up, softstop_down;
+
35
+
36 PID::pid_config_t lift_pid_cfg;
+
37 };
+
38
+
60 Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map<T, double> &setpoint_map, limit *homing_switch=NULL)
+
61 : lift_motors(lift_motors), cfg(lift_cfg), lift_pid(cfg.lift_pid_cfg), setpoint_map(setpoint_map), homing_switch(homing_switch)
+
62 {
+
63
+
64 is_async = true;
+
65 setpoint = 0;
+
66
+
67 // Create a background task that is constantly updating the lift PID, if requested.
+
68 // Set once, and forget.
+
69 task t([](void* ptr){
+
70 Lift &lift = *((Lift*) ptr);
+
71
+
72 while(true)
+
73 {
+
74 if(lift.get_async())
+
75 lift.hold();
+
76
+
77 vexDelay(50);
+
78 }
+
79
+
80 return 0;
+
81 }, this);
+
82
+
83 }
+
84
+
93 void control_continuous(bool up_ctrl, bool down_ctrl)
+
94 {
+
95 static timer tmr;
+
96
+
97 double cur_pos = 0;
+
98
+
99 // Check if there's a hook for a custom sensor. If not, use the motors.
+
100 if(get_sensor == NULL)
+
101 cur_pos = lift_motors.position(rev);
+
102 else
+
103 cur_pos = get_sensor();
+
104
+
105 if(up_ctrl && cur_pos < cfg.softstop_up)
+
106 {
+
107 lift_motors.spin(directionType::fwd, cfg.up_speed, volt);
+
108 setpoint = cur_pos + .3;
+
109
+
110 // std::cout << "DEBUG OUT: UP " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n";
+
111
+
112 // Disable the PID while going UP.
+
113 is_async = false;
+
114 } else if(down_ctrl && cur_pos > cfg.softstop_down)
+
115 {
+
116 // Lower the lift slowly, at a rate defined by down_speed
+
117 if(setpoint > cfg.softstop_down)
+
118 setpoint = setpoint - (tmr.time(sec) * cfg.down_speed);
+
119 // std::cout << "DEBUG OUT: DOWN " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n";
+
120 is_async = true;
+
121 } else
+
122 {
+
123 // Hold the lift at the last setpoint
+
124 is_async = true;
+
125 }
+
126
+
127 tmr.reset();
+
128 }
+
129
+
138 void control_manual(bool up_btn, bool down_btn, int volt_up, int volt_down)
+
139 {
+
140 static bool down_hold = false;
+
141 static bool init = true;
+
142
+
143 // Allow for setting position while still calling this function
+
144 if(init || up_btn || down_btn)
+
145 {
+
146 init = false;
+
147 is_async = false;
+
148 }
+
149
+
150 double rev = lift_motors.position(rotationUnits::rev);
+
151
+
152 if(rev < cfg.softstop_down && down_btn)
+
153 down_hold = true;
+
154 else if( !down_btn )
+
155 down_hold = false;
+
156
+
157 if(up_btn && rev < cfg.softstop_up)
+
158 lift_motors.spin(directionType::fwd, volt_up, voltageUnits::volt);
+
159 else if(down_btn && rev > cfg.softstop_down && !down_hold)
+
160 lift_motors.spin(directionType::rev, volt_down, voltageUnits::volt);
+
161 else
+
162 lift_motors.spin(directionType::fwd, 0, voltageUnits::volt);
+
163
+
164 }
+
165
+
177 void control_setpoints(bool up_step, bool down_step, vector<T> pos_list)
+
178 {
+
179 // Make sure inputs are only processed on the rising edge of the button
+
180 static bool up_last = up_step, down_last = down_step;
+
181
+
182 bool up_rising = up_step && !up_last;
+
183 bool down_rising = down_step && !down_last;
+
184
+
185 up_last = up_step;
+
186 down_last = down_step;
+
187
+
188 static int cur_index = 0;
+
189
+
190 // Avoid an index overflow. Shouldn't happen unless the user changes pos_list between calls.
+
191 if(cur_index >= pos_list.size())
+
192 cur_index = pos_list.size() - 1;
+
193
+
194 // Increment or decrement the index of the list, bringing it up or down.
+
195 if(up_rising && cur_index < (pos_list.size() - 1))
+
196 cur_index++;
+
197 else if(down_rising && cur_index > 0)
+
198 cur_index--;
+
199
+
200 // Set the lift to hold the position in the background with the PID loop
+
201 set_position(pos_list[cur_index]);
+
202 is_async = true;
+
203
+
204 }
+
205
+
214 bool set_position(T pos)
+
215 {
+
216 this->setpoint = setpoint_map[pos];
+
217 is_async = true;
+
218
+
219 return (lift_pid.get_target() == this->setpoint) && lift_pid.is_on_target();
+
220 }
+
221
+
228 bool set_setpoint(double val)
+
229 {
+
230 this->setpoint = val;
+
231 return (lift_pid.get_target() == this->setpoint) && lift_pid.is_on_target();
+
232 }
+
233
+ +
238 {
+
239 return this->setpoint;
+
240 }
+
241
+
246 void hold()
+
247 {
+
248 lift_pid.set_target(setpoint);
+
249 // std::cout << "DEBUG OUT: SETPOINT " << setpoint << "\n";
+
250
+
251 if(get_sensor != NULL)
+
252 lift_pid.update(get_sensor());
+
253 else
+
254 lift_pid.update(lift_motors.position(rev));
+
255
+
256 // std::cout << "DEBUG OUT: ROTATION " << lift_motors.rotation(rev) << "\n\n";
+
257
+
258 lift_motors.spin(fwd, lift_pid.get(), volt);
+
259 }
+
260
+
265 void home()
+
266 {
+
267 static timer tmr;
+
268 tmr.reset();
+
269
+
270 while(tmr.time(sec) < 3)
+
271 {
+
272 lift_motors.spin(directionType::rev, 6, volt);
+
273
+
274 if (homing_switch == NULL && lift_motors.current(currentUnits::amp) > 1.5)
+
275 break;
+
276 else if (homing_switch != NULL && homing_switch->pressing())
+
277 break;
+
278 }
+
279
+
280 if(reset_sensor != NULL)
+
281 reset_sensor();
+
282
+
283 lift_motors.resetPosition();
+
284 lift_motors.stop();
+
285
+
286 }
+
287
+ +
292 {
+
293 return is_async;
+
294 }
+
295
+
301 void set_async(bool val)
+
302 {
+
303 this->is_async = val;
+
304 }
+
305
+
315 void set_sensor_function(double (*fn_ptr) (void))
+
316 {
+
317 this->get_sensor = fn_ptr;
+
318 }
+
319
+
326 void set_sensor_reset(void (*fn_ptr) (void))
+
327 {
+
328 this->reset_sensor = fn_ptr;
+
329 }
+
330
+
331 private:
+
332
+
333 motor_group &lift_motors;
+
334 lift_cfg_t &cfg;
+
335 PID lift_pid;
+
336 map<T, double> &setpoint_map;
+
337 limit *homing_switch;
+
338
+
339 atomic<double> setpoint;
+
340 atomic<bool> is_async;
+
341
+
342 double (*get_sensor)(void) = NULL;
+
343 void (*reset_sensor)(void) = NULL;
+
344
+
345
+
346};
+
Definition: lift.h:22
+
void set_sensor_function(double(*fn_ptr)(void))
Definition: lift.h:315
+
bool set_setpoint(double val)
Definition: lift.h:228
+
bool get_async()
Definition: lift.h:291
+
void set_sensor_reset(void(*fn_ptr)(void))
Definition: lift.h:326
+
void control_setpoints(bool up_step, bool down_step, vector< T > pos_list)
Definition: lift.h:177
+
void set_async(bool val)
Definition: lift.h:301
+
void hold()
Definition: lift.h:246
+
Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map< T, double > &setpoint_map, limit *homing_switch=NULL)
Definition: lift.h:60
+
bool set_position(T pos)
Definition: lift.h:214
+
void home()
Definition: lift.h:265
+
void control_manual(bool up_btn, bool down_btn, int volt_up, int volt_down)
Definition: lift.h:138
+
double get_setpoint()
Definition: lift.h:237
+
void control_continuous(bool up_ctrl, bool down_ctrl)
Definition: lift.h:93
+
Definition: pid.h:24
+
double get_target()
Definition: pid.cpp:97
+
void set_target(double target)
Definition: pid.cpp:105
+
double update(double sensor_val) override
Definition: pid.cpp:25
+
double get() override
Definition: pid.cpp:81
+
bool is_on_target() override
Definition: pid.cpp:124
+
Definition: lift.h:32
+
Definition: pid.h:41
+
+ + + + diff --git a/documentation/html/math__util_8h_source.html b/documentation/html/math__util_8h_source.html new file mode 100644 index 0000000..179c2b5 --- /dev/null +++ b/documentation/html/math__util_8h_source.html @@ -0,0 +1,128 @@ + + + + + + + +RIT VEXU Core API: include/utils/math_util.h Source File + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
math_util.h
+
+
+
1#pragma once
+
2#include "math.h"
+
3#include "vex.h"
+
4#include <vector>
+
5
+
13double clamp(double value, double low, double high);
+
14
+
21double sign(double x);
+
22
+
23double wrap_angle_deg(double input);
+
24double wrap_angle_rad(double input);
+
25
+
26/*
+
27Calculates the variance of a set of numbers (needed for linear regression)
+
28https://en.wikipedia.org/wiki/Variance
+
29@param values the values for which the variance is taken
+
30@param mean the average of values
+
31*/
+
32double variance(std::vector<double> const &values, double mean);
+
33
+
34
+
35/*
+
36Calculates the average of a vector of doubles
+
37@param values the list of values for which the average is taken
+
38*/
+
39double mean(std::vector<double> const &values);
+
40
+
41/*
+
42Calculates the covariance of a set of points (needed for linear regression)
+
43https://en.wikipedia.org/wiki/Covariance
+
44
+
45@param points the points for which the covariance is taken
+
46@param meanx the mean value of all x coordinates in points
+
47@param meany the mean value of all y coordinates in points
+
48*/
+
49double covariance(std::vector<std::pair<double, double>> const &points, double meanx, double meany);
+
50
+
51/*
+
52Calculates the slope and y intercept of the line of best fit for the data
+
53@param points the points for the data
+
54*/
+
55std::pair<double, double> calculate_linear_regression(std::vector<std::pair<double, double>> const &points);
+
56
+
+ + + + diff --git a/documentation/html/md_README.html b/documentation/html/md_README.html new file mode 100644 index 0000000..4b959b6 --- /dev/null +++ b/documentation/html/md_README.html @@ -0,0 +1,109 @@ + + + + + + + +RIT VEXU Core API: Core + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
Core
+
+
+

This is the host repository for the custom VEX libraries used by the RIT VEXU team

+

+Getting Started

+

In order to simply use this repo, you can either clone it into your VEXcode project folder, or download the .zip and place it into a core/ subfolder. Then follow the instructions for setting up compilation at Wiki/BuildSystem

+

If you wish to contribute, follow the instructions at Wiki/ProjectSetup

+

+Features

+

Here is the current feature list this repo provides:

+

Subsystems (See Wiki/Subsystems):
+

    +
  • Tank drivetrain (user control / autonomous)
  • +
  • Mecanum drivetrain (user control / autonomous)
  • +
  • Odometry
  • +
  • Flywheel
  • +
  • Lift
  • +
  • Custom encoders
  • +
+

Utilities (See Wiki/Utilites):
+

    +
  • PID controller
  • +
  • FeedForward controller
  • +
  • Trapezoidal motion profile controller
  • +
  • Pure Pursuit
  • +
  • Generic auto program builder
  • +
  • Auto program UI selector
  • +
  • Mathematical classes (Vector2D, Moving Average)
  • +
+
+
+ + + + diff --git a/documentation/html/mecanum__drive_8h_source.html b/documentation/html/mecanum__drive_8h_source.html new file mode 100644 index 0000000..11f2c6c --- /dev/null +++ b/documentation/html/mecanum__drive_8h_source.html @@ -0,0 +1,151 @@ + + + + + + + +RIT VEXU Core API: include/subsystems/mecanum_drive.h Source File + + + + + + + + + +
+
+ + + + + + +
+
RIT VEXU Core API +
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
mecanum_drive.h
+
+
+
1#pragma once
+
2
+
3#include "vex.h"
+
4#include "../core/include/utils/pid.h"
+
5
+
6#ifndef PI
+
7#define PI 3.141592654
+
8#endif
+
9
+ +
15{
+
16
+
17 public:
+
18
+ +
23 {
+
24 // PID configurations for autonomous driving
+
25 PID::pid_config_t drive_pid_conf;
+
26 PID::pid_config_t drive_gyro_pid_conf;
+
27 PID::pid_config_t turn_pid_conf;
+
28
+
29 // Diameter of the mecanum wheels
+
30 double drive_wheel_diam;
+
31
+
32 // Diameter of the perpendicular undriven encoder wheel
+
33 double lateral_wheel_diam;
+
34
+
35 // Width between the center of the left and right wheels
+
36 double wheelbase_width;
+
37
+
38 };
+
39
+
43 MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear,
+
44 vex::rotation *lateral_wheel=NULL, vex::inertial *imu=NULL, mecanumdrive_config_t *config=NULL);
+
45
+
54 void drive_raw(double direction_deg, double magnitude, double rotation);
+
55
+
66 void drive(double left_y, double left_x, double right_x, int power=2);
+
67
+
80 bool auto_drive(double inches, double direction, double speed, bool gyro_correction=true);
+
81
+
92 bool auto_turn(double degrees, double speed, bool ignore_imu=false);
+
93
+
94 private:
+
95
+
96 vex::motor &left_front, &right_front, &left_rear, &right_rear;
+
97
+ +
99 vex::rotation *lateral_wheel;
+
100 vex::inertial *imu;
+
101
+
102 PID *drive_pid = NULL;
+
103 PID *drive_gyro_pid = NULL;
+
104 PID *turn_pid = NULL;
+
105
+
106 bool init = true;
+
107
+
108};
+
Definition: mecanum_drive.h:15
+
void drive_raw(double direction_deg, double magnitude, double rotation)
Definition: mecanum_drive.cpp:34
+
bool auto_drive(double inches, double direction, double speed, bool gyro_correction=true)
Definition: mecanum_drive.cpp:98
+
void drive(double left_y, double left_x, double right_x, int power=2)
Definition: mecanum_drive.cpp:68
+
bool auto_turn(double degrees, double speed, bool ignore_imu=false)
Definition: mecanum_drive.cpp:218
+
Definition: pid.h:24
+
Definition: mecanum_drive.h:23
+
Definition: pid.h:41
+
+ + + + diff --git a/documentation/html/menu.js b/documentation/html/menu.js new file mode 100644 index 0000000..b0b2693 --- /dev/null +++ b/documentation/html/menu.js @@ -0,0 +1,136 @@ +/* + @licstart The following is the entire license notice for the JavaScript code in this file. + + The MIT License (MIT) + + Copyright (C) 1997-2020 by Dimitri van Heesch + + Permission is hereby granted, free of charge, to any person obtaining a copy of this software + and associated documentation files (the "Software"), to deal in the Software without restriction, + including without limitation the rights to use, copy, modify, merge, publish, distribute, + sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in all copies or + substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING + BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, + DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + @licend The above is the entire license notice for the JavaScript code in this file + */ +function initMenu(relPath,searchEnabled,serverSide,searchPage,search) { + function makeTree(data,relPath) { + var result=''; + if ('children' in data) { + result+='
    '; + for (var i in data.children) { + var url; + var link; + link = data.children[i].url; + if (link.substring(0,1)=='^') { + url = link.substring(1); + } else { + url = relPath+link; + } + result+='
  • '+ + data.children[i].text+''+ + makeTree(data.children[i],relPath)+'
  • '; + } + result+='
'; + } + return result; + } + var searchBoxHtml; + if (searchEnabled) { + if (serverSide) { + searchBoxHtml='
'+ + '
'+ + '
 '+ + ''+ + '
'+ + '
'+ + '
'+ + '
'; + } else { + searchBoxHtml='
'+ + ''+ + ' '+ + ''+ + ''+ + ''+ + ''+ + ''+ + '
'; + } + } + + $('#main-nav').before('
'+ + ''+ + ''+ + '
'); + $('#main-nav').append(makeTree(menudata,relPath)); + $('#main-nav').children(':first').addClass('sm sm-dox').attr('id','main-menu'); + if (searchBoxHtml) { + $('#main-menu').append('
  • '); + } + var $mainMenuState = $('#main-menu-state'); + var prevWidth = 0; + if ($mainMenuState.length) { + function initResizableIfExists() { + if (typeof initResizable==='function') initResizable(); + } + // animate mobile menu + $mainMenuState.change(function(e) { + var $menu = $('#main-menu'); + var options = { duration: 250, step: initResizableIfExists }; + if (this.checked) { + options['complete'] = function() { $menu.css('display', 'block') }; + $menu.hide().slideDown(options); + } else { + options['complete'] = function() { $menu.css('display', 'none') }; + $menu.show().slideUp(options); + } + }); + // set default menu visibility + function resetState() { + var $menu = $('#main-menu'); + var $mainMenuState = $('#main-menu-state'); + var newWidth = $(window).outerWidth(); + if (newWidth!=prevWidth) { + if ($(window).outerWidth()<768) { + $mainMenuState.prop('checked',false); $menu.hide(); + $('#searchBoxPos1').html(searchBoxHtml); + $('#searchBoxPos2').hide(); + } else { + $menu.show(); + $('#searchBoxPos1').empty(); + $('#searchBoxPos2').html(searchBoxHtml); + $('#searchBoxPos2').show(); + } + if (typeof searchBox!=='undefined') { + searchBox.CloseResultsWindow(); + } + prevWidth = newWidth; + } + } + $(window).ready(function() { resetState(); initResizableIfExists(); }); + $(window).resize(resetState); + } + $('#main-menu').smartmenus(); +} +/* @license-end */ diff --git a/documentation/html/menudata.js b/documentation/html/menudata.js new file mode 100644 index 0000000..abafd6a --- /dev/null +++ b/documentation/html/menudata.js @@ -0,0 +1,104 @@ +/* + @licstart The following is the entire license notice for the JavaScript code in this file. + + The MIT License (MIT) + + Copyright (C) 1997-2020 by Dimitri van Heesch + + Permission is hereby granted, free of charge, to any person obtaining a copy of this software + and associated documentation files (the "Software"), to deal in the Software without restriction, + including without limitation the rights to use, copy, modify, merge, publish, distribute, + sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in all copies or + substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING + BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, + DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + @licend The above is the entire license notice for the JavaScript code in this file +*/ +var menudata={children:[ +{text:"Main Page",url:"index.html"}, +{text:"Related Pages",url:"pages.html"}, +{text:"Classes",url:"annotated.html",children:[ +{text:"Class List",url:"annotated.html"}, +{text:"Class Index",url:"classes.html"}, +{text:"Class Hierarchy",url:"hierarchy.html"}, +{text:"Class Members",url:"functions.html",children:[ +{text:"All",url:"functions.html",children:[ +{text:"a",url:"functions.html#index_a"}, +{text:"b",url:"functions_b.html#index_b"}, +{text:"c",url:"functions_c.html#index_c"}, +{text:"d",url:"functions_d.html#index_d"}, +{text:"e",url:"functions_e.html#index_e"}, +{text:"f",url:"functions_f.html#index_f"}, +{text:"g",url:"functions_g.html#index_g"}, +{text:"h",url:"functions_h.html#index_h"}, +{text:"i",url:"functions_i.html#index_i"}, +{text:"k",url:"functions_k.html#index_k"}, +{text:"l",url:"functions_l.html#index_l"}, +{text:"m",url:"functions_m.html#index_m"}, +{text:"n",url:"functions_n.html#index_n"}, +{text:"o",url:"functions_o.html#index_o"}, +{text:"p",url:"functions_p.html#index_p"}, +{text:"r",url:"functions_r.html#index_r"}, +{text:"s",url:"functions_s.html#index_s"}, +{text:"t",url:"functions_t.html#index_t"}, +{text:"u",url:"functions_u.html#index_u"}, +{text:"v",url:"functions_v.html#index_v"}, +{text:"w",url:"functions_w.html#index_w"}, +{text:"x",url:"functions_x.html#index_x"}, +{text:"y",url:"functions_y.html#index_y"}, +{text:"z",url:"functions_z.html#index_z"}]}, +{text:"Functions",url:"functions_func.html",children:[ +{text:"a",url:"functions_func.html#index_a"}, +{text:"b",url:"functions_func.html#index_b"}, +{text:"c",url:"functions_func.html#index_c"}, +{text:"d",url:"functions_func.html#index_d"}, +{text:"e",url:"functions_func.html#index_e"}, +{text:"f",url:"functions_func.html#index_f"}, +{text:"g",url:"functions_func.html#index_g"}, +{text:"h",url:"functions_func.html#index_h"}, +{text:"i",url:"functions_func.html#index_i"}, +{text:"l",url:"functions_func.html#index_l"}, +{text:"m",url:"functions_func.html#index_m"}, +{text:"n",url:"functions_func.html#index_n"}, +{text:"o",url:"functions_func.html#index_o"}, +{text:"p",url:"functions_func.html#index_p"}, +{text:"r",url:"functions_func.html#index_r"}, +{text:"s",url:"functions_func.html#index_s"}, +{text:"t",url:"functions_func.html#index_t"}, +{text:"u",url:"functions_func.html#index_u"}, +{text:"v",url:"functions_func.html#index_v"}, +{text:"w",url:"functions_func.html#index_w"}]}, +{text:"Variables",url:"functions_vars.html",children:[ +{text:"a",url:"functions_vars.html#index_a"}, +{text:"b",url:"functions_vars.html#index_b"}, +{text:"c",url:"functions_vars.html#index_c"}, +{text:"d",url:"functions_vars.html#index_d"}, +{text:"e",url:"functions_vars.html#index_e"}, +{text:"f",url:"functions_vars.html#index_f"}, +{text:"h",url:"functions_vars.html#index_h"}, +{text:"i",url:"functions_vars.html#index_i"}, +{text:"k",url:"functions_vars.html#index_k"}, +{text:"l",url:"functions_vars.html#index_l"}, +{text:"m",url:"functions_vars.html#index_m"}, +{text:"n",url:"functions_vars.html#index_n"}, +{text:"o",url:"functions_vars.html#index_o"}, +{text:"p",url:"functions_vars.html#index_p"}, +{text:"r",url:"functions_vars.html#index_r"}, +{text:"s",url:"functions_vars.html#index_s"}, +{text:"t",url:"functions_vars.html#index_t"}, +{text:"v",url:"functions_vars.html#index_v"}, +{text:"w",url:"functions_vars.html#index_w"}, +{text:"x",url:"functions_vars.html#index_x"}, +{text:"y",url:"functions_vars.html#index_y"}, +{text:"z",url:"functions_vars.html#index_z"}]}, +{text:"Enumerations",url:"functions_enum.html"}]}]}, +{text:"Files",url:"files.html",children:[ +{text:"File List",url:"files.html"}]}]} diff --git a/documentation/html/motion__controller_8h_source.html b/documentation/html/motion__controller_8h_source.html new file mode 100644 index 0000000..0c0ee99 --- /dev/null +++ b/documentation/html/motion__controller_8h_source.html @@ -0,0 +1,158 @@ + + + + + + + +RIT VEXU Core API: include/utils/motion_controller.h Source File + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    motion_controller.h
    +
    +
    +
    1#pragma once
    +
    2#include "../core/include/utils/pid.h"
    +
    3#include "../core/include/utils/feedforward.h"
    +
    4#include "../core/include/utils/trapezoid_profile.h"
    +
    5#include "../core/include/utils/feedback_base.h"
    +
    6#include "../core/include/subsystems/tank_drive.h"
    +
    7#include "vex.h"
    +
    8
    + +
    26{
    +
    27 public:
    +
    28
    +
    34 typedef struct
    +
    35 {
    +
    36 double max_v;
    +
    37 double accel;
    + + + +
    41
    + +
    52
    +
    57 void init(double start_pt, double end_pt) override;
    +
    58
    +
    65 double update(double sensor_val) override;
    +
    66
    +
    70 double get() override;
    +
    71
    +
    79 void set_limits(double lower, double upper) override;
    +
    80
    +
    85 bool is_on_target() override;
    +
    86
    + +
    91
    +
    110 static FeedForward::ff_config_t tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct=0.6, double duration=2);
    +
    111
    +
    112 private:
    +
    113
    +
    114 m_profile_cfg_t config;
    +
    115
    +
    116 PID pid;
    +
    117 FeedForward ff;
    +
    118 TrapezoidProfile profile;
    +
    119
    +
    120 double lower_limit = 0, upper_limit = 0;
    +
    121 double out = 0;
    +
    122 motion_t cur_motion;
    +
    123
    +
    124 vex::timer tmr;
    +
    125
    +
    126};
    +
    Definition: feedforward.h:30
    +
    Definition: feedback_base.h:11
    +
    Definition: motion_controller.h:26
    +
    static FeedForward::ff_config_t tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct=0.6, double duration=2)
    Definition: motion_controller.cpp:106
    +
    double get() override
    Definition: motion_controller.cpp:54
    +
    double update(double sensor_val) override
    Update the motion profile with a new sensor value.
    Definition: motion_controller.cpp:37
    +
    void set_limits(double lower, double upper) override
    Definition: motion_controller.cpp:65
    +
    bool is_on_target() override
    Definition: motion_controller.cpp:75
    +
    motion_t get_motion()
    Definition: motion_controller.cpp:83
    +
    void init(double start_pt, double end_pt) override
    Initialize the motion profile for a new movement This will also reset the PID and profile timers.
    Definition: motion_controller.cpp:24
    +
    Definition: odometry_tank.h:18
    +
    Definition: pid.h:24
    +
    Definition: tank_drive.h:23
    +
    Definition: trapezoid_profile.h:35
    +
    Definition: feedforward.h:42
    +
    Definition: motion_controller.h:35
    +
    PID::pid_config_t pid_cfg
    configuration parameters for the internal PID controller
    Definition: motion_controller.h:38
    +
    double max_v
    the maximum velocity the robot can drive
    Definition: motion_controller.h:36
    +
    double accel
    the most acceleration the robot can do
    Definition: motion_controller.h:37
    +
    FeedForward::ff_config_t ff_cfg
    configuration parameters for the internal
    Definition: motion_controller.h:39
    +
    Definition: pid.h:41
    +
    Definition: trapezoid_profile.h:7
    +
    + + + + diff --git a/documentation/html/moving__average_8h_source.html b/documentation/html/moving__average_8h_source.html new file mode 100644 index 0000000..f820872 --- /dev/null +++ b/documentation/html/moving__average_8h_source.html @@ -0,0 +1,129 @@ + + + + + + + +RIT VEXU Core API: include/utils/moving_average.h Source File + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    moving_average.h
    +
    +
    +
    1#include <vector>
    +
    2
    + +
    16 public:
    +
    17 /*
    +
    18 * Create a moving average calculator with 0 as the default value
    +
    19 *
    +
    20 * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading
    +
    21 */
    +
    22 MovingAverage(int buffer_size);
    +
    23 /*
    +
    24 * Create a moving average calculator with a specified default value
    +
    25 * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading
    +
    26 * @param starting_value The value that the average will be before any data is added
    +
    27 */
    +
    28 MovingAverage(int buffer_size, double starting_value);
    +
    29
    +
    30 /*
    +
    31 * Add a reading to the buffer
    +
    32 * Before:
    +
    33 * [ 1 1 2 2 3 3] => 2
    +
    34 * ^
    +
    35 * After:
    +
    36 * [ 2 1 2 2 3 3] => 2.16
    +
    37 * ^
    +
    38 * @param n the sample that will be added to the moving average.
    +
    39 */
    +
    40 void add_entry(double n);
    +
    41
    +
    46 double get_average();
    +
    47
    +
    52 int get_size();
    +
    53
    +
    54
    +
    55 private:
    +
    56 int buffer_index; //index of the next value to be overridden
    +
    57 std::vector<double> buffer; //all current data readings we've taken
    +
    58 double current_avg; //the current value of the data
    +
    59
    +
    60};
    +
    Definition: moving_average.h:15
    +
    void add_entry(double n)
    Definition: moving_average.cpp:50
    +
    double get_average()
    Definition: moving_average.cpp:63
    +
    int get_size()
    Definition: moving_average.cpp:68
    +
    + + + + diff --git a/documentation/html/nav_f.png b/documentation/html/nav_f.png new file mode 100644 index 0000000000000000000000000000000000000000..72a58a529ed3a9ed6aa0c51a79cf207e026deee2 GIT binary patch literal 153 zcmeAS@N?(olHy`uVBq!ia0vp^j6iI`!2~2XGqLUlQVE_ejv*C{Z|{2ZH7M}7UYxc) zn!W8uqtnIQ>_z8U literal 0 HcmV?d00001 diff --git a/documentation/html/nav_fd.png b/documentation/html/nav_fd.png new file mode 100644 index 0000000000000000000000000000000000000000..032fbdd4c54f54fa9a2e6423b94ef4b2ebdfaceb GIT binary patch literal 169 zcmeAS@N?(olHy`uVBq!ia0vp^j6iI`!2~2XGqLUlQU#tajv*C{Z|C~*H7f|XvG1G8 zt7aS*L7xwMeS}!z6R#{C5tIw-s~AJ==F^i}x3XyJseHR@yF& zerFf(Zf;Dd{+(0lDIROL@Sj-Ju2JQ8&-n%4%q?>|^bShc&lR?}7HeMo@BDl5N(aHY Uj$gdr1MOz;boFyt=akR{0D!zeaR2}S literal 0 HcmV?d00001 diff --git a/documentation/html/nav_g.png b/documentation/html/nav_g.png new file mode 100644 index 0000000000000000000000000000000000000000..2093a237a94f6c83e19ec6e5fd42f7ddabdafa81 GIT binary patch literal 95 zcmeAS@N?(olHy`uVBq!ia0vp^j6lrB!3HFm1ilyoDK$?Q$B+ufw|5PB85lU25BhtE tr?otc=hd~V+ws&_A@j8Fiv!KF$B+ufw|5=67#uj90@pIL wZ=Q8~_Ju`#59=RjDrmm`tMD@M=!-l18IR?&vFVdQ&MBb@0HFXL6W-eg#Jd_@e6*DPn)w;=|1H}Zvm9l6xXXB%>yL=NQU;mg M>FVdQ&MBb@0Bdt1Qvd(} literal 0 HcmV?d00001 diff --git a/documentation/html/odometry__3wheel_8h_source.html b/documentation/html/odometry__3wheel_8h_source.html new file mode 100644 index 0000000..e45a6db --- /dev/null +++ b/documentation/html/odometry__3wheel_8h_source.html @@ -0,0 +1,127 @@ + + + + + + + +RIT VEXU Core API: include/subsystems/odometry/odometry_3wheel.h Source File + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    odometry_3wheel.h
    +
    +
    +
    1#pragma once
    +
    2#include "../core/include/subsystems/odometry/odometry_base.h"
    +
    3#include "../core/include/subsystems/tank_drive.h"
    +
    4#include "../core/include/subsystems/custom_encoder.h"
    +
    5
    + +
    33{
    +
    34 public:
    +
    35
    +
    40 typedef struct
    +
    41 {
    + + +
    44 double wheel_diam;
    + +
    47
    +
    57 Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, odometry3wheel_cfg_t &cfg, bool is_async=true);
    +
    58
    +
    65 position_t update() override;
    +
    66
    +
    75 void tune(vex::controller &con, TankDrive &drive);
    +
    76
    +
    77 private:
    +
    78
    +
    91 static position_t calculate_new_pos(double lside_delta_deg, double rside_delta_deg, double offax_delta_deg, position_t old_pos, odometry3wheel_cfg_t cfg);
    +
    92
    +
    93 CustomEncoder &lside_fwd, &rside_fwd, &off_axis;
    + +
    95
    +
    96
    +
    97};
    +
    Definition: custom_encoder.h:9
    +
    Definition: odometry_3wheel.h:33
    +
    position_t update() override
    Definition: odometry_3wheel.cpp:15
    +
    void tune(vex::controller &con, TankDrive &drive)
    Definition: odometry_3wheel.cpp:135
    +
    Definition: odometry_base.h:33
    +
    Definition: tank_drive.h:23
    +
    Definition: odometry_3wheel.h:41
    +
    double wheel_diam
    Definition: odometry_3wheel.h:44
    +
    double wheelbase_dist
    Definition: odometry_3wheel.h:42
    +
    double off_axis_center_dist
    Definition: odometry_3wheel.h:43
    +
    Definition: odometry_base.h:14
    +
    + + + + diff --git a/documentation/html/odometry__base_8h_source.html b/documentation/html/odometry__base_8h_source.html new file mode 100644 index 0000000..0d6f32c --- /dev/null +++ b/documentation/html/odometry__base_8h_source.html @@ -0,0 +1,173 @@ + + + + + + + +RIT VEXU Core API: include/subsystems/odometry/odometry_base.h Source File + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    odometry_base.h
    +
    +
    +
    1#pragma once
    +
    2
    +
    3#include "vex.h"
    +
    4#include "../core/include/robot_specs.h"
    +
    5
    +
    6#ifndef PI
    +
    7#define PI 3.141592654
    +
    8#endif
    +
    9
    +
    13typedef struct
    +
    14{
    +
    15 double x;
    +
    16 double y;
    +
    17 double rot;
    + +
    19
    + +
    33{
    +
    34public:
    +
    35
    +
    41 OdometryBase(bool is_async);
    +
    42
    + +
    48
    +
    53 virtual void set_position(const position_t& newpos=zero_pos);
    +
    54
    +
    59 virtual position_t update() = 0;
    +
    60
    +
    68 static int background_task(void* ptr);
    +
    69
    +
    75 void end_async();
    +
    76
    +
    83 static double pos_diff(position_t start_pos, position_t end_pos);
    +
    84
    +
    91 static double rot_diff(position_t pos1, position_t pos2);
    +
    92
    +
    101 static double smallest_angle(double start_deg, double end_deg);
    +
    102
    +
    104 bool end_task = false;
    +
    105
    +
    110 double get_speed();
    +
    111
    +
    116 double get_accel();
    +
    117
    +
    122 double get_angular_speed_deg();
    +
    123
    +
    128 double get_angular_accel_deg();
    +
    129
    +
    133 inline static constexpr position_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L};
    +
    134
    +
    135protected:
    +
    139 vex::task *handle;
    +
    140
    +
    144 vex::mutex mut;
    +
    145
    + +
    150
    +
    151 double speed;
    +
    152 double accel;
    + + +
    155};
    +
    Definition: odometry_base.h:33
    +
    double ang_accel_deg
    Definition: odometry_base.h:154
    +
    static int background_task(void *ptr)
    Definition: odometry_base.cpp:22
    +
    double ang_speed_deg
    Definition: odometry_base.h:153
    +
    double get_accel()
    Definition: odometry_base.cpp:123
    +
    virtual void set_position(const position_t &newpos=zero_pos)
    Definition: odometry_base.cpp:63
    +
    position_t get_position(void)
    Definition: odometry_base.cpp:48
    +
    double get_angular_accel_deg()
    Definition: odometry_base.cpp:141
    +
    virtual position_t update()=0
    +
    double speed
    Definition: odometry_base.h:151
    +
    position_t current_pos
    Definition: odometry_base.h:149
    +
    static double smallest_angle(double start_deg, double end_deg)
    Definition: odometry_base.cpp:99
    +
    static constexpr position_t zero_pos
    Definition: odometry_base.h:133
    +
    vex::mutex mut
    Definition: odometry_base.h:144
    +
    static double pos_diff(position_t start_pos, position_t end_pos)
    Definition: odometry_base.cpp:78
    +
    double accel
    Definition: odometry_base.h:152
    +
    double get_speed()
    Definition: odometry_base.cpp:114
    +
    static double rot_diff(position_t pos1, position_t pos2)
    Definition: odometry_base.cpp:89
    +
    void end_async()
    Definition: odometry_base.cpp:40
    +
    vex::task * handle
    Definition: odometry_base.h:139
    +
    bool end_task
    end_task is true if we instruct the odometry thread to shut down
    Definition: odometry_base.h:104
    +
    double get_angular_speed_deg()
    Definition: odometry_base.cpp:132
    +
    Definition: odometry_base.h:14
    +
    double rot
    rotation in the world
    Definition: odometry_base.h:17
    +
    double x
    x position in the world
    Definition: odometry_base.h:15
    +
    double y
    y position in the world
    Definition: odometry_base.h:16
    +
    + + + + diff --git a/documentation/html/odometry__tank_8h_source.html b/documentation/html/odometry__tank_8h_source.html new file mode 100644 index 0000000..6c0ef8b --- /dev/null +++ b/documentation/html/odometry__tank_8h_source.html @@ -0,0 +1,127 @@ + + + + + + + +RIT VEXU Core API: include/subsystems/odometry/odometry_tank.h Source File + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    odometry_tank.h
    +
    +
    +
    1#pragma once
    +
    2
    +
    3#include "../core/include/subsystems/odometry/odometry_base.h"
    +
    4#include "../core/include/subsystems/custom_encoder.h"
    +
    5#include "../core/include/utils/vector2d.h"
    +
    6#include "../core/include/robot_specs.h"
    +
    7
    +
    8static int background_task(void* odom_obj);
    +
    9
    +
    10
    + +
    18{
    +
    19public:
    +
    28 OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true);
    +
    29
    +
    39 OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true);
    +
    40
    +
    45 position_t update() override;
    +
    46
    +
    51 void set_position(const position_t &newpos=zero_pos) override;
    +
    52
    +
    53
    +
    54
    +
    55private:
    +
    59 static position_t calculate_new_pos(robot_specs_t &config, position_t &stored_info, double lside_diff, double rside_diff, double angle_deg);
    +
    60
    +
    61 vex::motor_group *left_side, *right_side;
    +
    62 CustomEncoder *left_enc, *right_enc;
    +
    63 vex::inertial *imu;
    +
    64 robot_specs_t &config;
    +
    65
    +
    66 double rotation_offset = 0;
    +
    67
    +
    68};
    +
    Definition: custom_encoder.h:9
    +
    Definition: odometry_base.h:33
    +
    static constexpr position_t zero_pos
    Definition: odometry_base.h:133
    +
    Definition: odometry_tank.h:18
    +
    position_t update() override
    Definition: odometry_tank.cpp:46
    +
    void set_position(const position_t &newpos=zero_pos) override
    Definition: odometry_tank.cpp:33
    +
    Definition: odometry_base.h:14
    +
    Definition: robot_specs.h:12
    +
    + + + + diff --git a/documentation/html/open.png b/documentation/html/open.png new file mode 100644 index 0000000000000000000000000000000000000000..30f75c7efe2dd0c9e956e35b69777a02751f048b GIT binary patch literal 123 zcmeAS@N?(olHy`uVBq!ia0vp^oFL4>1|%O$WD@{VPM$7~Ar*{o?;hlAFyLXmaDC0y znK1_#cQqJWPES%4Uujug^TE?jMft$}Eq^WaR~)%f)vSNs&gek&x%A9X9sM + + + + + + +RIT VEXU Core API: Related Pages + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    Related Pages
    +
    +
    +
    Here is a list of all related documentation pages:
    + + +
     Core
    +
    +
    + + + + diff --git a/documentation/html/pid_8h_source.html b/documentation/html/pid_8h_source.html new file mode 100644 index 0000000..62a0607 --- /dev/null +++ b/documentation/html/pid_8h_source.html @@ -0,0 +1,177 @@ + + + + + + + +RIT VEXU Core API: include/utils/pid.h Source File + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    pid.h
    +
    +
    +
    1#pragma once
    +
    2
    +
    3#include <cmath>
    +
    4#include "vex.h"
    +
    5#include "../core/include/utils/feedback_base.h"
    +
    6
    +
    7using namespace vex;
    +
    8
    +
    23class PID : public Feedback
    +
    24{
    +
    25public:
    + +
    30 LINEAR,
    +
    31 ANGULAR // assumes degrees
    +
    32 };
    + +
    41 {
    +
    42 double p;
    +
    43 double i;
    +
    44 double d;
    +
    45 double deadband;
    + + +
    48 };
    +
    49
    +
    50
    +
    51
    + +
    57
    +
    58
    +
    67 void init(double start_pt, double set_pt) override;
    +
    68
    +
    75 double update(double sensor_val) override;
    +
    76
    +
    81 double get() override;
    +
    82
    +
    89 void set_limits(double lower, double upper) override;
    +
    90
    +
    95 bool is_on_target() override;
    +
    96
    +
    100 void reset();
    +
    101
    +
    106 double get_error();
    +
    107
    +
    112 double get_target();
    +
    113
    +
    118 void set_target(double target);
    +
    119
    +
    120 Feedback::FeedbackType get_type() override;
    +
    121
    + +
    123
    +
    124private:
    +
    125
    +
    126
    +
    127 double last_error = 0;
    +
    128 double accum_error = 0;
    +
    129
    +
    130 double last_time = 0;
    +
    131 double on_target_last_time = 0;
    +
    132
    +
    133 double lower_limit = 0;
    +
    134 double upper_limit = 0;
    +
    135
    +
    136 double target = 0;
    +
    137 double sensor_val = 0;
    +
    138 double out = 0;
    +
    139
    +
    140 bool is_checking_on_target = false;
    +
    141
    +
    142 timer pid_timer;
    +
    143};
    +
    Definition: feedback_base.h:11
    +
    Definition: pid.h:24
    +
    double get_target()
    Definition: pid.cpp:97
    +
    ERROR_TYPE
    Definition: pid.h:29
    +
    void set_target(double target)
    Definition: pid.cpp:105
    +
    double update(double sensor_val) override
    Definition: pid.cpp:25
    +
    pid_config_t & config
    configuration struct for this controller. see pid_config_t for information about what this contains
    Definition: pid.h:122
    +
    double get() override
    Definition: pid.cpp:81
    +
    void set_limits(double lower, double upper) override
    Definition: pid.cpp:114
    +
    bool is_on_target() override
    Definition: pid.cpp:124
    +
    void init(double start_pt, double set_pt) override
    Definition: pid.cpp:13
    +
    double get_error()
    Definition: pid.cpp:89
    +
    void reset()
    Definition: pid.cpp:66
    +
    Definition: pid.h:41
    +
    double on_target_time
    the time in seconds that we have to be on target for to say we are officially at the target
    Definition: pid.h:46
    +
    double d
    derivitave coeffecient d * derivative(error)
    Definition: pid.h:44
    +
    double p
    proportional coeffecient p * error()
    Definition: pid.h:42
    +
    double i
    integral coeffecient i * integral(error)
    Definition: pid.h:43
    +
    double deadband
    at what threshold are we close enough to be finished
    Definition: pid.h:45
    +
    ERROR_TYPE error_method
    Linear or angular. wheter to do error as a simple subtraction or to wrap.
    Definition: pid.h:47
    +
    + + + + diff --git a/documentation/html/pidff_8h_source.html b/documentation/html/pidff_8h_source.html new file mode 100644 index 0000000..8f2d7c0 --- /dev/null +++ b/documentation/html/pidff_8h_source.html @@ -0,0 +1,135 @@ + + + + + + + +RIT VEXU Core API: include/utils/pidff.h Source File + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    pidff.h
    +
    +
    +
    1#pragma once
    +
    2#include "../core/include/utils/feedback_base.h"
    +
    3#include "../core/include/utils/pid.h"
    +
    4#include "../core/include/utils/feedforward.h"
    +
    5
    +
    6class PIDFF : public Feedback
    +
    7{
    +
    8 public:
    +
    9
    + +
    11
    +
    18 void init(double start_pt, double set_pt) override;
    +
    19
    +
    24 void set_target(double set_pt);
    +
    25
    +
    33 double update(double val) override;
    +
    34
    +
    43 double update(double val, double vel_setpt, double a_setpt=0);
    +
    44
    +
    48 double get() override;
    +
    49
    +
    56 void set_limits(double lower, double upper) override;
    +
    57
    +
    61 bool is_on_target() override;
    +
    62
    +
    63 PID pid;
    +
    64
    +
    65
    +
    66 private:
    +
    67
    + +
    69
    +
    70 FeedForward ff;
    +
    71
    +
    72 double out;
    +
    73 double lower_lim, upper_lim;
    +
    74
    +
    75};
    +
    Definition: feedforward.h:30
    +
    Definition: feedback_base.h:11
    +
    Definition: pidff.h:7
    +
    bool is_on_target() override
    Definition: pidff.cpp:84
    +
    void init(double start_pt, double set_pt) override
    Definition: pidff.cpp:17
    +
    void set_target(double set_pt)
    Definition: pidff.cpp:22
    +
    double get() override
    Definition: pidff.cpp:64
    +
    double update(double val) override
    Definition: pidff.cpp:34
    +
    void set_limits(double lower, double upper) override
    Definition: pidff.cpp:75
    +
    Definition: pid.h:24
    +
    Definition: feedforward.h:42
    +
    Definition: pid.h:41
    +
    + + + + diff --git a/documentation/html/pure__pursuit_8h_source.html b/documentation/html/pure__pursuit_8h_source.html new file mode 100644 index 0000000..495dfec --- /dev/null +++ b/documentation/html/pure__pursuit_8h_source.html @@ -0,0 +1,133 @@ + + + + + + + +RIT VEXU Core API: include/utils/pure_pursuit.h Source File + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    pure_pursuit.h
    +
    +
    +
    1#pragma once
    +
    2
    +
    3#include <vector>
    +
    4#include "../core/include/utils/vector2d.h"
    +
    5#include "vex.h"
    +
    6
    +
    7using namespace vex;
    +
    8
    +
    9namespace PurePursuit {
    +
    14 struct spline
    +
    15 {
    +
    16 double a, b, c, d, x_start, x_end;
    +
    17
    +
    18 double getY(double x) {
    +
    19 return a * pow((x - x_start), 3) + b * pow((x - x_start), 2) + c * (x - x_start) + d;
    +
    20 }
    +
    21 };
    + +
    27 {
    +
    28 double x;
    +
    29 double y;
    +
    30 double dir;
    +
    31 double mag;
    +
    32
    +
    33 Vector2D::point_t getPoint() {
    +
    34 return {x, y};
    +
    35 }
    +
    36
    +
    37 Vector2D getTangent() {
    +
    38 return Vector2D(dir, mag);
    +
    39 }
    +
    40 };
    +
    41
    +
    46 static std::vector<Vector2D::point_t> line_circle_intersections(Vector2D::point_t center, double r, Vector2D::point_t point1, Vector2D::point_t point2);
    +
    50 static Vector2D::point_t get_lookahead(std::vector<Vector2D::point_t> path, Vector2D::point_t robot_loc, double radius);
    +
    51
    +
    55 static std::vector<Vector2D::point_t> inject_path(std::vector<Vector2D::point_t> path, double spacing);
    +
    56
    +
    68 static std::vector<Vector2D::point_t> smooth_path(std::vector<Vector2D::point_t> path, double weight_data, double weight_smooth, double tolerance);
    +
    69
    +
    70 static std::vector<Vector2D::point_t> smooth_path_cubic(std::vector<Vector2D::point_t> path, double res);
    +
    71
    +
    80 static std::vector<Vector2D::point_t> smooth_path_hermite(std::vector<hermite_point> path, double step);
    +
    81}
    +
    Definition: vector2d.h:14
    +
    Definition: pure_pursuit.h:27
    +
    Definition: pure_pursuit.h:15
    +
    Definition: vector2d.h:21
    +
    + + + + diff --git a/documentation/html/robot__specs_8h_source.html b/documentation/html/robot__specs_8h_source.html new file mode 100644 index 0000000..323aa96 --- /dev/null +++ b/documentation/html/robot__specs_8h_source.html @@ -0,0 +1,115 @@ + + + + + + + +RIT VEXU Core API: include/robot_specs.h Source File + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    robot_specs.h
    +
    +
    +
    1#pragma once
    +
    2#include "../core/include/utils/pid.h"
    +
    3#include "../core/include/utils/feedback_base.h"
    +
    4
    +
    11typedef struct
    +
    12{
    +
    13 double robot_radius;
    +
    14
    + + + +
    18
    + +
    20
    + + + +
    24
    + +
    Definition: feedback_base.h:11
    +
    Definition: pid.h:41
    +
    Definition: robot_specs.h:12
    +
    PID::pid_config_t correction_pid
    the pid controller to keep the robot driving in as straight a line as possible
    Definition: robot_specs.h:23
    +
    double robot_radius
    if you were to draw a circle with this radius, the robot would be entirely contained within it
    Definition: robot_specs.h:13
    +
    Feedback * drive_feedback
    the default feedback for autonomous driving
    Definition: robot_specs.h:21
    +
    double odom_gear_ratio
    the ratio of the odometry wheel to the encoder reading odometry data
    Definition: robot_specs.h:16
    +
    double drive_correction_cutoff
    the distance at which to stop trying to turn towards the target. If we are less than this value,...
    Definition: robot_specs.h:19
    +
    double odom_wheel_diam
    the diameter of the wheels used for
    Definition: robot_specs.h:15
    +
    Feedback * turn_feedback
    the defualt feedback for autonomous turning
    Definition: robot_specs.h:22
    +
    double dist_between_wheels
    the distance between centers of the central drive wheels
    Definition: robot_specs.h:17
    +
    + + + + diff --git a/documentation/html/screen_8h_source.html b/documentation/html/screen_8h_source.html new file mode 100644 index 0000000..d5f8e13 --- /dev/null +++ b/documentation/html/screen_8h_source.html @@ -0,0 +1,103 @@ + + + + + + + +RIT VEXU Core API: include/subsystems/screen.h Source File + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    screen.h
    +
    +
    +
    1#pragma once
    +
    2#include "vex.h"
    +
    3#include <vector>
    +
    4
    +
    9
    +
    10typedef void (*screenFunc)(vex::brain::lcd &screen, int x, int y, int width, int height, bool first_run);
    +
    11
    +
    12void draw_mot_header(vex::brain::lcd &screen, int x, int y, int width);
    +
    13// name should be no longer than 15 characters
    +
    14void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char *name, vex::motor &motor);
    +
    15void draw_battery_stats(vex::brain::lcd &screen, int x, int y, double voltage, double percentage);
    +
    16
    +
    17
    +
    18
    +
    19void draw_lr_arrows(vex::brain::lcd &screen, int bar_width, int width, int height);
    +
    20
    +
    21int handle_screen_thread(vex::brain::lcd &screen, std::vector<screenFunc> pages, int first_page);
    +
    22void StartScreen(vex::brain::lcd &screen, std::vector<screenFunc> pages, int first_page = 0);
    +
    + + + + diff --git a/documentation/html/search/all_0.js b/documentation/html/search/all_0.js new file mode 100644 index 0000000..b83f3ce --- /dev/null +++ b/documentation/html/search/all_0.js @@ -0,0 +1,15 @@ +var searchData= +[ + ['accel_0',['accel',['../classOdometryBase.html#a94c814dfb542dd891d84db7e74537249',1,'OdometryBase::accel()'],['../structMotionController_1_1m__profile__cfg__t.html#ac4f07f3ac52d12fd820ee4d8ce847f66',1,'MotionController::m_profile_cfg_t::accel()'],['../structmotion__t.html#a0bfa8ec05af92df3b8c0e7d0945824f2',1,'motion_t::accel()']]], + ['add_1',['add',['../classAutoChooser.html#a67b80bf6b62cfced155519f5b608e08c',1,'AutoChooser::add()'],['../classCommandController.html#a4cb2c06abd92fb99578f0da75c1411e5',1,'CommandController::add(AutoCommand *cmd, double timeout_seconds=10.0)'],['../classCommandController.html#a03fc0dd37c12ae7f43200d5588c768b8',1,'CommandController::add(std::vector< AutoCommand * > cmds)'],['../classGenericAuto.html#af48629556173af1f5106f7405a196f47',1,'GenericAuto::add(state_ptr new_state)']]], + ['add_5fasync_2',['add_async',['../classGenericAuto.html#a938fb69c14735d4cf88ebc7589dcad1c',1,'GenericAuto']]], + ['add_5fdelay_3',['add_delay',['../classCommandController.html#ae06b054f4aeea86e8c6bee56458dc6d1',1,'CommandController::add_delay()'],['../classGenericAuto.html#aaadc99efe49a375f0dc80db7e886d96c',1,'GenericAuto::add_delay()']]], + ['add_5fentry_4',['add_entry',['../classMovingAverage.html#a6c85ea575428ef7faf1f1f111a985db8',1,'MovingAverage']]], + ['add_5fsample_5',['add_sample',['../classGraphDrawer.html#a41cadd5ade1ae9de1a82cc97ee15557c',1,'GraphDrawer']]], + ['ang_5faccel_5fdeg_6',['ang_accel_deg',['../classOdometryBase.html#a01f14bfcecbcde7a74b9b98376deb19f',1,'OdometryBase']]], + ['ang_5fspeed_5fdeg_7',['ang_speed_deg',['../classOdometryBase.html#a250ceb6ed296ea579e37851e4a0048fb',1,'OdometryBase']]], + ['auto_5fdrive_8',['auto_drive',['../classMecanumDrive.html#aa0cfb8683fee99e0a534c3a725d338fd',1,'MecanumDrive']]], + ['auto_5fturn_9',['auto_turn',['../classMecanumDrive.html#ac8813aafec14f2d25c3abafefdb81498',1,'MecanumDrive']]], + ['autochooser_10',['AutoChooser',['../classAutoChooser.html',1,'AutoChooser'],['../classAutoChooser.html#a6e4f8f87e9cf0d0df2e36cda803f2c51',1,'AutoChooser::AutoChooser()']]], + ['autocommand_11',['AutoCommand',['../classAutoCommand.html',1,'']]] +]; diff --git a/documentation/html/search/all_1.js b/documentation/html/search/all_1.js new file mode 100644 index 0000000..b37ac8b --- /dev/null +++ b/documentation/html/search/all_1.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['background_5ftask_0',['background_task',['../classOdometryBase.html#a17a014f79b282ddfb715835214f3e2fb',1,'OdometryBase']]], + ['brain_1',['brain',['../classAutoChooser.html#a9889be17b1b6243563f975dd421802b4',1,'AutoChooser']]] +]; diff --git a/documentation/html/search/all_10.js b/documentation/html/search/all_10.js new file mode 100644 index 0000000..20a4baa --- /dev/null +++ b/documentation/html/search/all_10.js @@ -0,0 +1,26 @@ +var searchData= +[ + ['set_5faccel_0',['set_accel',['../classTrapezoidProfile.html#a1dcdfa1c290347cf0af48aca5afd167c',1,'TrapezoidProfile']]], + ['set_5fasync_1',['set_async',['../classLift.html#a7f37703180518390ec38cba9a780282b',1,'Lift']]], + ['set_5fendpts_2',['set_endpts',['../classTrapezoidProfile.html#a1d28f3fa6bf1dfa7f5c1a34d0d3b17b5',1,'TrapezoidProfile']]], + ['set_5flimits_3',['set_limits',['../classFeedback.html#a533a10b65cfc998898bf054f8b141de2',1,'Feedback::set_limits()'],['../classMotionController.html#a944c245002a1eb124dd8df40de4fcc57',1,'MotionController::set_limits()'],['../classPID.html#a8411ac48e8868d89e97afcf8990cca2c',1,'PID::set_limits()'],['../classPIDFF.html#ae0dccb27a91ec687f90c930441f246bb',1,'PIDFF::set_limits()']]], + ['set_5fmax_5fv_4',['set_max_v',['../classTrapezoidProfile.html#a6c08d08d8eadaa719f4dc9e607f9fe97',1,'TrapezoidProfile']]], + ['set_5fposition_5',['set_position',['../classLift.html#ab3cb7bc86faa079ec1249b5026ea6a85',1,'Lift::set_position()'],['../classOdometryBase.html#a34e4bd8567933d1b6bd6e41327a36549',1,'OdometryBase::set_position()'],['../classOdometryTank.html#ad3b4bcf351767992e2383ab000645335',1,'OdometryTank::set_position()']]], + ['set_5fsensor_5ffunction_6',['set_sensor_function',['../classLift.html#a08b7cdcfc9390f4945dd3737ac0e5ddc',1,'Lift']]], + ['set_5fsensor_5freset_7',['set_sensor_reset',['../classLift.html#a70b8e7cff5cd3b5827d8da07a02d92e6',1,'Lift']]], + ['set_5fsetpoint_8',['set_setpoint',['../classLift.html#a662bdc055d706699ef5cf308cd8872f8',1,'Lift']]], + ['set_5ftarget_9',['set_target',['../classPID.html#a2e301ab123c9e18e677b4873b03550dd',1,'PID::set_target()'],['../classPIDFF.html#a5b5584e4ca036b0e51c693a24a23b50b',1,'PIDFF::set_target()']]], + ['setpidtarget_10',['setPIDTarget',['../classFlywheel.html#a5eeb847c6ef4736b1917bf32843c69aa',1,'Flywheel']]], + ['setposition_11',['setPosition',['../classCustomEncoder.html#a0edd50e16020ccad5eafa55e0f80288d',1,'CustomEncoder']]], + ['setrotation_12',['setRotation',['../classCustomEncoder.html#abcb003c4627f59faa25c748c597da7fd',1,'CustomEncoder']]], + ['smallest_5fangle_13',['smallest_angle',['../classOdometryBase.html#a70ec71e9fb2e14f0a191a6bac927d36b',1,'OdometryBase']]], + ['speed_14',['speed',['../classOdometryBase.html#a6119ab3ce0b685e67a8b57871e0a2c26',1,'OdometryBase']]], + ['spin_5fmanual_15',['spin_manual',['../classFlywheel.html#a291e067bcc495a9d3da16a5832d78484',1,'Flywheel']]], + ['spin_5fraw_16',['spin_raw',['../classFlywheel.html#a5f4afa2ab8976acbf9fd47776a884dd3',1,'Flywheel']]], + ['spinrpm_17',['spinRPM',['../classFlywheel.html#aa72700130c0c8a08517ec1396fe9cc2b',1,'Flywheel']]], + ['spinrpmcommand_18',['SpinRPMCommand',['../classSpinRPMCommand.html#a9bfcf882448d6d4e0860c1a7de90f9ea',1,'SpinRPMCommand::SpinRPMCommand()'],['../classSpinRPMCommand.html',1,'SpinRPMCommand']]], + ['spline_19',['spline',['../structPurePursuit_1_1spline.html',1,'PurePursuit']]], + ['stop_20',['stop',['../classFlywheel.html#a6634f5126f0404e0edeeff1e0e14d05e',1,'Flywheel::stop()'],['../classTankDrive.html#af10e648e4de35fa72859fb96a9a80485',1,'TankDrive::stop()']]], + ['stopmotors_21',['stopMotors',['../classFlywheel.html#a78eaa40c9c069b8b4146c3ae34a21d4e',1,'Flywheel']]], + ['stopnontasks_22',['stopNonTasks',['../classFlywheel.html#a63c9c4d3646e4ed14f3b98ce3ab28684',1,'Flywheel']]] +]; diff --git a/documentation/html/search/all_11.js b/documentation/html/search/all_11.js new file mode 100644 index 0000000..0681ca8 --- /dev/null +++ b/documentation/html/search/all_11.js @@ -0,0 +1,13 @@ +var searchData= +[ + ['tankdrive_0',['TankDrive',['../classTankDrive.html',1,'TankDrive'],['../classTankDrive.html#a34f305bb1c996e3748c925af259aeeb4',1,'TankDrive::TankDrive()']]], + ['timeout_5fseconds_1',['timeout_seconds',['../classAutoCommand.html#ac3be7be26e49981ad1978491fd313472',1,'AutoCommand']]], + ['trapezoidprofile_2',['TrapezoidProfile',['../classTrapezoidProfile.html',1,'TrapezoidProfile'],['../classTrapezoidProfile.html#af693ca740c0112cfbf4a9ee13bbb6c5d',1,'TrapezoidProfile::TrapezoidProfile()']]], + ['tune_3',['tune',['../classOdometry3Wheel.html#acb23dbf715d342566fc7e44f58ebf654',1,'Odometry3Wheel']]], + ['tune_5ffeedforward_4',['tune_feedforward',['../classMotionController.html#a20749b6a4bd3cf509a3acf682831eb00',1,'MotionController']]], + ['turn_5fdegrees_5',['turn_degrees',['../classTankDrive.html#ac1ce9895b82b7298465d8e59fae95763',1,'TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_speed=1)'],['../classTankDrive.html#a26d51cc12145f2520ea0c4355716184d',1,'TankDrive::turn_degrees(double degrees, double max_speed=1)']]], + ['turn_5ffeedback_6',['turn_feedback',['../structrobot__specs__t.html#af8c8492ba755766847bb21b960b91bfe',1,'robot_specs_t']]], + ['turn_5fto_5fheading_7',['turn_to_heading',['../classTankDrive.html#a25030a7b5e9404a911f7b776a7df7f05',1,'TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double max_speed=1)'],['../classTankDrive.html#ab003af6cf2de93e649cce5245b092a36',1,'TankDrive::turn_to_heading(double heading_deg, double max_speed=1)']]], + ['turndegreescommand_8',['TurnDegreesCommand',['../classTurnDegreesCommand.html',1,'TurnDegreesCommand'],['../classTurnDegreesCommand.html#a70a7e4688c10f1b351e6d79a3a7862ee',1,'TurnDegreesCommand::TurnDegreesCommand()']]], + ['turntoheadingcommand_9',['TurnToHeadingCommand',['../classTurnToHeadingCommand.html',1,'TurnToHeadingCommand'],['../classTurnToHeadingCommand.html#a9a958d75babe94709827c827807d423d',1,'TurnToHeadingCommand::TurnToHeadingCommand()']]] +]; diff --git a/documentation/html/search/all_12.js b/documentation/html/search/all_12.js new file mode 100644 index 0000000..5fb0714 --- /dev/null +++ b/documentation/html/search/all_12.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['update_0',['update',['../classOdometry3Wheel.html#a85c5661989dae181a4db7d91bd0526f7',1,'Odometry3Wheel::update()'],['../classOdometryBase.html#a5d55b7987d97a9af721838596a520dec',1,'OdometryBase::update()'],['../classOdometryTank.html#a02508433d771c661c89d14f204a61d13',1,'OdometryTank::update()'],['../classFeedback.html#adda5fc7642539996be00632954dfc41f',1,'Feedback::update()'],['../classMotionController.html#a86ef0ef19858b5b407f7406bb5da30af',1,'MotionController::update()'],['../classPID.html#a53b5c34ba5e81fb79ed4258a143015b9',1,'PID::update()'],['../classPIDFF.html#a9a9b05ec43e4430019652b62799e761c',1,'PIDFF::update(double val) override'],['../classPIDFF.html#a015bebe6d1028451e612f103ee2c1c2c',1,'PIDFF::update(double val, double vel_setpt, double a_setpt=0)']]], + ['updatepid_1',['updatePID',['../classFlywheel.html#aa9df5ad636fb49d76ba922ecd1115aef',1,'Flywheel']]] +]; diff --git a/documentation/html/search/all_13.js b/documentation/html/search/all_13.js new file mode 100644 index 0000000..fbb1ddd --- /dev/null +++ b/documentation/html/search/all_13.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['vector2d_0',['Vector2D',['../classVector2D.html',1,'Vector2D'],['../classVector2D.html#af3084a6d83b0c8220c548fbf74df2744',1,'Vector2D::Vector2D(double dir, double mag)'],['../classVector2D.html#ae6429e185a05c8174d97beeec27432b5',1,'Vector2D::Vector2D(point_t p)']]], + ['vel_1',['vel',['../structmotion__t.html#a038b39985525b904bb8257ea86adbcee',1,'motion_t']]], + ['velocity_2',['velocity',['../classCustomEncoder.html#a92fe3a3227b4c4bc1ad1389b7b758455',1,'CustomEncoder']]] +]; diff --git a/documentation/html/search/all_14.js b/documentation/html/search/all_14.js new file mode 100644 index 0000000..b70319e --- /dev/null +++ b/documentation/html/search/all_14.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['waituntiluptospeedcommand_0',['WaitUntilUpToSpeedCommand',['../classWaitUntilUpToSpeedCommand.html',1,'WaitUntilUpToSpeedCommand'],['../classWaitUntilUpToSpeedCommand.html#afd000a8f148291a9d2310b76b9354fea',1,'WaitUntilUpToSpeedCommand::WaitUntilUpToSpeedCommand()']]], + ['wheel_5fdiam_1',['wheel_diam',['../structOdometry3Wheel_1_1odometry3wheel__cfg__t.html#a283cd9db8de27d9b3967d0c3203f1f7f',1,'Odometry3Wheel::odometry3wheel_cfg_t']]], + ['wheelbase_5fdist_2',['wheelbase_dist',['../structOdometry3Wheel_1_1odometry3wheel__cfg__t.html#a4de8559ac486dcfbf5baff9d9d6cb5b1',1,'Odometry3Wheel::odometry3wheel_cfg_t']]], + ['width_3',['width',['../structAutoChooser_1_1entry__t.html#a2459ffe56c165e35f3a63bec99990367',1,'AutoChooser::entry_t']]] +]; diff --git a/documentation/html/search/all_15.js b/documentation/html/search/all_15.js new file mode 100644 index 0000000..a7cd057 --- /dev/null +++ b/documentation/html/search/all_15.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['x_0',['x',['../structposition__t.html#aa554831febb89209dc5a2434e08265a8',1,'position_t::x()'],['../structAutoChooser_1_1entry__t.html#a7aa2aaaccd195c358c88afa6e24b5f73',1,'AutoChooser::entry_t::x()'],['../structVector2D_1_1point__t.html#ad139f137dd3554335c4ed9b51c8e3bd9',1,'Vector2D::point_t::x()']]] +]; diff --git a/documentation/html/search/all_16.js b/documentation/html/search/all_16.js new file mode 100644 index 0000000..579b23b --- /dev/null +++ b/documentation/html/search/all_16.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['y_0',['y',['../structposition__t.html#af5fb9bd02cb51336477d5290fe32cec6',1,'position_t::y()'],['../structAutoChooser_1_1entry__t.html#a2e303a71790d85a67819830302c4dcee',1,'AutoChooser::entry_t::y()'],['../structVector2D_1_1point__t.html#a8290e79feb502e69cd95a7580cf6f1fe',1,'Vector2D::point_t::y()']]] +]; diff --git a/documentation/html/search/all_17.js b/documentation/html/search/all_17.js new file mode 100644 index 0000000..490ff49 --- /dev/null +++ b/documentation/html/search/all_17.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['zero_5fpos_0',['zero_pos',['../classOdometryBase.html#a7bd3fd09b3a6fa78af3a5ed5e25b8d74',1,'OdometryBase']]] +]; diff --git a/documentation/html/search/all_2.js b/documentation/html/search/all_2.js new file mode 100644 index 0000000..159d974 --- /dev/null +++ b/documentation/html/search/all_2.js @@ -0,0 +1,14 @@ +var searchData= +[ + ['calculate_0',['calculate',['../classFeedForward.html#a2e2f7c12076225fa1dfd5f18aa210290',1,'FeedForward::calculate()'],['../classTrapezoidProfile.html#a0b65a924664e6e052a16db19f73af17c',1,'TrapezoidProfile::calculate()']]], + ['choice_1',['choice',['../classAutoChooser.html#a473e03a3e74487a38e94d3b5957f34bc',1,'AutoChooser']]], + ['commandcontroller_2',['CommandController',['../classCommandController.html',1,'']]], + ['config_3',['config',['../classPID.html#a67626fa764b201c7190ace37e068666b',1,'PID']]], + ['control_5fcontinuous_4',['control_continuous',['../classLift.html#ae585cb81d733c975a65bfa7914a6bfeb',1,'Lift']]], + ['control_5fmanual_5',['control_manual',['../classLift.html#acfeaf4547de1b6a01982e8e51b0bb224',1,'Lift']]], + ['control_5fsetpoints_6',['control_setpoints',['../classLift.html#a7197ad879474798a5c1fec4963058c3a',1,'Lift']]], + ['core_7',['Core',['../md_README.html',1,'']]], + ['correction_5fpid_8',['correction_pid',['../structrobot__specs__t.html#a23d091e4a5258c11db6cd9753b598d06',1,'robot_specs_t']]], + ['current_5fpos_9',['current_pos',['../classOdometryBase.html#a6870aebb6e05dcd152d3295462f559c3',1,'OdometryBase']]], + ['customencoder_10',['CustomEncoder',['../classCustomEncoder.html',1,'CustomEncoder'],['../classCustomEncoder.html#a6c17b425b7a899107be1bb7ed7e80b9d',1,'CustomEncoder::CustomEncoder()']]] +]; diff --git a/documentation/html/search/all_3.js b/documentation/html/search/all_3.js new file mode 100644 index 0000000..4b57e2e --- /dev/null +++ b/documentation/html/search/all_3.js @@ -0,0 +1,20 @@ +var searchData= +[ + ['d_0',['d',['../structPID_1_1pid__config__t.html#a1bb8ecda3f982ea983cd9f49b3d6706a',1,'PID::pid_config_t']]], + ['deadband_1',['deadband',['../structPID_1_1pid__config__t.html#a5fe836f65a951c00113996d32101172a',1,'PID::pid_config_t']]], + ['delaycommand_2',['DelayCommand',['../classDelayCommand.html',1,'DelayCommand'],['../classDelayCommand.html#a7dc6d1e547ec24b51d91aada84d1febb',1,'DelayCommand::DelayCommand()']]], + ['dist_3',['dist',['../structVector2D_1_1point__t.html#a118bb1552bd98c9708e452d593ed5e29',1,'Vector2D::point_t']]], + ['dist_5fbetween_5fwheels_4',['dist_between_wheels',['../structrobot__specs__t.html#afb03c2e2cbc0d8fd6686c9421e016dec',1,'robot_specs_t']]], + ['draw_5',['draw',['../classGraphDrawer.html#a420b88cacbf91908dc64624eb113d197',1,'GraphDrawer']]], + ['drive_6',['drive',['../classMecanumDrive.html#ac7a660a606aea694d21a4a2dd12faa24',1,'MecanumDrive']]], + ['drive_5farcade_7',['drive_arcade',['../classTankDrive.html#a4c52b51a9b149d97e9b0b175a10652ef',1,'TankDrive']]], + ['drive_5fcorrection_5fcutoff_8',['drive_correction_cutoff',['../structrobot__specs__t.html#aa9fc95ea4c235f455b712ac0cf5aa536',1,'robot_specs_t']]], + ['drive_5ffeedback_9',['drive_feedback',['../structrobot__specs__t.html#a828213e8d672431bd3bb87e6484db83f',1,'robot_specs_t']]], + ['drive_5fforward_10',['drive_forward',['../classTankDrive.html#a1fb3d661076afbb91452649cdaf8550f',1,'TankDrive::drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed=1)'],['../classTankDrive.html#a8edcf4316d5a22c32849d7d1d5d0a793',1,'TankDrive::drive_forward(double inches, directionType dir, double max_speed=1)']]], + ['drive_5fraw_11',['drive_raw',['../classMecanumDrive.html#a756383ba74cf555d42a147584f9ae646',1,'MecanumDrive']]], + ['drive_5ftank_12',['drive_tank',['../classTankDrive.html#a1dff7827546fb3d17e0d2ca150bdf630',1,'TankDrive']]], + ['drive_5fto_5fpoint_13',['drive_to_point',['../classTankDrive.html#a267114928d17e16d36ad14fd4d3bf91a',1,'TankDrive::drive_to_point(double x, double y, vex::directionType dir, double max_speed=1)'],['../classTankDrive.html#ad64cf88b180865f7e0f9810a344db791',1,'TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed=1)']]], + ['driveforwardcommand_14',['DriveForwardCommand',['../classDriveForwardCommand.html#a09fb0fc75fa06951c9dc160de169d726',1,'DriveForwardCommand::DriveForwardCommand()'],['../classDriveForwardCommand.html',1,'DriveForwardCommand']]], + ['drivestopcommand_15',['DriveStopCommand',['../classDriveStopCommand.html',1,'DriveStopCommand'],['../classDriveStopCommand.html#a64cc2eeb3a4d67482549a029f93ddde1',1,'DriveStopCommand::DriveStopCommand()']]], + ['drivetopointcommand_16',['DriveToPointCommand',['../classDriveToPointCommand.html',1,'DriveToPointCommand'],['../classDriveToPointCommand.html#ad9d5b904185abbddde096dc87e02f049',1,'DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed=1)'],['../classDriveToPointCommand.html#a716343f0c8befbd3a9c562c6a4fd6538',1,'DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, Vector2D::point_t point, directionType dir, double max_speed=1)']]] +]; diff --git a/documentation/html/search/all_4.js b/documentation/html/search/all_4.js new file mode 100644 index 0000000..3c35471 --- /dev/null +++ b/documentation/html/search/all_4.js @@ -0,0 +1,8 @@ +var searchData= +[ + ['end_5fasync_0',['end_async',['../classOdometryBase.html#ab65ccaa80d4bb0d0aa20e82b3b991436',1,'OdometryBase']]], + ['end_5ftask_1',['end_task',['../classOdometryBase.html#ae6e35ee98b4410f034cd37c0d2055a8d',1,'OdometryBase']]], + ['entry_5ft_2',['entry_t',['../structAutoChooser_1_1entry__t.html',1,'AutoChooser']]], + ['error_5fmethod_3',['error_method',['../structPID_1_1pid__config__t.html#ad2f96f58fba854b7e4329175497d1869',1,'PID::pid_config_t']]], + ['error_5ftype_4',['ERROR_TYPE',['../classPID.html#a259eb7bfd0750c7afd4a058c5d1c58a1',1,'PID']]] +]; diff --git a/documentation/html/search/all_5.js b/documentation/html/search/all_5.js new file mode 100644 index 0000000..b8250a3 --- /dev/null +++ b/documentation/html/search/all_5.js @@ -0,0 +1,11 @@ +var searchData= +[ + ['feedback_0',['Feedback',['../classFeedback.html',1,'']]], + ['feedforward_1',['FeedForward',['../classFeedForward.html',1,'FeedForward'],['../classFeedForward.html#aeea5ddbbcc6e75a479442cf69954665c',1,'FeedForward::FeedForward()']]], + ['ff_5fcfg_2',['ff_cfg',['../structMotionController_1_1m__profile__cfg__t.html#ad8131facbd379321cc7083361e68ff62',1,'MotionController::m_profile_cfg_t']]], + ['ff_5fconfig_5ft_3',['ff_config_t',['../structFeedForward_1_1ff__config__t.html',1,'FeedForward']]], + ['flywheel_4',['Flywheel',['../classFlywheel.html',1,'Flywheel'],['../classFlywheel.html#a61a1ba81b716c6f99a8d63394f8d185f',1,'Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio)'],['../classFlywheel.html#a38bb042949a6c6e7f283823a5786be65',1,'Flywheel::Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio)'],['../classFlywheel.html#a9ce96416ffe460e013fab3ba434bae79',1,'Flywheel::Flywheel(motor_group &motors, double tbh_gain, const double ratio)'],['../classFlywheel.html#a3ae86041ee9dc973538fcc6caf47cd58',1,'Flywheel::Flywheel(motor_group &motors, const double ratio)']]], + ['flywheelstopcommand_5',['FlywheelStopCommand',['../classFlywheelStopCommand.html',1,'FlywheelStopCommand'],['../classFlywheelStopCommand.html#a3e94b6c95ab4ad8216c9a87a22c07c4b',1,'FlywheelStopCommand::FlywheelStopCommand()']]], + ['flywheelstopmotorscommand_6',['FlywheelStopMotorsCommand',['../classFlywheelStopMotorsCommand.html',1,'FlywheelStopMotorsCommand'],['../classFlywheelStopMotorsCommand.html#a0e7ce6586a6ae1ec9322114ede691a13',1,'FlywheelStopMotorsCommand::FlywheelStopMotorsCommand()']]], + ['flywheelstopnontaskscommand_7',['FlywheelStopNonTasksCommand',['../classFlywheelStopNonTasksCommand.html',1,'']]] +]; diff --git a/documentation/html/search/all_6.js b/documentation/html/search/all_6.js new file mode 100644 index 0000000..24c6a7f --- /dev/null +++ b/documentation/html/search/all_6.js @@ -0,0 +1,31 @@ +var searchData= +[ + ['genericauto_0',['GenericAuto',['../classGenericAuto.html',1,'']]], + ['get_1',['get',['../classFeedback.html#ac44bb519a6f4e25c8e8250f3d30ab359',1,'Feedback::get()'],['../classMotionController.html#a2a1944f590618cd91770364aea416cd5',1,'MotionController::get()'],['../classPID.html#a69c2e66b8ff06c86ca9701d11e21da75',1,'PID::get()'],['../classPIDFF.html#a78a34d271bcc703fc803e15b275fd238',1,'PIDFF::get()']]], + ['get_5faccel_2',['get_accel',['../classOdometryBase.html#a3223bac952f79bf910b979690499b965',1,'OdometryBase']]], + ['get_5fangular_5faccel_5fdeg_3',['get_angular_accel_deg',['../classOdometryBase.html#a456e6433e51971d2640ff96ed3a59432',1,'OdometryBase']]], + ['get_5fangular_5fspeed_5fdeg_4',['get_angular_speed_deg',['../classOdometryBase.html#af30d97a35e9e9c4f9be0a81390e6c0f1',1,'OdometryBase']]], + ['get_5fasync_5',['get_async',['../classLift.html#a6913ab2df38f0429641c256ec9288370',1,'Lift']]], + ['get_5faverage_6',['get_average',['../classMovingAverage.html#aa91e650064d361abe51bfa0b166ac6c0',1,'MovingAverage']]], + ['get_5fchoice_7',['get_choice',['../classAutoChooser.html#ada27d20c06baeb169c3abed5fd0b06bb',1,'AutoChooser']]], + ['get_5fdir_8',['get_dir',['../classVector2D.html#a683dab4e55cfc8483a32c6805cd29980',1,'Vector2D']]], + ['get_5ferror_9',['get_error',['../classPID.html#ab5cdb296dbcce80703a9a98b9605c500',1,'PID']]], + ['get_5fmag_10',['get_mag',['../classVector2D.html#a4da6f92b5874470ed5642587a973c3df',1,'Vector2D']]], + ['get_5fmotion_11',['get_motion',['../classMotionController.html#ab958ce97fbc4929f4dd03965671e8d4d',1,'MotionController']]], + ['get_5fmovement_5ftime_12',['get_movement_time',['../classTrapezoidProfile.html#abd551042dfffe0923200c4546d109c55',1,'TrapezoidProfile']]], + ['get_5fposition_13',['get_position',['../classOdometryBase.html#a3cdcfcf70ef02e0efc2efd902fac3811',1,'OdometryBase']]], + ['get_5fsetpoint_14',['get_setpoint',['../classLift.html#adaa6cb65351d0c8a2c199a87a318b133',1,'Lift']]], + ['get_5fsize_15',['get_size',['../classMovingAverage.html#ac45976e15321d2c2f52d1f281475b53d',1,'MovingAverage']]], + ['get_5fspeed_16',['get_speed',['../classOdometryBase.html#a96c7be68db7424ddbe3704770dd1889f',1,'OdometryBase']]], + ['get_5ftarget_17',['get_target',['../classPID.html#a1cd58cedeccc45b67551e331ee547be9',1,'PID']]], + ['get_5fx_18',['get_x',['../classVector2D.html#a240e649d36dbda8bcba031f5fe5a2438',1,'Vector2D']]], + ['get_5fy_19',['get_y',['../classVector2D.html#aee94b809a4a63b972c72b22257fa3f30',1,'Vector2D']]], + ['getdesiredrpm_20',['getDesiredRPM',['../classFlywheel.html#a5dee80fd74903884478649b6ec2f4528',1,'Flywheel']]], + ['getfeedforwardvalue_21',['getFeedforwardValue',['../classFlywheel.html#aea43f1c07b799133113d7b9ff14a7f36',1,'Flywheel']]], + ['getmotors_22',['getMotors',['../classFlywheel.html#a5823c1242f4b00519f582a7468cf537a',1,'Flywheel']]], + ['getpid_23',['getPID',['../classFlywheel.html#adf7b3fab5fd8a708f339da649c72e775',1,'Flywheel']]], + ['getpidvalue_24',['getPIDValue',['../classFlywheel.html#a45bde10a01304c71e74564cd080a9052',1,'Flywheel']]], + ['getrpm_25',['getRPM',['../classFlywheel.html#a00e5ad15adfb23185f7713b86d9d7b9f',1,'Flywheel']]], + ['gettbhgain_26',['getTBHGain',['../classFlywheel.html#a8c1f0b98975b9d75bc5b350fa059043d',1,'Flywheel']]], + ['graphdrawer_27',['GraphDrawer',['../classGraphDrawer.html#a8066ff51adb3cbbeca34268d13f34c5f',1,'GraphDrawer::GraphDrawer()'],['../classGraphDrawer.html',1,'GraphDrawer']]] +]; diff --git a/documentation/html/search/all_7.js b/documentation/html/search/all_7.js new file mode 100644 index 0000000..32946e0 --- /dev/null +++ b/documentation/html/search/all_7.js @@ -0,0 +1,8 @@ +var searchData= +[ + ['handle_0',['handle',['../classOdometryBase.html#ae5308f20a4dfef9594631010c7612dab',1,'OdometryBase']]], + ['height_1',['height',['../structAutoChooser_1_1entry__t.html#a957eb90ff083c4a4f8dc90da976b86c7',1,'AutoChooser::entry_t']]], + ['hermite_5fpoint_2',['hermite_point',['../structPurePursuit_1_1hermite__point.html',1,'PurePursuit']]], + ['hold_3',['hold',['../classLift.html#a9afcbf54cdd919a2c5a68f95c7a0c9e8',1,'Lift']]], + ['home_4',['home',['../classLift.html#ab53178b13037a4c6b1fd07657cff1f25',1,'Lift']]] +]; diff --git a/documentation/html/search/all_8.js b/documentation/html/search/all_8.js new file mode 100644 index 0000000..80e164b --- /dev/null +++ b/documentation/html/search/all_8.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['i_0',['i',['../structPID_1_1pid__config__t.html#a4140c6884d1dc86366520a2543e654b3',1,'PID::pid_config_t']]], + ['init_1',['init',['../classFeedback.html#a22efb13216bfd51aea07e0b6e45135c1',1,'Feedback::init()'],['../classMotionController.html#af0d665d9916111cbce677da6df6b6667',1,'MotionController::init()'],['../classPID.html#aab0f3b4351cc4ee2b8bb366105e85e95',1,'PID::init()'],['../classPIDFF.html#a37226c8d3bfac97485b28105a15f29fc',1,'PIDFF::init()']]], + ['is_5fon_5ftarget_2',['is_on_target',['../classFeedback.html#ae4cc835c374aab9761d22603d4329d34',1,'Feedback::is_on_target()'],['../classMotionController.html#aa9e2af88b848646889deb1d43a283173',1,'MotionController::is_on_target()'],['../classPID.html#a9de884c31570c4ae0dc6e24eb26daa43',1,'PID::is_on_target()'],['../classPIDFF.html#a2534a33490570d839bf1849673a70bc1',1,'PIDFF::is_on_target()']]], + ['istaskrunning_3',['isTaskRunning',['../classFlywheel.html#a990fde5741011926c84c45ea3c51ced3',1,'Flywheel']]] +]; diff --git a/documentation/html/search/all_9.js b/documentation/html/search/all_9.js new file mode 100644 index 0000000..bd011ee --- /dev/null +++ b/documentation/html/search/all_9.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['ka_0',['kA',['../structFeedForward_1_1ff__config__t.html#a8528f04936dbcbf0bc406d0bfc6b8428',1,'FeedForward::ff_config_t']]], + ['kg_1',['kG',['../structFeedForward_1_1ff__config__t.html#a1eab464040edd69a63b528d6d21f0644',1,'FeedForward::ff_config_t']]], + ['ks_2',['kS',['../structFeedForward_1_1ff__config__t.html#af140ce6afc074040571d229b6a455c50',1,'FeedForward::ff_config_t']]], + ['kv_3',['kV',['../structFeedForward_1_1ff__config__t.html#afd4e01b20b64750ad2604b17ac10f57e',1,'FeedForward::ff_config_t']]] +]; diff --git a/documentation/html/search/all_a.js b/documentation/html/search/all_a.js new file mode 100644 index 0000000..22c068f --- /dev/null +++ b/documentation/html/search/all_a.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['last_5fcommand_5ftimed_5fout_0',['last_command_timed_out',['../classCommandController.html#a23306007060f97ab7f57715c5d8d0c57',1,'CommandController']]], + ['lift_1',['Lift',['../classLift.html',1,'Lift< T >'],['../classLift.html#aa5723874330725dec5176ec4174e9ea8',1,'Lift::Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map< T, double > &setpoint_map, limit *homing_switch=NULL)']]], + ['lift_5fcfg_5ft_2',['lift_cfg_t',['../structLift_1_1lift__cfg__t.html',1,'Lift']]], + ['list_3',['list',['../classAutoChooser.html#a5c2b8683579011b529b95aab423b120a',1,'AutoChooser']]] +]; diff --git a/documentation/html/search/all_b.js b/documentation/html/search/all_b.js new file mode 100644 index 0000000..9af57af --- /dev/null +++ b/documentation/html/search/all_b.js @@ -0,0 +1,13 @@ +var searchData= +[ + ['m_5fprofile_5fcfg_5ft_0',['m_profile_cfg_t',['../structMotionController_1_1m__profile__cfg__t.html',1,'MotionController']]], + ['max_5fv_1',['max_v',['../structMotionController_1_1m__profile__cfg__t.html#a949b084fe78795509ad8e65c74e9bc3f',1,'MotionController::m_profile_cfg_t']]], + ['measurerpm_2',['measureRPM',['../classFlywheel.html#ae46b69a8371dca7d6fb163c30192f666',1,'Flywheel']]], + ['mecanumdrive_3',['MecanumDrive',['../classMecanumDrive.html',1,'MecanumDrive'],['../classMecanumDrive.html#a780908c5b55ea8b9f228c84540a6c5f7',1,'MecanumDrive::MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear, vex::rotation *lateral_wheel=NULL, vex::inertial *imu=NULL, mecanumdrive_config_t *config=NULL)']]], + ['mecanumdrive_5fconfig_5ft_4',['mecanumdrive_config_t',['../structMecanumDrive_1_1mecanumdrive__config__t.html',1,'MecanumDrive']]], + ['modify_5finputs_5',['modify_inputs',['../classTankDrive.html#abb511cf1be40ef7be89c2ccff6a09cab',1,'TankDrive']]], + ['motion_5ft_6',['motion_t',['../structmotion__t.html',1,'']]], + ['motioncontroller_7',['MotionController',['../classMotionController.html',1,'MotionController'],['../classMotionController.html#a076c5aa4ea383dccaeec76f7554a7467',1,'MotionController::MotionController()']]], + ['movingaverage_8',['MovingAverage',['../classMovingAverage.html',1,'MovingAverage'],['../classMovingAverage.html#a2455b651d3c6ad1f14d1a0d65b2394b2',1,'MovingAverage::MovingAverage(int buffer_size)'],['../classMovingAverage.html#afd1c880fdd617fcbf02f54ac87f45d6f',1,'MovingAverage::MovingAverage(int buffer_size, double starting_value)']]], + ['mut_9',['mut',['../classOdometryBase.html#a88bb48858ca6ff8300a41e23482ec6f6',1,'OdometryBase']]] +]; diff --git a/documentation/html/search/all_c.js b/documentation/html/search/all_c.js new file mode 100644 index 0000000..ed08633 --- /dev/null +++ b/documentation/html/search/all_c.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['name_0',['name',['../structAutoChooser_1_1entry__t.html#ab876b8f9fa8bf03a91c45c55c2a7fa23',1,'AutoChooser::entry_t']]], + ['normalize_1',['normalize',['../classVector2D.html#a0bb684df2d724e4378dc5fbf0d4faa99',1,'Vector2D']]] +]; diff --git a/documentation/html/search/all_d.js b/documentation/html/search/all_d.js new file mode 100644 index 0000000..b6e8ae2 --- /dev/null +++ b/documentation/html/search/all_d.js @@ -0,0 +1,16 @@ +var searchData= +[ + ['odom_5fgear_5fratio_0',['odom_gear_ratio',['../structrobot__specs__t.html#a8c454d8b38efdd15dfa6f075c40e4ec7',1,'robot_specs_t']]], + ['odom_5fwheel_5fdiam_1',['odom_wheel_diam',['../structrobot__specs__t.html#acf12b29aa6a86cc09b2ef868f9e77a31',1,'robot_specs_t']]], + ['odometry3wheel_2',['Odometry3Wheel',['../classOdometry3Wheel.html',1,'Odometry3Wheel'],['../classOdometry3Wheel.html#a6755014965483b84e06e42d8e289bf40',1,'Odometry3Wheel::Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, odometry3wheel_cfg_t &cfg, bool is_async=true)']]], + ['odometry3wheel_5fcfg_5ft_3',['odometry3wheel_cfg_t',['../structOdometry3Wheel_1_1odometry3wheel__cfg__t.html',1,'Odometry3Wheel']]], + ['odometrybase_4',['OdometryBase',['../classOdometryBase.html',1,'OdometryBase'],['../classOdometryBase.html#a61286bd1c5105adbfa5b52c74f9e9466',1,'OdometryBase::OdometryBase()']]], + ['odometrytank_5',['OdometryTank',['../classOdometryTank.html',1,'OdometryTank'],['../classOdometryTank.html#add83c3320e43e90963c38f25ce06c4da',1,'OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true)'],['../classOdometryTank.html#a0fdb5e855104301ad83588362974b75a',1,'OdometryTank::OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true)']]], + ['odomsetposition_6',['OdomSetPosition',['../classOdomSetPosition.html#afcd92592689e2c3262dd9120286bbac2',1,'OdomSetPosition::OdomSetPosition()'],['../classOdomSetPosition.html',1,'OdomSetPosition']]], + ['off_5faxis_5fcenter_5fdist_7',['off_axis_center_dist',['../structOdometry3Wheel_1_1odometry3wheel__cfg__t.html#afd79024054d352789991bd816d955d9e',1,'Odometry3Wheel::odometry3wheel_cfg_t']]], + ['on_5ftarget_5ftime_8',['on_target_time',['../structPID_1_1pid__config__t.html#a14212579cfa1827b6cc04388c6b3626e',1,'PID::pid_config_t']]], + ['on_5ftimeout_9',['on_timeout',['../classAutoCommand.html#a68475854d11e7c3be90e9c6e8fc9e982',1,'AutoCommand::on_timeout()'],['../classDriveForwardCommand.html#a52b4e1ff386eeb1c00f219f40738d0af',1,'DriveForwardCommand::on_timeout()'],['../classTurnDegreesCommand.html#abd912b5906bafd9f4117e005eaeccb18',1,'TurnDegreesCommand::on_timeout()'],['../classTurnToHeadingCommand.html#acaa3b650ed9f02315eb6ba901181bc85',1,'TurnToHeadingCommand::on_timeout()']]], + ['operator_2a_10',['operator*',['../classVector2D.html#a00a0dc6776995d47659b3ddd58c33a78',1,'Vector2D']]], + ['operator_2b_11',['operator+',['../structVector2D_1_1point__t.html#a80783a6446695b14693816aaf1341bdb',1,'Vector2D::point_t::operator+()'],['../classVector2D.html#a2bed654f65df8c3bedbf8cd7d07071df',1,'Vector2D::operator+()']]], + ['operator_2d_12',['operator-',['../structVector2D_1_1point__t.html#aac0efd68a6d8dbe4cbb2437096a0a05d',1,'Vector2D::point_t::operator-()'],['../classVector2D.html#a07a043fc63572c1cf3104ec0a9a4e796',1,'Vector2D::operator-()']]] +]; diff --git a/documentation/html/search/all_e.js b/documentation/html/search/all_e.js new file mode 100644 index 0000000..d5c5780 --- /dev/null +++ b/documentation/html/search/all_e.js @@ -0,0 +1,15 @@ +var searchData= +[ + ['p_0',['p',['../structPID_1_1pid__config__t.html#a27290957ad115f4502f765ff292e3a23',1,'PID::pid_config_t']]], + ['pid_1',['PID',['../classPID.html',1,'PID'],['../classPID.html#a3b6b678b2d52a2be7fb572b766e43994',1,'PID::PID()']]], + ['pid_5fcfg_2',['pid_cfg',['../structMotionController_1_1m__profile__cfg__t.html#a2b6415c29fcab4f9b2ccff067a390baa',1,'MotionController::m_profile_cfg_t']]], + ['pid_5fconfig_5ft_3',['pid_config_t',['../structPID_1_1pid__config__t.html',1,'PID']]], + ['pidff_4',['PIDFF',['../classPIDFF.html',1,'']]], + ['point_5',['point',['../classVector2D.html#a567227aaadc7eceae0cbccf7f611aff4',1,'Vector2D']]], + ['point_5ft_6',['point_t',['../structVector2D_1_1point__t.html',1,'Vector2D']]], + ['pos_7',['pos',['../structmotion__t.html#a7f67afcb6e0a49061509a11c47de46e4',1,'motion_t']]], + ['pos_5fdiff_8',['pos_diff',['../classOdometryBase.html#a8a248f027d3ff98cb2df2e3cd90e1f66',1,'OdometryBase']]], + ['position_9',['position',['../classCustomEncoder.html#ab891fa278911c232bd0bf502a5ed95eb',1,'CustomEncoder']]], + ['position_5ft_10',['position_t',['../structposition__t.html',1,'']]], + ['pure_5fpursuit_11',['pure_pursuit',['../classTankDrive.html#a13bb19d1cf97b7f3534f4f2a0a13bf27',1,'TankDrive']]] +]; diff --git a/documentation/html/search/all_f.js b/documentation/html/search/all_f.js new file mode 100644 index 0000000..34d564c --- /dev/null +++ b/documentation/html/search/all_f.js @@ -0,0 +1,12 @@ +var searchData= +[ + ['render_0',['render',['../classAutoChooser.html#a9365d354e3401d819e58a999721c07d9',1,'AutoChooser']]], + ['reset_1',['reset',['../classPID.html#af9677e76cb1beffbcf3f54cbc627c530',1,'PID']]], + ['reset_5fauto_2',['reset_auto',['../classTankDrive.html#aaa68eae1521e5b87ecfed2a60b15bf34',1,'TankDrive']]], + ['robot_5fradius_3',['robot_radius',['../structrobot__specs__t.html#a37a65da54459d805cf1370cc6330bce0',1,'robot_specs_t']]], + ['robot_5fspecs_5ft_4',['robot_specs_t',['../structrobot__specs__t.html',1,'']]], + ['rot_5',['rot',['../structposition__t.html#aa22df5aed859f41200d2213ad3f2cd45',1,'position_t']]], + ['rot_5fdiff_6',['rot_diff',['../classOdometryBase.html#ab1f1a09cda37d799c82003b5284c6856',1,'OdometryBase']]], + ['rotation_7',['rotation',['../classCustomEncoder.html#a853fa3a11f2563d71f08ee3c3f38ff01',1,'CustomEncoder']]], + ['run_8',['run',['../classGenericAuto.html#af25dcaaf074980064382c458812b3c9c',1,'GenericAuto::run()'],['../classFlywheelStopMotorsCommand.html#ab5b75338d50c3674a5fe27a5e77698bc',1,'FlywheelStopMotorsCommand::run()'],['../classFlywheelStopCommand.html#a9be8ca8422bd7b5f5a03cbf8e21025a7',1,'FlywheelStopCommand::run()'],['../classWaitUntilUpToSpeedCommand.html#a38f75c01a4740d87a380c15cc51c6396',1,'WaitUntilUpToSpeedCommand::run()'],['../classSpinRPMCommand.html#af12f71f87967de0d9991272d9659b6ef',1,'SpinRPMCommand::run()'],['../classOdomSetPosition.html#a611e74a12a9eeb0fce1f38a596c3c467',1,'OdomSetPosition::run()'],['../classDriveStopCommand.html#a3b37806449b50b2f2c19179f1039237b',1,'DriveStopCommand::run()'],['../classTurnToHeadingCommand.html#af571168ca078be95cbc735c99c2f4093',1,'TurnToHeadingCommand::run()'],['../classDriveToPointCommand.html#a8ed58921bc3eeb8c04d0b11b4f7e4fbe',1,'DriveToPointCommand::run()'],['../classTurnDegreesCommand.html#a2206e4c5073a2e83f6bfa3eeca46a370',1,'TurnDegreesCommand::run()'],['../classDriveForwardCommand.html#aff482b72cab23cd569eb01efac6d1d31',1,'DriveForwardCommand::run()'],['../classDelayCommand.html#a6cff8fe05b3ca36ec2ab20e411cfd9ab',1,'DelayCommand::run()'],['../classCommandController.html#a0f7f6ccce0304c577521205ad37bb36a',1,'CommandController::run()'],['../classAutoCommand.html#a9f58c576ca6378b18a4136f60df50560',1,'AutoCommand::run()']]] +]; diff --git a/documentation/html/search/classes_0.js b/documentation/html/search/classes_0.js new file mode 100644 index 0000000..b733383 --- /dev/null +++ b/documentation/html/search/classes_0.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['autochooser_0',['AutoChooser',['../classAutoChooser.html',1,'']]], + ['autocommand_1',['AutoCommand',['../classAutoCommand.html',1,'']]] +]; diff --git a/documentation/html/search/classes_1.js b/documentation/html/search/classes_1.js new file mode 100644 index 0000000..5cfcda3 --- /dev/null +++ b/documentation/html/search/classes_1.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['commandcontroller_0',['CommandController',['../classCommandController.html',1,'']]], + ['customencoder_1',['CustomEncoder',['../classCustomEncoder.html',1,'']]] +]; diff --git a/documentation/html/search/classes_2.js b/documentation/html/search/classes_2.js new file mode 100644 index 0000000..5f3f612 --- /dev/null +++ b/documentation/html/search/classes_2.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['delaycommand_0',['DelayCommand',['../classDelayCommand.html',1,'']]], + ['driveforwardcommand_1',['DriveForwardCommand',['../classDriveForwardCommand.html',1,'']]], + ['drivestopcommand_2',['DriveStopCommand',['../classDriveStopCommand.html',1,'']]], + ['drivetopointcommand_3',['DriveToPointCommand',['../classDriveToPointCommand.html',1,'']]] +]; diff --git a/documentation/html/search/classes_3.js b/documentation/html/search/classes_3.js new file mode 100644 index 0000000..5a50111 --- /dev/null +++ b/documentation/html/search/classes_3.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['entry_5ft_0',['entry_t',['../structAutoChooser_1_1entry__t.html',1,'AutoChooser']]] +]; diff --git a/documentation/html/search/classes_4.js b/documentation/html/search/classes_4.js new file mode 100644 index 0000000..ea38884 --- /dev/null +++ b/documentation/html/search/classes_4.js @@ -0,0 +1,10 @@ +var searchData= +[ + ['feedback_0',['Feedback',['../classFeedback.html',1,'']]], + ['feedforward_1',['FeedForward',['../classFeedForward.html',1,'']]], + ['ff_5fconfig_5ft_2',['ff_config_t',['../structFeedForward_1_1ff__config__t.html',1,'FeedForward']]], + ['flywheel_3',['Flywheel',['../classFlywheel.html',1,'']]], + ['flywheelstopcommand_4',['FlywheelStopCommand',['../classFlywheelStopCommand.html',1,'']]], + ['flywheelstopmotorscommand_5',['FlywheelStopMotorsCommand',['../classFlywheelStopMotorsCommand.html',1,'']]], + ['flywheelstopnontaskscommand_6',['FlywheelStopNonTasksCommand',['../classFlywheelStopNonTasksCommand.html',1,'']]] +]; diff --git a/documentation/html/search/classes_5.js b/documentation/html/search/classes_5.js new file mode 100644 index 0000000..43b02b7 --- /dev/null +++ b/documentation/html/search/classes_5.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['genericauto_0',['GenericAuto',['../classGenericAuto.html',1,'']]], + ['graphdrawer_1',['GraphDrawer',['../classGraphDrawer.html',1,'']]] +]; diff --git a/documentation/html/search/classes_6.js b/documentation/html/search/classes_6.js new file mode 100644 index 0000000..58f30b3 --- /dev/null +++ b/documentation/html/search/classes_6.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['hermite_5fpoint_0',['hermite_point',['../structPurePursuit_1_1hermite__point.html',1,'PurePursuit']]] +]; diff --git a/documentation/html/search/classes_7.js b/documentation/html/search/classes_7.js new file mode 100644 index 0000000..930d3d3 --- /dev/null +++ b/documentation/html/search/classes_7.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['lift_0',['Lift',['../classLift.html',1,'']]], + ['lift_5fcfg_5ft_1',['lift_cfg_t',['../structLift_1_1lift__cfg__t.html',1,'Lift']]] +]; diff --git a/documentation/html/search/classes_8.js b/documentation/html/search/classes_8.js new file mode 100644 index 0000000..8aebec0 --- /dev/null +++ b/documentation/html/search/classes_8.js @@ -0,0 +1,9 @@ +var searchData= +[ + ['m_5fprofile_5fcfg_5ft_0',['m_profile_cfg_t',['../structMotionController_1_1m__profile__cfg__t.html',1,'MotionController']]], + ['mecanumdrive_1',['MecanumDrive',['../classMecanumDrive.html',1,'']]], + ['mecanumdrive_5fconfig_5ft_2',['mecanumdrive_config_t',['../structMecanumDrive_1_1mecanumdrive__config__t.html',1,'MecanumDrive']]], + ['motion_5ft_3',['motion_t',['../structmotion__t.html',1,'']]], + ['motioncontroller_4',['MotionController',['../classMotionController.html',1,'']]], + ['movingaverage_5',['MovingAverage',['../classMovingAverage.html',1,'']]] +]; diff --git a/documentation/html/search/classes_9.js b/documentation/html/search/classes_9.js new file mode 100644 index 0000000..f71ac9a --- /dev/null +++ b/documentation/html/search/classes_9.js @@ -0,0 +1,8 @@ +var searchData= +[ + ['odometry3wheel_0',['Odometry3Wheel',['../classOdometry3Wheel.html',1,'']]], + ['odometry3wheel_5fcfg_5ft_1',['odometry3wheel_cfg_t',['../structOdometry3Wheel_1_1odometry3wheel__cfg__t.html',1,'Odometry3Wheel']]], + ['odometrybase_2',['OdometryBase',['../classOdometryBase.html',1,'']]], + ['odometrytank_3',['OdometryTank',['../classOdometryTank.html',1,'']]], + ['odomsetposition_4',['OdomSetPosition',['../classOdomSetPosition.html',1,'']]] +]; diff --git a/documentation/html/search/classes_a.js b/documentation/html/search/classes_a.js new file mode 100644 index 0000000..b697c70 --- /dev/null +++ b/documentation/html/search/classes_a.js @@ -0,0 +1,8 @@ +var searchData= +[ + ['pid_0',['PID',['../classPID.html',1,'']]], + ['pid_5fconfig_5ft_1',['pid_config_t',['../structPID_1_1pid__config__t.html',1,'PID']]], + ['pidff_2',['PIDFF',['../classPIDFF.html',1,'']]], + ['point_5ft_3',['point_t',['../structVector2D_1_1point__t.html',1,'Vector2D']]], + ['position_5ft_4',['position_t',['../structposition__t.html',1,'']]] +]; diff --git a/documentation/html/search/classes_b.js b/documentation/html/search/classes_b.js new file mode 100644 index 0000000..a8d8c05 --- /dev/null +++ b/documentation/html/search/classes_b.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['robot_5fspecs_5ft_0',['robot_specs_t',['../structrobot__specs__t.html',1,'']]] +]; diff --git a/documentation/html/search/classes_c.js b/documentation/html/search/classes_c.js new file mode 100644 index 0000000..c5119ff --- /dev/null +++ b/documentation/html/search/classes_c.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['spinrpmcommand_0',['SpinRPMCommand',['../classSpinRPMCommand.html',1,'']]], + ['spline_1',['spline',['../structPurePursuit_1_1spline.html',1,'PurePursuit']]] +]; diff --git a/documentation/html/search/classes_d.js b/documentation/html/search/classes_d.js new file mode 100644 index 0000000..2a29d86 --- /dev/null +++ b/documentation/html/search/classes_d.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['tankdrive_0',['TankDrive',['../classTankDrive.html',1,'']]], + ['trapezoidprofile_1',['TrapezoidProfile',['../classTrapezoidProfile.html',1,'']]], + ['turndegreescommand_2',['TurnDegreesCommand',['../classTurnDegreesCommand.html',1,'']]], + ['turntoheadingcommand_3',['TurnToHeadingCommand',['../classTurnToHeadingCommand.html',1,'']]] +]; diff --git a/documentation/html/search/classes_e.js b/documentation/html/search/classes_e.js new file mode 100644 index 0000000..cd06f6b --- /dev/null +++ b/documentation/html/search/classes_e.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['vector2d_0',['Vector2D',['../classVector2D.html',1,'']]] +]; diff --git a/documentation/html/search/classes_f.js b/documentation/html/search/classes_f.js new file mode 100644 index 0000000..f42e8a0 --- /dev/null +++ b/documentation/html/search/classes_f.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['waituntiluptospeedcommand_0',['WaitUntilUpToSpeedCommand',['../classWaitUntilUpToSpeedCommand.html',1,'']]] +]; diff --git a/documentation/html/search/close.svg b/documentation/html/search/close.svg new file mode 100644 index 0000000..a933eea --- /dev/null +++ b/documentation/html/search/close.svg @@ -0,0 +1,31 @@ + + + + + + image/svg+xml + + + + + + + + diff --git a/documentation/html/search/enums_0.js b/documentation/html/search/enums_0.js new file mode 100644 index 0000000..3512f6a --- /dev/null +++ b/documentation/html/search/enums_0.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['error_5ftype_0',['ERROR_TYPE',['../classPID.html#a259eb7bfd0750c7afd4a058c5d1c58a1',1,'PID']]] +]; diff --git a/documentation/html/search/functions_0.js b/documentation/html/search/functions_0.js new file mode 100644 index 0000000..62057ce --- /dev/null +++ b/documentation/html/search/functions_0.js @@ -0,0 +1,11 @@ +var searchData= +[ + ['add_0',['add',['../classAutoChooser.html#a67b80bf6b62cfced155519f5b608e08c',1,'AutoChooser::add()'],['../classCommandController.html#a4cb2c06abd92fb99578f0da75c1411e5',1,'CommandController::add(AutoCommand *cmd, double timeout_seconds=10.0)'],['../classCommandController.html#a03fc0dd37c12ae7f43200d5588c768b8',1,'CommandController::add(std::vector< AutoCommand * > cmds)'],['../classGenericAuto.html#af48629556173af1f5106f7405a196f47',1,'GenericAuto::add(state_ptr new_state)']]], + ['add_5fasync_1',['add_async',['../classGenericAuto.html#a938fb69c14735d4cf88ebc7589dcad1c',1,'GenericAuto']]], + ['add_5fdelay_2',['add_delay',['../classCommandController.html#ae06b054f4aeea86e8c6bee56458dc6d1',1,'CommandController::add_delay()'],['../classGenericAuto.html#aaadc99efe49a375f0dc80db7e886d96c',1,'GenericAuto::add_delay()']]], + ['add_5fentry_3',['add_entry',['../classMovingAverage.html#a6c85ea575428ef7faf1f1f111a985db8',1,'MovingAverage']]], + ['add_5fsample_4',['add_sample',['../classGraphDrawer.html#a41cadd5ade1ae9de1a82cc97ee15557c',1,'GraphDrawer']]], + ['auto_5fdrive_5',['auto_drive',['../classMecanumDrive.html#aa0cfb8683fee99e0a534c3a725d338fd',1,'MecanumDrive']]], + ['auto_5fturn_6',['auto_turn',['../classMecanumDrive.html#ac8813aafec14f2d25c3abafefdb81498',1,'MecanumDrive']]], + ['autochooser_7',['AutoChooser',['../classAutoChooser.html#a6e4f8f87e9cf0d0df2e36cda803f2c51',1,'AutoChooser']]] +]; diff --git a/documentation/html/search/functions_1.js b/documentation/html/search/functions_1.js new file mode 100644 index 0000000..d2575c5 --- /dev/null +++ b/documentation/html/search/functions_1.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['background_5ftask_0',['background_task',['../classOdometryBase.html#a17a014f79b282ddfb715835214f3e2fb',1,'OdometryBase']]] +]; diff --git a/documentation/html/search/functions_10.js b/documentation/html/search/functions_10.js new file mode 100644 index 0000000..a529836 --- /dev/null +++ b/documentation/html/search/functions_10.js @@ -0,0 +1,11 @@ +var searchData= +[ + ['tankdrive_0',['TankDrive',['../classTankDrive.html#a34f305bb1c996e3748c925af259aeeb4',1,'TankDrive']]], + ['trapezoidprofile_1',['TrapezoidProfile',['../classTrapezoidProfile.html#af693ca740c0112cfbf4a9ee13bbb6c5d',1,'TrapezoidProfile']]], + ['tune_2',['tune',['../classOdometry3Wheel.html#acb23dbf715d342566fc7e44f58ebf654',1,'Odometry3Wheel']]], + ['tune_5ffeedforward_3',['tune_feedforward',['../classMotionController.html#a20749b6a4bd3cf509a3acf682831eb00',1,'MotionController']]], + ['turn_5fdegrees_4',['turn_degrees',['../classTankDrive.html#ac1ce9895b82b7298465d8e59fae95763',1,'TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_speed=1)'],['../classTankDrive.html#a26d51cc12145f2520ea0c4355716184d',1,'TankDrive::turn_degrees(double degrees, double max_speed=1)']]], + ['turn_5fto_5fheading_5',['turn_to_heading',['../classTankDrive.html#a25030a7b5e9404a911f7b776a7df7f05',1,'TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double max_speed=1)'],['../classTankDrive.html#ab003af6cf2de93e649cce5245b092a36',1,'TankDrive::turn_to_heading(double heading_deg, double max_speed=1)']]], + ['turndegreescommand_6',['TurnDegreesCommand',['../classTurnDegreesCommand.html#a70a7e4688c10f1b351e6d79a3a7862ee',1,'TurnDegreesCommand']]], + ['turntoheadingcommand_7',['TurnToHeadingCommand',['../classTurnToHeadingCommand.html#a9a958d75babe94709827c827807d423d',1,'TurnToHeadingCommand']]] +]; diff --git a/documentation/html/search/functions_11.js b/documentation/html/search/functions_11.js new file mode 100644 index 0000000..5fb0714 --- /dev/null +++ b/documentation/html/search/functions_11.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['update_0',['update',['../classOdometry3Wheel.html#a85c5661989dae181a4db7d91bd0526f7',1,'Odometry3Wheel::update()'],['../classOdometryBase.html#a5d55b7987d97a9af721838596a520dec',1,'OdometryBase::update()'],['../classOdometryTank.html#a02508433d771c661c89d14f204a61d13',1,'OdometryTank::update()'],['../classFeedback.html#adda5fc7642539996be00632954dfc41f',1,'Feedback::update()'],['../classMotionController.html#a86ef0ef19858b5b407f7406bb5da30af',1,'MotionController::update()'],['../classPID.html#a53b5c34ba5e81fb79ed4258a143015b9',1,'PID::update()'],['../classPIDFF.html#a9a9b05ec43e4430019652b62799e761c',1,'PIDFF::update(double val) override'],['../classPIDFF.html#a015bebe6d1028451e612f103ee2c1c2c',1,'PIDFF::update(double val, double vel_setpt, double a_setpt=0)']]], + ['updatepid_1',['updatePID',['../classFlywheel.html#aa9df5ad636fb49d76ba922ecd1115aef',1,'Flywheel']]] +]; diff --git a/documentation/html/search/functions_12.js b/documentation/html/search/functions_12.js new file mode 100644 index 0000000..d90ca7e --- /dev/null +++ b/documentation/html/search/functions_12.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['vector2d_0',['Vector2D',['../classVector2D.html#af3084a6d83b0c8220c548fbf74df2744',1,'Vector2D::Vector2D(double dir, double mag)'],['../classVector2D.html#ae6429e185a05c8174d97beeec27432b5',1,'Vector2D::Vector2D(point_t p)']]], + ['velocity_1',['velocity',['../classCustomEncoder.html#a92fe3a3227b4c4bc1ad1389b7b758455',1,'CustomEncoder']]] +]; diff --git a/documentation/html/search/functions_13.js b/documentation/html/search/functions_13.js new file mode 100644 index 0000000..b0f286b --- /dev/null +++ b/documentation/html/search/functions_13.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['waituntiluptospeedcommand_0',['WaitUntilUpToSpeedCommand',['../classWaitUntilUpToSpeedCommand.html#afd000a8f148291a9d2310b76b9354fea',1,'WaitUntilUpToSpeedCommand']]] +]; diff --git a/documentation/html/search/functions_2.js b/documentation/html/search/functions_2.js new file mode 100644 index 0000000..4233f6e --- /dev/null +++ b/documentation/html/search/functions_2.js @@ -0,0 +1,8 @@ +var searchData= +[ + ['calculate_0',['calculate',['../classFeedForward.html#a2e2f7c12076225fa1dfd5f18aa210290',1,'FeedForward::calculate()'],['../classTrapezoidProfile.html#a0b65a924664e6e052a16db19f73af17c',1,'TrapezoidProfile::calculate()']]], + ['control_5fcontinuous_1',['control_continuous',['../classLift.html#ae585cb81d733c975a65bfa7914a6bfeb',1,'Lift']]], + ['control_5fmanual_2',['control_manual',['../classLift.html#acfeaf4547de1b6a01982e8e51b0bb224',1,'Lift']]], + ['control_5fsetpoints_3',['control_setpoints',['../classLift.html#a7197ad879474798a5c1fec4963058c3a',1,'Lift']]], + ['customencoder_4',['CustomEncoder',['../classCustomEncoder.html#a6c17b425b7a899107be1bb7ed7e80b9d',1,'CustomEncoder']]] +]; diff --git a/documentation/html/search/functions_3.js b/documentation/html/search/functions_3.js new file mode 100644 index 0000000..e5c0a4f --- /dev/null +++ b/documentation/html/search/functions_3.js @@ -0,0 +1,15 @@ +var searchData= +[ + ['delaycommand_0',['DelayCommand',['../classDelayCommand.html#a7dc6d1e547ec24b51d91aada84d1febb',1,'DelayCommand']]], + ['dist_1',['dist',['../structVector2D_1_1point__t.html#a118bb1552bd98c9708e452d593ed5e29',1,'Vector2D::point_t']]], + ['draw_2',['draw',['../classGraphDrawer.html#a420b88cacbf91908dc64624eb113d197',1,'GraphDrawer']]], + ['drive_3',['drive',['../classMecanumDrive.html#ac7a660a606aea694d21a4a2dd12faa24',1,'MecanumDrive']]], + ['drive_5farcade_4',['drive_arcade',['../classTankDrive.html#a4c52b51a9b149d97e9b0b175a10652ef',1,'TankDrive']]], + ['drive_5fforward_5',['drive_forward',['../classTankDrive.html#a1fb3d661076afbb91452649cdaf8550f',1,'TankDrive::drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed=1)'],['../classTankDrive.html#a8edcf4316d5a22c32849d7d1d5d0a793',1,'TankDrive::drive_forward(double inches, directionType dir, double max_speed=1)']]], + ['drive_5fraw_6',['drive_raw',['../classMecanumDrive.html#a756383ba74cf555d42a147584f9ae646',1,'MecanumDrive']]], + ['drive_5ftank_7',['drive_tank',['../classTankDrive.html#a1dff7827546fb3d17e0d2ca150bdf630',1,'TankDrive']]], + ['drive_5fto_5fpoint_8',['drive_to_point',['../classTankDrive.html#ad64cf88b180865f7e0f9810a344db791',1,'TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed=1)'],['../classTankDrive.html#a267114928d17e16d36ad14fd4d3bf91a',1,'TankDrive::drive_to_point(double x, double y, vex::directionType dir, double max_speed=1)']]], + ['driveforwardcommand_9',['DriveForwardCommand',['../classDriveForwardCommand.html#a09fb0fc75fa06951c9dc160de169d726',1,'DriveForwardCommand']]], + ['drivestopcommand_10',['DriveStopCommand',['../classDriveStopCommand.html#a64cc2eeb3a4d67482549a029f93ddde1',1,'DriveStopCommand']]], + ['drivetopointcommand_11',['DriveToPointCommand',['../classDriveToPointCommand.html#ad9d5b904185abbddde096dc87e02f049',1,'DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed=1)'],['../classDriveToPointCommand.html#a716343f0c8befbd3a9c562c6a4fd6538',1,'DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, Vector2D::point_t point, directionType dir, double max_speed=1)']]] +]; diff --git a/documentation/html/search/functions_4.js b/documentation/html/search/functions_4.js new file mode 100644 index 0000000..364bca1 --- /dev/null +++ b/documentation/html/search/functions_4.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['end_5fasync_0',['end_async',['../classOdometryBase.html#ab65ccaa80d4bb0d0aa20e82b3b991436',1,'OdometryBase']]] +]; diff --git a/documentation/html/search/functions_5.js b/documentation/html/search/functions_5.js new file mode 100644 index 0000000..6b7d612 --- /dev/null +++ b/documentation/html/search/functions_5.js @@ -0,0 +1,7 @@ +var searchData= +[ + ['feedforward_0',['FeedForward',['../classFeedForward.html#aeea5ddbbcc6e75a479442cf69954665c',1,'FeedForward']]], + ['flywheel_1',['Flywheel',['../classFlywheel.html#a61a1ba81b716c6f99a8d63394f8d185f',1,'Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio)'],['../classFlywheel.html#a38bb042949a6c6e7f283823a5786be65',1,'Flywheel::Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio)'],['../classFlywheel.html#a9ce96416ffe460e013fab3ba434bae79',1,'Flywheel::Flywheel(motor_group &motors, double tbh_gain, const double ratio)'],['../classFlywheel.html#a3ae86041ee9dc973538fcc6caf47cd58',1,'Flywheel::Flywheel(motor_group &motors, const double ratio)']]], + ['flywheelstopcommand_2',['FlywheelStopCommand',['../classFlywheelStopCommand.html#a3e94b6c95ab4ad8216c9a87a22c07c4b',1,'FlywheelStopCommand']]], + ['flywheelstopmotorscommand_3',['FlywheelStopMotorsCommand',['../classFlywheelStopMotorsCommand.html#a0e7ce6586a6ae1ec9322114ede691a13',1,'FlywheelStopMotorsCommand']]] +]; diff --git a/documentation/html/search/functions_6.js b/documentation/html/search/functions_6.js new file mode 100644 index 0000000..3844fb5 --- /dev/null +++ b/documentation/html/search/functions_6.js @@ -0,0 +1,30 @@ +var searchData= +[ + ['get_0',['get',['../classMotionController.html#a2a1944f590618cd91770364aea416cd5',1,'MotionController::get()'],['../classPID.html#a69c2e66b8ff06c86ca9701d11e21da75',1,'PID::get()'],['../classPIDFF.html#a78a34d271bcc703fc803e15b275fd238',1,'PIDFF::get()'],['../classFeedback.html#ac44bb519a6f4e25c8e8250f3d30ab359',1,'Feedback::get()']]], + ['get_5faccel_1',['get_accel',['../classOdometryBase.html#a3223bac952f79bf910b979690499b965',1,'OdometryBase']]], + ['get_5fangular_5faccel_5fdeg_2',['get_angular_accel_deg',['../classOdometryBase.html#a456e6433e51971d2640ff96ed3a59432',1,'OdometryBase']]], + ['get_5fangular_5fspeed_5fdeg_3',['get_angular_speed_deg',['../classOdometryBase.html#af30d97a35e9e9c4f9be0a81390e6c0f1',1,'OdometryBase']]], + ['get_5fasync_4',['get_async',['../classLift.html#a6913ab2df38f0429641c256ec9288370',1,'Lift']]], + ['get_5faverage_5',['get_average',['../classMovingAverage.html#aa91e650064d361abe51bfa0b166ac6c0',1,'MovingAverage']]], + ['get_5fchoice_6',['get_choice',['../classAutoChooser.html#ada27d20c06baeb169c3abed5fd0b06bb',1,'AutoChooser']]], + ['get_5fdir_7',['get_dir',['../classVector2D.html#a683dab4e55cfc8483a32c6805cd29980',1,'Vector2D']]], + ['get_5ferror_8',['get_error',['../classPID.html#ab5cdb296dbcce80703a9a98b9605c500',1,'PID']]], + ['get_5fmag_9',['get_mag',['../classVector2D.html#a4da6f92b5874470ed5642587a973c3df',1,'Vector2D']]], + ['get_5fmotion_10',['get_motion',['../classMotionController.html#ab958ce97fbc4929f4dd03965671e8d4d',1,'MotionController']]], + ['get_5fmovement_5ftime_11',['get_movement_time',['../classTrapezoidProfile.html#abd551042dfffe0923200c4546d109c55',1,'TrapezoidProfile']]], + ['get_5fposition_12',['get_position',['../classOdometryBase.html#a3cdcfcf70ef02e0efc2efd902fac3811',1,'OdometryBase']]], + ['get_5fsetpoint_13',['get_setpoint',['../classLift.html#adaa6cb65351d0c8a2c199a87a318b133',1,'Lift']]], + ['get_5fsize_14',['get_size',['../classMovingAverage.html#ac45976e15321d2c2f52d1f281475b53d',1,'MovingAverage']]], + ['get_5fspeed_15',['get_speed',['../classOdometryBase.html#a96c7be68db7424ddbe3704770dd1889f',1,'OdometryBase']]], + ['get_5ftarget_16',['get_target',['../classPID.html#a1cd58cedeccc45b67551e331ee547be9',1,'PID']]], + ['get_5fx_17',['get_x',['../classVector2D.html#a240e649d36dbda8bcba031f5fe5a2438',1,'Vector2D']]], + ['get_5fy_18',['get_y',['../classVector2D.html#aee94b809a4a63b972c72b22257fa3f30',1,'Vector2D']]], + ['getdesiredrpm_19',['getDesiredRPM',['../classFlywheel.html#a5dee80fd74903884478649b6ec2f4528',1,'Flywheel']]], + ['getfeedforwardvalue_20',['getFeedforwardValue',['../classFlywheel.html#aea43f1c07b799133113d7b9ff14a7f36',1,'Flywheel']]], + ['getmotors_21',['getMotors',['../classFlywheel.html#a5823c1242f4b00519f582a7468cf537a',1,'Flywheel']]], + ['getpid_22',['getPID',['../classFlywheel.html#adf7b3fab5fd8a708f339da649c72e775',1,'Flywheel']]], + ['getpidvalue_23',['getPIDValue',['../classFlywheel.html#a45bde10a01304c71e74564cd080a9052',1,'Flywheel']]], + ['getrpm_24',['getRPM',['../classFlywheel.html#a00e5ad15adfb23185f7713b86d9d7b9f',1,'Flywheel']]], + ['gettbhgain_25',['getTBHGain',['../classFlywheel.html#a8c1f0b98975b9d75bc5b350fa059043d',1,'Flywheel']]], + ['graphdrawer_26',['GraphDrawer',['../classGraphDrawer.html#a8066ff51adb3cbbeca34268d13f34c5f',1,'GraphDrawer']]] +]; diff --git a/documentation/html/search/functions_7.js b/documentation/html/search/functions_7.js new file mode 100644 index 0000000..6de5b21 --- /dev/null +++ b/documentation/html/search/functions_7.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['hold_0',['hold',['../classLift.html#a9afcbf54cdd919a2c5a68f95c7a0c9e8',1,'Lift']]], + ['home_1',['home',['../classLift.html#ab53178b13037a4c6b1fd07657cff1f25',1,'Lift']]] +]; diff --git a/documentation/html/search/functions_8.js b/documentation/html/search/functions_8.js new file mode 100644 index 0000000..ff6afea --- /dev/null +++ b/documentation/html/search/functions_8.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['init_0',['init',['../classFeedback.html#a22efb13216bfd51aea07e0b6e45135c1',1,'Feedback::init()'],['../classMotionController.html#af0d665d9916111cbce677da6df6b6667',1,'MotionController::init()'],['../classPID.html#aab0f3b4351cc4ee2b8bb366105e85e95',1,'PID::init()'],['../classPIDFF.html#a37226c8d3bfac97485b28105a15f29fc',1,'PIDFF::init()']]], + ['is_5fon_5ftarget_1',['is_on_target',['../classFeedback.html#ae4cc835c374aab9761d22603d4329d34',1,'Feedback::is_on_target()'],['../classMotionController.html#aa9e2af88b848646889deb1d43a283173',1,'MotionController::is_on_target()'],['../classPID.html#a9de884c31570c4ae0dc6e24eb26daa43',1,'PID::is_on_target()'],['../classPIDFF.html#a2534a33490570d839bf1849673a70bc1',1,'PIDFF::is_on_target()']]], + ['istaskrunning_2',['isTaskRunning',['../classFlywheel.html#a990fde5741011926c84c45ea3c51ced3',1,'Flywheel']]] +]; diff --git a/documentation/html/search/functions_9.js b/documentation/html/search/functions_9.js new file mode 100644 index 0000000..d4951b6 --- /dev/null +++ b/documentation/html/search/functions_9.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['last_5fcommand_5ftimed_5fout_0',['last_command_timed_out',['../classCommandController.html#a23306007060f97ab7f57715c5d8d0c57',1,'CommandController']]], + ['lift_1',['Lift',['../classLift.html#aa5723874330725dec5176ec4174e9ea8',1,'Lift']]] +]; diff --git a/documentation/html/search/functions_a.js b/documentation/html/search/functions_a.js new file mode 100644 index 0000000..bdc25b0 --- /dev/null +++ b/documentation/html/search/functions_a.js @@ -0,0 +1,8 @@ +var searchData= +[ + ['measurerpm_0',['measureRPM',['../classFlywheel.html#ae46b69a8371dca7d6fb163c30192f666',1,'Flywheel']]], + ['mecanumdrive_1',['MecanumDrive',['../classMecanumDrive.html#a780908c5b55ea8b9f228c84540a6c5f7',1,'MecanumDrive']]], + ['modify_5finputs_2',['modify_inputs',['../classTankDrive.html#abb511cf1be40ef7be89c2ccff6a09cab',1,'TankDrive']]], + ['motioncontroller_3',['MotionController',['../classMotionController.html#a076c5aa4ea383dccaeec76f7554a7467',1,'MotionController']]], + ['movingaverage_4',['MovingAverage',['../classMovingAverage.html#a2455b651d3c6ad1f14d1a0d65b2394b2',1,'MovingAverage::MovingAverage(int buffer_size)'],['../classMovingAverage.html#afd1c880fdd617fcbf02f54ac87f45d6f',1,'MovingAverage::MovingAverage(int buffer_size, double starting_value)']]] +]; diff --git a/documentation/html/search/functions_b.js b/documentation/html/search/functions_b.js new file mode 100644 index 0000000..621b160 --- /dev/null +++ b/documentation/html/search/functions_b.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['normalize_0',['normalize',['../classVector2D.html#a0bb684df2d724e4378dc5fbf0d4faa99',1,'Vector2D']]] +]; diff --git a/documentation/html/search/functions_c.js b/documentation/html/search/functions_c.js new file mode 100644 index 0000000..903e180 --- /dev/null +++ b/documentation/html/search/functions_c.js @@ -0,0 +1,11 @@ +var searchData= +[ + ['odometry3wheel_0',['Odometry3Wheel',['../classOdometry3Wheel.html#a6755014965483b84e06e42d8e289bf40',1,'Odometry3Wheel']]], + ['odometrybase_1',['OdometryBase',['../classOdometryBase.html#a61286bd1c5105adbfa5b52c74f9e9466',1,'OdometryBase']]], + ['odometrytank_2',['OdometryTank',['../classOdometryTank.html#add83c3320e43e90963c38f25ce06c4da',1,'OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true)'],['../classOdometryTank.html#a0fdb5e855104301ad83588362974b75a',1,'OdometryTank::OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true)']]], + ['odomsetposition_3',['OdomSetPosition',['../classOdomSetPosition.html#afcd92592689e2c3262dd9120286bbac2',1,'OdomSetPosition']]], + ['on_5ftimeout_4',['on_timeout',['../classAutoCommand.html#a68475854d11e7c3be90e9c6e8fc9e982',1,'AutoCommand::on_timeout()'],['../classDriveForwardCommand.html#a52b4e1ff386eeb1c00f219f40738d0af',1,'DriveForwardCommand::on_timeout()'],['../classTurnDegreesCommand.html#abd912b5906bafd9f4117e005eaeccb18',1,'TurnDegreesCommand::on_timeout()'],['../classTurnToHeadingCommand.html#acaa3b650ed9f02315eb6ba901181bc85',1,'TurnToHeadingCommand::on_timeout()']]], + ['operator_2a_5',['operator*',['../classVector2D.html#a00a0dc6776995d47659b3ddd58c33a78',1,'Vector2D']]], + ['operator_2b_6',['operator+',['../structVector2D_1_1point__t.html#a80783a6446695b14693816aaf1341bdb',1,'Vector2D::point_t::operator+()'],['../classVector2D.html#a2bed654f65df8c3bedbf8cd7d07071df',1,'Vector2D::operator+()']]], + ['operator_2d_7',['operator-',['../structVector2D_1_1point__t.html#aac0efd68a6d8dbe4cbb2437096a0a05d',1,'Vector2D::point_t::operator-()'],['../classVector2D.html#a07a043fc63572c1cf3104ec0a9a4e796',1,'Vector2D::operator-()']]] +]; diff --git a/documentation/html/search/functions_d.js b/documentation/html/search/functions_d.js new file mode 100644 index 0000000..9b09c6b --- /dev/null +++ b/documentation/html/search/functions_d.js @@ -0,0 +1,8 @@ +var searchData= +[ + ['pid_0',['PID',['../classPID.html#a3b6b678b2d52a2be7fb572b766e43994',1,'PID']]], + ['point_1',['point',['../classVector2D.html#a567227aaadc7eceae0cbccf7f611aff4',1,'Vector2D']]], + ['pos_5fdiff_2',['pos_diff',['../classOdometryBase.html#a8a248f027d3ff98cb2df2e3cd90e1f66',1,'OdometryBase']]], + ['position_3',['position',['../classCustomEncoder.html#ab891fa278911c232bd0bf502a5ed95eb',1,'CustomEncoder']]], + ['pure_5fpursuit_4',['pure_pursuit',['../classTankDrive.html#a13bb19d1cf97b7f3534f4f2a0a13bf27',1,'TankDrive']]] +]; diff --git a/documentation/html/search/functions_e.js b/documentation/html/search/functions_e.js new file mode 100644 index 0000000..5966983 --- /dev/null +++ b/documentation/html/search/functions_e.js @@ -0,0 +1,9 @@ +var searchData= +[ + ['render_0',['render',['../classAutoChooser.html#a9365d354e3401d819e58a999721c07d9',1,'AutoChooser']]], + ['reset_1',['reset',['../classPID.html#af9677e76cb1beffbcf3f54cbc627c530',1,'PID']]], + ['reset_5fauto_2',['reset_auto',['../classTankDrive.html#aaa68eae1521e5b87ecfed2a60b15bf34',1,'TankDrive']]], + ['rot_5fdiff_3',['rot_diff',['../classOdometryBase.html#ab1f1a09cda37d799c82003b5284c6856',1,'OdometryBase']]], + ['rotation_4',['rotation',['../classCustomEncoder.html#a853fa3a11f2563d71f08ee3c3f38ff01',1,'CustomEncoder']]], + ['run_5',['run',['../classGenericAuto.html#af25dcaaf074980064382c458812b3c9c',1,'GenericAuto::run()'],['../classFlywheelStopMotorsCommand.html#ab5b75338d50c3674a5fe27a5e77698bc',1,'FlywheelStopMotorsCommand::run()'],['../classFlywheelStopCommand.html#a9be8ca8422bd7b5f5a03cbf8e21025a7',1,'FlywheelStopCommand::run()'],['../classWaitUntilUpToSpeedCommand.html#a38f75c01a4740d87a380c15cc51c6396',1,'WaitUntilUpToSpeedCommand::run()'],['../classSpinRPMCommand.html#af12f71f87967de0d9991272d9659b6ef',1,'SpinRPMCommand::run()'],['../classOdomSetPosition.html#a611e74a12a9eeb0fce1f38a596c3c467',1,'OdomSetPosition::run()'],['../classDriveStopCommand.html#a3b37806449b50b2f2c19179f1039237b',1,'DriveStopCommand::run()'],['../classTurnToHeadingCommand.html#af571168ca078be95cbc735c99c2f4093',1,'TurnToHeadingCommand::run()'],['../classDriveToPointCommand.html#a8ed58921bc3eeb8c04d0b11b4f7e4fbe',1,'DriveToPointCommand::run()'],['../classTurnDegreesCommand.html#a2206e4c5073a2e83f6bfa3eeca46a370',1,'TurnDegreesCommand::run()'],['../classDriveForwardCommand.html#aff482b72cab23cd569eb01efac6d1d31',1,'DriveForwardCommand::run()'],['../classDelayCommand.html#a6cff8fe05b3ca36ec2ab20e411cfd9ab',1,'DelayCommand::run()'],['../classCommandController.html#a0f7f6ccce0304c577521205ad37bb36a',1,'CommandController::run()'],['../classAutoCommand.html#a9f58c576ca6378b18a4136f60df50560',1,'AutoCommand::run()']]] +]; diff --git a/documentation/html/search/functions_f.js b/documentation/html/search/functions_f.js new file mode 100644 index 0000000..11f44dd --- /dev/null +++ b/documentation/html/search/functions_f.js @@ -0,0 +1,24 @@ +var searchData= +[ + ['set_5faccel_0',['set_accel',['../classTrapezoidProfile.html#a1dcdfa1c290347cf0af48aca5afd167c',1,'TrapezoidProfile']]], + ['set_5fasync_1',['set_async',['../classLift.html#a7f37703180518390ec38cba9a780282b',1,'Lift']]], + ['set_5fendpts_2',['set_endpts',['../classTrapezoidProfile.html#a1d28f3fa6bf1dfa7f5c1a34d0d3b17b5',1,'TrapezoidProfile']]], + ['set_5flimits_3',['set_limits',['../classFeedback.html#a533a10b65cfc998898bf054f8b141de2',1,'Feedback::set_limits()'],['../classMotionController.html#a944c245002a1eb124dd8df40de4fcc57',1,'MotionController::set_limits()'],['../classPID.html#a8411ac48e8868d89e97afcf8990cca2c',1,'PID::set_limits()'],['../classPIDFF.html#ae0dccb27a91ec687f90c930441f246bb',1,'PIDFF::set_limits()']]], + ['set_5fmax_5fv_4',['set_max_v',['../classTrapezoidProfile.html#a6c08d08d8eadaa719f4dc9e607f9fe97',1,'TrapezoidProfile']]], + ['set_5fposition_5',['set_position',['../classLift.html#ab3cb7bc86faa079ec1249b5026ea6a85',1,'Lift::set_position()'],['../classOdometryBase.html#a34e4bd8567933d1b6bd6e41327a36549',1,'OdometryBase::set_position()'],['../classOdometryTank.html#ad3b4bcf351767992e2383ab000645335',1,'OdometryTank::set_position()']]], + ['set_5fsensor_5ffunction_6',['set_sensor_function',['../classLift.html#a08b7cdcfc9390f4945dd3737ac0e5ddc',1,'Lift']]], + ['set_5fsensor_5freset_7',['set_sensor_reset',['../classLift.html#a70b8e7cff5cd3b5827d8da07a02d92e6',1,'Lift']]], + ['set_5fsetpoint_8',['set_setpoint',['../classLift.html#a662bdc055d706699ef5cf308cd8872f8',1,'Lift']]], + ['set_5ftarget_9',['set_target',['../classPID.html#a2e301ab123c9e18e677b4873b03550dd',1,'PID::set_target()'],['../classPIDFF.html#a5b5584e4ca036b0e51c693a24a23b50b',1,'PIDFF::set_target()']]], + ['setpidtarget_10',['setPIDTarget',['../classFlywheel.html#a5eeb847c6ef4736b1917bf32843c69aa',1,'Flywheel']]], + ['setposition_11',['setPosition',['../classCustomEncoder.html#a0edd50e16020ccad5eafa55e0f80288d',1,'CustomEncoder']]], + ['setrotation_12',['setRotation',['../classCustomEncoder.html#abcb003c4627f59faa25c748c597da7fd',1,'CustomEncoder']]], + ['smallest_5fangle_13',['smallest_angle',['../classOdometryBase.html#a70ec71e9fb2e14f0a191a6bac927d36b',1,'OdometryBase']]], + ['spin_5fmanual_14',['spin_manual',['../classFlywheel.html#a291e067bcc495a9d3da16a5832d78484',1,'Flywheel']]], + ['spin_5fraw_15',['spin_raw',['../classFlywheel.html#a5f4afa2ab8976acbf9fd47776a884dd3',1,'Flywheel']]], + ['spinrpm_16',['spinRPM',['../classFlywheel.html#aa72700130c0c8a08517ec1396fe9cc2b',1,'Flywheel']]], + ['spinrpmcommand_17',['SpinRPMCommand',['../classSpinRPMCommand.html#a9bfcf882448d6d4e0860c1a7de90f9ea',1,'SpinRPMCommand']]], + ['stop_18',['stop',['../classFlywheel.html#a6634f5126f0404e0edeeff1e0e14d05e',1,'Flywheel::stop()'],['../classTankDrive.html#af10e648e4de35fa72859fb96a9a80485',1,'TankDrive::stop()']]], + ['stopmotors_19',['stopMotors',['../classFlywheel.html#a78eaa40c9c069b8b4146c3ae34a21d4e',1,'Flywheel']]], + ['stopnontasks_20',['stopNonTasks',['../classFlywheel.html#a63c9c4d3646e4ed14f3b98ce3ab28684',1,'Flywheel']]] +]; diff --git a/documentation/html/search/mag.svg b/documentation/html/search/mag.svg new file mode 100644 index 0000000..9f46b30 --- /dev/null +++ b/documentation/html/search/mag.svg @@ -0,0 +1,37 @@ + + + + + + image/svg+xml + + + + + + + + + diff --git a/documentation/html/search/mag_d.svg b/documentation/html/search/mag_d.svg new file mode 100644 index 0000000..b9a814c --- /dev/null +++ b/documentation/html/search/mag_d.svg @@ -0,0 +1,37 @@ + + + + + + image/svg+xml + + + + + + + + + diff --git a/documentation/html/search/mag_sel.svg b/documentation/html/search/mag_sel.svg new file mode 100644 index 0000000..03626f6 --- /dev/null +++ b/documentation/html/search/mag_sel.svg @@ -0,0 +1,74 @@ + + + + + + + + image/svg+xml + + + + + + + + + + + diff --git a/documentation/html/search/mag_seld.svg b/documentation/html/search/mag_seld.svg new file mode 100644 index 0000000..6e720dc --- /dev/null +++ b/documentation/html/search/mag_seld.svg @@ -0,0 +1,74 @@ + + + + + + + + image/svg+xml + + + + + + + + + + + diff --git a/documentation/html/search/pages_0.js b/documentation/html/search/pages_0.js new file mode 100644 index 0000000..1c7152d --- /dev/null +++ b/documentation/html/search/pages_0.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['core_0',['Core',['../md_README.html',1,'']]] +]; diff --git a/documentation/html/search/search.css b/documentation/html/search/search.css new file mode 100644 index 0000000..19f76f9 --- /dev/null +++ b/documentation/html/search/search.css @@ -0,0 +1,291 @@ +/*---------------- Search Box positioning */ + +#main-menu > li:last-child { + /* This
  • object is the parent of the search bar */ + display: flex; + justify-content: center; + align-items: center; + height: 36px; + margin-right: 1em; +} + +/*---------------- Search box styling */ + +.SRPage * { + font-weight: normal; + line-height: normal; +} + +dark-mode-toggle { + margin-left: 5px; + display: flex; + float: right; +} + +#MSearchBox { + display: inline-block; + white-space : nowrap; + background: var(--search-background-color); + border-radius: 0.65em; + box-shadow: var(--search-box-shadow); + z-index: 102; +} + +#MSearchBox .left { + display: inline-block; + vertical-align: middle; + height: 1.4em; +} + +#MSearchSelect { + display: inline-block; + vertical-align: middle; + width: 20px; + height: 19px; + background-image: var(--search-magnification-select-image); + margin: 0 0 0 0.3em; + padding: 0; +} + +#MSearchSelectExt { + display: inline-block; + vertical-align: middle; + width: 10px; + height: 19px; + background-image: var(--search-magnification-image); + margin: 0 0 0 0.5em; + padding: 0; +} + + +#MSearchField { + display: inline-block; + vertical-align: middle; + width: 7.5em; + height: 19px; + margin: 0 0.15em; + padding: 0; + line-height: 1em; + border:none; + color: var(--search-foreground-color); + outline: none; + font-family: var(--font-family-search); + -webkit-border-radius: 0px; + border-radius: 0px; + background: none; +} + +@media(hover: none) { + /* to avoid zooming on iOS */ + #MSearchField { + font-size: 16px; + } +} + +#MSearchBox .right { + display: inline-block; + vertical-align: middle; + width: 1.4em; + height: 1.4em; +} + +#MSearchClose { + display: none; + font-size: inherit; + background : none; + border: none; + margin: 0; + padding: 0; + outline: none; + +} + +#MSearchCloseImg { + padding: 0.3em; + margin: 0; +} + +.MSearchBoxActive #MSearchField { + color: var(--search-active-color); +} + + + +/*---------------- Search filter selection */ + +#MSearchSelectWindow { + display: none; + position: absolute; + left: 0; top: 0; + border: 1px solid var(--search-filter-border-color); + background-color: var(--search-filter-background-color); + z-index: 10001; + padding-top: 4px; + padding-bottom: 4px; + -moz-border-radius: 4px; + -webkit-border-top-left-radius: 4px; + -webkit-border-top-right-radius: 4px; + -webkit-border-bottom-left-radius: 4px; + -webkit-border-bottom-right-radius: 4px; + -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); +} + +.SelectItem { + font: 8pt var(--font-family-search); + padding-left: 2px; + padding-right: 12px; + border: 0px; +} + +span.SelectionMark { + margin-right: 4px; + font-family: var(--font-family-monospace); + outline-style: none; + text-decoration: none; +} + +a.SelectItem { + display: block; + outline-style: none; + color: var(--search-filter-foreground-color); + text-decoration: none; + padding-left: 6px; + padding-right: 12px; +} + +a.SelectItem:focus, +a.SelectItem:active { + color: var(--search-filter-foreground-color); + outline-style: none; + text-decoration: none; +} + +a.SelectItem:hover { + color: var(--search-filter-highlight-text-color); + background-color: var(--search-filter-highlight-bg-color); + outline-style: none; + text-decoration: none; + cursor: pointer; + display: block; +} + +/*---------------- Search results window */ + +iframe#MSearchResults { + /*width: 60ex;*/ + height: 15em; +} + +#MSearchResultsWindow { + display: none; + position: absolute; + left: 0; top: 0; + border: 1px solid var(--search-results-border-color); + background-color: var(--search-results-background-color); + z-index:10000; + width: 300px; + height: 400px; + overflow: auto; +} + +/* ----------------------------------- */ + + +#SRIndex { + clear:both; +} + +.SREntry { + font-size: 10pt; + padding-left: 1ex; +} + +.SRPage .SREntry { + font-size: 8pt; + padding: 1px 5px; +} + +div.SRPage { + margin: 5px 2px; + background-color: var(--search-results-background-color); +} + +.SRChildren { + padding-left: 3ex; padding-bottom: .5em +} + +.SRPage .SRChildren { + display: none; +} + +.SRSymbol { + font-weight: bold; + color: var(--search-results-foreground-color); + font-family: var(--font-family-search); + text-decoration: none; + outline: none; +} + +a.SRScope { + display: block; + color: var(--search-results-foreground-color); + font-family: var(--font-family-search); + font-size: 8pt; + text-decoration: none; + outline: none; +} + +a.SRSymbol:focus, a.SRSymbol:active, +a.SRScope:focus, a.SRScope:active { + text-decoration: underline; +} + +span.SRScope { + padding-left: 4px; + font-family: var(--font-family-search); +} + +.SRPage .SRStatus { + padding: 2px 5px; + font-size: 8pt; + font-style: italic; + font-family: var(--font-family-search); +} + +.SRResult { + display: none; +} + +div.searchresults { + margin-left: 10px; + margin-right: 10px; +} + +/*---------------- External search page results */ + +.pages b { + color: white; + padding: 5px 5px 3px 5px; + background-image: var(--nav-gradient-active-image-parent); + background-repeat: repeat-x; + text-shadow: 0 1px 1px #000000; +} + +.pages { + line-height: 17px; + margin-left: 4px; + text-decoration: none; +} + +.hl { + font-weight: bold; +} + +#searchresults { + margin-bottom: 20px; +} + +.searchpages { + margin-top: 10px; +} + diff --git a/documentation/html/search/search.js b/documentation/html/search/search.js new file mode 100644 index 0000000..e103a26 --- /dev/null +++ b/documentation/html/search/search.js @@ -0,0 +1,816 @@ +/* + @licstart The following is the entire license notice for the JavaScript code in this file. + + The MIT License (MIT) + + Copyright (C) 1997-2020 by Dimitri van Heesch + + Permission is hereby granted, free of charge, to any person obtaining a copy of this software + and associated documentation files (the "Software"), to deal in the Software without restriction, + including without limitation the rights to use, copy, modify, merge, publish, distribute, + sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in all copies or + substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING + BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, + DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + @licend The above is the entire license notice for the JavaScript code in this file + */ +function convertToId(search) +{ + var result = ''; + for (i=0;i do a search + { + this.Search(); + } + } + + this.OnSearchSelectKey = function(evt) + { + var e = (evt) ? evt : window.event; // for IE + if (e.keyCode==40 && this.searchIndex0) // Up + { + this.searchIndex--; + this.OnSelectItem(this.searchIndex); + } + else if (e.keyCode==13 || e.keyCode==27) + { + this.OnSelectItem(this.searchIndex); + this.CloseSelectionWindow(); + this.DOMSearchField().focus(); + } + return false; + } + + // --------- Actions + + // Closes the results window. + this.CloseResultsWindow = function() + { + this.DOMPopupSearchResultsWindow().style.display = 'none'; + this.DOMSearchClose().style.display = 'none'; + this.Activate(false); + } + + this.CloseSelectionWindow = function() + { + this.DOMSearchSelectWindow().style.display = 'none'; + } + + // Performs a search. + this.Search = function() + { + this.keyTimeout = 0; + + // strip leading whitespace + var searchValue = this.DOMSearchField().value.replace(/^ +/, ""); + + var code = searchValue.toLowerCase().charCodeAt(0); + var idxChar = searchValue.substr(0, 1).toLowerCase(); + if ( 0xD800 <= code && code <= 0xDBFF && searchValue > 1) // surrogate pair + { + idxChar = searchValue.substr(0, 2); + } + + var jsFile; + + var idx = indexSectionsWithContent[this.searchIndex].indexOf(idxChar); + if (idx!=-1) + { + var hexCode=idx.toString(16); + jsFile = this.resultsPath + indexSectionNames[this.searchIndex] + '_' + hexCode + '.js'; + } + + var loadJS = function(url, impl, loc){ + var scriptTag = document.createElement('script'); + scriptTag.src = url; + scriptTag.onload = impl; + scriptTag.onreadystatechange = impl; + loc.appendChild(scriptTag); + } + + var domPopupSearchResultsWindow = this.DOMPopupSearchResultsWindow(); + var domSearchBox = this.DOMSearchBox(); + var domPopupSearchResults = this.DOMPopupSearchResults(); + var domSearchClose = this.DOMSearchClose(); + var resultsPath = this.resultsPath; + + var handleResults = function() { + document.getElementById("Loading").style.display="none"; + if (typeof searchData !== 'undefined') { + createResults(resultsPath); + document.getElementById("NoMatches").style.display="none"; + } + + searchResults.Search(searchValue); + + if (domPopupSearchResultsWindow.style.display!='block') + { + domSearchClose.style.display = 'inline-block'; + var left = getXPos(domSearchBox) + 150; + var top = getYPos(domSearchBox) + 20; + domPopupSearchResultsWindow.style.display = 'block'; + left -= domPopupSearchResults.offsetWidth; + var maxWidth = document.body.clientWidth; + var maxHeight = document.body.clientHeight; + var width = 300; + if (left<10) left=10; + if (width+left+8>maxWidth) width=maxWidth-left-8; + var height = 400; + if (height+top+8>maxHeight) height=maxHeight-top-8; + domPopupSearchResultsWindow.style.top = top + 'px'; + domPopupSearchResultsWindow.style.left = left + 'px'; + domPopupSearchResultsWindow.style.width = width + 'px'; + domPopupSearchResultsWindow.style.height = height + 'px'; + } + } + + if (jsFile) { + loadJS(jsFile, handleResults, this.DOMPopupSearchResultsWindow()); + } else { + handleResults(); + } + + this.lastSearchValue = searchValue; + } + + // -------- Activation Functions + + // Activates or deactivates the search panel, resetting things to + // their default values if necessary. + this.Activate = function(isActive) + { + if (isActive || // open it + this.DOMPopupSearchResultsWindow().style.display == 'block' + ) + { + this.DOMSearchBox().className = 'MSearchBoxActive'; + this.searchActive = true; + } + else if (!isActive) // directly remove the panel + { + this.DOMSearchBox().className = 'MSearchBoxInactive'; + this.searchActive = false; + this.lastSearchValue = '' + this.lastResultsPage = ''; + this.DOMSearchField().value = ''; + } + } +} + +// ----------------------------------------------------------------------- + +// The class that handles everything on the search results page. +function SearchResults(name) +{ + // The number of matches from the last run of . + this.lastMatchCount = 0; + this.lastKey = 0; + this.repeatOn = false; + + // Toggles the visibility of the passed element ID. + this.FindChildElement = function(id) + { + var parentElement = document.getElementById(id); + var element = parentElement.firstChild; + + while (element && element!=parentElement) + { + if (element.nodeName.toLowerCase() == 'div' && element.className == 'SRChildren') + { + return element; + } + + if (element.nodeName.toLowerCase() == 'div' && element.hasChildNodes()) + { + element = element.firstChild; + } + else if (element.nextSibling) + { + element = element.nextSibling; + } + else + { + do + { + element = element.parentNode; + } + while (element && element!=parentElement && !element.nextSibling); + + if (element && element!=parentElement) + { + element = element.nextSibling; + } + } + } + } + + this.Toggle = function(id) + { + var element = this.FindChildElement(id); + if (element) + { + if (element.style.display == 'block') + { + element.style.display = 'none'; + } + else + { + element.style.display = 'block'; + } + } + } + + // Searches for the passed string. If there is no parameter, + // it takes it from the URL query. + // + // Always returns true, since other documents may try to call it + // and that may or may not be possible. + this.Search = function(search) + { + if (!search) // get search word from URL + { + search = window.location.search; + search = search.substring(1); // Remove the leading '?' + search = unescape(search); + } + + search = search.replace(/^ +/, ""); // strip leading spaces + search = search.replace(/ +$/, ""); // strip trailing spaces + search = search.toLowerCase(); + search = convertToId(search); + + var resultRows = document.getElementsByTagName("div"); + var matches = 0; + + var i = 0; + while (i < resultRows.length) + { + var row = resultRows.item(i); + if (row.className == "SRResult") + { + var rowMatchName = row.id.toLowerCase(); + rowMatchName = rowMatchName.replace(/^sr\d*_/, ''); // strip 'sr123_' + + if (search.length<=rowMatchName.length && + rowMatchName.substr(0, search.length)==search) + { + row.style.display = 'block'; + matches++; + } + else + { + row.style.display = 'none'; + } + } + i++; + } + document.getElementById("Searching").style.display='none'; + if (matches == 0) // no results + { + document.getElementById("NoMatches").style.display='block'; + } + else // at least one result + { + document.getElementById("NoMatches").style.display='none'; + } + this.lastMatchCount = matches; + return true; + } + + // return the first item with index index or higher that is visible + this.NavNext = function(index) + { + var focusItem; + while (1) + { + var focusName = 'Item'+index; + focusItem = document.getElementById(focusName); + if (focusItem && focusItem.parentNode.parentNode.style.display=='block') + { + break; + } + else if (!focusItem) // last element + { + break; + } + focusItem=null; + index++; + } + return focusItem; + } + + this.NavPrev = function(index) + { + var focusItem; + while (1) + { + var focusName = 'Item'+index; + focusItem = document.getElementById(focusName); + if (focusItem && focusItem.parentNode.parentNode.style.display=='block') + { + break; + } + else if (!focusItem) // last element + { + break; + } + focusItem=null; + index--; + } + return focusItem; + } + + this.ProcessKeys = function(e) + { + if (e.type == "keydown") + { + this.repeatOn = false; + this.lastKey = e.keyCode; + } + else if (e.type == "keypress") + { + if (!this.repeatOn) + { + if (this.lastKey) this.repeatOn = true; + return false; // ignore first keypress after keydown + } + } + else if (e.type == "keyup") + { + this.lastKey = 0; + this.repeatOn = false; + } + return this.lastKey!=0; + } + + this.Nav = function(evt,itemIndex) + { + var e = (evt) ? evt : window.event; // for IE + if (e.keyCode==13) return true; + if (!this.ProcessKeys(e)) return false; + + if (this.lastKey==38) // Up + { + var newIndex = itemIndex-1; + var focusItem = this.NavPrev(newIndex); + if (focusItem) + { + var child = this.FindChildElement(focusItem.parentNode.parentNode.id); + if (child && child.style.display == 'block') // children visible + { + var n=0; + var tmpElem; + while (1) // search for last child + { + tmpElem = document.getElementById('Item'+newIndex+'_c'+n); + if (tmpElem) + { + focusItem = tmpElem; + } + else // found it! + { + break; + } + n++; + } + } + } + if (focusItem) + { + focusItem.focus(); + } + else // return focus to search field + { + document.getElementById("MSearchField").focus(); + } + } + else if (this.lastKey==40) // Down + { + var newIndex = itemIndex+1; + var focusItem; + var item = document.getElementById('Item'+itemIndex); + var elem = this.FindChildElement(item.parentNode.parentNode.id); + if (elem && elem.style.display == 'block') // children visible + { + focusItem = document.getElementById('Item'+itemIndex+'_c0'); + } + if (!focusItem) focusItem = this.NavNext(newIndex); + if (focusItem) focusItem.focus(); + } + else if (this.lastKey==39) // Right + { + var item = document.getElementById('Item'+itemIndex); + var elem = this.FindChildElement(item.parentNode.parentNode.id); + if (elem) elem.style.display = 'block'; + } + else if (this.lastKey==37) // Left + { + var item = document.getElementById('Item'+itemIndex); + var elem = this.FindChildElement(item.parentNode.parentNode.id); + if (elem) elem.style.display = 'none'; + } + else if (this.lastKey==27) // Escape + { + searchBox.CloseResultsWindow(); + document.getElementById("MSearchField").focus(); + } + else if (this.lastKey==13) // Enter + { + return true; + } + return false; + } + + this.NavChild = function(evt,itemIndex,childIndex) + { + var e = (evt) ? evt : window.event; // for IE + if (e.keyCode==13) return true; + if (!this.ProcessKeys(e)) return false; + + if (this.lastKey==38) // Up + { + if (childIndex>0) + { + var newIndex = childIndex-1; + document.getElementById('Item'+itemIndex+'_c'+newIndex).focus(); + } + else // already at first child, jump to parent + { + document.getElementById('Item'+itemIndex).focus(); + } + } + else if (this.lastKey==40) // Down + { + var newIndex = childIndex+1; + var elem = document.getElementById('Item'+itemIndex+'_c'+newIndex); + if (!elem) // last child, jump to parent next parent + { + elem = this.NavNext(itemIndex+1); + } + if (elem) + { + elem.focus(); + } + } + else if (this.lastKey==27) // Escape + { + searchBox.CloseResultsWindow(); + document.getElementById("MSearchField").focus(); + } + else if (this.lastKey==13) // Enter + { + return true; + } + return false; + } +} + +function setKeyActions(elem,action) +{ + elem.setAttribute('onkeydown',action); + elem.setAttribute('onkeypress',action); + elem.setAttribute('onkeyup',action); +} + +function setClassAttr(elem,attr) +{ + elem.setAttribute('class',attr); + elem.setAttribute('className',attr); +} + +function createResults(resultsPath) +{ + var results = document.getElementById("SRResults"); + results.innerHTML = ''; + for (var e=0; e-{AmhX=Jf(#6djGiuzAr*{o?=JLmPLyc> z_*`QK&+BH@jWrYJ7>r6%keRM@)Qyv8R=enp0jiI>aWlGyB58O zFVR20d+y`K7vDw(hJF3;>dD*3-?v=<8M)@x|EEGLnJsniYK!2U1 Y!`|5biEc?d1`HDhPgg&ebxsLQ02F6;9RL6T literal 0 HcmV?d00001 diff --git a/documentation/html/splitbard.png b/documentation/html/splitbard.png new file mode 100644 index 0000000000000000000000000000000000000000..8367416d757fd7b6dc4272b6432dc75a75abd068 GIT binary patch literal 282 zcmeAS@N?(olHy`uVBq!ia0vp^Yzz!63>-{AmhX=Jf@VhhFKy35^fiT zT~&lUj3=cDh^%3HDY9k5CEku}PHXNoNC(_$U3XPb&Q*ME25pT;2(*BOgAf<+R$lzakPG`kF31()Fx{L5Wrac|GQzjeE= zueY1`Ze{#x<8=S|`~MgGetGce)#vN&|J{Cd^tS%;tBYTo?+^d68<#n_Y_xx`J||4O V@QB{^CqU0Kc)I$ztaD0e0svEzbJzd? literal 0 HcmV?d00001 diff --git a/documentation/html/structAutoChooser_1_1entry__t-members.html b/documentation/html/structAutoChooser_1_1entry__t-members.html new file mode 100644 index 0000000..29aefb8 --- /dev/null +++ b/documentation/html/structAutoChooser_1_1entry__t-members.html @@ -0,0 +1,93 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    AutoChooser::entry_t Member List
    +
    +
    + +

    This is the complete list of members for AutoChooser::entry_t, including all inherited members.

    + + + + + + +
    heightAutoChooser::entry_t
    nameAutoChooser::entry_t
    widthAutoChooser::entry_t
    xAutoChooser::entry_t
    yAutoChooser::entry_t
    + + + + diff --git a/documentation/html/structAutoChooser_1_1entry__t.html b/documentation/html/structAutoChooser_1_1entry__t.html new file mode 100644 index 0000000..9ea28fd --- /dev/null +++ b/documentation/html/structAutoChooser_1_1entry__t.html @@ -0,0 +1,185 @@ + + + + + + + +RIT VEXU Core API: AutoChooser::entry_t Struct Reference + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    + +
    AutoChooser::entry_t Struct Reference
    +
    +
    + +

    #include <auto_chooser.h>

    + + + + + + + + + + + + +

    +Public Attributes

    int x
     
    int y
     
    int width
     
    int height
     
    std::string name
     
    +

    Detailed Description

    +

    entry_t is a datatype used to store information that the chooser knows about an auto selection button

    +

    Member Data Documentation

    + +

    ◆ height

    + +
    +
    + + + + +
    int AutoChooser::entry_t::height
    +
    +

    height of the block

    + +
    +
    + +

    ◆ name

    + +
    +
    + + + + +
    std::string AutoChooser::entry_t::name
    +
    +

    name of the auto repretsented by the block

    + +
    +
    + +

    ◆ width

    + +
    +
    + + + + +
    int AutoChooser::entry_t::width
    +
    +

    width of the block

    + +
    +
    + +

    ◆ x

    + +
    +
    + + + + +
    int AutoChooser::entry_t::x
    +
    +

    screen x position of the block

    + +
    +
    + +

    ◆ y

    + +
    +
    + + + + +
    int AutoChooser::entry_t::y
    +
    +

    screen y position of the block

    + +
    +
    +
    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/documentation/html/structFeedForward_1_1ff__config__t-members.html b/documentation/html/structFeedForward_1_1ff__config__t-members.html new file mode 100644 index 0000000..55707d9 --- /dev/null +++ b/documentation/html/structFeedForward_1_1ff__config__t-members.html @@ -0,0 +1,92 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    FeedForward::ff_config_t Member List
    +
    +
    + +

    This is the complete list of members for FeedForward::ff_config_t, including all inherited members.

    + + + + + +
    kAFeedForward::ff_config_t
    kGFeedForward::ff_config_t
    kSFeedForward::ff_config_t
    kVFeedForward::ff_config_t
    + + + + diff --git a/documentation/html/structFeedForward_1_1ff__config__t.html b/documentation/html/structFeedForward_1_1ff__config__t.html new file mode 100644 index 0000000..383a6fa --- /dev/null +++ b/documentation/html/structFeedForward_1_1ff__config__t.html @@ -0,0 +1,172 @@ + + + + + + + +RIT VEXU Core API: FeedForward::ff_config_t Struct Reference + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    + +
    FeedForward::ff_config_t Struct Reference
    +
    +
    + +

    #include <feedforward.h>

    + + + + + + + + + + +

    +Public Attributes

    double kS
     
    double kV
     
    double kA
     
    double kG
     
    +

    Detailed Description

    +

    ff_config_t holds the parameters to make the theoretical model of a real world system equation is of the form kS if the system is not stopped, 0 otherwise

      +
    • kV * desired velocity
    • +
    • kA * desired acceleration
    • +
    • kG
    • +
    +

    Member Data Documentation

    + +

    ◆ kA

    + +
    +
    + + + + +
    double FeedForward::ff_config_t::kA
    +
    +

    kA - Acceleration coefficient: the power required to change the mechanism's speed. Multiplied by the requested acceleration.

    + +
    +
    + +

    ◆ kG

    + +
    +
    + + + + +
    double FeedForward::ff_config_t::kG
    +
    +

    kG - Gravity coefficient: only needed for lifts. The power required to overcome gravity and stay at steady state.

    + +
    +
    + +

    ◆ kS

    + +
    +
    + + + + +
    double FeedForward::ff_config_t::kS
    +
    +

    Coefficient to overcome static friction: the point at which the motor starts to move.

    + +
    +
    + +

    ◆ kV

    + +
    +
    + + + + +
    double FeedForward::ff_config_t::kV
    +
    +

    Veclocity coefficient: the power required to keep the mechanism in motion. Multiplied by the requested velocity.

    + +
    +
    +
    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/documentation/html/structLift_1_1lift__cfg__t-members.html b/documentation/html/structLift_1_1lift__cfg__t-members.html new file mode 100644 index 0000000..5e638c5 --- /dev/null +++ b/documentation/html/structLift_1_1lift__cfg__t-members.html @@ -0,0 +1,93 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    Lift< T >::lift_cfg_t Member List
    +
    +
    + +

    This is the complete list of members for Lift< T >::lift_cfg_t, including all inherited members.

    + + + + + + +
    down_speed (defined in Lift< T >::lift_cfg_t)Lift< T >::lift_cfg_t
    lift_pid_cfg (defined in Lift< T >::lift_cfg_t)Lift< T >::lift_cfg_t
    softstop_down (defined in Lift< T >::lift_cfg_t)Lift< T >::lift_cfg_t
    softstop_up (defined in Lift< T >::lift_cfg_t)Lift< T >::lift_cfg_t
    up_speed (defined in Lift< T >::lift_cfg_t)Lift< T >::lift_cfg_t
    + + + + diff --git a/documentation/html/structLift_1_1lift__cfg__t.html b/documentation/html/structLift_1_1lift__cfg__t.html new file mode 100644 index 0000000..8be1571 --- /dev/null +++ b/documentation/html/structLift_1_1lift__cfg__t.html @@ -0,0 +1,118 @@ + + + + + + + +RIT VEXU Core API: Lift< T >::lift_cfg_t Struct Reference + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    + +
    Lift< T >::lift_cfg_t Struct Reference
    +
    +
    + +

    #include <lift.h>

    + + + + + + + + + + + + +

    +Public Attributes

    +double up_speed
     
    +double down_speed
     
    +double softstop_up
     
    +double softstop_down
     
    +PID::pid_config_t lift_pid_cfg
     
    +

    Detailed Description

    +
    template<typename T>
    +struct Lift< T >::lift_cfg_t

    lift_cfg_t holds the physical parameter specifications of a lify system. includes:

      +
    • maximum speeds for the system
    • +
    • softstops to stop the lift from hitting the hard stops too hard
    • +
    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/documentation/html/structMecanumDrive_1_1mecanumdrive__config__t-members.html b/documentation/html/structMecanumDrive_1_1mecanumdrive__config__t-members.html new file mode 100644 index 0000000..c9ca8e9 --- /dev/null +++ b/documentation/html/structMecanumDrive_1_1mecanumdrive__config__t-members.html @@ -0,0 +1,94 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    MecanumDrive::mecanumdrive_config_t Member List
    +
    + + + + + diff --git a/documentation/html/structMecanumDrive_1_1mecanumdrive__config__t.html b/documentation/html/structMecanumDrive_1_1mecanumdrive__config__t.html new file mode 100644 index 0000000..f06243a --- /dev/null +++ b/documentation/html/structMecanumDrive_1_1mecanumdrive__config__t.html @@ -0,0 +1,117 @@ + + + + + + + +RIT VEXU Core API: MecanumDrive::mecanumdrive_config_t Struct Reference + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    + +
    MecanumDrive::mecanumdrive_config_t Struct Reference
    +
    +
    + +

    #include <mecanum_drive.h>

    + + + + + + + + + + + + + + +

    +Public Attributes

    +PID::pid_config_t drive_pid_conf
     
    +PID::pid_config_t drive_gyro_pid_conf
     
    +PID::pid_config_t turn_pid_conf
     
    +double drive_wheel_diam
     
    +double lateral_wheel_diam
     
    +double wheelbase_width
     
    +

    Detailed Description

    +

    Configure the Mecanum drive PID tunings and robot configurations

    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/documentation/html/structMotionController_1_1m__profile__cfg__t-members.html b/documentation/html/structMotionController_1_1m__profile__cfg__t-members.html new file mode 100644 index 0000000..25c6351 --- /dev/null +++ b/documentation/html/structMotionController_1_1m__profile__cfg__t-members.html @@ -0,0 +1,92 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    MotionController::m_profile_cfg_t Member List
    +
    + + + + + diff --git a/documentation/html/structMotionController_1_1m__profile__cfg__t.html b/documentation/html/structMotionController_1_1m__profile__cfg__t.html new file mode 100644 index 0000000..46a92f1 --- /dev/null +++ b/documentation/html/structMotionController_1_1m__profile__cfg__t.html @@ -0,0 +1,115 @@ + + + + + + + +RIT VEXU Core API: MotionController::m_profile_cfg_t Struct Reference + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    + +
    MotionController::m_profile_cfg_t Struct Reference
    +
    +
    + +

    #include <motion_controller.h>

    + + + + + + + + + + + + + + +

    +Public Attributes

    +double max_v
     the maximum velocity the robot can drive
     
    +double accel
     the most acceleration the robot can do
     
    +PID::pid_config_t pid_cfg
     configuration parameters for the internal PID controller
     
    +FeedForward::ff_config_t ff_cfg
     configuration parameters for the internal
     
    +

    Detailed Description

    +

    m_profile_config holds all data the motion controller uses to plan paths When motion pofile is given a target to drive to, max_v and accel are used to make the trapezoid profile instructing the controller how to drive pid_cfg, ff_cfg are used to find the motor outputs necessary to execute this path

    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/documentation/html/structOdometry3Wheel_1_1odometry3wheel__cfg__t-members.html b/documentation/html/structOdometry3Wheel_1_1odometry3wheel__cfg__t-members.html new file mode 100644 index 0000000..d5cf655 --- /dev/null +++ b/documentation/html/structOdometry3Wheel_1_1odometry3wheel__cfg__t-members.html @@ -0,0 +1,91 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    Odometry3Wheel::odometry3wheel_cfg_t Member List
    +
    + + + + + diff --git a/documentation/html/structOdometry3Wheel_1_1odometry3wheel__cfg__t.html b/documentation/html/structOdometry3Wheel_1_1odometry3wheel__cfg__t.html new file mode 100644 index 0000000..fce4bb3 --- /dev/null +++ b/documentation/html/structOdometry3Wheel_1_1odometry3wheel__cfg__t.html @@ -0,0 +1,151 @@ + + + + + + + +RIT VEXU Core API: Odometry3Wheel::odometry3wheel_cfg_t Struct Reference + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    + +
    Odometry3Wheel::odometry3wheel_cfg_t Struct Reference
    +
    +
    + +

    #include <odometry_3wheel.h>

    + + + + + + + + +

    +Public Attributes

    double wheelbase_dist
     
    double off_axis_center_dist
     
    double wheel_diam
     
    +

    Detailed Description

    +

    odometry3wheel_cfg_t holds all the specifications for how to calculate position with 3 encoders See the core wiki for what exactly each of these parameters measures

    +

    Member Data Documentation

    + +

    ◆ off_axis_center_dist

    + +
    +
    + + + + +
    double Odometry3Wheel::odometry3wheel_cfg_t::off_axis_center_dist
    +
    +

    distance from the center of the robot to the center off axis wheel

    + +
    +
    + +

    ◆ wheel_diam

    + +
    +
    + + + + +
    double Odometry3Wheel::odometry3wheel_cfg_t::wheel_diam
    +
    +

    the diameter of the tracking wheel

    + +
    +
    + +

    ◆ wheelbase_dist

    + +
    +
    + + + + +
    double Odometry3Wheel::odometry3wheel_cfg_t::wheelbase_dist
    +
    +

    distance from the center of the left wheel to the center of the right wheel

    + +
    +
    +
    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/documentation/html/structPID_1_1pid__config__t-members.html b/documentation/html/structPID_1_1pid__config__t-members.html new file mode 100644 index 0000000..b47549d --- /dev/null +++ b/documentation/html/structPID_1_1pid__config__t-members.html @@ -0,0 +1,94 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    PID::pid_config_t Member List
    +
    + + + + + diff --git a/documentation/html/structPID_1_1pid__config__t.html b/documentation/html/structPID_1_1pid__config__t.html new file mode 100644 index 0000000..b10b51a --- /dev/null +++ b/documentation/html/structPID_1_1pid__config__t.html @@ -0,0 +1,126 @@ + + + + + + + +RIT VEXU Core API: PID::pid_config_t Struct Reference + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    + +
    PID::pid_config_t Struct Reference
    +
    +
    + +

    #include <pid.h>

    + + + + + + + + + + + + + + + + + + + + +

    +Public Attributes

    +double p
     proportional coeffecient p * error()
     
    +double i
     integral coeffecient i * integral(error)
     
    +double d
     derivitave coeffecient d * derivative(error)
     
    +double deadband
     at what threshold are we close enough to be finished
     
    +double on_target_time
     the time in seconds that we have to be on target for to say we are officially at the target
     
    +ERROR_TYPE error_method
     Linear or angular. wheter to do error as a simple subtraction or to wrap.
     
    +

    Detailed Description

    +

    pid_config_t holds the configuration parameters for a pid controller In addtion to the constant of proportional, integral and derivative, these parameters include:

      +
    • deadband -
    • +
    • on_target_time - for how long do we have to be at the target to stop As well, pid_config_t holds an error type which determines whether errors should be calculated as if the sensor position is a measure of distance or an angle
    • +
    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/documentation/html/structPurePursuit_1_1hermite__point-members.html b/documentation/html/structPurePursuit_1_1hermite__point-members.html new file mode 100644 index 0000000..1c11649 --- /dev/null +++ b/documentation/html/structPurePursuit_1_1hermite__point-members.html @@ -0,0 +1,94 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    PurePursuit::hermite_point Member List
    +
    + + + + + diff --git a/documentation/html/structPurePursuit_1_1hermite__point.html b/documentation/html/structPurePursuit_1_1hermite__point.html new file mode 100644 index 0000000..411c4ef --- /dev/null +++ b/documentation/html/structPurePursuit_1_1hermite__point.html @@ -0,0 +1,121 @@ + + + + + + + +RIT VEXU Core API: PurePursuit::hermite_point Struct Reference + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    + +
    PurePursuit::hermite_point Struct Reference
    +
    +
    + +

    #include <pure_pursuit.h>

    + + + + + + +

    +Public Member Functions

    +Vector2D::point_t getPoint ()
     
    +Vector2D getTangent ()
     
    + + + + + + + + + +

    +Public Attributes

    +double x
     
    +double y
     
    +double dir
     
    +double mag
     
    +

    Detailed Description

    +

    a position along the hermite path contains a position and orientation information that the robot would be at at this point

    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/documentation/html/structPurePursuit_1_1spline-members.html b/documentation/html/structPurePursuit_1_1spline-members.html new file mode 100644 index 0000000..a58bcd5 --- /dev/null +++ b/documentation/html/structPurePursuit_1_1spline-members.html @@ -0,0 +1,95 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    PurePursuit::spline Member List
    +
    +
    + +

    This is the complete list of members for PurePursuit::spline, including all inherited members.

    + + + + + + + + +
    a (defined in PurePursuit::spline)PurePursuit::spline
    b (defined in PurePursuit::spline)PurePursuit::spline
    c (defined in PurePursuit::spline)PurePursuit::spline
    d (defined in PurePursuit::spline)PurePursuit::spline
    getY(double x) (defined in PurePursuit::spline)PurePursuit::splineinline
    x_end (defined in PurePursuit::spline)PurePursuit::spline
    x_start (defined in PurePursuit::spline)PurePursuit::spline
    + + + + diff --git a/documentation/html/structPurePursuit_1_1spline.html b/documentation/html/structPurePursuit_1_1spline.html new file mode 100644 index 0000000..b4ac19b --- /dev/null +++ b/documentation/html/structPurePursuit_1_1spline.html @@ -0,0 +1,124 @@ + + + + + + + +RIT VEXU Core API: PurePursuit::spline Struct Reference + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    + +
    PurePursuit::spline Struct Reference
    +
    +
    + +

    #include <pure_pursuit.h>

    + + + + +

    +Public Member Functions

    +double getY (double x)
     
    + + + + + + + + + + + + + +

    +Public Attributes

    +double a
     
    +double b
     
    +double c
     
    +double d
     
    +double x_start
     
    +double x_end
     
    +

    Detailed Description

    +

    Represents a piece of a cubic spline with s(x) = a(x-xi)^3 + b(x-xi)^2 + c(x-xi) + d The x_start and x_end shows where the equation is valid.

    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/documentation/html/structVector2D_1_1point__t-members.html b/documentation/html/structVector2D_1_1point__t-members.html new file mode 100644 index 0000000..6bdec25 --- /dev/null +++ b/documentation/html/structVector2D_1_1point__t-members.html @@ -0,0 +1,93 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    Vector2D::point_t Member List
    +
    +
    + +

    This is the complete list of members for Vector2D::point_t, including all inherited members.

    + + + + + + +
    dist(const point_t other)Vector2D::point_tinline
    operator+(const point_t &other)Vector2D::point_tinline
    operator-(const point_t &other)Vector2D::point_tinline
    xVector2D::point_t
    yVector2D::point_t
    + + + + diff --git a/documentation/html/structVector2D_1_1point__t.html b/documentation/html/structVector2D_1_1point__t.html new file mode 100644 index 0000000..83ca1b1 --- /dev/null +++ b/documentation/html/structVector2D_1_1point__t.html @@ -0,0 +1,217 @@ + + + + + + + +RIT VEXU Core API: Vector2D::point_t Struct Reference + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    + +
    Vector2D::point_t Struct Reference
    +
    +
    + +

    #include <vector2d.h>

    + + + + + + + + +

    +Public Member Functions

    double dist (const point_t other)
     
    point_t operator+ (const point_t &other)
     
    point_t operator- (const point_t &other)
     
    + + + + + + + +

    +Public Attributes

    +double x
     the x position in space
     
    +double y
     the y position in space
     
    +

    Detailed Description

    +

    Data structure representing an X,Y coordinate

    +

    Member Function Documentation

    + +

    ◆ dist()

    + +
    +
    + + + + + +
    + + + + + + + + +
    double Vector2D::point_t::dist (const point_t other)
    +
    +inline
    +
    +

    dist calculates the euclidian distance between this point and another point using the pythagorean theorem

    Parameters
    + + +
    otherthe point to measure the distance from
    +
    +
    +
    Returns
    the euclidian distance between this and other
    + +
    +
    + +

    ◆ operator+()

    + +
    +
    + + + + + +
    + + + + + + + + +
    point_t Vector2D::point_t::operator+ (const point_tother)
    +
    +inline
    +
    +

    Vector2D addition operation on points

    Parameters
    + + +
    otherthe point to add on to this
    +
    +
    +
    Returns
    this + other (this.x + other.x, this.y + other.y)
    + +
    +
    + +

    ◆ operator-()

    + +
    +
    + + + + + +
    + + + + + + + + +
    point_t Vector2D::point_t::operator- (const point_tother)
    +
    +inline
    +
    +

    Vector2D subtraction operation on points

    Parameters
    + + +
    otherthe point_t to subtract from this
    +
    +
    +
    Returns
    this - other (this.x - other.x, this.y - other.y)
    + +
    +
    +
    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/documentation/html/structmotion__t-members.html b/documentation/html/structmotion__t-members.html new file mode 100644 index 0000000..73ce7f0 --- /dev/null +++ b/documentation/html/structmotion__t-members.html @@ -0,0 +1,87 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    +
    motion_t Member List
    +
    +
    + +

    This is the complete list of members for motion_t, including all inherited members.

    + + + + +
    accelmotion_t
    posmotion_t
    velmotion_t
    + + + + diff --git a/documentation/html/structmotion__t.html b/documentation/html/structmotion__t.html new file mode 100644 index 0000000..d995439 --- /dev/null +++ b/documentation/html/structmotion__t.html @@ -0,0 +1,107 @@ + + + + + + + +RIT VEXU Core API: motion_t Struct Reference + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    + +
    motion_t Struct Reference
    +
    +
    + +

    #include <trapezoid_profile.h>

    + + + + + + + + + + + +

    +Public Attributes

    +double pos
     1d position at this point in time
     
    +double vel
     1d velocity at this point in time
     
    +double accel
     1d acceleration at this point in time
     
    +

    Detailed Description

    +

    motion_t is a description of 1 dimensional motion at a point in time.

    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/documentation/html/structposition__t-members.html b/documentation/html/structposition__t-members.html new file mode 100644 index 0000000..70e5d9a --- /dev/null +++ b/documentation/html/structposition__t-members.html @@ -0,0 +1,87 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    +
    position_t Member List
    +
    +
    + +

    This is the complete list of members for position_t, including all inherited members.

    + + + + +
    rotposition_t
    xposition_t
    yposition_t
    + + + + diff --git a/documentation/html/structposition__t.html b/documentation/html/structposition__t.html new file mode 100644 index 0000000..2bb5f2e --- /dev/null +++ b/documentation/html/structposition__t.html @@ -0,0 +1,107 @@ + + + + + + + +RIT VEXU Core API: position_t Struct Reference + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    + +
    position_t Struct Reference
    +
    +
    + +

    #include <odometry_base.h>

    + + + + + + + + + + + +

    +Public Attributes

    +double x
     x position in the world
     
    +double y
     y position in the world
     
    +double rot
     rotation in the world
     
    +

    Detailed Description

    +

    Describes a single position and rotation

    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/documentation/html/structrobot__specs__t-members.html b/documentation/html/structrobot__specs__t-members.html new file mode 100644 index 0000000..ffedc78 --- /dev/null +++ b/documentation/html/structrobot__specs__t-members.html @@ -0,0 +1,92 @@ + + + + + + + +RIT VEXU Core API: Member List + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    +
    robot_specs_t Member List
    +
    + + + + + diff --git a/documentation/html/structrobot__specs__t.html b/documentation/html/structrobot__specs__t.html new file mode 100644 index 0000000..4014338 --- /dev/null +++ b/documentation/html/structrobot__specs__t.html @@ -0,0 +1,127 @@ + + + + + + + +RIT VEXU Core API: robot_specs_t Struct Reference + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    + +
    robot_specs_t Struct Reference
    +
    +
    + +

    #include <robot_specs.h>

    + + + + + + + + + + + + + + + + + + + + + + + + + + +

    +Public Attributes

    +double robot_radius
     if you were to draw a circle with this radius, the robot would be entirely contained within it
     
    +double odom_wheel_diam
     the diameter of the wheels used for
     
    +double odom_gear_ratio
     the ratio of the odometry wheel to the encoder reading odometry data
     
    +double dist_between_wheels
     the distance between centers of the central drive wheels
     
    +double drive_correction_cutoff
     the distance at which to stop trying to turn towards the target. If we are less than this value, we can continue driving forward to minimize our distance but will not try to spin around to point directly at the target
     
    +Feedbackdrive_feedback
     the default feedback for autonomous driving
     
    +Feedbackturn_feedback
     the defualt feedback for autonomous turning
     
    +PID::pid_config_t correction_pid
     the pid controller to keep the robot driving in as straight a line as possible
     
    +

    Detailed Description

    +

    Main robot characterization struct. This will be passed to all the major subsystems that require info about the robot. All distance measurements are in inches.

    +

    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/documentation/html/sync_off.png b/documentation/html/sync_off.png new file mode 100644 index 0000000000000000000000000000000000000000..3b443fc62892114406e3d399421b2a881b897acc GIT binary patch literal 853 zcmV-b1FHOqP)oT|#XixUYy%lpuf3i8{fX!o zUyDD0jOrAiT^tq>fLSOOABs-#u{dV^F$b{L9&!2=9&RmV;;8s^x&UqB$PCj4FdKbh zoB1WTskPUPu05XzFbA}=KZ-GP1fPpAfSs>6AHb12UlR%-i&uOlTpFNS7{jm@mkU1V zh`nrXr~+^lsV-s1dkZOaI|kYyVj3WBpPCY{n~yd%u%e+d=f%`N0FItMPtdgBb@py; zq@v6NVArhyTC7)ULw-Jy8y42S1~4n(3LkrW8mW(F-4oXUP3E`e#g**YyqI7h-J2zK zK{m9##m4ri!7N>CqQqCcnI3hqo1I;Yh&QLNY4T`*ptiQGozK>FF$!$+84Z`xwmeMh zJ0WT+OH$WYFALEaGj2_l+#DC3t7_S`vHpSivNeFbP6+r50cO8iu)`7i%Z4BTPh@_m3Tk!nAm^)5Bqnr%Ov|Baunj#&RPtRuK& z4RGz|D5HNrW83-#ydk}tVKJrNmyYt-sTxLGlJY5nc&Re zU4SgHNPx8~Yxwr$bsju?4q&%T1874xxzq+_%?h8_ofw~(bld=o3iC)LUNR*BY%c0y zWd_jX{Y8`l%z+ol1$@Qa?Cy!(0CVIEeYpKZ`(9{z>3$CIe;pJDQk$m3p}$>xBm4lb zKo{4S)`wdU9Ba9jJbVJ0C=SOefZe%d$8=2r={nu<_^a3~>c#t_U6dye5)JrR(_a^E f@}b6j1K9lwFJq@>o)+Ry00000NkvXXu0mjfWa5j* literal 0 HcmV?d00001 diff --git a/documentation/html/sync_on.png b/documentation/html/sync_on.png new file mode 100644 index 0000000000000000000000000000000000000000..e08320fb64e6fa33b573005ed6d8fe294e19db76 GIT binary patch literal 845 zcmV-T1G4;yP)Y;xxyHF2B5Wzm| zOOGupOTn@c(JmBOl)e;XMNnZuiTJP>rM8<|Q`7I_))aP?*T)ow&n59{}X4$3Goat zgjs?*aasfbrokzG5cT4K=uG`E14xZl@z)F={P0Y^?$4t z>v!teRnNZym<6h{7sLyF1V0HsfEl+l6TrZpsfr1}luH~F7L}ktXu|*uVX^RG$L0`K zWs3j|0tIvVe(N%_?2{(iCPFGf#B6Hjy6o&}D$A%W%jfO8_W%ZO#-mh}EM$LMn7joJ z05dHr!5Y92g+31l<%i1(=L1a1pXX+OYnalY>31V4K}BjyRe3)9n#;-cCVRD_IG1fT zOKGeNY8q;TL@K{dj@D^scf&VCs*-Jb>8b>|`b*osv52-!A?BpbYtTQBns5EAU**$m zSnVSm(teh>tQi*S*A>#ySc=n;`BHz`DuG4&g4Kf8lLhca+zvZ7t7RflD6-i-mcK=M z!=^P$*u2)bkY5asG4gsss!Hn%u~>}kIW`vMs%lJLH+u*9<4PaV_c6U`KqWXQH%+Nu zTv41O(^ZVi@qhjQdG!fbZw&y+2o!iYymO^?ud3{P*HdoX83YV*Uu_HB=?U&W9%AU# z80}k1SS-CXTU7dcQlsm<^oYLxVSseqY6NO}dc`Nj?8vrhNuCdm@^{a3AQ_>6myOj+ z`1RsLUXF|dm|3k7s2jD(B{rzE>WI2scH8i1;=O5Cc9xB3^aJk%fQjqsu+kH#0=_5a z0nCE8@dbQa-|YIuUVvG0L_IwHMEhOj$Mj4Uq05 X8=0q~qBNan00000NkvXXu0mjfptF>5 literal 0 HcmV?d00001 diff --git a/documentation/html/tab_a.png b/documentation/html/tab_a.png new file mode 100644 index 0000000000000000000000000000000000000000..3b725c41c5a527a3a3e40097077d0e206a681247 GIT binary patch literal 142 zcmeAS@N?(olHy`uVBq!ia0vp^j6kfy!2~3aiye;!QlXwMjv*C{Z|8b*H5dputLHD# z=<0|*y7z(Vor?d;H&?EG&cXR}?!j-Lm&u1OOI7AIF5&c)RFE;&p0MYK>*Kl@eiymD r@|NpwKX@^z+;{u_Z~trSBfrMKa%3`zocFjEXaR$#tDnm{r-UW|TZ1%4 literal 0 HcmV?d00001 diff --git a/documentation/html/tab_ad.png b/documentation/html/tab_ad.png new file mode 100644 index 0000000000000000000000000000000000000000..e34850acfc24be58da6d2fd1ccc6b29cc84fe34d GIT binary patch literal 135 zcmeAS@N?(olHy`uVBq!ia0vp^j6kfy!2~3aiye;!QhuH;jv*C{Z|5d*H3V=pKi{In zd2jxLclDRPylmD}^l7{QOtL{vUjO{-WqItb5sQp2h-99b8^^Scr-=2mblCdZuUm?4 jzOJvgvt3{(cjKLW5(A@0qPS@<&}0TrS3j3^P6y&q2{!U5bk+Tso_B!YCpDh>v z{CM*1U8YvQRyBUHt^Ju0W_sq-?;9@_4equ-bavTs=gk796zopr0EBT&m;e9( literal 0 HcmV?d00001 diff --git a/documentation/html/tab_s.png b/documentation/html/tab_s.png new file mode 100644 index 0000000000000000000000000000000000000000..ab478c95b67371d700a20869f7de1ddd73522d50 GIT binary patch literal 184 zcmeAS@N?(olHy`uVBq!ia0vp^j6kfy!2~3aiye;!QuUrLjv*C{Z|^p8HaRdjTwH7) zC?wLlL}}I{)n%R&r+1}IGmDnq;&J#%V6)9VsYhS`O^BVBQlxOUep0c$RENLq#g8A$ z)z7%K_bI&n@J+X_=x}fJoEKed-$<>=ZI-;YrdjIl`U`uzuDWSP?o#Dmo{%SgM#oan kX~E1%D-|#H#QbHoIja2U-MgvsK&LQxy85}Sb4q9e0Efg%P5=M^ literal 0 HcmV?d00001 diff --git a/documentation/html/tab_sd.png b/documentation/html/tab_sd.png new file mode 100644 index 0000000000000000000000000000000000000000..757a565ced4730f85c833fb2547d8e199ae68f19 GIT binary patch literal 188 zcmeAS@N?(olHy`uVBq!ia0vp^j6kfy!2~3aiye;!Qq7(&jv*C{Z|_!fH5o7*c=%9% zcILh!EA=pAQKdx-Cdiev=v{eg{8Ht<{e8_NAN~b=)%W>-WDCE0PyDHGemi$BoXwcK z{>e9^za6*c1ilttWw&V+U;WCPlV9{LdC~Ey%_H(qj`xgfES(4Yz5jSTZfCt`4E$0YRsR*S^mTCR^;V&sxC8{l_Cp7w8-YPgg&ebxsLQ00$vXK>z>% literal 0 HcmV?d00001 diff --git a/documentation/html/tabs.css b/documentation/html/tabs.css new file mode 100644 index 0000000..71c8a47 --- /dev/null +++ b/documentation/html/tabs.css @@ -0,0 +1 @@ +.sm{position:relative;z-index:9999}.sm,.sm ul,.sm li{display:block;list-style:none;margin:0;padding:0;line-height:normal;direction:ltr;text-align:left;-webkit-tap-highlight-color:rgba(0,0,0,0)}.sm-rtl,.sm-rtl ul,.sm-rtl li{direction:rtl;text-align:right}.sm>li>h1,.sm>li>h2,.sm>li>h3,.sm>li>h4,.sm>li>h5,.sm>li>h6{margin:0;padding:0}.sm ul{display:none}.sm li,.sm a{position:relative}.sm a{display:block}.sm a.disabled{cursor:not-allowed}.sm:after{content:"\00a0";display:block;height:0;font:0/0 serif;clear:both;visibility:hidden;overflow:hidden}.sm,.sm *,.sm *:before,.sm *:after{-moz-box-sizing:border-box;-webkit-box-sizing:border-box;box-sizing:border-box}.main-menu-btn{position:relative;display:inline-block;width:36px;height:36px;text-indent:36px;margin-left:8px;white-space:nowrap;overflow:hidden;cursor:pointer;-webkit-tap-highlight-color:rgba(0,0,0,0)}.main-menu-btn-icon,.main-menu-btn-icon:before,.main-menu-btn-icon:after{position:absolute;top:50%;left:2px;height:2px;width:24px;background:var(--nav-menu-button-color);-webkit-transition:all .25s;transition:all .25s}.main-menu-btn-icon:before{content:'';top:-7px;left:0}.main-menu-btn-icon:after{content:'';top:7px;left:0}#main-menu-state:checked ~ .main-menu-btn .main-menu-btn-icon{height:0}#main-menu-state:checked ~ .main-menu-btn .main-menu-btn-icon:before{top:0;-webkit-transform:rotate(-45deg);transform:rotate(-45deg)}#main-menu-state:checked ~ .main-menu-btn .main-menu-btn-icon:after{top:0;-webkit-transform:rotate(45deg);transform:rotate(45deg)}#main-menu-state{position:absolute;width:1px;height:1px;margin:-1px;border:0;padding:0;overflow:hidden;clip:rect(1px,1px,1px,1px)}#main-menu-state:not(:checked) ~ #main-menu{display:none}#main-menu-state:checked ~ #main-menu{display:block}@media(min-width:768px){.main-menu-btn{position:absolute;top:-99999px}#main-menu-state:not(:checked) ~ #main-menu{display:block}}.sm-dox{background-image:var(--nav-gradient-image)}.sm-dox a,.sm-dox a:focus,.sm-dox a:hover,.sm-dox a:active{padding:0 12px;padding-right:43px;font-family:var(--font-family-nav);font-size:13px;font-weight:bold;line-height:36px;text-decoration:none;text-shadow:var(--nav-text-normal-shadow);color:var(--nav-text-normal-color);outline:0}.sm-dox a:hover{background-image:var(--nav-gradient-active-image);background-repeat:repeat-x;color:var(--nav-text-hover-color);text-shadow:var(--nav-text-hover-shadow)}.sm-dox a.current{color:#d23600}.sm-dox a.disabled{color:#bbb}.sm-dox a span.sub-arrow{position:absolute;top:50%;margin-top:-14px;left:auto;right:3px;width:28px;height:28px;overflow:hidden;font:bold 12px/28px monospace !important;text-align:center;text-shadow:none;background:var(--nav-menu-toggle-color);-moz-border-radius:5px;-webkit-border-radius:5px;border-radius:5px}.sm-dox a span.sub-arrow:before{display:block;content:'+'}.sm-dox a.highlighted span.sub-arrow:before{display:block;content:'-'}.sm-dox>li:first-child>a,.sm-dox>li:first-child>:not(ul) a{-moz-border-radius:5px 5px 0 0;-webkit-border-radius:5px;border-radius:5px 5px 0 0}.sm-dox>li:last-child>a,.sm-dox>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul{-moz-border-radius:0 0 5px 5px;-webkit-border-radius:0;border-radius:0 0 5px 5px}.sm-dox>li:last-child>a.highlighted,.sm-dox>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted{-moz-border-radius:0;-webkit-border-radius:0;border-radius:0}.sm-dox ul{background:var(--nav-menu-background-color)}.sm-dox ul a,.sm-dox ul a:focus,.sm-dox ul a:hover,.sm-dox ul a:active{font-size:12px;border-left:8px solid transparent;line-height:36px;text-shadow:none;background-color:var(--nav-menu-background-color);background-image:none}.sm-dox ul a:hover{background-image:var(--nav-gradient-active-image);background-repeat:repeat-x;color:var(--nav-text-hover-color);text-shadow:0 1px 1px black}.sm-dox ul ul a,.sm-dox ul ul a:hover,.sm-dox ul ul a:focus,.sm-dox ul ul a:active{border-left:16px solid transparent}.sm-dox ul ul ul a,.sm-dox ul ul ul a:hover,.sm-dox ul ul ul a:focus,.sm-dox ul ul ul a:active{border-left:24px solid transparent}.sm-dox ul ul ul ul a,.sm-dox ul ul ul ul a:hover,.sm-dox ul ul ul ul a:focus,.sm-dox ul ul ul ul a:active{border-left:32px solid transparent}.sm-dox ul ul ul ul ul a,.sm-dox ul ul ul ul ul a:hover,.sm-dox ul ul ul ul ul a:focus,.sm-dox ul ul ul ul ul a:active{border-left:40px solid transparent}@media(min-width:768px){.sm-dox ul{position:absolute;width:12em}.sm-dox li{float:left}.sm-dox.sm-rtl li{float:right}.sm-dox ul li,.sm-dox.sm-rtl ul li,.sm-dox.sm-vertical li{float:none}.sm-dox a{white-space:nowrap}.sm-dox ul a,.sm-dox.sm-vertical a{white-space:normal}.sm-dox .sm-nowrap>li>a,.sm-dox .sm-nowrap>li>:not(ul) a{white-space:nowrap}.sm-dox{padding:0 10px;background-image:var(--nav-gradient-image);line-height:36px}.sm-dox a span.sub-arrow{top:50%;margin-top:-2px;right:12px;width:0;height:0;border-width:4px;border-style:solid dashed dashed dashed;border-color:var(--nav-text-normal-color) transparent transparent transparent;background:transparent;-moz-border-radius:0;-webkit-border-radius:0;border-radius:0}.sm-dox a,.sm-dox a:focus,.sm-dox a:active,.sm-dox a:hover,.sm-dox a.highlighted{padding:0 12px;background-image:var(--nav-separator-image);background-repeat:no-repeat;background-position:right;-moz-border-radius:0 !important;-webkit-border-radius:0;border-radius:0 !important}.sm-dox a:hover{background-image:var(--nav-gradient-active-image);background-repeat:repeat-x;color:var(--nav-text-hover-color);text-shadow:var(--nav-text-hover-shadow)}.sm-dox a:hover span.sub-arrow{border-color:var(--nav-text-hover-color) transparent transparent transparent}.sm-dox a.has-submenu{padding-right:24px}.sm-dox li{border-top:0}.sm-dox>li>ul:before,.sm-dox>li>ul:after{content:'';position:absolute;top:-18px;left:30px;width:0;height:0;overflow:hidden;border-width:9px;border-style:dashed dashed solid dashed;border-color:transparent transparent #bbb transparent}.sm-dox>li>ul:after{top:-16px;left:31px;border-width:8px;border-color:transparent transparent var(--nav-menu-background-color) transparent}.sm-dox ul{border:1px solid #bbb;padding:5px 0;background:var(--nav-menu-background-color);-moz-border-radius:5px !important;-webkit-border-radius:5px;border-radius:5px !important;-moz-box-shadow:0 5px 9px rgba(0,0,0,0.2);-webkit-box-shadow:0 5px 9px rgba(0,0,0,0.2);box-shadow:0 5px 9px rgba(0,0,0,0.2)}.sm-dox ul a span.sub-arrow{right:8px;top:50%;margin-top:-5px;border-width:5px;border-color:transparent transparent transparent var(--nav-menu-foreground-color);border-style:dashed dashed dashed solid}.sm-dox ul a,.sm-dox ul a:hover,.sm-dox ul a:focus,.sm-dox ul a:active,.sm-dox ul a.highlighted{color:var(--nav-menu-foreground-color);background-image:none;border:0 !important;color:var(--nav-menu-foreground-color);background-image:none}.sm-dox ul a:hover{background-image:var(--nav-gradient-active-image);background-repeat:repeat-x;color:var(--nav-text-hover-color);text-shadow:var(--nav-text-hover-shadow)}.sm-dox ul a:hover span.sub-arrow{border-color:transparent transparent transparent var(--nav-text-hover-color)}.sm-dox span.scroll-up,.sm-dox span.scroll-down{position:absolute;display:none;visibility:hidden;overflow:hidden;background:var(--nav-menu-background-color);height:36px}.sm-dox span.scroll-up:hover,.sm-dox span.scroll-down:hover{background:#eee}.sm-dox span.scroll-up:hover span.scroll-up-arrow,.sm-dox span.scroll-up:hover span.scroll-down-arrow{border-color:transparent transparent #d23600 transparent}.sm-dox span.scroll-down:hover span.scroll-down-arrow{border-color:#d23600 transparent transparent transparent}.sm-dox span.scroll-up-arrow,.sm-dox span.scroll-down-arrow{position:absolute;top:0;left:50%;margin-left:-6px;width:0;height:0;overflow:hidden;border-width:6px;border-style:dashed dashed solid dashed;border-color:transparent transparent var(--nav-menu-foreground-color) transparent}.sm-dox span.scroll-down-arrow{top:8px;border-style:solid dashed dashed dashed;border-color:var(--nav-menu-foreground-color) transparent transparent transparent}.sm-dox.sm-rtl a.has-submenu{padding-right:12px;padding-left:24px}.sm-dox.sm-rtl a span.sub-arrow{right:auto;left:12px}.sm-dox.sm-rtl.sm-vertical a.has-submenu{padding:10px 20px}.sm-dox.sm-rtl.sm-vertical a span.sub-arrow{right:auto;left:8px;border-style:dashed solid dashed dashed;border-color:transparent #555 transparent transparent}.sm-dox.sm-rtl>li>ul:before{left:auto;right:30px}.sm-dox.sm-rtl>li>ul:after{left:auto;right:31px}.sm-dox.sm-rtl ul a.has-submenu{padding:10px 20px !important}.sm-dox.sm-rtl ul a span.sub-arrow{right:auto;left:8px;border-style:dashed solid dashed dashed;border-color:transparent #555 transparent transparent}.sm-dox.sm-vertical{padding:10px 0;-moz-border-radius:5px;-webkit-border-radius:5px;border-radius:5px}.sm-dox.sm-vertical a{padding:10px 20px}.sm-dox.sm-vertical a:hover,.sm-dox.sm-vertical a:focus,.sm-dox.sm-vertical a:active,.sm-dox.sm-vertical a.highlighted{background:#fff}.sm-dox.sm-vertical a.disabled{background-image:var(--nav-gradient-image)}.sm-dox.sm-vertical a span.sub-arrow{right:8px;top:50%;margin-top:-5px;border-width:5px;border-style:dashed dashed dashed solid;border-color:transparent transparent transparent #555}.sm-dox.sm-vertical>li>ul:before,.sm-dox.sm-vertical>li>ul:after{display:none}.sm-dox.sm-vertical ul a{padding:10px 20px}.sm-dox.sm-vertical ul a:hover,.sm-dox.sm-vertical ul a:focus,.sm-dox.sm-vertical ul a:active,.sm-dox.sm-vertical ul a.highlighted{background:#eee}.sm-dox.sm-vertical ul a.disabled{background:var(--nav-menu-background-color)}} \ No newline at end of file diff --git a/documentation/html/tank__drive_8h_source.html b/documentation/html/tank__drive_8h_source.html new file mode 100644 index 0000000..5c60811 --- /dev/null +++ b/documentation/html/tank__drive_8h_source.html @@ -0,0 +1,165 @@ + + + + + + + +RIT VEXU Core API: include/subsystems/tank_drive.h Source File + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    tank_drive.h
    +
    +
    +
    1#pragma once
    +
    2
    +
    3#ifndef PI
    +
    4#define PI 3.141592654
    +
    5#endif
    +
    6
    +
    7#include "vex.h"
    +
    8#include "../core/include/subsystems/odometry/odometry_tank.h"
    +
    9#include "../core/include/utils/pid.h"
    +
    10#include "../core/include/utils/feedback_base.h"
    +
    11#include "../core/include/robot_specs.h"
    +
    12#include "../core/src/utils/pure_pursuit.cpp"
    +
    13#include <vector>
    +
    14
    +
    15
    +
    16using namespace vex;
    +
    17
    + +
    23{
    +
    24public:
    +
    25
    +
    33 TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom=NULL);
    +
    34
    +
    38 void stop();
    +
    39
    +
    50 void drive_tank(double left, double right, int power=1, bool isdriver=false);
    +
    51
    +
    62 void drive_arcade(double forward_back, double left_right, int power=1);
    +
    63
    +
    74 bool drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed=1);
    +
    75
    +
    84 bool drive_forward(double inches, directionType dir, double max_speed=1);
    +
    85
    +
    96 bool turn_degrees(double degrees, Feedback &feedback, double max_speed=1);
    +
    97
    +
    107 bool turn_degrees(double degrees, double max_speed=1);
    +
    108
    +
    120 bool drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed=1);
    +
    121
    +
    133 bool drive_to_point(double x, double y, vex::directionType dir, double max_speed=1);
    +
    134
    +
    143 bool turn_to_heading(double heading_deg, Feedback &feedback, double max_speed=1);
    +
    151 bool turn_to_heading(double heading_deg, double max_speed=1);
    +
    152
    +
    156 void reset_auto();
    +
    157
    +
    166 static double modify_inputs(double input, int power=2);
    +
    167
    +
    179 bool pure_pursuit(std::vector<PurePursuit::hermite_point> path, directionType dir, double radius, double res, Feedback &feedback, double max_speed=1);
    +
    180
    +
    181private:
    +
    182 motor_group &left_motors;
    +
    183 motor_group &right_motors;
    +
    184
    +
    185 PID correction_pid;
    +
    186 Feedback *drive_default_feedback = NULL;
    +
    187 Feedback *turn_default_feedback = NULL;
    +
    188
    +
    189 OdometryBase *odometry;
    +
    190
    +
    191 robot_specs_t &config;
    +
    192
    +
    193 bool func_initialized = false;
    +
    194 bool is_pure_pursuit = false;
    +
    195};
    +
    Definition: feedback_base.h:11
    +
    Definition: odometry_base.h:33
    +
    Definition: pid.h:24
    +
    Definition: tank_drive.h:23
    +
    bool pure_pursuit(std::vector< PurePursuit::hermite_point > path, directionType dir, double radius, double res, Feedback &feedback, double max_speed=1)
    Definition: tank_drive.cpp:411
    +
    void drive_tank(double left, double right, int power=1, bool isdriver=false)
    Definition: tank_drive.cpp:34
    +
    bool drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed=1)
    Definition: tank_drive.cpp:77
    +
    bool turn_to_heading(double heading_deg, Feedback &feedback, double max_speed=1)
    Definition: tank_drive.cpp:344
    +
    void drive_arcade(double forward_back, double left_right, int power=1)
    Definition: tank_drive.cpp:56
    +
    void reset_auto()
    Definition: tank_drive.cpp:14
    +
    static double modify_inputs(double input, int power=2)
    Definition: tank_drive.cpp:406
    +
    bool turn_degrees(double degrees, Feedback &feedback, double max_speed=1)
    Definition: tank_drive.cpp:143
    +
    bool drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed=1)
    Definition: tank_drive.cpp:198
    +
    void stop()
    Definition: tank_drive.cpp:22
    +
    Definition: robot_specs.h:12
    +
    + + + + diff --git a/documentation/html/trapezoid__profile_8h_source.html b/documentation/html/trapezoid__profile_8h_source.html new file mode 100644 index 0000000..ef76ce2 --- /dev/null +++ b/documentation/html/trapezoid__profile_8h_source.html @@ -0,0 +1,129 @@ + + + + + + + +RIT VEXU Core API: include/utils/trapezoid_profile.h Source File + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    trapezoid_profile.h
    +
    +
    +
    1#pragma once
    +
    2
    +
    6typedef struct
    +
    7{
    +
    8 double pos;
    +
    9 double vel;
    +
    10 double accel;
    +
    11
    +
    12} motion_t;
    +
    13
    + +
    35{
    +
    36 public:
    +
    37
    +
    44 TrapezoidProfile(double max_v, double accel);
    +
    45
    +
    52 motion_t calculate(double time_s);
    +
    53
    +
    59 void set_endpts(double start, double end);
    +
    60
    +
    65 void set_accel(double accel);
    +
    66
    +
    72 void set_max_v(double max_v);
    +
    73
    +
    78 double get_movement_time();
    +
    79
    +
    80 private:
    +
    81 double start, end;
    +
    82 double max_v;
    +
    83 double accel;
    +
    84 double time;
    +
    85
    +
    86
    +
    87};
    +
    Definition: trapezoid_profile.h:35
    +
    motion_t calculate(double time_s)
    Run the trapezoidal profile based on the time that's ellapsed.
    Definition: trapezoid_profile.cpp:35
    +
    void set_endpts(double start, double end)
    Definition: trapezoid_profile.cpp:19
    +
    void set_accel(double accel)
    Definition: trapezoid_profile.cpp:14
    +
    void set_max_v(double max_v)
    Definition: trapezoid_profile.cpp:9
    +
    double get_movement_time()
    Definition: trapezoid_profile.cpp:113
    +
    Definition: trapezoid_profile.h:7
    +
    double vel
    1d velocity at this point in time
    Definition: trapezoid_profile.h:9
    +
    double accel
    1d acceleration at this point in time
    Definition: trapezoid_profile.h:10
    +
    double pos
    1d position at this point in time
    Definition: trapezoid_profile.h:8
    +
    + + + + diff --git a/documentation/html/vector2d_8h_source.html b/documentation/html/vector2d_8h_source.html new file mode 100644 index 0000000..ccd8da4 --- /dev/null +++ b/documentation/html/vector2d_8h_source.html @@ -0,0 +1,173 @@ + + + + + + + +RIT VEXU Core API: include/utils/vector2d.h Source File + + + + + + + + + +
    +
    + + + + + + +
    +
    RIT VEXU Core API +
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + + +
    +
    +
    vector2d.h
    +
    +
    +
    1#pragma once
    +
    2
    +
    3#include <cmath>
    +
    4
    +
    5#ifndef PI
    +
    6#define PI 3.141592654
    +
    7#endif
    + +
    14{
    +
    15public:
    +
    16
    +
    20 struct point_t
    +
    21 {
    +
    22 double x;
    +
    23 double y;
    +
    24
    +
    25
    +
    31 double dist(const point_t other)
    +
    32 {
    +
    33 return sqrt(pow(this->x - other.x, 2) + pow(this->y - other.y, 2));
    +
    34 }
    +
    35
    + +
    42 {
    +
    43 point_t p
    +
    44 {
    +
    45 .x = this->x + other.x,
    +
    46 .y = this->y + other.y
    +
    47 };
    +
    48 return p;
    +
    49 }
    +
    50
    + +
    57 {
    +
    58 point_t p
    +
    59 {
    +
    60 .x = this->x - other.x,
    +
    61 .y = this->y - other.y
    +
    62 };
    +
    63 return p;
    +
    64 }
    +
    65 };
    +
    66
    +
    73 Vector2D(double dir, double mag);
    +
    74
    +
    80 Vector2D(point_t p);
    +
    81
    +
    89 double get_dir() const;
    +
    90
    +
    94 double get_mag() const;
    +
    95
    +
    99 double get_x() const;
    +
    100
    +
    104 double get_y() const;
    +
    105
    + +
    111
    + +
    117
    +
    123 Vector2D operator*(const double &x);
    +
    130 Vector2D operator+(const Vector2D &other);
    +
    137 Vector2D operator-(const Vector2D &other);
    +
    138
    +
    139private:
    +
    140
    +
    141 double dir, mag;
    +
    142
    +
    143};
    +
    144
    +
    150double deg2rad(double deg);
    +
    151
    +
    158double rad2deg(double r);
    +
    Definition: vector2d.h:14
    +
    Vector2D operator*(const double &x)
    Definition: vector2d.cpp:116
    +
    Vector2D operator-(const Vector2D &other)
    Definition: vector2d.cpp:101
    +
    Vector2D normalize()
    Definition: vector2d.cpp:58
    +
    double get_x() const
    Definition: vector2d.cpp:42
    +
    Vector2D operator+(const Vector2D &other)
    Definition: vector2d.cpp:84
    +
    double get_mag() const
    Definition: vector2d.cpp:37
    +
    Vector2D::point_t point()
    Definition: vector2d.cpp:67
    +
    double get_dir() const
    Definition: vector2d.cpp:32
    +
    double get_y() const
    Definition: vector2d.cpp:50
    +
    Definition: vector2d.h:21
    +
    double dist(const point_t other)
    Definition: vector2d.h:31
    +
    point_t operator+(const point_t &other)
    Definition: vector2d.h:41
    +
    double y
    the y position in space
    Definition: vector2d.h:23
    +
    point_t operator-(const point_t &other)
    Definition: vector2d.h:56
    +
    double x
    the x position in space
    Definition: vector2d.h:22
    +
    + + + + From 051ae2f3a62024637afcee2bd0e71e808045bd51 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 12 Mar 2023 20:08:40 -0400 Subject: [PATCH 185/243] Github pages test --- documentation/html/annotated.html | 132 -- .../html/auto__chooser_8h_source.html | 130 -- .../html/auto__command_8h_source.html | 109 - documentation/html/bc_s.png | Bin 676 -> 0 bytes documentation/html/bc_sd.png | Bin 635 -> 0 bytes documentation/html/bdwn.png | Bin 147 -> 0 bytes .../html/classAutoChooser-members.html | 91 - documentation/html/classAutoChooser.html | 296 --- .../html/classAutoCommand-members.html | 88 - documentation/html/classAutoCommand.html | 205 -- documentation/html/classAutoCommand.png | Bin 5628 -> 0 bytes .../html/classCommandController-members.html | 89 - .../html/classCommandController.html | 233 -- .../html/classCustomEncoder-members.html | 90 - documentation/html/classCustomEncoder.html | 296 --- documentation/html/classCustomEncoder.png | Bin 494 -> 0 bytes .../html/classDelayCommand-members.html | 89 - documentation/html/classDelayCommand.html | 184 -- documentation/html/classDelayCommand.png | Bin 508 -> 0 bytes .../classDriveForwardCommand-members.html | 89 - .../html/classDriveForwardCommand.html | 252 --- .../html/classDriveForwardCommand.png | Bin 613 -> 0 bytes .../html/classDriveStopCommand-members.html | 89 - documentation/html/classDriveStopCommand.html | 178 -- documentation/html/classDriveStopCommand.png | Bin 549 -> 0 bytes .../classDriveToPointCommand-members.html | 89 - .../html/classDriveToPointCommand.html | 274 --- .../html/classDriveToPointCommand.png | Bin 595 -> 0 bytes .../html/classFeedForward-members.html | 86 - documentation/html/classFeedForward.html | 199 -- documentation/html/classFeedback-members.html | 94 - documentation/html/classFeedback.html | 315 --- documentation/html/classFeedback.png | Bin 792 -> 0 bytes documentation/html/classFlywheel-members.html | 105 - documentation/html/classFlywheel.html | 684 ------ .../classFlywheelStopCommand-members.html | 89 - .../html/classFlywheelStopCommand.html | 177 -- .../html/classFlywheelStopCommand.png | Bin 621 -> 0 bytes ...lassFlywheelStopMotorsCommand-members.html | 89 - .../html/classFlywheelStopMotorsCommand.html | 177 -- .../html/classFlywheelStopMotorsCommand.png | Bin 678 -> 0 bytes ...ssFlywheelStopNonTasksCommand-members.html | 87 - .../classFlywheelStopNonTasksCommand.html | 115 - .../html/classFlywheelStopNonTasksCommand.png | Bin 718 -> 0 bytes .../html/classGenericAuto-members.html | 88 - documentation/html/classGenericAuto.html | 204 -- .../html/classGraphDrawer-members.html | 87 - documentation/html/classGraphDrawer.html | 277 --- documentation/html/classLift-members.html | 97 - documentation/html/classLift.html | 630 ------ .../html/classMecanumDrive-members.html | 89 - documentation/html/classMecanumDrive.html | 389 ---- .../html/classMotionController-members.html | 97 - documentation/html/classMotionController.html | 477 ---- documentation/html/classMotionController.png | Bin 474 -> 0 bytes .../html/classMovingAverage-members.html | 89 - documentation/html/classMovingAverage.html | 233 -- .../html/classOdomSetPosition-members.html | 89 - documentation/html/classOdomSetPosition.html | 195 -- documentation/html/classOdomSetPosition.png | Bin 525 -> 0 bytes .../html/classOdometry3Wheel-members.html | 108 - documentation/html/classOdometry3Wheel.html | 303 --- documentation/html/classOdometry3Wheel.png | Bin 548 -> 0 bytes .../html/classOdometryBase-members.html | 106 - documentation/html/classOdometryBase.html | 725 ------ documentation/html/classOdometryBase.png | Bin 776 -> 0 bytes .../html/classOdometryTank-members.html | 108 - documentation/html/classOdometryTank.html | 345 --- documentation/html/classOdometryTank.png | Bin 541 -> 0 bytes documentation/html/classPID-members.html | 103 - documentation/html/classPID.html | 509 ----- documentation/html/classPID.png | Bin 362 -> 0 bytes documentation/html/classPIDFF-members.html | 98 - documentation/html/classPIDFF.html | 401 ---- documentation/html/classPIDFF.png | Bin 377 -> 0 bytes .../html/classSpinRPMCommand-members.html | 89 - documentation/html/classSpinRPMCommand.html | 189 -- documentation/html/classSpinRPMCommand.png | Bin 543 -> 0 bytes .../html/classTankDrive-members.html | 99 - documentation/html/classTankDrive.html | 877 ------- .../html/classTrapezoidProfile-members.html | 90 - documentation/html/classTrapezoidProfile.html | 290 --- .../html/classTurnDegreesCommand-members.html | 89 - .../html/classTurnDegreesCommand.html | 233 -- .../html/classTurnDegreesCommand.png | Bin 614 -> 0 bytes .../classTurnToHeadingCommand-members.html | 89 - .../html/classTurnToHeadingCommand.html | 233 -- .../html/classTurnToHeadingCommand.png | Bin 624 -> 0 bytes documentation/html/classVector2D-members.html | 95 - documentation/html/classVector2D.html | 378 ---- ...lassWaitUntilUpToSpeedCommand-members.html | 89 - .../html/classWaitUntilUpToSpeedCommand.html | 188 -- .../html/classWaitUntilUpToSpeedCommand.png | Bin 660 -> 0 bytes documentation/html/classes.html | 132 -- documentation/html/closed.png | Bin 132 -> 0 bytes .../html/command__controller_8h_source.html | 113 - .../html/custom__encoder_8h_source.html | 115 - .../html/delay__command_8h_source.html | 107 - .../dir_313caf1132e152dd9b58bea13a4052ca.html | 91 - .../dir_42a35307dcefecb9f25978d1dedb502f.html | 91 - .../dir_68267d1309a1af8e8297ef4c3efbcdba.html | 93 - .../dir_821002d4f10779a80d4fb17bc32f21f1.html | 120 - .../dir_883d6c53cd62ec60a5d421a7bc1a2629.html | 95 - .../dir_8e84b5daa2b3f33b7b3fb9ecedbe5637.html | 106 - .../dir_ca1fd9fa48e5fdc0ddfbf442e09c4dab.html | 85 - .../dir_d44c64559bbebec7f509842c48db8b23.html | 98 - .../dir_d9631e0f4b8929605c336e8f080acaa3.html | 85 - .../dir_e0729c835bcfebced7012c88d9b3a1d3.html | 99 - documentation/html/doc.png | Bin 746 -> 0 bytes documentation/html/docd.png | Bin 756 -> 0 bytes documentation/html/doxygen.css | 2007 ----------------- documentation/html/doxygen.svg | 26 - .../html/drive__commands_8h_source.html | 229 -- documentation/html/dynsections.js | 123 - .../html/feedback__base_8h_source.html | 118 - documentation/html/feedforward_8h_source.html | 135 -- documentation/html/files.html | 118 - documentation/html/flywheel_8h_source.html | 197 -- .../html/flywheel__commands_8h_source.html | 161 -- documentation/html/folderclosed.png | Bin 616 -> 0 bytes documentation/html/folderopen.png | Bin 597 -> 0 bytes documentation/html/functions.html | 93 - documentation/html/functions_b.html | 84 - documentation/html/functions_c.html | 91 - documentation/html/functions_d.html | 99 - documentation/html/functions_e.html | 86 - documentation/html/functions_enum.html | 81 - documentation/html/functions_f.html | 87 - documentation/html/functions_func.html | 282 --- documentation/html/functions_g.html | 109 - documentation/html/functions_h.html | 86 - documentation/html/functions_i.html | 86 - documentation/html/functions_k.html | 86 - documentation/html/functions_l.html | 85 - documentation/html/functions_m.html | 89 - documentation/html/functions_n.html | 84 - documentation/html/functions_o.html | 94 - documentation/html/functions_p.html | 90 - documentation/html/functions_r.html | 90 - documentation/html/functions_s.html | 104 - documentation/html/functions_t.html | 92 - documentation/html/functions_u.html | 84 - documentation/html/functions_v.html | 85 - documentation/html/functions_vars.html | 212 -- documentation/html/functions_w.html | 86 - documentation/html/functions_x.html | 83 - documentation/html/functions_y.html | 83 - documentation/html/functions_z.html | 83 - .../html/generic__auto_8h_source.html | 116 - .../html/graph__drawer_8h_source.html | 199 -- documentation/html/hierarchy.html | 132 -- documentation/html/index.html | 81 - documentation/html/jquery.js | 34 - documentation/html/lift_8h_source.html | 344 --- documentation/html/math__util_8h_source.html | 128 -- documentation/html/md_README.html | 109 - .../html/mecanum__drive_8h_source.html | 151 -- documentation/html/menu.js | 136 -- documentation/html/menudata.js | 104 - .../html/motion__controller_8h_source.html | 158 -- .../html/moving__average_8h_source.html | 129 -- documentation/html/nav_f.png | Bin 153 -> 0 bytes documentation/html/nav_fd.png | Bin 169 -> 0 bytes documentation/html/nav_g.png | Bin 95 -> 0 bytes documentation/html/nav_h.png | Bin 98 -> 0 bytes documentation/html/nav_hd.png | Bin 114 -> 0 bytes .../html/odometry__3wheel_8h_source.html | 127 -- .../html/odometry__base_8h_source.html | 173 -- .../html/odometry__tank_8h_source.html | 127 -- documentation/html/open.png | Bin 123 -> 0 bytes documentation/html/pages.html | 86 - documentation/html/pid_8h_source.html | 177 -- documentation/html/pidff_8h_source.html | 135 -- .../html/pure__pursuit_8h_source.html | 133 -- .../html/robot__specs_8h_source.html | 115 - documentation/html/screen_8h_source.html | 103 - documentation/html/search/all_0.js | 15 - documentation/html/search/all_1.js | 5 - documentation/html/search/all_10.js | 26 - documentation/html/search/all_11.js | 13 - documentation/html/search/all_12.js | 5 - documentation/html/search/all_13.js | 6 - documentation/html/search/all_14.js | 7 - documentation/html/search/all_15.js | 4 - documentation/html/search/all_16.js | 4 - documentation/html/search/all_17.js | 4 - documentation/html/search/all_2.js | 14 - documentation/html/search/all_3.js | 20 - documentation/html/search/all_4.js | 8 - documentation/html/search/all_5.js | 11 - documentation/html/search/all_6.js | 31 - documentation/html/search/all_7.js | 8 - documentation/html/search/all_8.js | 7 - documentation/html/search/all_9.js | 7 - documentation/html/search/all_a.js | 7 - documentation/html/search/all_b.js | 13 - documentation/html/search/all_c.js | 5 - documentation/html/search/all_d.js | 16 - documentation/html/search/all_e.js | 15 - documentation/html/search/all_f.js | 12 - documentation/html/search/classes_0.js | 5 - documentation/html/search/classes_1.js | 5 - documentation/html/search/classes_2.js | 7 - documentation/html/search/classes_3.js | 4 - documentation/html/search/classes_4.js | 10 - documentation/html/search/classes_5.js | 5 - documentation/html/search/classes_6.js | 4 - documentation/html/search/classes_7.js | 5 - documentation/html/search/classes_8.js | 9 - documentation/html/search/classes_9.js | 8 - documentation/html/search/classes_a.js | 8 - documentation/html/search/classes_b.js | 4 - documentation/html/search/classes_c.js | 5 - documentation/html/search/classes_d.js | 7 - documentation/html/search/classes_e.js | 4 - documentation/html/search/classes_f.js | 4 - documentation/html/search/close.svg | 31 - documentation/html/search/enums_0.js | 4 - documentation/html/search/functions_0.js | 11 - documentation/html/search/functions_1.js | 4 - documentation/html/search/functions_10.js | 11 - documentation/html/search/functions_11.js | 5 - documentation/html/search/functions_12.js | 5 - documentation/html/search/functions_13.js | 4 - documentation/html/search/functions_2.js | 8 - documentation/html/search/functions_3.js | 15 - documentation/html/search/functions_4.js | 4 - documentation/html/search/functions_5.js | 7 - documentation/html/search/functions_6.js | 30 - documentation/html/search/functions_7.js | 5 - documentation/html/search/functions_8.js | 6 - documentation/html/search/functions_9.js | 5 - documentation/html/search/functions_a.js | 8 - documentation/html/search/functions_b.js | 4 - documentation/html/search/functions_c.js | 11 - documentation/html/search/functions_d.js | 8 - documentation/html/search/functions_e.js | 9 - documentation/html/search/functions_f.js | 24 - documentation/html/search/mag.svg | 37 - documentation/html/search/mag_d.svg | 37 - documentation/html/search/mag_sel.svg | 74 - documentation/html/search/mag_seld.svg | 74 - documentation/html/search/pages_0.js | 4 - documentation/html/search/search.css | 291 --- documentation/html/search/search.js | 816 ------- documentation/html/search/searchdata.js | 30 - documentation/html/search/variables_0.js | 6 - documentation/html/search/variables_1.js | 4 - documentation/html/search/variables_10.js | 5 - documentation/html/search/variables_11.js | 4 - documentation/html/search/variables_12.js | 6 - documentation/html/search/variables_13.js | 4 - documentation/html/search/variables_14.js | 4 - documentation/html/search/variables_15.js | 4 - documentation/html/search/variables_2.js | 7 - documentation/html/search/variables_3.js | 8 - documentation/html/search/variables_4.js | 5 - documentation/html/search/variables_5.js | 4 - documentation/html/search/variables_6.js | 5 - documentation/html/search/variables_7.js | 4 - documentation/html/search/variables_8.js | 7 - documentation/html/search/variables_9.js | 4 - documentation/html/search/variables_a.js | 5 - documentation/html/search/variables_b.js | 4 - documentation/html/search/variables_c.js | 7 - documentation/html/search/variables_d.js | 6 - documentation/html/search/variables_e.js | 5 - documentation/html/search/variables_f.js | 4 - documentation/html/splitbar.png | Bin 314 -> 0 bytes documentation/html/splitbard.png | Bin 282 -> 0 bytes ...structAutoChooser_1_1entry__t-members.html | 93 - .../html/structAutoChooser_1_1entry__t.html | 185 -- ...tFeedForward_1_1ff__config__t-members.html | 92 - .../structFeedForward_1_1ff__config__t.html | 172 -- .../structLift_1_1lift__cfg__t-members.html | 93 - .../html/structLift_1_1lift__cfg__t.html | 118 - ...ve_1_1mecanumdrive__config__t-members.html | 94 - ...canumDrive_1_1mecanumdrive__config__t.html | 117 - ...troller_1_1m__profile__cfg__t-members.html | 92 - ...otionController_1_1m__profile__cfg__t.html | 115 - ...eel_1_1odometry3wheel__cfg__t-members.html | 91 - ...metry3Wheel_1_1odometry3wheel__cfg__t.html | 151 -- .../structPID_1_1pid__config__t-members.html | 94 - .../html/structPID_1_1pid__config__t.html | 126 -- ...PurePursuit_1_1hermite__point-members.html | 94 - .../structPurePursuit_1_1hermite__point.html | 121 - .../structPurePursuit_1_1spline-members.html | 95 - .../html/structPurePursuit_1_1spline.html | 124 - .../structVector2D_1_1point__t-members.html | 93 - .../html/structVector2D_1_1point__t.html | 217 -- .../html/structmotion__t-members.html | 87 - documentation/html/structmotion__t.html | 107 - .../html/structposition__t-members.html | 87 - documentation/html/structposition__t.html | 107 - .../html/structrobot__specs__t-members.html | 92 - documentation/html/structrobot__specs__t.html | 127 -- documentation/html/sync_off.png | Bin 853 -> 0 bytes documentation/html/sync_on.png | Bin 845 -> 0 bytes documentation/html/tab_a.png | Bin 142 -> 0 bytes documentation/html/tab_ad.png | Bin 135 -> 0 bytes documentation/html/tab_b.png | Bin 169 -> 0 bytes documentation/html/tab_bd.png | Bin 173 -> 0 bytes documentation/html/tab_h.png | Bin 177 -> 0 bytes documentation/html/tab_hd.png | Bin 180 -> 0 bytes documentation/html/tab_s.png | Bin 184 -> 0 bytes documentation/html/tab_sd.png | Bin 188 -> 0 bytes documentation/html/tabs.css | 1 - documentation/html/tank__drive_8h_source.html | 165 -- .../html/trapezoid__profile_8h_source.html | 129 -- documentation/html/vector2d_8h_source.html | 173 -- 310 files changed, 29853 deletions(-) delete mode 100644 documentation/html/annotated.html delete mode 100644 documentation/html/auto__chooser_8h_source.html delete mode 100644 documentation/html/auto__command_8h_source.html delete mode 100644 documentation/html/bc_s.png delete mode 100644 documentation/html/bc_sd.png delete mode 100644 documentation/html/bdwn.png delete mode 100644 documentation/html/classAutoChooser-members.html delete mode 100644 documentation/html/classAutoChooser.html delete mode 100644 documentation/html/classAutoCommand-members.html delete mode 100644 documentation/html/classAutoCommand.html delete mode 100644 documentation/html/classAutoCommand.png delete mode 100644 documentation/html/classCommandController-members.html delete mode 100644 documentation/html/classCommandController.html delete mode 100644 documentation/html/classCustomEncoder-members.html delete mode 100644 documentation/html/classCustomEncoder.html delete mode 100644 documentation/html/classCustomEncoder.png delete mode 100644 documentation/html/classDelayCommand-members.html delete mode 100644 documentation/html/classDelayCommand.html delete mode 100644 documentation/html/classDelayCommand.png delete mode 100644 documentation/html/classDriveForwardCommand-members.html delete mode 100644 documentation/html/classDriveForwardCommand.html delete mode 100644 documentation/html/classDriveForwardCommand.png delete mode 100644 documentation/html/classDriveStopCommand-members.html delete mode 100644 documentation/html/classDriveStopCommand.html delete mode 100644 documentation/html/classDriveStopCommand.png delete mode 100644 documentation/html/classDriveToPointCommand-members.html delete mode 100644 documentation/html/classDriveToPointCommand.html delete mode 100644 documentation/html/classDriveToPointCommand.png delete mode 100644 documentation/html/classFeedForward-members.html delete mode 100644 documentation/html/classFeedForward.html delete mode 100644 documentation/html/classFeedback-members.html delete mode 100644 documentation/html/classFeedback.html delete mode 100644 documentation/html/classFeedback.png delete mode 100644 documentation/html/classFlywheel-members.html delete mode 100644 documentation/html/classFlywheel.html delete mode 100644 documentation/html/classFlywheelStopCommand-members.html delete mode 100644 documentation/html/classFlywheelStopCommand.html delete mode 100644 documentation/html/classFlywheelStopCommand.png delete mode 100644 documentation/html/classFlywheelStopMotorsCommand-members.html delete mode 100644 documentation/html/classFlywheelStopMotorsCommand.html delete mode 100644 documentation/html/classFlywheelStopMotorsCommand.png delete mode 100644 documentation/html/classFlywheelStopNonTasksCommand-members.html delete mode 100644 documentation/html/classFlywheelStopNonTasksCommand.html delete mode 100644 documentation/html/classFlywheelStopNonTasksCommand.png delete mode 100644 documentation/html/classGenericAuto-members.html delete mode 100644 documentation/html/classGenericAuto.html delete mode 100644 documentation/html/classGraphDrawer-members.html delete mode 100644 documentation/html/classGraphDrawer.html delete mode 100644 documentation/html/classLift-members.html delete mode 100644 documentation/html/classLift.html delete mode 100644 documentation/html/classMecanumDrive-members.html delete mode 100644 documentation/html/classMecanumDrive.html delete mode 100644 documentation/html/classMotionController-members.html delete mode 100644 documentation/html/classMotionController.html delete mode 100644 documentation/html/classMotionController.png delete mode 100644 documentation/html/classMovingAverage-members.html delete mode 100644 documentation/html/classMovingAverage.html delete mode 100644 documentation/html/classOdomSetPosition-members.html delete mode 100644 documentation/html/classOdomSetPosition.html delete mode 100644 documentation/html/classOdomSetPosition.png delete mode 100644 documentation/html/classOdometry3Wheel-members.html delete mode 100644 documentation/html/classOdometry3Wheel.html delete mode 100644 documentation/html/classOdometry3Wheel.png delete mode 100644 documentation/html/classOdometryBase-members.html delete mode 100644 documentation/html/classOdometryBase.html delete mode 100644 documentation/html/classOdometryBase.png delete mode 100644 documentation/html/classOdometryTank-members.html delete mode 100644 documentation/html/classOdometryTank.html delete mode 100644 documentation/html/classOdometryTank.png delete mode 100644 documentation/html/classPID-members.html delete mode 100644 documentation/html/classPID.html delete mode 100644 documentation/html/classPID.png delete mode 100644 documentation/html/classPIDFF-members.html delete mode 100644 documentation/html/classPIDFF.html delete mode 100644 documentation/html/classPIDFF.png delete mode 100644 documentation/html/classSpinRPMCommand-members.html delete mode 100644 documentation/html/classSpinRPMCommand.html delete mode 100644 documentation/html/classSpinRPMCommand.png delete mode 100644 documentation/html/classTankDrive-members.html delete mode 100644 documentation/html/classTankDrive.html delete mode 100644 documentation/html/classTrapezoidProfile-members.html delete mode 100644 documentation/html/classTrapezoidProfile.html delete mode 100644 documentation/html/classTurnDegreesCommand-members.html delete mode 100644 documentation/html/classTurnDegreesCommand.html delete mode 100644 documentation/html/classTurnDegreesCommand.png delete mode 100644 documentation/html/classTurnToHeadingCommand-members.html delete mode 100644 documentation/html/classTurnToHeadingCommand.html delete mode 100644 documentation/html/classTurnToHeadingCommand.png delete mode 100644 documentation/html/classVector2D-members.html delete mode 100644 documentation/html/classVector2D.html delete mode 100644 documentation/html/classWaitUntilUpToSpeedCommand-members.html delete mode 100644 documentation/html/classWaitUntilUpToSpeedCommand.html delete mode 100644 documentation/html/classWaitUntilUpToSpeedCommand.png delete mode 100644 documentation/html/classes.html delete mode 100644 documentation/html/closed.png delete mode 100644 documentation/html/command__controller_8h_source.html delete mode 100644 documentation/html/custom__encoder_8h_source.html delete mode 100644 documentation/html/delay__command_8h_source.html delete mode 100644 documentation/html/dir_313caf1132e152dd9b58bea13a4052ca.html delete mode 100644 documentation/html/dir_42a35307dcefecb9f25978d1dedb502f.html delete mode 100644 documentation/html/dir_68267d1309a1af8e8297ef4c3efbcdba.html delete mode 100644 documentation/html/dir_821002d4f10779a80d4fb17bc32f21f1.html delete mode 100644 documentation/html/dir_883d6c53cd62ec60a5d421a7bc1a2629.html delete mode 100644 documentation/html/dir_8e84b5daa2b3f33b7b3fb9ecedbe5637.html delete mode 100644 documentation/html/dir_ca1fd9fa48e5fdc0ddfbf442e09c4dab.html delete mode 100644 documentation/html/dir_d44c64559bbebec7f509842c48db8b23.html delete mode 100644 documentation/html/dir_d9631e0f4b8929605c336e8f080acaa3.html delete mode 100644 documentation/html/dir_e0729c835bcfebced7012c88d9b3a1d3.html delete mode 100644 documentation/html/doc.png delete mode 100644 documentation/html/docd.png delete mode 100644 documentation/html/doxygen.css delete mode 100644 documentation/html/doxygen.svg delete mode 100644 documentation/html/drive__commands_8h_source.html delete mode 100644 documentation/html/dynsections.js delete mode 100644 documentation/html/feedback__base_8h_source.html delete mode 100644 documentation/html/feedforward_8h_source.html delete mode 100644 documentation/html/files.html delete mode 100644 documentation/html/flywheel_8h_source.html delete mode 100644 documentation/html/flywheel__commands_8h_source.html delete mode 100644 documentation/html/folderclosed.png delete mode 100644 documentation/html/folderopen.png delete mode 100644 documentation/html/functions.html delete mode 100644 documentation/html/functions_b.html delete mode 100644 documentation/html/functions_c.html delete mode 100644 documentation/html/functions_d.html delete mode 100644 documentation/html/functions_e.html delete mode 100644 documentation/html/functions_enum.html delete mode 100644 documentation/html/functions_f.html delete mode 100644 documentation/html/functions_func.html delete mode 100644 documentation/html/functions_g.html delete mode 100644 documentation/html/functions_h.html delete mode 100644 documentation/html/functions_i.html delete mode 100644 documentation/html/functions_k.html delete mode 100644 documentation/html/functions_l.html delete mode 100644 documentation/html/functions_m.html delete mode 100644 documentation/html/functions_n.html delete mode 100644 documentation/html/functions_o.html delete mode 100644 documentation/html/functions_p.html delete mode 100644 documentation/html/functions_r.html delete mode 100644 documentation/html/functions_s.html delete mode 100644 documentation/html/functions_t.html delete mode 100644 documentation/html/functions_u.html delete mode 100644 documentation/html/functions_v.html delete mode 100644 documentation/html/functions_vars.html delete mode 100644 documentation/html/functions_w.html delete mode 100644 documentation/html/functions_x.html delete mode 100644 documentation/html/functions_y.html delete mode 100644 documentation/html/functions_z.html delete mode 100644 documentation/html/generic__auto_8h_source.html delete mode 100644 documentation/html/graph__drawer_8h_source.html delete mode 100644 documentation/html/hierarchy.html delete mode 100644 documentation/html/index.html delete mode 100644 documentation/html/jquery.js delete mode 100644 documentation/html/lift_8h_source.html delete mode 100644 documentation/html/math__util_8h_source.html delete mode 100644 documentation/html/md_README.html delete mode 100644 documentation/html/mecanum__drive_8h_source.html delete mode 100644 documentation/html/menu.js delete mode 100644 documentation/html/menudata.js delete mode 100644 documentation/html/motion__controller_8h_source.html delete mode 100644 documentation/html/moving__average_8h_source.html delete mode 100644 documentation/html/nav_f.png delete mode 100644 documentation/html/nav_fd.png delete mode 100644 documentation/html/nav_g.png delete mode 100644 documentation/html/nav_h.png delete mode 100644 documentation/html/nav_hd.png delete mode 100644 documentation/html/odometry__3wheel_8h_source.html delete mode 100644 documentation/html/odometry__base_8h_source.html delete mode 100644 documentation/html/odometry__tank_8h_source.html delete mode 100644 documentation/html/open.png delete mode 100644 documentation/html/pages.html delete mode 100644 documentation/html/pid_8h_source.html delete mode 100644 documentation/html/pidff_8h_source.html delete mode 100644 documentation/html/pure__pursuit_8h_source.html delete mode 100644 documentation/html/robot__specs_8h_source.html delete mode 100644 documentation/html/screen_8h_source.html delete mode 100644 documentation/html/search/all_0.js delete mode 100644 documentation/html/search/all_1.js delete mode 100644 documentation/html/search/all_10.js delete mode 100644 documentation/html/search/all_11.js delete mode 100644 documentation/html/search/all_12.js delete mode 100644 documentation/html/search/all_13.js delete mode 100644 documentation/html/search/all_14.js delete mode 100644 documentation/html/search/all_15.js delete mode 100644 documentation/html/search/all_16.js delete mode 100644 documentation/html/search/all_17.js delete mode 100644 documentation/html/search/all_2.js delete mode 100644 documentation/html/search/all_3.js delete mode 100644 documentation/html/search/all_4.js delete mode 100644 documentation/html/search/all_5.js delete mode 100644 documentation/html/search/all_6.js delete mode 100644 documentation/html/search/all_7.js delete mode 100644 documentation/html/search/all_8.js delete mode 100644 documentation/html/search/all_9.js delete mode 100644 documentation/html/search/all_a.js delete mode 100644 documentation/html/search/all_b.js delete mode 100644 documentation/html/search/all_c.js delete mode 100644 documentation/html/search/all_d.js delete mode 100644 documentation/html/search/all_e.js delete mode 100644 documentation/html/search/all_f.js delete mode 100644 documentation/html/search/classes_0.js delete mode 100644 documentation/html/search/classes_1.js delete mode 100644 documentation/html/search/classes_2.js delete mode 100644 documentation/html/search/classes_3.js delete mode 100644 documentation/html/search/classes_4.js delete mode 100644 documentation/html/search/classes_5.js delete mode 100644 documentation/html/search/classes_6.js delete mode 100644 documentation/html/search/classes_7.js delete mode 100644 documentation/html/search/classes_8.js delete mode 100644 documentation/html/search/classes_9.js delete mode 100644 documentation/html/search/classes_a.js delete mode 100644 documentation/html/search/classes_b.js delete mode 100644 documentation/html/search/classes_c.js delete mode 100644 documentation/html/search/classes_d.js delete mode 100644 documentation/html/search/classes_e.js delete mode 100644 documentation/html/search/classes_f.js delete mode 100644 documentation/html/search/close.svg delete mode 100644 documentation/html/search/enums_0.js delete mode 100644 documentation/html/search/functions_0.js delete mode 100644 documentation/html/search/functions_1.js delete mode 100644 documentation/html/search/functions_10.js delete mode 100644 documentation/html/search/functions_11.js delete mode 100644 documentation/html/search/functions_12.js delete mode 100644 documentation/html/search/functions_13.js delete mode 100644 documentation/html/search/functions_2.js delete mode 100644 documentation/html/search/functions_3.js delete mode 100644 documentation/html/search/functions_4.js delete mode 100644 documentation/html/search/functions_5.js delete mode 100644 documentation/html/search/functions_6.js delete mode 100644 documentation/html/search/functions_7.js delete mode 100644 documentation/html/search/functions_8.js delete mode 100644 documentation/html/search/functions_9.js delete mode 100644 documentation/html/search/functions_a.js delete mode 100644 documentation/html/search/functions_b.js delete mode 100644 documentation/html/search/functions_c.js delete mode 100644 documentation/html/search/functions_d.js delete mode 100644 documentation/html/search/functions_e.js delete mode 100644 documentation/html/search/functions_f.js delete mode 100644 documentation/html/search/mag.svg delete mode 100644 documentation/html/search/mag_d.svg delete mode 100644 documentation/html/search/mag_sel.svg delete mode 100644 documentation/html/search/mag_seld.svg delete mode 100644 documentation/html/search/pages_0.js delete mode 100644 documentation/html/search/search.css delete mode 100644 documentation/html/search/search.js delete mode 100644 documentation/html/search/searchdata.js delete mode 100644 documentation/html/search/variables_0.js delete mode 100644 documentation/html/search/variables_1.js delete mode 100644 documentation/html/search/variables_10.js delete mode 100644 documentation/html/search/variables_11.js delete mode 100644 documentation/html/search/variables_12.js delete mode 100644 documentation/html/search/variables_13.js delete mode 100644 documentation/html/search/variables_14.js delete mode 100644 documentation/html/search/variables_15.js delete mode 100644 documentation/html/search/variables_2.js delete mode 100644 documentation/html/search/variables_3.js delete mode 100644 documentation/html/search/variables_4.js delete mode 100644 documentation/html/search/variables_5.js delete mode 100644 documentation/html/search/variables_6.js delete mode 100644 documentation/html/search/variables_7.js delete mode 100644 documentation/html/search/variables_8.js delete mode 100644 documentation/html/search/variables_9.js delete mode 100644 documentation/html/search/variables_a.js delete mode 100644 documentation/html/search/variables_b.js delete mode 100644 documentation/html/search/variables_c.js delete mode 100644 documentation/html/search/variables_d.js delete mode 100644 documentation/html/search/variables_e.js delete mode 100644 documentation/html/search/variables_f.js delete mode 100644 documentation/html/splitbar.png delete mode 100644 documentation/html/splitbard.png delete mode 100644 documentation/html/structAutoChooser_1_1entry__t-members.html delete mode 100644 documentation/html/structAutoChooser_1_1entry__t.html delete mode 100644 documentation/html/structFeedForward_1_1ff__config__t-members.html delete mode 100644 documentation/html/structFeedForward_1_1ff__config__t.html delete mode 100644 documentation/html/structLift_1_1lift__cfg__t-members.html delete mode 100644 documentation/html/structLift_1_1lift__cfg__t.html delete mode 100644 documentation/html/structMecanumDrive_1_1mecanumdrive__config__t-members.html delete mode 100644 documentation/html/structMecanumDrive_1_1mecanumdrive__config__t.html delete mode 100644 documentation/html/structMotionController_1_1m__profile__cfg__t-members.html delete mode 100644 documentation/html/structMotionController_1_1m__profile__cfg__t.html delete mode 100644 documentation/html/structOdometry3Wheel_1_1odometry3wheel__cfg__t-members.html delete mode 100644 documentation/html/structOdometry3Wheel_1_1odometry3wheel__cfg__t.html delete mode 100644 documentation/html/structPID_1_1pid__config__t-members.html delete mode 100644 documentation/html/structPID_1_1pid__config__t.html delete mode 100644 documentation/html/structPurePursuit_1_1hermite__point-members.html delete mode 100644 documentation/html/structPurePursuit_1_1hermite__point.html delete mode 100644 documentation/html/structPurePursuit_1_1spline-members.html delete mode 100644 documentation/html/structPurePursuit_1_1spline.html delete mode 100644 documentation/html/structVector2D_1_1point__t-members.html delete mode 100644 documentation/html/structVector2D_1_1point__t.html delete mode 100644 documentation/html/structmotion__t-members.html delete mode 100644 documentation/html/structmotion__t.html delete mode 100644 documentation/html/structposition__t-members.html delete mode 100644 documentation/html/structposition__t.html delete mode 100644 documentation/html/structrobot__specs__t-members.html delete mode 100644 documentation/html/structrobot__specs__t.html delete mode 100644 documentation/html/sync_off.png delete mode 100644 documentation/html/sync_on.png delete mode 100644 documentation/html/tab_a.png delete mode 100644 documentation/html/tab_ad.png delete mode 100644 documentation/html/tab_b.png delete mode 100644 documentation/html/tab_bd.png delete mode 100644 documentation/html/tab_h.png delete mode 100644 documentation/html/tab_hd.png delete mode 100644 documentation/html/tab_s.png delete mode 100644 documentation/html/tab_sd.png delete mode 100644 documentation/html/tabs.css delete mode 100644 documentation/html/tank__drive_8h_source.html delete mode 100644 documentation/html/trapezoid__profile_8h_source.html delete mode 100644 documentation/html/vector2d_8h_source.html diff --git a/documentation/html/annotated.html b/documentation/html/annotated.html deleted file mode 100644 index 55c9901..0000000 --- a/documentation/html/annotated.html +++ /dev/null @@ -1,132 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Class List
    -
    - - - - - diff --git a/documentation/html/auto__chooser_8h_source.html b/documentation/html/auto__chooser_8h_source.html deleted file mode 100644 index 3fe6516..0000000 --- a/documentation/html/auto__chooser_8h_source.html +++ /dev/null @@ -1,130 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/auto_chooser.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    auto_chooser.h
    -
    -
    -
    1#pragma once
    -
    2#include "vex.h"
    -
    3#include <string>
    -
    4#include <vector>
    -
    5
    -
    6
    - -
    16{
    -
    17 public:
    -
    23 AutoChooser(vex::brain &brain);
    -
    24
    -
    29 void add(std::string name);
    -
    30
    -
    35 std::string get_choice();
    -
    36
    -
    37 protected:
    -
    38
    -
    42 struct entry_t
    -
    43 {
    -
    44 int x;
    -
    45 int y;
    -
    46 int width;
    -
    47 int height;
    -
    48 std::string name;
    -
    49 };
    -
    50
    -
    51 void render(entry_t *selected);
    -
    52
    -
    53 std::string choice;
    -
    54 std::vector<entry_t> list ;
    -
    55 vex::brain &brain;
    -
    58};
    -
    Definition: auto_chooser.h:16
    -
    std::string choice
    Definition: auto_chooser.h:53
    -
    std::vector< entry_t > list
    Definition: auto_chooser.h:54
    -
    void add(std::string name)
    Definition: auto_chooser.cpp:66
    -
    void render(entry_t *selected)
    Definition: auto_chooser.cpp:47
    -
    vex::brain & brain
    Definition: auto_chooser.h:55
    -
    std::string get_choice()
    Definition: auto_chooser.cpp:85
    -
    Definition: auto_chooser.h:43
    -
    int width
    Definition: auto_chooser.h:46
    -
    int y
    Definition: auto_chooser.h:45
    -
    int x
    Definition: auto_chooser.h:44
    -
    int height
    Definition: auto_chooser.h:47
    -
    std::string name
    Definition: auto_chooser.h:48
    -
    - - - - diff --git a/documentation/html/auto__command_8h_source.html b/documentation/html/auto__command_8h_source.html deleted file mode 100644 index a8c192c..0000000 --- a/documentation/html/auto__command_8h_source.html +++ /dev/null @@ -1,109 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/command_structure/auto_command.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    auto_command.h
    -
    -
    -
    1
    -
    7#pragma once
    -
    8
    -
    9#include "vex.h"
    -
    10
    - -
    12 public:
    -
    18 virtual bool run() { return true; }
    -
    22 virtual void on_timeout(){}
    -
    23 AutoCommand* withTimeout(double t_seconds){
    -
    24<<<<<<< HEAD
    -
    25 this->timeout_seconds = t_seconds;
    -
    26=======
    -
    27 timeout_seconds = t_seconds;
    -
    28>>>>>>> refs/subrepo/core/fetch
    -
    29 return this;
    -
    30 }
    -
    40 double timeout_seconds = 10.0;
    -
    41
    -
    42};
    -
    Definition: auto_command.h:11
    -
    virtual void on_timeout()
    Definition: auto_command.h:22
    -
    virtual bool run()
    Definition: auto_command.h:18
    -
    double timeout_seconds
    Definition: auto_command.h:40
    -
    - - - - diff --git a/documentation/html/bc_s.png b/documentation/html/bc_s.png deleted file mode 100644 index 224b29aa9847d5a4b3902efd602b7ddf7d33e6c2..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 676 zcmV;V0$crwP)y__>=_9%My z{n931IS})GlGUF8K#6VIbs%684A^L3@%PlP2>_sk`UWPq@f;rU*V%rPy_ekbhXT&s z(GN{DxFv}*vZp`F>S!r||M`I*nOwwKX+BC~3P5N3-)Y{65c;ywYiAh-1*hZcToLHK ztpl1xomJ+Yb}K(cfbJr2=GNOnT!UFA7Vy~fBz8?J>XHsbZoDad^8PxfSa0GDgENZS zuLCEqzb*xWX2CG*b&5IiO#NzrW*;`VC9455M`o1NBh+(k8~`XCEEoC1Ybwf;vr4K3 zg|EB<07?SOqHp9DhLpS&bzgo70I+ghB_#)K7H%AMU3v}xuyQq9&Bm~++VYhF09a+U zl7>n7Jjm$K#b*FONz~fj;I->Bf;ule1prFN9FovcDGBkpg>)O*-}eLnC{6oZHZ$o% zXKW$;0_{8hxHQ>l;_*HATI(`7t#^{$(zLe}h*mqwOc*nRY9=?Sx4OOeVIfI|0V(V2 zBrW#G7Ss9wvzr@>H*`r>zE z+e8bOBgqIgldUJlG(YUDviMB`9+DH8n-s9SXRLyJHO1!=wY^79WYZMTa(wiZ!zP66 zA~!21vmF3H2{ngD;+`6j#~6j;$*f*G_2ZD1E;9(yaw7d-QnSCpK(cR1zU3qU0000< KMNUMnLSTYoA~SLT diff --git a/documentation/html/bc_sd.png b/documentation/html/bc_sd.png deleted file mode 100644 index 31ca888dc71049713b35c351933a8d0f36180bf1..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 635 zcmV->0)+jEP)Jwi0r1~gdSq#w{Bu1q z`craw(p2!hu$4C_$Oc3X(sI6e=9QSTwPt{G) z=htT&^~&c~L2~e{r5_5SYe7#Is-$ln>~Kd%$F#tC65?{LvQ}8O`A~RBB0N~`2M+waajO;5>3B&-viHGJeEK2TQOiPRa zfDKyqwMc4wfaEh4jt>H`nW_Zidwk@Bowp`}(VUaj-pSI(-1L>FJVsX}Yl9~JsqgsZ zUD9(rMwf23Gez6KPa|wwInZodP-2}9@fK0Ga_9{8SOjU&4l`pH4@qlQp83>>HT$xW zER^U>)MyV%t(Lu=`d=Y?{k1@}&r7ZGkFQ%z%N+sE9BtYjovzxyxCPxN6&@wLK{soQ zSmkj$aLI}miuE^p@~4}mg9OjDfGEkgY4~^XzLRUBB*O{+&vq<3v(E%+k_i%=`~j%{ Vj14gnt9}3g002ovPDHLkV1n!oC4m3{ diff --git a/documentation/html/bdwn.png b/documentation/html/bdwn.png deleted file mode 100644 index 940a0b950443a0bb1b216ac03c45b8a16c955452..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 147 zcmeAS@N?(olHy`uVBq!ia0vp^>_E)H!3HEvS)PKZC{Gv1kP61Pb5HX&C2wk~_T - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    AutoChooser Member List
    -
    -
    - -

    This is the complete list of members for AutoChooser, including all inherited members.

    - - - - - - - - -
    add(std::string name)AutoChooser
    AutoChooser(vex::brain &brain)AutoChooser
    brainAutoChooserprotected
    choiceAutoChooserprotected
    get_choice()AutoChooser
    listAutoChooserprotected
    render(entry_t *selected)AutoChooserprotected
    - - - - diff --git a/documentation/html/classAutoChooser.html b/documentation/html/classAutoChooser.html deleted file mode 100644 index 834a586..0000000 --- a/documentation/html/classAutoChooser.html +++ /dev/null @@ -1,296 +0,0 @@ - - - - - - - -RIT VEXU Core API: AutoChooser Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    - -
    - -

    #include <auto_chooser.h>

    - - - - -

    -Classes

    struct  entry_t
     
    - - - - - - - -

    -Public Member Functions

     AutoChooser (vex::brain &brain)
     
    void add (std::string name)
     
    std::string get_choice ()
     
    - - - -

    -Protected Member Functions

    void render (entry_t *selected)
     
    - - - - - - - -

    -Protected Attributes

    std::string choice
     
    std::vector< entry_tlist
     
    vex::brain & brain
     
    -

    Detailed Description

    -

    Autochooser is a utility to make selecting robot autonomous programs easier source: RIT VexU Wiki During a season, we usually code between 4 and 6 autonomous programs. Most teams will change their entire robot program as a way of choosing autonomi but this may cause issues if you have an emergency patch to upload during a competition. This class was built as a way of using the robot screen to list autonomous programs, and the touchscreen to select them.

    -

    Constructor & Destructor Documentation

    - -

    ◆ AutoChooser()

    - -
    -
    - - - - - - - - -
    AutoChooser::AutoChooser (vex::brain & brain)
    -
    -

    Initialize the auto-chooser. This class places a choice menu on the brain screen, so the driver can choose which autonomous to run.

    Parameters
    - - -
    brainthe brain on which to draw the selection boxes
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ add()

    - -
    -
    - - - - - - - - -
    void AutoChooser::add (std::string name)
    -
    -

    Add an auto path to the chooser

    Parameters
    - - -
    nameThe name of the path. This should be used as an human readable identifier to the auto path
    -
    -
    -

    Add a new autonomous option. There are 3 options per row.

    - -
    -
    - -

    ◆ get_choice()

    - -
    -
    - - - - - - - -
    std::string AutoChooser::get_choice ()
    -
    -

    Get the currently selected auto choice

    Returns
    the identifier to the auto path
    -

    Return the selected autonomous

    - -
    -
    - -

    ◆ render()

    - -
    -
    - - - - - -
    - - - - - - - - -
    void AutoChooser::render (entry_tselected)
    -
    -protected
    -
    -

    Place all the autonomous choices on the screen. If one is selected, change it's color

    Parameters
    - - -
    selectedthe choice that is currently selected
    -
    -
    - -
    -
    -

    Member Data Documentation

    - -

    ◆ brain

    - -
    -
    - - - - - -
    - - - - -
    vex::brain& AutoChooser::brain
    -
    -protected
    -
    -

    the brain to show the choices on

    - -
    -
    - -

    ◆ choice

    - -
    -
    - - - - - -
    - - - - -
    std::string AutoChooser::choice
    -
    -protected
    -
    -

    the current choice of auto

    - -
    -
    - -

    ◆ list

    - -
    -
    - - - - - -
    - - - - -
    std::vector<entry_t> AutoChooser::list
    -
    -protected
    -
    -

    < a list of all possible auto choices

    - -
    -
    -
    The documentation for this class was generated from the following files: -
    - - - - diff --git a/documentation/html/classAutoCommand-members.html b/documentation/html/classAutoCommand-members.html deleted file mode 100644 index daf0d0e..0000000 --- a/documentation/html/classAutoCommand-members.html +++ /dev/null @@ -1,88 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    AutoCommand Member List
    -
    -
    - -

    This is the complete list of members for AutoCommand, including all inherited members.

    - - - - - -
    on_timeout()AutoCommandinlinevirtual
    run()AutoCommandinlinevirtual
    timeout_secondsAutoCommand
    withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
    - - - - diff --git a/documentation/html/classAutoCommand.html b/documentation/html/classAutoCommand.html deleted file mode 100644 index 9c9139f..0000000 --- a/documentation/html/classAutoCommand.html +++ /dev/null @@ -1,205 +0,0 @@ - - - - - - - -RIT VEXU Core API: AutoCommand Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    AutoCommand Class Reference
    -
    -
    - -

    #include <auto_command.h>

    -
    -Inheritance diagram for AutoCommand:
    -
    -
    - - -DelayCommand -DriveForwardCommand -DriveStopCommand -DriveToPointCommand -FlywheelStopCommand -FlywheelStopMotorsCommand -FlywheelStopNonTasksCommand -OdomSetPosition -SpinRPMCommand -TurnDegreesCommand -TurnToHeadingCommand -WaitUntilUpToSpeedCommand - -
    - - - - - - - - -

    -Public Member Functions

    virtual bool run ()
     
    virtual void on_timeout ()
     
    -AutoCommandwithTimeout (double t_seconds)
     
    - - - -

    -Public Attributes

    double timeout_seconds = 10.0
     
    -

    Detailed Description

    -

    File: auto_command.h Desc: Interface for module-specifc commands

    -

    Member Function Documentation

    - -

    ◆ on_timeout()

    - -
    -
    - - - - - -
    - - - - - - - -
    virtual void AutoCommand::on_timeout ()
    -
    -inlinevirtual
    -
    -

    What to do if we timeout instead of finishing. timeout is specified by the timeout seconds in the constructor

    - -

    Reimplemented in DriveForwardCommand, TurnDegreesCommand, and TurnToHeadingCommand.

    - -
    -
    - -

    ◆ run()

    - -
    -
    - - - - - -
    - - - - - - - -
    virtual bool AutoCommand::run ()
    -
    -inlinevirtual
    -
    -

    Executes the command Overridden by child classes

    Returns
    true when the command is finished, false otherwise
    - -

    Reimplemented in DelayCommand, DriveForwardCommand, TurnDegreesCommand, DriveToPointCommand, TurnToHeadingCommand, DriveStopCommand, OdomSetPosition, SpinRPMCommand, WaitUntilUpToSpeedCommand, FlywheelStopCommand, and FlywheelStopMotorsCommand.

    - -
    -
    -

    Member Data Documentation

    - -

    ◆ timeout_seconds

    - -
    -
    - - - - -
    double AutoCommand::timeout_seconds = 10.0
    -
    -

    How long to run until we cancel this command. If the command is cancelled, on_timeout() is called to allow any cleanup from the function. If the timeout_seconds <= 0, no timeout will be applied and this command will run forever A timeout can come in handy for some commands that can not reach the end due to some physical limitation such as

      -
    • a drive command hitting a wall and not being able to reach its target
    • -
    • a command that waits until something is up to speed that never gets up to speed because of battery voltage
    • -
    • something else...
    • -
    - -
    -
    -
    The documentation for this class was generated from the following file: -
    - - - - diff --git a/documentation/html/classAutoCommand.png b/documentation/html/classAutoCommand.png deleted file mode 100644 index dbc2ae9af026460a51e9ecb20c4ae5ea5939c1a3..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 5628 zcmdT|cT`hZzl|s|mQhDEj!IFmj3YNl88FfuMFD9FQRLEfLI;(OkVNGhkUp00f`kBq z5C{SS2?2zlg9FMXv=~B>Zi0jsM5L2<;puzdxZZnf-dgkhVg5)?ZdvP`-#+`d_dbzl z%?!R>ziT}Th5FXWP~QTDS_Pp{5~bg)My@!z9ws3_yU&{7PKm{0WcY4m%0K>h>d_;I zu700T|L)ndXUKKSyPRy~-a0=EGfNcmf90boL4J)wZI3Y0{}~swYLqhU(|>HsT5`a4 z{xqq-xR>l{Qo65iW1phCr^miRtM8>6zp6ESct( zX@WzX>(D$)*?|6m&_m~reC!jAbEXL-y`I^K>vvky(-3%uu=`h zNs@D{@l*v6`G&s(2tCvM+YoDf-sk^XM#8{mcdX2&2&U8?)SJfd_MmVIAc}TPyJo|2 zm2}CpUE;?tHXH|#(VjaJXX9K~{a`>x-B$!rb>9If{%!OPAN>u-vB+(i=D*{1tue#T zj#sINs$zREvRPWq>0q4eIlzFP4Jm>+WKo>Kt8?^5numrW?uw{aF{OEYAC56&!I1ITe1-wd4if>a z4XXg(b~F6xtJDaudZ);h6f-!lb*aukL8zEUG`HG$~2lGuCBlmT_FM`#+FEBpeb|K52>CBjw;C5IF$6GTZoTV}=Iv+e%^O8-i^ z3Y;;|ziWQAsI%fiwD74kKtq_w_4z#Y)I9#xIVE%2;TjR%F)F+J)yZl-TbMVS^t%>I z&diUV-Cg?|?cp9X(!glh_mD}7d{&C-Y<(B3no%6EFr)?I#?zZsANkhLUUJ!WL=tj} zZT4-IQk-N5EL;w;r>k$p&|}&wzOi*}t}gfTbe5inAg3M2}S?V$q;a>L76pa9XQO>yF49z3`lz;qQwUZ#irf{kiX+c+y{UB9d zY>Fj_=iSe^Y;1^*)iibtjY4zn5I%hrgfhoToHDs$6EL7$C1^!i)bE|I+Q;>=frCQT z!3%+hf$JBU8>l(R8yNaVa)VE~0}h@9!}lAzW98y&6CPdY^h?pGgIq%Ol<27OH+bF8~xbe4feeyZ{>(}$$u+!s7$qKYUWK-@?2gBDV z3VZ!DE9Nds*6&v}+Zp9K^5%Zyo36*@;4h#mh*O?D12^$rCSs}|W%=$b8}U2&iAy>m z-L)w|=L?4^mCPldx_q?G@v7a9Hp)DBF{sN$*~ z>Aa`Pdd_t23t7z9%fT~W;;Ql+Z<<>KK_sn;^!+Z;!u@&BP;Z;+TW{U4 z8j9<0DgkjrvWjq9SjnhNV$}PJ6ZC8%TNZ0k+1nmWW6t^k<}R8bYHV;X(0FiV@Z8jd zA@_y;PDriDvkoH9#thV&8#aHd`2Rn;U{DT}KU_X7)yoXdLvsTUezED6Dxm7w$#Gh_ zGu7jrjI(VGHE#ctr!OjQ2q~W7VgkUE4l;$yNR4k3hY#@QU!|gvUbVSZ755A$MSZ&W z`9Q8t!po!hABqZnOVvT>o%*7-za4&ZL{Mv0_0ysc9YLLSy2fuOr^?SvQPbLcEQu@F zrd%BHLRpiH@03_bE5?&&a&@zk?aj*a@I)yL{hd>nMvER%y7Pd0kR`R!H8do!woz7V z0}yF<`{o%ab$!eou+YM#MT2KZ4^MaPzogHOW&o$a0dnDy=+y}|<} z+Zq%>-EmL10=T>Cl3`uw+E|zYQF)7d2Z zDNG85I=4+elRq?adc!kjX+D4U?ebv8UD}ec;a|MTvg#qeaHu>#Bm_kyC%CWr2F3i_ z&E8+cd%^;+r?78SNIH=edV%{j(y%**voXp4QA6enwrtZz(5EgWl>xVrgD+9}4C zuT=hY&%sVJ+1_Ql&UW$p)^)2boXq8e?hT9ak7oPUA%XN)EP3@{)zGyOnW)~LY4u-* zk`%n6BD$SyLyFgQOyQ~&!0#eptp8-owNRz3SR8r4Q@AFmtCmGq@u#OvU z(J1}Y)Q{6Ck~BRddbYhw2M6b1_=O-W$DpOOWq-h2_6IrW8>p+%|L%i}|4qx3xyvDc z2?_ZH-1NDz&k^mjBX)7aZj|SKOMZE^SX1=6j6=d(a}S4N7Y1nj>lz&|c_5CLtR+9W z6?nQ%=BSvlHJnKt+L`Ofis7oVle8e(P9BBixbW&wlZj>5U^OH8uExRq$a*kou(@`w zrTz*vl~YyzU^QEvOVF(Z(XC)shVvmxEMuAUm*sSozCqt01K6$DdTelT60iNc)%bjA zQ>npEoXs62*KUrgb9HphqJ@p`@x=3~dq7;OK(P1W+?wX}IqiY&%(;7CRN||090VXD zyv)V*DP?%6T4Wv0*i73U-mbYeC%=7@SRW| zox3i;uL%eN1^o$n7O*Igzp=f%gpXSRl=472n8GazEU}d{OmKm%4wHTw zz063~hm!wQRe=~N3dTroQun>QBNH(4l(9}j~GPPNf9pD%srw#+2YMGc(I8CUD uoNei(OZL_-`@@C%Xs$T+f3^}SViZ*3XE+t8(vO_eqKrF1wty!9X6E{rz- diff --git a/documentation/html/classCommandController-members.html b/documentation/html/classCommandController-members.html deleted file mode 100644 index a530d84..0000000 --- a/documentation/html/classCommandController-members.html +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    CommandController Member List
    -
    -
    - -

    This is the complete list of members for CommandController, including all inherited members.

    - - - - - - -
    add(AutoCommand *cmd, double timeout_seconds=10.0)CommandController
    add(std::vector< AutoCommand * > cmds)CommandController
    add_delay(int ms)CommandController
    last_command_timed_out()CommandController
    run()CommandController
    - - - - diff --git a/documentation/html/classCommandController.html b/documentation/html/classCommandController.html deleted file mode 100644 index d377e9e..0000000 --- a/documentation/html/classCommandController.html +++ /dev/null @@ -1,233 +0,0 @@ - - - - - - - -RIT VEXU Core API: CommandController Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    CommandController Class Reference
    -
    -
    - -

    #include <command_controller.h>

    - - - - - - - - - - - - -

    -Public Member Functions

    void add (AutoCommand *cmd, double timeout_seconds=10.0)
     
    void add (std::vector< AutoCommand * > cmds)
     
    void add_delay (int ms)
     
    void run ()
     
    bool last_command_timed_out ()
     
    -

    Detailed Description

    -

    File: command_controller.h Desc: A CommandController manages the AutoCommands that make up an autonomous route. The AutoCommands are kept in a queue and get executed and removed from the queue in FIFO order.

    -

    Member Function Documentation

    - -

    ◆ add() [1/2]

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    void CommandController::add (AutoCommandcmd,
    double timeout_seconds = 10.0 
    )
    -
    -

    Adds a command to the queue

    Parameters
    - - - -
    cmdthe AutoCommand we want to add to our list
    timeout_secondsthe number of seconds we will let the command run for. If it exceeds this, we cancel it and run on_timeout. if it is <= 0 no time out will be applied
    -
    -
    -

    File: command_controller.cpp Desc: A CommandController manages the AutoCommands that make up an autonomous route. The AutoCommands are kept in a queue and get executed and removed from the queue in FIFO order. Adds a command to the queue

    Parameters
    - - - -
    cmdthe AutoCommand we want to add to our list
    timeout_secondsthe number of seconds we will let the command run for. If it exceeds this, we cancel it and run on_timeout
    -
    -
    - -
    -
    - -

    ◆ add() [2/2]

    - -
    -
    - - - - - - - - -
    void CommandController::add (std::vector< AutoCommand * > cmds)
    -
    -

    Add multiple commands to the queue. No timeout here.

    Parameters
    - - -
    cmdsthe AutoCommands we want to add to our list
    -
    -
    - -
    -
    - -

    ◆ add_delay()

    - -
    -
    - - - - - - - - -
    void CommandController::add_delay (int ms)
    -
    -

    Adds a command that will delay progression of the queue

    Parameters
    - - -
    ms- number of milliseconds to wait before continuing execution of autonomous
    -
    -
    - -
    -
    - -

    ◆ last_command_timed_out()

    - -
    -
    - - - - - - - -
    bool CommandController::last_command_timed_out ()
    -
    -

    last_command_timed_out tells how the last command ended Use this if you want to make decisions based on the end of the last command

    Returns
    true if the last command timed out. false if it finished regularly
    - -
    -
    - -

    ◆ run()

    - -
    -
    - - - - - - - -
    void CommandController::run ()
    -
    -

    Begin execution of the queue Execute and remove commands in FIFO order

    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/utils/command_structure/command_controller.h
    • -
    • src/utils/command_structure/command_controller.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classCustomEncoder-members.html b/documentation/html/classCustomEncoder-members.html deleted file mode 100644 index fa936ea..0000000 --- a/documentation/html/classCustomEncoder-members.html +++ /dev/null @@ -1,90 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    CustomEncoder Member List
    -
    -
    - -

    This is the complete list of members for CustomEncoder, including all inherited members.

    - - - - - - - -
    CustomEncoder(vex::triport::port &port, double ticks_per_rev)CustomEncoder
    position(vex::rotationUnits units)CustomEncoder
    rotation(vex::rotationUnits units)CustomEncoder
    setPosition(double val, vex::rotationUnits units)CustomEncoder
    setRotation(double val, vex::rotationUnits units)CustomEncoder
    velocity(vex::velocityUnits units)CustomEncoder
    - - - - diff --git a/documentation/html/classCustomEncoder.html b/documentation/html/classCustomEncoder.html deleted file mode 100644 index dfb1463..0000000 --- a/documentation/html/classCustomEncoder.html +++ /dev/null @@ -1,296 +0,0 @@ - - - - - - - -RIT VEXU Core API: CustomEncoder Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    CustomEncoder Class Reference
    -
    -
    - -

    #include <custom_encoder.h>

    -
    -Inheritance diagram for CustomEncoder:
    -
    -
    - -
    - - - - - - - - - - - - - - -

    -Public Member Functions

     CustomEncoder (vex::triport::port &port, double ticks_per_rev)
     
    void setRotation (double val, vex::rotationUnits units)
     
    void setPosition (double val, vex::rotationUnits units)
     
    double rotation (vex::rotationUnits units)
     
    double position (vex::rotationUnits units)
     
    double velocity (vex::velocityUnits units)
     
    -

    Detailed Description

    -

    A wrapper class for the vex encoder that allows the use of 3rd party encoders with different tick-per-revolution values.

    -

    Constructor & Destructor Documentation

    - -

    ◆ CustomEncoder()

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    CustomEncoder::CustomEncoder (vex::triport::port & port,
    double ticks_per_rev 
    )
    -
    -

    Construct an encoder with a custom number of ticks

    Parameters
    - - - -
    portthe triport port on the brain the encoder is plugged into
    ticks_per_revthe number of ticks the encoder will report for one revolution
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ position()

    - -
    -
    - - - - - - - - -
    double CustomEncoder::position (vex::rotationUnits units)
    -
    -

    get the position that the encoder is at

    Parameters
    - - -
    unitsthe unit we want the return value to be in
    -
    -
    -
    Returns
    the position of the encoder in the units specified
    - -
    -
    - -

    ◆ rotation()

    - -
    -
    - - - - - - - - -
    double CustomEncoder::rotation (vex::rotationUnits units)
    -
    -

    get the rotation that the encoder is at

    Parameters
    - - -
    unitsthe unit we want the return value to be in
    -
    -
    -
    Returns
    the rotation of the encoder in the units specified
    - -
    -
    - -

    ◆ setPosition()

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    void CustomEncoder::setPosition (double val,
    vex::rotationUnits units 
    )
    -
    -

    sets the stored position of the encoder. Any further movements will be from this value

    Parameters
    - - - -
    valthe numerical value of the position we are setting to
    unitsthe unit of val
    -
    -
    - -
    -
    - -

    ◆ setRotation()

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    void CustomEncoder::setRotation (double val,
    vex::rotationUnits units 
    )
    -
    -

    sets the stored rotation of the encoder. Any further movements will be from this value

    Parameters
    - - - -
    valthe numerical value of the angle we are setting to
    unitsthe unit of val
    -
    -
    - -
    -
    - -

    ◆ velocity()

    - -
    -
    - - - - - - - - -
    double CustomEncoder::velocity (vex::velocityUnits units)
    -
    -

    get the velocity that the encoder is moving at

    Parameters
    - - -
    unitsthe unit we want the return value to be in
    -
    -
    -
    Returns
    the velocity of the encoder in the units specified
    - -
    -
    -
    The documentation for this class was generated from the following files: -
    - - - - diff --git a/documentation/html/classCustomEncoder.png b/documentation/html/classCustomEncoder.png deleted file mode 100644 index 88e06a2b60fc27308a74888eecee5a5b25fb0f4d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 494 zcmeAS@N?(olHy`uVBq!ia0vp^sX!dS!3-qLMZF&bDd_;85ZC|z{{xvX-h3_XKeXJ! zK(jz%`k5C84jcfA2T!`Z0w~8>666=m0OW&#In(Sb3=E8wo-U3d6^w7^9-P#oz~f>) z{pG*^`f=<60gW?d3bJEYT?$G##H~`*HuGl5L64$MVy!B+zlx_EbldMz>EE1F-Bx~6 zQ78AZ!IDTxuaFOlk!##FopTc{&UMAlTxzp#*_D6OYj1b&K300tz5jb~;G;_uHn~q+ zv)23M>?xaKzP*+G!0n}3xhhfimX^nAJ(cX&fqb^xjz7P>;`YkB$tv2>^%9f5WCVI# zTHGFZ=1dwl!<;I{10{EzD)+uSaL4JUf_cKbg*K~>i?K4qM2Rqb$OvROu-KK6p&uw< z0~h%3XJ|ZIZ-$ERwM8D2+_wkc+pF+0p;sj7vPY2n+8I8ak8ds(RrFNu)p+W$dz-t5 zRa)Nrqkm(+bgO%@pLXW*^K^f&w{)99OYCKvx8eKs0z=JypY79_{$q>xn$rj0b6L-; zu1NOv(w=RsYI-95)X!rvQ-YOas@KH4y*{Nb_Sb#yyve&R?kfFxA^EkvnrEGEmrCUq fgRYr3bN({?VyYD8Oskp&j2Q+`S3j3^P6 - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    DelayCommand Member List
    -
    -
    - -

    This is the complete list of members for DelayCommand, including all inherited members.

    - - - - - - -
    DelayCommand(int ms)DelayCommandinline
    on_timeout()AutoCommandinlinevirtual
    run() overrideDelayCommandinlinevirtual
    timeout_secondsAutoCommand
    withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
    - - - - diff --git a/documentation/html/classDelayCommand.html b/documentation/html/classDelayCommand.html deleted file mode 100644 index 5ac6f9b..0000000 --- a/documentation/html/classDelayCommand.html +++ /dev/null @@ -1,184 +0,0 @@ - - - - - - - -RIT VEXU Core API: DelayCommand Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    DelayCommand Class Reference
    -
    -
    - -

    #include <delay_command.h>

    -
    -Inheritance diagram for DelayCommand:
    -
    -
    - - -AutoCommand - -
    - - - - - - - - - - - - - -

    -Public Member Functions

     DelayCommand (int ms)
     
    bool run () override
     
    - Public Member Functions inherited from AutoCommand
    virtual bool run ()
     
    virtual void on_timeout ()
     
    -AutoCommandwithTimeout (double t_seconds)
     
    - - - - -

    -Additional Inherited Members

    - Public Attributes inherited from AutoCommand
    double timeout_seconds = 10.0
     
    -

    Detailed Description

    -

    File: delay_command.h Desc: A DelayCommand will make the robot wait the set amount of milliseconds before continuing execution of the autonomous route

    -

    Constructor & Destructor Documentation

    - -

    ◆ DelayCommand()

    - -
    -
    - - - - - -
    - - - - - - - - -
    DelayCommand::DelayCommand (int ms)
    -
    -inline
    -
    -

    Construct a delay command

    Parameters
    - - -
    msthe number of milliseconds to delay for
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ run()

    - -
    -
    - - - - - -
    - - - - - - - -
    bool DelayCommand::run ()
    -
    -inlineoverridevirtual
    -
    -

    Delays for the amount of milliseconds stored in the command Overrides run from AutoCommand

    Returns
    true when complete
    - -

    Reimplemented from AutoCommand.

    - -
    -
    -
    The documentation for this class was generated from the following file: -
    - - - - diff --git a/documentation/html/classDelayCommand.png b/documentation/html/classDelayCommand.png deleted file mode 100644 index 0275ee5a7ae92b1f70e62ff0c92d7724de5dfdcb..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 508 zcmeAS@N?(olHy`uVBq!ia0vp^DL@>+!3-pCTvxaYq@)9ULR|m<{|{uoc=NTi|Il&^ z1I+@7>1SRXIB)4W!G&`m#=`8|>vJ_XWT6eW=#j0Ij#RViwpZp9C{d#)I zc7e>^-OtjeNInU*oxOhRasCy;MgK)N^-6i{RaE({D!SN8@jL(KWr0kU&q_O1ZBb?Q z{UTBBd5P=TggYsCG)a&nS8Ae`W76LYsvJ{E42A< z*~(RQYj^`gOJA>6P;A){!SG?B9K(jFatFD7X^nD+c|BjJL@UIX>^5Uz_;X8up&;9t z;lNs6MuzP`fje-4dR{@nNL>z3pcf`AiT>`?7oEVYa&y&bg_E6|${S10rSG@4TX%V;ipR=76F$$JQtw#3`%P1jo2S5~X;b3U=kIG#ao_bzqe5Z2 ryd3+JUyrxVubNZ>^pcWN_g7}wM?qm8e_p=<#uJ05tDnm{r-UW|$HeC2 diff --git a/documentation/html/classDriveForwardCommand-members.html b/documentation/html/classDriveForwardCommand-members.html deleted file mode 100644 index 375c415..0000000 --- a/documentation/html/classDriveForwardCommand-members.html +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    DriveForwardCommand Member List
    -
    -
    - -

    This is the complete list of members for DriveForwardCommand, including all inherited members.

    - - - - - - -
    DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed=1)DriveForwardCommand
    on_timeout() overrideDriveForwardCommandvirtual
    run() overrideDriveForwardCommandvirtual
    timeout_secondsAutoCommand
    withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
    - - - - diff --git a/documentation/html/classDriveForwardCommand.html b/documentation/html/classDriveForwardCommand.html deleted file mode 100644 index 25ba864..0000000 --- a/documentation/html/classDriveForwardCommand.html +++ /dev/null @@ -1,252 +0,0 @@ - - - - - - - -RIT VEXU Core API: DriveForwardCommand Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    DriveForwardCommand Class Reference
    -
    -
    - -

    #include <drive_commands.h>

    -
    -Inheritance diagram for DriveForwardCommand:
    -
    -
    - - -AutoCommand - -
    - - - - - - - - - - - - - - - -

    -Public Member Functions

     DriveForwardCommand (TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed=1)
     
    bool run () override
     
    void on_timeout () override
     
    - Public Member Functions inherited from AutoCommand
    virtual bool run ()
     
    virtual void on_timeout ()
     
    -AutoCommandwithTimeout (double t_seconds)
     
    - - - - -

    -Additional Inherited Members

    - Public Attributes inherited from AutoCommand
    double timeout_seconds = 10.0
     
    -

    Detailed Description

    -

    AutoCommand wrapper class for the drive_forward function in the TankDrive class

    -

    Constructor & Destructor Documentation

    - -

    ◆ DriveForwardCommand()

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    DriveForwardCommand::DriveForwardCommand (TankDrivedrive_sys,
    Feedbackfeedback,
    double inches,
    directionType dir,
    double max_speed = 1 
    )
    -
    -

    File: drive_commands.h Desc: Holds all the AutoCommand subclasses that wrap (currently) TankDrive functions

    -

    Currently includes:

      -
    • drive_forward
    • -
    • turn_degrees
    • -
    • drive_to_point
    • -
    • turn_to_heading
    • -
    • stop
    • -
    -

    Also holds AutoCommand subclasses that wrap OdometryBase functions

    -

    Currently includes:

      -
    • set_position Construct a DriveForward Command
      Parameters
      - - - - - - -
      drive_systhe drive system we are commanding
      feedbackthe feedback controller we are using to execute the drive
      incheshow far forward to drive
      dirthe direction to drive
      max_speed0 -> 1 percentage of the drive systems speed to drive at
      -
      -
      -
    • -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ on_timeout()

    - -
    -
    - - - - - -
    - - - - - - - -
    void DriveForwardCommand::on_timeout ()
    -
    -overridevirtual
    -
    -

    Cleans up drive system if we time out before finishing

    -

    reset the drive system if we timeout

    - -

    Reimplemented from AutoCommand.

    - -
    -
    - -

    ◆ run()

    - -
    -
    - - - - - -
    - - - - - - - -
    bool DriveForwardCommand::run ()
    -
    -overridevirtual
    -
    -

    Run drive_forward Overrides run from AutoCommand

    Returns
    true when execution is complete, false otherwise
    - -

    Reimplemented from AutoCommand.

    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/utils/command_structure/drive_commands.h
    • -
    • src/utils/command_structure/drive_commands.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classDriveForwardCommand.png b/documentation/html/classDriveForwardCommand.png deleted file mode 100644 index fc8d72471098ed76d0e31fd1ac25e1e6eecfa68b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 613 zcmeAS@N?(olHy`uVBq!ia0vp^lYlsYgBeI3ZM_4cqyv0HT>t<74`jZ0^R=}9&~gg{ z%>s$(XI>mQZ~!PCJn8ZZpd4pOkY6wZkPimtOtY^rFfe}bba4!+V0=6GcHV0P9+v6a z3OD}$fAqL}U7xH~Yqf$%j_FzvuPYIPlf#!xxfG)?@rh51kY^PL-wEEdx>46&rBc5B zm#(U`Dc{}qbLNFc{nxqsHRjvl%$KJtc)!jSJF&QZ%BgoVcjbD=AG>|cc{$suQ~%ex z+`3V;VfOzCLHmx_2i}@)w|0xVq|p5^sn|N#m9bsZ{%d5X+~@n4KK0h!v#nR`roXZV z^0ys`OVefatW($*;BiTL3IZnwdTB0Q$BZzr`q1u((}O$m>?KDUHx3vIVCg! E0BqtSOaK4? diff --git a/documentation/html/classDriveStopCommand-members.html b/documentation/html/classDriveStopCommand-members.html deleted file mode 100644 index 877cc5e..0000000 --- a/documentation/html/classDriveStopCommand-members.html +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    DriveStopCommand Member List
    -
    -
    - -

    This is the complete list of members for DriveStopCommand, including all inherited members.

    - - - - - - -
    DriveStopCommand(TankDrive &drive_sys)DriveStopCommand
    on_timeout()AutoCommandinlinevirtual
    run() overrideDriveStopCommandvirtual
    timeout_secondsAutoCommand
    withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
    - - - - diff --git a/documentation/html/classDriveStopCommand.html b/documentation/html/classDriveStopCommand.html deleted file mode 100644 index 0691bb1..0000000 --- a/documentation/html/classDriveStopCommand.html +++ /dev/null @@ -1,178 +0,0 @@ - - - - - - - -RIT VEXU Core API: DriveStopCommand Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    DriveStopCommand Class Reference
    -
    -
    - -

    #include <drive_commands.h>

    -
    -Inheritance diagram for DriveStopCommand:
    -
    -
    - - -AutoCommand - -
    - - - - - - - - - - - - - -

    -Public Member Functions

     DriveStopCommand (TankDrive &drive_sys)
     
    bool run () override
     
    - Public Member Functions inherited from AutoCommand
    virtual bool run ()
     
    virtual void on_timeout ()
     
    -AutoCommandwithTimeout (double t_seconds)
     
    - - - - -

    -Additional Inherited Members

    - Public Attributes inherited from AutoCommand
    double timeout_seconds = 10.0
     
    -

    Detailed Description

    -

    AutoCommand wrapper class for the stop() function in the TankDrive class

    -

    Constructor & Destructor Documentation

    - -

    ◆ DriveStopCommand()

    - -
    -
    - - - - - - - - -
    DriveStopCommand::DriveStopCommand (TankDrivedrive_sys)
    -
    -

    Construct a DriveStop Command

    Parameters
    - - -
    drive_systhe drive system we are commanding
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ run()

    - -
    -
    - - - - - -
    - - - - - - - -
    bool DriveStopCommand::run ()
    -
    -overridevirtual
    -
    -

    Stop the drive system Overrides run from AutoCommand

    Returns
    true when execution is complete, false otherwise
    -

    Stop the drive train Overrides run from AutoCommand

    Returns
    true when execution is complete, false otherwise
    - -

    Reimplemented from AutoCommand.

    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/utils/command_structure/drive_commands.h
    • -
    • src/utils/command_structure/drive_commands.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classDriveStopCommand.png b/documentation/html/classDriveStopCommand.png deleted file mode 100644 index 535e91ddba4db331b47fc65da562e61ce3605bda..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 549 zcmeAS@N?(olHy`uVBq!ia0vp^)j%A;!3-q%ihk_?QqloFA+G=b{|7Q(y!l$%e`vXd zfo6fk^fNCG95?_J51w>+1yGK&B*-tA0mugfbEer>7#J8gc)B=-R4~4so85O{+ z+_qWQdDb7y-}F6C`kl4yw%L!5{LIs0zbTLwep66*%A@BNh3_Pcl3~Z?oUTcr2{>{MS$a=!s30hXe0e zGI*Lr-4B^0v-+so$&J5`=RBV?TbW_UdUgh%OD^9Y8}i#t+`Dl3!Sqf4bLZ-tG4NbV zVm=U|YsS!X6)Pik=1gB9pGnIyHmYW>`NwiwJg!d1b86Gh$(dUNCf(Cg65idv=FawY zldrsPopfc@>2G^~)=T`#6@B+x#V(Ui$@W~LQ_|A^_x2~qXFENZ<5beo_9kq}TW9$j zCK-PpYrlH8`#7JsUz>3Brd_6*`z=2|y0A*>jqC~bH_C@(zpcEsZqxj^$?MNe-a4oB zM(P5sZJxf_Z`8}IZqJfkWpelZwsSyliyvCDsnXf*h~HfAORBa1ZDVpgrB)xEwq)b1 eGiJuK7t3=pqz0CJK6Vcnp$wj`elF{r5}E*In+j3@ diff --git a/documentation/html/classDriveToPointCommand-members.html b/documentation/html/classDriveToPointCommand-members.html deleted file mode 100644 index 8765c93..0000000 --- a/documentation/html/classDriveToPointCommand-members.html +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    DriveToPointCommand Member List
    -
    -
    - -

    This is the complete list of members for DriveToPointCommand, including all inherited members.

    - - - - - - -
    DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed=1)DriveToPointCommand
    DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, Vector2D::point_t point, directionType dir, double max_speed=1)DriveToPointCommand
    run() overrideDriveToPointCommandvirtual
    timeout_secondsAutoCommand
    withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
    - - - - diff --git a/documentation/html/classDriveToPointCommand.html b/documentation/html/classDriveToPointCommand.html deleted file mode 100644 index 6037c14..0000000 --- a/documentation/html/classDriveToPointCommand.html +++ /dev/null @@ -1,274 +0,0 @@ - - - - - - - -RIT VEXU Core API: DriveToPointCommand Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    DriveToPointCommand Class Reference
    -
    -
    - -

    #include <drive_commands.h>

    -
    -Inheritance diagram for DriveToPointCommand:
    -
    -
    - - -AutoCommand - -
    - - - - - - - - - - - - - - - -

    -Public Member Functions

     DriveToPointCommand (TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed=1)
     
     DriveToPointCommand (TankDrive &drive_sys, Feedback &feedback, Vector2D::point_t point, directionType dir, double max_speed=1)
     
    bool run () override
     
    - Public Member Functions inherited from AutoCommand
    virtual bool run ()
     
    virtual void on_timeout ()
     
    -AutoCommandwithTimeout (double t_seconds)
     
    - - - - -

    -Additional Inherited Members

    - Public Attributes inherited from AutoCommand
    double timeout_seconds = 10.0
     
    -

    Detailed Description

    -

    AutoCommand wrapper class for the drive_to_point function in the TankDrive class

    -

    Constructor & Destructor Documentation

    - -

    ◆ DriveToPointCommand() [1/2]

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    DriveToPointCommand::DriveToPointCommand (TankDrivedrive_sys,
    Feedbackfeedback,
    double x,
    double y,
    directionType dir,
    double max_speed = 1 
    )
    -
    -

    Construct a DriveForward Command

    Parameters
    - - - - - - - -
    drive_systhe drive system we are commanding
    feedbackthe feedback controller we are using to execute the drive
    xwhere to drive in the x dimension
    ywhere to drive in the y dimension
    dirthe direction to drive
    max_speed0 -> 1 percentage of the drive systems speed to drive at
    -
    -
    - -
    -
    - -

    ◆ DriveToPointCommand() [2/2]

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    DriveToPointCommand::DriveToPointCommand (TankDrivedrive_sys,
    Feedbackfeedback,
    Vector2D::point_t point,
    directionType dir,
    double max_speed = 1 
    )
    -
    -

    Construct a DriveForward Command

    Parameters
    - - - - - - -
    drive_systhe drive system we are commanding
    feedbackthe feedback controller we are using to execute the drive
    pointthe point to drive to
    dirthe direction to drive
    max_speed0 -> 1 percentage of the drive systems speed to drive at
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ run()

    - -
    -
    - - - - - -
    - - - - - - - -
    bool DriveToPointCommand::run ()
    -
    -overridevirtual
    -
    -

    Run drive_to_point Overrides run from AutoCommand

    Returns
    true when execution is complete, false otherwise
    - -

    Reimplemented from AutoCommand.

    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/utils/command_structure/drive_commands.h
    • -
    • src/utils/command_structure/drive_commands.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classDriveToPointCommand.png b/documentation/html/classDriveToPointCommand.png deleted file mode 100644 index 690e372fedbe6424ef275b37e2ee92c4dd0933b1..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 595 zcmeAS@N?(olHy`uVBq!ia0vp^JwP15!3-q-Jj#s#QqloFA+G=b{|7Q(y!l$%e`vXd zfo6fk^fNCG95?_J51w>+1yGK&B*-tA0mugfbEer>7#JAudAc};R4~4sd%JIqf`Dsz z?xb`7{_EStP3WGs_Hu683D2(^cp{j*HRgmbnQ}=(Vd4{s79P(k5WX{EDw zAANk?=oi-#=4R@|E=Yfuq=h``=;G|c6JKq>jTl%GqG+28X{+&0>K^srIs=hr8yeU)!->b6%6-fS#C>DOG% z-x(><(+*U%ykbzPbo*ni;MqSx5rI9`mQG<~WRQEn%COjA(wWz$6V7@VO+Ia5=6v!< zCKJQ_35*Q=#Nz*f$Ij%4Bup}4Q&jep17X*+lh3N6gQAPJm7i6+b^X@@mDr7zB9iA1 zzWng-;m>_2;=Q2mhLxzJ51H>2b lliMU47 - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    FeedForward Member List
    -
    -
    - -

    This is the complete list of members for FeedForward, including all inherited members.

    - - - -
    calculate(double v, double a, double pid_ref=0.0)FeedForwardinline
    FeedForward(ff_config_t &cfg)FeedForwardinline
    - - - - diff --git a/documentation/html/classFeedForward.html b/documentation/html/classFeedForward.html deleted file mode 100644 index 687b0e0..0000000 --- a/documentation/html/classFeedForward.html +++ /dev/null @@ -1,199 +0,0 @@ - - - - - - - -RIT VEXU Core API: FeedForward Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    FeedForward Class Reference
    -
    -
    - -

    #include <feedforward.h>

    - - - - -

    -Classes

    struct  ff_config_t
     
    - - - - - - -

    -Public Member Functions

     FeedForward (ff_config_t &cfg)
     
    double calculate (double v, double a, double pid_ref=0.0)
     Perform the feedforward calculation.
     
    -

    Detailed Description

    -

    FeedForward

    -

    Stores the feedfoward constants, and allows for quick computation. Feedfoward should be used in systems that require smooth precise movements and have high inertia, such as drivetrains and lifts.

    -

    This is best used alongside a PID loop, with the form: output = pid.get() + feedforward.calculate(v, a);

    -

    In this case, the feedforward does the majority of the heavy lifting, and the pid loop only corrects for inconsistencies

    -

    For information about tuning feedforward, I reccommend looking at this post: https://www.chiefdelphi.com/t/paper-frc-drivetrain-characterization/160915 (yes I know it's for FRC but trust me, it's useful)

    -
    Author
    Ryan McGee
    -
    Date
    6/13/2022
    -

    Constructor & Destructor Documentation

    - -

    ◆ FeedForward()

    - -
    -
    - - - - - -
    - - - - - - - - -
    FeedForward::FeedForward (ff_config_tcfg)
    -
    -inline
    -
    -

    Creates a FeedForward object.

    Parameters
    - - -
    cfgConfiguration Struct for tuning
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ calculate()

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - - - - - - - -
    double FeedForward::calculate (double v,
    double a,
    double pid_ref = 0.0 
    )
    -
    -inline
    -
    - -

    Perform the feedforward calculation.

    -

    This calculation is the equation: F = kG + kS*sgn(v) + kV*v + kA*a

    -
    Parameters
    - - - -
    vRequested velocity of system
    aRequested acceleration of system
    -
    -
    -
    Returns
    A feedforward that should closely represent the system if tuned correctly
    - -
    -
    -
    The documentation for this class was generated from the following file: -
    - - - - diff --git a/documentation/html/classFeedback-members.html b/documentation/html/classFeedback-members.html deleted file mode 100644 index fc5a22e..0000000 --- a/documentation/html/classFeedback-members.html +++ /dev/null @@ -1,94 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    Feedback Member List
    -
    -
    - -

    This is the complete list of members for Feedback, including all inherited members.

    - - - - - - - - - - - -
    FeedbackType enum name (defined in Feedback)Feedback
    FeedforwardType enum value (defined in Feedback)Feedback
    get()=0Feedbackpure virtual
    get_type() (defined in Feedback)Feedbackinlinevirtual
    init(double start_pt, double set_pt)=0Feedbackpure virtual
    is_on_target()=0Feedbackpure virtual
    OtherType enum value (defined in Feedback)Feedback
    PIDType enum value (defined in Feedback)Feedback
    set_limits(double lower, double upper)=0Feedbackpure virtual
    update(double val)=0Feedbackpure virtual
    - - - - diff --git a/documentation/html/classFeedback.html b/documentation/html/classFeedback.html deleted file mode 100644 index 9412358..0000000 --- a/documentation/html/classFeedback.html +++ /dev/null @@ -1,315 +0,0 @@ - - - - - - - -RIT VEXU Core API: Feedback Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    Feedback Class Referenceabstract
    -
    -
    - -

    #include <feedback_base.h>

    -
    -Inheritance diagram for Feedback:
    -
    -
    - - -MotionController -PID -PIDFF - -
    - - - - -

    -Public Types

    enum  FeedbackType { PIDType -, FeedforwardType -, OtherType - }
     
    - - - - - - - - - - - - - -

    -Public Member Functions

    virtual void init (double start_pt, double set_pt)=0
     
    virtual double update (double val)=0
     
    virtual double get ()=0
     
    virtual void set_limits (double lower, double upper)=0
     
    virtual bool is_on_target ()=0
     
    -virtual Feedback::FeedbackType get_type ()
     
    -

    Detailed Description

    -

    Interface so that subsystems can easily switch between feedback loops

    -
    Author
    Ryan McGee
    -
    Date
    9/25/2022
    -

    Member Function Documentation

    - -

    ◆ get()

    - -
    -
    - - - - - -
    - - - - - - - -
    virtual double Feedback::get ()
    -
    -pure virtual
    -
    -
    Returns
    the last saved result from the feedback controller
    - -

    Implemented in MotionController, PID, and PIDFF.

    - -
    -
    - -

    ◆ init()

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - -
    virtual void Feedback::init (double start_pt,
    double set_pt 
    )
    -
    -pure virtual
    -
    -

    Initialize the feedback controller for a movement

    -
    Parameters
    - - - -
    start_ptthe current sensor value
    set_ptwhere the sensor value should be
    -
    -
    - -

    Implemented in MotionController, PID, and PIDFF.

    - -
    -
    - -

    ◆ is_on_target()

    - -
    -
    - - - - - -
    - - - - - - - -
    virtual bool Feedback::is_on_target ()
    -
    -pure virtual
    -
    -
    Returns
    true if the feedback controller has reached it's setpoint
    - -

    Implemented in MotionController, PID, and PIDFF.

    - -
    -
    - -

    ◆ set_limits()

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - -
    virtual void Feedback::set_limits (double lower,
    double upper 
    )
    -
    -pure virtual
    -
    -

    Clamp the upper and lower limits of the output. If both are 0, no limits should be applied.

    -
    Parameters
    - - - -
    lowerUpper limit
    upperLower limit
    -
    -
    - -

    Implemented in MotionController, PID, and PIDFF.

    - -
    -
    - -

    ◆ update()

    - -
    -
    - - - - - -
    - - - - - - - - -
    virtual double Feedback::update (double val)
    -
    -pure virtual
    -
    -

    Iterate the feedback loop once with an updated sensor value

    -
    Parameters
    - - -
    valvalue from the sensor
    -
    -
    -
    Returns
    feedback loop result
    - -

    Implemented in MotionController, PID, and PIDFF.

    - -
    -
    -
    The documentation for this class was generated from the following file: -
    - - - - diff --git a/documentation/html/classFeedback.png b/documentation/html/classFeedback.png deleted file mode 100644 index fe590a2623212573b01ca6e3a12913cdb44220a5..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 792 zcmeAS@N?(olHy`uVBq!ia0y~yU<6`@01jp#S+j*V2}nr?_=LFr|NkGzeDUUMY5$?+ z76zIH64TGTIB?(qP&|0jhFmGyEx<8m9GZw3fwip zlqbB_TyFpGg?@`mY`niu(QEr^xS{@&+sovsd|AsA*Ou_Py)5ScS9N3U&D)`Je?DzC zdAoAiWB%obbnb7H@5HbcUErtE(%9>z%NYb1zP(^%au5yV3h=ytT+=}j$T)d4V-C|5 z!KDmGT{IjtfdXDrn5GCVWmxK>iNXE9^U}Wezt=N7kg*Fi{9k!agH=P-i_xnys3B;P z$bu=vaQiaWZe9K|I{R(pKDG48ON=A*{3o4zU~IWKWD-|rkf)Zam+HzX8dH}9z4O{_ zXwbWT_0PjHd-teh9#z{^|GfM3ZnZt<%I21s?^Kcfm~w7!%=T{053}EFzVz^V_w2HK z`Ar^Cd+)C*nOA5JQn2RI+?f8YYM%BRR+rqGns}=4{<62T&A-UW)!Dy$yQbvUvybbP zmik-%U3@9EaLhtzt7A3{>@xVzqjsN6Ef-E>25F8m#KD>je$O&0P^{w zkV(KGMG6X#z)p?awOfNDbk=XZ=J!z8@;_tHp-#5TCys3greOw8S3j3^P6 - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    Flywheel Member List
    -
    -
    - -

    This is the complete list of members for Flywheel, including all inherited members.

    - - - - - - - - - - - - - - - - - - - - - - -
    Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio)Flywheel
    Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio)Flywheel
    Flywheel(motor_group &motors, double tbh_gain, const double ratio)Flywheel
    Flywheel(motor_group &motors, const double ratio)Flywheel
    getDesiredRPM()Flywheel
    getFeedforwardValue()Flywheel
    getMotors()Flywheel
    getPID()Flywheel
    getPIDValue()Flywheel
    getRPM()Flywheel
    getTBHGain()Flywheel
    isTaskRunning()Flywheel
    measureRPM()Flywheel
    setPIDTarget(double value)Flywheel
    spin_manual(double speed, directionType dir=fwd)Flywheel
    spin_raw(double speed, directionType dir=fwd)Flywheel
    spinRPM(int rpm)Flywheel
    stop()Flywheel
    stopMotors()Flywheel
    stopNonTasks()Flywheel
    updatePID(double value)Flywheel
    - - - - diff --git a/documentation/html/classFlywheel.html b/documentation/html/classFlywheel.html deleted file mode 100644 index 4112a90..0000000 --- a/documentation/html/classFlywheel.html +++ /dev/null @@ -1,684 +0,0 @@ - - - - - - - -RIT VEXU Core API: Flywheel Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    Flywheel Class Reference
    -
    -
    - -

    #include <flywheel.h>

    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

    -Public Member Functions

     Flywheel (motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio)
     
     Flywheel (motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio)
     
     Flywheel (motor_group &motors, double tbh_gain, const double ratio)
     
     Flywheel (motor_group &motors, const double ratio)
     
    double getDesiredRPM ()
     
    bool isTaskRunning ()
     
    motor_group * getMotors ()
     
    double measureRPM ()
     
    double getRPM ()
     
    PIDgetPID ()
     
    double getPIDValue ()
     
    double getFeedforwardValue ()
     
    double getTBHGain ()
     
    void setPIDTarget (double value)
     
    void updatePID (double value)
     
    void spin_raw (double speed, directionType dir=fwd)
     
    void spin_manual (double speed, directionType dir=fwd)
     
    void spinRPM (int rpm)
     
    void stop ()
     
    void stopMotors ()
     
    void stopNonTasks ()
     
    -

    Detailed Description

    -

    a Flywheel class that handles all control of a high inertia spinning disk It gives multiple options for what control system to use in order to control wheel velocity and functions alerting the user when the flywheel is up to speed. Flywheel is a set and forget class. Once you create it you can call spinRPM or stop on it at any time and it will take all necessary steps to accomplish this

    -

    Constructor & Destructor Documentation

    - -

    ◆ Flywheel() [1/4]

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    Flywheel::Flywheel (motor_group & motors,
    PID::pid_config_tpid_config,
    FeedForward::ff_config_tff_config,
    const double ratio 
    )
    -
    -

    Create the Flywheel object using PID + feedforward for control.

    Parameters
    - - - - - -
    motorspointer to the motors on the fly wheel
    pid_configpointer the pid config to use
    ff_configthe feedforward config to use
    ratioratio of the whatever just multiplies the velocity
    -
    -
    -

    Create the Flywheel object using PID + feedforward for control.

    - -
    -
    - -

    ◆ Flywheel() [2/4]

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - -
    Flywheel::Flywheel (motor_group & motors,
    FeedForward::ff_config_tff_config,
    const double ratio 
    )
    -
    -

    Create the Flywheel object using only feedforward for control

    Parameters
    - - - - -
    motorsthe motors on the fly wheel
    ff_configthe feedforward config to use
    ratioratio of the whatever just multiplies the velocity
    -
    -
    -

    Create the Flywheel object using only feedforward for control

    - -
    -
    - -

    ◆ Flywheel() [3/4]

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - -
    Flywheel::Flywheel (motor_group & motors,
    double tbh_gain,
    const double ratio 
    )
    -
    -

    Create the Flywheel object using Take Back Half for control

    Parameters
    - - - - -
    motorsthe motors on the fly wheel
    tbh_gainthe TBH control paramater
    ratioratio of the whatever just multiplies the velocity
    -
    -
    -

    Create the Flywheel object using Take Back Half for control

    - -
    -
    - -

    ◆ Flywheel() [4/4]

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    Flywheel::Flywheel (motor_group & motors,
    const double ratio 
    )
    -
    -

    Create the Flywheel object using Bang Bang for control

    Parameters
    - - - -
    motorsthe motors on the fly wheel
    ratioratio of the whatever just multiplies the velocity
    -
    -
    -

    Create the Flywheel object using Bang Bang for control

    - -
    -
    -

    Member Function Documentation

    - -

    ◆ getDesiredRPM()

    - -
    -
    - - - - - - - -
    double Flywheel::getDesiredRPM ()
    -
    -

    Return the RPM that the flywheel is currently trying to achieve

    Returns
    RPM the target rpm
    -

    Return the current value that the RPM should be set to

    - -
    -
    - -

    ◆ getFeedforwardValue()

    - -
    -
    - - - - - - - -
    double Flywheel::getFeedforwardValue ()
    -
    -

    returns the current OUT value of the PID - the value that the PID would set the motors to

    -

    returns the current OUT value of the Feedforward - the value that the Feedforward would set the motors to

    Returns
    the voltage that feedforward wants the motors at to achieve the target RPM
    - -
    -
    - -

    ◆ getMotors()

    - -
    -
    - - - - - - - -
    motor_group * Flywheel::getMotors ()
    -
    -

    Returns a POINTER to the motors

    -

    Returns a POINTER TO the motors; not currently used.

    Returns
    motorPointer -pointer to the motors
    - -
    -
    - -

    ◆ getPID()

    - -
    -
    - - - - - - - -
    PID * Flywheel::getPID ()
    -
    -

    Returns a POINTER to the PID.

    -

    Returns a POINTER TO the PID; not currently used.

    Returns
    pidPointer -pointer to the PID
    - -
    -
    - -

    ◆ getPIDValue()

    - -
    -
    - - - - - - - -
    double Flywheel::getPIDValue ()
    -
    -

    returns the current OUT value of the PID - the value that the PID would set the motors to

    -

    returns the current OUT value of the PID - the value that the PID would set the motors to

    Returns
    the voltage that PID wants the motors at to achieve the target RPM
    - -
    -
    - -

    ◆ getRPM()

    - -
    -
    - - - - - - - -
    double Flywheel::getRPM ()
    -
    -

    return the current smoothed velocity of the flywheel motors, in RPM

    - -
    -
    - -

    ◆ getTBHGain()

    - -
    -
    - - - - - - - -
    double Flywheel::getTBHGain ()
    -
    -

    get the gain used for TBH control

    -

    get the gain used for TBH control

    Returns
    the gain used in TBH control
    - -
    -
    - -

    ◆ isTaskRunning()

    - -
    -
    - - - - - - - -
    bool Flywheel::isTaskRunning ()
    -
    -

    Checks if the background RPM controlling task is running

    Returns
    true if the task is running
    -

    Checks if the background RPM controlling task is running

    Returns
    taskRunning - If the task is running
    - -
    -
    - -

    ◆ measureRPM()

    - -
    -
    - - - - - - - -
    double Flywheel::measureRPM ()
    -
    -

    make a measurement of the current RPM of the flywheel motor and return a smoothed version

    -

    return the current velocity of the flywheel motors, in RPM

    Returns
    the measured velocity of the flywheel
    - -
    -
    - -

    ◆ setPIDTarget()

    - -
    -
    - - - - - - - - -
    void Flywheel::setPIDTarget (double value)
    -
    -

    Sets the value of the PID target

    Parameters
    - - -
    value- desired value of the PID
    -
    -
    - -
    -
    - -

    ◆ spin_manual()

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    void Flywheel::spin_manual (double speed,
    directionType dir = fwd 
    )
    -
    -

    Spin motors using voltage; defaults forward at 12 volts FOR USE BY OPCONTROL AND AUTONOMOUS - this only applies if the RPM thread is not running

    Parameters
    - - - -
    speed- speed (between -1 and 1) to set the motor
    dir- direction that the motor moves in; defaults to forward
    -
    -
    - -
    -
    - -

    ◆ spin_raw()

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    void Flywheel::spin_raw (double speed,
    directionType dir = fwd 
    )
    -
    -

    Spin motors using voltage; defaults forward at 12 volts FOR USE BY TASKS ONLY

    Parameters
    - - - -
    speed- speed (between -1 and 1) to set the motor
    dir- direction that the motor moves in; defaults to forward
    -
    -
    - -
    -
    - -

    ◆ spinRPM()

    - -
    -
    - - - - - - - - -
    void Flywheel::spinRPM (int inputRPM)
    -
    -

    starts or sets the RPM thread at new value what control scheme is dependent on control_style

    Parameters
    - - -
    rpm- the RPM we want to spin at
    -
    -
    -

    starts or sets the RPM thread at new value what control scheme is dependent on control_style

    Parameters
    - - -
    inputRPM- set the current RPM
    -
    -
    - -
    -
    - -

    ◆ stop()

    - -
    -
    - - - - - - - -
    void Flywheel::stop ()
    -
    -

    stop the RPM thread and the wheel

    - -
    -
    - -

    ◆ stopMotors()

    - -
    -
    - - - - - - - -
    void Flywheel::stopMotors ()
    -
    -

    stop only the motors; exclusively for BANG BANG use

    - -
    -
    - -

    ◆ stopNonTasks()

    - -
    -
    - - - - - - - -
    void Flywheel::stopNonTasks ()
    -
    -

    Stop the motors if the task isn't running - stop manual control

    - -
    -
    - -

    ◆ updatePID()

    - -
    -
    - - - - - - - - -
    void Flywheel::updatePID (double value)
    -
    -

    updates the value of the PID

    Parameters
    - - -
    value- value to update the PID with
    -
    -
    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/subsystems/flywheel.h
    • -
    • src/subsystems/flywheel.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classFlywheelStopCommand-members.html b/documentation/html/classFlywheelStopCommand-members.html deleted file mode 100644 index 0fa5c63..0000000 --- a/documentation/html/classFlywheelStopCommand-members.html +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    FlywheelStopCommand Member List
    -
    -
    - -

    This is the complete list of members for FlywheelStopCommand, including all inherited members.

    - - - - - - -
    FlywheelStopCommand(Flywheel &flywheel)FlywheelStopCommand
    on_timeout()AutoCommandinlinevirtual
    run() overrideFlywheelStopCommandvirtual
    timeout_secondsAutoCommand
    withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
    - - - - diff --git a/documentation/html/classFlywheelStopCommand.html b/documentation/html/classFlywheelStopCommand.html deleted file mode 100644 index d0bb13c..0000000 --- a/documentation/html/classFlywheelStopCommand.html +++ /dev/null @@ -1,177 +0,0 @@ - - - - - - - -RIT VEXU Core API: FlywheelStopCommand Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    FlywheelStopCommand Class Reference
    -
    -
    - -

    #include <flywheel_commands.h>

    -
    -Inheritance diagram for FlywheelStopCommand:
    -
    -
    - - -AutoCommand - -
    - - - - - - - - - - - - - -

    -Public Member Functions

     FlywheelStopCommand (Flywheel &flywheel)
     
    bool run () override
     
    - Public Member Functions inherited from AutoCommand
    virtual bool run ()
     
    virtual void on_timeout ()
     
    -AutoCommandwithTimeout (double t_seconds)
     
    - - - - -

    -Additional Inherited Members

    - Public Attributes inherited from AutoCommand
    double timeout_seconds = 10.0
     
    -

    Detailed Description

    -

    AutoCommand wrapper class for the stop function in the Flywheel class

    -

    Constructor & Destructor Documentation

    - -

    ◆ FlywheelStopCommand()

    - -
    -
    - - - - - - - - -
    FlywheelStopCommand::FlywheelStopCommand (Flywheelflywheel)
    -
    -

    Construct a FlywheelStopCommand

    Parameters
    - - -
    flywheelthe flywheel system we are commanding
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ run()

    - -
    -
    - - - - - -
    - - - - - - - -
    bool FlywheelStopCommand::run ()
    -
    -overridevirtual
    -
    -

    Run stop Overrides run from AutoCommand

    Returns
    true when execution is complete, false otherwise
    - -

    Reimplemented from AutoCommand.

    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/utils/command_structure/flywheel_commands.h
    • -
    • src/utils/command_structure/flywheel_commands.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classFlywheelStopCommand.png b/documentation/html/classFlywheelStopCommand.png deleted file mode 100644 index 3c321f66210de7d5a34627551a35b1ad207189a8..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 621 zcmeAS@N?(olHy`uVBq!ia0vp^{XiVR!3-qDuU?A=QqloFA+G=b{|7Q(y!l$%e`vXd zfo6fk^fNCG95?_J51w>+1yGK&B*-tA0mugfbEer>7#J9Tc)B=-R4~4sd%Nhdf`H5H zWv8zG|9@0lvd~mmGb+_N*Z0sy!H$OoU$v8Z3Ka!BizM%~tK@>P-cOd-iaGTvm2)>= zU;m@!UgC*5{}+z)|0bV)XFO@y(qre&SBK7CDSG^}u-(qr&6m=9=gzraAm)&cFTJ&C}&X0RiIe(X6)`yEG6LO_q$$wcn`>Tc7*MFMa zQYXyzYF}EoiqYfJk$QcPOUG&vIPG(%;jvPN2K5TY15P^6K3A<(-7@3+vdvR2WZBj2 zV|bu_hn*pZSo|+~zJOB%2a9JE+xLko(m*`>(d4r4-*i1~gCFlT*gC_^({xhF#5I96 zZ_eq?FaKG>vD0mm-ltZ7sbaaG^SqmFkHx4hJ(r^^qqauGJaD&y<&*6-L6ON5_XjOr zwqakSxM}J15U;cvd;R?V^~dCVC*FCUK6z!o$S)I~$0d7@Ib?EFrrxT}*PQ?3io$cd z)Qy+^U+}iyHQVlTrtQbfvI{oHjx6W3i?2NVy!d~O+*O5@$rkZX|4E(?-&=pn)^c5V zb(-Dz=}Tt4yLYp`{ - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    FlywheelStopMotorsCommand Member List
    -
    -
    - -

    This is the complete list of members for FlywheelStopMotorsCommand, including all inherited members.

    - - - - - - -
    FlywheelStopMotorsCommand(Flywheel &flywheel)FlywheelStopMotorsCommand
    on_timeout()AutoCommandinlinevirtual
    run() overrideFlywheelStopMotorsCommandvirtual
    timeout_secondsAutoCommand
    withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
    - - - - diff --git a/documentation/html/classFlywheelStopMotorsCommand.html b/documentation/html/classFlywheelStopMotorsCommand.html deleted file mode 100644 index 3962966..0000000 --- a/documentation/html/classFlywheelStopMotorsCommand.html +++ /dev/null @@ -1,177 +0,0 @@ - - - - - - - -RIT VEXU Core API: FlywheelStopMotorsCommand Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    FlywheelStopMotorsCommand Class Reference
    -
    -
    - -

    #include <flywheel_commands.h>

    -
    -Inheritance diagram for FlywheelStopMotorsCommand:
    -
    -
    - - -AutoCommand - -
    - - - - - - - - - - - - - -

    -Public Member Functions

     FlywheelStopMotorsCommand (Flywheel &flywheel)
     
    bool run () override
     
    - Public Member Functions inherited from AutoCommand
    virtual bool run ()
     
    virtual void on_timeout ()
     
    -AutoCommandwithTimeout (double t_seconds)
     
    - - - - -

    -Additional Inherited Members

    - Public Attributes inherited from AutoCommand
    double timeout_seconds = 10.0
     
    -

    Detailed Description

    -

    AutoCommand wrapper class for the stopMotors function in the Flywheel class

    -

    Constructor & Destructor Documentation

    - -

    ◆ FlywheelStopMotorsCommand()

    - -
    -
    - - - - - - - - -
    FlywheelStopMotorsCommand::FlywheelStopMotorsCommand (Flywheelflywheel)
    -
    -

    Construct a FlywheeStopMotors Command

    Parameters
    - - -
    flywheelthe flywheel system we are commanding
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ run()

    - -
    -
    - - - - - -
    - - - - - - - -
    bool FlywheelStopMotorsCommand::run ()
    -
    -overridevirtual
    -
    -

    Run stop Overrides run from AutoCommand

    Returns
    true when execution is complete, false otherwise
    - -

    Reimplemented from AutoCommand.

    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/utils/command_structure/flywheel_commands.h
    • -
    • src/utils/command_structure/flywheel_commands.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classFlywheelStopMotorsCommand.png b/documentation/html/classFlywheelStopMotorsCommand.png deleted file mode 100644 index 1d73925219da75f2122ab845b0a56ba24386722f..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 678 zcmeAS@N?(olHy`uVBq!ia0vp^+kiNLgBeIR8`rM{QqloFA+G=b{|7Q(y!l$%e`vXd zfo6fk^fNCG95?_J51w>+1yGK&B*-tA0mugfbEer>7#NrgJzX3_Dj46+jpbWxz|*4M z9CG%r|DFpI>TfWuE|oqRx~zrexO`u7+(w<#M)NmJc#>0;Gil4D&P!_FJbS}G zk59Yu?EdNBSm^q8*LR0E8@KP@y8Ea(+fIcgzjIf;o6`CBoPf39yHgpgig)*aoaHyq zW7_@>-?nXUCtv;CcH{TK>Lyv={f)A+rswpNx9^ERtmhde@k^X5NiFAzA**9 zDm%Bx;o4hU!PD-M4J!F3?cb?nsvcMK)V4J9j5@i|^OBeLw@o^yOPCt|FBNAvv)poH z{Cdru&yU2dOn)*@x+JV!e;cn`ccC5cl+MXF-f(+da#g+6 zQ~T}#&u`nhFUzdGTT6JRi%nS4{foP-C!y={wQh#$jG~Uyc2f^ltlV%q$Ebexw%t?K zYCrE?|Kz7wnat{h%c;k;n_r&nTl6Y)b?TcW*@Iroqs{UYX5Y5Gp_%{5a#qc;bB0nI zmR{JVry)OiNxa6s%v-O2y_mNrGRf}PyGc)EcK`U*6YILVJEB%&mU5-|Zwt>Q23uZV zytnapuC3R?MCYnQmsKdDgT6)Mev!Je<8jK!AQdA@pO5GLfg z)b?-DtlC2Ujq=t1wZ0WUzu&t}?YzL>B-6 diff --git a/documentation/html/classFlywheelStopNonTasksCommand-members.html b/documentation/html/classFlywheelStopNonTasksCommand-members.html deleted file mode 100644 index 69e1e10..0000000 --- a/documentation/html/classFlywheelStopNonTasksCommand-members.html +++ /dev/null @@ -1,87 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    FlywheelStopNonTasksCommand Member List
    -
    -
    - -

    This is the complete list of members for FlywheelStopNonTasksCommand, including all inherited members.

    - - - - -
    on_timeout()AutoCommandinlinevirtual
    timeout_secondsAutoCommand
    withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
    - - - - diff --git a/documentation/html/classFlywheelStopNonTasksCommand.html b/documentation/html/classFlywheelStopNonTasksCommand.html deleted file mode 100644 index d69510f..0000000 --- a/documentation/html/classFlywheelStopNonTasksCommand.html +++ /dev/null @@ -1,115 +0,0 @@ - - - - - - - -RIT VEXU Core API: FlywheelStopNonTasksCommand Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    FlywheelStopNonTasksCommand Class Reference
    -
    -
    - -

    #include <flywheel_commands.h>

    -
    -Inheritance diagram for FlywheelStopNonTasksCommand:
    -
    -
    - - -AutoCommand - -
    - - - - - - - - - - - - -

    -Additional Inherited Members

    - Public Member Functions inherited from AutoCommand
    virtual bool run ()
     
    virtual void on_timeout ()
     
    -AutoCommandwithTimeout (double t_seconds)
     
    - Public Attributes inherited from AutoCommand
    double timeout_seconds = 10.0
     
    -

    Detailed Description

    -

    AutoCommand wrapper class for the stopNonTasks function in the Flywheel class

    -

    The documentation for this class was generated from the following files:
      -
    • include/utils/command_structure/flywheel_commands.h
    • -
    • src/utils/command_structure/flywheel_commands.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classFlywheelStopNonTasksCommand.png b/documentation/html/classFlywheelStopNonTasksCommand.png deleted file mode 100644 index 9db847fdcf55b7adcb4600473b7bff95d1a87a3a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 718 zcmeAS@N?(olHy`uVBq!ia0vp^$ACD1gBeJcR{b&rQqloFA+G=b{|7Q(y!l$%e`vXd zfo6fk^fNCG95?_J51w>+1yGK&B*-tA0mugfbEer>7#Nr$JzX3_Dj46+eYkG5ff7E>kcS*>T~f-`m)I1@X{N_ zwf2*0V)OU;ZJNq&7?fYTqxSrb?}ppzU%%b<&ywS8Q02W@Z+x?F%-`1$DD!?**zBdB zYPR3Ld!_BtXD*49SEuh~-21O|tZu^jgeU9d3_cy1J9D~W)&D$$TWb09+zzwmj5Y0bUjE|uV4$B&nJ{_;Lrdvr$iyu>@N`%i41KHcqA zR@z;a%tiJFpSY%%-g{RT|LxM7=L+wpKE3ql>Z#MxjQx><`d-GN)hWZ%tCI4qR zJg4vFu}Y2^nH5bFmn&GX+TFX=DoD7@9H-SauE#?^V!x}~6S0SAz%^3o}K>+8S1Ud*@U T=LZg8%46_!^>bP0l+XkKIon$W diff --git a/documentation/html/classGenericAuto-members.html b/documentation/html/classGenericAuto-members.html deleted file mode 100644 index 685b6a4..0000000 --- a/documentation/html/classGenericAuto-members.html +++ /dev/null @@ -1,88 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    GenericAuto Member List
    -
    -
    - -

    This is the complete list of members for GenericAuto, including all inherited members.

    - - - - - -
    add(state_ptr new_state)GenericAuto
    add_async(state_ptr async_state)GenericAuto
    add_delay(int ms)GenericAuto
    run(bool blocking)GenericAuto
    - - - - diff --git a/documentation/html/classGenericAuto.html b/documentation/html/classGenericAuto.html deleted file mode 100644 index c843843..0000000 --- a/documentation/html/classGenericAuto.html +++ /dev/null @@ -1,204 +0,0 @@ - - - - - - - -RIT VEXU Core API: GenericAuto Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    GenericAuto Class Reference
    -
    -
    - -

    #include <generic_auto.h>

    - - - - - - - - - - -

    -Public Member Functions

    bool run (bool blocking)
     
    void add (state_ptr new_state)
     
    void add_async (state_ptr async_state)
     
    void add_delay (int ms)
     
    -

    Detailed Description

    -

    GenericAuto provides a pleasant interface for organizing an auto path steps of the path can be added with add() and when ready, calling run() will begin executing the path

    -

    Member Function Documentation

    - -

    ◆ add()

    - -
    -
    - - - - - - - - -
    void GenericAuto::add (state_ptr new_state)
    -
    -

    Add a new state to the autonomous via function point of type "bool (ptr*)()"

    Parameters
    - - -
    new_statethe function to run
    -
    -
    - -
    -
    - -

    ◆ add_async()

    - -
    -
    - - - - - - - - -
    void GenericAuto::add_async (state_ptr async_state)
    -
    -

    Add a new state to the autonomous via function point of type "bool (ptr*)()" that will run asynchronously

    Parameters
    - - -
    async_statethe function to run
    -
    -
    - -
    -
    - -

    ◆ add_delay()

    - -
    -
    - - - - - - - - -
    void GenericAuto::add_delay (int ms)
    -
    -

    add_delay adds a period where the auto system will simply wait for the specified time

    Parameters
    - - -
    mshow long to wait in milliseconds
    -
    -
    - -
    -
    - -

    ◆ run()

    - -
    -
    - - - - - - - - -
    bool GenericAuto::run (bool blocking)
    -
    -

    The method that runs the autonomous. If 'blocking' is true, then this method will run through every state until it finished.

    -

    If blocking is false, then assuming every state is also non-blocking, the method will run through the current state in the list and return immediately.

    -
    Parameters
    - - -
    blockingWhether or not to block the thread until all states have run
    -
    -
    -
    Returns
    true after all states have finished.
    - -
    -
    -
    The documentation for this class was generated from the following files: -
    - - - - diff --git a/documentation/html/classGraphDrawer-members.html b/documentation/html/classGraphDrawer-members.html deleted file mode 100644 index 1afa5d4..0000000 --- a/documentation/html/classGraphDrawer-members.html +++ /dev/null @@ -1,87 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    GraphDrawer Member List
    -
    -
    - -

    This is the complete list of members for GraphDrawer, including all inherited members.

    - - - - -
    add_sample(Vector2D::point_t sample)GraphDrawerinline
    draw(int x, int y, int width, int height)GraphDrawerinline
    GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound)GraphDrawerinline
    - - - - diff --git a/documentation/html/classGraphDrawer.html b/documentation/html/classGraphDrawer.html deleted file mode 100644 index 20307e4..0000000 --- a/documentation/html/classGraphDrawer.html +++ /dev/null @@ -1,277 +0,0 @@ - - - - - - - -RIT VEXU Core API: GraphDrawer Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    GraphDrawer Class Reference
    -
    -
    - - - - - - - - - -

    -Public Member Functions

     GraphDrawer (vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound)
     a helper class to graph values on the brain screen
     
    void add_sample (Vector2D::point_t sample)
     
    void draw (int x, int y, int width, int height)
     
    -

    Constructor & Destructor Documentation

    - -

    ◆ GraphDrawer()

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    GraphDrawer::GraphDrawer (vex::brain::lcd & screen,
    int num_samples,
    std::string x_label,
    std::string y_label,
    vex::color col,
    bool draw_border,
    double lower_bound,
    double upper_bound 
    )
    -
    -inline
    -
    - -

    a helper class to graph values on the brain screen

    -

    Construct a GraphDrawer

    Parameters
    - - - - - - - - -
    screena reference to Brain.screen we can save for later
    num_samplesthe graph works on a fixed window and will plot the last num_samples before the history is forgotten. Larger values give more context but may slow down if you have many graphs or an exceptionally high
    x_labelthe name of the x axis (currently unused)
    y_labelthe name of the y axis (currently unused)
    draw_borderwhether to draw the border around the graph. can be turned off if there are multiple graphs in the same space ie. a graph of error and output
    lower_boundthe bottom of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints
    -
    upper_boundthe top of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints
    -
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ add_sample()

    - -
    -
    - - - - - -
    - - - - - - - - -
    void GraphDrawer::add_sample (Vector2D::point_t sample)
    -
    -inline
    -
    -

    add_sample adds a point to the graph, removing one from the back

    Parameters
    - - -
    samplean x, y coordinate of the next point to graph
    -
    -
    - -
    -
    - -

    ◆ draw()

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    void GraphDrawer::draw (int x,
    int y,
    int width,
    int height 
    )
    -
    -inline
    -
    -

    draws the graph to the screen in the constructor

    Parameters
    - - - - - -
    xx position of the top left of the graphed region
    yy position of the top left of the graphed region
    widththe width of the graphed region
    heightthe height of the graphed region
    -
    -
    - -
    -
    -
    The documentation for this class was generated from the following file: -
    - - - - diff --git a/documentation/html/classLift-members.html b/documentation/html/classLift-members.html deleted file mode 100644 index dbb6aea..0000000 --- a/documentation/html/classLift-members.html +++ /dev/null @@ -1,97 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    Lift< T > Member List
    -
    -
    - -

    This is the complete list of members for Lift< T >, including all inherited members.

    - - - - - - - - - - - - - - -
    control_continuous(bool up_ctrl, bool down_ctrl)Lift< T >inline
    control_manual(bool up_btn, bool down_btn, int volt_up, int volt_down)Lift< T >inline
    control_setpoints(bool up_step, bool down_step, vector< T > pos_list)Lift< T >inline
    get_async()Lift< T >inline
    get_setpoint()Lift< T >inline
    hold()Lift< T >inline
    home()Lift< T >inline
    Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map< T, double > &setpoint_map, limit *homing_switch=NULL)Lift< T >inline
    set_async(bool val)Lift< T >inline
    set_position(T pos)Lift< T >inline
    set_sensor_function(double(*fn_ptr)(void))Lift< T >inline
    set_sensor_reset(void(*fn_ptr)(void))Lift< T >inline
    set_setpoint(double val)Lift< T >inline
    - - - - diff --git a/documentation/html/classLift.html b/documentation/html/classLift.html deleted file mode 100644 index 747497d..0000000 --- a/documentation/html/classLift.html +++ /dev/null @@ -1,630 +0,0 @@ - - - - - - - -RIT VEXU Core API: Lift< T > Class Template Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    Lift< T > Class Template Reference
    -
    -
    - -

    #include <lift.h>

    - - - - -

    -Classes

    struct  lift_cfg_t
     
    - - - - - - - - - - - - - - - - - - - - - - - - - - - -

    -Public Member Functions

     Lift (motor_group &lift_motors, lift_cfg_t &lift_cfg, map< T, double > &setpoint_map, limit *homing_switch=NULL)
     
    void control_continuous (bool up_ctrl, bool down_ctrl)
     
    void control_manual (bool up_btn, bool down_btn, int volt_up, int volt_down)
     
    void control_setpoints (bool up_step, bool down_step, vector< T > pos_list)
     
    bool set_position (T pos)
     
    bool set_setpoint (double val)
     
    double get_setpoint ()
     
    void hold ()
     
    void home ()
     
    bool get_async ()
     
    void set_async (bool val)
     
    void set_sensor_function (double(*fn_ptr)(void))
     
    void set_sensor_reset (void(*fn_ptr)(void))
     
    -

    Detailed Description

    -
    template<typename T>
    -class Lift< T >

    LIFT A general class for lifts (e.g. 4bar, dr4bar, linear, etc) Uses a PID to hold the lift at a certain height under load, and to move the lift to different heights

    -
    Author
    Ryan McGee
    -

    Constructor & Destructor Documentation

    - -

    ◆ Lift()

    - -
    -
    -
    -template<typename T >
    - - - - - -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    Lift< T >::Lift (motor_group & lift_motors,
    lift_cfg_tlift_cfg,
    map< T, double > & setpoint_map,
    limit * homing_switch = NULL 
    )
    -
    -inline
    -
    -

    Construct the Lift object and begin the background task that controls the lift.

    -

    Usage example: /code{.cpp} enum Positions {UP, MID, DOWN}; map<Positions, double> setpt_map { {DOWN, 0.0}, {MID, 0.5}, {UP, 1.0} }; Lift<Positions> my_lift(motors, lift_cfg, setpt_map); /endcode

    -
    Parameters
    - - - - -
    lift_motorsA set of motors, all set that positive rotation correlates with the lift going up
    lift_cfgLift characterization information; PID tunings and movement speeds
    setpoint_mapA map of enum type T, in which each enum entry corresponds to a different lift height
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ control_continuous()

    - -
    -
    -
    -template<typename T >
    - - - - - -
    - - - - - - - - - - - - - - - - - - -
    void Lift< T >::control_continuous (bool up_ctrl,
    bool down_ctrl 
    )
    -
    -inline
    -
    -

    Control the lift with an "up" button and a "down" button. Use PID to hold the lift when letting go.

    Parameters
    - - - -
    up_ctrlButton controlling the "UP" motion
    down_ctrlButton controlling the "DOWN" motion
    -
    -
    - -
    -
    - -

    ◆ control_manual()

    - -
    -
    -
    -template<typename T >
    - - - - - -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    void Lift< T >::control_manual (bool up_btn,
    bool down_btn,
    int volt_up,
    int volt_down 
    )
    -
    -inline
    -
    -

    Control the lift with manual controls (no holding voltage)

    -
    Parameters
    - - - - - -
    up_btnRaise the lift when true
    down_btnLower the lift when true
    volt_upMotor voltage when raising the lift
    volt_downMotor voltage when lowering the lift
    -
    -
    - -
    -
    - -

    ◆ control_setpoints()

    - -
    -
    -
    -template<typename T >
    - - - - - -
    - - - - - - - - - - - - - - - - - - - - - - - - -
    void Lift< T >::control_setpoints (bool up_step,
    bool down_step,
    vector< T > pos_list 
    )
    -
    -inline
    -
    -

    Control the lift in "steps". When the "up" button is pressed, the lift will go to the next position as defined by pos_list. Order matters!

    -
    Parameters
    - - - - -
    up_stepA button that increments the position of the lift.
    down_stepA button that decrements the position of the lift.
    pos_listA list of positions for the lift to go through. The higher the index, the higher the lift should be (generally).
    -
    -
    - -
    -
    - -

    ◆ get_async()

    - -
    -
    -
    -template<typename T >
    - - - - - -
    - - - - - - - -
    bool Lift< T >::get_async ()
    -
    -inline
    -
    -
    Returns
    whether or not the background thread is running the lift
    - -
    -
    - -

    ◆ get_setpoint()

    - -
    -
    -
    -template<typename T >
    - - - - - -
    - - - - - - - -
    double Lift< T >::get_setpoint ()
    -
    -inline
    -
    -
    Returns
    The current setpoint for the lift
    - -
    -
    - -

    ◆ hold()

    - -
    -
    -
    -template<typename T >
    - - - - - -
    - - - - - - - -
    void Lift< T >::hold ()
    -
    -inline
    -
    -

    Target the class's setpoint. Calculate the PID output and set the lift motors accordingly.

    - -
    -
    - -

    ◆ home()

    - -
    -
    -
    -template<typename T >
    - - - - - -
    - - - - - - - -
    void Lift< T >::home ()
    -
    -inline
    -
    -

    A blocking function that automatically homes the lift based on a sensor or hard stop, and sets the position to 0. A watchdog times out after 3 seconds, to avoid damage.

    - -
    -
    - -

    ◆ set_async()

    - -
    -
    -
    -template<typename T >
    - - - - - -
    - - - - - - - - -
    void Lift< T >::set_async (bool val)
    -
    -inline
    -
    -

    Enables or disables the background task. Note that running the control functions, or set_position functions will immediately re-enable the task for autonomous use.

    Parameters
    - - -
    Whetheror not the background thread should run the lift
    -
    -
    - -
    -
    - -

    ◆ set_position()

    - -
    -
    -
    -template<typename T >
    - - - - - -
    - - - - - - - - -
    bool Lift< T >::set_position (pos)
    -
    -inline
    -
    -

    Enable the background task, and send the lift to a position, specified by the setpoint map from the constructor.

    -
    Parameters
    - - -
    posA lift position enum type
    -
    -
    -
    Returns
    True if the pid has reached the setpoint
    - -
    -
    - -

    ◆ set_sensor_function()

    - -
    -
    -
    -template<typename T >
    - - - - - -
    - - - - - - - - -
    void Lift< T >::set_sensor_function (double(*)(void) fn_ptr)
    -
    -inline
    -
    -

    Creates a custom hook for any other type of sensor to be used on the lift. Example: /code{.cpp} my_lift.set_sensor_function( [](){return my_sensor.position();} ); /endcode

    -
    Parameters
    - - -
    fn_ptrPointer to custom sensor function
    -
    -
    - -
    -
    - -

    ◆ set_sensor_reset()

    - -
    -
    -
    -template<typename T >
    - - - - - -
    - - - - - - - - -
    void Lift< T >::set_sensor_reset (void(*)(void) fn_ptr)
    -
    -inline
    -
    -

    Creates a custom hook to reset the sensor used in set_sensor_function(). Example: /code{.cpp} my_lift.set_sensor_reset( my_sensor.resetPosition ); /endcode

    - -
    -
    - -

    ◆ set_setpoint()

    - -
    -
    -
    -template<typename T >
    - - - - - -
    - - - - - - - - -
    bool Lift< T >::set_setpoint (double val)
    -
    -inline
    -
    -

    Manually set a setpoint value for the lift PID to go to.

    Parameters
    - - -
    valLift setpoint, in motor revolutions or sensor units defined by get_sensor. Cannot be outside the softstops.
    -
    -
    -
    Returns
    True if the pid has reached the setpoint
    - -
    -
    -
    The documentation for this class was generated from the following file: -
    - - - - diff --git a/documentation/html/classMecanumDrive-members.html b/documentation/html/classMecanumDrive-members.html deleted file mode 100644 index cabe2a6..0000000 --- a/documentation/html/classMecanumDrive-members.html +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    MecanumDrive Member List
    -
    -
    - -

    This is the complete list of members for MecanumDrive, including all inherited members.

    - - - - - - -
    auto_drive(double inches, double direction, double speed, bool gyro_correction=true)MecanumDrive
    auto_turn(double degrees, double speed, bool ignore_imu=false)MecanumDrive
    drive(double left_y, double left_x, double right_x, int power=2)MecanumDrive
    drive_raw(double direction_deg, double magnitude, double rotation)MecanumDrive
    MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear, vex::rotation *lateral_wheel=NULL, vex::inertial *imu=NULL, mecanumdrive_config_t *config=NULL)MecanumDrive
    - - - - diff --git a/documentation/html/classMecanumDrive.html b/documentation/html/classMecanumDrive.html deleted file mode 100644 index a6cfd10..0000000 --- a/documentation/html/classMecanumDrive.html +++ /dev/null @@ -1,389 +0,0 @@ - - - - - - - -RIT VEXU Core API: MecanumDrive Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    MecanumDrive Class Reference
    -
    -
    - -

    #include <mecanum_drive.h>

    - - - - -

    -Classes

    struct  mecanumdrive_config_t
     
    - - - - - - - - - - - -

    -Public Member Functions

     MecanumDrive (vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear, vex::rotation *lateral_wheel=NULL, vex::inertial *imu=NULL, mecanumdrive_config_t *config=NULL)
     
    void drive_raw (double direction_deg, double magnitude, double rotation)
     
    void drive (double left_y, double left_x, double right_x, int power=2)
     
    bool auto_drive (double inches, double direction, double speed, bool gyro_correction=true)
     
    bool auto_turn (double degrees, double speed, bool ignore_imu=false)
     
    -

    Detailed Description

    -

    A class representing the Mecanum drivetrain. Contains 4 motors, a possible IMU (intertial), and a possible undriven perpendicular wheel.

    -

    Constructor & Destructor Documentation

    - -

    ◆ MecanumDrive()

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    MecanumDrive::MecanumDrive (vex::motor & left_front,
    vex::motor & right_front,
    vex::motor & left_rear,
    vex::motor & right_rear,
    vex::rotation * lateral_wheel = NULL,
    vex::inertial * imu = NULL,
    mecanumdrive_config_tconfig = NULL 
    )
    -
    -

    Create the Mecanum drivetrain object

    - -
    -
    -

    Member Function Documentation

    - -

    ◆ auto_drive()

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    bool MecanumDrive::auto_drive (double inches,
    double direction,
    double speed,
    bool gyro_correction = true 
    )
    -
    -

    Drive the robot in a straight line automatically. If the inertial was declared in the constructor, use it to correct while driving. If the lateral wheel was declared in the constructor, use it for more accurate positioning while strafing.

    -
    Parameters
    - - - - - -
    inchesHow far the robot should drive, in inches
    directionWhat direction the robot should travel in, in degrees. 0 is forward, +/-180 is reverse, clockwise is positive.
    speedThe maximum speed the robot should travel, in percent: -1.0->+1.0
    gyro_correction=true Whether or not to use the gyro to help correct while driving. Will always be false if no gyro was declared in the constructor.
    -
    -
    -

    Drive the robot in a straight line automatically. If the inertial was declared in the constructor, use it to correct while driving. If the lateral wheel was declared in the constructor, use it for more accurate positioning while strafing.

    -
    Parameters
    - - - - - -
    inchesHow far the robot should drive, in inches
    directionWhat direction the robot should travel in, in degrees. 0 is forward, +/-180 is reverse, clockwise is positive.
    speedThe maximum speed the robot should travel, in percent: -1.0->+1.0
    gyro_correction= true Whether or not to use the gyro to help correct while driving. Will always be false if no gyro was declared in the constructor.
    -
    -
    -
    Returns
    Whether or not the maneuver is complete.
    - -
    -
    - -

    ◆ auto_turn()

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - -
    bool MecanumDrive::auto_turn (double degrees,
    double speed,
    bool ignore_imu = false 
    )
    -
    -

    Autonomously turn the robot X degrees over it's center point. Uses a closed loop for control.

    Parameters
    - - - - -
    degreesHow many degrees to rotate the robot. Clockwise postive.
    speedWhat percentage to run the motors at: 0.0 -> 1.0
    ignore_imu=false Whether or not to use the Inertial for determining angle. Will instead use circumference formula + robot's wheelbase + encoders to determine.
    -
    -
    -
    Returns
    whether or not the robot has finished the maneuver
    -

    Autonomously turn the robot X degrees over it's center point. Uses a closed loop for control.

    Parameters
    - - - - -
    degreesHow many degrees to rotate the robot. Clockwise postive.
    speedWhat percentage to run the motors at: 0.0 -> 1.0
    ignore_imu= false Whether or not to use the Inertial for determining angle. Will instead use circumference formula + robot's wheelbase + encoders to determine.
    -
    -
    -
    Returns
    whether or not the robot has finished the maneuver
    - -
    -
    - -

    ◆ drive()

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    void MecanumDrive::drive (double left_y,
    double left_x,
    double right_x,
    int power = 2 
    )
    -
    -

    Drive the robot with a mecanum-style / arcade drive. Inputs are in percent (-100.0 -> 100.0) straight from the controller. Controls are mixed, so the robot can drive forward / strafe / rotate all at the same time.

    -
    Parameters
    - - - - - -
    left_yleft joystick, Y axis (forward / backwards)
    left_xleft joystick, X axis (strafe left / right)
    right_xright joystick, X axis (rotation left / right)
    power=2 how much of a "curve" there should be on drive controls; better for low speed maneuvers. Leave blank for a default curve of 2 (higher means more fidelity)
    -
    -
    -

    Drive the robot with a mecanum-style / arcade drive. Inputs are in percent (-100.0 -> 100.0) straight from the controller. Controls are mixed, so the robot can drive forward / strafe / rotate all at the same time.

    -
    Parameters
    - - - - - -
    left_yleft joystick, Y axis (forward / backwards)
    left_xleft joystick, X axis (strafe left / right)
    right_xright joystick, X axis (rotation left / right)
    power= 2 how much of a "curve" there should be on drive controls; better for low speed maneuvers. Leave blank for a default curve of 2 (higher means more fidelity)
    -
    -
    - -
    -
    - -

    ◆ drive_raw()

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - -
    void MecanumDrive::drive_raw (double direction_deg,
    double magnitude,
    double rotation 
    )
    -
    -

    Drive the robot using vectors. This handles all the math required for mecanum control.

    -
    Parameters
    - - - - -
    direction_degthe direction to drive the robot, in degrees. 0 is forward, 180 is back, clockwise is positive, counterclockwise is negative.
    magnitudeHow fast the robot should drive, in percent: 0.0->1.0
    rotationHow fast the robot should rotate, in percent: -1.0->+1.0
    -
    -
    - -
    -
    -
    The documentation for this class was generated from the following files: -
    - - - - diff --git a/documentation/html/classMotionController-members.html b/documentation/html/classMotionController-members.html deleted file mode 100644 index 8d8a6a6..0000000 --- a/documentation/html/classMotionController-members.html +++ /dev/null @@ -1,97 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    MotionController Member List
    -
    -
    - -

    This is the complete list of members for MotionController, including all inherited members.

    - - - - - - - - - - - - - - -
    FeedbackType enum name (defined in Feedback)Feedback
    FeedforwardType enum value (defined in Feedback)Feedback
    get() overrideMotionControllervirtual
    get_motion()MotionController
    get_type() (defined in Feedback)Feedbackinlinevirtual
    init(double start_pt, double end_pt) overrideMotionControllervirtual
    is_on_target() overrideMotionControllervirtual
    MotionController(m_profile_cfg_t &config)MotionController
    OtherType enum value (defined in Feedback)Feedback
    PIDType enum value (defined in Feedback)Feedback
    set_limits(double lower, double upper) overrideMotionControllervirtual
    tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct=0.6, double duration=2)MotionControllerstatic
    update(double sensor_val) overrideMotionControllervirtual
    - - - - diff --git a/documentation/html/classMotionController.html b/documentation/html/classMotionController.html deleted file mode 100644 index 9ceaa44..0000000 --- a/documentation/html/classMotionController.html +++ /dev/null @@ -1,477 +0,0 @@ - - - - - - - -RIT VEXU Core API: MotionController Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    MotionController Class Reference
    -
    -
    - -

    #include <motion_controller.h>

    -
    -Inheritance diagram for MotionController:
    -
    -
    - - -Feedback - -
    - - - - -

    -Classes

    struct  m_profile_cfg_t
     
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

    -Public Member Functions

     MotionController (m_profile_cfg_t &config)
     Construct a new Motion Controller object.
     
    void init (double start_pt, double end_pt) override
     Initialize the motion profile for a new movement This will also reset the PID and profile timers.
     
    double update (double sensor_val) override
     Update the motion profile with a new sensor value.
     
    double get () override
     
    void set_limits (double lower, double upper) override
     
    bool is_on_target () override
     
    motion_t get_motion ()
     
    - Public Member Functions inherited from Feedback
    virtual void init (double start_pt, double set_pt)=0
     
    virtual double update (double val)=0
     
    virtual double get ()=0
     
    virtual void set_limits (double lower, double upper)=0
     
    virtual bool is_on_target ()=0
     
    -virtual Feedback::FeedbackType get_type ()
     
    - - - -

    -Static Public Member Functions

    static FeedForward::ff_config_t tune_feedforward (TankDrive &drive, OdometryTank &odometry, double pct=0.6, double duration=2)
     
    - - - - -

    -Additional Inherited Members

    - Public Types inherited from Feedback
    enum  FeedbackType { PIDType -, FeedforwardType -, OtherType - }
     
    -

    Detailed Description

    -

    Motion Controller class

    -

    This class defines a top-level motion profile, which can act as an intermediate between a subsystem class and the motors themselves

    -

    This takes the constants kS, kV, kA, kP, kI, kD, max_v and acceleration and wraps around a feedforward, PID and trapezoid profile. It does so with the following formula:

    -

    out = feedfoward.calculate(motion_profile.get(time_s)) + pid.get(motion_profile.get(time_s))

    -

    For PID and Feedforward specific formulae, see pid.h, feedforward.h, and trapezoid_profile.h

    -
    Author
    Ryan McGee
    -
    Date
    7/13/2022
    -

    Constructor & Destructor Documentation

    - -

    ◆ MotionController()

    - -
    -
    - - - - - - - - -
    MotionController::MotionController (m_profile_cfg_tconfig)
    -
    - -

    Construct a new Motion Controller object.

    -
    Parameters
    - - -
    configThe definition of how the robot is able to move max_v Maximum velocity the movement is capable of accel Acceleration / deceleration of the movement pid_cfg Definitions of kP, kI, and kD ff_cfg Definitions of kS, kV, and kA
    -
    -
    -
    Parameters
    - - -
    configThe definition of how the robot is able to move max_v Maximum velocity the movement is capable of accel Acceleration / deceleration of the movement pid_cfg Definitions of kP, kI, and kD ff_cfg Definitions of kS, kV, and kA
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ get()

    - -
    -
    - - - - - -
    - - - - - - - -
    double MotionController::get ()
    -
    -overridevirtual
    -
    -
    Returns
    the last saved result from the feedback controller
    - -

    Implements Feedback.

    - -
    -
    - -

    ◆ get_motion()

    - -
    -
    - - - - - - - -
    motion_t MotionController::get_motion ()
    -
    -
    Returns
    The current postion, velocity and acceleration setpoints
    - -
    -
    - -

    ◆ init()

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - -
    void MotionController::init (double start_pt,
    double end_pt 
    )
    -
    -overridevirtual
    -
    - -

    Initialize the motion profile for a new movement This will also reset the PID and profile timers.

    -
    Parameters
    - - - -
    start_ptMovement starting position
    end_ptMovement ending posiiton
    -
    -
    - -

    Implements Feedback.

    - -
    -
    - -

    ◆ is_on_target()

    - -
    -
    - - - - - -
    - - - - - - - -
    bool MotionController::is_on_target ()
    -
    -overridevirtual
    -
    -
    Returns
    Whether or not the movement has finished, and the PID confirms it is on target
    - -

    Implements Feedback.

    - -
    -
    - -

    ◆ set_limits()

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - -
    void MotionController::set_limits (double lower,
    double upper 
    )
    -
    -overridevirtual
    -
    -

    Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. if limits are applied, the controller will not target any value below lower or above upper

    -
    Parameters
    - - - -
    lowerupper limit
    upperlower limiet
    -
    -
    -

    Clamp the upper and lower limits of the output. If both are 0, no limits should be applied.

    -
    Parameters
    - - - -
    lowerUpper limit
    upperLower limit
    -
    -
    - -

    Implements Feedback.

    - -
    -
    - -

    ◆ tune_feedforward()

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    FeedForward::ff_config_t MotionController::tune_feedforward (TankDrivedrive,
    OdometryTankodometry,
    double pct = 0.6,
    double duration = 2 
    )
    -
    -static
    -
    -

    This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. It does this by first calculating the kS (voltage to overcome static friction) by slowly increasing the voltage until it moves.

    -

    Next is kV (voltage to sustain a certain velocity), where the robot will record it's steady-state velocity at 'pct' speed.

    -

    Finally, kA (voltage needed to accelerate by a certain rate), where the robot will record the entire movement's velocity and acceleration, record a plot of [X=(pct-kV*V-kS), Y=(Acceleration)] along the movement, and since kA*Accel = pct-kV*V-kS, the reciprocal of the linear regression is the kA value.

    -
    Parameters
    - - - - - -
    driveThe tankdrive to operate on
    odometryThe robot's odometry subsystem
    pctMaximum velocity in percent (0->1.0)
    durationAmount of time the robot should be moving for the test
    -
    -
    -
    Returns
    A tuned feedforward object
    - -
    -
    - -

    ◆ update()

    - -
    -
    - - - - - -
    - - - - - - - - -
    double MotionController::update (double sensor_val)
    -
    -overridevirtual
    -
    - -

    Update the motion profile with a new sensor value.

    -
    Parameters
    - - -
    sensor_valValue from the sensor
    -
    -
    -
    Returns
    the motor input generated from the motion profile
    -
    Parameters
    - - -
    sensor_valValue from the sensor
    -
    -
    -
    Returns
    the motor input generated from the motion profile
    - -

    Implements Feedback.

    - -
    -
    -
    The documentation for this class was generated from the following files: -
    - - - - diff --git a/documentation/html/classMotionController.png b/documentation/html/classMotionController.png deleted file mode 100644 index 3063bd77d06358dd6d7a19e19db2307972f03c03..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 474 zcmeAS@N?(olHy`uVBq!ia0vp^SwI}X!3-pi$qD2EDd_;85ZC|z{{xvX-h3_XKeXJ! zK(jz%`k5C84jcfA2T!`Z0w~8>666=m0OW&#In(Sb3=E8^o-U3d6^w7^zRf$Vz~ibf zuKDS={YN1?A*PhrN9Sg1h1;5%HXd%DdcVWaOxoZB~A5vd#Xa(-TPK?^{yvk>!y834mI}VyS=4z%1@kz&iX3wC;)gD0ykFQGVxyZt><2)0C*^QOc zj-E+f9_1UR=X|w2Y{6;HtqPV{CSV} z+%SxtCG_OSJK60acX#%@Z1XeK?0!`_eO1VW)>W%#25;nl{Cx7+@PgM2v%7V!-waE* zdSzGE<*h1uS{Lp&Dk){fs46XbkQ}Pml5j|TB~N&F^`dVzz*u1LboFyt=akR{0DXGg AH~;_u diff --git a/documentation/html/classMovingAverage-members.html b/documentation/html/classMovingAverage-members.html deleted file mode 100644 index f3476cc..0000000 --- a/documentation/html/classMovingAverage-members.html +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    MovingAverage Member List
    -
    -
    - -

    This is the complete list of members for MovingAverage, including all inherited members.

    - - - - - - -
    add_entry(double n)MovingAverage
    get_average()MovingAverage
    get_size()MovingAverage
    MovingAverage(int buffer_size)MovingAverage
    MovingAverage(int buffer_size, double starting_value)MovingAverage
    - - - - diff --git a/documentation/html/classMovingAverage.html b/documentation/html/classMovingAverage.html deleted file mode 100644 index 2d74470..0000000 --- a/documentation/html/classMovingAverage.html +++ /dev/null @@ -1,233 +0,0 @@ - - - - - - - -RIT VEXU Core API: MovingAverage Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    MovingAverage Class Reference
    -
    -
    - -

    #include <moving_average.h>

    - - - - - - - - - - - - -

    -Public Member Functions

     MovingAverage (int buffer_size)
     
     MovingAverage (int buffer_size, double starting_value)
     
    void add_entry (double n)
     
    double get_average ()
     
    int get_size ()
     
    -

    Detailed Description

    -

    MovingAverage

    -

    A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. This means that if you collect enough samples those that are too high are cancelled out by the samples that are too low leaving the real value.

    -

    The MovingAverage class provides a simple interface to do this smoothing from our noisy sensor values.

    -

    WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' behind the actual value that the sensor is reading. Using a MovingAverage is thus a tradeoff between accuracy and lag time (more samples) vs. less accuracy and faster updating (less samples).
    -

    -

    Constructor & Destructor Documentation

    - -

    ◆ MovingAverage() [1/2]

    - -
    -
    - - - - - - - - -
    MovingAverage::MovingAverage (int buffer_size)
    -
    -

    Create a moving average calculator with 0 as the default value

    -
    Parameters
    - - -
    buffer_sizeThe size of the buffer. The number of samples that constitute a valid reading
    -
    -
    - -
    -
    - -

    ◆ MovingAverage() [2/2]

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    MovingAverage::MovingAverage (int buffer_size,
    double starting_value 
    )
    -
    -

    Create a moving average calculator with a specified default value

    Parameters
    - - - -
    buffer_sizeThe size of the buffer. The number of samples that constitute a valid reading
    starting_valueThe value that the average will be before any data is added
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ add_entry()

    - -
    -
    - - - - - - - - -
    void MovingAverage::add_entry (double n)
    -
    -

    Add a reading to the buffer Before: [ 1 1 2 2 3 3] => 2 ^ After: [ 2 1 2 2 3 3] => 2.16 ^

    Parameters
    - - -
    nthe sample that will be added to the moving average.
    -
    -
    - -
    -
    - -

    ◆ get_average()

    - -
    -
    - - - - - - - -
    double MovingAverage::get_average ()
    -
    -

    Returns the average based off of all the samples collected so far

    Returns
    the calculated average. sum(samples)/numsamples
    -

    How many samples the average is made from

    Returns
    the number of samples used to calculate this average
    - -
    -
    - -

    ◆ get_size()

    - -
    -
    - - - - - - - -
    int MovingAverage::get_size ()
    -
    -

    How many samples the average is made from

    Returns
    the number of samples used to calculate this average
    - -
    -
    -
    The documentation for this class was generated from the following files: -
    - - - - diff --git a/documentation/html/classOdomSetPosition-members.html b/documentation/html/classOdomSetPosition-members.html deleted file mode 100644 index 1da2f8e..0000000 --- a/documentation/html/classOdomSetPosition-members.html +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    OdomSetPosition Member List
    -
    -
    - -

    This is the complete list of members for OdomSetPosition, including all inherited members.

    - - - - - - -
    OdomSetPosition(OdometryBase &odom, const position_t &newpos=OdometryBase::zero_pos)OdomSetPosition
    on_timeout()AutoCommandinlinevirtual
    run() overrideOdomSetPositionvirtual
    timeout_secondsAutoCommand
    withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
    - - - - diff --git a/documentation/html/classOdomSetPosition.html b/documentation/html/classOdomSetPosition.html deleted file mode 100644 index 1c0897d..0000000 --- a/documentation/html/classOdomSetPosition.html +++ /dev/null @@ -1,195 +0,0 @@ - - - - - - - -RIT VEXU Core API: OdomSetPosition Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    OdomSetPosition Class Reference
    -
    -
    - -

    #include <drive_commands.h>

    -
    -Inheritance diagram for OdomSetPosition:
    -
    -
    - - -AutoCommand - -
    - - - - - - - - - - - - - -

    -Public Member Functions

     OdomSetPosition (OdometryBase &odom, const position_t &newpos=OdometryBase::zero_pos)
     
    bool run () override
     
    - Public Member Functions inherited from AutoCommand
    virtual bool run ()
     
    virtual void on_timeout ()
     
    -AutoCommandwithTimeout (double t_seconds)
     
    - - - - -

    -Additional Inherited Members

    - Public Attributes inherited from AutoCommand
    double timeout_seconds = 10.0
     
    -

    Detailed Description

    -

    AutoCommand wrapper class for the set_position function in the Odometry class

    -

    Constructor & Destructor Documentation

    - -

    ◆ OdomSetPosition()

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    OdomSetPosition::OdomSetPosition (OdometryBaseodom,
    const position_tnewpos = OdometryBase::zero_pos 
    )
    -
    -

    constructs a new OdomSetPosition command

    Parameters
    - - - -
    odomthe odometry system we are setting
    newposthe position we are telling the odometry to take. defaults to (0, 0), angle = 90
    -
    -
    -

    Construct an Odometry set pos

    Parameters
    - - - -
    odomthe odometry system we are setting
    newposthe now position to set the odometry to
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ run()

    - -
    -
    - - - - - -
    - - - - - - - -
    bool OdomSetPosition::run ()
    -
    -overridevirtual
    -
    -

    Run set_position Overrides run from AutoCommand

    Returns
    true when execution is complete, false otherwise
    - -

    Reimplemented from AutoCommand.

    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/utils/command_structure/drive_commands.h
    • -
    • src/utils/command_structure/drive_commands.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classOdomSetPosition.png b/documentation/html/classOdomSetPosition.png deleted file mode 100644 index 7d9b7504e42e4fe77173907be2d266d77bafb305..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 525 zcmeAS@N?(olHy`uVBq!ia0vp^*+3k?!3-od?^Fi>Dd_;85ZC|z{{xvX-h3_XKeXJ! zK(jz%`k5C84jcfA2T!`Z0w~8>666=m0OW&#In(Sb3=E7jJY5_^Dj46+jqN+Ez|(Tv zZPl}X>i1e$axymgPScyJ6+Vx_@Z0hJ%jrv|TvAb7xymnaLrCcHFNxFU@TUA+xhgK) z`tMBD+<)t;`O7A5wVU>C*W_GlvG8N7PnVzB*dMpi>sGAk{G(F~&)qCpwb*4}?^3O` zZ~e^wi)OEH*uP=hh0|-!-gb#e+d83I$GU?1O}OH!dshElr^Wt>i~Cl4)mbbw|K>)~ z`KlfNokOo~*Nj-TD*0DZn3v{RL54fmnHkhFm0o|G!9M#$RKVo~QS~ z+s`&E*?cUY^L*N*l;x+2&ThJ~_T>3VSKrrHhg{pY*JywLdg+R^r#`0tr6Q7YP0#L| zWqz+_Rq(Yyw&)#eSLob5|1whVyX-XeE&92S^AmpxXIJUXopA45#Jgp;fB*VgHZT8! z(CK~i*Y#z&=$ePG37h$jXZH_gG0%Uin_MR)bBTHOWg2oJbA-|1vc+3>a|? Mp00i_>zopr06Kp56951J diff --git a/documentation/html/classOdometry3Wheel-members.html b/documentation/html/classOdometry3Wheel-members.html deleted file mode 100644 index f722eb7..0000000 --- a/documentation/html/classOdometry3Wheel-members.html +++ /dev/null @@ -1,108 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    Odometry3Wheel Member List
    -
    -
    - -

    This is the complete list of members for Odometry3Wheel, including all inherited members.

    - - - - - - - - - - - - - - - - - - - - - - - - - -
    accelOdometryBaseprotected
    ang_accel_degOdometryBaseprotected
    ang_speed_degOdometryBaseprotected
    background_task(void *ptr)OdometryBasestatic
    current_posOdometryBaseprotected
    end_async()OdometryBase
    end_taskOdometryBase
    get_accel()OdometryBase
    get_angular_accel_deg()OdometryBase
    get_angular_speed_deg()OdometryBase
    get_position(void)OdometryBase
    get_speed()OdometryBase
    handleOdometryBaseprotected
    mutOdometryBaseprotected
    Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, odometry3wheel_cfg_t &cfg, bool is_async=true)Odometry3Wheel
    OdometryBase(bool is_async)OdometryBase
    pos_diff(position_t start_pos, position_t end_pos)OdometryBasestatic
    rot_diff(position_t pos1, position_t pos2)OdometryBasestatic
    set_position(const position_t &newpos=zero_pos)OdometryBasevirtual
    smallest_angle(double start_deg, double end_deg)OdometryBasestatic
    speedOdometryBaseprotected
    tune(vex::controller &con, TankDrive &drive)Odometry3Wheel
    update() overrideOdometry3Wheelvirtual
    zero_posOdometryBaseinlinestatic
    - - - - diff --git a/documentation/html/classOdometry3Wheel.html b/documentation/html/classOdometry3Wheel.html deleted file mode 100644 index b566fbb..0000000 --- a/documentation/html/classOdometry3Wheel.html +++ /dev/null @@ -1,303 +0,0 @@ - - - - - - - -RIT VEXU Core API: Odometry3Wheel Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    Odometry3Wheel Class Reference
    -
    -
    - -

    #include <odometry_3wheel.h>

    -
    -Inheritance diagram for Odometry3Wheel:
    -
    -
    - - -OdometryBase - -
    - - - - -

    -Classes

    struct  odometry3wheel_cfg_t
     
    - - - - - - - - - - - - - - - - - - - - - - - - - - -

    -Public Member Functions

     Odometry3Wheel (CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, odometry3wheel_cfg_t &cfg, bool is_async=true)
     
    position_t update () override
     
    void tune (vex::controller &con, TankDrive &drive)
     
    - Public Member Functions inherited from OdometryBase
     OdometryBase (bool is_async)
     
    position_t get_position (void)
     
    virtual void set_position (const position_t &newpos=zero_pos)
     
    virtual position_t update ()=0
     
    void end_async ()
     
    double get_speed ()
     
    double get_accel ()
     
    double get_angular_speed_deg ()
     
    double get_angular_accel_deg ()
     
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

    -Additional Inherited Members

    - Static Public Member Functions inherited from OdometryBase
    static int background_task (void *ptr)
     
    static double pos_diff (position_t start_pos, position_t end_pos)
     
    static double rot_diff (position_t pos1, position_t pos2)
     
    static double smallest_angle (double start_deg, double end_deg)
     
    - Public Attributes inherited from OdometryBase
    -bool end_task = false
     end_task is true if we instruct the odometry thread to shut down
     
    - Static Public Attributes inherited from OdometryBase
    static constexpr position_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}
     
    - Protected Attributes inherited from OdometryBase
    vex::task * handle
     
    vex::mutex mut
     
    position_t current_pos
     
    double speed
     
    double accel
     
    double ang_speed_deg
     
    double ang_accel_deg
     
    -

    Detailed Description

    -

    Odometry3Wheel

    -

    This class handles the code for a standard 3-pod odometry setup, where there are 3 "pods" made up of undriven (dead) wheels connected to encoders in the following configuration:

    -

    +Y ------------— ^ | | | | | | | || O || | | | | | | === | | ------------— | +----------------—> + X

    -

    Where O is the center of rotation. The robot will monitor the changes in rotation of these wheels and calculate the robot's X, Y and rotation on the field.

    -

    This is a "set and forget" class, meaning once the object is created, the robot will immediately begin tracking it's movement in the background.

    -
    Author
    Ryan McGee
    -
    Date
    Oct 31 2022
    -

    Constructor & Destructor Documentation

    - -

    ◆ Odometry3Wheel()

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    Odometry3Wheel::Odometry3Wheel (CustomEncoderlside_fwd,
    CustomEncoderrside_fwd,
    CustomEncoderoff_axis,
    odometry3wheel_cfg_tcfg,
    bool is_async = true 
    )
    -
    -

    Construct a new Odometry 3 Wheel object

    -
    Parameters
    - - - - - - -
    lside_fwdleft-side encoder reference
    rside_fwdright-side encoder reference
    off_axisoff-axis (perpendicular) encoder reference
    cfgrobot odometry configuration
    is_asynctrue to constantly run in the background
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ tune()

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    void Odometry3Wheel::tune (vex::controller & con,
    TankDrivedrive 
    )
    -
    -

    A guided tuning process to automatically find tuning parameters. This method is blocking, and returns when tuning has finished. Follow the instructions on the controller to complete the tuning process

    -
    Parameters
    - - - -
    conController reference, for screen and button control
    driveDrivetrain reference for robot control
    -
    -
    -

    A guided tuning process to automatically find tuning parameters. This method is blocking, and returns when tuning has finished. Follow the instructions on the controller to complete the tuning process

    -

    It is assumed the gear ratio and encoder PPR have been set correctly

    - -
    -
    - -

    ◆ update()

    - -
    -
    - - - - - -
    - - - - - - - -
    position_t Odometry3Wheel::update ()
    -
    -overridevirtual
    -
    -

    Update the current position of the robot once, using the current state of the encoders and the previous known location

    -
    Returns
    the robot's updated position
    - -

    Implements OdometryBase.

    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/subsystems/odometry/odometry_3wheel.h
    • -
    • src/subsystems/odometry/odometry_3wheel.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classOdometry3Wheel.png b/documentation/html/classOdometry3Wheel.png deleted file mode 100644 index e1b39c48649336e03dde2ef7a4e4da634399f51f..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 548 zcmV+<0^9wGP)vTJr#LVva2S`&=)l0h|Ns9}lGCUF000SeQchC<|NsC0|NsC0Hv*f~00056 zNklfGV!(xIAk_jYlT zecI@~neWZjq}GP55G_h;?SIoreJu^(%anfaa`7@yOg_#V?9 m+15V}GjoJ~oR(5bv-Ahx;#s6>)d8mf0000 - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    OdometryBase Member List
    -
    -
    - -

    This is the complete list of members for OdometryBase, including all inherited members.

    - - - - - - - - - - - - - - - - - - - - - - - -
    accelOdometryBaseprotected
    ang_accel_degOdometryBaseprotected
    ang_speed_degOdometryBaseprotected
    background_task(void *ptr)OdometryBasestatic
    current_posOdometryBaseprotected
    end_async()OdometryBase
    end_taskOdometryBase
    get_accel()OdometryBase
    get_angular_accel_deg()OdometryBase
    get_angular_speed_deg()OdometryBase
    get_position(void)OdometryBase
    get_speed()OdometryBase
    handleOdometryBaseprotected
    mutOdometryBaseprotected
    OdometryBase(bool is_async)OdometryBase
    pos_diff(position_t start_pos, position_t end_pos)OdometryBasestatic
    rot_diff(position_t pos1, position_t pos2)OdometryBasestatic
    set_position(const position_t &newpos=zero_pos)OdometryBasevirtual
    smallest_angle(double start_deg, double end_deg)OdometryBasestatic
    speedOdometryBaseprotected
    update()=0OdometryBasepure virtual
    zero_posOdometryBaseinlinestatic
    - - - - diff --git a/documentation/html/classOdometryBase.html b/documentation/html/classOdometryBase.html deleted file mode 100644 index f0cab51..0000000 --- a/documentation/html/classOdometryBase.html +++ /dev/null @@ -1,725 +0,0 @@ - - - - - - - -RIT VEXU Core API: OdometryBase Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    - -
    - -

    #include <odometry_base.h>

    -
    -Inheritance diagram for OdometryBase:
    -
    -
    - - -Odometry3Wheel -OdometryTank - -
    - - - - - - - - - - - - - - - - - - - - -

    -Public Member Functions

     OdometryBase (bool is_async)
     
    position_t get_position (void)
     
    virtual void set_position (const position_t &newpos=zero_pos)
     
    virtual position_t update ()=0
     
    void end_async ()
     
    double get_speed ()
     
    double get_accel ()
     
    double get_angular_speed_deg ()
     
    double get_angular_accel_deg ()
     
    - - - - - - - - - -

    -Static Public Member Functions

    static int background_task (void *ptr)
     
    static double pos_diff (position_t start_pos, position_t end_pos)
     
    static double rot_diff (position_t pos1, position_t pos2)
     
    static double smallest_angle (double start_deg, double end_deg)
     
    - - - - -

    -Public Attributes

    -bool end_task = false
     end_task is true if we instruct the odometry thread to shut down
     
    - - - -

    -Static Public Attributes

    static constexpr position_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}
     
    - - - - - - - - - - - - - - - -

    -Protected Attributes

    vex::task * handle
     
    vex::mutex mut
     
    position_t current_pos
     
    double speed
     
    double accel
     
    double ang_speed_deg
     
    double ang_accel_deg
     
    -

    Detailed Description

    -

    OdometryBase

    -

    This base class contains all the shared code between different implementations of odometry. It handles the asynchronous management, position input/output and basic math functions, and holds positional types specific to field orientation.

    -

    All future odometry implementations should extend this file and redefine update() function.

    -
    Author
    Ryan McGee
    -
    Date
    Aug 11 2021
    -

    Constructor & Destructor Documentation

    - -

    ◆ OdometryBase()

    - -
    -
    - - - - - - - - -
    OdometryBase::OdometryBase (bool is_async)
    -
    -

    Construct a new Odometry Base object

    -
    Parameters
    - - -
    is_asyncTrue to run constantly in the background, false to call update() manually
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ background_task()

    - -
    -
    - - - - - -
    - - - - - - - - -
    int OdometryBase::background_task (void * ptr)
    -
    -static
    -
    -

    Function that runs in the background task. This function pointer is passed to the vex::task constructor.

    -
    Parameters
    - - -
    ptrPointer to OdometryBase object
    -
    -
    -
    Returns
    Required integer return code. Unused.
    - -
    -
    - -

    ◆ end_async()

    - -
    -
    - - - - - - - -
    void OdometryBase::end_async ()
    -
    -

    End the background task. Cannot be restarted. If the user wants to end the thread but keep the data up to date, they must run the update() function manually from then on.

    - -
    -
    - -

    ◆ get_accel()

    - -
    -
    - - - - - - - -
    double OdometryBase::get_accel ()
    -
    -

    Get the current acceleration

    Returns
    the acceleration rate of the robot (inch/s^2)
    - -
    -
    - -

    ◆ get_angular_accel_deg()

    - -
    -
    - - - - - - - -
    double OdometryBase::get_angular_accel_deg ()
    -
    -

    Get the current angular acceleration in degrees

    Returns
    the angular acceleration at which we are turning (deg/s^2)
    - -
    -
    - -

    ◆ get_angular_speed_deg()

    - -
    -
    - - - - - - - -
    double OdometryBase::get_angular_speed_deg ()
    -
    -

    Get the current angular speed in degrees

    Returns
    the angular velocity at which we are turning (deg/s)
    - -
    -
    - -

    ◆ get_position()

    - -
    -
    - - - - - - - - -
    position_t OdometryBase::get_position (void )
    -
    -

    Gets the current position and rotation

    Returns
    the position that the odometry believes the robot is at
    -

    Gets the current position and rotation

    - -
    -
    - -

    ◆ get_speed()

    - -
    -
    - - - - - - - -
    double OdometryBase::get_speed ()
    -
    -

    Get the current speed

    Returns
    the speed at which the robot is moving and grooving (inch/s)
    - -
    -
    - -

    ◆ pos_diff()

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - -
    double OdometryBase::pos_diff (position_t start_pos,
    position_t end_pos 
    )
    -
    -static
    -
    -

    Get the distance between two points

    Parameters
    - - - -
    start_posdistance from this point
    end_posto this point
    -
    -
    -
    Returns
    the euclidean distance between start_pos and end_pos
    - -
    -
    - -

    ◆ rot_diff()

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - -
    double OdometryBase::rot_diff (position_t pos1,
    position_t pos2 
    )
    -
    -static
    -
    -

    Get the change in rotation between two points

    Parameters
    - - - -
    pos1position with initial rotation
    pos2position with final rotation
    -
    -
    -
    Returns
    change in rotation between pos1 and pos2
    -

    Get the change in rotation between two points

    - -
    -
    - -

    ◆ set_position()

    - -
    -
    - - - - - -
    - - - - - - - - -
    void OdometryBase::set_position (const position_tnewpos = zero_pos)
    -
    -virtual
    -
    -

    Sets the current position of the robot

    Parameters
    - - -
    newposthe new position that the odometry will believe it is at
    -
    -
    -

    Sets the current position of the robot

    - -

    Reimplemented in OdometryTank.

    - -
    -
    - -

    ◆ smallest_angle()

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - -
    double OdometryBase::smallest_angle (double start_deg,
    double end_deg 
    )
    -
    -static
    -
    -

    Get the smallest difference in angle between a start heading and end heading. Returns the difference between -180 degrees and +180 degrees, representing the robot turning left or right, respectively.

    Parameters
    - - - -
    start_degintitial angle (degrees)
    end_degfinal angle (degrees)
    -
    -
    -
    Returns
    the smallest angle from the initial to the final angle. This takes into account the wrapping of rotations around 360 degrees
    -

    Get the smallest difference in angle between a start heading and end heading. Returns the difference between -180 degrees and +180 degrees, representing the robot turning left or right, respectively.

    - -
    -
    - -

    ◆ update()

    - -
    -
    - - - - - -
    - - - - - - - -
    virtual position_t OdometryBase::update ()
    -
    -pure virtual
    -
    -

    Update the current position on the field based on the sensors

    Returns
    the location that the robot is at after the odometry does its calculations
    - -

    Implemented in Odometry3Wheel, and OdometryTank.

    - -
    -
    -

    Member Data Documentation

    - -

    ◆ accel

    - -
    -
    - - - - - -
    - - - - -
    double OdometryBase::accel
    -
    -protected
    -
    -

    the rate at which we are accelerating (inch/s^2)

    - -
    -
    - -

    ◆ ang_accel_deg

    - -
    -
    - - - - - -
    - - - - -
    double OdometryBase::ang_accel_deg
    -
    -protected
    -
    -

    the rate at which we are accelerating our turn (deg/s^2)

    - -
    -
    - -

    ◆ ang_speed_deg

    - -
    -
    - - - - - -
    - - - - -
    double OdometryBase::ang_speed_deg
    -
    -protected
    -
    -

    the speed at which we are turning (deg/s)

    - -
    -
    - -

    ◆ current_pos

    - -
    -
    - - - - - -
    - - - - -
    position_t OdometryBase::current_pos
    -
    -protected
    -
    -

    Current position of the robot in terms of x,y,rotation

    - -
    -
    - -

    ◆ handle

    - -
    -
    - - - - - -
    - - - - -
    vex::task* OdometryBase::handle
    -
    -protected
    -
    -

    handle to the vex task that is running the odometry code

    - -
    -
    - -

    ◆ mut

    - -
    -
    - - - - - -
    - - - - -
    vex::mutex OdometryBase::mut
    -
    -protected
    -
    -

    Mutex to control multithreading

    - -
    -
    - -

    ◆ speed

    - -
    -
    - - - - - -
    - - - - -
    double OdometryBase::speed
    -
    -protected
    -
    -

    the speed at which we are travelling (inch/s)

    - -
    -
    - -

    ◆ zero_pos

    - -
    -
    - - - - - -
    - - - - -
    constexpr position_t OdometryBase::zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}
    -
    -inlinestaticconstexpr
    -
    -

    Zeroed position. X=0, Y=0, Rotation= 90 degrees

    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/subsystems/odometry/odometry_base.h
    • -
    • src/subsystems/odometry/odometry_base.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classOdometryBase.png b/documentation/html/classOdometryBase.png deleted file mode 100644 index ad76095914622330d748df91defd2bc7f2f459c3..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 776 zcmV+j1NZ!iP)vTJr#LVva2S`&=)l0h|Ns9}lGCUF000SeQchC<|NsC0|NsC0Hv*f~0007$ zNkl zb<~W%t7O&in@ZM=zHPdSi0nlr0pKW9QbeR9DhU8bVT>`S0RZ=50D!0S2FYP~f#n+{ z{~e!i`3gy`t^n{1R1yH5fJy?u6HrM2cmgU30GDAHhT#_gz-jzwJ5&+?x}uT*a11I5 z09{c@05}Gf1c0unBmf+PN&-MvR1yG=K_vm8D>sw0*4laoYpt#4S79wlowTfUQIk-WzZiYN~C4>u%RqK{*uVXLEqa?Jn+VG$xUBYwMRd?DUpob96UwdAYpM18&*DY$yHlW?9=PSra`z$B`?^=u;u-&UoSUl_mY_Vbph$ zE76y9?If90nmH?yB~5bY6p?ZOk)*ZOp2Z)$N^&*WVI4030000 - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    OdometryTank Member List
    -
    -
    - -

    This is the complete list of members for OdometryTank, including all inherited members.

    - - - - - - - - - - - - - - - - - - - - - - - - - -
    accelOdometryBaseprotected
    ang_accel_degOdometryBaseprotected
    ang_speed_degOdometryBaseprotected
    background_task(void *ptr)OdometryBasestatic
    current_posOdometryBaseprotected
    end_async()OdometryBase
    end_taskOdometryBase
    get_accel()OdometryBase
    get_angular_accel_deg()OdometryBase
    get_angular_speed_deg()OdometryBase
    get_position(void)OdometryBase
    get_speed()OdometryBase
    handleOdometryBaseprotected
    mutOdometryBaseprotected
    OdometryBase(bool is_async)OdometryBase
    OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true)OdometryTank
    OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true)OdometryTank
    pos_diff(position_t start_pos, position_t end_pos)OdometryBasestatic
    rot_diff(position_t pos1, position_t pos2)OdometryBasestatic
    set_position(const position_t &newpos=zero_pos) overrideOdometryTankvirtual
    smallest_angle(double start_deg, double end_deg)OdometryBasestatic
    speedOdometryBaseprotected
    update() overrideOdometryTankvirtual
    zero_posOdometryBaseinlinestatic
    - - - - diff --git a/documentation/html/classOdometryTank.html b/documentation/html/classOdometryTank.html deleted file mode 100644 index 57a3165..0000000 --- a/documentation/html/classOdometryTank.html +++ /dev/null @@ -1,345 +0,0 @@ - - - - - - - -RIT VEXU Core API: OdometryTank Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    OdometryTank Class Reference
    -
    -
    - -

    #include <odometry_tank.h>

    -
    -Inheritance diagram for OdometryTank:
    -
    -
    - - -OdometryBase - -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

    -Public Member Functions

     OdometryTank (vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true)
     
     OdometryTank (CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true)
     
    position_t update () override
     
    void set_position (const position_t &newpos=zero_pos) override
     
    - Public Member Functions inherited from OdometryBase
     OdometryBase (bool is_async)
     
    position_t get_position (void)
     
    virtual void set_position (const position_t &newpos=zero_pos)
     
    virtual position_t update ()=0
     
    void end_async ()
     
    double get_speed ()
     
    double get_accel ()
     
    double get_angular_speed_deg ()
     
    double get_angular_accel_deg ()
     
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

    -Additional Inherited Members

    - Static Public Member Functions inherited from OdometryBase
    static int background_task (void *ptr)
     
    static double pos_diff (position_t start_pos, position_t end_pos)
     
    static double rot_diff (position_t pos1, position_t pos2)
     
    static double smallest_angle (double start_deg, double end_deg)
     
    - Public Attributes inherited from OdometryBase
    -bool end_task = false
     end_task is true if we instruct the odometry thread to shut down
     
    - Static Public Attributes inherited from OdometryBase
    static constexpr position_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}
     
    - Protected Attributes inherited from OdometryBase
    vex::task * handle
     
    vex::mutex mut
     
    position_t current_pos
     
    double speed
     
    double accel
     
    double ang_speed_deg
     
    double ang_accel_deg
     
    -

    Detailed Description

    -

    OdometryTank defines an odometry system for a tank drivetrain This requires encoders in the same orientation as the drive wheels Odometry is a "start and forget" subsystem, which means once it's created and configured, it will constantly run in the background and track the robot's X, Y and rotation coordinates.

    -

    Constructor & Destructor Documentation

    - -

    ◆ OdometryTank() [1/2]

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    OdometryTank::OdometryTank (vex::motor_group & left_side,
    vex::motor_group & right_side,
    robot_specs_tconfig,
    vex::inertial * imu = NULL,
    bool is_async = true 
    )
    -
    -

    Initialize the Odometry module, calculating position from the drive motors.

    Parameters
    - - - - - - -
    left_sideThe left motors
    right_sideThe right motors
    configthe specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained
    imuThe robot's inertial sensor. If not included, rotation is calculated from the encoders.
    is_asyncIf true, position will be updated in the background continuously. If false, the programmer will have to manually call update().
    -
    -
    - -
    -
    - -

    ◆ OdometryTank() [2/2]

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    OdometryTank::OdometryTank (CustomEncoderleft_enc,
    CustomEncoderright_enc,
    robot_specs_tconfig,
    vex::inertial * imu = NULL,
    bool is_async = true 
    )
    -
    -

    Initialize the Odometry module, calculating position from the drive motors.

    Parameters
    - - - - - - -
    left_encThe left motors
    right_encThe right motors
    configthe specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained
    imuThe robot's inertial sensor. If not included, rotation is calculated from the encoders.
    is_asyncIf true, position will be updated in the background continuously. If false, the programmer will have to manually call update().
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ set_position()

    - -
    -
    - - - - - -
    - - - - - - - - -
    void OdometryTank::set_position (const position_tnewpos = zero_pos)
    -
    -overridevirtual
    -
    -

    set_position tells the odometry to place itself at a position

    Parameters
    - - -
    newposthe position the odometry will take
    -
    -
    -

    Resets the position and rotational data to the input.

    - -

    Reimplemented from OdometryBase.

    - -
    -
    - -

    ◆ update()

    - -
    -
    - - - - - -
    - - - - - - - -
    position_t OdometryTank::update ()
    -
    -overridevirtual
    -
    -

    Update the current position on the field based on the sensors

    Returns
    the position that odometry has calculated itself to be at
    -

    Update, store and return the current position of the robot. Only use if not initializing with a separate thread.

    - -

    Implements OdometryBase.

    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/subsystems/odometry/odometry_tank.h
    • -
    • src/subsystems/odometry/odometry_tank.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classOdometryTank.png b/documentation/html/classOdometryTank.png deleted file mode 100644 index 84c96799bab641858ec7d9a0c377dff4274a1c77..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 541 zcmV+&0^vTJr#LVva2S`&=)l0h|Ns9}lGCUF000SeQchC<|NsC0|NsC0Hv*f~0004~ zNklo8_LGO=^j`cnwo-y7C3@BApCh-jcM;Kvx_JORKRy#QdM zCi7pfxeg}tH~drwv-y9%e-%zV=6q;s{$H`5l6O#7JD;ydkS zkheCZayh>*fu8w0C3_NQ#m6z})(mPV-Us}8Dvz1k_-h+Y&<(y6(y()8Omn=&HwBV~ z;kP#D{Pgn3fvd;nXUsp>*YtnWKU!5=+v*>Z!_rhGhPQsdmkgituh~83Uo>0aXJ%$! fU%(F`gn9Y_VW3V+flA{300000NkvXXu0mjfwf_-5 diff --git a/documentation/html/classPID-members.html b/documentation/html/classPID-members.html deleted file mode 100644 index ba81b0f..0000000 --- a/documentation/html/classPID-members.html +++ /dev/null @@ -1,103 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    PID Member List
    -
    -
    - -

    This is the complete list of members for PID, including all inherited members.

    - - - - - - - - - - - - - - - - - - - - -
    ANGULAR enum value (defined in PID)PID
    configPID
    ERROR_TYPE enum namePID
    FeedbackType enum name (defined in Feedback)Feedback
    FeedforwardType enum value (defined in Feedback)Feedback
    get() overridePIDvirtual
    get_error()PID
    get_target()PID
    get_type() override (defined in PID)PIDvirtual
    init(double start_pt, double set_pt) overridePIDvirtual
    is_on_target() overridePIDvirtual
    LINEAR enum value (defined in PID)PID
    OtherType enum value (defined in Feedback)Feedback
    PID(pid_config_t &config)PID
    PIDType enum value (defined in Feedback)Feedback
    reset()PID
    set_limits(double lower, double upper) overridePIDvirtual
    set_target(double target)PID
    update(double sensor_val) overridePIDvirtual
    - - - - diff --git a/documentation/html/classPID.html b/documentation/html/classPID.html deleted file mode 100644 index f418f70..0000000 --- a/documentation/html/classPID.html +++ /dev/null @@ -1,509 +0,0 @@ - - - - - - - -RIT VEXU Core API: PID Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    - -
    - -

    #include <pid.h>

    -
    -Inheritance diagram for PID:
    -
    -
    - - -Feedback - -
    - - - - -

    -Classes

    struct  pid_config_t
     
    - - - - - - -

    -Public Types

    enum  ERROR_TYPE { LINEAR -, ANGULAR - }
     
    - Public Types inherited from Feedback
    enum  FeedbackType { PIDType -, FeedforwardType -, OtherType - }
     
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

    -Public Member Functions

     PID (pid_config_t &config)
     
    void init (double start_pt, double set_pt) override
     
    double update (double sensor_val) override
     
    double get () override
     
    void set_limits (double lower, double upper) override
     
    bool is_on_target () override
     
    void reset ()
     
    double get_error ()
     
    double get_target ()
     
    void set_target (double target)
     
    Feedback::FeedbackType get_type () override
     
    virtual void init (double start_pt, double set_pt)=0
     
    virtual double update (double val)=0
     
    virtual double get ()=0
     
    virtual void set_limits (double lower, double upper)=0
     
    virtual bool is_on_target ()=0
     
    -virtual Feedback::FeedbackType get_type ()
     
    - - - - -

    -Public Attributes

    -pid_config_tconfig
     configuration struct for this controller. see pid_config_t for information about what this contains
     
    -

    Detailed Description

    -

    PID Class

    -

    Defines a standard feedback loop using the constants kP, kI, kD, deadband, and on_target_time. The formula is:

    -

    out = kP*error + kI*integral(d Error) + kD*(dError/dt)

    -

    The PID object will determine it is "on target" when the error is within the deadband, for a duration of on_target_time

    -
    Author
    Ryan McGee
    -
    Date
    4/3/2020
    -

    Member Enumeration Documentation

    - -

    ◆ ERROR_TYPE

    - -
    -
    - - - - -
    enum PID::ERROR_TYPE
    -
    -

    An enum to distinguish between a linear and angular caluclation of PID error.

    - -
    -
    -

    Constructor & Destructor Documentation

    - -

    ◆ PID()

    - -
    -
    - - - - - - - - -
    PID::PID (pid_config_tconfig)
    -
    -

    Create the PID object

    Parameters
    - - -
    configthe configuration data for this controller
    -
    -
    -

    Create the PID object

    - -
    -
    -

    Member Function Documentation

    - -

    ◆ get()

    - -
    -
    - - - - - -
    - - - - - - - -
    double PID::get ()
    -
    -overridevirtual
    -
    -

    Gets the current PID out value, from when update() was last run

    Returns
    the Out value of the controller (voltage, RPM, whatever the PID controller is controlling)
    -

    Gets the current PID out value, from when update() was last run

    - -

    Implements Feedback.

    - -
    -
    - -

    ◆ get_error()

    - -
    -
    - - - - - - - -
    double PID::get_error ()
    -
    -

    Get the delta between the current sensor data and the target

    Returns
    the error calculated. how it is calculated depends on error_method specified in pid_config_t
    -

    Get the delta between the current sensor data and the target

    - -
    -
    - -

    ◆ get_target()

    - -
    -
    - - - - - - - -
    double PID::get_target ()
    -
    -

    Get the PID's target

    Returns
    the target the PID controller is trying to achieve
    - -
    -
    - -

    ◆ get_type()

    - -
    -
    - - - - - -
    - - - - - - - -
    Feedback::FeedbackType PID::get_type ()
    -
    -overridevirtual
    -
    - -

    Reimplemented from Feedback.

    - -
    -
    - -

    ◆ init()

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - -
    void PID::init (double start_pt,
    double set_pt 
    )
    -
    -overridevirtual
    -
    -

    Inherited from Feedback for interoperability. Update the setpoint and reset integral accumulation

    -

    start_pt can be safely ignored in this feedback controller

    Parameters
    - - - -
    start_ptcommpletely ignored for PID. necessary to satisfy Feedback base
    set_ptsets the target of the PID controller
    -
    -
    - -

    Implements Feedback.

    - -
    -
    - -

    ◆ is_on_target()

    - -
    -
    - - - - - -
    - - - - - - - -
    bool PID::is_on_target ()
    -
    -overridevirtual
    -
    -

    Checks if the PID controller is on target.
    -

    Returns
    true if the loop is within [deadband] for [on_target_time] seconds
    -

    Returns true if the loop is within [deadband] for [on_target_time] seconds

    - -

    Implements Feedback.

    - -
    -
    - -

    ◆ reset()

    - -
    -
    - - - - - - - -
    void PID::reset ()
    -
    -

    Reset the PID loop by resetting time since 0 and accumulated error.

    - -
    -
    - -

    ◆ set_limits()

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - -
    void PID::set_limits (double lower,
    double upper 
    )
    -
    -overridevirtual
    -
    -

    Set the limits on the PID out. The PID out will "clip" itself to be between the limits.

    Parameters
    - - - -
    lowerthe lower limit. the PID controller will never command the output go below lower
    upperthe upper limit. the PID controller will never command the output go higher than upper
    -
    -
    -

    Set the limits on the PID out. The PID out will "clip" itself to be between the limits.

    - -

    Implements Feedback.

    - -
    -
    - -

    ◆ set_target()

    - -
    -
    - - - - - - - - -
    void PID::set_target (double target)
    -
    -

    Set the target for the PID loop, where the robot is trying to end up

    Parameters
    - - -
    targetthe sensor reading we would like to achieve
    -
    -
    -

    Set the target for the PID loop, where the robot is trying to end up

    - -
    -
    - -

    ◆ update()

    - -
    -
    - - - - - -
    - - - - - - - - -
    double PID::update (double sensor_val)
    -
    -overridevirtual
    -
    -

    Update the PID loop by taking the time difference from last update, and running the PID formula with the new sensor data

    Parameters
    - - -
    sensor_valthe distance, angle, encoder position or whatever it is we are measuring
    -
    -
    -
    Returns
    the new output. What would be returned by PID::get()
    - -

    Implements Feedback.

    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/utils/pid.h
    • -
    • src/utils/pid.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classPID.png b/documentation/html/classPID.png deleted file mode 100644 index 364123b3e5af956757c94b478945a17461604170..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 362 zcmeAS@N?(olHy`uVBq!ia0vp^E!3-p)cPaA%Dd_;85ZC|z{{xvX-h3_XKeXJ! zK(jz%`k5C84jcfA2T!`Z0w~8>666=m0OW&#In(SbK*6t`E{-7;jBn>&>}xjQVYx2N z`SySPN5+M`Y60tJcwL<Q?H&B`eAmq>>KTso7_K4nr1VxBysz?%4_-0 zo&5QvtE;R^*S{_O$vi2=9cZSpmzSn02g4i#28SuuDu)Z2pYol2(Gi_DvF75-B`geP zKy0JQ$l&kAaA2|!!-qfioiigvW~dzX=v1kU^LVz;f1|HzW_$Rg)D_>2Jc5o(Pf9+0 zTy^!lBU(SbPJX@IS*Jefi*=Ba=e+&uhQ{2Vn59{)CSGgUvIQ6b44$rjF6*2UngHFh Bn3w - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    PIDFF Member List
    -
    -
    - -

    This is the complete list of members for PIDFF, including all inherited members.

    - - - - - - - - - - - - - - - -
    FeedbackType enum name (defined in Feedback)Feedback
    FeedforwardType enum value (defined in Feedback)Feedback
    get() overridePIDFFvirtual
    get_type() (defined in Feedback)Feedbackinlinevirtual
    init(double start_pt, double set_pt) overridePIDFFvirtual
    is_on_target() overridePIDFFvirtual
    OtherType enum value (defined in Feedback)Feedback
    pid (defined in PIDFF)PIDFF
    PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg) (defined in PIDFF)PIDFF
    PIDType enum value (defined in Feedback)Feedback
    set_limits(double lower, double upper) overridePIDFFvirtual
    set_target(double set_pt)PIDFF
    update(double val) overridePIDFFvirtual
    update(double val, double vel_setpt, double a_setpt=0)PIDFF
    - - - - diff --git a/documentation/html/classPIDFF.html b/documentation/html/classPIDFF.html deleted file mode 100644 index 131cf69..0000000 --- a/documentation/html/classPIDFF.html +++ /dev/null @@ -1,401 +0,0 @@ - - - - - - - -RIT VEXU Core API: PIDFF Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    - -
    -
    -Inheritance diagram for PIDFF:
    -
    -
    - - -Feedback - -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

    -Public Member Functions

    PIDFF (PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg)
     
    void init (double start_pt, double set_pt) override
     
    void set_target (double set_pt)
     
    double update (double val) override
     
    double update (double val, double vel_setpt, double a_setpt=0)
     
    double get () override
     
    void set_limits (double lower, double upper) override
     
    bool is_on_target () override
     
    - Public Member Functions inherited from Feedback
    virtual void init (double start_pt, double set_pt)=0
     
    virtual double update (double val)=0
     
    virtual double get ()=0
     
    virtual void set_limits (double lower, double upper)=0
     
    virtual bool is_on_target ()=0
     
    -virtual Feedback::FeedbackType get_type ()
     
    - - - -

    -Public Attributes

    -PID pid
     
    - - - - -

    -Additional Inherited Members

    - Public Types inherited from Feedback
    enum  FeedbackType { PIDType -, FeedforwardType -, OtherType - }
     
    -

    Member Function Documentation

    - -

    ◆ get()

    - -
    -
    - - - - - -
    - - - - - - - -
    double PIDFF::get ()
    -
    -overridevirtual
    -
    -
    Returns
    the last saved result from the feedback controller
    - -

    Implements Feedback.

    - -
    -
    - -

    ◆ init()

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - -
    void PIDFF::init (double start_pt,
    double set_pt 
    )
    -
    -overridevirtual
    -
    -

    Initialize the feedback controller for a movement

    -
    Parameters
    - - - -
    start_ptthe current sensor value
    set_ptwhere the sensor value should be
    -
    -
    - -

    Implements Feedback.

    - -
    -
    - -

    ◆ is_on_target()

    - -
    -
    - - - - - -
    - - - - - - - -
    bool PIDFF::is_on_target ()
    -
    -overridevirtual
    -
    -
    Returns
    true if the feedback controller has reached it's setpoint
    - -

    Implements Feedback.

    - -
    -
    - -

    ◆ set_limits()

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - -
    void PIDFF::set_limits (double lower,
    double upper 
    )
    -
    -overridevirtual
    -
    -

    Clamp the upper and lower limits of the output. If both are 0, no limits should be applied.

    -
    Parameters
    - - - -
    lowerUpper limit
    upperLower limit
    -
    -
    - -

    Implements Feedback.

    - -
    -
    - -

    ◆ set_target()

    - -
    -
    - - - - - - - - -
    void PIDFF::set_target (double set_pt)
    -
    -

    Set the target of the PID loop

    Parameters
    - - -
    set_ptSetpoint / target value
    -
    -
    - -
    -
    - -

    ◆ update() [1/2]

    - -
    -
    - - - - - -
    - - - - - - - - -
    double PIDFF::update (double val)
    -
    -overridevirtual
    -
    -

    Iterate the feedback loop once with an updated sensor value. Only kS for feedfoward will be applied.

    -
    Parameters
    - - -
    valvalue from the sensor
    -
    -
    -
    Returns
    feedback loop result
    - -

    Implements Feedback.

    - -
    -
    - -

    ◆ update() [2/2]

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - -
    double PIDFF::update (double val,
    double vel_setpt,
    double a_setpt = 0 
    )
    -
    -

    Iterate the feedback loop once with an updated sensor value

    -
    Parameters
    - - - - -
    valvalue from the sensor
    vel_setptVelocity for feedforward
    a_setptAcceleration for feedfoward
    -
    -
    -
    Returns
    feedback loop result
    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/utils/pidff.h
    • -
    • src/utils/pidff.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classPIDFF.png b/documentation/html/classPIDFF.png deleted file mode 100644 index 6d05d23a375c177db25840a37677290b0377730c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 377 zcmeAS@N?(olHy`uVBq!ia0vp^E!3-p)cPaA%Dd_;85ZC|z{{xvX-h3_XKeXJ! zK(jz%`k5C84jcfA2T!`Z0w~8>666=m0OW&#In(Sb3=E7co-U3d6^w7^UhHd8;Bn2* z7ry-e|D#aJBTUCaPo!;*Ha>0^dTxr*XTH#@feTbD-8?)l6?>%Y_t=!C8+TQj)3dBn z`RAA77L}D<(HfuJimK)u+Lo}qcG~qHGry=Te_$T2cB5=kie-hT<~@&D7v5%{zx8&{ zjFV3j^8MA{Zmo&^!|1t5QAOotr0S|w%?t;4xfyzloHywR>lmx7PQGL0`l;JbU4A6}3k!pdA|r#p2g8BS|5cQf7CW3dbBv>N=FH{FH=pl4I%%1T_$^V{lh3Ewy_^>R zYWrVaPtUrTqFE;uPj0>Ep=Z5Pb^SKu=uiJjUfn+#+&S~6u~Smov!B&Mf)gG0F_^bm VPMv)uApsaj44$rjF6*2UngHUNr7Hjc diff --git a/documentation/html/classSpinRPMCommand-members.html b/documentation/html/classSpinRPMCommand-members.html deleted file mode 100644 index 6f34ef6..0000000 --- a/documentation/html/classSpinRPMCommand-members.html +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    SpinRPMCommand Member List
    -
    -
    - -

    This is the complete list of members for SpinRPMCommand, including all inherited members.

    - - - - - - -
    on_timeout()AutoCommandinlinevirtual
    run() overrideSpinRPMCommandvirtual
    SpinRPMCommand(Flywheel &flywheel, int rpm)SpinRPMCommand
    timeout_secondsAutoCommand
    withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
    - - - - diff --git a/documentation/html/classSpinRPMCommand.html b/documentation/html/classSpinRPMCommand.html deleted file mode 100644 index 72ab14c..0000000 --- a/documentation/html/classSpinRPMCommand.html +++ /dev/null @@ -1,189 +0,0 @@ - - - - - - - -RIT VEXU Core API: SpinRPMCommand Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    SpinRPMCommand Class Reference
    -
    -
    - -

    #include <flywheel_commands.h>

    -
    -Inheritance diagram for SpinRPMCommand:
    -
    -
    - - -AutoCommand - -
    - - - - - - - - - - - - - -

    -Public Member Functions

     SpinRPMCommand (Flywheel &flywheel, int rpm)
     
    bool run () override
     
    - Public Member Functions inherited from AutoCommand
    virtual bool run ()
     
    virtual void on_timeout ()
     
    -AutoCommandwithTimeout (double t_seconds)
     
    - - - - -

    -Additional Inherited Members

    - Public Attributes inherited from AutoCommand
    double timeout_seconds = 10.0
     
    -

    Detailed Description

    -

    File: flywheel_commands.h Desc: [insert meaningful desc] AutoCommand wrapper class for the spinRPM function in the Flywheel class

    -

    Constructor & Destructor Documentation

    - -

    ◆ SpinRPMCommand()

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    SpinRPMCommand::SpinRPMCommand (Flywheelflywheel,
    int rpm 
    )
    -
    -

    Construct a SpinRPM Command

    Parameters
    - - - -
    flywheelthe flywheel sys to command
    rpmthe rpm that we should spin at
    -
    -
    -

    File: flywheel_commands.cpp Desc: [insert meaningful desc]

    - -
    -
    -

    Member Function Documentation

    - -

    ◆ run()

    - -
    -
    - - - - - -
    - - - - - - - -
    bool SpinRPMCommand::run ()
    -
    -overridevirtual
    -
    -

    Run spin_manual Overrides run from AutoCommand

    Returns
    true when execution is complete, false otherwise
    - -

    Reimplemented from AutoCommand.

    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/utils/command_structure/flywheel_commands.h
    • -
    • src/utils/command_structure/flywheel_commands.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classSpinRPMCommand.png b/documentation/html/classSpinRPMCommand.png deleted file mode 100644 index 1d9f067b838fa3b50907740b084fe8b767e50efe..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 543 zcmeAS@N?(olHy`uVBq!ia0vp^{mhF42Mz$mgC|{H0hHq`3GxeO0P?}WoN4wI1_s7eo-U3d6^w7^#`Yan;AuJD z9CG%r|DN0*h8IfAJ6$4HhWHq6{P>(j{XBmNm(es!k!0r#Ej_b=DnP2A&qe&Tig@Z25BYtI!JE3JI;O{Q}1)BK)CC#>5GJhR=4 z!ak<&SXsTU;PEx@I}$hF*qzC3yuPz8VBV7TCr(tA{Ns+vpLJ!~zkk!34K~TmRyNzH zu5i-rwYBG@$6%}DPw*aj2i0@BiiStc(5dSsGG+~=L^)mE?DJyj-ko$@W;NnfT1RXjXqGUg@N|8mMH>*f&qx(>$Y4HFJ+z(b+TauJbn?OWd_N Tb{`KgDj7Uo{an^LB{Ts5AD|31 diff --git a/documentation/html/classTankDrive-members.html b/documentation/html/classTankDrive-members.html deleted file mode 100644 index d42c75b..0000000 --- a/documentation/html/classTankDrive-members.html +++ /dev/null @@ -1,99 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    TankDrive Member List
    -
    -
    - -

    This is the complete list of members for TankDrive, including all inherited members.

    - - - - - - - - - - - - - - - - -
    drive_arcade(double forward_back, double left_right, int power=1)TankDrive
    drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed=1)TankDrive
    drive_forward(double inches, directionType dir, double max_speed=1)TankDrive
    drive_tank(double left, double right, int power=1, bool isdriver=false)TankDrive
    drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed=1)TankDrive
    drive_to_point(double x, double y, vex::directionType dir, double max_speed=1)TankDrive
    modify_inputs(double input, int power=2)TankDrivestatic
    pure_pursuit(std::vector< PurePursuit::hermite_point > path, directionType dir, double radius, double res, Feedback &feedback, double max_speed=1)TankDrive
    reset_auto()TankDrive
    stop()TankDrive
    TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom=NULL)TankDrive
    turn_degrees(double degrees, Feedback &feedback, double max_speed=1)TankDrive
    turn_degrees(double degrees, double max_speed=1)TankDrive
    turn_to_heading(double heading_deg, Feedback &feedback, double max_speed=1)TankDrive
    turn_to_heading(double heading_deg, double max_speed=1)TankDrive
    - - - - diff --git a/documentation/html/classTankDrive.html b/documentation/html/classTankDrive.html deleted file mode 100644 index 12429bc..0000000 --- a/documentation/html/classTankDrive.html +++ /dev/null @@ -1,877 +0,0 @@ - - - - - - - -RIT VEXU Core API: TankDrive Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    - -
    - -

    #include <tank_drive.h>

    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

    -Public Member Functions

     TankDrive (motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom=NULL)
     
    void stop ()
     
    void drive_tank (double left, double right, int power=1, bool isdriver=false)
     
    void drive_arcade (double forward_back, double left_right, int power=1)
     
    bool drive_forward (double inches, directionType dir, Feedback &feedback, double max_speed=1)
     
    bool drive_forward (double inches, directionType dir, double max_speed=1)
     
    bool turn_degrees (double degrees, Feedback &feedback, double max_speed=1)
     
    bool turn_degrees (double degrees, double max_speed=1)
     
    bool drive_to_point (double x, double y, vex::directionType dir, Feedback &feedback, double max_speed=1)
     
    bool drive_to_point (double x, double y, vex::directionType dir, double max_speed=1)
     
    bool turn_to_heading (double heading_deg, Feedback &feedback, double max_speed=1)
     
    bool turn_to_heading (double heading_deg, double max_speed=1)
     
    void reset_auto ()
     
    bool pure_pursuit (std::vector< PurePursuit::hermite_point > path, directionType dir, double radius, double res, Feedback &feedback, double max_speed=1)
     
    - - - -

    -Static Public Member Functions

    static double modify_inputs (double input, int power=2)
     
    -

    Detailed Description

    -

    TankDrive is a class to run a tank drive system. A tank drive system, sometimes called differential drive, has a motor (or group of synchronized motors) on the left and right side

    -

    Constructor & Destructor Documentation

    - -

    ◆ TankDrive()

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    TankDrive::TankDrive (motor_group & left_motors,
    motor_group & right_motors,
    robot_specs_tconfig,
    OdometryBaseodom = NULL 
    )
    -
    -

    Create the TankDrive object

    Parameters
    - - - - - -
    left_motorsleft side drive motors
    right_motorsright side drive motors
    configthe configuration specification defining physical dimensions about the robot. See robot_specs_t for more info
    odoman odometry system to track position and rotation. this is necessary to execute autonomous paths
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ drive_arcade()

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - -
    void TankDrive::drive_arcade (double forward_back,
    double left_right,
    int power = 1 
    )
    -
    -

    Drive the robot using arcade style controls. forward_back controls the linear motion, left_right controls the turning.

    -

    forward_back and left_right are in "percent": -1.0 -> 1.0

    -
    Parameters
    - - - - -
    forward_backthe percent to move forward or backward
    left_rightthe percent to turn left or right
    powermodifies the input velocities left^power, right^power
    -
    -
    -

    Drive the robot using arcade style controls. forward_back controls the linear motion, left_right controls the turning.

    -

    left_motors and right_motors are in "percent": -1.0 -> 1.0

    - -
    -
    - -

    ◆ drive_forward() [1/2]

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - -
    bool TankDrive::drive_forward (double inches,
    directionType dir,
    double max_speed = 1 
    )
    -
    -

    Autonomously drive the robot forward a certain distance

    -
    Parameters
    - - - - -
    inchesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
    dirthe direction we want to travel forward and backward
    max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
    -
    -
    -

    Autonomously drive the robot forward a certain distance

    -
    Parameters
    - - - - -
    inchesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
    dirthe direction we want to travel forward and backward
    max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
    -
    -
    -
    Returns
    true if we have finished driving to our point
    - -
    -
    - -

    ◆ drive_forward() [2/2]

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    bool TankDrive::drive_forward (double inches,
    directionType dir,
    Feedbackfeedback,
    double max_speed = 1 
    )
    -
    -

    Use odometry to drive forward a certain distance using a custom feedback controller

    -

    Returns whether or not the robot has reached it's destination.

    Parameters
    - - - - - -
    inchesthe distance to drive forward
    dirthe direction we want to travel forward and backward
    feedbackthe custom feedback controller we will use to travel. controls the rate at which we accelerate and drive.
    max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
    -
    -
    -
    Returns
    true when we have reached our target distance
    -

    Use odometry to drive forward a certain distance using a custom feedback controller

    -

    Returns whether or not the robot has reached it's destination.

    Parameters
    - - - - - -
    inchesthe distance to drive forward
    dirthe direction we want to travel forward and backward
    feedbackthe custom feedback controller we will use to travel. controls the rate at which we accelerate and drive.
    max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
    -
    -
    - -
    -
    - -

    ◆ drive_tank()

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    void TankDrive::drive_tank (double left,
    double right,
    int power = 1,
    bool isdriver = false 
    )
    -
    -

    Drive the robot using differential style controls. left_motors controls the left motors, right_motors controls the right motors.

    -

    left_motors and right_motors are in "percent": -1.0 -> 1.0

    Parameters
    - - - - - -
    leftthe percent to run the left motors
    rightthe percent to run the right motors
    powermodifies the input velocities left^power, right^power
    isdriverdefault false. if true uses motor percentage. if false uses plain percentage of maximum voltage
    -
    -
    -

    Drive the robot using differential style controls. left_motors controls the left motors, right_motors controls the right motors.

    -

    left_motors and right_motors are in "percent": -1.0 -> 1.0

    - -
    -
    - -

    ◆ drive_to_point() [1/2]

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    bool TankDrive::drive_to_point (double x,
    double y,
    vex::directionType dir,
    double max_speed = 1 
    )
    -
    -

    Use odometry to automatically drive the robot to a point on the field. X and Y is the final point we want the robot. Here we use the default feedback controller from the drive_sys

    -

    Returns whether or not the robot has reached it's destination.

    Parameters
    - - - - - -
    xthe x position of the target
    ythe y position of the target
    dirthe direction we want to travel forward and backward
    max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
    -
    -
    -

    Use odometry to automatically drive the robot to a point on the field. X and Y is the final point we want the robot. Here we use the default feedback controller from the drive_sys

    -

    Returns whether or not the robot has reached it's destination.

    Parameters
    - - - - - -
    xthe x position of the target
    ythe y position of the target
    dirthe direction we want to travel forward and backward
    max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
    -
    -
    -
    Returns
    true if we have reached our target point
    - -
    -
    - -

    ◆ drive_to_point() [2/2]

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    bool TankDrive::drive_to_point (double x,
    double y,
    vex::directionType dir,
    Feedbackfeedback,
    double max_speed = 1 
    )
    -
    -

    Use odometry to automatically drive the robot to a point on the field. X and Y is the final point we want the robot.

    -

    Returns whether or not the robot has reached it's destination.

    Parameters
    - - - - - - -
    xthe x position of the target
    ythe y position of the target
    dirthe direction we want to travel forward and backward
    feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
    max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
    -
    -
    -

    Use odometry to automatically drive the robot to a point on the field. X and Y is the final point we want the robot.

    -

    Returns whether or not the robot has reached it's destination.

    Parameters
    - - - - - - -
    xthe x position of the target
    ythe y position of the target
    dirthe direction we want to travel forward and backward
    feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
    max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
    -
    -
    -
    Returns
    true if we have reached our target point
    - -
    -
    - -

    ◆ modify_inputs()

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - -
    double TankDrive::modify_inputs (double input,
    int power = 2 
    )
    -
    -static
    -
    -

    Create a curve for the inputs, so that drivers have more control at lower speeds. Curves are exponential, with the default being squaring the inputs.

    -
    Parameters
    - - - -
    inputthe input before modification
    powerthe power to raise input to
    -
    -
    -
    Returns
    input ^ power (accounts for negative inputs and odd numbered powers)
    -

    Modify the inputs from the controller by squaring / cubing, etc Allows for better control of the robot at slower speeds

    Parameters
    - - - -
    inputthe input signal -1 -> 1
    powerthe power to raise the signal to
    -
    -
    -
    Returns
    input^power accounting for any sign issues that would arise with this naive solution
    - -
    -
    - -

    ◆ pure_pursuit()

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    bool TankDrive::pure_pursuit (std::vector< PurePursuit::hermite_pointpath,
    directionType dir,
    double radius,
    double res,
    Feedbackfeedback,
    double max_speed = 1 
    )
    -
    -

    Follow a hermite curve using the pure pursuit algorithm.

    -
    Parameters
    - - - - - - - -
    pathThe hermite curve for the robot to take. Must have 2 or more points.
    dirWhether the robot should move forward or backwards
    radiusHow the pure pursuit radius, in inches, for finding the lookahead point
    resThe number of points to use along the path; the hermite curve is split up into "res" individual points.
    feedbackThe feedback controller to use
    max_speedRobot's maximum speed throughout the path, between 0 and 1.0
    -
    -
    -
    Returns
    true when we reach the end of the path
    - -
    -
    - -

    ◆ reset_auto()

    - -
    -
    - - - - - - - -
    void TankDrive::reset_auto ()
    -
    -

    Reset the initialization for autonomous drive functions

    - -
    -
    - -

    ◆ stop()

    - -
    -
    - - - - - - - -
    void TankDrive::stop ()
    -
    -

    Stops rotation of all the motors using their "brake mode"

    - -
    -
    - -

    ◆ turn_degrees() [1/2]

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    bool TankDrive::turn_degrees (double degrees,
    double max_speed = 1 
    )
    -
    -

    Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed of percent_speed (-1.0 -> 1.0)

    -

    Uses the defualt turning feedback of the drive system.

    -
    Parameters
    - - - -
    degreesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
    max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
    -
    -
    -

    Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed of percent_speed (-1.0 -> 1.0)

    -

    Uses the defualt turning feedback of the drive system.

    -
    Parameters
    - - - -
    degreesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
    max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
    -
    -
    -
    Returns
    true if we turned te target number of degrees
    - -
    -
    - -

    ◆ turn_degrees() [2/2]

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - -
    bool TankDrive::turn_degrees (double degrees,
    Feedbackfeedback,
    double max_speed = 1 
    )
    -
    -

    Autonomously turn the robot X degrees counterclockwise (negative for clockwise), with a maximum motor speed of percent_speed (-1.0 -> 1.0)

    -

    Uses PID + Feedforward for it's control.

    -
    Parameters
    - - - - -
    degreesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
    feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
    max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
    -
    -
    -

    Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed of percent_speed (-1.0 -> 1.0)

    -

    Uses the specified feedback for it's control.

    -
    Parameters
    - - - - -
    degreesdegrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw
    feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
    max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
    -
    -
    -
    Returns
    true if we have turned our target number of degrees
    - -
    -
    - -

    ◆ turn_to_heading() [1/2]

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    bool TankDrive::turn_to_heading (double heading_deg,
    double max_speed = 1 
    )
    -
    -

    Turn the robot in place to an exact heading relative to the field. 0 is forward. Uses the defualt turn feedback of the drive system

    -
    Parameters
    - - - -
    heading_degthe heading to which we will turn
    max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
    -
    -
    -

    Turn the robot in place to an exact heading relative to the field. 0 is forward. Uses the defualt turn feedback of the drive system

    -
    Parameters
    - - - -
    heading_degthe heading to which we will turn
    max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
    -
    -
    -
    Returns
    true if we have reached our target heading
    - -
    -
    - -

    ◆ turn_to_heading() [2/2]

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - -
    bool TankDrive::turn_to_heading (double heading_deg,
    Feedbackfeedback,
    double max_speed = 1 
    )
    -
    -

    Turn the robot in place to an exact heading relative to the field. 0 is forward.

    -
    Parameters
    - - - - -
    heading_degthe heading to which we will turn
    feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
    max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
    -
    -
    -

    Turn the robot in place to an exact heading relative to the field. 0 is forward.

    -
    Parameters
    - - - - -
    heading_degthe heading to which we will turn
    feedbackthe feedback controller we will use to travel. controls the rate at which we accelerate and drive.
    max_speedthe maximum percentage of robot speed at which the robot will travel. 1 = full power
    -
    -
    -
    Returns
    true if we have reached our target heading
    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/subsystems/tank_drive.h
    • -
    • src/subsystems/tank_drive.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classTrapezoidProfile-members.html b/documentation/html/classTrapezoidProfile-members.html deleted file mode 100644 index 6e7caba..0000000 --- a/documentation/html/classTrapezoidProfile-members.html +++ /dev/null @@ -1,90 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    TrapezoidProfile Member List
    -
    -
    - -

    This is the complete list of members for TrapezoidProfile, including all inherited members.

    - - - - - - - -
    calculate(double time_s)TrapezoidProfile
    get_movement_time()TrapezoidProfile
    set_accel(double accel)TrapezoidProfile
    set_endpts(double start, double end)TrapezoidProfile
    set_max_v(double max_v)TrapezoidProfile
    TrapezoidProfile(double max_v, double accel)TrapezoidProfile
    - - - - diff --git a/documentation/html/classTrapezoidProfile.html b/documentation/html/classTrapezoidProfile.html deleted file mode 100644 index 0847ad1..0000000 --- a/documentation/html/classTrapezoidProfile.html +++ /dev/null @@ -1,290 +0,0 @@ - - - - - - - -RIT VEXU Core API: TrapezoidProfile Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    TrapezoidProfile Class Reference
    -
    -
    - -

    #include <trapezoid_profile.h>

    - - - - - - - - - - - - - - - - -

    -Public Member Functions

     TrapezoidProfile (double max_v, double accel)
     Construct a new Trapezoid Profile object.
     
    motion_t calculate (double time_s)
     Run the trapezoidal profile based on the time that's ellapsed.
     
    void set_endpts (double start, double end)
     
    void set_accel (double accel)
     
    void set_max_v (double max_v)
     
    double get_movement_time ()
     
    -

    Detailed Description

    -

    Trapezoid Profile

    -

    This is a motion profile defined by an acceleration, maximum velocity, start point and end point. Using this information, a parametric function is generated, with a period of acceleration, constant velocity, and deceleration. The velocity graph looks like a trapezoid, giving it it's name.

    -

    If the maximum velocity is set high enough, this will become a S-curve profile, with only acceleration and deceleration.

    -

    This class is designed for use in properly modelling the motion of the robots to create a feedfoward and target for PID. Acceleration and Maximum velocity should be measured on the robot and tuned down slightly to account for battery drop.

    -

    Here are the equations graphed for ease of understanding: https://www.desmos.com/calculator/rkm3ivu1yk

    -
    Author
    Ryan McGee
    -
    Date
    7/12/2022
    -

    Constructor & Destructor Documentation

    - -

    ◆ TrapezoidProfile()

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    TrapezoidProfile::TrapezoidProfile (double max_v,
    double accel 
    )
    -
    - -

    Construct a new Trapezoid Profile object.

    -
    Parameters
    - - - -
    max_vMaximum velocity the robot can run at
    accelMaximum acceleration of the robot
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ calculate()

    - -
    -
    - - - - - - - - -
    motion_t TrapezoidProfile::calculate (double time_s)
    -
    - -

    Run the trapezoidal profile based on the time that's ellapsed.

    -
    Parameters
    - - -
    time_sTime since start of movement
    -
    -
    -
    Returns
    motion_t Position, velocity and acceleration
    -
    Parameters
    - - -
    time_sTime since start of movement
    -
    -
    -
    Returns
    motion_t Position, velocity and acceleration
    - -
    -
    - -

    ◆ get_movement_time()

    - -
    -
    - - - - - - - -
    double TrapezoidProfile::get_movement_time ()
    -
    -

    uses the kinematic equations to and specified accel and max_v to figure out how long moving along the profile would take

    Returns
    the time the path will take to travel
    - -
    -
    - -

    ◆ set_accel()

    - -
    -
    - - - - - - - - -
    void TrapezoidProfile::set_accel (double accel)
    -
    -

    set_accel sets the acceleration this profile will use (the left and right legs of the trapezoid)

    Parameters
    - - -
    accelthe acceleration amount to use
    -
    -
    - -
    -
    - -

    ◆ set_endpts()

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    void TrapezoidProfile::set_endpts (double start,
    double end 
    )
    -
    -

    set_endpts defines a start and end position

    Parameters
    - - - -
    startthe starting position of the path
    endthe ending position of the path
    -
    -
    - -
    -
    - -

    ◆ set_max_v()

    - -
    -
    - - - - - - - - -
    void TrapezoidProfile::set_max_v (double max_v)
    -
    -

    sets the maximum velocity for the profile (the height of the top of the trapezoid)

    Parameters
    - - -
    max_vthe maximum velocity the robot can travel at
    -
    -
    - -
    -
    -
    The documentation for this class was generated from the following files: -
    - - - - diff --git a/documentation/html/classTurnDegreesCommand-members.html b/documentation/html/classTurnDegreesCommand-members.html deleted file mode 100644 index 70f2a65..0000000 --- a/documentation/html/classTurnDegreesCommand-members.html +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    TurnDegreesCommand Member List
    -
    -
    - -

    This is the complete list of members for TurnDegreesCommand, including all inherited members.

    - - - - - - -
    on_timeout() overrideTurnDegreesCommandvirtual
    run() overrideTurnDegreesCommandvirtual
    timeout_secondsAutoCommand
    TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed=1)TurnDegreesCommand
    withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
    - - - - diff --git a/documentation/html/classTurnDegreesCommand.html b/documentation/html/classTurnDegreesCommand.html deleted file mode 100644 index 79bf994..0000000 --- a/documentation/html/classTurnDegreesCommand.html +++ /dev/null @@ -1,233 +0,0 @@ - - - - - - - -RIT VEXU Core API: TurnDegreesCommand Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    TurnDegreesCommand Class Reference
    -
    -
    - -

    #include <drive_commands.h>

    -
    -Inheritance diagram for TurnDegreesCommand:
    -
    -
    - - -AutoCommand - -
    - - - - - - - - - - - - - - - -

    -Public Member Functions

     TurnDegreesCommand (TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed=1)
     
    bool run () override
     
    void on_timeout () override
     
    - Public Member Functions inherited from AutoCommand
    virtual bool run ()
     
    virtual void on_timeout ()
     
    -AutoCommandwithTimeout (double t_seconds)
     
    - - - - -

    -Additional Inherited Members

    - Public Attributes inherited from AutoCommand
    double timeout_seconds = 10.0
     
    -

    Detailed Description

    -

    AutoCommand wrapper class for the turn_degrees function in the TankDrive class

    -

    Constructor & Destructor Documentation

    - -

    ◆ TurnDegreesCommand()

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    TurnDegreesCommand::TurnDegreesCommand (TankDrivedrive_sys,
    Feedbackfeedback,
    double degrees,
    double max_speed = 1 
    )
    -
    -

    Construct a TurnDegreesCommand Command

    Parameters
    - - - - - -
    drive_systhe drive system we are commanding
    feedbackthe feedback controller we are using to execute the turn
    degreeshow many degrees to rotate
    max_speed0 -> 1 percentage of the drive systems speed to drive at
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ on_timeout()

    - -
    -
    - - - - - -
    - - - - - - - -
    void TurnDegreesCommand::on_timeout ()
    -
    -overridevirtual
    -
    -

    Cleans up drive system if we time out before finishing

    -

    reset the drive system if we timeout

    - -

    Reimplemented from AutoCommand.

    - -
    -
    - -

    ◆ run()

    - -
    -
    - - - - - -
    - - - - - - - -
    bool TurnDegreesCommand::run ()
    -
    -overridevirtual
    -
    -

    Run turn_degrees Overrides run from AutoCommand

    Returns
    true when execution is complete, false otherwise
    - -

    Reimplemented from AutoCommand.

    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/utils/command_structure/drive_commands.h
    • -
    • src/utils/command_structure/drive_commands.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classTurnDegreesCommand.png b/documentation/html/classTurnDegreesCommand.png deleted file mode 100644 index fff51ee3c144b350062b9ba92a57f7b716a5cfbe..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 614 zcmeAS@N?(olHy`uVBq!ia0vp^y+9nm!3-pY71+{%lyrbki0l9V|AEXGZ@!lHA6jl< zpjjX>{mhF42Mz$mgC|{H0hHq`3GxeO0P?}WoN4wI1_s8Do-U3d6^w7^Ud(%}AmFMm zuDR>~|D&Zm6348!l)Z{wcy)`Nn1R6@0fqG^ET5-3sGW4>ke>8~6Nq;vO-`G-NhTfbG$HYqNi(4_n*&R5}0swWa1;PrL|>^4<^hbn?FUIp1b}`;-`*Y&r z7k8fh$mlK|{e9Pr&O3Kaw$FS!yDp*a?6r0MpJz(V{x$Q}cVBBOFQfBv63;%Ko1zl? zR6q8C{EZvdu9M^*Pu{w-_PzHd)ko$rlWGpRO{$r;*;8|A=ntkC-V%?01`n12Qv`#j LtDnm{r-UW|-_Ij= diff --git a/documentation/html/classTurnToHeadingCommand-members.html b/documentation/html/classTurnToHeadingCommand-members.html deleted file mode 100644 index acb092b..0000000 --- a/documentation/html/classTurnToHeadingCommand-members.html +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    TurnToHeadingCommand Member List
    -
    -
    - -

    This is the complete list of members for TurnToHeadingCommand, including all inherited members.

    - - - - - - -
    on_timeout() overrideTurnToHeadingCommandvirtual
    run() overrideTurnToHeadingCommandvirtual
    timeout_secondsAutoCommand
    TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed=1)TurnToHeadingCommand
    withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
    - - - - diff --git a/documentation/html/classTurnToHeadingCommand.html b/documentation/html/classTurnToHeadingCommand.html deleted file mode 100644 index 0e0896b..0000000 --- a/documentation/html/classTurnToHeadingCommand.html +++ /dev/null @@ -1,233 +0,0 @@ - - - - - - - -RIT VEXU Core API: TurnToHeadingCommand Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    TurnToHeadingCommand Class Reference
    -
    -
    - -

    #include <drive_commands.h>

    -
    -Inheritance diagram for TurnToHeadingCommand:
    -
    -
    - - -AutoCommand - -
    - - - - - - - - - - - - - - - -

    -Public Member Functions

     TurnToHeadingCommand (TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed=1)
     
    bool run () override
     
    void on_timeout () override
     
    - Public Member Functions inherited from AutoCommand
    virtual bool run ()
     
    virtual void on_timeout ()
     
    -AutoCommandwithTimeout (double t_seconds)
     
    - - - - -

    -Additional Inherited Members

    - Public Attributes inherited from AutoCommand
    double timeout_seconds = 10.0
     
    -

    Detailed Description

    -

    AutoCommand wrapper class for the turn_to_heading() function in the TankDrive class

    -

    Constructor & Destructor Documentation

    - -

    ◆ TurnToHeadingCommand()

    - -
    -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    TurnToHeadingCommand::TurnToHeadingCommand (TankDrivedrive_sys,
    Feedbackfeedback,
    double heading_deg,
    double max_speed = 1 
    )
    -
    -

    Construct a TurnToHeadingCommand Command

    Parameters
    - - - - - -
    drive_systhe drive system we are commanding
    feedbackthe feedback controller we are using to execute the drive
    heading_degthe heading to turn to in degrees
    max_speed0 -> 1 percentage of the drive systems speed to drive at
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ on_timeout()

    - -
    -
    - - - - - -
    - - - - - - - -
    void TurnToHeadingCommand::on_timeout ()
    -
    -overridevirtual
    -
    -

    Cleans up drive system if we time out before finishing

    -

    reset the drive system if we don't hit our target

    - -

    Reimplemented from AutoCommand.

    - -
    -
    - -

    ◆ run()

    - -
    -
    - - - - - -
    - - - - - - - -
    bool TurnToHeadingCommand::run ()
    -
    -overridevirtual
    -
    -

    Run turn_to_heading Overrides run from AutoCommand

    Returns
    true when execution is complete, false otherwise
    - -

    Reimplemented from AutoCommand.

    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/utils/command_structure/drive_commands.h
    • -
    • src/utils/command_structure/drive_commands.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classTurnToHeadingCommand.png b/documentation/html/classTurnToHeadingCommand.png deleted file mode 100644 index 5bb95c50a13fe6406ea6055259fd4067906bdb1f..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 624 zcmV-$0+0QPP)54J0000RP)t-s|Ns90 z008Lh^>vTJr#LVva2S`&=)l0h|Ns9}lGCUF000SeQchC<|NsC0|NsC0Hv*f~0005| zNklhD_lj|Z|XTVOwybpVq50e?}Eq!m{qNh_{Kl2%-eB&{rJF~&G00PsCt05B)> zs=Z#*y3MP$n9b@ov6`Py0I=g~0AR({0Kkf?0e}@(0{|vH2|>U zY5-ux)d0YXs{w$O|3)o@5at9yl4iu!B*}`aNs^VUmJWp^4GfXgU6MwY#t-cW!%ETt zse7|(#{;yHb2Ulo*&1zb2WsnOXZveK_NT8cX*J4MTD6>28tUq$amxg0${c9YPSw`L zlH5d!T63SA`mZLxP2Uu{N(nS+=c`uf)$-P>OE?(5nRjYZ=*!0^y{A^jO8dJLy`we` z@CCJT%A0EM{g2hkZvR>B<6i3;>Zq61j`mtUA@6EuCp2yA?z!_(%fD+SJxFay1B_`8 zzYTsj^kZtxrjeu@Jhy7*_miZq`~$CdNtz5-lO!v1tA!B4l>7m49De7pStqgp0000< KMNUMnLSTa4eJz~; diff --git a/documentation/html/classVector2D-members.html b/documentation/html/classVector2D-members.html deleted file mode 100644 index dae6379..0000000 --- a/documentation/html/classVector2D-members.html +++ /dev/null @@ -1,95 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    Vector2D Member List
    -
    -
    - -

    This is the complete list of members for Vector2D, including all inherited members.

    - - - - - - - - - - - - -
    get_dir() constVector2D
    get_mag() constVector2D
    get_x() constVector2D
    get_y() constVector2D
    normalize()Vector2D
    operator*(const double &x)Vector2D
    operator+(const Vector2D &other)Vector2D
    operator-(const Vector2D &other)Vector2D
    point()Vector2D
    Vector2D(double dir, double mag)Vector2D
    Vector2D(point_t p)Vector2D
    - - - - diff --git a/documentation/html/classVector2D.html b/documentation/html/classVector2D.html deleted file mode 100644 index 8ed6b49..0000000 --- a/documentation/html/classVector2D.html +++ /dev/null @@ -1,378 +0,0 @@ - - - - - - - -RIT VEXU Core API: Vector2D Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    Vector2D Class Reference
    -
    -
    - -

    #include <vector2d.h>

    - - - - -

    -Classes

    struct  point_t
     
    - - - - - - - - - - - - - - - - - - - - - - - -

    -Public Member Functions

     Vector2D (double dir, double mag)
     
     Vector2D (point_t p)
     
    double get_dir () const
     
    double get_mag () const
     
    double get_x () const
     
    double get_y () const
     
    Vector2D normalize ()
     
    Vector2D::point_t point ()
     
    Vector2D operator* (const double &x)
     
    Vector2D operator+ (const Vector2D &other)
     
    Vector2D operator- (const Vector2D &other)
     
    -

    Detailed Description

    -

    Vector2D is an x,y pair Used to represent 2D locations on the field. It can also be treated as a direction and magnitude

    -

    Constructor & Destructor Documentation

    - -

    ◆ Vector2D() [1/2]

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    Vector2D::Vector2D (double dir,
    double mag 
    )
    -
    -

    Construct a vector object.

    -
    Parameters
    - - - -
    dirDirection, in radians. 'foward' is 0, clockwise positive when viewed from the top.
    magMagnitude.
    -
    -
    - -
    -
    - -

    ◆ Vector2D() [2/2]

    - -
    -
    - - - - - - - - -
    Vector2D::Vector2D (point_t p)
    -
    -

    Construct a vector object from a cartesian point.

    -
    Parameters
    - - -
    ppoint_t.x , point_t.y
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ get_dir()

    - -
    -
    - - - - - - - -
    double Vector2D::get_dir () const
    -
    -

    Get the direction of the vector, in radians. '0' is forward, clockwise positive when viewed from the top.

    -

    Use r2d() to convert.

    Returns
    the direction of the vetctor in radians
    -

    Get the direction of the vector, in radians. '0' is forward, clockwise positive when viewed from the top.

    -

    Use r2d() to convert.

    - -
    -
    - -

    ◆ get_mag()

    - -
    -
    - - - - - - - -
    double Vector2D::get_mag () const
    -
    -
    Returns
    the magnitude of the vector
    -

    Get the magnitude of the vector

    - -
    -
    - -

    ◆ get_x()

    - -
    -
    - - - - - - - -
    double Vector2D::get_x () const
    -
    -
    Returns
    the X component of the vector; positive to the right.
    -

    Get the X component of the vector; positive to the right.

    - -
    -
    - -

    ◆ get_y()

    - -
    -
    - - - - - - - -
    double Vector2D::get_y () const
    -
    -
    Returns
    the Y component of the vector, positive forward.
    -

    Get the Y component of the vector, positive forward.

    - -
    -
    - -

    ◆ normalize()

    - -
    -
    - - - - - - - -
    Vector2D Vector2D::normalize ()
    -
    -

    Changes the magnitude of the vector to 1

    Returns
    the normalized vector
    -

    Changes the magnetude of the vector to 1

    - -
    -
    - -

    ◆ operator*()

    - -
    -
    - - - - - - - - -
    Vector2D Vector2D::operator* (const double & x)
    -
    -

    Scales a Vector2D by a scalar with the * operator

    Parameters
    - - -
    xthe value to scale the vector by
    -
    -
    -
    Returns
    the this Vector2D scaled by x
    - -
    -
    - -

    ◆ operator+()

    - -
    -
    - - - - - - - - -
    Vector2D Vector2D::operator+ (const Vector2Dother)
    -
    -

    Add the components of two vectors together Vector2D + Vector2D = (this.x + other.x, this.y + other.y)

    Parameters
    - - -
    otherthe vector to add to this
    -
    -
    -
    Returns
    the sum of the vectors
    - -
    -
    - -

    ◆ operator-()

    - -
    -
    - - - - - - - - -
    Vector2D Vector2D::operator- (const Vector2Dother)
    -
    -

    Subtract the components of two vectors together Vector2D - Vector2D = (this.x - other.x, this.y - other.y)

    Parameters
    - - -
    otherthe vector to subtract from this
    -
    -
    -
    Returns
    the difference of the vectors
    - -
    -
    - -

    ◆ point()

    - -
    -
    - - - - - - - -
    Vector2D::point_t Vector2D::point ()
    -
    -

    Returns a point from the vector

    Returns
    the point represented by the vector
    -

    Convert a direction and magnitude representation to an x, y representation

    Returns
    the x, y representation of the vector
    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/utils/vector2d.h
    • -
    • src/utils/vector2d.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classWaitUntilUpToSpeedCommand-members.html b/documentation/html/classWaitUntilUpToSpeedCommand-members.html deleted file mode 100644 index e4ef8cb..0000000 --- a/documentation/html/classWaitUntilUpToSpeedCommand-members.html +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    WaitUntilUpToSpeedCommand Member List
    -
    -
    - -

    This is the complete list of members for WaitUntilUpToSpeedCommand, including all inherited members.

    - - - - - - -
    on_timeout()AutoCommandinlinevirtual
    run() overrideWaitUntilUpToSpeedCommandvirtual
    timeout_secondsAutoCommand
    WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshold_rpm)WaitUntilUpToSpeedCommand
    withTimeout(double t_seconds) (defined in AutoCommand)AutoCommandinline
    - - - - diff --git a/documentation/html/classWaitUntilUpToSpeedCommand.html b/documentation/html/classWaitUntilUpToSpeedCommand.html deleted file mode 100644 index 157edc8..0000000 --- a/documentation/html/classWaitUntilUpToSpeedCommand.html +++ /dev/null @@ -1,188 +0,0 @@ - - - - - - - -RIT VEXU Core API: WaitUntilUpToSpeedCommand Class Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    WaitUntilUpToSpeedCommand Class Reference
    -
    -
    - -

    #include <flywheel_commands.h>

    -
    -Inheritance diagram for WaitUntilUpToSpeedCommand:
    -
    -
    - - -AutoCommand - -
    - - - - - - - - - - - - - -

    -Public Member Functions

     WaitUntilUpToSpeedCommand (Flywheel &flywheel, int threshold_rpm)
     
    bool run () override
     
    - Public Member Functions inherited from AutoCommand
    virtual bool run ()
     
    virtual void on_timeout ()
     
    -AutoCommandwithTimeout (double t_seconds)
     
    - - - - -

    -Additional Inherited Members

    - Public Attributes inherited from AutoCommand
    double timeout_seconds = 10.0
     
    -

    Detailed Description

    -

    AutoCommand that listens to the Flywheel and waits until it is at its target speed +/- the specified threshold

    -

    Constructor & Destructor Documentation

    - -

    ◆ WaitUntilUpToSpeedCommand()

    - -
    -
    - - - - - - - - - - - - - - - - - - -
    WaitUntilUpToSpeedCommand::WaitUntilUpToSpeedCommand (Flywheelflywheel,
    int threshold_rpm 
    )
    -
    -

    Creat a WaitUntilUpToSpeedCommand

    Parameters
    - - - -
    flywheelthe flywheel system we are commanding
    threshold_rpmthe threshold over and under the flywheel target RPM that we define to be acceptable
    -
    -
    - -
    -
    -

    Member Function Documentation

    - -

    ◆ run()

    - -
    -
    - - - - - -
    - - - - - - - -
    bool WaitUntilUpToSpeedCommand::run ()
    -
    -overridevirtual
    -
    -

    Run spin_manual Overrides run from AutoCommand

    Returns
    true when execution is complete, false otherwise
    - -

    Reimplemented from AutoCommand.

    - -
    -
    -
    The documentation for this class was generated from the following files:
      -
    • include/utils/command_structure/flywheel_commands.h
    • -
    • src/utils/command_structure/flywheel_commands.cpp
    • -
    -
    - - - - diff --git a/documentation/html/classWaitUntilUpToSpeedCommand.png b/documentation/html/classWaitUntilUpToSpeedCommand.png deleted file mode 100644 index 0783fa1dbb2baf02213f965b941a9170b40144f3..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 660 zcmeAS@N?(olHy`uVBq!ia0vp^TYxx#gBeJ+A6q{KNJ$6ygt-3y{~ySF@#br3|Doj; z2ATyD)6cv(aNqz?Jb2RO6+k)8k|4ie1|S~{%$a6iVPIgA_jGX#sbG9N_jcZE1p(LZ zIo=ol{nxki+mWo^d%4VS;GS!exgv8nT{qdY^u2ubw|(0(8)rLc-gmBD##(gJch`^9RT07(PuuTISlM{# z^Lx+9X3J#W+}iE={PDNWl2@!V}R)>2o0VD=hK6)I34WlfUdG&}l~*8sZV0+$#bIC?NQuq*O1$Pp4);GLGXnsM@ytsI%2pA?p;o@~~t ztryAi^;$kPxz_IL+Q|3`OFFOo?sl7G5)?DvJN&5UuPy&n{(G%BS912()RHL1YMav+ zz6W*nXwQ9h`}LD`sTV}fct^>XHZ1gCmviyi#a+GCyLP6iSx#Pd<$AgN%dMOJ>@&>s z^kY}a7dbyO_}p3YtA11YbMu+6)L+^hJXlu6b7@lVOM}lhy~1CXIPFunEjh(}t?>R7 zyDjz}{g>iw7+Oa|D{PKbJy29tGrC-%=DD{vHH@aC%zuulh_q?J>}k9N=xhh a$Y1h(^5L01H*W*e4}+(xpUXO@geCx{3_%6} diff --git a/documentation/html/classes.html b/documentation/html/classes.html deleted file mode 100644 index b8374fd..0000000 --- a/documentation/html/classes.html +++ /dev/null @@ -1,132 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Index - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Class Index
    -
    - - - - - diff --git a/documentation/html/closed.png b/documentation/html/closed.png deleted file mode 100644 index 98cc2c909da37a6df914fbf67780eebd99c597f5..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 132 zcmeAS@N?(olHy`uVBq!ia0vp^oFL4>1|%O$WD@{V-kvUwAr*{o@8{^CZMh(5KoB^r_<4^zF@3)Cp&&t3hdujKf f*?bjBoY!V+E))@{xMcbjXe@)LtDnm{r-UW|*e5JT diff --git a/documentation/html/command__controller_8h_source.html b/documentation/html/command__controller_8h_source.html deleted file mode 100644 index 553e9c3..0000000 --- a/documentation/html/command__controller_8h_source.html +++ /dev/null @@ -1,113 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/command_structure/command_controller.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    command_controller.h
    -
    -
    -
    1
    -
    10#pragma once
    -
    11
    -
    12#include <queue>
    -
    13#include "../core/include/utils/command_structure/auto_command.h"
    -
    14
    - -
    16 public:
    -
    17
    -
    23 void add(AutoCommand *cmd, double timeout_seconds = 10.0);
    -
    24
    -
    29 void add(std::vector<AutoCommand *> cmds);
    -
    30
    -
    37 void add_delay(int ms);
    -
    38
    -
    43 void run();
    - -
    50
    -
    51 private:
    -
    52 std::queue<AutoCommand*> command_queue;
    -
    53 bool command_timed_out = false;
    -
    54};
    -
    Definition: auto_command.h:11
    -
    Definition: command_controller.h:15
    -
    void run()
    Definition: command_controller.cpp:48
    -
    bool last_command_timed_out()
    Definition: command_controller.cpp:94
    -
    void add(AutoCommand *cmd, double timeout_seconds=10.0)
    Definition: command_controller.cpp:18
    -
    void add_delay(int ms)
    Definition: command_controller.cpp:39
    -
    - - - - diff --git a/documentation/html/custom__encoder_8h_source.html b/documentation/html/custom__encoder_8h_source.html deleted file mode 100644 index e3d7ae4..0000000 --- a/documentation/html/custom__encoder_8h_source.html +++ /dev/null @@ -1,115 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/subsystems/custom_encoder.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    custom_encoder.h
    -
    -
    -
    1#pragma once
    -
    2#include "vex.h"
    -
    3
    -
    8class CustomEncoder : public vex::encoder
    -
    9{
    -
    10 typedef vex::encoder super;
    -
    11
    -
    12 public:
    -
    18 CustomEncoder(vex::triport::port &port, double ticks_per_rev);
    -
    19
    -
    25 void setRotation(double val, vex::rotationUnits units);
    -
    26
    -
    32 void setPosition(double val, vex::rotationUnits units);
    -
    33
    -
    39 double rotation(vex::rotationUnits units);
    -
    40
    -
    46 double position(vex::rotationUnits units);
    -
    47
    -
    53 double velocity(vex::velocityUnits units);
    -
    54
    -
    55
    -
    56 private:
    -
    57 double tick_scalar;
    -
    58};
    -
    Definition: custom_encoder.h:9
    -
    void setPosition(double val, vex::rotationUnits units)
    Definition: custom_encoder.cpp:15
    -
    double rotation(vex::rotationUnits units)
    Definition: custom_encoder.cpp:20
    -
    double velocity(vex::velocityUnits units)
    Definition: custom_encoder.cpp:36
    -
    double position(vex::rotationUnits units)
    Definition: custom_encoder.cpp:28
    -
    void setRotation(double val, vex::rotationUnits units)
    Definition: custom_encoder.cpp:10
    -
    - - - - diff --git a/documentation/html/delay__command_8h_source.html b/documentation/html/delay__command_8h_source.html deleted file mode 100644 index 19814a4..0000000 --- a/documentation/html/delay__command_8h_source.html +++ /dev/null @@ -1,107 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/command_structure/delay_command.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    delay_command.h
    -
    -
    -
    1
    -
    8#pragma once
    -
    9
    -
    10#include "../core/include/utils/command_structure/auto_command.h"
    -
    11
    - -
    13 public:
    -
    18 DelayCommand(int ms): ms(ms) {}
    -
    19
    -
    25 bool run() override {
    -
    26 vexDelay(ms);
    -
    27 return true;
    -
    28 }
    -
    29
    -
    30 private:
    -
    31 // amount of milliseconds to wait
    -
    32 int ms;
    -
    33};
    -
    Definition: auto_command.h:11
    -
    Definition: delay_command.h:12
    -
    bool run() override
    Definition: delay_command.h:25
    -
    DelayCommand(int ms)
    Definition: delay_command.h:18
    -
    - - - - diff --git a/documentation/html/dir_313caf1132e152dd9b58bea13a4052ca.html b/documentation/html/dir_313caf1132e152dd9b58bea13a4052ca.html deleted file mode 100644 index 5ca5097..0000000 --- a/documentation/html/dir_313caf1132e152dd9b58bea13a4052ca.html +++ /dev/null @@ -1,91 +0,0 @@ - - - - - - - -RIT VEXU Core API: src/utils Directory Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    utils Directory Reference
    -
    -
    - - - - -

    -Directories

    directory  command_structure
     
    -
    - - - - diff --git a/documentation/html/dir_42a35307dcefecb9f25978d1dedb502f.html b/documentation/html/dir_42a35307dcefecb9f25978d1dedb502f.html deleted file mode 100644 index 68dae65..0000000 --- a/documentation/html/dir_42a35307dcefecb9f25978d1dedb502f.html +++ /dev/null @@ -1,91 +0,0 @@ - - - - - - - -RIT VEXU Core API: src/subsystems Directory Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    subsystems Directory Reference
    -
    -
    - - - - -

    -Directories

    directory  odometry
     
    -
    - - - - diff --git a/documentation/html/dir_68267d1309a1af8e8297ef4c3efbcdba.html b/documentation/html/dir_68267d1309a1af8e8297ef4c3efbcdba.html deleted file mode 100644 index 3971108..0000000 --- a/documentation/html/dir_68267d1309a1af8e8297ef4c3efbcdba.html +++ /dev/null @@ -1,93 +0,0 @@ - - - - - - - -RIT VEXU Core API: src Directory Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    src Directory Reference
    -
    -
    - - - - - - -

    -Directories

    directory  subsystems
     
    directory  utils
     
    -
    - - - - diff --git a/documentation/html/dir_821002d4f10779a80d4fb17bc32f21f1.html b/documentation/html/dir_821002d4f10779a80d4fb17bc32f21f1.html deleted file mode 100644 index 04d997a..0000000 --- a/documentation/html/dir_821002d4f10779a80d4fb17bc32f21f1.html +++ /dev/null @@ -1,120 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils Directory Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    utils Directory Reference
    -
    -
    - - - - -

    -Directories

    directory  command_structure
     
    - - - - - - - - - - - - - - - - - - - - - - - - - - - -

    -Files

    file  auto_chooser.h [code]
     
    file  feedback_base.h [code]
     
    file  feedforward.h [code]
     
    file  generic_auto.h [code]
     
    file  graph_drawer.h [code]
     
    file  math_util.h [code]
     
    file  motion_controller.h [code]
     
    file  moving_average.h [code]
     
    file  pid.h [code]
     
    file  pidff.h [code]
     
    file  pure_pursuit.h [code]
     
    file  trapezoid_profile.h [code]
     
    file  vector2d.h [code]
     
    -
    - - - - diff --git a/documentation/html/dir_883d6c53cd62ec60a5d421a7bc1a2629.html b/documentation/html/dir_883d6c53cd62ec60a5d421a7bc1a2629.html deleted file mode 100644 index fe41ce4..0000000 --- a/documentation/html/dir_883d6c53cd62ec60a5d421a7bc1a2629.html +++ /dev/null @@ -1,95 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/subsystems/odometry Directory Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    odometry Directory Reference
    -
    -
    - - - - - - - - -

    -Files

    file  odometry_3wheel.h [code]
     
    file  odometry_base.h [code]
     
    file  odometry_tank.h [code]
     
    -
    - - - - diff --git a/documentation/html/dir_8e84b5daa2b3f33b7b3fb9ecedbe5637.html b/documentation/html/dir_8e84b5daa2b3f33b7b3fb9ecedbe5637.html deleted file mode 100644 index 121f259..0000000 --- a/documentation/html/dir_8e84b5daa2b3f33b7b3fb9ecedbe5637.html +++ /dev/null @@ -1,106 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/subsystems Directory Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    subsystems Directory Reference
    -
    -
    - - - - -

    -Directories

    directory  odometry
     
    - - - - - - - - - - - - - -

    -Files

    file  custom_encoder.h [code]
     
    file  flywheel.h [code]
     
    file  lift.h [code]
     
    file  mecanum_drive.h [code]
     
    file  screen.h [code]
     
    file  tank_drive.h [code]
     
    -
    - - - - diff --git a/documentation/html/dir_ca1fd9fa48e5fdc0ddfbf442e09c4dab.html b/documentation/html/dir_ca1fd9fa48e5fdc0ddfbf442e09c4dab.html deleted file mode 100644 index fbc5eaf..0000000 --- a/documentation/html/dir_ca1fd9fa48e5fdc0ddfbf442e09c4dab.html +++ /dev/null @@ -1,85 +0,0 @@ - - - - - - - -RIT VEXU Core API: src/subsystems/odometry Directory Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    odometry Directory Reference
    -
    -
    -
    - - - - diff --git a/documentation/html/dir_d44c64559bbebec7f509842c48db8b23.html b/documentation/html/dir_d44c64559bbebec7f509842c48db8b23.html deleted file mode 100644 index b8ee575..0000000 --- a/documentation/html/dir_d44c64559bbebec7f509842c48db8b23.html +++ /dev/null @@ -1,98 +0,0 @@ - - - - - - - -RIT VEXU Core API: include Directory Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    include Directory Reference
    -
    -
    - - - - - - -

    -Directories

    directory  subsystems
     
    directory  utils
     
    - - - -

    -Files

    file  robot_specs.h [code]
     
    -
    - - - - diff --git a/documentation/html/dir_d9631e0f4b8929605c336e8f080acaa3.html b/documentation/html/dir_d9631e0f4b8929605c336e8f080acaa3.html deleted file mode 100644 index 00b6a4b..0000000 --- a/documentation/html/dir_d9631e0f4b8929605c336e8f080acaa3.html +++ /dev/null @@ -1,85 +0,0 @@ - - - - - - - -RIT VEXU Core API: src/utils/command_structure Directory Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    command_structure Directory Reference
    -
    -
    -
    - - - - diff --git a/documentation/html/dir_e0729c835bcfebced7012c88d9b3a1d3.html b/documentation/html/dir_e0729c835bcfebced7012c88d9b3a1d3.html deleted file mode 100644 index c393732..0000000 --- a/documentation/html/dir_e0729c835bcfebced7012c88d9b3a1d3.html +++ /dev/null @@ -1,99 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/command_structure Directory Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    command_structure Directory Reference
    -
    -
    - - - - - - - - - - - - -

    -Files

    file  auto_command.h [code]
     
    file  command_controller.h [code]
     
    file  delay_command.h [code]
     
    file  drive_commands.h [code]
     
    file  flywheel_commands.h [code]
     
    -
    - - - - diff --git a/documentation/html/doc.png b/documentation/html/doc.png deleted file mode 100644 index 17edabff95f7b8da13c9516a04efe05493c29501..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 746 zcmV7=@pnbNXRFEm&G8P!&WHG=d)>K?YZ1bzou)2{$)) zumDct!>4SyxL;zgaG>wy`^Hv*+}0kUfCrz~BCOViSb$_*&;{TGGn2^x9K*!Sf0=lV zpP=7O;GA0*Jm*tTYj$IoXvimpnV4S1Z5f$p*f$Db2iq2zrVGQUz~yq`ahn7ck(|CE z7Gz;%OP~J6)tEZWDzjhL9h2hdfoU2)Nd%T<5Kt;Y0XLt&<@6pQx!nw*5`@bq#?l*?3z{Hlzoc=Pr>oB5(9i6~_&-}A(4{Q$>c>%rV&E|a(r&;?i5cQB=} zYSDU5nXG)NS4HEs0it2AHe2>shCyr7`6@4*6{r@8fXRbTA?=IFVWAQJL&H5H{)DpM#{W(GL+Idzf^)uRV@oB8u$ z8v{MfJbTiiRg4bza<41NAzrl{=3fl_D+$t+^!xlQ8S}{UtY`e z;;&9UhyZqQRN%2pot{*Ei0*4~hSF_3AH2@fKU!$NSflS>{@tZpDT4`M2WRTTVH+D? z)GFlEGGHe?koB}i|1w45!BF}N_q&^HJ&-tyR{(afC6H7|aml|tBBbv}55C5DNP8p3 z)~jLEO4Z&2hZmP^i-e%(@d!(E|KRafiU8Q5u(wU((j8un3OR*Hvj+t diff --git a/documentation/html/docd.png b/documentation/html/docd.png deleted file mode 100644 index d7c94fda9bf08ecc02c7190d968452b7a2dbf04b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 756 zcmV1wr-rhpn+wxm%q2)IkAYsr{iGq<}_z5JCD4J;FN?6Qh;@TCubdp(_XdD-^ zG_#)IP7_z6hKNdx5^+FGArwLWTWCG!j+oKji?U!hxA#d-ljgkN`+e^@-P+RWG{Bx= z2iQyYTtEf*o~ySWrIVW}HWHi0_hd4~$E6Jx1U`>Owo}EYJ1O>iZvS?!z8}B}QwLMA zC3Keqf1c}K@?C`X>68b(EUzYUYAS&OH^VPteZLPr{S&|nQvp@6W4GH-1U8!u&7l~A zx~RUSNH+>7@q38W6!BzirtjLFCzc|XGx)EF#G%^pWION*k@?vP<2O>|XkCD3ujl%1 z{55JSVkw{~HbX>iEZ2%yJ2eHj5Yh8OTpzs0A2;tZ^x!#5D+y-es{k1&0|Ns9-|+Xt ziGiTsZ8(^nUo#wdTpIDkb-Zp(3|A*FzW}GZ5SQD-r^R`&X@`26E3W|GyrwDIZjtQ& z$g5f8Sv=VgVtDien@J(!^BK+#l;s-LgP--p7C;7;E!ysXcXK6?+9D>_-B(?Wm(U zQbNm-5TyYxIU=rs0+)!ixqzhuxw(AqKc3?KKX32{D~Qibp*r0x&Wux5-9WCMMRi3U zTd6dOCQlj>a;gr;gLwRKulT&(m@^L{&HkSC(qH05HSSf$YEhynGvH zWNez``Z8FJXE+BSg=%ak{OR z+Nylcb{?evLYLuE1_HngYw0g%LC#=$a@?4~Tx>F9295Q>9UJ|_6v-KMw;!YZSgGj@ zR8fRov=hJ#QvsO@xw*{0%zH@OKVEUrsummary { - list-style-type: none; -} - -details > summary::-webkit-details-marker { - display: none; -} - -details>summary::before { - content: "\25ba"; - padding-right:4px; - font-size: 80%; -} - -details[open]>summary::before { - content: "\25bc"; - padding-right:4px; - font-size: 80%; -} - -body { - scrollbar-color: var(--scrollbar-thumb-color) var(--scrollbar-background-color); -} - -::-webkit-scrollbar { - background-color: var(--scrollbar-background-color); - height: 12px; - width: 12px; -} -::-webkit-scrollbar-thumb { - border-radius: 6px; - box-shadow: inset 0 0 12px 12px var(--scrollbar-thumb-color); - border: solid 2px transparent; -} -::-webkit-scrollbar-corner { - background-color: var(--scrollbar-background-color); -} - diff --git a/documentation/html/doxygen.svg b/documentation/html/doxygen.svg deleted file mode 100644 index d42dad5..0000000 --- a/documentation/html/doxygen.svg +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/drive__commands_8h_source.html b/documentation/html/drive__commands_8h_source.html deleted file mode 100644 index 9f3d850..0000000 --- a/documentation/html/drive__commands_8h_source.html +++ /dev/null @@ -1,229 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/command_structure/drive_commands.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    drive_commands.h
    -
    -
    -
    1
    -
    19#pragma once
    -
    20
    -
    21#include "vex.h"
    -
    22#include "../core/include/utils/command_structure/auto_command.h"
    -
    23#include "../core/include/subsystems/tank_drive.h"
    -
    24
    -
    25using namespace vex;
    -
    26
    -
    27
    -
    28// ==== DRIVING ====
    -
    29
    - -
    36 public:
    -
    37 DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed=1);
    -
    38
    -
    44 bool run() override;
    -
    48 void on_timeout() override;
    -
    49
    -
    50 private:
    -
    51 // drive system to run the function on
    -
    52 TankDrive &drive_sys;
    -
    53
    -
    54 // feedback controller to use
    -
    55 Feedback &feedback;
    -
    56
    -
    57 // parameters for drive_forward
    -
    58 double inches;
    -
    59 directionType dir;
    -
    60 double max_speed;
    -
    61};
    -
    62
    - -
    68 public:
    -
    69 TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed = 1);
    -
    70
    -
    76 bool run() override;
    -
    80 void on_timeout() override;
    -
    81
    -
    82
    -
    83 private:
    -
    84 // drive system to run the function on
    -
    85 TankDrive &drive_sys;
    -
    86
    -
    87 // feedback controller to use
    -
    88 Feedback &feedback;
    -
    89
    -
    90 // parameters for turn_degrees
    -
    91 double degrees;
    -
    92 double max_speed;
    -
    93};
    -
    94
    - -
    100 public:
    -
    101 DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed = 1);
    -
    102 DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, Vector2D::point_t point, directionType dir, double max_speed=1);
    -
    103
    -
    109 bool run() override;
    -
    110
    -
    111 private:
    -
    112 // drive system to run the function on
    -
    113 TankDrive &drive_sys;
    -
    114
    -
    118 void on_timeout() override;
    -
    119
    -
    120
    -
    121 // feedback controller to use
    -
    122 Feedback &feedback;
    -
    123
    -
    124 // parameters for drive_to_point
    -
    125 double x;
    -
    126 double y;
    -
    127 directionType dir;
    -
    128 double max_speed;
    -
    129
    -
    130};
    -
    131
    - -
    138 public:
    -
    139 TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed = 1);
    -
    140
    -
    146 bool run() override;
    -
    150 void on_timeout() override;
    -
    151
    -
    152
    -
    153 private:
    -
    154 // drive system to run the function on
    -
    155 TankDrive &drive_sys;
    -
    156
    -
    157 // feedback controller to use
    -
    158 Feedback &feedback;
    -
    159
    -
    160 // parameters for turn_to_heading
    -
    161 double heading_deg;
    -
    162 double max_speed;
    -
    163};
    -
    164
    - -
    170 public:
    -
    171 DriveStopCommand(TankDrive &drive_sys);
    -
    172
    -
    178 bool run() override;
    -
    179
    -
    180 private:
    -
    181 // drive system to run the function on
    -
    182 TankDrive &drive_sys;
    -
    183};
    -
    184
    -
    185
    -
    186// ==== ODOMETRY ====
    -
    187
    - -
    193 public:
    - -
    200
    -
    206 bool run() override;
    -
    207
    -
    208 private:
    -
    209 // drive system with an odometry config
    -
    210 OdometryBase &odom;
    -
    211 position_t newpos;
    -
    212};
    -
    Definition: auto_command.h:11
    -
    Definition: drive_commands.h:35
    -
    void on_timeout() override
    Definition: drive_commands.cpp:47
    -
    bool run() override
    Definition: drive_commands.cpp:40
    -
    Definition: drive_commands.h:169
    -
    bool run() override
    Definition: drive_commands.cpp:164
    -
    Definition: drive_commands.h:99
    -
    bool run() override
    Definition: drive_commands.cpp:108
    -
    Definition: feedback_base.h:11
    -
    Definition: drive_commands.h:192
    -
    bool run() override
    Definition: drive_commands.cpp:178
    -
    Definition: odometry_base.h:33
    -
    static constexpr position_t zero_pos
    Definition: odometry_base.h:133
    -
    Definition: tank_drive.h:23
    -
    Definition: drive_commands.h:67
    -
    bool run() override
    Definition: drive_commands.cpp:68
    -
    void on_timeout() override
    Definition: drive_commands.cpp:74
    -
    Definition: drive_commands.h:137
    -
    void on_timeout() override
    Definition: drive_commands.cpp:141
    -
    bool run() override
    Definition: drive_commands.cpp:135
    -
    Definition: vector2d.h:21
    -
    Definition: odometry_base.h:14
    -
    - - - - diff --git a/documentation/html/dynsections.js b/documentation/html/dynsections.js deleted file mode 100644 index f579fbf..0000000 --- a/documentation/html/dynsections.js +++ /dev/null @@ -1,123 +0,0 @@ -/* - @licstart The following is the entire license notice for the JavaScript code in this file. - - The MIT License (MIT) - - Copyright (C) 1997-2020 by Dimitri van Heesch - - Permission is hereby granted, free of charge, to any person obtaining a copy of this software - and associated documentation files (the "Software"), to deal in the Software without restriction, - including without limitation the rights to use, copy, modify, merge, publish, distribute, - sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is - furnished to do so, subject to the following conditions: - - The above copyright notice and this permission notice shall be included in all copies or - substantial portions of the Software. - - THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING - BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, - DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - - @licend The above is the entire license notice for the JavaScript code in this file - */ -function toggleVisibility(linkObj) -{ - var base = $(linkObj).attr('id'); - var summary = $('#'+base+'-summary'); - var content = $('#'+base+'-content'); - var trigger = $('#'+base+'-trigger'); - var src=$(trigger).attr('src'); - if (content.is(':visible')===true) { - content.hide(); - summary.show(); - $(linkObj).addClass('closed').removeClass('opened'); - $(trigger).attr('src',src.substring(0,src.length-8)+'closed.png'); - } else { - content.show(); - summary.hide(); - $(linkObj).removeClass('closed').addClass('opened'); - $(trigger).attr('src',src.substring(0,src.length-10)+'open.png'); - } - return false; -} - -function updateStripes() -{ - $('table.directory tr'). - removeClass('even').filter(':visible:even').addClass('even'); - $('table.directory tr'). - removeClass('odd').filter(':visible:odd').addClass('odd'); -} - -function toggleLevel(level) -{ - $('table.directory tr').each(function() { - var l = this.id.split('_').length-1; - var i = $('#img'+this.id.substring(3)); - var a = $('#arr'+this.id.substring(3)); - if (l - - - - - - -RIT VEXU Core API: include/utils/feedback_base.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    feedback_base.h
    -
    -
    -
    1#pragma once
    -
    2
    - -
    11{
    -
    12public:
    -
    13 enum FeedbackType
    -
    14 {
    -
    15 PIDType,
    -
    16 FeedforwardType,
    -
    17 OtherType,
    -
    18 };
    -
    19
    -
    26 virtual void init(double start_pt, double set_pt) = 0;
    -
    27
    -
    34 virtual double update(double val) = 0;
    -
    35
    -
    39 virtual double get() = 0;
    -
    40
    -
    47 virtual void set_limits(double lower, double upper) = 0;
    -
    48
    -
    52 virtual bool is_on_target() = 0;
    -
    53
    -
    54 virtual Feedback::FeedbackType get_type()
    -
    55 {
    -
    56 return FeedbackType::OtherType;
    -
    57 }
    -
    58};
    -
    Definition: feedback_base.h:11
    -
    virtual void init(double start_pt, double set_pt)=0
    -
    virtual void set_limits(double lower, double upper)=0
    -
    virtual double get()=0
    -
    virtual double update(double val)=0
    -
    virtual bool is_on_target()=0
    -
    - - - - diff --git a/documentation/html/feedforward_8h_source.html b/documentation/html/feedforward_8h_source.html deleted file mode 100644 index 4b70867..0000000 --- a/documentation/html/feedforward_8h_source.html +++ /dev/null @@ -1,135 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/feedforward.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    feedforward.h
    -
    -
    -
    1#pragma once
    -
    2
    -
    3#include <math.h>
    -
    4#include <vector>
    -
    5#include "../core/include/utils/math_util.h"
    -
    6#include "../core/include/utils/moving_average.h"
    -
    7#include "vex.h"
    -
    8
    - -
    30{
    -
    31 public:
    -
    32
    -
    41 typedef struct
    -
    42 {
    -
    43 double kS;
    -
    44 double kV;
    -
    45 double kA;
    -
    46 double kG;
    - -
    48
    -
    49
    -
    54 FeedForward(ff_config_t &cfg) : cfg(cfg) {}
    -
    55
    -
    66 double calculate(double v, double a, double pid_ref=0.0)
    -
    67 {
    -
    68 double ks_sign = 0;
    -
    69 if(v != 0)
    -
    70 ks_sign = sign(v);
    -
    71 else if(pid_ref != 0)
    -
    72 ks_sign = sign(pid_ref);
    -
    73
    -
    74 return (cfg.kS * ks_sign) + (cfg.kV * v) + (cfg.kA * a) + cfg.kG;
    -
    75 }
    -
    76
    -
    77 private:
    -
    78
    -
    79 ff_config_t &cfg;
    -
    80
    -
    81};
    -
    82
    -
    83
    -
    91FeedForward::ff_config_t tune_feedforward(vex::motor_group &motor, double pct, double duration);
    -
    Definition: feedforward.h:30
    -
    double calculate(double v, double a, double pid_ref=0.0)
    Perform the feedforward calculation.
    Definition: feedforward.h:66
    -
    FeedForward(ff_config_t &cfg)
    Definition: feedforward.h:54
    -
    Definition: feedforward.h:42
    -
    double kG
    Definition: feedforward.h:46
    -
    double kA
    Definition: feedforward.h:45
    -
    double kS
    Definition: feedforward.h:43
    -
    double kV
    Definition: feedforward.h:44
    -
    - - - - diff --git a/documentation/html/files.html b/documentation/html/files.html deleted file mode 100644 index f100989..0000000 --- a/documentation/html/files.html +++ /dev/null @@ -1,118 +0,0 @@ - - - - - - - -RIT VEXU Core API: File List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    File List
    -
    -
    -
    Here is a list of all documented files with brief descriptions:
    -
    [detail level 1234]
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
      include
      subsystems
      odometry
     odometry_3wheel.h
     odometry_base.h
     odometry_tank.h
     custom_encoder.h
     flywheel.h
     lift.h
     mecanum_drive.h
     screen.h
     tank_drive.h
      utils
      command_structure
     auto_command.h
     command_controller.h
     delay_command.h
     drive_commands.h
     flywheel_commands.h
     auto_chooser.h
     feedback_base.h
     feedforward.h
     generic_auto.h
     graph_drawer.h
     math_util.h
     motion_controller.h
     moving_average.h
     pid.h
     pidff.h
     pure_pursuit.h
     trapezoid_profile.h
     vector2d.h
     robot_specs.h
    -
    -
    - - - - diff --git a/documentation/html/flywheel_8h_source.html b/documentation/html/flywheel_8h_source.html deleted file mode 100644 index e2532f6..0000000 --- a/documentation/html/flywheel_8h_source.html +++ /dev/null @@ -1,197 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/subsystems/flywheel.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    flywheel.h
    -
    -
    -
    1#pragma once
    -
    2/*********************************************************
    -
    3*
    -
    4* File: Flywheel.h
    -
    5* Purpose: Generalized flywheel class for Core.
    -
    6* Author: Chris Nokes
    -
    7*
    -
    8**********************************************************
    -
    9* EDIT HISTORY
    -
    10**********************************************************
    -
    11* 09/23/2022 <CRN> Reorganized, added documentation.
    -
    12* 09/23/2022 <CRN> Added functions elaborated on in .cpp.
    -
    13*********************************************************/
    -
    14#include "../core/include/utils/feedforward.h"
    -
    15#include "vex.h"
    -
    16#include "../core/include/robot_specs.h"
    -
    17#include "../core/include/utils/pid.h"
    -
    18#include <atomic>
    -
    19
    -
    20using namespace vex;
    -
    21
    - -
    30 enum FlywheelControlStyle{
    -
    31 PID_Feedforward,
    -
    32 Feedforward,
    -
    33 Take_Back_Half,
    -
    34 Bang_Bang,
    -
    35 };
    -
    36 public:
    -
    37
    -
    38 // CONSTRUCTORS, GETTERS, AND SETTERS
    -
    46 Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio);
    -
    47
    -
    54 Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio);
    -
    55
    -
    62 Flywheel(motor_group &motors, double tbh_gain, const double ratio);
    -
    63
    -
    69 Flywheel(motor_group &motors, const double ratio);
    -
    70
    -
    75 double getDesiredRPM();
    -
    76
    -
    81 bool isTaskRunning();
    -
    82
    -
    86 motor_group* getMotors();
    -
    87
    -
    91 double measureRPM();
    -
    92
    -
    96 double getRPM();
    -
    100 PID* getPID();
    -
    101
    -
    105 double getPIDValue();
    -
    106
    -
    110 double getFeedforwardValue();
    -
    111
    -
    115 double getTBHGain();
    -
    116
    -
    121 void setPIDTarget(double value);
    -
    122
    -
    127 void updatePID(double value);
    -
    128
    -
    129 // SPINNERS AND STOPPERS
    -
    130
    -
    137 void spin_raw(double speed, directionType dir=fwd);
    -
    138
    -
    145 void spin_manual(double speed, directionType dir=fwd);
    -
    146
    -
    152 void spinRPM(int rpm);
    -
    153
    -
    157 void stop();
    -
    158
    -
    159
    -
    163 void stopMotors();
    -
    164
    -
    168 void stopNonTasks();
    -
    169
    -
    170 private:
    -
    171
    -
    172 motor_group &motors; // motors that make up the flywheel
    -
    173 bool taskRunning = false; // is the task (thread but not) currently running?
    -
    174 PID pid; // PID on the flywheel
    -
    175 FeedForward ff; // FF constants for the flywheel
    -
    176 double TBH_gain; // TBH gain parameter for the flywheel
    -
    177 double ratio; // multiplies the velocity by this value
    -
    178 std::atomic<double> RPM; // Desired RPM of the flywheel.
    -
    179 task rpmTask; // task (thread but not) that handles spinning the wheel at a given RPM
    -
    180 FlywheelControlStyle control_style; // how the flywheel should be controlled
    -
    181 double smoothedRPM;
    -
    182 MovingAverage RPM_avger;
    -
    183 };
    -
    Definition: feedforward.h:30
    -
    Definition: flywheel.h:29
    -
    double getRPM()
    Definition: flywheel.cpp:91
    -
    void spin_manual(double speed, directionType dir=fwd)
    Definition: flywheel.cpp:250
    -
    double getPIDValue()
    Definition: flywheel.cpp:104
    -
    motor_group * getMotors()
    Definition: flywheel.cpp:78
    -
    double getDesiredRPM()
    Definition: flywheel.cpp:66
    -
    void setPIDTarget(double value)
    Definition: flywheel.cpp:127
    -
    void spin_raw(double speed, directionType dir=fwd)
    Definition: flywheel.cpp:240
    -
    void stopNonTasks()
    Definition: flywheel.cpp:311
    -
    void stop()
    Definition: flywheel.cpp:295
    -
    void stopMotors()
    Definition: flywheel.cpp:306
    -
    double getTBHGain()
    Definition: flywheel.cpp:119
    -
    bool isTaskRunning()
    Definition: flywheel.cpp:72
    -
    void spinRPM(int rpm)
    Definition: flywheel.cpp:259
    -
    void updatePID(double value)
    Definition: flywheel.cpp:133
    -
    PID * getPID()
    Definition: flywheel.cpp:98
    -
    double measureRPM()
    Definition: flywheel.cpp:84
    -
    double getFeedforwardValue()
    Definition: flywheel.cpp:110
    -
    Definition: moving_average.h:15
    -
    Definition: pid.h:24
    -
    Definition: feedforward.h:42
    -
    Definition: pid.h:41
    -
    - - - - diff --git a/documentation/html/flywheel__commands_8h_source.html b/documentation/html/flywheel__commands_8h_source.html deleted file mode 100644 index 67e2001..0000000 --- a/documentation/html/flywheel__commands_8h_source.html +++ /dev/null @@ -1,161 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/command_structure/flywheel_commands.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    flywheel_commands.h
    -
    -
    -
    1
    -
    7#pragma once
    -
    8
    -
    9#include "../core/include/subsystems/flywheel.h"
    -
    10#include "../core/include/utils/command_structure/auto_command.h"
    -
    11
    - -
    18 public:
    -
    24 SpinRPMCommand(Flywheel &flywheel, int rpm);
    -
    25
    -
    31 bool run() override;
    -
    32
    -
    33 private:
    -
    34 // Flywheel instance to run the function on
    -
    35 Flywheel &flywheel;
    -
    36
    -
    37 // parameters for spinRPM
    -
    38 int rpm;
    -
    39};
    -
    40
    - -
    46 public:
    -
    52 WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshold_rpm);
    -
    53
    -
    59 bool run() override;
    -
    60
    -
    61 private:
    -
    62 // Flywheel instance to run the function on
    -
    63 Flywheel &flywheel;
    -
    64
    -
    65 // if the actual speed is equal to the desired speed +/- this value, we are ready to fire
    -
    66 int threshold_rpm;
    -
    67};
    -
    68
    - -
    75 public:
    - -
    81
    -
    87 bool run() override;
    -
    88
    -
    89 private:
    -
    90 // Flywheel instance to run the function on
    -
    91 Flywheel &flywheel;
    -
    92};
    -
    93
    - -
    100 public:
    - -
    106
    -
    112 bool run() override;
    -
    113
    -
    114 private:
    -
    115 // Flywheel instance to run the function on
    -
    116 Flywheel &flywheel;
    -
    117};
    -
    118
    - - -
    126
    -
    132 bool run() override;
    -
    133
    -
    134 private:
    -
    135 // Flywheel instance to run the function on
    -
    136 Flywheel &flywheel;
    -
    137};
    -
    Definition: auto_command.h:11
    -
    Definition: flywheel_commands.h:74
    -
    bool run() override
    Definition: flywheel_commands.cpp:35
    -
    Definition: flywheel_commands.h:99
    -
    bool run() override
    Definition: flywheel_commands.cpp:44
    -
    Definition: flywheel_commands.h:124
    -
    Definition: flywheel.h:29
    -
    Definition: flywheel_commands.h:17
    -
    bool run() override
    Definition: flywheel_commands.cpp:13
    -
    Definition: flywheel_commands.h:45
    -
    bool run() override
    Definition: flywheel_commands.cpp:21
    -
    - - - - diff --git a/documentation/html/folderclosed.png b/documentation/html/folderclosed.png deleted file mode 100644 index bb8ab35edce8e97554e360005ee9fc5bffb36e66..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 616 zcmV-u0+;=XP)a9#ETzayK)T~Jw&MMH>OIr#&;dC}is*2Mqdf&akCc=O@`qC+4i z5Iu3w#1M@KqXCz8TIZd1wli&kkl2HVcAiZ8PUn5z_kG@-y;?yK06=cA0U%H0PH+kU zl6dp}OR(|r8-RG+YLu`zbI}5TlOU6ToR41{9=uz^?dGTNL;wIMf|V3`d1Wj3y!#6` zBLZ?xpKR~^2x}?~zA(_NUu3IaDB$tKma*XUdOZN~c=dLt_h_k!dbxm_*ibDM zlFX`g{k$X}yIe%$N)cn1LNu=q9_CS)*>A zsX_mM4L@`(cSNQKMFc$RtYbx{79#j-J7hk*>*+ZZhM4Hw?I?rsXCi#mRWJ=-0LGV5a-WR0Qgt<|Nqf)C-@80`5gIz45^_20000IqP)X=#(TiCT&PiIIVc55T}TU}EUh*{q$|`3@{d>{Tc9Bo>e= zfmF3!f>fbI9#GoEHh0f`i5)wkLpva0ztf%HpZneK?w-7AK@b4Itw{y|Zd3k!fH?q2 zlhckHd_V2M_X7+)U&_Xcfvtw60l;--DgZmLSw-Y?S>)zIqMyJ1#FwLU*%bl38ok+! zh78H87n`ZTS;uhzAR$M`zZ`bVhq=+%u9^$5jDplgxd44}9;IRqUH1YHH|@6oFe%z( zo4)_>E$F&^P-f(#)>(TrnbE>Pefs9~@iN=|)Rz|V`sGfHNrJ)0gJb8xx+SBmRf@1l zvuzt=vGfI)<-F9!o&3l?>9~0QbUDT(wFdnQPv%xdD)m*g%!20>Bc9iYmGAp<9YAa( z0QgYgTWqf1qN++Gqp z8@AYPTB3E|6s=WLG?xw0tm|U!o=&zd+H0oRYE;Dbx+Na9s^STqX|Gnq%H8s(nGDGJ j8vwW|`Ts`)fSK|Kx=IK@RG@g200000NkvXXu0mjfauFEA diff --git a/documentation/html/functions.html b/documentation/html/functions.html deleted file mode 100644 index a2547a0..0000000 --- a/documentation/html/functions.html +++ /dev/null @@ -1,93 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - a -

    -
    - - - - diff --git a/documentation/html/functions_b.html b/documentation/html/functions_b.html deleted file mode 100644 index 2bce74c..0000000 --- a/documentation/html/functions_b.html +++ /dev/null @@ -1,84 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - b -

    -
    - - - - diff --git a/documentation/html/functions_c.html b/documentation/html/functions_c.html deleted file mode 100644 index f7095bf..0000000 --- a/documentation/html/functions_c.html +++ /dev/null @@ -1,91 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - c -

    -
    - - - - diff --git a/documentation/html/functions_d.html b/documentation/html/functions_d.html deleted file mode 100644 index 13767b6..0000000 --- a/documentation/html/functions_d.html +++ /dev/null @@ -1,99 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - d -

    -
    - - - - diff --git a/documentation/html/functions_e.html b/documentation/html/functions_e.html deleted file mode 100644 index bc84988..0000000 --- a/documentation/html/functions_e.html +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - e -

    -
    - - - - diff --git a/documentation/html/functions_enum.html b/documentation/html/functions_enum.html deleted file mode 100644 index 4081f5f..0000000 --- a/documentation/html/functions_enum.html +++ /dev/null @@ -1,81 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - Enumerations - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
      -
    • ERROR_TYPE : PID
    • -
    -
    - - - - diff --git a/documentation/html/functions_f.html b/documentation/html/functions_f.html deleted file mode 100644 index 9ccef83..0000000 --- a/documentation/html/functions_f.html +++ /dev/null @@ -1,87 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - f -

    -
    - - - - diff --git a/documentation/html/functions_func.html b/documentation/html/functions_func.html deleted file mode 100644 index 2bb052d..0000000 --- a/documentation/html/functions_func.html +++ /dev/null @@ -1,282 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - Functions - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -  - -

    - a -

    - - -

    - b -

    - - -

    - c -

    - - -

    - d -

    - - -

    - e -

    - - -

    - f -

    - - -

    - g -

    - - -

    - h -

    - - -

    - i -

    - - -

    - l -

    - - -

    - m -

    - - -

    - n -

    - - -

    - o -

    - - -

    - p -

    - - -

    - r -

    - - -

    - s -

    - - -

    - t -

    - - -

    - u -

    - - -

    - v -

    - - -

    - w -

    -
    - - - - diff --git a/documentation/html/functions_g.html b/documentation/html/functions_g.html deleted file mode 100644 index 4e74ecb..0000000 --- a/documentation/html/functions_g.html +++ /dev/null @@ -1,109 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - g -

    -
    - - - - diff --git a/documentation/html/functions_h.html b/documentation/html/functions_h.html deleted file mode 100644 index 3a9d1b7..0000000 --- a/documentation/html/functions_h.html +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - h -

    -
    - - - - diff --git a/documentation/html/functions_i.html b/documentation/html/functions_i.html deleted file mode 100644 index 4983d51..0000000 --- a/documentation/html/functions_i.html +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - i -

    -
    - - - - diff --git a/documentation/html/functions_k.html b/documentation/html/functions_k.html deleted file mode 100644 index c7ff6db..0000000 --- a/documentation/html/functions_k.html +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - k -

    -
    - - - - diff --git a/documentation/html/functions_l.html b/documentation/html/functions_l.html deleted file mode 100644 index eea2f87..0000000 --- a/documentation/html/functions_l.html +++ /dev/null @@ -1,85 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - l -

    -
    - - - - diff --git a/documentation/html/functions_m.html b/documentation/html/functions_m.html deleted file mode 100644 index efed15c..0000000 --- a/documentation/html/functions_m.html +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - m -

    -
    - - - - diff --git a/documentation/html/functions_n.html b/documentation/html/functions_n.html deleted file mode 100644 index fa9a804..0000000 --- a/documentation/html/functions_n.html +++ /dev/null @@ -1,84 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - n -

    -
    - - - - diff --git a/documentation/html/functions_o.html b/documentation/html/functions_o.html deleted file mode 100644 index 7e48198..0000000 --- a/documentation/html/functions_o.html +++ /dev/null @@ -1,94 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - o -

    -
    - - - - diff --git a/documentation/html/functions_p.html b/documentation/html/functions_p.html deleted file mode 100644 index 28d8b87..0000000 --- a/documentation/html/functions_p.html +++ /dev/null @@ -1,90 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - p -

    -
    - - - - diff --git a/documentation/html/functions_r.html b/documentation/html/functions_r.html deleted file mode 100644 index 1a4754f..0000000 --- a/documentation/html/functions_r.html +++ /dev/null @@ -1,90 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - r -

    -
    - - - - diff --git a/documentation/html/functions_s.html b/documentation/html/functions_s.html deleted file mode 100644 index 3e4d6ba..0000000 --- a/documentation/html/functions_s.html +++ /dev/null @@ -1,104 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - s -

    -
    - - - - diff --git a/documentation/html/functions_t.html b/documentation/html/functions_t.html deleted file mode 100644 index 6a24775..0000000 --- a/documentation/html/functions_t.html +++ /dev/null @@ -1,92 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - t -

    -
    - - - - diff --git a/documentation/html/functions_u.html b/documentation/html/functions_u.html deleted file mode 100644 index c40b5c9..0000000 --- a/documentation/html/functions_u.html +++ /dev/null @@ -1,84 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - u -

    -
    - - - - diff --git a/documentation/html/functions_v.html b/documentation/html/functions_v.html deleted file mode 100644 index c4fefd4..0000000 --- a/documentation/html/functions_v.html +++ /dev/null @@ -1,85 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - v -

    -
    - - - - diff --git a/documentation/html/functions_vars.html b/documentation/html/functions_vars.html deleted file mode 100644 index 0e6ecfb..0000000 --- a/documentation/html/functions_vars.html +++ /dev/null @@ -1,212 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - Variables - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -  - -

    - a -

    - - -

    - b -

    - - -

    - c -

    - - -

    - d -

    - - -

    - e -

    - - -

    - f -

    - - -

    - h -

    - - -

    - i -

    - - -

    - k -

    - - -

    - l -

    - - -

    - m -

    - - -

    - n -

    - - -

    - o -

    - - -

    - p -

    - - -

    - r -

    - - -

    - s -

    - - -

    - t -

    - - -

    - v -

    - - -

    - w -

    - - -

    - x -

    - - -

    - y -

    - - -

    - z -

    -
    - - - - diff --git a/documentation/html/functions_w.html b/documentation/html/functions_w.html deleted file mode 100644 index b6cc523..0000000 --- a/documentation/html/functions_w.html +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - w -

    -
    - - - - diff --git a/documentation/html/functions_x.html b/documentation/html/functions_x.html deleted file mode 100644 index abf1351..0000000 --- a/documentation/html/functions_x.html +++ /dev/null @@ -1,83 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - x -

    -
    - - - - diff --git a/documentation/html/functions_y.html b/documentation/html/functions_y.html deleted file mode 100644 index f44bc19..0000000 --- a/documentation/html/functions_y.html +++ /dev/null @@ -1,83 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - y -

    -
    - - - - diff --git a/documentation/html/functions_z.html b/documentation/html/functions_z.html deleted file mode 100644 index f76fdf7..0000000 --- a/documentation/html/functions_z.html +++ /dev/null @@ -1,83 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Members - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Here is a list of all documented class members with links to the class documentation for each member:
    - -

    - z -

    -
    - - - - diff --git a/documentation/html/generic__auto_8h_source.html b/documentation/html/generic__auto_8h_source.html deleted file mode 100644 index f361c3e..0000000 --- a/documentation/html/generic__auto_8h_source.html +++ /dev/null @@ -1,116 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/generic_auto.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    generic_auto.h
    -
    -
    -
    1#pragma once
    -
    2
    -
    3#include <queue>
    -
    4#include <map>
    -
    5#include "vex.h"
    -
    6#include <functional>
    -
    7
    -
    8typedef std::function<bool(void)> state_ptr;
    -
    9
    - -
    15{
    -
    16 public:
    -
    17
    -
    31 bool run(bool blocking);
    -
    32
    -
    37 void add(state_ptr new_state);
    -
    38
    -
    43 void add_async(state_ptr async_state);
    -
    44
    -
    49 void add_delay(int ms);
    -
    50
    -
    51 private:
    -
    52
    -
    53 std::queue<state_ptr> state_list;
    -
    54
    -
    55};
    -
    Definition: generic_auto.h:15
    -
    void add_async(state_ptr async_state)
    Definition: generic_auto.cpp:41
    -
    void add_delay(int ms)
    Definition: generic_auto.cpp:56
    -
    bool run(bool blocking)
    Definition: generic_auto.cpp:16
    -
    void add(state_ptr new_state)
    Definition: generic_auto.cpp:36
    -
    - - - - diff --git a/documentation/html/graph__drawer_8h_source.html b/documentation/html/graph__drawer_8h_source.html deleted file mode 100644 index 2a6f2eb..0000000 --- a/documentation/html/graph__drawer_8h_source.html +++ /dev/null @@ -1,199 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/graph_drawer.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    graph_drawer.h
    -
    -
    -
    1#pragma once
    -
    2
    -
    3#include <string>
    -
    4#include <stdio.h>
    -
    5#include <vector>
    -
    6#include "vex.h"
    -
    7#include "../core/include/utils/vector2d.h"
    -
    8
    - -
    10{
    -
    11public:
    -
    23 GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound) : Screen(screen), sample_index(0), xlabel(x_label), ylabel(y_label), col(col), border(draw_border), upper(upper_bound), lower(lower_bound)
    -
    24 {
    -
    25 std::vector<Vector2D::point_t> temp(num_samples, Vector2D::point_t{.x = 0.0, .y = 0.0});
    -
    26 samples = temp;
    -
    27 }
    -
    28
    - -
    34 {
    -
    35 samples[sample_index] = sample;
    -
    36 sample_index++;
    -
    37 sample_index %= samples.size();
    -
    38 }
    -
    46 void draw(int x, int y, int width, int height)
    -
    47 {
    -
    48 if (samples.size() < 1)
    -
    49 {
    -
    50 return;
    -
    51 }
    -
    52
    -
    53 double current_min = samples[0].y;
    -
    54 double current_max = samples[0].y;
    -
    55 double earliest_time = samples[0].x;
    -
    56 double latest_time = samples[0].x;
    -
    57 // collect data
    -
    58 for (int i = 0; i < samples.size(); i++)
    -
    59 {
    -
    60 Vector2D::point_t p = samples[i];
    -
    61 if (p.x < earliest_time)
    -
    62 {
    -
    63 earliest_time = p.x;
    -
    64 }
    -
    65 else if (p.x > latest_time)
    -
    66 {
    -
    67 latest_time = p.x;
    -
    68 }
    -
    69
    -
    70 if (p.y < current_min)
    -
    71 {
    -
    72 current_min = p.y;
    -
    73 }
    -
    74 else if (p.y > current_max)
    -
    75 {
    -
    76 current_max = p.y;
    -
    77 }
    -
    78 }
    -
    79 if (fabs(latest_time - earliest_time) < 0.001)
    -
    80 {
    -
    81 Screen.printAt(width / 2, height / 2, "Not enough Data");
    -
    82 return;
    -
    83 }
    -
    84 if (upper != lower)
    -
    85 {
    -
    86 current_min = lower;
    -
    87 current_max = upper;
    -
    88 }
    -
    89
    -
    90 if (border)
    -
    91 {
    -
    92 Screen.setPenWidth(1);
    -
    93 Screen.setPenColor(vex::white);
    -
    94 Screen.setFillColor(bgcol);
    -
    95 Screen.drawRectangle(x, y, width, height);
    -
    96 }
    -
    97
    -
    98 double time_range = latest_time - earliest_time;
    -
    99 double sample_range = current_max - current_min;
    -
    100 double x_s = (double)x;
    -
    101 double y_s = (double)y + (double)height;
    -
    102 Screen.setPenWidth(4);
    -
    103 Screen.setPenColor(col);
    -
    104 for (int i = sample_index; i < samples.size() + sample_index - 1; i++)
    -
    105 {
    -
    106 Vector2D::point_t p = samples[i % samples.size()];
    -
    107 double x_pos = x_s + ((p.x - earliest_time) / time_range) * (double)width;
    -
    108 double y_pos = y_s + ((p.y - current_min) / sample_range) * (double)(-height);
    -
    109
    -
    110 Vector2D::point_t p2 = samples[(i + 1) % samples.size()];
    -
    111 double x_pos2 = x_s + ((p2.x - earliest_time) / time_range) * (double)width;
    -
    112 double y_pos2 = y_s + ((p2.y - current_min) / sample_range) * (double)(-height);
    -
    113
    -
    114 Screen.drawLine((int)x_pos, (int)y_pos, (int)x_pos2, (int)y_pos2);
    -
    115 }
    -
    116 }
    -
    117
    -
    118private:
    -
    119 vex::brain::lcd &Screen;
    -
    120 std::vector<Vector2D::point_t> samples;
    -
    121 int sample_index = 0;
    -
    122 std::string xlabel;
    -
    123 std::string ylabel;
    -
    124 vex::color col = vex::red;
    -
    125 vex::color bgcol = vex::transparent;
    -
    126 bool border;
    -
    127 double upper;
    -
    128 double lower;
    -
    129};
    -
    Definition: graph_drawer.h:10
    -
    void add_sample(Vector2D::point_t sample)
    Definition: graph_drawer.h:33
    -
    void draw(int x, int y, int width, int height)
    Definition: graph_drawer.h:46
    -
    GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound)
    a helper class to graph values on the brain screen
    Definition: graph_drawer.h:23
    -
    Definition: vector2d.h:21
    -
    double y
    the y position in space
    Definition: vector2d.h:23
    -
    double x
    the x position in space
    Definition: vector2d.h:22
    -
    - - - - diff --git a/documentation/html/hierarchy.html b/documentation/html/hierarchy.html deleted file mode 100644 index 656e20b..0000000 --- a/documentation/html/hierarchy.html +++ /dev/null @@ -1,132 +0,0 @@ - - - - - - - -RIT VEXU Core API: Class Hierarchy - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Class Hierarchy
    -
    - - - - - diff --git a/documentation/html/index.html b/documentation/html/index.html deleted file mode 100644 index 98612e5..0000000 --- a/documentation/html/index.html +++ /dev/null @@ -1,81 +0,0 @@ - - - - - - - -RIT VEXU Core API: Main Page - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    RIT VEXU Core API Documentation
    -
    -
    -
    - - - - diff --git a/documentation/html/jquery.js b/documentation/html/jquery.js deleted file mode 100644 index 1dffb65..0000000 --- a/documentation/html/jquery.js +++ /dev/null @@ -1,34 +0,0 @@ -/*! jQuery v3.6.0 | (c) OpenJS Foundation and other contributors | jquery.org/license */ -!function(e,t){"use strict";"object"==typeof module&&"object"==typeof module.exports?module.exports=e.document?t(e,!0):function(e){if(!e.document)throw new Error("jQuery requires a window with a document");return t(e)}:t(e)}("undefined"!=typeof window?window:this,function(C,e){"use strict";var t=[],r=Object.getPrototypeOf,s=t.slice,g=t.flat?function(e){return t.flat.call(e)}:function(e){return t.concat.apply([],e)},u=t.push,i=t.indexOf,n={},o=n.toString,v=n.hasOwnProperty,a=v.toString,l=a.call(Object),y={},m=function(e){return"function"==typeof e&&"number"!=typeof e.nodeType&&"function"!=typeof e.item},x=function(e){return null!=e&&e===e.window},E=C.document,c={type:!0,src:!0,nonce:!0,noModule:!0};function b(e,t,n){var r,i,o=(n=n||E).createElement("script");if(o.text=e,t)for(r in c)(i=t[r]||t.getAttribute&&t.getAttribute(r))&&o.setAttribute(r,i);n.head.appendChild(o).parentNode.removeChild(o)}function w(e){return null==e?e+"":"object"==typeof e||"function"==typeof e?n[o.call(e)]||"object":typeof e}var f="3.6.0",S=function(e,t){return new S.fn.init(e,t)};function p(e){var t=!!e&&"length"in e&&e.length,n=w(e);return!m(e)&&!x(e)&&("array"===n||0===t||"number"==typeof t&&0+~]|"+M+")"+M+"*"),U=new RegExp(M+"|>"),X=new RegExp(F),V=new RegExp("^"+I+"$"),G={ID:new RegExp("^#("+I+")"),CLASS:new RegExp("^\\.("+I+")"),TAG:new RegExp("^("+I+"|[*])"),ATTR:new RegExp("^"+W),PSEUDO:new RegExp("^"+F),CHILD:new RegExp("^:(only|first|last|nth|nth-last)-(child|of-type)(?:\\("+M+"*(even|odd|(([+-]|)(\\d*)n|)"+M+"*(?:([+-]|)"+M+"*(\\d+)|))"+M+"*\\)|)","i"),bool:new RegExp("^(?:"+R+")$","i"),needsContext:new RegExp("^"+M+"*[>+~]|:(even|odd|eq|gt|lt|nth|first|last)(?:\\("+M+"*((?:-\\d)?\\d*)"+M+"*\\)|)(?=[^-]|$)","i")},Y=/HTML$/i,Q=/^(?:input|select|textarea|button)$/i,J=/^h\d$/i,K=/^[^{]+\{\s*\[native \w/,Z=/^(?:#([\w-]+)|(\w+)|\.([\w-]+))$/,ee=/[+~]/,te=new RegExp("\\\\[\\da-fA-F]{1,6}"+M+"?|\\\\([^\\r\\n\\f])","g"),ne=function(e,t){var n="0x"+e.slice(1)-65536;return t||(n<0?String.fromCharCode(n+65536):String.fromCharCode(n>>10|55296,1023&n|56320))},re=/([\0-\x1f\x7f]|^-?\d)|^-$|[^\0-\x1f\x7f-\uFFFF\w-]/g,ie=function(e,t){return t?"\0"===e?"\ufffd":e.slice(0,-1)+"\\"+e.charCodeAt(e.length-1).toString(16)+" ":"\\"+e},oe=function(){T()},ae=be(function(e){return!0===e.disabled&&"fieldset"===e.nodeName.toLowerCase()},{dir:"parentNode",next:"legend"});try{H.apply(t=O.call(p.childNodes),p.childNodes),t[p.childNodes.length].nodeType}catch(e){H={apply:t.length?function(e,t){L.apply(e,O.call(t))}:function(e,t){var n=e.length,r=0;while(e[n++]=t[r++]);e.length=n-1}}}function se(t,e,n,r){var i,o,a,s,u,l,c,f=e&&e.ownerDocument,p=e?e.nodeType:9;if(n=n||[],"string"!=typeof t||!t||1!==p&&9!==p&&11!==p)return n;if(!r&&(T(e),e=e||C,E)){if(11!==p&&(u=Z.exec(t)))if(i=u[1]){if(9===p){if(!(a=e.getElementById(i)))return n;if(a.id===i)return n.push(a),n}else if(f&&(a=f.getElementById(i))&&y(e,a)&&a.id===i)return n.push(a),n}else{if(u[2])return H.apply(n,e.getElementsByTagName(t)),n;if((i=u[3])&&d.getElementsByClassName&&e.getElementsByClassName)return H.apply(n,e.getElementsByClassName(i)),n}if(d.qsa&&!N[t+" "]&&(!v||!v.test(t))&&(1!==p||"object"!==e.nodeName.toLowerCase())){if(c=t,f=e,1===p&&(U.test(t)||z.test(t))){(f=ee.test(t)&&ye(e.parentNode)||e)===e&&d.scope||((s=e.getAttribute("id"))?s=s.replace(re,ie):e.setAttribute("id",s=S)),o=(l=h(t)).length;while(o--)l[o]=(s?"#"+s:":scope")+" "+xe(l[o]);c=l.join(",")}try{return H.apply(n,f.querySelectorAll(c)),n}catch(e){N(t,!0)}finally{s===S&&e.removeAttribute("id")}}}return g(t.replace($,"$1"),e,n,r)}function ue(){var r=[];return function e(t,n){return r.push(t+" ")>b.cacheLength&&delete e[r.shift()],e[t+" "]=n}}function le(e){return e[S]=!0,e}function ce(e){var t=C.createElement("fieldset");try{return!!e(t)}catch(e){return!1}finally{t.parentNode&&t.parentNode.removeChild(t),t=null}}function fe(e,t){var n=e.split("|"),r=n.length;while(r--)b.attrHandle[n[r]]=t}function pe(e,t){var n=t&&e,r=n&&1===e.nodeType&&1===t.nodeType&&e.sourceIndex-t.sourceIndex;if(r)return r;if(n)while(n=n.nextSibling)if(n===t)return-1;return e?1:-1}function de(t){return function(e){return"input"===e.nodeName.toLowerCase()&&e.type===t}}function he(n){return function(e){var t=e.nodeName.toLowerCase();return("input"===t||"button"===t)&&e.type===n}}function ge(t){return function(e){return"form"in e?e.parentNode&&!1===e.disabled?"label"in e?"label"in e.parentNode?e.parentNode.disabled===t:e.disabled===t:e.isDisabled===t||e.isDisabled!==!t&&ae(e)===t:e.disabled===t:"label"in e&&e.disabled===t}}function ve(a){return le(function(o){return o=+o,le(function(e,t){var n,r=a([],e.length,o),i=r.length;while(i--)e[n=r[i]]&&(e[n]=!(t[n]=e[n]))})})}function ye(e){return e&&"undefined"!=typeof e.getElementsByTagName&&e}for(e in d=se.support={},i=se.isXML=function(e){var t=e&&e.namespaceURI,n=e&&(e.ownerDocument||e).documentElement;return!Y.test(t||n&&n.nodeName||"HTML")},T=se.setDocument=function(e){var t,n,r=e?e.ownerDocument||e:p;return r!=C&&9===r.nodeType&&r.documentElement&&(a=(C=r).documentElement,E=!i(C),p!=C&&(n=C.defaultView)&&n.top!==n&&(n.addEventListener?n.addEventListener("unload",oe,!1):n.attachEvent&&n.attachEvent("onunload",oe)),d.scope=ce(function(e){return a.appendChild(e).appendChild(C.createElement("div")),"undefined"!=typeof e.querySelectorAll&&!e.querySelectorAll(":scope fieldset div").length}),d.attributes=ce(function(e){return e.className="i",!e.getAttribute("className")}),d.getElementsByTagName=ce(function(e){return e.appendChild(C.createComment("")),!e.getElementsByTagName("*").length}),d.getElementsByClassName=K.test(C.getElementsByClassName),d.getById=ce(function(e){return a.appendChild(e).id=S,!C.getElementsByName||!C.getElementsByName(S).length}),d.getById?(b.filter.ID=function(e){var t=e.replace(te,ne);return function(e){return e.getAttribute("id")===t}},b.find.ID=function(e,t){if("undefined"!=typeof t.getElementById&&E){var n=t.getElementById(e);return n?[n]:[]}}):(b.filter.ID=function(e){var n=e.replace(te,ne);return function(e){var t="undefined"!=typeof e.getAttributeNode&&e.getAttributeNode("id");return t&&t.value===n}},b.find.ID=function(e,t){if("undefined"!=typeof t.getElementById&&E){var n,r,i,o=t.getElementById(e);if(o){if((n=o.getAttributeNode("id"))&&n.value===e)return[o];i=t.getElementsByName(e),r=0;while(o=i[r++])if((n=o.getAttributeNode("id"))&&n.value===e)return[o]}return[]}}),b.find.TAG=d.getElementsByTagName?function(e,t){return"undefined"!=typeof t.getElementsByTagName?t.getElementsByTagName(e):d.qsa?t.querySelectorAll(e):void 0}:function(e,t){var n,r=[],i=0,o=t.getElementsByTagName(e);if("*"===e){while(n=o[i++])1===n.nodeType&&r.push(n);return r}return o},b.find.CLASS=d.getElementsByClassName&&function(e,t){if("undefined"!=typeof t.getElementsByClassName&&E)return t.getElementsByClassName(e)},s=[],v=[],(d.qsa=K.test(C.querySelectorAll))&&(ce(function(e){var t;a.appendChild(e).innerHTML="",e.querySelectorAll("[msallowcapture^='']").length&&v.push("[*^$]="+M+"*(?:''|\"\")"),e.querySelectorAll("[selected]").length||v.push("\\["+M+"*(?:value|"+R+")"),e.querySelectorAll("[id~="+S+"-]").length||v.push("~="),(t=C.createElement("input")).setAttribute("name",""),e.appendChild(t),e.querySelectorAll("[name='']").length||v.push("\\["+M+"*name"+M+"*="+M+"*(?:''|\"\")"),e.querySelectorAll(":checked").length||v.push(":checked"),e.querySelectorAll("a#"+S+"+*").length||v.push(".#.+[+~]"),e.querySelectorAll("\\\f"),v.push("[\\r\\n\\f]")}),ce(function(e){e.innerHTML="";var t=C.createElement("input");t.setAttribute("type","hidden"),e.appendChild(t).setAttribute("name","D"),e.querySelectorAll("[name=d]").length&&v.push("name"+M+"*[*^$|!~]?="),2!==e.querySelectorAll(":enabled").length&&v.push(":enabled",":disabled"),a.appendChild(e).disabled=!0,2!==e.querySelectorAll(":disabled").length&&v.push(":enabled",":disabled"),e.querySelectorAll("*,:x"),v.push(",.*:")})),(d.matchesSelector=K.test(c=a.matches||a.webkitMatchesSelector||a.mozMatchesSelector||a.oMatchesSelector||a.msMatchesSelector))&&ce(function(e){d.disconnectedMatch=c.call(e,"*"),c.call(e,"[s!='']:x"),s.push("!=",F)}),v=v.length&&new RegExp(v.join("|")),s=s.length&&new RegExp(s.join("|")),t=K.test(a.compareDocumentPosition),y=t||K.test(a.contains)?function(e,t){var n=9===e.nodeType?e.documentElement:e,r=t&&t.parentNode;return e===r||!(!r||1!==r.nodeType||!(n.contains?n.contains(r):e.compareDocumentPosition&&16&e.compareDocumentPosition(r)))}:function(e,t){if(t)while(t=t.parentNode)if(t===e)return!0;return!1},j=t?function(e,t){if(e===t)return l=!0,0;var n=!e.compareDocumentPosition-!t.compareDocumentPosition;return n||(1&(n=(e.ownerDocument||e)==(t.ownerDocument||t)?e.compareDocumentPosition(t):1)||!d.sortDetached&&t.compareDocumentPosition(e)===n?e==C||e.ownerDocument==p&&y(p,e)?-1:t==C||t.ownerDocument==p&&y(p,t)?1:u?P(u,e)-P(u,t):0:4&n?-1:1)}:function(e,t){if(e===t)return l=!0,0;var n,r=0,i=e.parentNode,o=t.parentNode,a=[e],s=[t];if(!i||!o)return e==C?-1:t==C?1:i?-1:o?1:u?P(u,e)-P(u,t):0;if(i===o)return pe(e,t);n=e;while(n=n.parentNode)a.unshift(n);n=t;while(n=n.parentNode)s.unshift(n);while(a[r]===s[r])r++;return r?pe(a[r],s[r]):a[r]==p?-1:s[r]==p?1:0}),C},se.matches=function(e,t){return se(e,null,null,t)},se.matchesSelector=function(e,t){if(T(e),d.matchesSelector&&E&&!N[t+" "]&&(!s||!s.test(t))&&(!v||!v.test(t)))try{var n=c.call(e,t);if(n||d.disconnectedMatch||e.document&&11!==e.document.nodeType)return n}catch(e){N(t,!0)}return 0":{dir:"parentNode",first:!0}," ":{dir:"parentNode"},"+":{dir:"previousSibling",first:!0},"~":{dir:"previousSibling"}},preFilter:{ATTR:function(e){return e[1]=e[1].replace(te,ne),e[3]=(e[3]||e[4]||e[5]||"").replace(te,ne),"~="===e[2]&&(e[3]=" "+e[3]+" "),e.slice(0,4)},CHILD:function(e){return e[1]=e[1].toLowerCase(),"nth"===e[1].slice(0,3)?(e[3]||se.error(e[0]),e[4]=+(e[4]?e[5]+(e[6]||1):2*("even"===e[3]||"odd"===e[3])),e[5]=+(e[7]+e[8]||"odd"===e[3])):e[3]&&se.error(e[0]),e},PSEUDO:function(e){var t,n=!e[6]&&e[2];return G.CHILD.test(e[0])?null:(e[3]?e[2]=e[4]||e[5]||"":n&&X.test(n)&&(t=h(n,!0))&&(t=n.indexOf(")",n.length-t)-n.length)&&(e[0]=e[0].slice(0,t),e[2]=n.slice(0,t)),e.slice(0,3))}},filter:{TAG:function(e){var t=e.replace(te,ne).toLowerCase();return"*"===e?function(){return!0}:function(e){return e.nodeName&&e.nodeName.toLowerCase()===t}},CLASS:function(e){var t=m[e+" "];return t||(t=new RegExp("(^|"+M+")"+e+"("+M+"|$)"))&&m(e,function(e){return t.test("string"==typeof e.className&&e.className||"undefined"!=typeof e.getAttribute&&e.getAttribute("class")||"")})},ATTR:function(n,r,i){return function(e){var t=se.attr(e,n);return null==t?"!="===r:!r||(t+="","="===r?t===i:"!="===r?t!==i:"^="===r?i&&0===t.indexOf(i):"*="===r?i&&-1:\x20\t\r\n\f]*)[\x20\t\r\n\f]*\/?>(?:<\/\1>|)$/i;function j(e,n,r){return m(n)?S.grep(e,function(e,t){return!!n.call(e,t,e)!==r}):n.nodeType?S.grep(e,function(e){return e===n!==r}):"string"!=typeof n?S.grep(e,function(e){return-1)[^>]*|#([\w-]+))$/;(S.fn.init=function(e,t,n){var r,i;if(!e)return this;if(n=n||D,"string"==typeof e){if(!(r="<"===e[0]&&">"===e[e.length-1]&&3<=e.length?[null,e,null]:q.exec(e))||!r[1]&&t)return!t||t.jquery?(t||n).find(e):this.constructor(t).find(e);if(r[1]){if(t=t instanceof S?t[0]:t,S.merge(this,S.parseHTML(r[1],t&&t.nodeType?t.ownerDocument||t:E,!0)),N.test(r[1])&&S.isPlainObject(t))for(r in t)m(this[r])?this[r](t[r]):this.attr(r,t[r]);return this}return(i=E.getElementById(r[2]))&&(this[0]=i,this.length=1),this}return e.nodeType?(this[0]=e,this.length=1,this):m(e)?void 0!==n.ready?n.ready(e):e(S):S.makeArray(e,this)}).prototype=S.fn,D=S(E);var L=/^(?:parents|prev(?:Until|All))/,H={children:!0,contents:!0,next:!0,prev:!0};function O(e,t){while((e=e[t])&&1!==e.nodeType);return e}S.fn.extend({has:function(e){var t=S(e,this),n=t.length;return this.filter(function(){for(var e=0;e\x20\t\r\n\f]*)/i,he=/^$|^module$|\/(?:java|ecma)script/i;ce=E.createDocumentFragment().appendChild(E.createElement("div")),(fe=E.createElement("input")).setAttribute("type","radio"),fe.setAttribute("checked","checked"),fe.setAttribute("name","t"),ce.appendChild(fe),y.checkClone=ce.cloneNode(!0).cloneNode(!0).lastChild.checked,ce.innerHTML="",y.noCloneChecked=!!ce.cloneNode(!0).lastChild.defaultValue,ce.innerHTML="",y.option=!!ce.lastChild;var ge={thead:[1,"","
    "],col:[2,"","
    "],tr:[2,"","
    "],td:[3,"","
    "],_default:[0,"",""]};function ve(e,t){var n;return n="undefined"!=typeof e.getElementsByTagName?e.getElementsByTagName(t||"*"):"undefined"!=typeof e.querySelectorAll?e.querySelectorAll(t||"*"):[],void 0===t||t&&A(e,t)?S.merge([e],n):n}function ye(e,t){for(var n=0,r=e.length;n",""]);var me=/<|&#?\w+;/;function xe(e,t,n,r,i){for(var o,a,s,u,l,c,f=t.createDocumentFragment(),p=[],d=0,h=e.length;d\s*$/g;function je(e,t){return A(e,"table")&&A(11!==t.nodeType?t:t.firstChild,"tr")&&S(e).children("tbody")[0]||e}function De(e){return e.type=(null!==e.getAttribute("type"))+"/"+e.type,e}function qe(e){return"true/"===(e.type||"").slice(0,5)?e.type=e.type.slice(5):e.removeAttribute("type"),e}function Le(e,t){var n,r,i,o,a,s;if(1===t.nodeType){if(Y.hasData(e)&&(s=Y.get(e).events))for(i in Y.remove(t,"handle events"),s)for(n=0,r=s[i].length;n").attr(n.scriptAttrs||{}).prop({charset:n.scriptCharset,src:n.url}).on("load error",i=function(e){r.remove(),i=null,e&&t("error"===e.type?404:200,e.type)}),E.head.appendChild(r[0])},abort:function(){i&&i()}}});var _t,zt=[],Ut=/(=)\?(?=&|$)|\?\?/;S.ajaxSetup({jsonp:"callback",jsonpCallback:function(){var e=zt.pop()||S.expando+"_"+wt.guid++;return this[e]=!0,e}}),S.ajaxPrefilter("json jsonp",function(e,t,n){var r,i,o,a=!1!==e.jsonp&&(Ut.test(e.url)?"url":"string"==typeof e.data&&0===(e.contentType||"").indexOf("application/x-www-form-urlencoded")&&Ut.test(e.data)&&"data");if(a||"jsonp"===e.dataTypes[0])return r=e.jsonpCallback=m(e.jsonpCallback)?e.jsonpCallback():e.jsonpCallback,a?e[a]=e[a].replace(Ut,"$1"+r):!1!==e.jsonp&&(e.url+=(Tt.test(e.url)?"&":"?")+e.jsonp+"="+r),e.converters["script json"]=function(){return o||S.error(r+" was not called"),o[0]},e.dataTypes[0]="json",i=C[r],C[r]=function(){o=arguments},n.always(function(){void 0===i?S(C).removeProp(r):C[r]=i,e[r]&&(e.jsonpCallback=t.jsonpCallback,zt.push(r)),o&&m(i)&&i(o[0]),o=i=void 0}),"script"}),y.createHTMLDocument=((_t=E.implementation.createHTMLDocument("").body).innerHTML="
    ",2===_t.childNodes.length),S.parseHTML=function(e,t,n){return"string"!=typeof e?[]:("boolean"==typeof t&&(n=t,t=!1),t||(y.createHTMLDocument?((r=(t=E.implementation.createHTMLDocument("")).createElement("base")).href=E.location.href,t.head.appendChild(r)):t=E),o=!n&&[],(i=N.exec(e))?[t.createElement(i[1])]:(i=xe([e],t,o),o&&o.length&&S(o).remove(),S.merge([],i.childNodes)));var r,i,o},S.fn.load=function(e,t,n){var r,i,o,a=this,s=e.indexOf(" ");return-1").append(S.parseHTML(e)).find(r):e)}).always(n&&function(e,t){a.each(function(){n.apply(this,o||[e.responseText,t,e])})}),this},S.expr.pseudos.animated=function(t){return S.grep(S.timers,function(e){return t===e.elem}).length},S.offset={setOffset:function(e,t,n){var r,i,o,a,s,u,l=S.css(e,"position"),c=S(e),f={};"static"===l&&(e.style.position="relative"),s=c.offset(),o=S.css(e,"top"),u=S.css(e,"left"),("absolute"===l||"fixed"===l)&&-1<(o+u).indexOf("auto")?(a=(r=c.position()).top,i=r.left):(a=parseFloat(o)||0,i=parseFloat(u)||0),m(t)&&(t=t.call(e,n,S.extend({},s))),null!=t.top&&(f.top=t.top-s.top+a),null!=t.left&&(f.left=t.left-s.left+i),"using"in t?t.using.call(e,f):c.css(f)}},S.fn.extend({offset:function(t){if(arguments.length)return void 0===t?this:this.each(function(e){S.offset.setOffset(this,t,e)});var e,n,r=this[0];return r?r.getClientRects().length?(e=r.getBoundingClientRect(),n=r.ownerDocument.defaultView,{top:e.top+n.pageYOffset,left:e.left+n.pageXOffset}):{top:0,left:0}:void 0},position:function(){if(this[0]){var e,t,n,r=this[0],i={top:0,left:0};if("fixed"===S.css(r,"position"))t=r.getBoundingClientRect();else{t=this.offset(),n=r.ownerDocument,e=r.offsetParent||n.documentElement;while(e&&(e===n.body||e===n.documentElement)&&"static"===S.css(e,"position"))e=e.parentNode;e&&e!==r&&1===e.nodeType&&((i=S(e).offset()).top+=S.css(e,"borderTopWidth",!0),i.left+=S.css(e,"borderLeftWidth",!0))}return{top:t.top-i.top-S.css(r,"marginTop",!0),left:t.left-i.left-S.css(r,"marginLeft",!0)}}},offsetParent:function(){return this.map(function(){var e=this.offsetParent;while(e&&"static"===S.css(e,"position"))e=e.offsetParent;return e||re})}}),S.each({scrollLeft:"pageXOffset",scrollTop:"pageYOffset"},function(t,i){var o="pageYOffset"===i;S.fn[t]=function(e){return $(this,function(e,t,n){var r;if(x(e)?r=e:9===e.nodeType&&(r=e.defaultView),void 0===n)return r?r[i]:e[t];r?r.scrollTo(o?r.pageXOffset:n,o?n:r.pageYOffset):e[t]=n},t,e,arguments.length)}}),S.each(["top","left"],function(e,n){S.cssHooks[n]=Fe(y.pixelPosition,function(e,t){if(t)return t=We(e,n),Pe.test(t)?S(e).position()[n]+"px":t})}),S.each({Height:"height",Width:"width"},function(a,s){S.each({padding:"inner"+a,content:s,"":"outer"+a},function(r,o){S.fn[o]=function(e,t){var n=arguments.length&&(r||"boolean"!=typeof e),i=r||(!0===e||!0===t?"margin":"border");return $(this,function(e,t,n){var r;return x(e)?0===o.indexOf("outer")?e["inner"+a]:e.document.documentElement["client"+a]:9===e.nodeType?(r=e.documentElement,Math.max(e.body["scroll"+a],r["scroll"+a],e.body["offset"+a],r["offset"+a],r["client"+a])):void 0===n?S.css(e,t,i):S.style(e,t,n,i)},s,n?e:void 0,n)}})}),S.each(["ajaxStart","ajaxStop","ajaxComplete","ajaxError","ajaxSuccess","ajaxSend"],function(e,t){S.fn[t]=function(e){return this.on(t,e)}}),S.fn.extend({bind:function(e,t,n){return this.on(e,null,t,n)},unbind:function(e,t){return this.off(e,null,t)},delegate:function(e,t,n,r){return this.on(t,e,n,r)},undelegate:function(e,t,n){return 1===arguments.length?this.off(e,"**"):this.off(t,e||"**",n)},hover:function(e,t){return this.mouseenter(e).mouseleave(t||e)}}),S.each("blur focus focusin focusout resize scroll click dblclick mousedown mouseup mousemove mouseover mouseout mouseenter mouseleave change select submit keydown keypress keyup contextmenu".split(" "),function(e,n){S.fn[n]=function(e,t){return 0",options:{classes:{},disabled:!1,create:null},_createWidget:function(t,e){e=y(e||this.defaultElement||this)[0],this.element=y(e),this.uuid=i++,this.eventNamespace="."+this.widgetName+this.uuid,this.bindings=y(),this.hoverable=y(),this.focusable=y(),this.classesElementLookup={},e!==this&&(y.data(e,this.widgetFullName,this),this._on(!0,this.element,{remove:function(t){t.target===e&&this.destroy()}}),this.document=y(e.style?e.ownerDocument:e.document||e),this.window=y(this.document[0].defaultView||this.document[0].parentWindow)),this.options=y.widget.extend({},this.options,this._getCreateOptions(),t),this._create(),this.options.disabled&&this._setOptionDisabled(this.options.disabled),this._trigger("create",null,this._getCreateEventData()),this._init()},_getCreateOptions:function(){return{}},_getCreateEventData:y.noop,_create:y.noop,_init:y.noop,destroy:function(){var i=this;this._destroy(),y.each(this.classesElementLookup,function(t,e){i._removeClass(e,t)}),this.element.off(this.eventNamespace).removeData(this.widgetFullName),this.widget().off(this.eventNamespace).removeAttr("aria-disabled"),this.bindings.off(this.eventNamespace)},_destroy:y.noop,widget:function(){return this.element},option:function(t,e){var i,s,n,o=t;if(0===arguments.length)return y.widget.extend({},this.options);if("string"==typeof t)if(o={},t=(i=t.split(".")).shift(),i.length){for(s=o[t]=y.widget.extend({},this.options[t]),n=0;n
  • "),i=e.children()[0];return y("body").append(e),t=i.offsetWidth,e.css("overflow","scroll"),t===(i=i.offsetWidth)&&(i=e[0].clientWidth),e.remove(),s=t-i},getScrollInfo:function(t){var e=t.isWindow||t.isDocument?"":t.element.css("overflow-x"),i=t.isWindow||t.isDocument?"":t.element.css("overflow-y"),e="scroll"===e||"auto"===e&&t.widthx(D(s),D(n))?o.important="horizontal":o.important="vertical",p.using.call(this,t,o)}),h.offset(y.extend(l,{using:t}))})},y.ui.position={fit:{left:function(t,e){var i=e.within,s=i.isWindow?i.scrollLeft:i.offset.left,n=i.width,o=t.left-e.collisionPosition.marginLeft,h=s-o,a=o+e.collisionWidth-n-s;e.collisionWidth>n?0n?0=this.options.distance},_mouseDelayMet:function(){return this.mouseDelayMet},_mouseStart:function(){},_mouseDrag:function(){},_mouseStop:function(){},_mouseCapture:function(){return!0}}),y.ui.plugin={add:function(t,e,i){var s,n=y.ui[t].prototype;for(s in i)n.plugins[s]=n.plugins[s]||[],n.plugins[s].push([e,i[s]])},call:function(t,e,i,s){var n,o=t.plugins[e];if(o&&(s||t.element[0].parentNode&&11!==t.element[0].parentNode.nodeType))for(n=0;n").css({overflow:"hidden",position:this.element.css("position"),width:this.element.outerWidth(),height:this.element.outerHeight(),top:this.element.css("top"),left:this.element.css("left")})),this.element=this.element.parent().data("ui-resizable",this.element.resizable("instance")),this.elementIsWrapper=!0,t={marginTop:this.originalElement.css("marginTop"),marginRight:this.originalElement.css("marginRight"),marginBottom:this.originalElement.css("marginBottom"),marginLeft:this.originalElement.css("marginLeft")},this.element.css(t),this.originalElement.css("margin",0),this.originalResizeStyle=this.originalElement.css("resize"),this.originalElement.css("resize","none"),this._proportionallyResizeElements.push(this.originalElement.css({position:"static",zoom:1,display:"block"})),this.originalElement.css(t),this._proportionallyResize()),this._setupHandles(),e.autoHide&&y(this.element).on("mouseenter",function(){e.disabled||(i._removeClass("ui-resizable-autohide"),i._handles.show())}).on("mouseleave",function(){e.disabled||i.resizing||(i._addClass("ui-resizable-autohide"),i._handles.hide())}),this._mouseInit()},_destroy:function(){this._mouseDestroy(),this._addedHandles.remove();function t(t){y(t).removeData("resizable").removeData("ui-resizable").off(".resizable")}var e;return this.elementIsWrapper&&(t(this.element),e=this.element,this.originalElement.css({position:e.css("position"),width:e.outerWidth(),height:e.outerHeight(),top:e.css("top"),left:e.css("left")}).insertAfter(e),e.remove()),this.originalElement.css("resize",this.originalResizeStyle),t(this.originalElement),this},_setOption:function(t,e){switch(this._super(t,e),t){case"handles":this._removeHandles(),this._setupHandles();break;case"aspectRatio":this._aspectRatio=!!e}},_setupHandles:function(){var t,e,i,s,n,o=this.options,h=this;if(this.handles=o.handles||(y(".ui-resizable-handle",this.element).length?{n:".ui-resizable-n",e:".ui-resizable-e",s:".ui-resizable-s",w:".ui-resizable-w",se:".ui-resizable-se",sw:".ui-resizable-sw",ne:".ui-resizable-ne",nw:".ui-resizable-nw"}:"e,s,se"),this._handles=y(),this._addedHandles=y(),this.handles.constructor===String)for("all"===this.handles&&(this.handles="n,e,s,w,se,sw,ne,nw"),i=this.handles.split(","),this.handles={},e=0;e"),this._addClass(n,"ui-resizable-handle "+s),n.css({zIndex:o.zIndex}),this.handles[t]=".ui-resizable-"+t,this.element.children(this.handles[t]).length||(this.element.append(n),this._addedHandles=this._addedHandles.add(n));this._renderAxis=function(t){var e,i,s;for(e in t=t||this.element,this.handles)this.handles[e].constructor===String?this.handles[e]=this.element.children(this.handles[e]).first().show():(this.handles[e].jquery||this.handles[e].nodeType)&&(this.handles[e]=y(this.handles[e]),this._on(this.handles[e],{mousedown:h._mouseDown})),this.elementIsWrapper&&this.originalElement[0].nodeName.match(/^(textarea|input|select|button)$/i)&&(i=y(this.handles[e],this.element),s=/sw|ne|nw|se|n|s/.test(e)?i.outerHeight():i.outerWidth(),i=["padding",/ne|nw|n/.test(e)?"Top":/se|sw|s/.test(e)?"Bottom":/^e$/.test(e)?"Right":"Left"].join(""),t.css(i,s),this._proportionallyResize()),this._handles=this._handles.add(this.handles[e])},this._renderAxis(this.element),this._handles=this._handles.add(this.element.find(".ui-resizable-handle")),this._handles.disableSelection(),this._handles.on("mouseover",function(){h.resizing||(this.className&&(n=this.className.match(/ui-resizable-(se|sw|ne|nw|n|e|s|w)/i)),h.axis=n&&n[1]?n[1]:"se")}),o.autoHide&&(this._handles.hide(),this._addClass("ui-resizable-autohide"))},_removeHandles:function(){this._addedHandles.remove()},_mouseCapture:function(t){var e,i,s=!1;for(e in this.handles)(i=y(this.handles[e])[0])!==t.target&&!y.contains(i,t.target)||(s=!0);return!this.options.disabled&&s},_mouseStart:function(t){var e,i,s=this.options,n=this.element;return this.resizing=!0,this._renderProxy(),e=this._num(this.helper.css("left")),i=this._num(this.helper.css("top")),s.containment&&(e+=y(s.containment).scrollLeft()||0,i+=y(s.containment).scrollTop()||0),this.offset=this.helper.offset(),this.position={left:e,top:i},this.size=this._helper?{width:this.helper.width(),height:this.helper.height()}:{width:n.width(),height:n.height()},this.originalSize=this._helper?{width:n.outerWidth(),height:n.outerHeight()}:{width:n.width(),height:n.height()},this.sizeDiff={width:n.outerWidth()-n.width(),height:n.outerHeight()-n.height()},this.originalPosition={left:e,top:i},this.originalMousePosition={left:t.pageX,top:t.pageY},this.aspectRatio="number"==typeof s.aspectRatio?s.aspectRatio:this.originalSize.width/this.originalSize.height||1,s=y(".ui-resizable-"+this.axis).css("cursor"),y("body").css("cursor","auto"===s?this.axis+"-resize":s),this._addClass("ui-resizable-resizing"),this._propagate("start",t),!0},_mouseDrag:function(t){var e=this.originalMousePosition,i=this.axis,s=t.pageX-e.left||0,e=t.pageY-e.top||0,i=this._change[i];return this._updatePrevProperties(),i&&(e=i.apply(this,[t,s,e]),this._updateVirtualBoundaries(t.shiftKey),(this._aspectRatio||t.shiftKey)&&(e=this._updateRatio(e,t)),e=this._respectSize(e,t),this._updateCache(e),this._propagate("resize",t),e=this._applyChanges(),!this._helper&&this._proportionallyResizeElements.length&&this._proportionallyResize(),y.isEmptyObject(e)||(this._updatePrevProperties(),this._trigger("resize",t,this.ui()),this._applyChanges())),!1},_mouseStop:function(t){this.resizing=!1;var e,i,s,n=this.options,o=this;return this._helper&&(s=(e=(i=this._proportionallyResizeElements).length&&/textarea/i.test(i[0].nodeName))&&this._hasScroll(i[0],"left")?0:o.sizeDiff.height,i=e?0:o.sizeDiff.width,e={width:o.helper.width()-i,height:o.helper.height()-s},i=parseFloat(o.element.css("left"))+(o.position.left-o.originalPosition.left)||null,s=parseFloat(o.element.css("top"))+(o.position.top-o.originalPosition.top)||null,n.animate||this.element.css(y.extend(e,{top:s,left:i})),o.helper.height(o.size.height),o.helper.width(o.size.width),this._helper&&!n.animate&&this._proportionallyResize()),y("body").css("cursor","auto"),this._removeClass("ui-resizable-resizing"),this._propagate("stop",t),this._helper&&this.helper.remove(),!1},_updatePrevProperties:function(){this.prevPosition={top:this.position.top,left:this.position.left},this.prevSize={width:this.size.width,height:this.size.height}},_applyChanges:function(){var t={};return this.position.top!==this.prevPosition.top&&(t.top=this.position.top+"px"),this.position.left!==this.prevPosition.left&&(t.left=this.position.left+"px"),this.size.width!==this.prevSize.width&&(t.width=this.size.width+"px"),this.size.height!==this.prevSize.height&&(t.height=this.size.height+"px"),this.helper.css(t),t},_updateVirtualBoundaries:function(t){var e,i,s=this.options,n={minWidth:this._isNumber(s.minWidth)?s.minWidth:0,maxWidth:this._isNumber(s.maxWidth)?s.maxWidth:1/0,minHeight:this._isNumber(s.minHeight)?s.minHeight:0,maxHeight:this._isNumber(s.maxHeight)?s.maxHeight:1/0};(this._aspectRatio||t)&&(e=n.minHeight*this.aspectRatio,i=n.minWidth/this.aspectRatio,s=n.maxHeight*this.aspectRatio,t=n.maxWidth/this.aspectRatio,e>n.minWidth&&(n.minWidth=e),i>n.minHeight&&(n.minHeight=i),st.width,h=this._isNumber(t.height)&&e.minHeight&&e.minHeight>t.height,a=this.originalPosition.left+this.originalSize.width,r=this.originalPosition.top+this.originalSize.height,l=/sw|nw|w/.test(i),i=/nw|ne|n/.test(i);return o&&(t.width=e.minWidth),h&&(t.height=e.minHeight),s&&(t.width=e.maxWidth),n&&(t.height=e.maxHeight),o&&l&&(t.left=a-e.minWidth),s&&l&&(t.left=a-e.maxWidth),h&&i&&(t.top=r-e.minHeight),n&&i&&(t.top=r-e.maxHeight),t.width||t.height||t.left||!t.top?t.width||t.height||t.top||!t.left||(t.left=null):t.top=null,t},_getPaddingPlusBorderDimensions:function(t){for(var e=0,i=[],s=[t.css("borderTopWidth"),t.css("borderRightWidth"),t.css("borderBottomWidth"),t.css("borderLeftWidth")],n=[t.css("paddingTop"),t.css("paddingRight"),t.css("paddingBottom"),t.css("paddingLeft")];e<4;e++)i[e]=parseFloat(s[e])||0,i[e]+=parseFloat(n[e])||0;return{height:i[0]+i[2],width:i[1]+i[3]}},_proportionallyResize:function(){if(this._proportionallyResizeElements.length)for(var t,e=0,i=this.helper||this.element;e").css({overflow:"hidden"}),this._addClass(this.helper,this._helper),this.helper.css({width:this.element.outerWidth(),height:this.element.outerHeight(),position:"absolute",left:this.elementOffset.left+"px",top:this.elementOffset.top+"px",zIndex:++e.zIndex}),this.helper.appendTo("body").disableSelection()):this.helper=this.element},_change:{e:function(t,e){return{width:this.originalSize.width+e}},w:function(t,e){var i=this.originalSize;return{left:this.originalPosition.left+e,width:i.width-e}},n:function(t,e,i){var s=this.originalSize;return{top:this.originalPosition.top+i,height:s.height-i}},s:function(t,e,i){return{height:this.originalSize.height+i}},se:function(t,e,i){return y.extend(this._change.s.apply(this,arguments),this._change.e.apply(this,[t,e,i]))},sw:function(t,e,i){return y.extend(this._change.s.apply(this,arguments),this._change.w.apply(this,[t,e,i]))},ne:function(t,e,i){return y.extend(this._change.n.apply(this,arguments),this._change.e.apply(this,[t,e,i]))},nw:function(t,e,i){return y.extend(this._change.n.apply(this,arguments),this._change.w.apply(this,[t,e,i]))}},_propagate:function(t,e){y.ui.plugin.call(this,t,[e,this.ui()]),"resize"!==t&&this._trigger(t,e,this.ui())},plugins:{},ui:function(){return{originalElement:this.originalElement,element:this.element,helper:this.helper,position:this.position,size:this.size,originalSize:this.originalSize,originalPosition:this.originalPosition}}}),y.ui.plugin.add("resizable","animate",{stop:function(e){var i=y(this).resizable("instance"),t=i.options,s=i._proportionallyResizeElements,n=s.length&&/textarea/i.test(s[0].nodeName),o=n&&i._hasScroll(s[0],"left")?0:i.sizeDiff.height,h=n?0:i.sizeDiff.width,n={width:i.size.width-h,height:i.size.height-o},h=parseFloat(i.element.css("left"))+(i.position.left-i.originalPosition.left)||null,o=parseFloat(i.element.css("top"))+(i.position.top-i.originalPosition.top)||null;i.element.animate(y.extend(n,o&&h?{top:o,left:h}:{}),{duration:t.animateDuration,easing:t.animateEasing,step:function(){var t={width:parseFloat(i.element.css("width")),height:parseFloat(i.element.css("height")),top:parseFloat(i.element.css("top")),left:parseFloat(i.element.css("left"))};s&&s.length&&y(s[0]).css({width:t.width,height:t.height}),i._updateCache(t),i._propagate("resize",e)}})}}),y.ui.plugin.add("resizable","containment",{start:function(){var i,s,n=y(this).resizable("instance"),t=n.options,e=n.element,o=t.containment,h=o instanceof y?o.get(0):/parent/.test(o)?e.parent().get(0):o;h&&(n.containerElement=y(h),/document/.test(o)||o===document?(n.containerOffset={left:0,top:0},n.containerPosition={left:0,top:0},n.parentData={element:y(document),left:0,top:0,width:y(document).width(),height:y(document).height()||document.body.parentNode.scrollHeight}):(i=y(h),s=[],y(["Top","Right","Left","Bottom"]).each(function(t,e){s[t]=n._num(i.css("padding"+e))}),n.containerOffset=i.offset(),n.containerPosition=i.position(),n.containerSize={height:i.innerHeight()-s[3],width:i.innerWidth()-s[1]},t=n.containerOffset,e=n.containerSize.height,o=n.containerSize.width,o=n._hasScroll(h,"left")?h.scrollWidth:o,e=n._hasScroll(h)?h.scrollHeight:e,n.parentData={element:h,left:t.left,top:t.top,width:o,height:e}))},resize:function(t){var e=y(this).resizable("instance"),i=e.options,s=e.containerOffset,n=e.position,o=e._aspectRatio||t.shiftKey,h={top:0,left:0},a=e.containerElement,t=!0;a[0]!==document&&/static/.test(a.css("position"))&&(h=s),n.left<(e._helper?s.left:0)&&(e.size.width=e.size.width+(e._helper?e.position.left-s.left:e.position.left-h.left),o&&(e.size.height=e.size.width/e.aspectRatio,t=!1),e.position.left=i.helper?s.left:0),n.top<(e._helper?s.top:0)&&(e.size.height=e.size.height+(e._helper?e.position.top-s.top:e.position.top),o&&(e.size.width=e.size.height*e.aspectRatio,t=!1),e.position.top=e._helper?s.top:0),i=e.containerElement.get(0)===e.element.parent().get(0),n=/relative|absolute/.test(e.containerElement.css("position")),i&&n?(e.offset.left=e.parentData.left+e.position.left,e.offset.top=e.parentData.top+e.position.top):(e.offset.left=e.element.offset().left,e.offset.top=e.element.offset().top),n=Math.abs(e.sizeDiff.width+(e._helper?e.offset.left-h.left:e.offset.left-s.left)),s=Math.abs(e.sizeDiff.height+(e._helper?e.offset.top-h.top:e.offset.top-s.top)),n+e.size.width>=e.parentData.width&&(e.size.width=e.parentData.width-n,o&&(e.size.height=e.size.width/e.aspectRatio,t=!1)),s+e.size.height>=e.parentData.height&&(e.size.height=e.parentData.height-s,o&&(e.size.width=e.size.height*e.aspectRatio,t=!1)),t||(e.position.left=e.prevPosition.left,e.position.top=e.prevPosition.top,e.size.width=e.prevSize.width,e.size.height=e.prevSize.height)},stop:function(){var t=y(this).resizable("instance"),e=t.options,i=t.containerOffset,s=t.containerPosition,n=t.containerElement,o=y(t.helper),h=o.offset(),a=o.outerWidth()-t.sizeDiff.width,o=o.outerHeight()-t.sizeDiff.height;t._helper&&!e.animate&&/relative/.test(n.css("position"))&&y(this).css({left:h.left-s.left-i.left,width:a,height:o}),t._helper&&!e.animate&&/static/.test(n.css("position"))&&y(this).css({left:h.left-s.left-i.left,width:a,height:o})}}),y.ui.plugin.add("resizable","alsoResize",{start:function(){var t=y(this).resizable("instance").options;y(t.alsoResize).each(function(){var t=y(this);t.data("ui-resizable-alsoresize",{width:parseFloat(t.width()),height:parseFloat(t.height()),left:parseFloat(t.css("left")),top:parseFloat(t.css("top"))})})},resize:function(t,i){var e=y(this).resizable("instance"),s=e.options,n=e.originalSize,o=e.originalPosition,h={height:e.size.height-n.height||0,width:e.size.width-n.width||0,top:e.position.top-o.top||0,left:e.position.left-o.left||0};y(s.alsoResize).each(function(){var t=y(this),s=y(this).data("ui-resizable-alsoresize"),n={},e=t.parents(i.originalElement[0]).length?["width","height"]:["width","height","top","left"];y.each(e,function(t,e){var i=(s[e]||0)+(h[e]||0);i&&0<=i&&(n[e]=i||null)}),t.css(n)})},stop:function(){y(this).removeData("ui-resizable-alsoresize")}}),y.ui.plugin.add("resizable","ghost",{start:function(){var t=y(this).resizable("instance"),e=t.size;t.ghost=t.originalElement.clone(),t.ghost.css({opacity:.25,display:"block",position:"relative",height:e.height,width:e.width,margin:0,left:0,top:0}),t._addClass(t.ghost,"ui-resizable-ghost"),!1!==y.uiBackCompat&&"string"==typeof t.options.ghost&&t.ghost.addClass(this.options.ghost),t.ghost.appendTo(t.helper)},resize:function(){var t=y(this).resizable("instance");t.ghost&&t.ghost.css({position:"relative",height:t.size.height,width:t.size.width})},stop:function(){var t=y(this).resizable("instance");t.ghost&&t.helper&&t.helper.get(0).removeChild(t.ghost.get(0))}}),y.ui.plugin.add("resizable","grid",{resize:function(){var t,e=y(this).resizable("instance"),i=e.options,s=e.size,n=e.originalSize,o=e.originalPosition,h=e.axis,a="number"==typeof i.grid?[i.grid,i.grid]:i.grid,r=a[0]||1,l=a[1]||1,u=Math.round((s.width-n.width)/r)*r,p=Math.round((s.height-n.height)/l)*l,d=n.width+u,c=n.height+p,f=i.maxWidth&&i.maxWidthd,s=i.minHeight&&i.minHeight>c;i.grid=a,m&&(d+=r),s&&(c+=l),f&&(d-=r),g&&(c-=l),/^(se|s|e)$/.test(h)?(e.size.width=d,e.size.height=c):/^(ne)$/.test(h)?(e.size.width=d,e.size.height=c,e.position.top=o.top-p):/^(sw)$/.test(h)?(e.size.width=d,e.size.height=c,e.position.left=o.left-u):((c-l<=0||d-r<=0)&&(t=e._getPaddingPlusBorderDimensions(this)),0=f[g]?0:Math.min(f[g],n));!a&&1-1){targetElements.on(evt+EVENT_NAMESPACE,function elementToggle(event){$.powerTip.toggle(this,event)})}else{targetElements.on(evt+EVENT_NAMESPACE,function elementOpen(event){$.powerTip.show(this,event)})}});$.each(options.closeEvents,function(idx,evt){if($.inArray(evt,options.openEvents)<0){targetElements.on(evt+EVENT_NAMESPACE,function elementClose(event){$.powerTip.hide(this,!isMouseEvent(event))})}});targetElements.on("keydown"+EVENT_NAMESPACE,function elementKeyDown(event){if(event.keyCode===27){$.powerTip.hide(this,true)}})}return targetElements};$.fn.powerTip.defaults={fadeInTime:200,fadeOutTime:100,followMouse:false,popupId:"powerTip",popupClass:null,intentSensitivity:7,intentPollInterval:100,closeDelay:100,placement:"n",smartPlacement:false,offset:10,mouseOnToPopup:false,manual:false,openEvents:["mouseenter","focus"],closeEvents:["mouseleave","blur"]};$.fn.powerTip.smartPlacementLists={n:["n","ne","nw","s"],e:["e","ne","se","w","nw","sw","n","s","e"],s:["s","se","sw","n"],w:["w","nw","sw","e","ne","se","n","s","w"],nw:["nw","w","sw","n","s","se","nw"],ne:["ne","e","se","n","s","sw","ne"],sw:["sw","w","nw","s","n","ne","sw"],se:["se","e","ne","s","n","nw","se"],"nw-alt":["nw-alt","n","ne-alt","sw-alt","s","se-alt","w","e"],"ne-alt":["ne-alt","n","nw-alt","se-alt","s","sw-alt","e","w"],"sw-alt":["sw-alt","s","se-alt","nw-alt","n","ne-alt","w","e"],"se-alt":["se-alt","s","sw-alt","ne-alt","n","nw-alt","e","w"]};$.powerTip={show:function apiShowTip(element,event){if(isMouseEvent(event)){trackMouse(event);session.previousX=event.pageX;session.previousY=event.pageY;$(element).data(DATA_DISPLAYCONTROLLER).show()}else{$(element).first().data(DATA_DISPLAYCONTROLLER).show(true,true)}return element},reposition:function apiResetPosition(element){$(element).first().data(DATA_DISPLAYCONTROLLER).resetPosition();return element},hide:function apiCloseTip(element,immediate){var displayController;immediate=element?immediate:true;if(element){displayController=$(element).first().data(DATA_DISPLAYCONTROLLER)}else if(session.activeHover){displayController=session.activeHover.data(DATA_DISPLAYCONTROLLER)}if(displayController){displayController.hide(immediate)}return element},toggle:function apiToggle(element,event){if(session.activeHover&&session.activeHover.is(element)){$.powerTip.hide(element,!isMouseEvent(event))}else{$.powerTip.show(element,event)}return element}};$.powerTip.showTip=$.powerTip.show;$.powerTip.closeTip=$.powerTip.hide;function CSSCoordinates(){var me=this;me.top="auto";me.left="auto";me.right="auto";me.bottom="auto";me.set=function(property,value){if($.isNumeric(value)){me[property]=Math.round(value)}}}function DisplayController(element,options,tipController){var hoverTimer=null,myCloseDelay=null;function openTooltip(immediate,forceOpen){cancelTimer();if(!element.data(DATA_HASACTIVEHOVER)){if(!immediate){session.tipOpenImminent=true;hoverTimer=setTimeout(function intentDelay(){hoverTimer=null;checkForIntent()},options.intentPollInterval)}else{if(forceOpen){element.data(DATA_FORCEDOPEN,true)}closeAnyDelayed();tipController.showTip(element)}}else{cancelClose()}}function closeTooltip(disableDelay){if(myCloseDelay){myCloseDelay=session.closeDelayTimeout=clearTimeout(myCloseDelay);session.delayInProgress=false}cancelTimer();session.tipOpenImminent=false;if(element.data(DATA_HASACTIVEHOVER)){element.data(DATA_FORCEDOPEN,false);if(!disableDelay){session.delayInProgress=true;session.closeDelayTimeout=setTimeout(function closeDelay(){session.closeDelayTimeout=null;tipController.hideTip(element);session.delayInProgress=false;myCloseDelay=null},options.closeDelay);myCloseDelay=session.closeDelayTimeout}else{tipController.hideTip(element)}}}function checkForIntent(){var xDifference=Math.abs(session.previousX-session.currentX),yDifference=Math.abs(session.previousY-session.currentY),totalDifference=xDifference+yDifference;if(totalDifference",{id:options.popupId});if($body.length===0){$body=$("body")}$body.append(tipElement);session.tooltips=session.tooltips?session.tooltips.add(tipElement):tipElement}if(options.followMouse){if(!tipElement.data(DATA_HASMOUSEMOVE)){$document.on("mousemove"+EVENT_NAMESPACE,positionTipOnCursor);$window.on("scroll"+EVENT_NAMESPACE,positionTipOnCursor);tipElement.data(DATA_HASMOUSEMOVE,true)}}function beginShowTip(element){element.data(DATA_HASACTIVEHOVER,true);tipElement.queue(function queueTipInit(next){showTip(element);next()})}function showTip(element){var tipContent;if(!element.data(DATA_HASACTIVEHOVER)){return}if(session.isTipOpen){if(!session.isClosing){hideTip(session.activeHover)}tipElement.delay(100).queue(function queueTipAgain(next){showTip(element);next()});return}element.trigger("powerTipPreRender");tipContent=getTooltipContent(element);if(tipContent){tipElement.empty().append(tipContent)}else{return}element.trigger("powerTipRender");session.activeHover=element;session.isTipOpen=true;tipElement.data(DATA_MOUSEONTOTIP,options.mouseOnToPopup);tipElement.addClass(options.popupClass);if(!options.followMouse||element.data(DATA_FORCEDOPEN)){positionTipOnElement(element);session.isFixedTipOpen=true}else{positionTipOnCursor()}if(!element.data(DATA_FORCEDOPEN)&&!options.followMouse){$document.on("click"+EVENT_NAMESPACE,function documentClick(event){var target=event.target;if(target!==element[0]){if(options.mouseOnToPopup){if(target!==tipElement[0]&&!$.contains(tipElement[0],target)){$.powerTip.hide()}}else{$.powerTip.hide()}}})}if(options.mouseOnToPopup&&!options.manual){tipElement.on("mouseenter"+EVENT_NAMESPACE,function tipMouseEnter(){if(session.activeHover){session.activeHover.data(DATA_DISPLAYCONTROLLER).cancel()}});tipElement.on("mouseleave"+EVENT_NAMESPACE,function tipMouseLeave(){if(session.activeHover){session.activeHover.data(DATA_DISPLAYCONTROLLER).hide()}})}tipElement.fadeIn(options.fadeInTime,function fadeInCallback(){if(!session.desyncTimeout){session.desyncTimeout=setInterval(closeDesyncedTip,500)}element.trigger("powerTipOpen")})}function hideTip(element){session.isClosing=true;session.isTipOpen=false;session.desyncTimeout=clearInterval(session.desyncTimeout);element.data(DATA_HASACTIVEHOVER,false);element.data(DATA_FORCEDOPEN,false);$document.off("click"+EVENT_NAMESPACE);tipElement.off(EVENT_NAMESPACE);tipElement.fadeOut(options.fadeOutTime,function fadeOutCallback(){var coords=new CSSCoordinates;session.activeHover=null;session.isClosing=false;session.isFixedTipOpen=false;tipElement.removeClass();coords.set("top",session.currentY+options.offset);coords.set("left",session.currentX+options.offset);tipElement.css(coords);element.trigger("powerTipClose")})}function positionTipOnCursor(){var tipWidth,tipHeight,coords,collisions,collisionCount;if(!session.isFixedTipOpen&&(session.isTipOpen||session.tipOpenImminent&&tipElement.data(DATA_HASMOUSEMOVE))){tipWidth=tipElement.outerWidth();tipHeight=tipElement.outerHeight();coords=new CSSCoordinates;coords.set("top",session.currentY+options.offset);coords.set("left",session.currentX+options.offset);collisions=getViewportCollisions(coords,tipWidth,tipHeight);if(collisions!==Collision.none){collisionCount=countFlags(collisions);if(collisionCount===1){if(collisions===Collision.right){coords.set("left",session.scrollLeft+session.windowWidth-tipWidth)}else if(collisions===Collision.bottom){coords.set("top",session.scrollTop+session.windowHeight-tipHeight)}}else{coords.set("left",session.currentX-tipWidth-options.offset);coords.set("top",session.currentY-tipHeight-options.offset)}}tipElement.css(coords)}}function positionTipOnElement(element){var priorityList,finalPlacement;if(options.smartPlacement||options.followMouse&&element.data(DATA_FORCEDOPEN)){priorityList=$.fn.powerTip.smartPlacementLists[options.placement];$.each(priorityList,function(idx,pos){var collisions=getViewportCollisions(placeTooltip(element,pos),tipElement.outerWidth(),tipElement.outerHeight());finalPlacement=pos;return collisions!==Collision.none})}else{placeTooltip(element,options.placement);finalPlacement=options.placement}tipElement.removeClass("w nw sw e ne se n s w se-alt sw-alt ne-alt nw-alt");tipElement.addClass(finalPlacement)}function placeTooltip(element,placement){var iterationCount=0,tipWidth,tipHeight,coords=new CSSCoordinates;coords.set("top",0);coords.set("left",0);tipElement.css(coords);do{tipWidth=tipElement.outerWidth();tipHeight=tipElement.outerHeight();coords=placementCalculator.compute(element,placement,tipWidth,tipHeight,options.offset);tipElement.css(coords)}while(++iterationCount<=5&&(tipWidth!==tipElement.outerWidth()||tipHeight!==tipElement.outerHeight()));return coords}function closeDesyncedTip(){var isDesynced=false,hasDesyncableCloseEvent=$.grep(["mouseleave","mouseout","blur","focusout"],function(eventType){return $.inArray(eventType,options.closeEvents)!==-1}).length>0;if(session.isTipOpen&&!session.isClosing&&!session.delayInProgress&&hasDesyncableCloseEvent){if(session.activeHover.data(DATA_HASACTIVEHOVER)===false||session.activeHover.is(":disabled")){isDesynced=true}else if(!isMouseOver(session.activeHover)&&!session.activeHover.is(":focus")&&!session.activeHover.data(DATA_FORCEDOPEN)){if(tipElement.data(DATA_MOUSEONTOTIP)){if(!isMouseOver(tipElement)){isDesynced=true}}else{isDesynced=true}}if(isDesynced){hideTip(session.activeHover)}}}this.showTip=beginShowTip;this.hideTip=hideTip;this.resetPosition=positionTipOnElement}function isSvgElement(element){return Boolean(window.SVGElement&&element[0]instanceof SVGElement)}function isMouseEvent(event){return Boolean(event&&$.inArray(event.type,MOUSE_EVENTS)>-1&&typeof event.pageX==="number")}function initTracking(){if(!session.mouseTrackingActive){session.mouseTrackingActive=true;getViewportDimensions();$(getViewportDimensions);$document.on("mousemove"+EVENT_NAMESPACE,trackMouse);$window.on("resize"+EVENT_NAMESPACE,trackResize);$window.on("scroll"+EVENT_NAMESPACE,trackScroll)}}function getViewportDimensions(){session.scrollLeft=$window.scrollLeft();session.scrollTop=$window.scrollTop();session.windowWidth=$window.width();session.windowHeight=$window.height()}function trackResize(){session.windowWidth=$window.width();session.windowHeight=$window.height()}function trackScroll(){var x=$window.scrollLeft(),y=$window.scrollTop();if(x!==session.scrollLeft){session.currentX+=x-session.scrollLeft;session.scrollLeft=x}if(y!==session.scrollTop){session.currentY+=y-session.scrollTop;session.scrollTop=y}}function trackMouse(event){session.currentX=event.pageX;session.currentY=event.pageY}function isMouseOver(element){var elementPosition=element.offset(),elementBox=element[0].getBoundingClientRect(),elementWidth=elementBox.right-elementBox.left,elementHeight=elementBox.bottom-elementBox.top;return session.currentX>=elementPosition.left&&session.currentX<=elementPosition.left+elementWidth&&session.currentY>=elementPosition.top&&session.currentY<=elementPosition.top+elementHeight}function getTooltipContent(element){var tipText=element.data(DATA_POWERTIP),tipObject=element.data(DATA_POWERTIPJQ),tipTarget=element.data(DATA_POWERTIPTARGET),targetElement,content;if(tipText){if($.isFunction(tipText)){tipText=tipText.call(element[0])}content=tipText}else if(tipObject){if($.isFunction(tipObject)){tipObject=tipObject.call(element[0])}if(tipObject.length>0){content=tipObject.clone(true,true)}}else if(tipTarget){targetElement=$("#"+tipTarget);if(targetElement.length>0){content=targetElement.html()}}return content}function getViewportCollisions(coords,elementWidth,elementHeight){var viewportTop=session.scrollTop,viewportLeft=session.scrollLeft,viewportBottom=viewportTop+session.windowHeight,viewportRight=viewportLeft+session.windowWidth,collisions=Collision.none;if(coords.topviewportBottom||Math.abs(coords.bottom-session.windowHeight)>viewportBottom){collisions|=Collision.bottom}if(coords.leftviewportRight){collisions|=Collision.left}if(coords.left+elementWidth>viewportRight||coords.right1)){a.preventDefault();var c=a.originalEvent.changedTouches[0],d=document.createEvent("MouseEvents");d.initMouseEvent(b,!0,!0,window,1,c.screenX,c.screenY,c.clientX,c.clientY,!1,!1,!1,!1,0,null),a.target.dispatchEvent(d)}}if(a.support.touch="ontouchend"in document,a.support.touch){var e,b=a.ui.mouse.prototype,c=b._mouseInit,d=b._mouseDestroy;b._touchStart=function(a){var b=this;!e&&b._mouseCapture(a.originalEvent.changedTouches[0])&&(e=!0,b._touchMoved=!1,f(a,"mouseover"),f(a,"mousemove"),f(a,"mousedown"))},b._touchMove=function(a){e&&(this._touchMoved=!0,f(a,"mousemove"))},b._touchEnd=function(a){e&&(f(a,"mouseup"),f(a,"mouseout"),this._touchMoved||f(a,"click"),e=!1)},b._mouseInit=function(){var b=this;b.element.bind({touchstart:a.proxy(b,"_touchStart"),touchmove:a.proxy(b,"_touchMove"),touchend:a.proxy(b,"_touchEnd")}),c.call(b)},b._mouseDestroy=function(){var b=this;b.element.unbind({touchstart:a.proxy(b,"_touchStart"),touchmove:a.proxy(b,"_touchMove"),touchend:a.proxy(b,"_touchEnd")}),d.call(b)}}}(jQuery);/*! SmartMenus jQuery Plugin - v1.1.0 - September 17, 2017 - * http://www.smartmenus.org/ - * Copyright Vasil Dinkov, Vadikom Web Ltd. http://vadikom.com; Licensed MIT */(function(t){"function"==typeof define&&define.amd?define(["jquery"],t):"object"==typeof module&&"object"==typeof module.exports?module.exports=t(require("jquery")):t(jQuery)})(function($){function initMouseDetection(t){var e=".smartmenus_mouse";if(mouseDetectionEnabled||t)mouseDetectionEnabled&&t&&($(document).off(e),mouseDetectionEnabled=!1);else{var i=!0,s=null,o={mousemove:function(t){var e={x:t.pageX,y:t.pageY,timeStamp:(new Date).getTime()};if(s){var o=Math.abs(s.x-e.x),a=Math.abs(s.y-e.y);if((o>0||a>0)&&2>=o&&2>=a&&300>=e.timeStamp-s.timeStamp&&(mouse=!0,i)){var n=$(t.target).closest("a");n.is("a")&&$.each(menuTrees,function(){return $.contains(this.$root[0],n[0])?(this.itemEnter({currentTarget:n[0]}),!1):void 0}),i=!1}}s=e}};o[touchEvents?"touchstart":"pointerover pointermove pointerout MSPointerOver MSPointerMove MSPointerOut"]=function(t){isTouchEvent(t.originalEvent)&&(mouse=!1)},$(document).on(getEventsNS(o,e)),mouseDetectionEnabled=!0}}function isTouchEvent(t){return!/^(4|mouse)$/.test(t.pointerType)}function getEventsNS(t,e){e||(e="");var i={};for(var s in t)i[s.split(" ").join(e+" ")+e]=t[s];return i}var menuTrees=[],mouse=!1,touchEvents="ontouchstart"in window,mouseDetectionEnabled=!1,requestAnimationFrame=window.requestAnimationFrame||function(t){return setTimeout(t,1e3/60)},cancelAnimationFrame=window.cancelAnimationFrame||function(t){clearTimeout(t)},canAnimate=!!$.fn.animate;return $.SmartMenus=function(t,e){this.$root=$(t),this.opts=e,this.rootId="",this.accessIdPrefix="",this.$subArrow=null,this.activatedItems=[],this.visibleSubMenus=[],this.showTimeout=0,this.hideTimeout=0,this.scrollTimeout=0,this.clickActivated=!1,this.focusActivated=!1,this.zIndexInc=0,this.idInc=0,this.$firstLink=null,this.$firstSub=null,this.disabled=!1,this.$disableOverlay=null,this.$touchScrollingSub=null,this.cssTransforms3d="perspective"in t.style||"webkitPerspective"in t.style,this.wasCollapsible=!1,this.init()},$.extend($.SmartMenus,{hideAll:function(){$.each(menuTrees,function(){this.menuHideAll()})},destroy:function(){for(;menuTrees.length;)menuTrees[0].destroy();initMouseDetection(!0)},prototype:{init:function(t){var e=this;if(!t){menuTrees.push(this),this.rootId=((new Date).getTime()+Math.random()+"").replace(/\D/g,""),this.accessIdPrefix="sm-"+this.rootId+"-",this.$root.hasClass("sm-rtl")&&(this.opts.rightToLeftSubMenus=!0);var i=".smartmenus";this.$root.data("smartmenus",this).attr("data-smartmenus-id",this.rootId).dataSM("level",1).on(getEventsNS({"mouseover focusin":$.proxy(this.rootOver,this),"mouseout focusout":$.proxy(this.rootOut,this),keydown:$.proxy(this.rootKeyDown,this)},i)).on(getEventsNS({mouseenter:$.proxy(this.itemEnter,this),mouseleave:$.proxy(this.itemLeave,this),mousedown:$.proxy(this.itemDown,this),focus:$.proxy(this.itemFocus,this),blur:$.proxy(this.itemBlur,this),click:$.proxy(this.itemClick,this)},i),"a"),i+=this.rootId,this.opts.hideOnClick&&$(document).on(getEventsNS({touchstart:$.proxy(this.docTouchStart,this),touchmove:$.proxy(this.docTouchMove,this),touchend:$.proxy(this.docTouchEnd,this),click:$.proxy(this.docClick,this)},i)),$(window).on(getEventsNS({"resize orientationchange":$.proxy(this.winResize,this)},i)),this.opts.subIndicators&&(this.$subArrow=$("").addClass("sub-arrow"),this.opts.subIndicatorsText&&this.$subArrow.html(this.opts.subIndicatorsText)),initMouseDetection()}if(this.$firstSub=this.$root.find("ul").each(function(){e.menuInit($(this))}).eq(0),this.$firstLink=this.$root.find("a").eq(0),this.opts.markCurrentItem){var s=/(index|default)\.[^#\?\/]*/i,o=/#.*/,a=window.location.href.replace(s,""),n=a.replace(o,"");this.$root.find("a").each(function(){var t=this.href.replace(s,""),i=$(this);(t==a||t==n)&&(i.addClass("current"),e.opts.markCurrentTree&&i.parentsUntil("[data-smartmenus-id]","ul").each(function(){$(this).dataSM("parent-a").addClass("current")}))})}this.wasCollapsible=this.isCollapsible()},destroy:function(t){if(!t){var e=".smartmenus";this.$root.removeData("smartmenus").removeAttr("data-smartmenus-id").removeDataSM("level").off(e),e+=this.rootId,$(document).off(e),$(window).off(e),this.opts.subIndicators&&(this.$subArrow=null)}this.menuHideAll();var i=this;this.$root.find("ul").each(function(){var t=$(this);t.dataSM("scroll-arrows")&&t.dataSM("scroll-arrows").remove(),t.dataSM("shown-before")&&((i.opts.subMenusMinWidth||i.opts.subMenusMaxWidth)&&t.css({width:"",minWidth:"",maxWidth:""}).removeClass("sm-nowrap"),t.dataSM("scroll-arrows")&&t.dataSM("scroll-arrows").remove(),t.css({zIndex:"",top:"",left:"",marginLeft:"",marginTop:"",display:""})),0==(t.attr("id")||"").indexOf(i.accessIdPrefix)&&t.removeAttr("id")}).removeDataSM("in-mega").removeDataSM("shown-before").removeDataSM("scroll-arrows").removeDataSM("parent-a").removeDataSM("level").removeDataSM("beforefirstshowfired").removeAttr("role").removeAttr("aria-hidden").removeAttr("aria-labelledby").removeAttr("aria-expanded"),this.$root.find("a.has-submenu").each(function(){var t=$(this);0==t.attr("id").indexOf(i.accessIdPrefix)&&t.removeAttr("id")}).removeClass("has-submenu").removeDataSM("sub").removeAttr("aria-haspopup").removeAttr("aria-controls").removeAttr("aria-expanded").closest("li").removeDataSM("sub"),this.opts.subIndicators&&this.$root.find("span.sub-arrow").remove(),this.opts.markCurrentItem&&this.$root.find("a.current").removeClass("current"),t||(this.$root=null,this.$firstLink=null,this.$firstSub=null,this.$disableOverlay&&(this.$disableOverlay.remove(),this.$disableOverlay=null),menuTrees.splice($.inArray(this,menuTrees),1))},disable:function(t){if(!this.disabled){if(this.menuHideAll(),!t&&!this.opts.isPopup&&this.$root.is(":visible")){var e=this.$root.offset();this.$disableOverlay=$('
    ').css({position:"absolute",top:e.top,left:e.left,width:this.$root.outerWidth(),height:this.$root.outerHeight(),zIndex:this.getStartZIndex(!0),opacity:0}).appendTo(document.body)}this.disabled=!0}},docClick:function(t){return this.$touchScrollingSub?(this.$touchScrollingSub=null,void 0):((this.visibleSubMenus.length&&!$.contains(this.$root[0],t.target)||$(t.target).closest("a").length)&&this.menuHideAll(),void 0)},docTouchEnd:function(){if(this.lastTouch){if(!(!this.visibleSubMenus.length||void 0!==this.lastTouch.x2&&this.lastTouch.x1!=this.lastTouch.x2||void 0!==this.lastTouch.y2&&this.lastTouch.y1!=this.lastTouch.y2||this.lastTouch.target&&$.contains(this.$root[0],this.lastTouch.target))){this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0);var t=this;this.hideTimeout=setTimeout(function(){t.menuHideAll()},350)}this.lastTouch=null}},docTouchMove:function(t){if(this.lastTouch){var e=t.originalEvent.touches[0];this.lastTouch.x2=e.pageX,this.lastTouch.y2=e.pageY}},docTouchStart:function(t){var e=t.originalEvent.touches[0];this.lastTouch={x1:e.pageX,y1:e.pageY,target:e.target}},enable:function(){this.disabled&&(this.$disableOverlay&&(this.$disableOverlay.remove(),this.$disableOverlay=null),this.disabled=!1)},getClosestMenu:function(t){for(var e=$(t).closest("ul");e.dataSM("in-mega");)e=e.parent().closest("ul");return e[0]||null},getHeight:function(t){return this.getOffset(t,!0)},getOffset:function(t,e){var i;"none"==t.css("display")&&(i={position:t[0].style.position,visibility:t[0].style.visibility},t.css({position:"absolute",visibility:"hidden"}).show());var s=t[0].getBoundingClientRect&&t[0].getBoundingClientRect(),o=s&&(e?s.height||s.bottom-s.top:s.width||s.right-s.left);return o||0===o||(o=e?t[0].offsetHeight:t[0].offsetWidth),i&&t.hide().css(i),o},getStartZIndex:function(t){var e=parseInt(this[t?"$root":"$firstSub"].css("z-index"));return!t&&isNaN(e)&&(e=parseInt(this.$root.css("z-index"))),isNaN(e)?1:e},getTouchPoint:function(t){return t.touches&&t.touches[0]||t.changedTouches&&t.changedTouches[0]||t},getViewport:function(t){var e=t?"Height":"Width",i=document.documentElement["client"+e],s=window["inner"+e];return s&&(i=Math.min(i,s)),i},getViewportHeight:function(){return this.getViewport(!0)},getViewportWidth:function(){return this.getViewport()},getWidth:function(t){return this.getOffset(t)},handleEvents:function(){return!this.disabled&&this.isCSSOn()},handleItemEvents:function(t){return this.handleEvents()&&!this.isLinkInMegaMenu(t)},isCollapsible:function(){return"static"==this.$firstSub.css("position")},isCSSOn:function(){return"inline"!=this.$firstLink.css("display")},isFixed:function(){var t="fixed"==this.$root.css("position");return t||this.$root.parentsUntil("body").each(function(){return"fixed"==$(this).css("position")?(t=!0,!1):void 0}),t},isLinkInMegaMenu:function(t){return $(this.getClosestMenu(t[0])).hasClass("mega-menu")},isTouchMode:function(){return!mouse||this.opts.noMouseOver||this.isCollapsible()},itemActivate:function(t,e){var i=t.closest("ul"),s=i.dataSM("level");if(s>1&&(!this.activatedItems[s-2]||this.activatedItems[s-2][0]!=i.dataSM("parent-a")[0])){var o=this;$(i.parentsUntil("[data-smartmenus-id]","ul").get().reverse()).add(i).each(function(){o.itemActivate($(this).dataSM("parent-a"))})}if((!this.isCollapsible()||e)&&this.menuHideSubMenus(this.activatedItems[s-1]&&this.activatedItems[s-1][0]==t[0]?s:s-1),this.activatedItems[s-1]=t,this.$root.triggerHandler("activate.smapi",t[0])!==!1){var a=t.dataSM("sub");a&&(this.isTouchMode()||!this.opts.showOnClick||this.clickActivated)&&this.menuShow(a)}},itemBlur:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&this.$root.triggerHandler("blur.smapi",e[0])},itemClick:function(t){var e=$(t.currentTarget);if(this.handleItemEvents(e)){if(this.$touchScrollingSub&&this.$touchScrollingSub[0]==e.closest("ul")[0])return this.$touchScrollingSub=null,t.stopPropagation(),!1;if(this.$root.triggerHandler("click.smapi",e[0])===!1)return!1;var i=$(t.target).is(".sub-arrow"),s=e.dataSM("sub"),o=s?2==s.dataSM("level"):!1,a=this.isCollapsible(),n=/toggle$/.test(this.opts.collapsibleBehavior),r=/link$/.test(this.opts.collapsibleBehavior),h=/^accordion/.test(this.opts.collapsibleBehavior);if(s&&!s.is(":visible")){if((!r||!a||i)&&(this.opts.showOnClick&&o&&(this.clickActivated=!0),this.itemActivate(e,h),s.is(":visible")))return this.focusActivated=!0,!1}else if(a&&(n||i))return this.itemActivate(e,h),this.menuHide(s),n&&(this.focusActivated=!1),!1;return this.opts.showOnClick&&o||e.hasClass("disabled")||this.$root.triggerHandler("select.smapi",e[0])===!1?!1:void 0}},itemDown:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&e.dataSM("mousedown",!0)},itemEnter:function(t){var e=$(t.currentTarget);if(this.handleItemEvents(e)){if(!this.isTouchMode()){this.showTimeout&&(clearTimeout(this.showTimeout),this.showTimeout=0);var i=this;this.showTimeout=setTimeout(function(){i.itemActivate(e)},this.opts.showOnClick&&1==e.closest("ul").dataSM("level")?1:this.opts.showTimeout)}this.$root.triggerHandler("mouseenter.smapi",e[0])}},itemFocus:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&(!this.focusActivated||this.isTouchMode()&&e.dataSM("mousedown")||this.activatedItems.length&&this.activatedItems[this.activatedItems.length-1][0]==e[0]||this.itemActivate(e,!0),this.$root.triggerHandler("focus.smapi",e[0]))},itemLeave:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&(this.isTouchMode()||(e[0].blur(),this.showTimeout&&(clearTimeout(this.showTimeout),this.showTimeout=0)),e.removeDataSM("mousedown"),this.$root.triggerHandler("mouseleave.smapi",e[0]))},menuHide:function(t){if(this.$root.triggerHandler("beforehide.smapi",t[0])!==!1&&(canAnimate&&t.stop(!0,!0),"none"!=t.css("display"))){var e=function(){t.css("z-index","")};this.isCollapsible()?canAnimate&&this.opts.collapsibleHideFunction?this.opts.collapsibleHideFunction.call(this,t,e):t.hide(this.opts.collapsibleHideDuration,e):canAnimate&&this.opts.hideFunction?this.opts.hideFunction.call(this,t,e):t.hide(this.opts.hideDuration,e),t.dataSM("scroll")&&(this.menuScrollStop(t),t.css({"touch-action":"","-ms-touch-action":"","-webkit-transform":"",transform:""}).off(".smartmenus_scroll").removeDataSM("scroll").dataSM("scroll-arrows").hide()),t.dataSM("parent-a").removeClass("highlighted").attr("aria-expanded","false"),t.attr({"aria-expanded":"false","aria-hidden":"true"});var i=t.dataSM("level");this.activatedItems.splice(i-1,1),this.visibleSubMenus.splice($.inArray(t,this.visibleSubMenus),1),this.$root.triggerHandler("hide.smapi",t[0])}},menuHideAll:function(){this.showTimeout&&(clearTimeout(this.showTimeout),this.showTimeout=0);for(var t=this.opts.isPopup?1:0,e=this.visibleSubMenus.length-1;e>=t;e--)this.menuHide(this.visibleSubMenus[e]);this.opts.isPopup&&(canAnimate&&this.$root.stop(!0,!0),this.$root.is(":visible")&&(canAnimate&&this.opts.hideFunction?this.opts.hideFunction.call(this,this.$root):this.$root.hide(this.opts.hideDuration))),this.activatedItems=[],this.visibleSubMenus=[],this.clickActivated=!1,this.focusActivated=!1,this.zIndexInc=0,this.$root.triggerHandler("hideAll.smapi")},menuHideSubMenus:function(t){for(var e=this.activatedItems.length-1;e>=t;e--){var i=this.activatedItems[e].dataSM("sub");i&&this.menuHide(i)}},menuInit:function(t){if(!t.dataSM("in-mega")){t.hasClass("mega-menu")&&t.find("ul").dataSM("in-mega",!0);for(var e=2,i=t[0];(i=i.parentNode.parentNode)!=this.$root[0];)e++;var s=t.prevAll("a").eq(-1);s.length||(s=t.prevAll().find("a").eq(-1)),s.addClass("has-submenu").dataSM("sub",t),t.dataSM("parent-a",s).dataSM("level",e).parent().dataSM("sub",t);var o=s.attr("id")||this.accessIdPrefix+ ++this.idInc,a=t.attr("id")||this.accessIdPrefix+ ++this.idInc;s.attr({id:o,"aria-haspopup":"true","aria-controls":a,"aria-expanded":"false"}),t.attr({id:a,role:"group","aria-hidden":"true","aria-labelledby":o,"aria-expanded":"false"}),this.opts.subIndicators&&s[this.opts.subIndicatorsPos](this.$subArrow.clone())}},menuPosition:function(t){var e,i,s=t.dataSM("parent-a"),o=s.closest("li"),a=o.parent(),n=t.dataSM("level"),r=this.getWidth(t),h=this.getHeight(t),u=s.offset(),l=u.left,c=u.top,d=this.getWidth(s),m=this.getHeight(s),p=$(window),f=p.scrollLeft(),v=p.scrollTop(),b=this.getViewportWidth(),S=this.getViewportHeight(),g=a.parent().is("[data-sm-horizontal-sub]")||2==n&&!a.hasClass("sm-vertical"),M=this.opts.rightToLeftSubMenus&&!o.is("[data-sm-reverse]")||!this.opts.rightToLeftSubMenus&&o.is("[data-sm-reverse]"),w=2==n?this.opts.mainMenuSubOffsetX:this.opts.subMenusSubOffsetX,T=2==n?this.opts.mainMenuSubOffsetY:this.opts.subMenusSubOffsetY;if(g?(e=M?d-r-w:w,i=this.opts.bottomToTopSubMenus?-h-T:m+T):(e=M?w-r:d-w,i=this.opts.bottomToTopSubMenus?m-T-h:T),this.opts.keepInViewport){var y=l+e,I=c+i;if(M&&f>y?e=g?f-y+e:d-w:!M&&y+r>f+b&&(e=g?f+b-r-y+e:w-r),g||(S>h&&I+h>v+S?i+=v+S-h-I:(h>=S||v>I)&&(i+=v-I)),g&&(I+h>v+S+.49||v>I)||!g&&h>S+.49){var x=this;t.dataSM("scroll-arrows")||t.dataSM("scroll-arrows",$([$('')[0],$('')[0]]).on({mouseenter:function(){t.dataSM("scroll").up=$(this).hasClass("scroll-up"),x.menuScroll(t)},mouseleave:function(e){x.menuScrollStop(t),x.menuScrollOut(t,e)},"mousewheel DOMMouseScroll":function(t){t.preventDefault()}}).insertAfter(t));var A=".smartmenus_scroll";if(t.dataSM("scroll",{y:this.cssTransforms3d?0:i-m,step:1,itemH:m,subH:h,arrowDownH:this.getHeight(t.dataSM("scroll-arrows").eq(1))}).on(getEventsNS({mouseover:function(e){x.menuScrollOver(t,e)},mouseout:function(e){x.menuScrollOut(t,e)},"mousewheel DOMMouseScroll":function(e){x.menuScrollMousewheel(t,e)}},A)).dataSM("scroll-arrows").css({top:"auto",left:"0",marginLeft:e+(parseInt(t.css("border-left-width"))||0),width:r-(parseInt(t.css("border-left-width"))||0)-(parseInt(t.css("border-right-width"))||0),zIndex:t.css("z-index")}).eq(g&&this.opts.bottomToTopSubMenus?0:1).show(),this.isFixed()){var C={};C[touchEvents?"touchstart touchmove touchend":"pointerdown pointermove pointerup MSPointerDown MSPointerMove MSPointerUp"]=function(e){x.menuScrollTouch(t,e)},t.css({"touch-action":"none","-ms-touch-action":"none"}).on(getEventsNS(C,A))}}}t.css({top:"auto",left:"0",marginLeft:e,marginTop:i-m})},menuScroll:function(t,e,i){var s,o=t.dataSM("scroll"),a=t.dataSM("scroll-arrows"),n=o.up?o.upEnd:o.downEnd;if(!e&&o.momentum){if(o.momentum*=.92,s=o.momentum,.5>s)return this.menuScrollStop(t),void 0}else s=i||(e||!this.opts.scrollAccelerate?this.opts.scrollStep:Math.floor(o.step));var r=t.dataSM("level");if(this.activatedItems[r-1]&&this.activatedItems[r-1].dataSM("sub")&&this.activatedItems[r-1].dataSM("sub").is(":visible")&&this.menuHideSubMenus(r-1),o.y=o.up&&o.y>=n||!o.up&&n>=o.y?o.y:Math.abs(n-o.y)>s?o.y+(o.up?s:-s):n,t.css(this.cssTransforms3d?{"-webkit-transform":"translate3d(0, "+o.y+"px, 0)",transform:"translate3d(0, "+o.y+"px, 0)"}:{marginTop:o.y}),mouse&&(o.up&&o.y>o.downEnd||!o.up&&o.y0;t.dataSM("scroll-arrows").eq(i?0:1).is(":visible")&&(t.dataSM("scroll").up=i,this.menuScroll(t,!0))}e.preventDefault()},menuScrollOut:function(t,e){mouse&&(/^scroll-(up|down)/.test((e.relatedTarget||"").className)||(t[0]==e.relatedTarget||$.contains(t[0],e.relatedTarget))&&this.getClosestMenu(e.relatedTarget)==t[0]||t.dataSM("scroll-arrows").css("visibility","hidden"))},menuScrollOver:function(t,e){if(mouse&&!/^scroll-(up|down)/.test(e.target.className)&&this.getClosestMenu(e.target)==t[0]){this.menuScrollRefreshData(t);var i=t.dataSM("scroll"),s=$(window).scrollTop()-t.dataSM("parent-a").offset().top-i.itemH;t.dataSM("scroll-arrows").eq(0).css("margin-top",s).end().eq(1).css("margin-top",s+this.getViewportHeight()-i.arrowDownH).end().css("visibility","visible")}},menuScrollRefreshData:function(t){var e=t.dataSM("scroll"),i=$(window).scrollTop()-t.dataSM("parent-a").offset().top-e.itemH;this.cssTransforms3d&&(i=-(parseFloat(t.css("margin-top"))-i)),$.extend(e,{upEnd:i,downEnd:i+this.getViewportHeight()-e.subH})},menuScrollStop:function(t){return this.scrollTimeout?(cancelAnimationFrame(this.scrollTimeout),this.scrollTimeout=0,t.dataSM("scroll").step=1,!0):void 0},menuScrollTouch:function(t,e){if(e=e.originalEvent,isTouchEvent(e)){var i=this.getTouchPoint(e);if(this.getClosestMenu(i.target)==t[0]){var s=t.dataSM("scroll");if(/(start|down)$/i.test(e.type))this.menuScrollStop(t)?(e.preventDefault(),this.$touchScrollingSub=t):this.$touchScrollingSub=null,this.menuScrollRefreshData(t),$.extend(s,{touchStartY:i.pageY,touchStartTime:e.timeStamp});else if(/move$/i.test(e.type)){var o=void 0!==s.touchY?s.touchY:s.touchStartY;if(void 0!==o&&o!=i.pageY){this.$touchScrollingSub=t;var a=i.pageY>o;void 0!==s.up&&s.up!=a&&$.extend(s,{touchStartY:i.pageY,touchStartTime:e.timeStamp}),$.extend(s,{up:a,touchY:i.pageY}),this.menuScroll(t,!0,Math.abs(i.pageY-o))}e.preventDefault()}else void 0!==s.touchY&&((s.momentum=15*Math.pow(Math.abs(i.pageY-s.touchStartY)/(e.timeStamp-s.touchStartTime),2))&&(this.menuScrollStop(t),this.menuScroll(t),e.preventDefault()),delete s.touchY)}}},menuShow:function(t){if((t.dataSM("beforefirstshowfired")||(t.dataSM("beforefirstshowfired",!0),this.$root.triggerHandler("beforefirstshow.smapi",t[0])!==!1))&&this.$root.triggerHandler("beforeshow.smapi",t[0])!==!1&&(t.dataSM("shown-before",!0),canAnimate&&t.stop(!0,!0),!t.is(":visible"))){var e=t.dataSM("parent-a"),i=this.isCollapsible();if((this.opts.keepHighlighted||i)&&e.addClass("highlighted"),i)t.removeClass("sm-nowrap").css({zIndex:"",width:"auto",minWidth:"",maxWidth:"",top:"",left:"",marginLeft:"",marginTop:""});else{if(t.css("z-index",this.zIndexInc=(this.zIndexInc||this.getStartZIndex())+1),(this.opts.subMenusMinWidth||this.opts.subMenusMaxWidth)&&(t.css({width:"auto",minWidth:"",maxWidth:""}).addClass("sm-nowrap"),this.opts.subMenusMinWidth&&t.css("min-width",this.opts.subMenusMinWidth),this.opts.subMenusMaxWidth)){var s=this.getWidth(t);t.css("max-width",this.opts.subMenusMaxWidth),s>this.getWidth(t)&&t.removeClass("sm-nowrap").css("width",this.opts.subMenusMaxWidth)}this.menuPosition(t)}var o=function(){t.css("overflow","")};i?canAnimate&&this.opts.collapsibleShowFunction?this.opts.collapsibleShowFunction.call(this,t,o):t.show(this.opts.collapsibleShowDuration,o):canAnimate&&this.opts.showFunction?this.opts.showFunction.call(this,t,o):t.show(this.opts.showDuration,o),e.attr("aria-expanded","true"),t.attr({"aria-expanded":"true","aria-hidden":"false"}),this.visibleSubMenus.push(t),this.$root.triggerHandler("show.smapi",t[0])}},popupHide:function(t){this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0);var e=this;this.hideTimeout=setTimeout(function(){e.menuHideAll()},t?1:this.opts.hideTimeout)},popupShow:function(t,e){if(!this.opts.isPopup)return alert('SmartMenus jQuery Error:\n\nIf you want to show this menu via the "popupShow" method, set the isPopup:true option.'),void 0;if(this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0),this.$root.dataSM("shown-before",!0),canAnimate&&this.$root.stop(!0,!0),!this.$root.is(":visible")){this.$root.css({left:t,top:e});var i=this,s=function(){i.$root.css("overflow","")};canAnimate&&this.opts.showFunction?this.opts.showFunction.call(this,this.$root,s):this.$root.show(this.opts.showDuration,s),this.visibleSubMenus[0]=this.$root}},refresh:function(){this.destroy(!0),this.init(!0)},rootKeyDown:function(t){if(this.handleEvents())switch(t.keyCode){case 27:var e=this.activatedItems[0];if(e){this.menuHideAll(),e[0].focus();var i=e.dataSM("sub");i&&this.menuHide(i)}break;case 32:var s=$(t.target);if(s.is("a")&&this.handleItemEvents(s)){var i=s.dataSM("sub");i&&!i.is(":visible")&&(this.itemClick({currentTarget:t.target}),t.preventDefault())}}},rootOut:function(t){if(this.handleEvents()&&!this.isTouchMode()&&t.target!=this.$root[0]&&(this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0),!this.opts.showOnClick||!this.opts.hideOnClick)){var e=this;this.hideTimeout=setTimeout(function(){e.menuHideAll()},this.opts.hideTimeout)}},rootOver:function(t){this.handleEvents()&&!this.isTouchMode()&&t.target!=this.$root[0]&&this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0)},winResize:function(t){if(this.handleEvents()){if(!("onorientationchange"in window)||"orientationchange"==t.type){var e=this.isCollapsible();this.wasCollapsible&&e||(this.activatedItems.length&&this.activatedItems[this.activatedItems.length-1][0].blur(),this.menuHideAll()),this.wasCollapsible=e}}else if(this.$disableOverlay){var i=this.$root.offset();this.$disableOverlay.css({top:i.top,left:i.left,width:this.$root.outerWidth(),height:this.$root.outerHeight()})}}}}),$.fn.dataSM=function(t,e){return e?this.data(t+"_smartmenus",e):this.data(t+"_smartmenus")},$.fn.removeDataSM=function(t){return this.removeData(t+"_smartmenus")},$.fn.smartmenus=function(options){if("string"==typeof options){var args=arguments,method=options;return Array.prototype.shift.call(args),this.each(function(){var t=$(this).data("smartmenus");t&&t[method]&&t[method].apply(t,args)})}return this.each(function(){var dataOpts=$(this).data("sm-options")||null;if(dataOpts)try{dataOpts=eval("("+dataOpts+")")}catch(e){dataOpts=null,alert('ERROR\n\nSmartMenus jQuery init:\nInvalid "data-sm-options" attribute value syntax.')}new $.SmartMenus(this,$.extend({},$.fn.smartmenus.defaults,options,dataOpts))})},$.fn.smartmenus.defaults={isPopup:!1,mainMenuSubOffsetX:0,mainMenuSubOffsetY:0,subMenusSubOffsetX:0,subMenusSubOffsetY:0,subMenusMinWidth:"10em",subMenusMaxWidth:"20em",subIndicators:!0,subIndicatorsPos:"append",subIndicatorsText:"",scrollStep:30,scrollAccelerate:!0,showTimeout:250,hideTimeout:500,showDuration:0,showFunction:null,hideDuration:0,hideFunction:function(t,e){t.fadeOut(200,e)},collapsibleShowDuration:0,collapsibleShowFunction:function(t,e){t.slideDown(200,e)},collapsibleHideDuration:0,collapsibleHideFunction:function(t,e){t.slideUp(200,e)},showOnClick:!1,hideOnClick:!0,noMouseOver:!1,keepInViewport:!0,keepHighlighted:!0,markCurrentItem:!1,markCurrentTree:!0,rightToLeftSubMenus:!1,bottomToTopSubMenus:!1,collapsibleBehavior:"default"},$}); \ No newline at end of file diff --git a/documentation/html/lift_8h_source.html b/documentation/html/lift_8h_source.html deleted file mode 100644 index 5f4ded0..0000000 --- a/documentation/html/lift_8h_source.html +++ /dev/null @@ -1,344 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/subsystems/lift.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    lift.h
    -
    -
    -
    1#pragma once
    -
    2
    -
    3#include "vex.h"
    -
    4#include "../core/include/utils/pid.h"
    -
    5#include <iostream>
    -
    6#include <map>
    -
    7#include <atomic>
    -
    8#include <vector>
    -
    9
    -
    10using namespace vex;
    -
    11using namespace std;
    -
    12
    -
    20template <typename T>
    -
    21class Lift
    -
    22{
    -
    23 public:
    -
    24
    - -
    32 {
    -
    33 double up_speed, down_speed;
    -
    34 double softstop_up, softstop_down;
    -
    35
    -
    36 PID::pid_config_t lift_pid_cfg;
    -
    37 };
    -
    38
    -
    60 Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map<T, double> &setpoint_map, limit *homing_switch=NULL)
    -
    61 : lift_motors(lift_motors), cfg(lift_cfg), lift_pid(cfg.lift_pid_cfg), setpoint_map(setpoint_map), homing_switch(homing_switch)
    -
    62 {
    -
    63
    -
    64 is_async = true;
    -
    65 setpoint = 0;
    -
    66
    -
    67 // Create a background task that is constantly updating the lift PID, if requested.
    -
    68 // Set once, and forget.
    -
    69 task t([](void* ptr){
    -
    70 Lift &lift = *((Lift*) ptr);
    -
    71
    -
    72 while(true)
    -
    73 {
    -
    74 if(lift.get_async())
    -
    75 lift.hold();
    -
    76
    -
    77 vexDelay(50);
    -
    78 }
    -
    79
    -
    80 return 0;
    -
    81 }, this);
    -
    82
    -
    83 }
    -
    84
    -
    93 void control_continuous(bool up_ctrl, bool down_ctrl)
    -
    94 {
    -
    95 static timer tmr;
    -
    96
    -
    97 double cur_pos = 0;
    -
    98
    -
    99 // Check if there's a hook for a custom sensor. If not, use the motors.
    -
    100 if(get_sensor == NULL)
    -
    101 cur_pos = lift_motors.position(rev);
    -
    102 else
    -
    103 cur_pos = get_sensor();
    -
    104
    -
    105 if(up_ctrl && cur_pos < cfg.softstop_up)
    -
    106 {
    -
    107 lift_motors.spin(directionType::fwd, cfg.up_speed, volt);
    -
    108 setpoint = cur_pos + .3;
    -
    109
    -
    110 // std::cout << "DEBUG OUT: UP " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n";
    -
    111
    -
    112 // Disable the PID while going UP.
    -
    113 is_async = false;
    -
    114 } else if(down_ctrl && cur_pos > cfg.softstop_down)
    -
    115 {
    -
    116 // Lower the lift slowly, at a rate defined by down_speed
    -
    117 if(setpoint > cfg.softstop_down)
    -
    118 setpoint = setpoint - (tmr.time(sec) * cfg.down_speed);
    -
    119 // std::cout << "DEBUG OUT: DOWN " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n";
    -
    120 is_async = true;
    -
    121 } else
    -
    122 {
    -
    123 // Hold the lift at the last setpoint
    -
    124 is_async = true;
    -
    125 }
    -
    126
    -
    127 tmr.reset();
    -
    128 }
    -
    129
    -
    138 void control_manual(bool up_btn, bool down_btn, int volt_up, int volt_down)
    -
    139 {
    -
    140 static bool down_hold = false;
    -
    141 static bool init = true;
    -
    142
    -
    143 // Allow for setting position while still calling this function
    -
    144 if(init || up_btn || down_btn)
    -
    145 {
    -
    146 init = false;
    -
    147 is_async = false;
    -
    148 }
    -
    149
    -
    150 double rev = lift_motors.position(rotationUnits::rev);
    -
    151
    -
    152 if(rev < cfg.softstop_down && down_btn)
    -
    153 down_hold = true;
    -
    154 else if( !down_btn )
    -
    155 down_hold = false;
    -
    156
    -
    157 if(up_btn && rev < cfg.softstop_up)
    -
    158 lift_motors.spin(directionType::fwd, volt_up, voltageUnits::volt);
    -
    159 else if(down_btn && rev > cfg.softstop_down && !down_hold)
    -
    160 lift_motors.spin(directionType::rev, volt_down, voltageUnits::volt);
    -
    161 else
    -
    162 lift_motors.spin(directionType::fwd, 0, voltageUnits::volt);
    -
    163
    -
    164 }
    -
    165
    -
    177 void control_setpoints(bool up_step, bool down_step, vector<T> pos_list)
    -
    178 {
    -
    179 // Make sure inputs are only processed on the rising edge of the button
    -
    180 static bool up_last = up_step, down_last = down_step;
    -
    181
    -
    182 bool up_rising = up_step && !up_last;
    -
    183 bool down_rising = down_step && !down_last;
    -
    184
    -
    185 up_last = up_step;
    -
    186 down_last = down_step;
    -
    187
    -
    188 static int cur_index = 0;
    -
    189
    -
    190 // Avoid an index overflow. Shouldn't happen unless the user changes pos_list between calls.
    -
    191 if(cur_index >= pos_list.size())
    -
    192 cur_index = pos_list.size() - 1;
    -
    193
    -
    194 // Increment or decrement the index of the list, bringing it up or down.
    -
    195 if(up_rising && cur_index < (pos_list.size() - 1))
    -
    196 cur_index++;
    -
    197 else if(down_rising && cur_index > 0)
    -
    198 cur_index--;
    -
    199
    -
    200 // Set the lift to hold the position in the background with the PID loop
    -
    201 set_position(pos_list[cur_index]);
    -
    202 is_async = true;
    -
    203
    -
    204 }
    -
    205
    -
    214 bool set_position(T pos)
    -
    215 {
    -
    216 this->setpoint = setpoint_map[pos];
    -
    217 is_async = true;
    -
    218
    -
    219 return (lift_pid.get_target() == this->setpoint) && lift_pid.is_on_target();
    -
    220 }
    -
    221
    -
    228 bool set_setpoint(double val)
    -
    229 {
    -
    230 this->setpoint = val;
    -
    231 return (lift_pid.get_target() == this->setpoint) && lift_pid.is_on_target();
    -
    232 }
    -
    233
    - -
    238 {
    -
    239 return this->setpoint;
    -
    240 }
    -
    241
    -
    246 void hold()
    -
    247 {
    -
    248 lift_pid.set_target(setpoint);
    -
    249 // std::cout << "DEBUG OUT: SETPOINT " << setpoint << "\n";
    -
    250
    -
    251 if(get_sensor != NULL)
    -
    252 lift_pid.update(get_sensor());
    -
    253 else
    -
    254 lift_pid.update(lift_motors.position(rev));
    -
    255
    -
    256 // std::cout << "DEBUG OUT: ROTATION " << lift_motors.rotation(rev) << "\n\n";
    -
    257
    -
    258 lift_motors.spin(fwd, lift_pid.get(), volt);
    -
    259 }
    -
    260
    -
    265 void home()
    -
    266 {
    -
    267 static timer tmr;
    -
    268 tmr.reset();
    -
    269
    -
    270 while(tmr.time(sec) < 3)
    -
    271 {
    -
    272 lift_motors.spin(directionType::rev, 6, volt);
    -
    273
    -
    274 if (homing_switch == NULL && lift_motors.current(currentUnits::amp) > 1.5)
    -
    275 break;
    -
    276 else if (homing_switch != NULL && homing_switch->pressing())
    -
    277 break;
    -
    278 }
    -
    279
    -
    280 if(reset_sensor != NULL)
    -
    281 reset_sensor();
    -
    282
    -
    283 lift_motors.resetPosition();
    -
    284 lift_motors.stop();
    -
    285
    -
    286 }
    -
    287
    - -
    292 {
    -
    293 return is_async;
    -
    294 }
    -
    295
    -
    301 void set_async(bool val)
    -
    302 {
    -
    303 this->is_async = val;
    -
    304 }
    -
    305
    -
    315 void set_sensor_function(double (*fn_ptr) (void))
    -
    316 {
    -
    317 this->get_sensor = fn_ptr;
    -
    318 }
    -
    319
    -
    326 void set_sensor_reset(void (*fn_ptr) (void))
    -
    327 {
    -
    328 this->reset_sensor = fn_ptr;
    -
    329 }
    -
    330
    -
    331 private:
    -
    332
    -
    333 motor_group &lift_motors;
    -
    334 lift_cfg_t &cfg;
    -
    335 PID lift_pid;
    -
    336 map<T, double> &setpoint_map;
    -
    337 limit *homing_switch;
    -
    338
    -
    339 atomic<double> setpoint;
    -
    340 atomic<bool> is_async;
    -
    341
    -
    342 double (*get_sensor)(void) = NULL;
    -
    343 void (*reset_sensor)(void) = NULL;
    -
    344
    -
    345
    -
    346};
    -
    Definition: lift.h:22
    -
    void set_sensor_function(double(*fn_ptr)(void))
    Definition: lift.h:315
    -
    bool set_setpoint(double val)
    Definition: lift.h:228
    -
    bool get_async()
    Definition: lift.h:291
    -
    void set_sensor_reset(void(*fn_ptr)(void))
    Definition: lift.h:326
    -
    void control_setpoints(bool up_step, bool down_step, vector< T > pos_list)
    Definition: lift.h:177
    -
    void set_async(bool val)
    Definition: lift.h:301
    -
    void hold()
    Definition: lift.h:246
    -
    Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map< T, double > &setpoint_map, limit *homing_switch=NULL)
    Definition: lift.h:60
    -
    bool set_position(T pos)
    Definition: lift.h:214
    -
    void home()
    Definition: lift.h:265
    -
    void control_manual(bool up_btn, bool down_btn, int volt_up, int volt_down)
    Definition: lift.h:138
    -
    double get_setpoint()
    Definition: lift.h:237
    -
    void control_continuous(bool up_ctrl, bool down_ctrl)
    Definition: lift.h:93
    -
    Definition: pid.h:24
    -
    double get_target()
    Definition: pid.cpp:97
    -
    void set_target(double target)
    Definition: pid.cpp:105
    -
    double update(double sensor_val) override
    Definition: pid.cpp:25
    -
    double get() override
    Definition: pid.cpp:81
    -
    bool is_on_target() override
    Definition: pid.cpp:124
    -
    Definition: lift.h:32
    -
    Definition: pid.h:41
    -
    - - - - diff --git a/documentation/html/math__util_8h_source.html b/documentation/html/math__util_8h_source.html deleted file mode 100644 index 179c2b5..0000000 --- a/documentation/html/math__util_8h_source.html +++ /dev/null @@ -1,128 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/math_util.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    math_util.h
    -
    -
    -
    1#pragma once
    -
    2#include "math.h"
    -
    3#include "vex.h"
    -
    4#include <vector>
    -
    5
    -
    13double clamp(double value, double low, double high);
    -
    14
    -
    21double sign(double x);
    -
    22
    -
    23double wrap_angle_deg(double input);
    -
    24double wrap_angle_rad(double input);
    -
    25
    -
    26/*
    -
    27Calculates the variance of a set of numbers (needed for linear regression)
    -
    28https://en.wikipedia.org/wiki/Variance
    -
    29@param values the values for which the variance is taken
    -
    30@param mean the average of values
    -
    31*/
    -
    32double variance(std::vector<double> const &values, double mean);
    -
    33
    -
    34
    -
    35/*
    -
    36Calculates the average of a vector of doubles
    -
    37@param values the list of values for which the average is taken
    -
    38*/
    -
    39double mean(std::vector<double> const &values);
    -
    40
    -
    41/*
    -
    42Calculates the covariance of a set of points (needed for linear regression)
    -
    43https://en.wikipedia.org/wiki/Covariance
    -
    44
    -
    45@param points the points for which the covariance is taken
    -
    46@param meanx the mean value of all x coordinates in points
    -
    47@param meany the mean value of all y coordinates in points
    -
    48*/
    -
    49double covariance(std::vector<std::pair<double, double>> const &points, double meanx, double meany);
    -
    50
    -
    51/*
    -
    52Calculates the slope and y intercept of the line of best fit for the data
    -
    53@param points the points for the data
    -
    54*/
    -
    55std::pair<double, double> calculate_linear_regression(std::vector<std::pair<double, double>> const &points);
    -
    56
    -
    - - - - diff --git a/documentation/html/md_README.html b/documentation/html/md_README.html deleted file mode 100644 index 4b959b6..0000000 --- a/documentation/html/md_README.html +++ /dev/null @@ -1,109 +0,0 @@ - - - - - - - -RIT VEXU Core API: Core - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    Core
    -
    -
    -

    This is the host repository for the custom VEX libraries used by the RIT VEXU team

    -

    -Getting Started

    -

    In order to simply use this repo, you can either clone it into your VEXcode project folder, or download the .zip and place it into a core/ subfolder. Then follow the instructions for setting up compilation at Wiki/BuildSystem

    -

    If you wish to contribute, follow the instructions at Wiki/ProjectSetup

    -

    -Features

    -

    Here is the current feature list this repo provides:

    -

    Subsystems (See Wiki/Subsystems):
    -

      -
    • Tank drivetrain (user control / autonomous)
    • -
    • Mecanum drivetrain (user control / autonomous)
    • -
    • Odometry
    • -
    • Flywheel
    • -
    • Lift
    • -
    • Custom encoders
    • -
    -

    Utilities (See Wiki/Utilites):
    -

      -
    • PID controller
    • -
    • FeedForward controller
    • -
    • Trapezoidal motion profile controller
    • -
    • Pure Pursuit
    • -
    • Generic auto program builder
    • -
    • Auto program UI selector
    • -
    • Mathematical classes (Vector2D, Moving Average)
    • -
    -
    -
    - - - - diff --git a/documentation/html/mecanum__drive_8h_source.html b/documentation/html/mecanum__drive_8h_source.html deleted file mode 100644 index 11f2c6c..0000000 --- a/documentation/html/mecanum__drive_8h_source.html +++ /dev/null @@ -1,151 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/subsystems/mecanum_drive.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    mecanum_drive.h
    -
    -
    -
    1#pragma once
    -
    2
    -
    3#include "vex.h"
    -
    4#include "../core/include/utils/pid.h"
    -
    5
    -
    6#ifndef PI
    -
    7#define PI 3.141592654
    -
    8#endif
    -
    9
    - -
    15{
    -
    16
    -
    17 public:
    -
    18
    - -
    23 {
    -
    24 // PID configurations for autonomous driving
    -
    25 PID::pid_config_t drive_pid_conf;
    -
    26 PID::pid_config_t drive_gyro_pid_conf;
    -
    27 PID::pid_config_t turn_pid_conf;
    -
    28
    -
    29 // Diameter of the mecanum wheels
    -
    30 double drive_wheel_diam;
    -
    31
    -
    32 // Diameter of the perpendicular undriven encoder wheel
    -
    33 double lateral_wheel_diam;
    -
    34
    -
    35 // Width between the center of the left and right wheels
    -
    36 double wheelbase_width;
    -
    37
    -
    38 };
    -
    39
    -
    43 MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear,
    -
    44 vex::rotation *lateral_wheel=NULL, vex::inertial *imu=NULL, mecanumdrive_config_t *config=NULL);
    -
    45
    -
    54 void drive_raw(double direction_deg, double magnitude, double rotation);
    -
    55
    -
    66 void drive(double left_y, double left_x, double right_x, int power=2);
    -
    67
    -
    80 bool auto_drive(double inches, double direction, double speed, bool gyro_correction=true);
    -
    81
    -
    92 bool auto_turn(double degrees, double speed, bool ignore_imu=false);
    -
    93
    -
    94 private:
    -
    95
    -
    96 vex::motor &left_front, &right_front, &left_rear, &right_rear;
    -
    97
    - -
    99 vex::rotation *lateral_wheel;
    -
    100 vex::inertial *imu;
    -
    101
    -
    102 PID *drive_pid = NULL;
    -
    103 PID *drive_gyro_pid = NULL;
    -
    104 PID *turn_pid = NULL;
    -
    105
    -
    106 bool init = true;
    -
    107
    -
    108};
    -
    Definition: mecanum_drive.h:15
    -
    void drive_raw(double direction_deg, double magnitude, double rotation)
    Definition: mecanum_drive.cpp:34
    -
    bool auto_drive(double inches, double direction, double speed, bool gyro_correction=true)
    Definition: mecanum_drive.cpp:98
    -
    void drive(double left_y, double left_x, double right_x, int power=2)
    Definition: mecanum_drive.cpp:68
    -
    bool auto_turn(double degrees, double speed, bool ignore_imu=false)
    Definition: mecanum_drive.cpp:218
    -
    Definition: pid.h:24
    -
    Definition: mecanum_drive.h:23
    -
    Definition: pid.h:41
    -
    - - - - diff --git a/documentation/html/menu.js b/documentation/html/menu.js deleted file mode 100644 index b0b2693..0000000 --- a/documentation/html/menu.js +++ /dev/null @@ -1,136 +0,0 @@ -/* - @licstart The following is the entire license notice for the JavaScript code in this file. - - The MIT License (MIT) - - Copyright (C) 1997-2020 by Dimitri van Heesch - - Permission is hereby granted, free of charge, to any person obtaining a copy of this software - and associated documentation files (the "Software"), to deal in the Software without restriction, - including without limitation the rights to use, copy, modify, merge, publish, distribute, - sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is - furnished to do so, subject to the following conditions: - - The above copyright notice and this permission notice shall be included in all copies or - substantial portions of the Software. - - THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING - BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, - DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - - @licend The above is the entire license notice for the JavaScript code in this file - */ -function initMenu(relPath,searchEnabled,serverSide,searchPage,search) { - function makeTree(data,relPath) { - var result=''; - if ('children' in data) { - result+='
      '; - for (var i in data.children) { - var url; - var link; - link = data.children[i].url; - if (link.substring(0,1)=='^') { - url = link.substring(1); - } else { - url = relPath+link; - } - result+='
    • '+ - data.children[i].text+''+ - makeTree(data.children[i],relPath)+'
    • '; - } - result+='
    '; - } - return result; - } - var searchBoxHtml; - if (searchEnabled) { - if (serverSide) { - searchBoxHtml='
    '+ - '
    '+ - '
     '+ - ''+ - '
    '+ - '
    '+ - '
    '+ - '
    '; - } else { - searchBoxHtml='
    '+ - ''+ - ' '+ - ''+ - ''+ - ''+ - ''+ - ''+ - '
    '; - } - } - - $('#main-nav').before('
    '+ - ''+ - ''+ - '
    '); - $('#main-nav').append(makeTree(menudata,relPath)); - $('#main-nav').children(':first').addClass('sm sm-dox').attr('id','main-menu'); - if (searchBoxHtml) { - $('#main-menu').append('
  • '); - } - var $mainMenuState = $('#main-menu-state'); - var prevWidth = 0; - if ($mainMenuState.length) { - function initResizableIfExists() { - if (typeof initResizable==='function') initResizable(); - } - // animate mobile menu - $mainMenuState.change(function(e) { - var $menu = $('#main-menu'); - var options = { duration: 250, step: initResizableIfExists }; - if (this.checked) { - options['complete'] = function() { $menu.css('display', 'block') }; - $menu.hide().slideDown(options); - } else { - options['complete'] = function() { $menu.css('display', 'none') }; - $menu.show().slideUp(options); - } - }); - // set default menu visibility - function resetState() { - var $menu = $('#main-menu'); - var $mainMenuState = $('#main-menu-state'); - var newWidth = $(window).outerWidth(); - if (newWidth!=prevWidth) { - if ($(window).outerWidth()<768) { - $mainMenuState.prop('checked',false); $menu.hide(); - $('#searchBoxPos1').html(searchBoxHtml); - $('#searchBoxPos2').hide(); - } else { - $menu.show(); - $('#searchBoxPos1').empty(); - $('#searchBoxPos2').html(searchBoxHtml); - $('#searchBoxPos2').show(); - } - if (typeof searchBox!=='undefined') { - searchBox.CloseResultsWindow(); - } - prevWidth = newWidth; - } - } - $(window).ready(function() { resetState(); initResizableIfExists(); }); - $(window).resize(resetState); - } - $('#main-menu').smartmenus(); -} -/* @license-end */ diff --git a/documentation/html/menudata.js b/documentation/html/menudata.js deleted file mode 100644 index abafd6a..0000000 --- a/documentation/html/menudata.js +++ /dev/null @@ -1,104 +0,0 @@ -/* - @licstart The following is the entire license notice for the JavaScript code in this file. - - The MIT License (MIT) - - Copyright (C) 1997-2020 by Dimitri van Heesch - - Permission is hereby granted, free of charge, to any person obtaining a copy of this software - and associated documentation files (the "Software"), to deal in the Software without restriction, - including without limitation the rights to use, copy, modify, merge, publish, distribute, - sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is - furnished to do so, subject to the following conditions: - - The above copyright notice and this permission notice shall be included in all copies or - substantial portions of the Software. - - THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING - BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, - DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - - @licend The above is the entire license notice for the JavaScript code in this file -*/ -var menudata={children:[ -{text:"Main Page",url:"index.html"}, -{text:"Related Pages",url:"pages.html"}, -{text:"Classes",url:"annotated.html",children:[ -{text:"Class List",url:"annotated.html"}, -{text:"Class Index",url:"classes.html"}, -{text:"Class Hierarchy",url:"hierarchy.html"}, -{text:"Class Members",url:"functions.html",children:[ -{text:"All",url:"functions.html",children:[ -{text:"a",url:"functions.html#index_a"}, -{text:"b",url:"functions_b.html#index_b"}, -{text:"c",url:"functions_c.html#index_c"}, -{text:"d",url:"functions_d.html#index_d"}, -{text:"e",url:"functions_e.html#index_e"}, -{text:"f",url:"functions_f.html#index_f"}, -{text:"g",url:"functions_g.html#index_g"}, -{text:"h",url:"functions_h.html#index_h"}, -{text:"i",url:"functions_i.html#index_i"}, -{text:"k",url:"functions_k.html#index_k"}, -{text:"l",url:"functions_l.html#index_l"}, -{text:"m",url:"functions_m.html#index_m"}, -{text:"n",url:"functions_n.html#index_n"}, -{text:"o",url:"functions_o.html#index_o"}, -{text:"p",url:"functions_p.html#index_p"}, -{text:"r",url:"functions_r.html#index_r"}, -{text:"s",url:"functions_s.html#index_s"}, -{text:"t",url:"functions_t.html#index_t"}, -{text:"u",url:"functions_u.html#index_u"}, -{text:"v",url:"functions_v.html#index_v"}, -{text:"w",url:"functions_w.html#index_w"}, -{text:"x",url:"functions_x.html#index_x"}, -{text:"y",url:"functions_y.html#index_y"}, -{text:"z",url:"functions_z.html#index_z"}]}, -{text:"Functions",url:"functions_func.html",children:[ -{text:"a",url:"functions_func.html#index_a"}, -{text:"b",url:"functions_func.html#index_b"}, -{text:"c",url:"functions_func.html#index_c"}, -{text:"d",url:"functions_func.html#index_d"}, -{text:"e",url:"functions_func.html#index_e"}, -{text:"f",url:"functions_func.html#index_f"}, -{text:"g",url:"functions_func.html#index_g"}, -{text:"h",url:"functions_func.html#index_h"}, -{text:"i",url:"functions_func.html#index_i"}, -{text:"l",url:"functions_func.html#index_l"}, -{text:"m",url:"functions_func.html#index_m"}, -{text:"n",url:"functions_func.html#index_n"}, -{text:"o",url:"functions_func.html#index_o"}, -{text:"p",url:"functions_func.html#index_p"}, -{text:"r",url:"functions_func.html#index_r"}, -{text:"s",url:"functions_func.html#index_s"}, -{text:"t",url:"functions_func.html#index_t"}, -{text:"u",url:"functions_func.html#index_u"}, -{text:"v",url:"functions_func.html#index_v"}, -{text:"w",url:"functions_func.html#index_w"}]}, -{text:"Variables",url:"functions_vars.html",children:[ -{text:"a",url:"functions_vars.html#index_a"}, -{text:"b",url:"functions_vars.html#index_b"}, -{text:"c",url:"functions_vars.html#index_c"}, -{text:"d",url:"functions_vars.html#index_d"}, -{text:"e",url:"functions_vars.html#index_e"}, -{text:"f",url:"functions_vars.html#index_f"}, -{text:"h",url:"functions_vars.html#index_h"}, -{text:"i",url:"functions_vars.html#index_i"}, -{text:"k",url:"functions_vars.html#index_k"}, -{text:"l",url:"functions_vars.html#index_l"}, -{text:"m",url:"functions_vars.html#index_m"}, -{text:"n",url:"functions_vars.html#index_n"}, -{text:"o",url:"functions_vars.html#index_o"}, -{text:"p",url:"functions_vars.html#index_p"}, -{text:"r",url:"functions_vars.html#index_r"}, -{text:"s",url:"functions_vars.html#index_s"}, -{text:"t",url:"functions_vars.html#index_t"}, -{text:"v",url:"functions_vars.html#index_v"}, -{text:"w",url:"functions_vars.html#index_w"}, -{text:"x",url:"functions_vars.html#index_x"}, -{text:"y",url:"functions_vars.html#index_y"}, -{text:"z",url:"functions_vars.html#index_z"}]}, -{text:"Enumerations",url:"functions_enum.html"}]}]}, -{text:"Files",url:"files.html",children:[ -{text:"File List",url:"files.html"}]}]} diff --git a/documentation/html/motion__controller_8h_source.html b/documentation/html/motion__controller_8h_source.html deleted file mode 100644 index 0c0ee99..0000000 --- a/documentation/html/motion__controller_8h_source.html +++ /dev/null @@ -1,158 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/motion_controller.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    motion_controller.h
    -
    -
    -
    1#pragma once
    -
    2#include "../core/include/utils/pid.h"
    -
    3#include "../core/include/utils/feedforward.h"
    -
    4#include "../core/include/utils/trapezoid_profile.h"
    -
    5#include "../core/include/utils/feedback_base.h"
    -
    6#include "../core/include/subsystems/tank_drive.h"
    -
    7#include "vex.h"
    -
    8
    - -
    26{
    -
    27 public:
    -
    28
    -
    34 typedef struct
    -
    35 {
    -
    36 double max_v;
    -
    37 double accel;
    - - - -
    41
    - -
    52
    -
    57 void init(double start_pt, double end_pt) override;
    -
    58
    -
    65 double update(double sensor_val) override;
    -
    66
    -
    70 double get() override;
    -
    71
    -
    79 void set_limits(double lower, double upper) override;
    -
    80
    -
    85 bool is_on_target() override;
    -
    86
    - -
    91
    -
    110 static FeedForward::ff_config_t tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct=0.6, double duration=2);
    -
    111
    -
    112 private:
    -
    113
    -
    114 m_profile_cfg_t config;
    -
    115
    -
    116 PID pid;
    -
    117 FeedForward ff;
    -
    118 TrapezoidProfile profile;
    -
    119
    -
    120 double lower_limit = 0, upper_limit = 0;
    -
    121 double out = 0;
    -
    122 motion_t cur_motion;
    -
    123
    -
    124 vex::timer tmr;
    -
    125
    -
    126};
    -
    Definition: feedforward.h:30
    -
    Definition: feedback_base.h:11
    -
    Definition: motion_controller.h:26
    -
    static FeedForward::ff_config_t tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct=0.6, double duration=2)
    Definition: motion_controller.cpp:106
    -
    double get() override
    Definition: motion_controller.cpp:54
    -
    double update(double sensor_val) override
    Update the motion profile with a new sensor value.
    Definition: motion_controller.cpp:37
    -
    void set_limits(double lower, double upper) override
    Definition: motion_controller.cpp:65
    -
    bool is_on_target() override
    Definition: motion_controller.cpp:75
    -
    motion_t get_motion()
    Definition: motion_controller.cpp:83
    -
    void init(double start_pt, double end_pt) override
    Initialize the motion profile for a new movement This will also reset the PID and profile timers.
    Definition: motion_controller.cpp:24
    -
    Definition: odometry_tank.h:18
    -
    Definition: pid.h:24
    -
    Definition: tank_drive.h:23
    -
    Definition: trapezoid_profile.h:35
    -
    Definition: feedforward.h:42
    -
    Definition: motion_controller.h:35
    -
    PID::pid_config_t pid_cfg
    configuration parameters for the internal PID controller
    Definition: motion_controller.h:38
    -
    double max_v
    the maximum velocity the robot can drive
    Definition: motion_controller.h:36
    -
    double accel
    the most acceleration the robot can do
    Definition: motion_controller.h:37
    -
    FeedForward::ff_config_t ff_cfg
    configuration parameters for the internal
    Definition: motion_controller.h:39
    -
    Definition: pid.h:41
    -
    Definition: trapezoid_profile.h:7
    -
    - - - - diff --git a/documentation/html/moving__average_8h_source.html b/documentation/html/moving__average_8h_source.html deleted file mode 100644 index f820872..0000000 --- a/documentation/html/moving__average_8h_source.html +++ /dev/null @@ -1,129 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/moving_average.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    moving_average.h
    -
    -
    -
    1#include <vector>
    -
    2
    - -
    16 public:
    -
    17 /*
    -
    18 * Create a moving average calculator with 0 as the default value
    -
    19 *
    -
    20 * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading
    -
    21 */
    -
    22 MovingAverage(int buffer_size);
    -
    23 /*
    -
    24 * Create a moving average calculator with a specified default value
    -
    25 * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading
    -
    26 * @param starting_value The value that the average will be before any data is added
    -
    27 */
    -
    28 MovingAverage(int buffer_size, double starting_value);
    -
    29
    -
    30 /*
    -
    31 * Add a reading to the buffer
    -
    32 * Before:
    -
    33 * [ 1 1 2 2 3 3] => 2
    -
    34 * ^
    -
    35 * After:
    -
    36 * [ 2 1 2 2 3 3] => 2.16
    -
    37 * ^
    -
    38 * @param n the sample that will be added to the moving average.
    -
    39 */
    -
    40 void add_entry(double n);
    -
    41
    -
    46 double get_average();
    -
    47
    -
    52 int get_size();
    -
    53
    -
    54
    -
    55 private:
    -
    56 int buffer_index; //index of the next value to be overridden
    -
    57 std::vector<double> buffer; //all current data readings we've taken
    -
    58 double current_avg; //the current value of the data
    -
    59
    -
    60};
    -
    Definition: moving_average.h:15
    -
    void add_entry(double n)
    Definition: moving_average.cpp:50
    -
    double get_average()
    Definition: moving_average.cpp:63
    -
    int get_size()
    Definition: moving_average.cpp:68
    -
    - - - - diff --git a/documentation/html/nav_f.png b/documentation/html/nav_f.png deleted file mode 100644 index 72a58a529ed3a9ed6aa0c51a79cf207e026deee2..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 153 zcmeAS@N?(olHy`uVBq!ia0vp^j6iI`!2~2XGqLUlQVE_ejv*C{Z|{2ZH7M}7UYxc) zn!W8uqtnIQ>_z8U diff --git a/documentation/html/nav_fd.png b/documentation/html/nav_fd.png deleted file mode 100644 index 032fbdd4c54f54fa9a2e6423b94ef4b2ebdfaceb..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 169 zcmeAS@N?(olHy`uVBq!ia0vp^j6iI`!2~2XGqLUlQU#tajv*C{Z|C~*H7f|XvG1G8 zt7aS*L7xwMeS}!z6R#{C5tIw-s~AJ==F^i}x3XyJseHR@yF& zerFf(Zf;Dd{+(0lDIROL@Sj-Ju2JQ8&-n%4%q?>|^bShc&lR?}7HeMo@BDl5N(aHY Uj$gdr1MOz;boFyt=akR{0D!zeaR2}S diff --git a/documentation/html/nav_g.png b/documentation/html/nav_g.png deleted file mode 100644 index 2093a237a94f6c83e19ec6e5fd42f7ddabdafa81..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 95 zcmeAS@N?(olHy`uVBq!ia0vp^j6lrB!3HFm1ilyoDK$?Q$B+ufw|5PB85lU25BhtE tr?otc=hd~V+ws&_A@j8Fiv!KF$B+ufw|5=67#uj90@pIL wZ=Q8~_Ju`#59=RjDrmm`tMD@M=!-l18IR?&vFVdQ&MBb@0HFXL6W-eg#Jd_@e6*DPn)w;=|1H}Zvm9l6xXXB%>yL=NQU;mg M>FVdQ&MBb@0Bdt1Qvd(} diff --git a/documentation/html/odometry__3wheel_8h_source.html b/documentation/html/odometry__3wheel_8h_source.html deleted file mode 100644 index e45a6db..0000000 --- a/documentation/html/odometry__3wheel_8h_source.html +++ /dev/null @@ -1,127 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/subsystems/odometry/odometry_3wheel.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    odometry_3wheel.h
    -
    -
    -
    1#pragma once
    -
    2#include "../core/include/subsystems/odometry/odometry_base.h"
    -
    3#include "../core/include/subsystems/tank_drive.h"
    -
    4#include "../core/include/subsystems/custom_encoder.h"
    -
    5
    - -
    33{
    -
    34 public:
    -
    35
    -
    40 typedef struct
    -
    41 {
    - - -
    44 double wheel_diam;
    - -
    47
    -
    57 Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, odometry3wheel_cfg_t &cfg, bool is_async=true);
    -
    58
    -
    65 position_t update() override;
    -
    66
    -
    75 void tune(vex::controller &con, TankDrive &drive);
    -
    76
    -
    77 private:
    -
    78
    -
    91 static position_t calculate_new_pos(double lside_delta_deg, double rside_delta_deg, double offax_delta_deg, position_t old_pos, odometry3wheel_cfg_t cfg);
    -
    92
    -
    93 CustomEncoder &lside_fwd, &rside_fwd, &off_axis;
    - -
    95
    -
    96
    -
    97};
    -
    Definition: custom_encoder.h:9
    -
    Definition: odometry_3wheel.h:33
    -
    position_t update() override
    Definition: odometry_3wheel.cpp:15
    -
    void tune(vex::controller &con, TankDrive &drive)
    Definition: odometry_3wheel.cpp:135
    -
    Definition: odometry_base.h:33
    -
    Definition: tank_drive.h:23
    -
    Definition: odometry_3wheel.h:41
    -
    double wheel_diam
    Definition: odometry_3wheel.h:44
    -
    double wheelbase_dist
    Definition: odometry_3wheel.h:42
    -
    double off_axis_center_dist
    Definition: odometry_3wheel.h:43
    -
    Definition: odometry_base.h:14
    -
    - - - - diff --git a/documentation/html/odometry__base_8h_source.html b/documentation/html/odometry__base_8h_source.html deleted file mode 100644 index 0d6f32c..0000000 --- a/documentation/html/odometry__base_8h_source.html +++ /dev/null @@ -1,173 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/subsystems/odometry/odometry_base.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    odometry_base.h
    -
    -
    -
    1#pragma once
    -
    2
    -
    3#include "vex.h"
    -
    4#include "../core/include/robot_specs.h"
    -
    5
    -
    6#ifndef PI
    -
    7#define PI 3.141592654
    -
    8#endif
    -
    9
    -
    13typedef struct
    -
    14{
    -
    15 double x;
    -
    16 double y;
    -
    17 double rot;
    - -
    19
    - -
    33{
    -
    34public:
    -
    35
    -
    41 OdometryBase(bool is_async);
    -
    42
    - -
    48
    -
    53 virtual void set_position(const position_t& newpos=zero_pos);
    -
    54
    -
    59 virtual position_t update() = 0;
    -
    60
    -
    68 static int background_task(void* ptr);
    -
    69
    -
    75 void end_async();
    -
    76
    -
    83 static double pos_diff(position_t start_pos, position_t end_pos);
    -
    84
    -
    91 static double rot_diff(position_t pos1, position_t pos2);
    -
    92
    -
    101 static double smallest_angle(double start_deg, double end_deg);
    -
    102
    -
    104 bool end_task = false;
    -
    105
    -
    110 double get_speed();
    -
    111
    -
    116 double get_accel();
    -
    117
    -
    122 double get_angular_speed_deg();
    -
    123
    -
    128 double get_angular_accel_deg();
    -
    129
    -
    133 inline static constexpr position_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L};
    -
    134
    -
    135protected:
    -
    139 vex::task *handle;
    -
    140
    -
    144 vex::mutex mut;
    -
    145
    - -
    150
    -
    151 double speed;
    -
    152 double accel;
    - - -
    155};
    -
    Definition: odometry_base.h:33
    -
    double ang_accel_deg
    Definition: odometry_base.h:154
    -
    static int background_task(void *ptr)
    Definition: odometry_base.cpp:22
    -
    double ang_speed_deg
    Definition: odometry_base.h:153
    -
    double get_accel()
    Definition: odometry_base.cpp:123
    -
    virtual void set_position(const position_t &newpos=zero_pos)
    Definition: odometry_base.cpp:63
    -
    position_t get_position(void)
    Definition: odometry_base.cpp:48
    -
    double get_angular_accel_deg()
    Definition: odometry_base.cpp:141
    -
    virtual position_t update()=0
    -
    double speed
    Definition: odometry_base.h:151
    -
    position_t current_pos
    Definition: odometry_base.h:149
    -
    static double smallest_angle(double start_deg, double end_deg)
    Definition: odometry_base.cpp:99
    -
    static constexpr position_t zero_pos
    Definition: odometry_base.h:133
    -
    vex::mutex mut
    Definition: odometry_base.h:144
    -
    static double pos_diff(position_t start_pos, position_t end_pos)
    Definition: odometry_base.cpp:78
    -
    double accel
    Definition: odometry_base.h:152
    -
    double get_speed()
    Definition: odometry_base.cpp:114
    -
    static double rot_diff(position_t pos1, position_t pos2)
    Definition: odometry_base.cpp:89
    -
    void end_async()
    Definition: odometry_base.cpp:40
    -
    vex::task * handle
    Definition: odometry_base.h:139
    -
    bool end_task
    end_task is true if we instruct the odometry thread to shut down
    Definition: odometry_base.h:104
    -
    double get_angular_speed_deg()
    Definition: odometry_base.cpp:132
    -
    Definition: odometry_base.h:14
    -
    double rot
    rotation in the world
    Definition: odometry_base.h:17
    -
    double x
    x position in the world
    Definition: odometry_base.h:15
    -
    double y
    y position in the world
    Definition: odometry_base.h:16
    -
    - - - - diff --git a/documentation/html/odometry__tank_8h_source.html b/documentation/html/odometry__tank_8h_source.html deleted file mode 100644 index 6c0ef8b..0000000 --- a/documentation/html/odometry__tank_8h_source.html +++ /dev/null @@ -1,127 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/subsystems/odometry/odometry_tank.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    odometry_tank.h
    -
    -
    -
    1#pragma once
    -
    2
    -
    3#include "../core/include/subsystems/odometry/odometry_base.h"
    -
    4#include "../core/include/subsystems/custom_encoder.h"
    -
    5#include "../core/include/utils/vector2d.h"
    -
    6#include "../core/include/robot_specs.h"
    -
    7
    -
    8static int background_task(void* odom_obj);
    -
    9
    -
    10
    - -
    18{
    -
    19public:
    -
    28 OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true);
    -
    29
    -
    39 OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true);
    -
    40
    -
    45 position_t update() override;
    -
    46
    -
    51 void set_position(const position_t &newpos=zero_pos) override;
    -
    52
    -
    53
    -
    54
    -
    55private:
    -
    59 static position_t calculate_new_pos(robot_specs_t &config, position_t &stored_info, double lside_diff, double rside_diff, double angle_deg);
    -
    60
    -
    61 vex::motor_group *left_side, *right_side;
    -
    62 CustomEncoder *left_enc, *right_enc;
    -
    63 vex::inertial *imu;
    -
    64 robot_specs_t &config;
    -
    65
    -
    66 double rotation_offset = 0;
    -
    67
    -
    68};
    -
    Definition: custom_encoder.h:9
    -
    Definition: odometry_base.h:33
    -
    static constexpr position_t zero_pos
    Definition: odometry_base.h:133
    -
    Definition: odometry_tank.h:18
    -
    position_t update() override
    Definition: odometry_tank.cpp:46
    -
    void set_position(const position_t &newpos=zero_pos) override
    Definition: odometry_tank.cpp:33
    -
    Definition: odometry_base.h:14
    -
    Definition: robot_specs.h:12
    -
    - - - - diff --git a/documentation/html/open.png b/documentation/html/open.png deleted file mode 100644 index 30f75c7efe2dd0c9e956e35b69777a02751f048b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 123 zcmeAS@N?(olHy`uVBq!ia0vp^oFL4>1|%O$WD@{VPM$7~Ar*{o?;hlAFyLXmaDC0y znK1_#cQqJWPES%4Uujug^TE?jMft$}Eq^WaR~)%f)vSNs&gek&x%A9X9sM - - - - - - -RIT VEXU Core API: Related Pages - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Related Pages
    -
    -
    -
    Here is a list of all related documentation pages:
    - - -
     Core
    -
    -
    - - - - diff --git a/documentation/html/pid_8h_source.html b/documentation/html/pid_8h_source.html deleted file mode 100644 index 62a0607..0000000 --- a/documentation/html/pid_8h_source.html +++ /dev/null @@ -1,177 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/pid.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    pid.h
    -
    -
    -
    1#pragma once
    -
    2
    -
    3#include <cmath>
    -
    4#include "vex.h"
    -
    5#include "../core/include/utils/feedback_base.h"
    -
    6
    -
    7using namespace vex;
    -
    8
    -
    23class PID : public Feedback
    -
    24{
    -
    25public:
    - -
    30 LINEAR,
    -
    31 ANGULAR // assumes degrees
    -
    32 };
    - -
    41 {
    -
    42 double p;
    -
    43 double i;
    -
    44 double d;
    -
    45 double deadband;
    - - -
    48 };
    -
    49
    -
    50
    -
    51
    - -
    57
    -
    58
    -
    67 void init(double start_pt, double set_pt) override;
    -
    68
    -
    75 double update(double sensor_val) override;
    -
    76
    -
    81 double get() override;
    -
    82
    -
    89 void set_limits(double lower, double upper) override;
    -
    90
    -
    95 bool is_on_target() override;
    -
    96
    -
    100 void reset();
    -
    101
    -
    106 double get_error();
    -
    107
    -
    112 double get_target();
    -
    113
    -
    118 void set_target(double target);
    -
    119
    -
    120 Feedback::FeedbackType get_type() override;
    -
    121
    - -
    123
    -
    124private:
    -
    125
    -
    126
    -
    127 double last_error = 0;
    -
    128 double accum_error = 0;
    -
    129
    -
    130 double last_time = 0;
    -
    131 double on_target_last_time = 0;
    -
    132
    -
    133 double lower_limit = 0;
    -
    134 double upper_limit = 0;
    -
    135
    -
    136 double target = 0;
    -
    137 double sensor_val = 0;
    -
    138 double out = 0;
    -
    139
    -
    140 bool is_checking_on_target = false;
    -
    141
    -
    142 timer pid_timer;
    -
    143};
    -
    Definition: feedback_base.h:11
    -
    Definition: pid.h:24
    -
    double get_target()
    Definition: pid.cpp:97
    -
    ERROR_TYPE
    Definition: pid.h:29
    -
    void set_target(double target)
    Definition: pid.cpp:105
    -
    double update(double sensor_val) override
    Definition: pid.cpp:25
    -
    pid_config_t & config
    configuration struct for this controller. see pid_config_t for information about what this contains
    Definition: pid.h:122
    -
    double get() override
    Definition: pid.cpp:81
    -
    void set_limits(double lower, double upper) override
    Definition: pid.cpp:114
    -
    bool is_on_target() override
    Definition: pid.cpp:124
    -
    void init(double start_pt, double set_pt) override
    Definition: pid.cpp:13
    -
    double get_error()
    Definition: pid.cpp:89
    -
    void reset()
    Definition: pid.cpp:66
    -
    Definition: pid.h:41
    -
    double on_target_time
    the time in seconds that we have to be on target for to say we are officially at the target
    Definition: pid.h:46
    -
    double d
    derivitave coeffecient d * derivative(error)
    Definition: pid.h:44
    -
    double p
    proportional coeffecient p * error()
    Definition: pid.h:42
    -
    double i
    integral coeffecient i * integral(error)
    Definition: pid.h:43
    -
    double deadband
    at what threshold are we close enough to be finished
    Definition: pid.h:45
    -
    ERROR_TYPE error_method
    Linear or angular. wheter to do error as a simple subtraction or to wrap.
    Definition: pid.h:47
    -
    - - - - diff --git a/documentation/html/pidff_8h_source.html b/documentation/html/pidff_8h_source.html deleted file mode 100644 index 8f2d7c0..0000000 --- a/documentation/html/pidff_8h_source.html +++ /dev/null @@ -1,135 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/pidff.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    pidff.h
    -
    -
    -
    1#pragma once
    -
    2#include "../core/include/utils/feedback_base.h"
    -
    3#include "../core/include/utils/pid.h"
    -
    4#include "../core/include/utils/feedforward.h"
    -
    5
    -
    6class PIDFF : public Feedback
    -
    7{
    -
    8 public:
    -
    9
    - -
    11
    -
    18 void init(double start_pt, double set_pt) override;
    -
    19
    -
    24 void set_target(double set_pt);
    -
    25
    -
    33 double update(double val) override;
    -
    34
    -
    43 double update(double val, double vel_setpt, double a_setpt=0);
    -
    44
    -
    48 double get() override;
    -
    49
    -
    56 void set_limits(double lower, double upper) override;
    -
    57
    -
    61 bool is_on_target() override;
    -
    62
    -
    63 PID pid;
    -
    64
    -
    65
    -
    66 private:
    -
    67
    - -
    69
    -
    70 FeedForward ff;
    -
    71
    -
    72 double out;
    -
    73 double lower_lim, upper_lim;
    -
    74
    -
    75};
    -
    Definition: feedforward.h:30
    -
    Definition: feedback_base.h:11
    -
    Definition: pidff.h:7
    -
    bool is_on_target() override
    Definition: pidff.cpp:84
    -
    void init(double start_pt, double set_pt) override
    Definition: pidff.cpp:17
    -
    void set_target(double set_pt)
    Definition: pidff.cpp:22
    -
    double get() override
    Definition: pidff.cpp:64
    -
    double update(double val) override
    Definition: pidff.cpp:34
    -
    void set_limits(double lower, double upper) override
    Definition: pidff.cpp:75
    -
    Definition: pid.h:24
    -
    Definition: feedforward.h:42
    -
    Definition: pid.h:41
    -
    - - - - diff --git a/documentation/html/pure__pursuit_8h_source.html b/documentation/html/pure__pursuit_8h_source.html deleted file mode 100644 index 495dfec..0000000 --- a/documentation/html/pure__pursuit_8h_source.html +++ /dev/null @@ -1,133 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/pure_pursuit.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    pure_pursuit.h
    -
    -
    -
    1#pragma once
    -
    2
    -
    3#include <vector>
    -
    4#include "../core/include/utils/vector2d.h"
    -
    5#include "vex.h"
    -
    6
    -
    7using namespace vex;
    -
    8
    -
    9namespace PurePursuit {
    -
    14 struct spline
    -
    15 {
    -
    16 double a, b, c, d, x_start, x_end;
    -
    17
    -
    18 double getY(double x) {
    -
    19 return a * pow((x - x_start), 3) + b * pow((x - x_start), 2) + c * (x - x_start) + d;
    -
    20 }
    -
    21 };
    - -
    27 {
    -
    28 double x;
    -
    29 double y;
    -
    30 double dir;
    -
    31 double mag;
    -
    32
    -
    33 Vector2D::point_t getPoint() {
    -
    34 return {x, y};
    -
    35 }
    -
    36
    -
    37 Vector2D getTangent() {
    -
    38 return Vector2D(dir, mag);
    -
    39 }
    -
    40 };
    -
    41
    -
    46 static std::vector<Vector2D::point_t> line_circle_intersections(Vector2D::point_t center, double r, Vector2D::point_t point1, Vector2D::point_t point2);
    -
    50 static Vector2D::point_t get_lookahead(std::vector<Vector2D::point_t> path, Vector2D::point_t robot_loc, double radius);
    -
    51
    -
    55 static std::vector<Vector2D::point_t> inject_path(std::vector<Vector2D::point_t> path, double spacing);
    -
    56
    -
    68 static std::vector<Vector2D::point_t> smooth_path(std::vector<Vector2D::point_t> path, double weight_data, double weight_smooth, double tolerance);
    -
    69
    -
    70 static std::vector<Vector2D::point_t> smooth_path_cubic(std::vector<Vector2D::point_t> path, double res);
    -
    71
    -
    80 static std::vector<Vector2D::point_t> smooth_path_hermite(std::vector<hermite_point> path, double step);
    -
    81}
    -
    Definition: vector2d.h:14
    -
    Definition: pure_pursuit.h:27
    -
    Definition: pure_pursuit.h:15
    -
    Definition: vector2d.h:21
    -
    - - - - diff --git a/documentation/html/robot__specs_8h_source.html b/documentation/html/robot__specs_8h_source.html deleted file mode 100644 index 323aa96..0000000 --- a/documentation/html/robot__specs_8h_source.html +++ /dev/null @@ -1,115 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/robot_specs.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    robot_specs.h
    -
    -
    -
    1#pragma once
    -
    2#include "../core/include/utils/pid.h"
    -
    3#include "../core/include/utils/feedback_base.h"
    -
    4
    -
    11typedef struct
    -
    12{
    -
    13 double robot_radius;
    -
    14
    - - - -
    18
    - -
    20
    - - - -
    24
    - -
    Definition: feedback_base.h:11
    -
    Definition: pid.h:41
    -
    Definition: robot_specs.h:12
    -
    PID::pid_config_t correction_pid
    the pid controller to keep the robot driving in as straight a line as possible
    Definition: robot_specs.h:23
    -
    double robot_radius
    if you were to draw a circle with this radius, the robot would be entirely contained within it
    Definition: robot_specs.h:13
    -
    Feedback * drive_feedback
    the default feedback for autonomous driving
    Definition: robot_specs.h:21
    -
    double odom_gear_ratio
    the ratio of the odometry wheel to the encoder reading odometry data
    Definition: robot_specs.h:16
    -
    double drive_correction_cutoff
    the distance at which to stop trying to turn towards the target. If we are less than this value,...
    Definition: robot_specs.h:19
    -
    double odom_wheel_diam
    the diameter of the wheels used for
    Definition: robot_specs.h:15
    -
    Feedback * turn_feedback
    the defualt feedback for autonomous turning
    Definition: robot_specs.h:22
    -
    double dist_between_wheels
    the distance between centers of the central drive wheels
    Definition: robot_specs.h:17
    -
    - - - - diff --git a/documentation/html/screen_8h_source.html b/documentation/html/screen_8h_source.html deleted file mode 100644 index d5f8e13..0000000 --- a/documentation/html/screen_8h_source.html +++ /dev/null @@ -1,103 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/subsystems/screen.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    screen.h
    -
    -
    -
    1#pragma once
    -
    2#include "vex.h"
    -
    3#include <vector>
    -
    4
    -
    9
    -
    10typedef void (*screenFunc)(vex::brain::lcd &screen, int x, int y, int width, int height, bool first_run);
    -
    11
    -
    12void draw_mot_header(vex::brain::lcd &screen, int x, int y, int width);
    -
    13// name should be no longer than 15 characters
    -
    14void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char *name, vex::motor &motor);
    -
    15void draw_battery_stats(vex::brain::lcd &screen, int x, int y, double voltage, double percentage);
    -
    16
    -
    17
    -
    18
    -
    19void draw_lr_arrows(vex::brain::lcd &screen, int bar_width, int width, int height);
    -
    20
    -
    21int handle_screen_thread(vex::brain::lcd &screen, std::vector<screenFunc> pages, int first_page);
    -
    22void StartScreen(vex::brain::lcd &screen, std::vector<screenFunc> pages, int first_page = 0);
    -
    - - - - diff --git a/documentation/html/search/all_0.js b/documentation/html/search/all_0.js deleted file mode 100644 index b83f3ce..0000000 --- a/documentation/html/search/all_0.js +++ /dev/null @@ -1,15 +0,0 @@ -var searchData= -[ - ['accel_0',['accel',['../classOdometryBase.html#a94c814dfb542dd891d84db7e74537249',1,'OdometryBase::accel()'],['../structMotionController_1_1m__profile__cfg__t.html#ac4f07f3ac52d12fd820ee4d8ce847f66',1,'MotionController::m_profile_cfg_t::accel()'],['../structmotion__t.html#a0bfa8ec05af92df3b8c0e7d0945824f2',1,'motion_t::accel()']]], - ['add_1',['add',['../classAutoChooser.html#a67b80bf6b62cfced155519f5b608e08c',1,'AutoChooser::add()'],['../classCommandController.html#a4cb2c06abd92fb99578f0da75c1411e5',1,'CommandController::add(AutoCommand *cmd, double timeout_seconds=10.0)'],['../classCommandController.html#a03fc0dd37c12ae7f43200d5588c768b8',1,'CommandController::add(std::vector< AutoCommand * > cmds)'],['../classGenericAuto.html#af48629556173af1f5106f7405a196f47',1,'GenericAuto::add(state_ptr new_state)']]], - ['add_5fasync_2',['add_async',['../classGenericAuto.html#a938fb69c14735d4cf88ebc7589dcad1c',1,'GenericAuto']]], - ['add_5fdelay_3',['add_delay',['../classCommandController.html#ae06b054f4aeea86e8c6bee56458dc6d1',1,'CommandController::add_delay()'],['../classGenericAuto.html#aaadc99efe49a375f0dc80db7e886d96c',1,'GenericAuto::add_delay()']]], - ['add_5fentry_4',['add_entry',['../classMovingAverage.html#a6c85ea575428ef7faf1f1f111a985db8',1,'MovingAverage']]], - ['add_5fsample_5',['add_sample',['../classGraphDrawer.html#a41cadd5ade1ae9de1a82cc97ee15557c',1,'GraphDrawer']]], - ['ang_5faccel_5fdeg_6',['ang_accel_deg',['../classOdometryBase.html#a01f14bfcecbcde7a74b9b98376deb19f',1,'OdometryBase']]], - ['ang_5fspeed_5fdeg_7',['ang_speed_deg',['../classOdometryBase.html#a250ceb6ed296ea579e37851e4a0048fb',1,'OdometryBase']]], - ['auto_5fdrive_8',['auto_drive',['../classMecanumDrive.html#aa0cfb8683fee99e0a534c3a725d338fd',1,'MecanumDrive']]], - ['auto_5fturn_9',['auto_turn',['../classMecanumDrive.html#ac8813aafec14f2d25c3abafefdb81498',1,'MecanumDrive']]], - ['autochooser_10',['AutoChooser',['../classAutoChooser.html',1,'AutoChooser'],['../classAutoChooser.html#a6e4f8f87e9cf0d0df2e36cda803f2c51',1,'AutoChooser::AutoChooser()']]], - ['autocommand_11',['AutoCommand',['../classAutoCommand.html',1,'']]] -]; diff --git a/documentation/html/search/all_1.js b/documentation/html/search/all_1.js deleted file mode 100644 index b37ac8b..0000000 --- a/documentation/html/search/all_1.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['background_5ftask_0',['background_task',['../classOdometryBase.html#a17a014f79b282ddfb715835214f3e2fb',1,'OdometryBase']]], - ['brain_1',['brain',['../classAutoChooser.html#a9889be17b1b6243563f975dd421802b4',1,'AutoChooser']]] -]; diff --git a/documentation/html/search/all_10.js b/documentation/html/search/all_10.js deleted file mode 100644 index 20a4baa..0000000 --- a/documentation/html/search/all_10.js +++ /dev/null @@ -1,26 +0,0 @@ -var searchData= -[ - ['set_5faccel_0',['set_accel',['../classTrapezoidProfile.html#a1dcdfa1c290347cf0af48aca5afd167c',1,'TrapezoidProfile']]], - ['set_5fasync_1',['set_async',['../classLift.html#a7f37703180518390ec38cba9a780282b',1,'Lift']]], - ['set_5fendpts_2',['set_endpts',['../classTrapezoidProfile.html#a1d28f3fa6bf1dfa7f5c1a34d0d3b17b5',1,'TrapezoidProfile']]], - ['set_5flimits_3',['set_limits',['../classFeedback.html#a533a10b65cfc998898bf054f8b141de2',1,'Feedback::set_limits()'],['../classMotionController.html#a944c245002a1eb124dd8df40de4fcc57',1,'MotionController::set_limits()'],['../classPID.html#a8411ac48e8868d89e97afcf8990cca2c',1,'PID::set_limits()'],['../classPIDFF.html#ae0dccb27a91ec687f90c930441f246bb',1,'PIDFF::set_limits()']]], - ['set_5fmax_5fv_4',['set_max_v',['../classTrapezoidProfile.html#a6c08d08d8eadaa719f4dc9e607f9fe97',1,'TrapezoidProfile']]], - ['set_5fposition_5',['set_position',['../classLift.html#ab3cb7bc86faa079ec1249b5026ea6a85',1,'Lift::set_position()'],['../classOdometryBase.html#a34e4bd8567933d1b6bd6e41327a36549',1,'OdometryBase::set_position()'],['../classOdometryTank.html#ad3b4bcf351767992e2383ab000645335',1,'OdometryTank::set_position()']]], - ['set_5fsensor_5ffunction_6',['set_sensor_function',['../classLift.html#a08b7cdcfc9390f4945dd3737ac0e5ddc',1,'Lift']]], - ['set_5fsensor_5freset_7',['set_sensor_reset',['../classLift.html#a70b8e7cff5cd3b5827d8da07a02d92e6',1,'Lift']]], - ['set_5fsetpoint_8',['set_setpoint',['../classLift.html#a662bdc055d706699ef5cf308cd8872f8',1,'Lift']]], - ['set_5ftarget_9',['set_target',['../classPID.html#a2e301ab123c9e18e677b4873b03550dd',1,'PID::set_target()'],['../classPIDFF.html#a5b5584e4ca036b0e51c693a24a23b50b',1,'PIDFF::set_target()']]], - ['setpidtarget_10',['setPIDTarget',['../classFlywheel.html#a5eeb847c6ef4736b1917bf32843c69aa',1,'Flywheel']]], - ['setposition_11',['setPosition',['../classCustomEncoder.html#a0edd50e16020ccad5eafa55e0f80288d',1,'CustomEncoder']]], - ['setrotation_12',['setRotation',['../classCustomEncoder.html#abcb003c4627f59faa25c748c597da7fd',1,'CustomEncoder']]], - ['smallest_5fangle_13',['smallest_angle',['../classOdometryBase.html#a70ec71e9fb2e14f0a191a6bac927d36b',1,'OdometryBase']]], - ['speed_14',['speed',['../classOdometryBase.html#a6119ab3ce0b685e67a8b57871e0a2c26',1,'OdometryBase']]], - ['spin_5fmanual_15',['spin_manual',['../classFlywheel.html#a291e067bcc495a9d3da16a5832d78484',1,'Flywheel']]], - ['spin_5fraw_16',['spin_raw',['../classFlywheel.html#a5f4afa2ab8976acbf9fd47776a884dd3',1,'Flywheel']]], - ['spinrpm_17',['spinRPM',['../classFlywheel.html#aa72700130c0c8a08517ec1396fe9cc2b',1,'Flywheel']]], - ['spinrpmcommand_18',['SpinRPMCommand',['../classSpinRPMCommand.html#a9bfcf882448d6d4e0860c1a7de90f9ea',1,'SpinRPMCommand::SpinRPMCommand()'],['../classSpinRPMCommand.html',1,'SpinRPMCommand']]], - ['spline_19',['spline',['../structPurePursuit_1_1spline.html',1,'PurePursuit']]], - ['stop_20',['stop',['../classFlywheel.html#a6634f5126f0404e0edeeff1e0e14d05e',1,'Flywheel::stop()'],['../classTankDrive.html#af10e648e4de35fa72859fb96a9a80485',1,'TankDrive::stop()']]], - ['stopmotors_21',['stopMotors',['../classFlywheel.html#a78eaa40c9c069b8b4146c3ae34a21d4e',1,'Flywheel']]], - ['stopnontasks_22',['stopNonTasks',['../classFlywheel.html#a63c9c4d3646e4ed14f3b98ce3ab28684',1,'Flywheel']]] -]; diff --git a/documentation/html/search/all_11.js b/documentation/html/search/all_11.js deleted file mode 100644 index 0681ca8..0000000 --- a/documentation/html/search/all_11.js +++ /dev/null @@ -1,13 +0,0 @@ -var searchData= -[ - ['tankdrive_0',['TankDrive',['../classTankDrive.html',1,'TankDrive'],['../classTankDrive.html#a34f305bb1c996e3748c925af259aeeb4',1,'TankDrive::TankDrive()']]], - ['timeout_5fseconds_1',['timeout_seconds',['../classAutoCommand.html#ac3be7be26e49981ad1978491fd313472',1,'AutoCommand']]], - ['trapezoidprofile_2',['TrapezoidProfile',['../classTrapezoidProfile.html',1,'TrapezoidProfile'],['../classTrapezoidProfile.html#af693ca740c0112cfbf4a9ee13bbb6c5d',1,'TrapezoidProfile::TrapezoidProfile()']]], - ['tune_3',['tune',['../classOdometry3Wheel.html#acb23dbf715d342566fc7e44f58ebf654',1,'Odometry3Wheel']]], - ['tune_5ffeedforward_4',['tune_feedforward',['../classMotionController.html#a20749b6a4bd3cf509a3acf682831eb00',1,'MotionController']]], - ['turn_5fdegrees_5',['turn_degrees',['../classTankDrive.html#ac1ce9895b82b7298465d8e59fae95763',1,'TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_speed=1)'],['../classTankDrive.html#a26d51cc12145f2520ea0c4355716184d',1,'TankDrive::turn_degrees(double degrees, double max_speed=1)']]], - ['turn_5ffeedback_6',['turn_feedback',['../structrobot__specs__t.html#af8c8492ba755766847bb21b960b91bfe',1,'robot_specs_t']]], - ['turn_5fto_5fheading_7',['turn_to_heading',['../classTankDrive.html#a25030a7b5e9404a911f7b776a7df7f05',1,'TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double max_speed=1)'],['../classTankDrive.html#ab003af6cf2de93e649cce5245b092a36',1,'TankDrive::turn_to_heading(double heading_deg, double max_speed=1)']]], - ['turndegreescommand_8',['TurnDegreesCommand',['../classTurnDegreesCommand.html',1,'TurnDegreesCommand'],['../classTurnDegreesCommand.html#a70a7e4688c10f1b351e6d79a3a7862ee',1,'TurnDegreesCommand::TurnDegreesCommand()']]], - ['turntoheadingcommand_9',['TurnToHeadingCommand',['../classTurnToHeadingCommand.html',1,'TurnToHeadingCommand'],['../classTurnToHeadingCommand.html#a9a958d75babe94709827c827807d423d',1,'TurnToHeadingCommand::TurnToHeadingCommand()']]] -]; diff --git a/documentation/html/search/all_12.js b/documentation/html/search/all_12.js deleted file mode 100644 index 5fb0714..0000000 --- a/documentation/html/search/all_12.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['update_0',['update',['../classOdometry3Wheel.html#a85c5661989dae181a4db7d91bd0526f7',1,'Odometry3Wheel::update()'],['../classOdometryBase.html#a5d55b7987d97a9af721838596a520dec',1,'OdometryBase::update()'],['../classOdometryTank.html#a02508433d771c661c89d14f204a61d13',1,'OdometryTank::update()'],['../classFeedback.html#adda5fc7642539996be00632954dfc41f',1,'Feedback::update()'],['../classMotionController.html#a86ef0ef19858b5b407f7406bb5da30af',1,'MotionController::update()'],['../classPID.html#a53b5c34ba5e81fb79ed4258a143015b9',1,'PID::update()'],['../classPIDFF.html#a9a9b05ec43e4430019652b62799e761c',1,'PIDFF::update(double val) override'],['../classPIDFF.html#a015bebe6d1028451e612f103ee2c1c2c',1,'PIDFF::update(double val, double vel_setpt, double a_setpt=0)']]], - ['updatepid_1',['updatePID',['../classFlywheel.html#aa9df5ad636fb49d76ba922ecd1115aef',1,'Flywheel']]] -]; diff --git a/documentation/html/search/all_13.js b/documentation/html/search/all_13.js deleted file mode 100644 index fbb1ddd..0000000 --- a/documentation/html/search/all_13.js +++ /dev/null @@ -1,6 +0,0 @@ -var searchData= -[ - ['vector2d_0',['Vector2D',['../classVector2D.html',1,'Vector2D'],['../classVector2D.html#af3084a6d83b0c8220c548fbf74df2744',1,'Vector2D::Vector2D(double dir, double mag)'],['../classVector2D.html#ae6429e185a05c8174d97beeec27432b5',1,'Vector2D::Vector2D(point_t p)']]], - ['vel_1',['vel',['../structmotion__t.html#a038b39985525b904bb8257ea86adbcee',1,'motion_t']]], - ['velocity_2',['velocity',['../classCustomEncoder.html#a92fe3a3227b4c4bc1ad1389b7b758455',1,'CustomEncoder']]] -]; diff --git a/documentation/html/search/all_14.js b/documentation/html/search/all_14.js deleted file mode 100644 index b70319e..0000000 --- a/documentation/html/search/all_14.js +++ /dev/null @@ -1,7 +0,0 @@ -var searchData= -[ - ['waituntiluptospeedcommand_0',['WaitUntilUpToSpeedCommand',['../classWaitUntilUpToSpeedCommand.html',1,'WaitUntilUpToSpeedCommand'],['../classWaitUntilUpToSpeedCommand.html#afd000a8f148291a9d2310b76b9354fea',1,'WaitUntilUpToSpeedCommand::WaitUntilUpToSpeedCommand()']]], - ['wheel_5fdiam_1',['wheel_diam',['../structOdometry3Wheel_1_1odometry3wheel__cfg__t.html#a283cd9db8de27d9b3967d0c3203f1f7f',1,'Odometry3Wheel::odometry3wheel_cfg_t']]], - ['wheelbase_5fdist_2',['wheelbase_dist',['../structOdometry3Wheel_1_1odometry3wheel__cfg__t.html#a4de8559ac486dcfbf5baff9d9d6cb5b1',1,'Odometry3Wheel::odometry3wheel_cfg_t']]], - ['width_3',['width',['../structAutoChooser_1_1entry__t.html#a2459ffe56c165e35f3a63bec99990367',1,'AutoChooser::entry_t']]] -]; diff --git a/documentation/html/search/all_15.js b/documentation/html/search/all_15.js deleted file mode 100644 index a7cd057..0000000 --- a/documentation/html/search/all_15.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['x_0',['x',['../structposition__t.html#aa554831febb89209dc5a2434e08265a8',1,'position_t::x()'],['../structAutoChooser_1_1entry__t.html#a7aa2aaaccd195c358c88afa6e24b5f73',1,'AutoChooser::entry_t::x()'],['../structVector2D_1_1point__t.html#ad139f137dd3554335c4ed9b51c8e3bd9',1,'Vector2D::point_t::x()']]] -]; diff --git a/documentation/html/search/all_16.js b/documentation/html/search/all_16.js deleted file mode 100644 index 579b23b..0000000 --- a/documentation/html/search/all_16.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['y_0',['y',['../structposition__t.html#af5fb9bd02cb51336477d5290fe32cec6',1,'position_t::y()'],['../structAutoChooser_1_1entry__t.html#a2e303a71790d85a67819830302c4dcee',1,'AutoChooser::entry_t::y()'],['../structVector2D_1_1point__t.html#a8290e79feb502e69cd95a7580cf6f1fe',1,'Vector2D::point_t::y()']]] -]; diff --git a/documentation/html/search/all_17.js b/documentation/html/search/all_17.js deleted file mode 100644 index 490ff49..0000000 --- a/documentation/html/search/all_17.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['zero_5fpos_0',['zero_pos',['../classOdometryBase.html#a7bd3fd09b3a6fa78af3a5ed5e25b8d74',1,'OdometryBase']]] -]; diff --git a/documentation/html/search/all_2.js b/documentation/html/search/all_2.js deleted file mode 100644 index 159d974..0000000 --- a/documentation/html/search/all_2.js +++ /dev/null @@ -1,14 +0,0 @@ -var searchData= -[ - ['calculate_0',['calculate',['../classFeedForward.html#a2e2f7c12076225fa1dfd5f18aa210290',1,'FeedForward::calculate()'],['../classTrapezoidProfile.html#a0b65a924664e6e052a16db19f73af17c',1,'TrapezoidProfile::calculate()']]], - ['choice_1',['choice',['../classAutoChooser.html#a473e03a3e74487a38e94d3b5957f34bc',1,'AutoChooser']]], - ['commandcontroller_2',['CommandController',['../classCommandController.html',1,'']]], - ['config_3',['config',['../classPID.html#a67626fa764b201c7190ace37e068666b',1,'PID']]], - ['control_5fcontinuous_4',['control_continuous',['../classLift.html#ae585cb81d733c975a65bfa7914a6bfeb',1,'Lift']]], - ['control_5fmanual_5',['control_manual',['../classLift.html#acfeaf4547de1b6a01982e8e51b0bb224',1,'Lift']]], - ['control_5fsetpoints_6',['control_setpoints',['../classLift.html#a7197ad879474798a5c1fec4963058c3a',1,'Lift']]], - ['core_7',['Core',['../md_README.html',1,'']]], - ['correction_5fpid_8',['correction_pid',['../structrobot__specs__t.html#a23d091e4a5258c11db6cd9753b598d06',1,'robot_specs_t']]], - ['current_5fpos_9',['current_pos',['../classOdometryBase.html#a6870aebb6e05dcd152d3295462f559c3',1,'OdometryBase']]], - ['customencoder_10',['CustomEncoder',['../classCustomEncoder.html',1,'CustomEncoder'],['../classCustomEncoder.html#a6c17b425b7a899107be1bb7ed7e80b9d',1,'CustomEncoder::CustomEncoder()']]] -]; diff --git a/documentation/html/search/all_3.js b/documentation/html/search/all_3.js deleted file mode 100644 index 4b57e2e..0000000 --- a/documentation/html/search/all_3.js +++ /dev/null @@ -1,20 +0,0 @@ -var searchData= -[ - ['d_0',['d',['../structPID_1_1pid__config__t.html#a1bb8ecda3f982ea983cd9f49b3d6706a',1,'PID::pid_config_t']]], - ['deadband_1',['deadband',['../structPID_1_1pid__config__t.html#a5fe836f65a951c00113996d32101172a',1,'PID::pid_config_t']]], - ['delaycommand_2',['DelayCommand',['../classDelayCommand.html',1,'DelayCommand'],['../classDelayCommand.html#a7dc6d1e547ec24b51d91aada84d1febb',1,'DelayCommand::DelayCommand()']]], - ['dist_3',['dist',['../structVector2D_1_1point__t.html#a118bb1552bd98c9708e452d593ed5e29',1,'Vector2D::point_t']]], - ['dist_5fbetween_5fwheels_4',['dist_between_wheels',['../structrobot__specs__t.html#afb03c2e2cbc0d8fd6686c9421e016dec',1,'robot_specs_t']]], - ['draw_5',['draw',['../classGraphDrawer.html#a420b88cacbf91908dc64624eb113d197',1,'GraphDrawer']]], - ['drive_6',['drive',['../classMecanumDrive.html#ac7a660a606aea694d21a4a2dd12faa24',1,'MecanumDrive']]], - ['drive_5farcade_7',['drive_arcade',['../classTankDrive.html#a4c52b51a9b149d97e9b0b175a10652ef',1,'TankDrive']]], - ['drive_5fcorrection_5fcutoff_8',['drive_correction_cutoff',['../structrobot__specs__t.html#aa9fc95ea4c235f455b712ac0cf5aa536',1,'robot_specs_t']]], - ['drive_5ffeedback_9',['drive_feedback',['../structrobot__specs__t.html#a828213e8d672431bd3bb87e6484db83f',1,'robot_specs_t']]], - ['drive_5fforward_10',['drive_forward',['../classTankDrive.html#a1fb3d661076afbb91452649cdaf8550f',1,'TankDrive::drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed=1)'],['../classTankDrive.html#a8edcf4316d5a22c32849d7d1d5d0a793',1,'TankDrive::drive_forward(double inches, directionType dir, double max_speed=1)']]], - ['drive_5fraw_11',['drive_raw',['../classMecanumDrive.html#a756383ba74cf555d42a147584f9ae646',1,'MecanumDrive']]], - ['drive_5ftank_12',['drive_tank',['../classTankDrive.html#a1dff7827546fb3d17e0d2ca150bdf630',1,'TankDrive']]], - ['drive_5fto_5fpoint_13',['drive_to_point',['../classTankDrive.html#a267114928d17e16d36ad14fd4d3bf91a',1,'TankDrive::drive_to_point(double x, double y, vex::directionType dir, double max_speed=1)'],['../classTankDrive.html#ad64cf88b180865f7e0f9810a344db791',1,'TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed=1)']]], - ['driveforwardcommand_14',['DriveForwardCommand',['../classDriveForwardCommand.html#a09fb0fc75fa06951c9dc160de169d726',1,'DriveForwardCommand::DriveForwardCommand()'],['../classDriveForwardCommand.html',1,'DriveForwardCommand']]], - ['drivestopcommand_15',['DriveStopCommand',['../classDriveStopCommand.html',1,'DriveStopCommand'],['../classDriveStopCommand.html#a64cc2eeb3a4d67482549a029f93ddde1',1,'DriveStopCommand::DriveStopCommand()']]], - ['drivetopointcommand_16',['DriveToPointCommand',['../classDriveToPointCommand.html',1,'DriveToPointCommand'],['../classDriveToPointCommand.html#ad9d5b904185abbddde096dc87e02f049',1,'DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed=1)'],['../classDriveToPointCommand.html#a716343f0c8befbd3a9c562c6a4fd6538',1,'DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, Vector2D::point_t point, directionType dir, double max_speed=1)']]] -]; diff --git a/documentation/html/search/all_4.js b/documentation/html/search/all_4.js deleted file mode 100644 index 3c35471..0000000 --- a/documentation/html/search/all_4.js +++ /dev/null @@ -1,8 +0,0 @@ -var searchData= -[ - ['end_5fasync_0',['end_async',['../classOdometryBase.html#ab65ccaa80d4bb0d0aa20e82b3b991436',1,'OdometryBase']]], - ['end_5ftask_1',['end_task',['../classOdometryBase.html#ae6e35ee98b4410f034cd37c0d2055a8d',1,'OdometryBase']]], - ['entry_5ft_2',['entry_t',['../structAutoChooser_1_1entry__t.html',1,'AutoChooser']]], - ['error_5fmethod_3',['error_method',['../structPID_1_1pid__config__t.html#ad2f96f58fba854b7e4329175497d1869',1,'PID::pid_config_t']]], - ['error_5ftype_4',['ERROR_TYPE',['../classPID.html#a259eb7bfd0750c7afd4a058c5d1c58a1',1,'PID']]] -]; diff --git a/documentation/html/search/all_5.js b/documentation/html/search/all_5.js deleted file mode 100644 index b8250a3..0000000 --- a/documentation/html/search/all_5.js +++ /dev/null @@ -1,11 +0,0 @@ -var searchData= -[ - ['feedback_0',['Feedback',['../classFeedback.html',1,'']]], - ['feedforward_1',['FeedForward',['../classFeedForward.html',1,'FeedForward'],['../classFeedForward.html#aeea5ddbbcc6e75a479442cf69954665c',1,'FeedForward::FeedForward()']]], - ['ff_5fcfg_2',['ff_cfg',['../structMotionController_1_1m__profile__cfg__t.html#ad8131facbd379321cc7083361e68ff62',1,'MotionController::m_profile_cfg_t']]], - ['ff_5fconfig_5ft_3',['ff_config_t',['../structFeedForward_1_1ff__config__t.html',1,'FeedForward']]], - ['flywheel_4',['Flywheel',['../classFlywheel.html',1,'Flywheel'],['../classFlywheel.html#a61a1ba81b716c6f99a8d63394f8d185f',1,'Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio)'],['../classFlywheel.html#a38bb042949a6c6e7f283823a5786be65',1,'Flywheel::Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio)'],['../classFlywheel.html#a9ce96416ffe460e013fab3ba434bae79',1,'Flywheel::Flywheel(motor_group &motors, double tbh_gain, const double ratio)'],['../classFlywheel.html#a3ae86041ee9dc973538fcc6caf47cd58',1,'Flywheel::Flywheel(motor_group &motors, const double ratio)']]], - ['flywheelstopcommand_5',['FlywheelStopCommand',['../classFlywheelStopCommand.html',1,'FlywheelStopCommand'],['../classFlywheelStopCommand.html#a3e94b6c95ab4ad8216c9a87a22c07c4b',1,'FlywheelStopCommand::FlywheelStopCommand()']]], - ['flywheelstopmotorscommand_6',['FlywheelStopMotorsCommand',['../classFlywheelStopMotorsCommand.html',1,'FlywheelStopMotorsCommand'],['../classFlywheelStopMotorsCommand.html#a0e7ce6586a6ae1ec9322114ede691a13',1,'FlywheelStopMotorsCommand::FlywheelStopMotorsCommand()']]], - ['flywheelstopnontaskscommand_7',['FlywheelStopNonTasksCommand',['../classFlywheelStopNonTasksCommand.html',1,'']]] -]; diff --git a/documentation/html/search/all_6.js b/documentation/html/search/all_6.js deleted file mode 100644 index 24c6a7f..0000000 --- a/documentation/html/search/all_6.js +++ /dev/null @@ -1,31 +0,0 @@ -var searchData= -[ - ['genericauto_0',['GenericAuto',['../classGenericAuto.html',1,'']]], - ['get_1',['get',['../classFeedback.html#ac44bb519a6f4e25c8e8250f3d30ab359',1,'Feedback::get()'],['../classMotionController.html#a2a1944f590618cd91770364aea416cd5',1,'MotionController::get()'],['../classPID.html#a69c2e66b8ff06c86ca9701d11e21da75',1,'PID::get()'],['../classPIDFF.html#a78a34d271bcc703fc803e15b275fd238',1,'PIDFF::get()']]], - ['get_5faccel_2',['get_accel',['../classOdometryBase.html#a3223bac952f79bf910b979690499b965',1,'OdometryBase']]], - ['get_5fangular_5faccel_5fdeg_3',['get_angular_accel_deg',['../classOdometryBase.html#a456e6433e51971d2640ff96ed3a59432',1,'OdometryBase']]], - ['get_5fangular_5fspeed_5fdeg_4',['get_angular_speed_deg',['../classOdometryBase.html#af30d97a35e9e9c4f9be0a81390e6c0f1',1,'OdometryBase']]], - ['get_5fasync_5',['get_async',['../classLift.html#a6913ab2df38f0429641c256ec9288370',1,'Lift']]], - ['get_5faverage_6',['get_average',['../classMovingAverage.html#aa91e650064d361abe51bfa0b166ac6c0',1,'MovingAverage']]], - ['get_5fchoice_7',['get_choice',['../classAutoChooser.html#ada27d20c06baeb169c3abed5fd0b06bb',1,'AutoChooser']]], - ['get_5fdir_8',['get_dir',['../classVector2D.html#a683dab4e55cfc8483a32c6805cd29980',1,'Vector2D']]], - ['get_5ferror_9',['get_error',['../classPID.html#ab5cdb296dbcce80703a9a98b9605c500',1,'PID']]], - ['get_5fmag_10',['get_mag',['../classVector2D.html#a4da6f92b5874470ed5642587a973c3df',1,'Vector2D']]], - ['get_5fmotion_11',['get_motion',['../classMotionController.html#ab958ce97fbc4929f4dd03965671e8d4d',1,'MotionController']]], - ['get_5fmovement_5ftime_12',['get_movement_time',['../classTrapezoidProfile.html#abd551042dfffe0923200c4546d109c55',1,'TrapezoidProfile']]], - ['get_5fposition_13',['get_position',['../classOdometryBase.html#a3cdcfcf70ef02e0efc2efd902fac3811',1,'OdometryBase']]], - ['get_5fsetpoint_14',['get_setpoint',['../classLift.html#adaa6cb65351d0c8a2c199a87a318b133',1,'Lift']]], - ['get_5fsize_15',['get_size',['../classMovingAverage.html#ac45976e15321d2c2f52d1f281475b53d',1,'MovingAverage']]], - ['get_5fspeed_16',['get_speed',['../classOdometryBase.html#a96c7be68db7424ddbe3704770dd1889f',1,'OdometryBase']]], - ['get_5ftarget_17',['get_target',['../classPID.html#a1cd58cedeccc45b67551e331ee547be9',1,'PID']]], - ['get_5fx_18',['get_x',['../classVector2D.html#a240e649d36dbda8bcba031f5fe5a2438',1,'Vector2D']]], - ['get_5fy_19',['get_y',['../classVector2D.html#aee94b809a4a63b972c72b22257fa3f30',1,'Vector2D']]], - ['getdesiredrpm_20',['getDesiredRPM',['../classFlywheel.html#a5dee80fd74903884478649b6ec2f4528',1,'Flywheel']]], - ['getfeedforwardvalue_21',['getFeedforwardValue',['../classFlywheel.html#aea43f1c07b799133113d7b9ff14a7f36',1,'Flywheel']]], - ['getmotors_22',['getMotors',['../classFlywheel.html#a5823c1242f4b00519f582a7468cf537a',1,'Flywheel']]], - ['getpid_23',['getPID',['../classFlywheel.html#adf7b3fab5fd8a708f339da649c72e775',1,'Flywheel']]], - ['getpidvalue_24',['getPIDValue',['../classFlywheel.html#a45bde10a01304c71e74564cd080a9052',1,'Flywheel']]], - ['getrpm_25',['getRPM',['../classFlywheel.html#a00e5ad15adfb23185f7713b86d9d7b9f',1,'Flywheel']]], - ['gettbhgain_26',['getTBHGain',['../classFlywheel.html#a8c1f0b98975b9d75bc5b350fa059043d',1,'Flywheel']]], - ['graphdrawer_27',['GraphDrawer',['../classGraphDrawer.html#a8066ff51adb3cbbeca34268d13f34c5f',1,'GraphDrawer::GraphDrawer()'],['../classGraphDrawer.html',1,'GraphDrawer']]] -]; diff --git a/documentation/html/search/all_7.js b/documentation/html/search/all_7.js deleted file mode 100644 index 32946e0..0000000 --- a/documentation/html/search/all_7.js +++ /dev/null @@ -1,8 +0,0 @@ -var searchData= -[ - ['handle_0',['handle',['../classOdometryBase.html#ae5308f20a4dfef9594631010c7612dab',1,'OdometryBase']]], - ['height_1',['height',['../structAutoChooser_1_1entry__t.html#a957eb90ff083c4a4f8dc90da976b86c7',1,'AutoChooser::entry_t']]], - ['hermite_5fpoint_2',['hermite_point',['../structPurePursuit_1_1hermite__point.html',1,'PurePursuit']]], - ['hold_3',['hold',['../classLift.html#a9afcbf54cdd919a2c5a68f95c7a0c9e8',1,'Lift']]], - ['home_4',['home',['../classLift.html#ab53178b13037a4c6b1fd07657cff1f25',1,'Lift']]] -]; diff --git a/documentation/html/search/all_8.js b/documentation/html/search/all_8.js deleted file mode 100644 index 80e164b..0000000 --- a/documentation/html/search/all_8.js +++ /dev/null @@ -1,7 +0,0 @@ -var searchData= -[ - ['i_0',['i',['../structPID_1_1pid__config__t.html#a4140c6884d1dc86366520a2543e654b3',1,'PID::pid_config_t']]], - ['init_1',['init',['../classFeedback.html#a22efb13216bfd51aea07e0b6e45135c1',1,'Feedback::init()'],['../classMotionController.html#af0d665d9916111cbce677da6df6b6667',1,'MotionController::init()'],['../classPID.html#aab0f3b4351cc4ee2b8bb366105e85e95',1,'PID::init()'],['../classPIDFF.html#a37226c8d3bfac97485b28105a15f29fc',1,'PIDFF::init()']]], - ['is_5fon_5ftarget_2',['is_on_target',['../classFeedback.html#ae4cc835c374aab9761d22603d4329d34',1,'Feedback::is_on_target()'],['../classMotionController.html#aa9e2af88b848646889deb1d43a283173',1,'MotionController::is_on_target()'],['../classPID.html#a9de884c31570c4ae0dc6e24eb26daa43',1,'PID::is_on_target()'],['../classPIDFF.html#a2534a33490570d839bf1849673a70bc1',1,'PIDFF::is_on_target()']]], - ['istaskrunning_3',['isTaskRunning',['../classFlywheel.html#a990fde5741011926c84c45ea3c51ced3',1,'Flywheel']]] -]; diff --git a/documentation/html/search/all_9.js b/documentation/html/search/all_9.js deleted file mode 100644 index bd011ee..0000000 --- a/documentation/html/search/all_9.js +++ /dev/null @@ -1,7 +0,0 @@ -var searchData= -[ - ['ka_0',['kA',['../structFeedForward_1_1ff__config__t.html#a8528f04936dbcbf0bc406d0bfc6b8428',1,'FeedForward::ff_config_t']]], - ['kg_1',['kG',['../structFeedForward_1_1ff__config__t.html#a1eab464040edd69a63b528d6d21f0644',1,'FeedForward::ff_config_t']]], - ['ks_2',['kS',['../structFeedForward_1_1ff__config__t.html#af140ce6afc074040571d229b6a455c50',1,'FeedForward::ff_config_t']]], - ['kv_3',['kV',['../structFeedForward_1_1ff__config__t.html#afd4e01b20b64750ad2604b17ac10f57e',1,'FeedForward::ff_config_t']]] -]; diff --git a/documentation/html/search/all_a.js b/documentation/html/search/all_a.js deleted file mode 100644 index 22c068f..0000000 --- a/documentation/html/search/all_a.js +++ /dev/null @@ -1,7 +0,0 @@ -var searchData= -[ - ['last_5fcommand_5ftimed_5fout_0',['last_command_timed_out',['../classCommandController.html#a23306007060f97ab7f57715c5d8d0c57',1,'CommandController']]], - ['lift_1',['Lift',['../classLift.html',1,'Lift< T >'],['../classLift.html#aa5723874330725dec5176ec4174e9ea8',1,'Lift::Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map< T, double > &setpoint_map, limit *homing_switch=NULL)']]], - ['lift_5fcfg_5ft_2',['lift_cfg_t',['../structLift_1_1lift__cfg__t.html',1,'Lift']]], - ['list_3',['list',['../classAutoChooser.html#a5c2b8683579011b529b95aab423b120a',1,'AutoChooser']]] -]; diff --git a/documentation/html/search/all_b.js b/documentation/html/search/all_b.js deleted file mode 100644 index 9af57af..0000000 --- a/documentation/html/search/all_b.js +++ /dev/null @@ -1,13 +0,0 @@ -var searchData= -[ - ['m_5fprofile_5fcfg_5ft_0',['m_profile_cfg_t',['../structMotionController_1_1m__profile__cfg__t.html',1,'MotionController']]], - ['max_5fv_1',['max_v',['../structMotionController_1_1m__profile__cfg__t.html#a949b084fe78795509ad8e65c74e9bc3f',1,'MotionController::m_profile_cfg_t']]], - ['measurerpm_2',['measureRPM',['../classFlywheel.html#ae46b69a8371dca7d6fb163c30192f666',1,'Flywheel']]], - ['mecanumdrive_3',['MecanumDrive',['../classMecanumDrive.html',1,'MecanumDrive'],['../classMecanumDrive.html#a780908c5b55ea8b9f228c84540a6c5f7',1,'MecanumDrive::MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear, vex::rotation *lateral_wheel=NULL, vex::inertial *imu=NULL, mecanumdrive_config_t *config=NULL)']]], - ['mecanumdrive_5fconfig_5ft_4',['mecanumdrive_config_t',['../structMecanumDrive_1_1mecanumdrive__config__t.html',1,'MecanumDrive']]], - ['modify_5finputs_5',['modify_inputs',['../classTankDrive.html#abb511cf1be40ef7be89c2ccff6a09cab',1,'TankDrive']]], - ['motion_5ft_6',['motion_t',['../structmotion__t.html',1,'']]], - ['motioncontroller_7',['MotionController',['../classMotionController.html',1,'MotionController'],['../classMotionController.html#a076c5aa4ea383dccaeec76f7554a7467',1,'MotionController::MotionController()']]], - ['movingaverage_8',['MovingAverage',['../classMovingAverage.html',1,'MovingAverage'],['../classMovingAverage.html#a2455b651d3c6ad1f14d1a0d65b2394b2',1,'MovingAverage::MovingAverage(int buffer_size)'],['../classMovingAverage.html#afd1c880fdd617fcbf02f54ac87f45d6f',1,'MovingAverage::MovingAverage(int buffer_size, double starting_value)']]], - ['mut_9',['mut',['../classOdometryBase.html#a88bb48858ca6ff8300a41e23482ec6f6',1,'OdometryBase']]] -]; diff --git a/documentation/html/search/all_c.js b/documentation/html/search/all_c.js deleted file mode 100644 index ed08633..0000000 --- a/documentation/html/search/all_c.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['name_0',['name',['../structAutoChooser_1_1entry__t.html#ab876b8f9fa8bf03a91c45c55c2a7fa23',1,'AutoChooser::entry_t']]], - ['normalize_1',['normalize',['../classVector2D.html#a0bb684df2d724e4378dc5fbf0d4faa99',1,'Vector2D']]] -]; diff --git a/documentation/html/search/all_d.js b/documentation/html/search/all_d.js deleted file mode 100644 index b6e8ae2..0000000 --- a/documentation/html/search/all_d.js +++ /dev/null @@ -1,16 +0,0 @@ -var searchData= -[ - ['odom_5fgear_5fratio_0',['odom_gear_ratio',['../structrobot__specs__t.html#a8c454d8b38efdd15dfa6f075c40e4ec7',1,'robot_specs_t']]], - ['odom_5fwheel_5fdiam_1',['odom_wheel_diam',['../structrobot__specs__t.html#acf12b29aa6a86cc09b2ef868f9e77a31',1,'robot_specs_t']]], - ['odometry3wheel_2',['Odometry3Wheel',['../classOdometry3Wheel.html',1,'Odometry3Wheel'],['../classOdometry3Wheel.html#a6755014965483b84e06e42d8e289bf40',1,'Odometry3Wheel::Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, odometry3wheel_cfg_t &cfg, bool is_async=true)']]], - ['odometry3wheel_5fcfg_5ft_3',['odometry3wheel_cfg_t',['../structOdometry3Wheel_1_1odometry3wheel__cfg__t.html',1,'Odometry3Wheel']]], - ['odometrybase_4',['OdometryBase',['../classOdometryBase.html',1,'OdometryBase'],['../classOdometryBase.html#a61286bd1c5105adbfa5b52c74f9e9466',1,'OdometryBase::OdometryBase()']]], - ['odometrytank_5',['OdometryTank',['../classOdometryTank.html',1,'OdometryTank'],['../classOdometryTank.html#add83c3320e43e90963c38f25ce06c4da',1,'OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true)'],['../classOdometryTank.html#a0fdb5e855104301ad83588362974b75a',1,'OdometryTank::OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true)']]], - ['odomsetposition_6',['OdomSetPosition',['../classOdomSetPosition.html#afcd92592689e2c3262dd9120286bbac2',1,'OdomSetPosition::OdomSetPosition()'],['../classOdomSetPosition.html',1,'OdomSetPosition']]], - ['off_5faxis_5fcenter_5fdist_7',['off_axis_center_dist',['../structOdometry3Wheel_1_1odometry3wheel__cfg__t.html#afd79024054d352789991bd816d955d9e',1,'Odometry3Wheel::odometry3wheel_cfg_t']]], - ['on_5ftarget_5ftime_8',['on_target_time',['../structPID_1_1pid__config__t.html#a14212579cfa1827b6cc04388c6b3626e',1,'PID::pid_config_t']]], - ['on_5ftimeout_9',['on_timeout',['../classAutoCommand.html#a68475854d11e7c3be90e9c6e8fc9e982',1,'AutoCommand::on_timeout()'],['../classDriveForwardCommand.html#a52b4e1ff386eeb1c00f219f40738d0af',1,'DriveForwardCommand::on_timeout()'],['../classTurnDegreesCommand.html#abd912b5906bafd9f4117e005eaeccb18',1,'TurnDegreesCommand::on_timeout()'],['../classTurnToHeadingCommand.html#acaa3b650ed9f02315eb6ba901181bc85',1,'TurnToHeadingCommand::on_timeout()']]], - ['operator_2a_10',['operator*',['../classVector2D.html#a00a0dc6776995d47659b3ddd58c33a78',1,'Vector2D']]], - ['operator_2b_11',['operator+',['../structVector2D_1_1point__t.html#a80783a6446695b14693816aaf1341bdb',1,'Vector2D::point_t::operator+()'],['../classVector2D.html#a2bed654f65df8c3bedbf8cd7d07071df',1,'Vector2D::operator+()']]], - ['operator_2d_12',['operator-',['../structVector2D_1_1point__t.html#aac0efd68a6d8dbe4cbb2437096a0a05d',1,'Vector2D::point_t::operator-()'],['../classVector2D.html#a07a043fc63572c1cf3104ec0a9a4e796',1,'Vector2D::operator-()']]] -]; diff --git a/documentation/html/search/all_e.js b/documentation/html/search/all_e.js deleted file mode 100644 index d5c5780..0000000 --- a/documentation/html/search/all_e.js +++ /dev/null @@ -1,15 +0,0 @@ -var searchData= -[ - ['p_0',['p',['../structPID_1_1pid__config__t.html#a27290957ad115f4502f765ff292e3a23',1,'PID::pid_config_t']]], - ['pid_1',['PID',['../classPID.html',1,'PID'],['../classPID.html#a3b6b678b2d52a2be7fb572b766e43994',1,'PID::PID()']]], - ['pid_5fcfg_2',['pid_cfg',['../structMotionController_1_1m__profile__cfg__t.html#a2b6415c29fcab4f9b2ccff067a390baa',1,'MotionController::m_profile_cfg_t']]], - ['pid_5fconfig_5ft_3',['pid_config_t',['../structPID_1_1pid__config__t.html',1,'PID']]], - ['pidff_4',['PIDFF',['../classPIDFF.html',1,'']]], - ['point_5',['point',['../classVector2D.html#a567227aaadc7eceae0cbccf7f611aff4',1,'Vector2D']]], - ['point_5ft_6',['point_t',['../structVector2D_1_1point__t.html',1,'Vector2D']]], - ['pos_7',['pos',['../structmotion__t.html#a7f67afcb6e0a49061509a11c47de46e4',1,'motion_t']]], - ['pos_5fdiff_8',['pos_diff',['../classOdometryBase.html#a8a248f027d3ff98cb2df2e3cd90e1f66',1,'OdometryBase']]], - ['position_9',['position',['../classCustomEncoder.html#ab891fa278911c232bd0bf502a5ed95eb',1,'CustomEncoder']]], - ['position_5ft_10',['position_t',['../structposition__t.html',1,'']]], - ['pure_5fpursuit_11',['pure_pursuit',['../classTankDrive.html#a13bb19d1cf97b7f3534f4f2a0a13bf27',1,'TankDrive']]] -]; diff --git a/documentation/html/search/all_f.js b/documentation/html/search/all_f.js deleted file mode 100644 index 34d564c..0000000 --- a/documentation/html/search/all_f.js +++ /dev/null @@ -1,12 +0,0 @@ -var searchData= -[ - ['render_0',['render',['../classAutoChooser.html#a9365d354e3401d819e58a999721c07d9',1,'AutoChooser']]], - ['reset_1',['reset',['../classPID.html#af9677e76cb1beffbcf3f54cbc627c530',1,'PID']]], - ['reset_5fauto_2',['reset_auto',['../classTankDrive.html#aaa68eae1521e5b87ecfed2a60b15bf34',1,'TankDrive']]], - ['robot_5fradius_3',['robot_radius',['../structrobot__specs__t.html#a37a65da54459d805cf1370cc6330bce0',1,'robot_specs_t']]], - ['robot_5fspecs_5ft_4',['robot_specs_t',['../structrobot__specs__t.html',1,'']]], - ['rot_5',['rot',['../structposition__t.html#aa22df5aed859f41200d2213ad3f2cd45',1,'position_t']]], - ['rot_5fdiff_6',['rot_diff',['../classOdometryBase.html#ab1f1a09cda37d799c82003b5284c6856',1,'OdometryBase']]], - ['rotation_7',['rotation',['../classCustomEncoder.html#a853fa3a11f2563d71f08ee3c3f38ff01',1,'CustomEncoder']]], - ['run_8',['run',['../classGenericAuto.html#af25dcaaf074980064382c458812b3c9c',1,'GenericAuto::run()'],['../classFlywheelStopMotorsCommand.html#ab5b75338d50c3674a5fe27a5e77698bc',1,'FlywheelStopMotorsCommand::run()'],['../classFlywheelStopCommand.html#a9be8ca8422bd7b5f5a03cbf8e21025a7',1,'FlywheelStopCommand::run()'],['../classWaitUntilUpToSpeedCommand.html#a38f75c01a4740d87a380c15cc51c6396',1,'WaitUntilUpToSpeedCommand::run()'],['../classSpinRPMCommand.html#af12f71f87967de0d9991272d9659b6ef',1,'SpinRPMCommand::run()'],['../classOdomSetPosition.html#a611e74a12a9eeb0fce1f38a596c3c467',1,'OdomSetPosition::run()'],['../classDriveStopCommand.html#a3b37806449b50b2f2c19179f1039237b',1,'DriveStopCommand::run()'],['../classTurnToHeadingCommand.html#af571168ca078be95cbc735c99c2f4093',1,'TurnToHeadingCommand::run()'],['../classDriveToPointCommand.html#a8ed58921bc3eeb8c04d0b11b4f7e4fbe',1,'DriveToPointCommand::run()'],['../classTurnDegreesCommand.html#a2206e4c5073a2e83f6bfa3eeca46a370',1,'TurnDegreesCommand::run()'],['../classDriveForwardCommand.html#aff482b72cab23cd569eb01efac6d1d31',1,'DriveForwardCommand::run()'],['../classDelayCommand.html#a6cff8fe05b3ca36ec2ab20e411cfd9ab',1,'DelayCommand::run()'],['../classCommandController.html#a0f7f6ccce0304c577521205ad37bb36a',1,'CommandController::run()'],['../classAutoCommand.html#a9f58c576ca6378b18a4136f60df50560',1,'AutoCommand::run()']]] -]; diff --git a/documentation/html/search/classes_0.js b/documentation/html/search/classes_0.js deleted file mode 100644 index b733383..0000000 --- a/documentation/html/search/classes_0.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['autochooser_0',['AutoChooser',['../classAutoChooser.html',1,'']]], - ['autocommand_1',['AutoCommand',['../classAutoCommand.html',1,'']]] -]; diff --git a/documentation/html/search/classes_1.js b/documentation/html/search/classes_1.js deleted file mode 100644 index 5cfcda3..0000000 --- a/documentation/html/search/classes_1.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['commandcontroller_0',['CommandController',['../classCommandController.html',1,'']]], - ['customencoder_1',['CustomEncoder',['../classCustomEncoder.html',1,'']]] -]; diff --git a/documentation/html/search/classes_2.js b/documentation/html/search/classes_2.js deleted file mode 100644 index 5f3f612..0000000 --- a/documentation/html/search/classes_2.js +++ /dev/null @@ -1,7 +0,0 @@ -var searchData= -[ - ['delaycommand_0',['DelayCommand',['../classDelayCommand.html',1,'']]], - ['driveforwardcommand_1',['DriveForwardCommand',['../classDriveForwardCommand.html',1,'']]], - ['drivestopcommand_2',['DriveStopCommand',['../classDriveStopCommand.html',1,'']]], - ['drivetopointcommand_3',['DriveToPointCommand',['../classDriveToPointCommand.html',1,'']]] -]; diff --git a/documentation/html/search/classes_3.js b/documentation/html/search/classes_3.js deleted file mode 100644 index 5a50111..0000000 --- a/documentation/html/search/classes_3.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['entry_5ft_0',['entry_t',['../structAutoChooser_1_1entry__t.html',1,'AutoChooser']]] -]; diff --git a/documentation/html/search/classes_4.js b/documentation/html/search/classes_4.js deleted file mode 100644 index ea38884..0000000 --- a/documentation/html/search/classes_4.js +++ /dev/null @@ -1,10 +0,0 @@ -var searchData= -[ - ['feedback_0',['Feedback',['../classFeedback.html',1,'']]], - ['feedforward_1',['FeedForward',['../classFeedForward.html',1,'']]], - ['ff_5fconfig_5ft_2',['ff_config_t',['../structFeedForward_1_1ff__config__t.html',1,'FeedForward']]], - ['flywheel_3',['Flywheel',['../classFlywheel.html',1,'']]], - ['flywheelstopcommand_4',['FlywheelStopCommand',['../classFlywheelStopCommand.html',1,'']]], - ['flywheelstopmotorscommand_5',['FlywheelStopMotorsCommand',['../classFlywheelStopMotorsCommand.html',1,'']]], - ['flywheelstopnontaskscommand_6',['FlywheelStopNonTasksCommand',['../classFlywheelStopNonTasksCommand.html',1,'']]] -]; diff --git a/documentation/html/search/classes_5.js b/documentation/html/search/classes_5.js deleted file mode 100644 index 43b02b7..0000000 --- a/documentation/html/search/classes_5.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['genericauto_0',['GenericAuto',['../classGenericAuto.html',1,'']]], - ['graphdrawer_1',['GraphDrawer',['../classGraphDrawer.html',1,'']]] -]; diff --git a/documentation/html/search/classes_6.js b/documentation/html/search/classes_6.js deleted file mode 100644 index 58f30b3..0000000 --- a/documentation/html/search/classes_6.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['hermite_5fpoint_0',['hermite_point',['../structPurePursuit_1_1hermite__point.html',1,'PurePursuit']]] -]; diff --git a/documentation/html/search/classes_7.js b/documentation/html/search/classes_7.js deleted file mode 100644 index 930d3d3..0000000 --- a/documentation/html/search/classes_7.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['lift_0',['Lift',['../classLift.html',1,'']]], - ['lift_5fcfg_5ft_1',['lift_cfg_t',['../structLift_1_1lift__cfg__t.html',1,'Lift']]] -]; diff --git a/documentation/html/search/classes_8.js b/documentation/html/search/classes_8.js deleted file mode 100644 index 8aebec0..0000000 --- a/documentation/html/search/classes_8.js +++ /dev/null @@ -1,9 +0,0 @@ -var searchData= -[ - ['m_5fprofile_5fcfg_5ft_0',['m_profile_cfg_t',['../structMotionController_1_1m__profile__cfg__t.html',1,'MotionController']]], - ['mecanumdrive_1',['MecanumDrive',['../classMecanumDrive.html',1,'']]], - ['mecanumdrive_5fconfig_5ft_2',['mecanumdrive_config_t',['../structMecanumDrive_1_1mecanumdrive__config__t.html',1,'MecanumDrive']]], - ['motion_5ft_3',['motion_t',['../structmotion__t.html',1,'']]], - ['motioncontroller_4',['MotionController',['../classMotionController.html',1,'']]], - ['movingaverage_5',['MovingAverage',['../classMovingAverage.html',1,'']]] -]; diff --git a/documentation/html/search/classes_9.js b/documentation/html/search/classes_9.js deleted file mode 100644 index f71ac9a..0000000 --- a/documentation/html/search/classes_9.js +++ /dev/null @@ -1,8 +0,0 @@ -var searchData= -[ - ['odometry3wheel_0',['Odometry3Wheel',['../classOdometry3Wheel.html',1,'']]], - ['odometry3wheel_5fcfg_5ft_1',['odometry3wheel_cfg_t',['../structOdometry3Wheel_1_1odometry3wheel__cfg__t.html',1,'Odometry3Wheel']]], - ['odometrybase_2',['OdometryBase',['../classOdometryBase.html',1,'']]], - ['odometrytank_3',['OdometryTank',['../classOdometryTank.html',1,'']]], - ['odomsetposition_4',['OdomSetPosition',['../classOdomSetPosition.html',1,'']]] -]; diff --git a/documentation/html/search/classes_a.js b/documentation/html/search/classes_a.js deleted file mode 100644 index b697c70..0000000 --- a/documentation/html/search/classes_a.js +++ /dev/null @@ -1,8 +0,0 @@ -var searchData= -[ - ['pid_0',['PID',['../classPID.html',1,'']]], - ['pid_5fconfig_5ft_1',['pid_config_t',['../structPID_1_1pid__config__t.html',1,'PID']]], - ['pidff_2',['PIDFF',['../classPIDFF.html',1,'']]], - ['point_5ft_3',['point_t',['../structVector2D_1_1point__t.html',1,'Vector2D']]], - ['position_5ft_4',['position_t',['../structposition__t.html',1,'']]] -]; diff --git a/documentation/html/search/classes_b.js b/documentation/html/search/classes_b.js deleted file mode 100644 index a8d8c05..0000000 --- a/documentation/html/search/classes_b.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['robot_5fspecs_5ft_0',['robot_specs_t',['../structrobot__specs__t.html',1,'']]] -]; diff --git a/documentation/html/search/classes_c.js b/documentation/html/search/classes_c.js deleted file mode 100644 index c5119ff..0000000 --- a/documentation/html/search/classes_c.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['spinrpmcommand_0',['SpinRPMCommand',['../classSpinRPMCommand.html',1,'']]], - ['spline_1',['spline',['../structPurePursuit_1_1spline.html',1,'PurePursuit']]] -]; diff --git a/documentation/html/search/classes_d.js b/documentation/html/search/classes_d.js deleted file mode 100644 index 2a29d86..0000000 --- a/documentation/html/search/classes_d.js +++ /dev/null @@ -1,7 +0,0 @@ -var searchData= -[ - ['tankdrive_0',['TankDrive',['../classTankDrive.html',1,'']]], - ['trapezoidprofile_1',['TrapezoidProfile',['../classTrapezoidProfile.html',1,'']]], - ['turndegreescommand_2',['TurnDegreesCommand',['../classTurnDegreesCommand.html',1,'']]], - ['turntoheadingcommand_3',['TurnToHeadingCommand',['../classTurnToHeadingCommand.html',1,'']]] -]; diff --git a/documentation/html/search/classes_e.js b/documentation/html/search/classes_e.js deleted file mode 100644 index cd06f6b..0000000 --- a/documentation/html/search/classes_e.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['vector2d_0',['Vector2D',['../classVector2D.html',1,'']]] -]; diff --git a/documentation/html/search/classes_f.js b/documentation/html/search/classes_f.js deleted file mode 100644 index f42e8a0..0000000 --- a/documentation/html/search/classes_f.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['waituntiluptospeedcommand_0',['WaitUntilUpToSpeedCommand',['../classWaitUntilUpToSpeedCommand.html',1,'']]] -]; diff --git a/documentation/html/search/close.svg b/documentation/html/search/close.svg deleted file mode 100644 index a933eea..0000000 --- a/documentation/html/search/close.svg +++ /dev/null @@ -1,31 +0,0 @@ - - - - - - image/svg+xml - - - - - - - - diff --git a/documentation/html/search/enums_0.js b/documentation/html/search/enums_0.js deleted file mode 100644 index 3512f6a..0000000 --- a/documentation/html/search/enums_0.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['error_5ftype_0',['ERROR_TYPE',['../classPID.html#a259eb7bfd0750c7afd4a058c5d1c58a1',1,'PID']]] -]; diff --git a/documentation/html/search/functions_0.js b/documentation/html/search/functions_0.js deleted file mode 100644 index 62057ce..0000000 --- a/documentation/html/search/functions_0.js +++ /dev/null @@ -1,11 +0,0 @@ -var searchData= -[ - ['add_0',['add',['../classAutoChooser.html#a67b80bf6b62cfced155519f5b608e08c',1,'AutoChooser::add()'],['../classCommandController.html#a4cb2c06abd92fb99578f0da75c1411e5',1,'CommandController::add(AutoCommand *cmd, double timeout_seconds=10.0)'],['../classCommandController.html#a03fc0dd37c12ae7f43200d5588c768b8',1,'CommandController::add(std::vector< AutoCommand * > cmds)'],['../classGenericAuto.html#af48629556173af1f5106f7405a196f47',1,'GenericAuto::add(state_ptr new_state)']]], - ['add_5fasync_1',['add_async',['../classGenericAuto.html#a938fb69c14735d4cf88ebc7589dcad1c',1,'GenericAuto']]], - ['add_5fdelay_2',['add_delay',['../classCommandController.html#ae06b054f4aeea86e8c6bee56458dc6d1',1,'CommandController::add_delay()'],['../classGenericAuto.html#aaadc99efe49a375f0dc80db7e886d96c',1,'GenericAuto::add_delay()']]], - ['add_5fentry_3',['add_entry',['../classMovingAverage.html#a6c85ea575428ef7faf1f1f111a985db8',1,'MovingAverage']]], - ['add_5fsample_4',['add_sample',['../classGraphDrawer.html#a41cadd5ade1ae9de1a82cc97ee15557c',1,'GraphDrawer']]], - ['auto_5fdrive_5',['auto_drive',['../classMecanumDrive.html#aa0cfb8683fee99e0a534c3a725d338fd',1,'MecanumDrive']]], - ['auto_5fturn_6',['auto_turn',['../classMecanumDrive.html#ac8813aafec14f2d25c3abafefdb81498',1,'MecanumDrive']]], - ['autochooser_7',['AutoChooser',['../classAutoChooser.html#a6e4f8f87e9cf0d0df2e36cda803f2c51',1,'AutoChooser']]] -]; diff --git a/documentation/html/search/functions_1.js b/documentation/html/search/functions_1.js deleted file mode 100644 index d2575c5..0000000 --- a/documentation/html/search/functions_1.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['background_5ftask_0',['background_task',['../classOdometryBase.html#a17a014f79b282ddfb715835214f3e2fb',1,'OdometryBase']]] -]; diff --git a/documentation/html/search/functions_10.js b/documentation/html/search/functions_10.js deleted file mode 100644 index a529836..0000000 --- a/documentation/html/search/functions_10.js +++ /dev/null @@ -1,11 +0,0 @@ -var searchData= -[ - ['tankdrive_0',['TankDrive',['../classTankDrive.html#a34f305bb1c996e3748c925af259aeeb4',1,'TankDrive']]], - ['trapezoidprofile_1',['TrapezoidProfile',['../classTrapezoidProfile.html#af693ca740c0112cfbf4a9ee13bbb6c5d',1,'TrapezoidProfile']]], - ['tune_2',['tune',['../classOdometry3Wheel.html#acb23dbf715d342566fc7e44f58ebf654',1,'Odometry3Wheel']]], - ['tune_5ffeedforward_3',['tune_feedforward',['../classMotionController.html#a20749b6a4bd3cf509a3acf682831eb00',1,'MotionController']]], - ['turn_5fdegrees_4',['turn_degrees',['../classTankDrive.html#ac1ce9895b82b7298465d8e59fae95763',1,'TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_speed=1)'],['../classTankDrive.html#a26d51cc12145f2520ea0c4355716184d',1,'TankDrive::turn_degrees(double degrees, double max_speed=1)']]], - ['turn_5fto_5fheading_5',['turn_to_heading',['../classTankDrive.html#a25030a7b5e9404a911f7b776a7df7f05',1,'TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double max_speed=1)'],['../classTankDrive.html#ab003af6cf2de93e649cce5245b092a36',1,'TankDrive::turn_to_heading(double heading_deg, double max_speed=1)']]], - ['turndegreescommand_6',['TurnDegreesCommand',['../classTurnDegreesCommand.html#a70a7e4688c10f1b351e6d79a3a7862ee',1,'TurnDegreesCommand']]], - ['turntoheadingcommand_7',['TurnToHeadingCommand',['../classTurnToHeadingCommand.html#a9a958d75babe94709827c827807d423d',1,'TurnToHeadingCommand']]] -]; diff --git a/documentation/html/search/functions_11.js b/documentation/html/search/functions_11.js deleted file mode 100644 index 5fb0714..0000000 --- a/documentation/html/search/functions_11.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['update_0',['update',['../classOdometry3Wheel.html#a85c5661989dae181a4db7d91bd0526f7',1,'Odometry3Wheel::update()'],['../classOdometryBase.html#a5d55b7987d97a9af721838596a520dec',1,'OdometryBase::update()'],['../classOdometryTank.html#a02508433d771c661c89d14f204a61d13',1,'OdometryTank::update()'],['../classFeedback.html#adda5fc7642539996be00632954dfc41f',1,'Feedback::update()'],['../classMotionController.html#a86ef0ef19858b5b407f7406bb5da30af',1,'MotionController::update()'],['../classPID.html#a53b5c34ba5e81fb79ed4258a143015b9',1,'PID::update()'],['../classPIDFF.html#a9a9b05ec43e4430019652b62799e761c',1,'PIDFF::update(double val) override'],['../classPIDFF.html#a015bebe6d1028451e612f103ee2c1c2c',1,'PIDFF::update(double val, double vel_setpt, double a_setpt=0)']]], - ['updatepid_1',['updatePID',['../classFlywheel.html#aa9df5ad636fb49d76ba922ecd1115aef',1,'Flywheel']]] -]; diff --git a/documentation/html/search/functions_12.js b/documentation/html/search/functions_12.js deleted file mode 100644 index d90ca7e..0000000 --- a/documentation/html/search/functions_12.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['vector2d_0',['Vector2D',['../classVector2D.html#af3084a6d83b0c8220c548fbf74df2744',1,'Vector2D::Vector2D(double dir, double mag)'],['../classVector2D.html#ae6429e185a05c8174d97beeec27432b5',1,'Vector2D::Vector2D(point_t p)']]], - ['velocity_1',['velocity',['../classCustomEncoder.html#a92fe3a3227b4c4bc1ad1389b7b758455',1,'CustomEncoder']]] -]; diff --git a/documentation/html/search/functions_13.js b/documentation/html/search/functions_13.js deleted file mode 100644 index b0f286b..0000000 --- a/documentation/html/search/functions_13.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['waituntiluptospeedcommand_0',['WaitUntilUpToSpeedCommand',['../classWaitUntilUpToSpeedCommand.html#afd000a8f148291a9d2310b76b9354fea',1,'WaitUntilUpToSpeedCommand']]] -]; diff --git a/documentation/html/search/functions_2.js b/documentation/html/search/functions_2.js deleted file mode 100644 index 4233f6e..0000000 --- a/documentation/html/search/functions_2.js +++ /dev/null @@ -1,8 +0,0 @@ -var searchData= -[ - ['calculate_0',['calculate',['../classFeedForward.html#a2e2f7c12076225fa1dfd5f18aa210290',1,'FeedForward::calculate()'],['../classTrapezoidProfile.html#a0b65a924664e6e052a16db19f73af17c',1,'TrapezoidProfile::calculate()']]], - ['control_5fcontinuous_1',['control_continuous',['../classLift.html#ae585cb81d733c975a65bfa7914a6bfeb',1,'Lift']]], - ['control_5fmanual_2',['control_manual',['../classLift.html#acfeaf4547de1b6a01982e8e51b0bb224',1,'Lift']]], - ['control_5fsetpoints_3',['control_setpoints',['../classLift.html#a7197ad879474798a5c1fec4963058c3a',1,'Lift']]], - ['customencoder_4',['CustomEncoder',['../classCustomEncoder.html#a6c17b425b7a899107be1bb7ed7e80b9d',1,'CustomEncoder']]] -]; diff --git a/documentation/html/search/functions_3.js b/documentation/html/search/functions_3.js deleted file mode 100644 index e5c0a4f..0000000 --- a/documentation/html/search/functions_3.js +++ /dev/null @@ -1,15 +0,0 @@ -var searchData= -[ - ['delaycommand_0',['DelayCommand',['../classDelayCommand.html#a7dc6d1e547ec24b51d91aada84d1febb',1,'DelayCommand']]], - ['dist_1',['dist',['../structVector2D_1_1point__t.html#a118bb1552bd98c9708e452d593ed5e29',1,'Vector2D::point_t']]], - ['draw_2',['draw',['../classGraphDrawer.html#a420b88cacbf91908dc64624eb113d197',1,'GraphDrawer']]], - ['drive_3',['drive',['../classMecanumDrive.html#ac7a660a606aea694d21a4a2dd12faa24',1,'MecanumDrive']]], - ['drive_5farcade_4',['drive_arcade',['../classTankDrive.html#a4c52b51a9b149d97e9b0b175a10652ef',1,'TankDrive']]], - ['drive_5fforward_5',['drive_forward',['../classTankDrive.html#a1fb3d661076afbb91452649cdaf8550f',1,'TankDrive::drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed=1)'],['../classTankDrive.html#a8edcf4316d5a22c32849d7d1d5d0a793',1,'TankDrive::drive_forward(double inches, directionType dir, double max_speed=1)']]], - ['drive_5fraw_6',['drive_raw',['../classMecanumDrive.html#a756383ba74cf555d42a147584f9ae646',1,'MecanumDrive']]], - ['drive_5ftank_7',['drive_tank',['../classTankDrive.html#a1dff7827546fb3d17e0d2ca150bdf630',1,'TankDrive']]], - ['drive_5fto_5fpoint_8',['drive_to_point',['../classTankDrive.html#ad64cf88b180865f7e0f9810a344db791',1,'TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed=1)'],['../classTankDrive.html#a267114928d17e16d36ad14fd4d3bf91a',1,'TankDrive::drive_to_point(double x, double y, vex::directionType dir, double max_speed=1)']]], - ['driveforwardcommand_9',['DriveForwardCommand',['../classDriveForwardCommand.html#a09fb0fc75fa06951c9dc160de169d726',1,'DriveForwardCommand']]], - ['drivestopcommand_10',['DriveStopCommand',['../classDriveStopCommand.html#a64cc2eeb3a4d67482549a029f93ddde1',1,'DriveStopCommand']]], - ['drivetopointcommand_11',['DriveToPointCommand',['../classDriveToPointCommand.html#ad9d5b904185abbddde096dc87e02f049',1,'DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed=1)'],['../classDriveToPointCommand.html#a716343f0c8befbd3a9c562c6a4fd6538',1,'DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, Vector2D::point_t point, directionType dir, double max_speed=1)']]] -]; diff --git a/documentation/html/search/functions_4.js b/documentation/html/search/functions_4.js deleted file mode 100644 index 364bca1..0000000 --- a/documentation/html/search/functions_4.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['end_5fasync_0',['end_async',['../classOdometryBase.html#ab65ccaa80d4bb0d0aa20e82b3b991436',1,'OdometryBase']]] -]; diff --git a/documentation/html/search/functions_5.js b/documentation/html/search/functions_5.js deleted file mode 100644 index 6b7d612..0000000 --- a/documentation/html/search/functions_5.js +++ /dev/null @@ -1,7 +0,0 @@ -var searchData= -[ - ['feedforward_0',['FeedForward',['../classFeedForward.html#aeea5ddbbcc6e75a479442cf69954665c',1,'FeedForward']]], - ['flywheel_1',['Flywheel',['../classFlywheel.html#a61a1ba81b716c6f99a8d63394f8d185f',1,'Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio)'],['../classFlywheel.html#a38bb042949a6c6e7f283823a5786be65',1,'Flywheel::Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio)'],['../classFlywheel.html#a9ce96416ffe460e013fab3ba434bae79',1,'Flywheel::Flywheel(motor_group &motors, double tbh_gain, const double ratio)'],['../classFlywheel.html#a3ae86041ee9dc973538fcc6caf47cd58',1,'Flywheel::Flywheel(motor_group &motors, const double ratio)']]], - ['flywheelstopcommand_2',['FlywheelStopCommand',['../classFlywheelStopCommand.html#a3e94b6c95ab4ad8216c9a87a22c07c4b',1,'FlywheelStopCommand']]], - ['flywheelstopmotorscommand_3',['FlywheelStopMotorsCommand',['../classFlywheelStopMotorsCommand.html#a0e7ce6586a6ae1ec9322114ede691a13',1,'FlywheelStopMotorsCommand']]] -]; diff --git a/documentation/html/search/functions_6.js b/documentation/html/search/functions_6.js deleted file mode 100644 index 3844fb5..0000000 --- a/documentation/html/search/functions_6.js +++ /dev/null @@ -1,30 +0,0 @@ -var searchData= -[ - ['get_0',['get',['../classMotionController.html#a2a1944f590618cd91770364aea416cd5',1,'MotionController::get()'],['../classPID.html#a69c2e66b8ff06c86ca9701d11e21da75',1,'PID::get()'],['../classPIDFF.html#a78a34d271bcc703fc803e15b275fd238',1,'PIDFF::get()'],['../classFeedback.html#ac44bb519a6f4e25c8e8250f3d30ab359',1,'Feedback::get()']]], - ['get_5faccel_1',['get_accel',['../classOdometryBase.html#a3223bac952f79bf910b979690499b965',1,'OdometryBase']]], - ['get_5fangular_5faccel_5fdeg_2',['get_angular_accel_deg',['../classOdometryBase.html#a456e6433e51971d2640ff96ed3a59432',1,'OdometryBase']]], - ['get_5fangular_5fspeed_5fdeg_3',['get_angular_speed_deg',['../classOdometryBase.html#af30d97a35e9e9c4f9be0a81390e6c0f1',1,'OdometryBase']]], - ['get_5fasync_4',['get_async',['../classLift.html#a6913ab2df38f0429641c256ec9288370',1,'Lift']]], - ['get_5faverage_5',['get_average',['../classMovingAverage.html#aa91e650064d361abe51bfa0b166ac6c0',1,'MovingAverage']]], - ['get_5fchoice_6',['get_choice',['../classAutoChooser.html#ada27d20c06baeb169c3abed5fd0b06bb',1,'AutoChooser']]], - ['get_5fdir_7',['get_dir',['../classVector2D.html#a683dab4e55cfc8483a32c6805cd29980',1,'Vector2D']]], - ['get_5ferror_8',['get_error',['../classPID.html#ab5cdb296dbcce80703a9a98b9605c500',1,'PID']]], - ['get_5fmag_9',['get_mag',['../classVector2D.html#a4da6f92b5874470ed5642587a973c3df',1,'Vector2D']]], - ['get_5fmotion_10',['get_motion',['../classMotionController.html#ab958ce97fbc4929f4dd03965671e8d4d',1,'MotionController']]], - ['get_5fmovement_5ftime_11',['get_movement_time',['../classTrapezoidProfile.html#abd551042dfffe0923200c4546d109c55',1,'TrapezoidProfile']]], - ['get_5fposition_12',['get_position',['../classOdometryBase.html#a3cdcfcf70ef02e0efc2efd902fac3811',1,'OdometryBase']]], - ['get_5fsetpoint_13',['get_setpoint',['../classLift.html#adaa6cb65351d0c8a2c199a87a318b133',1,'Lift']]], - ['get_5fsize_14',['get_size',['../classMovingAverage.html#ac45976e15321d2c2f52d1f281475b53d',1,'MovingAverage']]], - ['get_5fspeed_15',['get_speed',['../classOdometryBase.html#a96c7be68db7424ddbe3704770dd1889f',1,'OdometryBase']]], - ['get_5ftarget_16',['get_target',['../classPID.html#a1cd58cedeccc45b67551e331ee547be9',1,'PID']]], - ['get_5fx_17',['get_x',['../classVector2D.html#a240e649d36dbda8bcba031f5fe5a2438',1,'Vector2D']]], - ['get_5fy_18',['get_y',['../classVector2D.html#aee94b809a4a63b972c72b22257fa3f30',1,'Vector2D']]], - ['getdesiredrpm_19',['getDesiredRPM',['../classFlywheel.html#a5dee80fd74903884478649b6ec2f4528',1,'Flywheel']]], - ['getfeedforwardvalue_20',['getFeedforwardValue',['../classFlywheel.html#aea43f1c07b799133113d7b9ff14a7f36',1,'Flywheel']]], - ['getmotors_21',['getMotors',['../classFlywheel.html#a5823c1242f4b00519f582a7468cf537a',1,'Flywheel']]], - ['getpid_22',['getPID',['../classFlywheel.html#adf7b3fab5fd8a708f339da649c72e775',1,'Flywheel']]], - ['getpidvalue_23',['getPIDValue',['../classFlywheel.html#a45bde10a01304c71e74564cd080a9052',1,'Flywheel']]], - ['getrpm_24',['getRPM',['../classFlywheel.html#a00e5ad15adfb23185f7713b86d9d7b9f',1,'Flywheel']]], - ['gettbhgain_25',['getTBHGain',['../classFlywheel.html#a8c1f0b98975b9d75bc5b350fa059043d',1,'Flywheel']]], - ['graphdrawer_26',['GraphDrawer',['../classGraphDrawer.html#a8066ff51adb3cbbeca34268d13f34c5f',1,'GraphDrawer']]] -]; diff --git a/documentation/html/search/functions_7.js b/documentation/html/search/functions_7.js deleted file mode 100644 index 6de5b21..0000000 --- a/documentation/html/search/functions_7.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['hold_0',['hold',['../classLift.html#a9afcbf54cdd919a2c5a68f95c7a0c9e8',1,'Lift']]], - ['home_1',['home',['../classLift.html#ab53178b13037a4c6b1fd07657cff1f25',1,'Lift']]] -]; diff --git a/documentation/html/search/functions_8.js b/documentation/html/search/functions_8.js deleted file mode 100644 index ff6afea..0000000 --- a/documentation/html/search/functions_8.js +++ /dev/null @@ -1,6 +0,0 @@ -var searchData= -[ - ['init_0',['init',['../classFeedback.html#a22efb13216bfd51aea07e0b6e45135c1',1,'Feedback::init()'],['../classMotionController.html#af0d665d9916111cbce677da6df6b6667',1,'MotionController::init()'],['../classPID.html#aab0f3b4351cc4ee2b8bb366105e85e95',1,'PID::init()'],['../classPIDFF.html#a37226c8d3bfac97485b28105a15f29fc',1,'PIDFF::init()']]], - ['is_5fon_5ftarget_1',['is_on_target',['../classFeedback.html#ae4cc835c374aab9761d22603d4329d34',1,'Feedback::is_on_target()'],['../classMotionController.html#aa9e2af88b848646889deb1d43a283173',1,'MotionController::is_on_target()'],['../classPID.html#a9de884c31570c4ae0dc6e24eb26daa43',1,'PID::is_on_target()'],['../classPIDFF.html#a2534a33490570d839bf1849673a70bc1',1,'PIDFF::is_on_target()']]], - ['istaskrunning_2',['isTaskRunning',['../classFlywheel.html#a990fde5741011926c84c45ea3c51ced3',1,'Flywheel']]] -]; diff --git a/documentation/html/search/functions_9.js b/documentation/html/search/functions_9.js deleted file mode 100644 index d4951b6..0000000 --- a/documentation/html/search/functions_9.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['last_5fcommand_5ftimed_5fout_0',['last_command_timed_out',['../classCommandController.html#a23306007060f97ab7f57715c5d8d0c57',1,'CommandController']]], - ['lift_1',['Lift',['../classLift.html#aa5723874330725dec5176ec4174e9ea8',1,'Lift']]] -]; diff --git a/documentation/html/search/functions_a.js b/documentation/html/search/functions_a.js deleted file mode 100644 index bdc25b0..0000000 --- a/documentation/html/search/functions_a.js +++ /dev/null @@ -1,8 +0,0 @@ -var searchData= -[ - ['measurerpm_0',['measureRPM',['../classFlywheel.html#ae46b69a8371dca7d6fb163c30192f666',1,'Flywheel']]], - ['mecanumdrive_1',['MecanumDrive',['../classMecanumDrive.html#a780908c5b55ea8b9f228c84540a6c5f7',1,'MecanumDrive']]], - ['modify_5finputs_2',['modify_inputs',['../classTankDrive.html#abb511cf1be40ef7be89c2ccff6a09cab',1,'TankDrive']]], - ['motioncontroller_3',['MotionController',['../classMotionController.html#a076c5aa4ea383dccaeec76f7554a7467',1,'MotionController']]], - ['movingaverage_4',['MovingAverage',['../classMovingAverage.html#a2455b651d3c6ad1f14d1a0d65b2394b2',1,'MovingAverage::MovingAverage(int buffer_size)'],['../classMovingAverage.html#afd1c880fdd617fcbf02f54ac87f45d6f',1,'MovingAverage::MovingAverage(int buffer_size, double starting_value)']]] -]; diff --git a/documentation/html/search/functions_b.js b/documentation/html/search/functions_b.js deleted file mode 100644 index 621b160..0000000 --- a/documentation/html/search/functions_b.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['normalize_0',['normalize',['../classVector2D.html#a0bb684df2d724e4378dc5fbf0d4faa99',1,'Vector2D']]] -]; diff --git a/documentation/html/search/functions_c.js b/documentation/html/search/functions_c.js deleted file mode 100644 index 903e180..0000000 --- a/documentation/html/search/functions_c.js +++ /dev/null @@ -1,11 +0,0 @@ -var searchData= -[ - ['odometry3wheel_0',['Odometry3Wheel',['../classOdometry3Wheel.html#a6755014965483b84e06e42d8e289bf40',1,'Odometry3Wheel']]], - ['odometrybase_1',['OdometryBase',['../classOdometryBase.html#a61286bd1c5105adbfa5b52c74f9e9466',1,'OdometryBase']]], - ['odometrytank_2',['OdometryTank',['../classOdometryTank.html#add83c3320e43e90963c38f25ce06c4da',1,'OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true)'],['../classOdometryTank.html#a0fdb5e855104301ad83588362974b75a',1,'OdometryTank::OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true)']]], - ['odomsetposition_3',['OdomSetPosition',['../classOdomSetPosition.html#afcd92592689e2c3262dd9120286bbac2',1,'OdomSetPosition']]], - ['on_5ftimeout_4',['on_timeout',['../classAutoCommand.html#a68475854d11e7c3be90e9c6e8fc9e982',1,'AutoCommand::on_timeout()'],['../classDriveForwardCommand.html#a52b4e1ff386eeb1c00f219f40738d0af',1,'DriveForwardCommand::on_timeout()'],['../classTurnDegreesCommand.html#abd912b5906bafd9f4117e005eaeccb18',1,'TurnDegreesCommand::on_timeout()'],['../classTurnToHeadingCommand.html#acaa3b650ed9f02315eb6ba901181bc85',1,'TurnToHeadingCommand::on_timeout()']]], - ['operator_2a_5',['operator*',['../classVector2D.html#a00a0dc6776995d47659b3ddd58c33a78',1,'Vector2D']]], - ['operator_2b_6',['operator+',['../structVector2D_1_1point__t.html#a80783a6446695b14693816aaf1341bdb',1,'Vector2D::point_t::operator+()'],['../classVector2D.html#a2bed654f65df8c3bedbf8cd7d07071df',1,'Vector2D::operator+()']]], - ['operator_2d_7',['operator-',['../structVector2D_1_1point__t.html#aac0efd68a6d8dbe4cbb2437096a0a05d',1,'Vector2D::point_t::operator-()'],['../classVector2D.html#a07a043fc63572c1cf3104ec0a9a4e796',1,'Vector2D::operator-()']]] -]; diff --git a/documentation/html/search/functions_d.js b/documentation/html/search/functions_d.js deleted file mode 100644 index 9b09c6b..0000000 --- a/documentation/html/search/functions_d.js +++ /dev/null @@ -1,8 +0,0 @@ -var searchData= -[ - ['pid_0',['PID',['../classPID.html#a3b6b678b2d52a2be7fb572b766e43994',1,'PID']]], - ['point_1',['point',['../classVector2D.html#a567227aaadc7eceae0cbccf7f611aff4',1,'Vector2D']]], - ['pos_5fdiff_2',['pos_diff',['../classOdometryBase.html#a8a248f027d3ff98cb2df2e3cd90e1f66',1,'OdometryBase']]], - ['position_3',['position',['../classCustomEncoder.html#ab891fa278911c232bd0bf502a5ed95eb',1,'CustomEncoder']]], - ['pure_5fpursuit_4',['pure_pursuit',['../classTankDrive.html#a13bb19d1cf97b7f3534f4f2a0a13bf27',1,'TankDrive']]] -]; diff --git a/documentation/html/search/functions_e.js b/documentation/html/search/functions_e.js deleted file mode 100644 index 5966983..0000000 --- a/documentation/html/search/functions_e.js +++ /dev/null @@ -1,9 +0,0 @@ -var searchData= -[ - ['render_0',['render',['../classAutoChooser.html#a9365d354e3401d819e58a999721c07d9',1,'AutoChooser']]], - ['reset_1',['reset',['../classPID.html#af9677e76cb1beffbcf3f54cbc627c530',1,'PID']]], - ['reset_5fauto_2',['reset_auto',['../classTankDrive.html#aaa68eae1521e5b87ecfed2a60b15bf34',1,'TankDrive']]], - ['rot_5fdiff_3',['rot_diff',['../classOdometryBase.html#ab1f1a09cda37d799c82003b5284c6856',1,'OdometryBase']]], - ['rotation_4',['rotation',['../classCustomEncoder.html#a853fa3a11f2563d71f08ee3c3f38ff01',1,'CustomEncoder']]], - ['run_5',['run',['../classGenericAuto.html#af25dcaaf074980064382c458812b3c9c',1,'GenericAuto::run()'],['../classFlywheelStopMotorsCommand.html#ab5b75338d50c3674a5fe27a5e77698bc',1,'FlywheelStopMotorsCommand::run()'],['../classFlywheelStopCommand.html#a9be8ca8422bd7b5f5a03cbf8e21025a7',1,'FlywheelStopCommand::run()'],['../classWaitUntilUpToSpeedCommand.html#a38f75c01a4740d87a380c15cc51c6396',1,'WaitUntilUpToSpeedCommand::run()'],['../classSpinRPMCommand.html#af12f71f87967de0d9991272d9659b6ef',1,'SpinRPMCommand::run()'],['../classOdomSetPosition.html#a611e74a12a9eeb0fce1f38a596c3c467',1,'OdomSetPosition::run()'],['../classDriveStopCommand.html#a3b37806449b50b2f2c19179f1039237b',1,'DriveStopCommand::run()'],['../classTurnToHeadingCommand.html#af571168ca078be95cbc735c99c2f4093',1,'TurnToHeadingCommand::run()'],['../classDriveToPointCommand.html#a8ed58921bc3eeb8c04d0b11b4f7e4fbe',1,'DriveToPointCommand::run()'],['../classTurnDegreesCommand.html#a2206e4c5073a2e83f6bfa3eeca46a370',1,'TurnDegreesCommand::run()'],['../classDriveForwardCommand.html#aff482b72cab23cd569eb01efac6d1d31',1,'DriveForwardCommand::run()'],['../classDelayCommand.html#a6cff8fe05b3ca36ec2ab20e411cfd9ab',1,'DelayCommand::run()'],['../classCommandController.html#a0f7f6ccce0304c577521205ad37bb36a',1,'CommandController::run()'],['../classAutoCommand.html#a9f58c576ca6378b18a4136f60df50560',1,'AutoCommand::run()']]] -]; diff --git a/documentation/html/search/functions_f.js b/documentation/html/search/functions_f.js deleted file mode 100644 index 11f44dd..0000000 --- a/documentation/html/search/functions_f.js +++ /dev/null @@ -1,24 +0,0 @@ -var searchData= -[ - ['set_5faccel_0',['set_accel',['../classTrapezoidProfile.html#a1dcdfa1c290347cf0af48aca5afd167c',1,'TrapezoidProfile']]], - ['set_5fasync_1',['set_async',['../classLift.html#a7f37703180518390ec38cba9a780282b',1,'Lift']]], - ['set_5fendpts_2',['set_endpts',['../classTrapezoidProfile.html#a1d28f3fa6bf1dfa7f5c1a34d0d3b17b5',1,'TrapezoidProfile']]], - ['set_5flimits_3',['set_limits',['../classFeedback.html#a533a10b65cfc998898bf054f8b141de2',1,'Feedback::set_limits()'],['../classMotionController.html#a944c245002a1eb124dd8df40de4fcc57',1,'MotionController::set_limits()'],['../classPID.html#a8411ac48e8868d89e97afcf8990cca2c',1,'PID::set_limits()'],['../classPIDFF.html#ae0dccb27a91ec687f90c930441f246bb',1,'PIDFF::set_limits()']]], - ['set_5fmax_5fv_4',['set_max_v',['../classTrapezoidProfile.html#a6c08d08d8eadaa719f4dc9e607f9fe97',1,'TrapezoidProfile']]], - ['set_5fposition_5',['set_position',['../classLift.html#ab3cb7bc86faa079ec1249b5026ea6a85',1,'Lift::set_position()'],['../classOdometryBase.html#a34e4bd8567933d1b6bd6e41327a36549',1,'OdometryBase::set_position()'],['../classOdometryTank.html#ad3b4bcf351767992e2383ab000645335',1,'OdometryTank::set_position()']]], - ['set_5fsensor_5ffunction_6',['set_sensor_function',['../classLift.html#a08b7cdcfc9390f4945dd3737ac0e5ddc',1,'Lift']]], - ['set_5fsensor_5freset_7',['set_sensor_reset',['../classLift.html#a70b8e7cff5cd3b5827d8da07a02d92e6',1,'Lift']]], - ['set_5fsetpoint_8',['set_setpoint',['../classLift.html#a662bdc055d706699ef5cf308cd8872f8',1,'Lift']]], - ['set_5ftarget_9',['set_target',['../classPID.html#a2e301ab123c9e18e677b4873b03550dd',1,'PID::set_target()'],['../classPIDFF.html#a5b5584e4ca036b0e51c693a24a23b50b',1,'PIDFF::set_target()']]], - ['setpidtarget_10',['setPIDTarget',['../classFlywheel.html#a5eeb847c6ef4736b1917bf32843c69aa',1,'Flywheel']]], - ['setposition_11',['setPosition',['../classCustomEncoder.html#a0edd50e16020ccad5eafa55e0f80288d',1,'CustomEncoder']]], - ['setrotation_12',['setRotation',['../classCustomEncoder.html#abcb003c4627f59faa25c748c597da7fd',1,'CustomEncoder']]], - ['smallest_5fangle_13',['smallest_angle',['../classOdometryBase.html#a70ec71e9fb2e14f0a191a6bac927d36b',1,'OdometryBase']]], - ['spin_5fmanual_14',['spin_manual',['../classFlywheel.html#a291e067bcc495a9d3da16a5832d78484',1,'Flywheel']]], - ['spin_5fraw_15',['spin_raw',['../classFlywheel.html#a5f4afa2ab8976acbf9fd47776a884dd3',1,'Flywheel']]], - ['spinrpm_16',['spinRPM',['../classFlywheel.html#aa72700130c0c8a08517ec1396fe9cc2b',1,'Flywheel']]], - ['spinrpmcommand_17',['SpinRPMCommand',['../classSpinRPMCommand.html#a9bfcf882448d6d4e0860c1a7de90f9ea',1,'SpinRPMCommand']]], - ['stop_18',['stop',['../classFlywheel.html#a6634f5126f0404e0edeeff1e0e14d05e',1,'Flywheel::stop()'],['../classTankDrive.html#af10e648e4de35fa72859fb96a9a80485',1,'TankDrive::stop()']]], - ['stopmotors_19',['stopMotors',['../classFlywheel.html#a78eaa40c9c069b8b4146c3ae34a21d4e',1,'Flywheel']]], - ['stopnontasks_20',['stopNonTasks',['../classFlywheel.html#a63c9c4d3646e4ed14f3b98ce3ab28684',1,'Flywheel']]] -]; diff --git a/documentation/html/search/mag.svg b/documentation/html/search/mag.svg deleted file mode 100644 index 9f46b30..0000000 --- a/documentation/html/search/mag.svg +++ /dev/null @@ -1,37 +0,0 @@ - - - - - - image/svg+xml - - - - - - - - - diff --git a/documentation/html/search/mag_d.svg b/documentation/html/search/mag_d.svg deleted file mode 100644 index b9a814c..0000000 --- a/documentation/html/search/mag_d.svg +++ /dev/null @@ -1,37 +0,0 @@ - - - - - - image/svg+xml - - - - - - - - - diff --git a/documentation/html/search/mag_sel.svg b/documentation/html/search/mag_sel.svg deleted file mode 100644 index 03626f6..0000000 --- a/documentation/html/search/mag_sel.svg +++ /dev/null @@ -1,74 +0,0 @@ - - - - - - - - image/svg+xml - - - - - - - - - - - diff --git a/documentation/html/search/mag_seld.svg b/documentation/html/search/mag_seld.svg deleted file mode 100644 index 6e720dc..0000000 --- a/documentation/html/search/mag_seld.svg +++ /dev/null @@ -1,74 +0,0 @@ - - - - - - - - image/svg+xml - - - - - - - - - - - diff --git a/documentation/html/search/pages_0.js b/documentation/html/search/pages_0.js deleted file mode 100644 index 1c7152d..0000000 --- a/documentation/html/search/pages_0.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['core_0',['Core',['../md_README.html',1,'']]] -]; diff --git a/documentation/html/search/search.css b/documentation/html/search/search.css deleted file mode 100644 index 19f76f9..0000000 --- a/documentation/html/search/search.css +++ /dev/null @@ -1,291 +0,0 @@ -/*---------------- Search Box positioning */ - -#main-menu > li:last-child { - /* This
  • object is the parent of the search bar */ - display: flex; - justify-content: center; - align-items: center; - height: 36px; - margin-right: 1em; -} - -/*---------------- Search box styling */ - -.SRPage * { - font-weight: normal; - line-height: normal; -} - -dark-mode-toggle { - margin-left: 5px; - display: flex; - float: right; -} - -#MSearchBox { - display: inline-block; - white-space : nowrap; - background: var(--search-background-color); - border-radius: 0.65em; - box-shadow: var(--search-box-shadow); - z-index: 102; -} - -#MSearchBox .left { - display: inline-block; - vertical-align: middle; - height: 1.4em; -} - -#MSearchSelect { - display: inline-block; - vertical-align: middle; - width: 20px; - height: 19px; - background-image: var(--search-magnification-select-image); - margin: 0 0 0 0.3em; - padding: 0; -} - -#MSearchSelectExt { - display: inline-block; - vertical-align: middle; - width: 10px; - height: 19px; - background-image: var(--search-magnification-image); - margin: 0 0 0 0.5em; - padding: 0; -} - - -#MSearchField { - display: inline-block; - vertical-align: middle; - width: 7.5em; - height: 19px; - margin: 0 0.15em; - padding: 0; - line-height: 1em; - border:none; - color: var(--search-foreground-color); - outline: none; - font-family: var(--font-family-search); - -webkit-border-radius: 0px; - border-radius: 0px; - background: none; -} - -@media(hover: none) { - /* to avoid zooming on iOS */ - #MSearchField { - font-size: 16px; - } -} - -#MSearchBox .right { - display: inline-block; - vertical-align: middle; - width: 1.4em; - height: 1.4em; -} - -#MSearchClose { - display: none; - font-size: inherit; - background : none; - border: none; - margin: 0; - padding: 0; - outline: none; - -} - -#MSearchCloseImg { - padding: 0.3em; - margin: 0; -} - -.MSearchBoxActive #MSearchField { - color: var(--search-active-color); -} - - - -/*---------------- Search filter selection */ - -#MSearchSelectWindow { - display: none; - position: absolute; - left: 0; top: 0; - border: 1px solid var(--search-filter-border-color); - background-color: var(--search-filter-background-color); - z-index: 10001; - padding-top: 4px; - padding-bottom: 4px; - -moz-border-radius: 4px; - -webkit-border-top-left-radius: 4px; - -webkit-border-top-right-radius: 4px; - -webkit-border-bottom-left-radius: 4px; - -webkit-border-bottom-right-radius: 4px; - -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); -} - -.SelectItem { - font: 8pt var(--font-family-search); - padding-left: 2px; - padding-right: 12px; - border: 0px; -} - -span.SelectionMark { - margin-right: 4px; - font-family: var(--font-family-monospace); - outline-style: none; - text-decoration: none; -} - -a.SelectItem { - display: block; - outline-style: none; - color: var(--search-filter-foreground-color); - text-decoration: none; - padding-left: 6px; - padding-right: 12px; -} - -a.SelectItem:focus, -a.SelectItem:active { - color: var(--search-filter-foreground-color); - outline-style: none; - text-decoration: none; -} - -a.SelectItem:hover { - color: var(--search-filter-highlight-text-color); - background-color: var(--search-filter-highlight-bg-color); - outline-style: none; - text-decoration: none; - cursor: pointer; - display: block; -} - -/*---------------- Search results window */ - -iframe#MSearchResults { - /*width: 60ex;*/ - height: 15em; -} - -#MSearchResultsWindow { - display: none; - position: absolute; - left: 0; top: 0; - border: 1px solid var(--search-results-border-color); - background-color: var(--search-results-background-color); - z-index:10000; - width: 300px; - height: 400px; - overflow: auto; -} - -/* ----------------------------------- */ - - -#SRIndex { - clear:both; -} - -.SREntry { - font-size: 10pt; - padding-left: 1ex; -} - -.SRPage .SREntry { - font-size: 8pt; - padding: 1px 5px; -} - -div.SRPage { - margin: 5px 2px; - background-color: var(--search-results-background-color); -} - -.SRChildren { - padding-left: 3ex; padding-bottom: .5em -} - -.SRPage .SRChildren { - display: none; -} - -.SRSymbol { - font-weight: bold; - color: var(--search-results-foreground-color); - font-family: var(--font-family-search); - text-decoration: none; - outline: none; -} - -a.SRScope { - display: block; - color: var(--search-results-foreground-color); - font-family: var(--font-family-search); - font-size: 8pt; - text-decoration: none; - outline: none; -} - -a.SRSymbol:focus, a.SRSymbol:active, -a.SRScope:focus, a.SRScope:active { - text-decoration: underline; -} - -span.SRScope { - padding-left: 4px; - font-family: var(--font-family-search); -} - -.SRPage .SRStatus { - padding: 2px 5px; - font-size: 8pt; - font-style: italic; - font-family: var(--font-family-search); -} - -.SRResult { - display: none; -} - -div.searchresults { - margin-left: 10px; - margin-right: 10px; -} - -/*---------------- External search page results */ - -.pages b { - color: white; - padding: 5px 5px 3px 5px; - background-image: var(--nav-gradient-active-image-parent); - background-repeat: repeat-x; - text-shadow: 0 1px 1px #000000; -} - -.pages { - line-height: 17px; - margin-left: 4px; - text-decoration: none; -} - -.hl { - font-weight: bold; -} - -#searchresults { - margin-bottom: 20px; -} - -.searchpages { - margin-top: 10px; -} - diff --git a/documentation/html/search/search.js b/documentation/html/search/search.js deleted file mode 100644 index e103a26..0000000 --- a/documentation/html/search/search.js +++ /dev/null @@ -1,816 +0,0 @@ -/* - @licstart The following is the entire license notice for the JavaScript code in this file. - - The MIT License (MIT) - - Copyright (C) 1997-2020 by Dimitri van Heesch - - Permission is hereby granted, free of charge, to any person obtaining a copy of this software - and associated documentation files (the "Software"), to deal in the Software without restriction, - including without limitation the rights to use, copy, modify, merge, publish, distribute, - sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is - furnished to do so, subject to the following conditions: - - The above copyright notice and this permission notice shall be included in all copies or - substantial portions of the Software. - - THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING - BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, - DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - - @licend The above is the entire license notice for the JavaScript code in this file - */ -function convertToId(search) -{ - var result = ''; - for (i=0;i do a search - { - this.Search(); - } - } - - this.OnSearchSelectKey = function(evt) - { - var e = (evt) ? evt : window.event; // for IE - if (e.keyCode==40 && this.searchIndex0) // Up - { - this.searchIndex--; - this.OnSelectItem(this.searchIndex); - } - else if (e.keyCode==13 || e.keyCode==27) - { - this.OnSelectItem(this.searchIndex); - this.CloseSelectionWindow(); - this.DOMSearchField().focus(); - } - return false; - } - - // --------- Actions - - // Closes the results window. - this.CloseResultsWindow = function() - { - this.DOMPopupSearchResultsWindow().style.display = 'none'; - this.DOMSearchClose().style.display = 'none'; - this.Activate(false); - } - - this.CloseSelectionWindow = function() - { - this.DOMSearchSelectWindow().style.display = 'none'; - } - - // Performs a search. - this.Search = function() - { - this.keyTimeout = 0; - - // strip leading whitespace - var searchValue = this.DOMSearchField().value.replace(/^ +/, ""); - - var code = searchValue.toLowerCase().charCodeAt(0); - var idxChar = searchValue.substr(0, 1).toLowerCase(); - if ( 0xD800 <= code && code <= 0xDBFF && searchValue > 1) // surrogate pair - { - idxChar = searchValue.substr(0, 2); - } - - var jsFile; - - var idx = indexSectionsWithContent[this.searchIndex].indexOf(idxChar); - if (idx!=-1) - { - var hexCode=idx.toString(16); - jsFile = this.resultsPath + indexSectionNames[this.searchIndex] + '_' + hexCode + '.js'; - } - - var loadJS = function(url, impl, loc){ - var scriptTag = document.createElement('script'); - scriptTag.src = url; - scriptTag.onload = impl; - scriptTag.onreadystatechange = impl; - loc.appendChild(scriptTag); - } - - var domPopupSearchResultsWindow = this.DOMPopupSearchResultsWindow(); - var domSearchBox = this.DOMSearchBox(); - var domPopupSearchResults = this.DOMPopupSearchResults(); - var domSearchClose = this.DOMSearchClose(); - var resultsPath = this.resultsPath; - - var handleResults = function() { - document.getElementById("Loading").style.display="none"; - if (typeof searchData !== 'undefined') { - createResults(resultsPath); - document.getElementById("NoMatches").style.display="none"; - } - - searchResults.Search(searchValue); - - if (domPopupSearchResultsWindow.style.display!='block') - { - domSearchClose.style.display = 'inline-block'; - var left = getXPos(domSearchBox) + 150; - var top = getYPos(domSearchBox) + 20; - domPopupSearchResultsWindow.style.display = 'block'; - left -= domPopupSearchResults.offsetWidth; - var maxWidth = document.body.clientWidth; - var maxHeight = document.body.clientHeight; - var width = 300; - if (left<10) left=10; - if (width+left+8>maxWidth) width=maxWidth-left-8; - var height = 400; - if (height+top+8>maxHeight) height=maxHeight-top-8; - domPopupSearchResultsWindow.style.top = top + 'px'; - domPopupSearchResultsWindow.style.left = left + 'px'; - domPopupSearchResultsWindow.style.width = width + 'px'; - domPopupSearchResultsWindow.style.height = height + 'px'; - } - } - - if (jsFile) { - loadJS(jsFile, handleResults, this.DOMPopupSearchResultsWindow()); - } else { - handleResults(); - } - - this.lastSearchValue = searchValue; - } - - // -------- Activation Functions - - // Activates or deactivates the search panel, resetting things to - // their default values if necessary. - this.Activate = function(isActive) - { - if (isActive || // open it - this.DOMPopupSearchResultsWindow().style.display == 'block' - ) - { - this.DOMSearchBox().className = 'MSearchBoxActive'; - this.searchActive = true; - } - else if (!isActive) // directly remove the panel - { - this.DOMSearchBox().className = 'MSearchBoxInactive'; - this.searchActive = false; - this.lastSearchValue = '' - this.lastResultsPage = ''; - this.DOMSearchField().value = ''; - } - } -} - -// ----------------------------------------------------------------------- - -// The class that handles everything on the search results page. -function SearchResults(name) -{ - // The number of matches from the last run of . - this.lastMatchCount = 0; - this.lastKey = 0; - this.repeatOn = false; - - // Toggles the visibility of the passed element ID. - this.FindChildElement = function(id) - { - var parentElement = document.getElementById(id); - var element = parentElement.firstChild; - - while (element && element!=parentElement) - { - if (element.nodeName.toLowerCase() == 'div' && element.className == 'SRChildren') - { - return element; - } - - if (element.nodeName.toLowerCase() == 'div' && element.hasChildNodes()) - { - element = element.firstChild; - } - else if (element.nextSibling) - { - element = element.nextSibling; - } - else - { - do - { - element = element.parentNode; - } - while (element && element!=parentElement && !element.nextSibling); - - if (element && element!=parentElement) - { - element = element.nextSibling; - } - } - } - } - - this.Toggle = function(id) - { - var element = this.FindChildElement(id); - if (element) - { - if (element.style.display == 'block') - { - element.style.display = 'none'; - } - else - { - element.style.display = 'block'; - } - } - } - - // Searches for the passed string. If there is no parameter, - // it takes it from the URL query. - // - // Always returns true, since other documents may try to call it - // and that may or may not be possible. - this.Search = function(search) - { - if (!search) // get search word from URL - { - search = window.location.search; - search = search.substring(1); // Remove the leading '?' - search = unescape(search); - } - - search = search.replace(/^ +/, ""); // strip leading spaces - search = search.replace(/ +$/, ""); // strip trailing spaces - search = search.toLowerCase(); - search = convertToId(search); - - var resultRows = document.getElementsByTagName("div"); - var matches = 0; - - var i = 0; - while (i < resultRows.length) - { - var row = resultRows.item(i); - if (row.className == "SRResult") - { - var rowMatchName = row.id.toLowerCase(); - rowMatchName = rowMatchName.replace(/^sr\d*_/, ''); // strip 'sr123_' - - if (search.length<=rowMatchName.length && - rowMatchName.substr(0, search.length)==search) - { - row.style.display = 'block'; - matches++; - } - else - { - row.style.display = 'none'; - } - } - i++; - } - document.getElementById("Searching").style.display='none'; - if (matches == 0) // no results - { - document.getElementById("NoMatches").style.display='block'; - } - else // at least one result - { - document.getElementById("NoMatches").style.display='none'; - } - this.lastMatchCount = matches; - return true; - } - - // return the first item with index index or higher that is visible - this.NavNext = function(index) - { - var focusItem; - while (1) - { - var focusName = 'Item'+index; - focusItem = document.getElementById(focusName); - if (focusItem && focusItem.parentNode.parentNode.style.display=='block') - { - break; - } - else if (!focusItem) // last element - { - break; - } - focusItem=null; - index++; - } - return focusItem; - } - - this.NavPrev = function(index) - { - var focusItem; - while (1) - { - var focusName = 'Item'+index; - focusItem = document.getElementById(focusName); - if (focusItem && focusItem.parentNode.parentNode.style.display=='block') - { - break; - } - else if (!focusItem) // last element - { - break; - } - focusItem=null; - index--; - } - return focusItem; - } - - this.ProcessKeys = function(e) - { - if (e.type == "keydown") - { - this.repeatOn = false; - this.lastKey = e.keyCode; - } - else if (e.type == "keypress") - { - if (!this.repeatOn) - { - if (this.lastKey) this.repeatOn = true; - return false; // ignore first keypress after keydown - } - } - else if (e.type == "keyup") - { - this.lastKey = 0; - this.repeatOn = false; - } - return this.lastKey!=0; - } - - this.Nav = function(evt,itemIndex) - { - var e = (evt) ? evt : window.event; // for IE - if (e.keyCode==13) return true; - if (!this.ProcessKeys(e)) return false; - - if (this.lastKey==38) // Up - { - var newIndex = itemIndex-1; - var focusItem = this.NavPrev(newIndex); - if (focusItem) - { - var child = this.FindChildElement(focusItem.parentNode.parentNode.id); - if (child && child.style.display == 'block') // children visible - { - var n=0; - var tmpElem; - while (1) // search for last child - { - tmpElem = document.getElementById('Item'+newIndex+'_c'+n); - if (tmpElem) - { - focusItem = tmpElem; - } - else // found it! - { - break; - } - n++; - } - } - } - if (focusItem) - { - focusItem.focus(); - } - else // return focus to search field - { - document.getElementById("MSearchField").focus(); - } - } - else if (this.lastKey==40) // Down - { - var newIndex = itemIndex+1; - var focusItem; - var item = document.getElementById('Item'+itemIndex); - var elem = this.FindChildElement(item.parentNode.parentNode.id); - if (elem && elem.style.display == 'block') // children visible - { - focusItem = document.getElementById('Item'+itemIndex+'_c0'); - } - if (!focusItem) focusItem = this.NavNext(newIndex); - if (focusItem) focusItem.focus(); - } - else if (this.lastKey==39) // Right - { - var item = document.getElementById('Item'+itemIndex); - var elem = this.FindChildElement(item.parentNode.parentNode.id); - if (elem) elem.style.display = 'block'; - } - else if (this.lastKey==37) // Left - { - var item = document.getElementById('Item'+itemIndex); - var elem = this.FindChildElement(item.parentNode.parentNode.id); - if (elem) elem.style.display = 'none'; - } - else if (this.lastKey==27) // Escape - { - searchBox.CloseResultsWindow(); - document.getElementById("MSearchField").focus(); - } - else if (this.lastKey==13) // Enter - { - return true; - } - return false; - } - - this.NavChild = function(evt,itemIndex,childIndex) - { - var e = (evt) ? evt : window.event; // for IE - if (e.keyCode==13) return true; - if (!this.ProcessKeys(e)) return false; - - if (this.lastKey==38) // Up - { - if (childIndex>0) - { - var newIndex = childIndex-1; - document.getElementById('Item'+itemIndex+'_c'+newIndex).focus(); - } - else // already at first child, jump to parent - { - document.getElementById('Item'+itemIndex).focus(); - } - } - else if (this.lastKey==40) // Down - { - var newIndex = childIndex+1; - var elem = document.getElementById('Item'+itemIndex+'_c'+newIndex); - if (!elem) // last child, jump to parent next parent - { - elem = this.NavNext(itemIndex+1); - } - if (elem) - { - elem.focus(); - } - } - else if (this.lastKey==27) // Escape - { - searchBox.CloseResultsWindow(); - document.getElementById("MSearchField").focus(); - } - else if (this.lastKey==13) // Enter - { - return true; - } - return false; - } -} - -function setKeyActions(elem,action) -{ - elem.setAttribute('onkeydown',action); - elem.setAttribute('onkeypress',action); - elem.setAttribute('onkeyup',action); -} - -function setClassAttr(elem,attr) -{ - elem.setAttribute('class',attr); - elem.setAttribute('className',attr); -} - -function createResults(resultsPath) -{ - var results = document.getElementById("SRResults"); - results.innerHTML = ''; - for (var e=0; e-{AmhX=Jf(#6djGiuzAr*{o?=JLmPLyc> z_*`QK&+BH@jWrYJ7>r6%keRM@)Qyv8R=enp0jiI>aWlGyB58O zFVR20d+y`K7vDw(hJF3;>dD*3-?v=<8M)@x|EEGLnJsniYK!2U1 Y!`|5biEc?d1`HDhPgg&ebxsLQ02F6;9RL6T diff --git a/documentation/html/splitbard.png b/documentation/html/splitbard.png deleted file mode 100644 index 8367416d757fd7b6dc4272b6432dc75a75abd068..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 282 zcmeAS@N?(olHy`uVBq!ia0vp^Yzz!63>-{AmhX=Jf@VhhFKy35^fiT zT~&lUj3=cDh^%3HDY9k5CEku}PHXNoNC(_$U3XPb&Q*ME25pT;2(*BOgAf<+R$lzakPG`kF31()Fx{L5Wrac|GQzjeE= zueY1`Ze{#x<8=S|`~MgGetGce)#vN&|J{Cd^tS%;tBYTo?+^d68<#n_Y_xx`J||4O V@QB{^CqU0Kc)I$ztaD0e0svEzbJzd? diff --git a/documentation/html/structAutoChooser_1_1entry__t-members.html b/documentation/html/structAutoChooser_1_1entry__t-members.html deleted file mode 100644 index 29aefb8..0000000 --- a/documentation/html/structAutoChooser_1_1entry__t-members.html +++ /dev/null @@ -1,93 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    AutoChooser::entry_t Member List
    -
    -
    - -

    This is the complete list of members for AutoChooser::entry_t, including all inherited members.

    - - - - - - -
    heightAutoChooser::entry_t
    nameAutoChooser::entry_t
    widthAutoChooser::entry_t
    xAutoChooser::entry_t
    yAutoChooser::entry_t
    - - - - diff --git a/documentation/html/structAutoChooser_1_1entry__t.html b/documentation/html/structAutoChooser_1_1entry__t.html deleted file mode 100644 index 9ea28fd..0000000 --- a/documentation/html/structAutoChooser_1_1entry__t.html +++ /dev/null @@ -1,185 +0,0 @@ - - - - - - - -RIT VEXU Core API: AutoChooser::entry_t Struct Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    - -
    AutoChooser::entry_t Struct Reference
    -
    -
    - -

    #include <auto_chooser.h>

    - - - - - - - - - - - - -

    -Public Attributes

    int x
     
    int y
     
    int width
     
    int height
     
    std::string name
     
    -

    Detailed Description

    -

    entry_t is a datatype used to store information that the chooser knows about an auto selection button

    -

    Member Data Documentation

    - -

    ◆ height

    - -
    -
    - - - - -
    int AutoChooser::entry_t::height
    -
    -

    height of the block

    - -
    -
    - -

    ◆ name

    - -
    -
    - - - - -
    std::string AutoChooser::entry_t::name
    -
    -

    name of the auto repretsented by the block

    - -
    -
    - -

    ◆ width

    - -
    -
    - - - - -
    int AutoChooser::entry_t::width
    -
    -

    width of the block

    - -
    -
    - -

    ◆ x

    - -
    -
    - - - - -
    int AutoChooser::entry_t::x
    -
    -

    screen x position of the block

    - -
    -
    - -

    ◆ y

    - -
    -
    - - - - -
    int AutoChooser::entry_t::y
    -
    -

    screen y position of the block

    - -
    -
    -
    The documentation for this struct was generated from the following file: -
    - - - - diff --git a/documentation/html/structFeedForward_1_1ff__config__t-members.html b/documentation/html/structFeedForward_1_1ff__config__t-members.html deleted file mode 100644 index 55707d9..0000000 --- a/documentation/html/structFeedForward_1_1ff__config__t-members.html +++ /dev/null @@ -1,92 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    FeedForward::ff_config_t Member List
    -
    -
    - -

    This is the complete list of members for FeedForward::ff_config_t, including all inherited members.

    - - - - - -
    kAFeedForward::ff_config_t
    kGFeedForward::ff_config_t
    kSFeedForward::ff_config_t
    kVFeedForward::ff_config_t
    - - - - diff --git a/documentation/html/structFeedForward_1_1ff__config__t.html b/documentation/html/structFeedForward_1_1ff__config__t.html deleted file mode 100644 index 383a6fa..0000000 --- a/documentation/html/structFeedForward_1_1ff__config__t.html +++ /dev/null @@ -1,172 +0,0 @@ - - - - - - - -RIT VEXU Core API: FeedForward::ff_config_t Struct Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    - -
    FeedForward::ff_config_t Struct Reference
    -
    -
    - -

    #include <feedforward.h>

    - - - - - - - - - - -

    -Public Attributes

    double kS
     
    double kV
     
    double kA
     
    double kG
     
    -

    Detailed Description

    -

    ff_config_t holds the parameters to make the theoretical model of a real world system equation is of the form kS if the system is not stopped, 0 otherwise

      -
    • kV * desired velocity
    • -
    • kA * desired acceleration
    • -
    • kG
    • -
    -

    Member Data Documentation

    - -

    ◆ kA

    - -
    -
    - - - - -
    double FeedForward::ff_config_t::kA
    -
    -

    kA - Acceleration coefficient: the power required to change the mechanism's speed. Multiplied by the requested acceleration.

    - -
    -
    - -

    ◆ kG

    - -
    -
    - - - - -
    double FeedForward::ff_config_t::kG
    -
    -

    kG - Gravity coefficient: only needed for lifts. The power required to overcome gravity and stay at steady state.

    - -
    -
    - -

    ◆ kS

    - -
    -
    - - - - -
    double FeedForward::ff_config_t::kS
    -
    -

    Coefficient to overcome static friction: the point at which the motor starts to move.

    - -
    -
    - -

    ◆ kV

    - -
    -
    - - - - -
    double FeedForward::ff_config_t::kV
    -
    -

    Veclocity coefficient: the power required to keep the mechanism in motion. Multiplied by the requested velocity.

    - -
    -
    -
    The documentation for this struct was generated from the following file: -
    - - - - diff --git a/documentation/html/structLift_1_1lift__cfg__t-members.html b/documentation/html/structLift_1_1lift__cfg__t-members.html deleted file mode 100644 index 5e638c5..0000000 --- a/documentation/html/structLift_1_1lift__cfg__t-members.html +++ /dev/null @@ -1,93 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    Lift< T >::lift_cfg_t Member List
    -
    -
    - -

    This is the complete list of members for Lift< T >::lift_cfg_t, including all inherited members.

    - - - - - - -
    down_speed (defined in Lift< T >::lift_cfg_t)Lift< T >::lift_cfg_t
    lift_pid_cfg (defined in Lift< T >::lift_cfg_t)Lift< T >::lift_cfg_t
    softstop_down (defined in Lift< T >::lift_cfg_t)Lift< T >::lift_cfg_t
    softstop_up (defined in Lift< T >::lift_cfg_t)Lift< T >::lift_cfg_t
    up_speed (defined in Lift< T >::lift_cfg_t)Lift< T >::lift_cfg_t
    - - - - diff --git a/documentation/html/structLift_1_1lift__cfg__t.html b/documentation/html/structLift_1_1lift__cfg__t.html deleted file mode 100644 index 8be1571..0000000 --- a/documentation/html/structLift_1_1lift__cfg__t.html +++ /dev/null @@ -1,118 +0,0 @@ - - - - - - - -RIT VEXU Core API: Lift< T >::lift_cfg_t Struct Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    - -
    Lift< T >::lift_cfg_t Struct Reference
    -
    -
    - -

    #include <lift.h>

    - - - - - - - - - - - - -

    -Public Attributes

    -double up_speed
     
    -double down_speed
     
    -double softstop_up
     
    -double softstop_down
     
    -PID::pid_config_t lift_pid_cfg
     
    -

    Detailed Description

    -
    template<typename T>
    -struct Lift< T >::lift_cfg_t

    lift_cfg_t holds the physical parameter specifications of a lify system. includes:

      -
    • maximum speeds for the system
    • -
    • softstops to stop the lift from hitting the hard stops too hard
    • -
    -

    The documentation for this struct was generated from the following file: -
    - - - - diff --git a/documentation/html/structMecanumDrive_1_1mecanumdrive__config__t-members.html b/documentation/html/structMecanumDrive_1_1mecanumdrive__config__t-members.html deleted file mode 100644 index c9ca8e9..0000000 --- a/documentation/html/structMecanumDrive_1_1mecanumdrive__config__t-members.html +++ /dev/null @@ -1,94 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    MecanumDrive::mecanumdrive_config_t Member List
    -
    - - - - - diff --git a/documentation/html/structMecanumDrive_1_1mecanumdrive__config__t.html b/documentation/html/structMecanumDrive_1_1mecanumdrive__config__t.html deleted file mode 100644 index f06243a..0000000 --- a/documentation/html/structMecanumDrive_1_1mecanumdrive__config__t.html +++ /dev/null @@ -1,117 +0,0 @@ - - - - - - - -RIT VEXU Core API: MecanumDrive::mecanumdrive_config_t Struct Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    - -
    MecanumDrive::mecanumdrive_config_t Struct Reference
    -
    -
    - -

    #include <mecanum_drive.h>

    - - - - - - - - - - - - - - -

    -Public Attributes

    -PID::pid_config_t drive_pid_conf
     
    -PID::pid_config_t drive_gyro_pid_conf
     
    -PID::pid_config_t turn_pid_conf
     
    -double drive_wheel_diam
     
    -double lateral_wheel_diam
     
    -double wheelbase_width
     
    -

    Detailed Description

    -

    Configure the Mecanum drive PID tunings and robot configurations

    -

    The documentation for this struct was generated from the following file: -
    - - - - diff --git a/documentation/html/structMotionController_1_1m__profile__cfg__t-members.html b/documentation/html/structMotionController_1_1m__profile__cfg__t-members.html deleted file mode 100644 index 25c6351..0000000 --- a/documentation/html/structMotionController_1_1m__profile__cfg__t-members.html +++ /dev/null @@ -1,92 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    MotionController::m_profile_cfg_t Member List
    -
    - - - - - diff --git a/documentation/html/structMotionController_1_1m__profile__cfg__t.html b/documentation/html/structMotionController_1_1m__profile__cfg__t.html deleted file mode 100644 index 46a92f1..0000000 --- a/documentation/html/structMotionController_1_1m__profile__cfg__t.html +++ /dev/null @@ -1,115 +0,0 @@ - - - - - - - -RIT VEXU Core API: MotionController::m_profile_cfg_t Struct Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    - -
    MotionController::m_profile_cfg_t Struct Reference
    -
    -
    - -

    #include <motion_controller.h>

    - - - - - - - - - - - - - - -

    -Public Attributes

    -double max_v
     the maximum velocity the robot can drive
     
    -double accel
     the most acceleration the robot can do
     
    -PID::pid_config_t pid_cfg
     configuration parameters for the internal PID controller
     
    -FeedForward::ff_config_t ff_cfg
     configuration parameters for the internal
     
    -

    Detailed Description

    -

    m_profile_config holds all data the motion controller uses to plan paths When motion pofile is given a target to drive to, max_v and accel are used to make the trapezoid profile instructing the controller how to drive pid_cfg, ff_cfg are used to find the motor outputs necessary to execute this path

    -

    The documentation for this struct was generated from the following file: -
    - - - - diff --git a/documentation/html/structOdometry3Wheel_1_1odometry3wheel__cfg__t-members.html b/documentation/html/structOdometry3Wheel_1_1odometry3wheel__cfg__t-members.html deleted file mode 100644 index d5cf655..0000000 --- a/documentation/html/structOdometry3Wheel_1_1odometry3wheel__cfg__t-members.html +++ /dev/null @@ -1,91 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    Odometry3Wheel::odometry3wheel_cfg_t Member List
    -
    - - - - - diff --git a/documentation/html/structOdometry3Wheel_1_1odometry3wheel__cfg__t.html b/documentation/html/structOdometry3Wheel_1_1odometry3wheel__cfg__t.html deleted file mode 100644 index fce4bb3..0000000 --- a/documentation/html/structOdometry3Wheel_1_1odometry3wheel__cfg__t.html +++ /dev/null @@ -1,151 +0,0 @@ - - - - - - - -RIT VEXU Core API: Odometry3Wheel::odometry3wheel_cfg_t Struct Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    - -
    Odometry3Wheel::odometry3wheel_cfg_t Struct Reference
    -
    -
    - -

    #include <odometry_3wheel.h>

    - - - - - - - - -

    -Public Attributes

    double wheelbase_dist
     
    double off_axis_center_dist
     
    double wheel_diam
     
    -

    Detailed Description

    -

    odometry3wheel_cfg_t holds all the specifications for how to calculate position with 3 encoders See the core wiki for what exactly each of these parameters measures

    -

    Member Data Documentation

    - -

    ◆ off_axis_center_dist

    - -
    -
    - - - - -
    double Odometry3Wheel::odometry3wheel_cfg_t::off_axis_center_dist
    -
    -

    distance from the center of the robot to the center off axis wheel

    - -
    -
    - -

    ◆ wheel_diam

    - -
    -
    - - - - -
    double Odometry3Wheel::odometry3wheel_cfg_t::wheel_diam
    -
    -

    the diameter of the tracking wheel

    - -
    -
    - -

    ◆ wheelbase_dist

    - -
    -
    - - - - -
    double Odometry3Wheel::odometry3wheel_cfg_t::wheelbase_dist
    -
    -

    distance from the center of the left wheel to the center of the right wheel

    - -
    -
    -
    The documentation for this struct was generated from the following file: -
    - - - - diff --git a/documentation/html/structPID_1_1pid__config__t-members.html b/documentation/html/structPID_1_1pid__config__t-members.html deleted file mode 100644 index b47549d..0000000 --- a/documentation/html/structPID_1_1pid__config__t-members.html +++ /dev/null @@ -1,94 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    PID::pid_config_t Member List
    -
    - - - - - diff --git a/documentation/html/structPID_1_1pid__config__t.html b/documentation/html/structPID_1_1pid__config__t.html deleted file mode 100644 index b10b51a..0000000 --- a/documentation/html/structPID_1_1pid__config__t.html +++ /dev/null @@ -1,126 +0,0 @@ - - - - - - - -RIT VEXU Core API: PID::pid_config_t Struct Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    - -
    PID::pid_config_t Struct Reference
    -
    -
    - -

    #include <pid.h>

    - - - - - - - - - - - - - - - - - - - - -

    -Public Attributes

    -double p
     proportional coeffecient p * error()
     
    -double i
     integral coeffecient i * integral(error)
     
    -double d
     derivitave coeffecient d * derivative(error)
     
    -double deadband
     at what threshold are we close enough to be finished
     
    -double on_target_time
     the time in seconds that we have to be on target for to say we are officially at the target
     
    -ERROR_TYPE error_method
     Linear or angular. wheter to do error as a simple subtraction or to wrap.
     
    -

    Detailed Description

    -

    pid_config_t holds the configuration parameters for a pid controller In addtion to the constant of proportional, integral and derivative, these parameters include:

      -
    • deadband -
    • -
    • on_target_time - for how long do we have to be at the target to stop As well, pid_config_t holds an error type which determines whether errors should be calculated as if the sensor position is a measure of distance or an angle
    • -
    -

    The documentation for this struct was generated from the following file: -
    - - - - diff --git a/documentation/html/structPurePursuit_1_1hermite__point-members.html b/documentation/html/structPurePursuit_1_1hermite__point-members.html deleted file mode 100644 index 1c11649..0000000 --- a/documentation/html/structPurePursuit_1_1hermite__point-members.html +++ /dev/null @@ -1,94 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    PurePursuit::hermite_point Member List
    -
    - - - - - diff --git a/documentation/html/structPurePursuit_1_1hermite__point.html b/documentation/html/structPurePursuit_1_1hermite__point.html deleted file mode 100644 index 411c4ef..0000000 --- a/documentation/html/structPurePursuit_1_1hermite__point.html +++ /dev/null @@ -1,121 +0,0 @@ - - - - - - - -RIT VEXU Core API: PurePursuit::hermite_point Struct Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    - -
    PurePursuit::hermite_point Struct Reference
    -
    -
    - -

    #include <pure_pursuit.h>

    - - - - - - -

    -Public Member Functions

    -Vector2D::point_t getPoint ()
     
    -Vector2D getTangent ()
     
    - - - - - - - - - -

    -Public Attributes

    -double x
     
    -double y
     
    -double dir
     
    -double mag
     
    -

    Detailed Description

    -

    a position along the hermite path contains a position and orientation information that the robot would be at at this point

    -

    The documentation for this struct was generated from the following file: -
    - - - - diff --git a/documentation/html/structPurePursuit_1_1spline-members.html b/documentation/html/structPurePursuit_1_1spline-members.html deleted file mode 100644 index a58bcd5..0000000 --- a/documentation/html/structPurePursuit_1_1spline-members.html +++ /dev/null @@ -1,95 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    PurePursuit::spline Member List
    -
    -
    - -

    This is the complete list of members for PurePursuit::spline, including all inherited members.

    - - - - - - - - -
    a (defined in PurePursuit::spline)PurePursuit::spline
    b (defined in PurePursuit::spline)PurePursuit::spline
    c (defined in PurePursuit::spline)PurePursuit::spline
    d (defined in PurePursuit::spline)PurePursuit::spline
    getY(double x) (defined in PurePursuit::spline)PurePursuit::splineinline
    x_end (defined in PurePursuit::spline)PurePursuit::spline
    x_start (defined in PurePursuit::spline)PurePursuit::spline
    - - - - diff --git a/documentation/html/structPurePursuit_1_1spline.html b/documentation/html/structPurePursuit_1_1spline.html deleted file mode 100644 index b4ac19b..0000000 --- a/documentation/html/structPurePursuit_1_1spline.html +++ /dev/null @@ -1,124 +0,0 @@ - - - - - - - -RIT VEXU Core API: PurePursuit::spline Struct Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    - -
    PurePursuit::spline Struct Reference
    -
    -
    - -

    #include <pure_pursuit.h>

    - - - - -

    -Public Member Functions

    -double getY (double x)
     
    - - - - - - - - - - - - - -

    -Public Attributes

    -double a
     
    -double b
     
    -double c
     
    -double d
     
    -double x_start
     
    -double x_end
     
    -

    Detailed Description

    -

    Represents a piece of a cubic spline with s(x) = a(x-xi)^3 + b(x-xi)^2 + c(x-xi) + d The x_start and x_end shows where the equation is valid.

    -

    The documentation for this struct was generated from the following file: -
    - - - - diff --git a/documentation/html/structVector2D_1_1point__t-members.html b/documentation/html/structVector2D_1_1point__t-members.html deleted file mode 100644 index 6bdec25..0000000 --- a/documentation/html/structVector2D_1_1point__t-members.html +++ /dev/null @@ -1,93 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    Vector2D::point_t Member List
    -
    -
    - -

    This is the complete list of members for Vector2D::point_t, including all inherited members.

    - - - - - - -
    dist(const point_t other)Vector2D::point_tinline
    operator+(const point_t &other)Vector2D::point_tinline
    operator-(const point_t &other)Vector2D::point_tinline
    xVector2D::point_t
    yVector2D::point_t
    - - - - diff --git a/documentation/html/structVector2D_1_1point__t.html b/documentation/html/structVector2D_1_1point__t.html deleted file mode 100644 index 83ca1b1..0000000 --- a/documentation/html/structVector2D_1_1point__t.html +++ /dev/null @@ -1,217 +0,0 @@ - - - - - - - -RIT VEXU Core API: Vector2D::point_t Struct Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    - -
    Vector2D::point_t Struct Reference
    -
    -
    - -

    #include <vector2d.h>

    - - - - - - - - -

    -Public Member Functions

    double dist (const point_t other)
     
    point_t operator+ (const point_t &other)
     
    point_t operator- (const point_t &other)
     
    - - - - - - - -

    -Public Attributes

    -double x
     the x position in space
     
    -double y
     the y position in space
     
    -

    Detailed Description

    -

    Data structure representing an X,Y coordinate

    -

    Member Function Documentation

    - -

    ◆ dist()

    - -
    -
    - - - - - -
    - - - - - - - - -
    double Vector2D::point_t::dist (const point_t other)
    -
    -inline
    -
    -

    dist calculates the euclidian distance between this point and another point using the pythagorean theorem

    Parameters
    - - -
    otherthe point to measure the distance from
    -
    -
    -
    Returns
    the euclidian distance between this and other
    - -
    -
    - -

    ◆ operator+()

    - -
    -
    - - - - - -
    - - - - - - - - -
    point_t Vector2D::point_t::operator+ (const point_tother)
    -
    -inline
    -
    -

    Vector2D addition operation on points

    Parameters
    - - -
    otherthe point to add on to this
    -
    -
    -
    Returns
    this + other (this.x + other.x, this.y + other.y)
    - -
    -
    - -

    ◆ operator-()

    - -
    -
    - - - - - -
    - - - - - - - - -
    point_t Vector2D::point_t::operator- (const point_tother)
    -
    -inline
    -
    -

    Vector2D subtraction operation on points

    Parameters
    - - -
    otherthe point_t to subtract from this
    -
    -
    -
    Returns
    this - other (this.x - other.x, this.y - other.y)
    - -
    -
    -
    The documentation for this struct was generated from the following file: -
    - - - - diff --git a/documentation/html/structmotion__t-members.html b/documentation/html/structmotion__t-members.html deleted file mode 100644 index 73ce7f0..0000000 --- a/documentation/html/structmotion__t-members.html +++ /dev/null @@ -1,87 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    motion_t Member List
    -
    -
    - -

    This is the complete list of members for motion_t, including all inherited members.

    - - - - -
    accelmotion_t
    posmotion_t
    velmotion_t
    - - - - diff --git a/documentation/html/structmotion__t.html b/documentation/html/structmotion__t.html deleted file mode 100644 index d995439..0000000 --- a/documentation/html/structmotion__t.html +++ /dev/null @@ -1,107 +0,0 @@ - - - - - - - -RIT VEXU Core API: motion_t Struct Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    motion_t Struct Reference
    -
    -
    - -

    #include <trapezoid_profile.h>

    - - - - - - - - - - - -

    -Public Attributes

    -double pos
     1d position at this point in time
     
    -double vel
     1d velocity at this point in time
     
    -double accel
     1d acceleration at this point in time
     
    -

    Detailed Description

    -

    motion_t is a description of 1 dimensional motion at a point in time.

    -

    The documentation for this struct was generated from the following file: -
    - - - - diff --git a/documentation/html/structposition__t-members.html b/documentation/html/structposition__t-members.html deleted file mode 100644 index 70e5d9a..0000000 --- a/documentation/html/structposition__t-members.html +++ /dev/null @@ -1,87 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    position_t Member List
    -
    -
    - -

    This is the complete list of members for position_t, including all inherited members.

    - - - - -
    rotposition_t
    xposition_t
    yposition_t
    - - - - diff --git a/documentation/html/structposition__t.html b/documentation/html/structposition__t.html deleted file mode 100644 index 2bb5f2e..0000000 --- a/documentation/html/structposition__t.html +++ /dev/null @@ -1,107 +0,0 @@ - - - - - - - -RIT VEXU Core API: position_t Struct Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    position_t Struct Reference
    -
    -
    - -

    #include <odometry_base.h>

    - - - - - - - - - - - -

    -Public Attributes

    -double x
     x position in the world
     
    -double y
     y position in the world
     
    -double rot
     rotation in the world
     
    -

    Detailed Description

    -

    Describes a single position and rotation

    -

    The documentation for this struct was generated from the following file: -
    - - - - diff --git a/documentation/html/structrobot__specs__t-members.html b/documentation/html/structrobot__specs__t-members.html deleted file mode 100644 index ffedc78..0000000 --- a/documentation/html/structrobot__specs__t-members.html +++ /dev/null @@ -1,92 +0,0 @@ - - - - - - - -RIT VEXU Core API: Member List - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    -
    robot_specs_t Member List
    -
    - - - - - diff --git a/documentation/html/structrobot__specs__t.html b/documentation/html/structrobot__specs__t.html deleted file mode 100644 index 4014338..0000000 --- a/documentation/html/structrobot__specs__t.html +++ /dev/null @@ -1,127 +0,0 @@ - - - - - - - -RIT VEXU Core API: robot_specs_t Struct Reference - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    - -
    robot_specs_t Struct Reference
    -
    -
    - -

    #include <robot_specs.h>

    - - - - - - - - - - - - - - - - - - - - - - - - - - -

    -Public Attributes

    -double robot_radius
     if you were to draw a circle with this radius, the robot would be entirely contained within it
     
    -double odom_wheel_diam
     the diameter of the wheels used for
     
    -double odom_gear_ratio
     the ratio of the odometry wheel to the encoder reading odometry data
     
    -double dist_between_wheels
     the distance between centers of the central drive wheels
     
    -double drive_correction_cutoff
     the distance at which to stop trying to turn towards the target. If we are less than this value, we can continue driving forward to minimize our distance but will not try to spin around to point directly at the target
     
    -Feedbackdrive_feedback
     the default feedback for autonomous driving
     
    -Feedbackturn_feedback
     the defualt feedback for autonomous turning
     
    -PID::pid_config_t correction_pid
     the pid controller to keep the robot driving in as straight a line as possible
     
    -

    Detailed Description

    -

    Main robot characterization struct. This will be passed to all the major subsystems that require info about the robot. All distance measurements are in inches.

    -

    The documentation for this struct was generated from the following file: -
    - - - - diff --git a/documentation/html/sync_off.png b/documentation/html/sync_off.png deleted file mode 100644 index 3b443fc62892114406e3d399421b2a881b897acc..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 853 zcmV-b1FHOqP)oT|#XixUYy%lpuf3i8{fX!o zUyDD0jOrAiT^tq>fLSOOABs-#u{dV^F$b{L9&!2=9&RmV;;8s^x&UqB$PCj4FdKbh zoB1WTskPUPu05XzFbA}=KZ-GP1fPpAfSs>6AHb12UlR%-i&uOlTpFNS7{jm@mkU1V zh`nrXr~+^lsV-s1dkZOaI|kYyVj3WBpPCY{n~yd%u%e+d=f%`N0FItMPtdgBb@py; zq@v6NVArhyTC7)ULw-Jy8y42S1~4n(3LkrW8mW(F-4oXUP3E`e#g**YyqI7h-J2zK zK{m9##m4ri!7N>CqQqCcnI3hqo1I;Yh&QLNY4T`*ptiQGozK>FF$!$+84Z`xwmeMh zJ0WT+OH$WYFALEaGj2_l+#DC3t7_S`vHpSivNeFbP6+r50cO8iu)`7i%Z4BTPh@_m3Tk!nAm^)5Bqnr%Ov|Baunj#&RPtRuK& z4RGz|D5HNrW83-#ydk}tVKJrNmyYt-sTxLGlJY5nc&Re zU4SgHNPx8~Yxwr$bsju?4q&%T1874xxzq+_%?h8_ofw~(bld=o3iC)LUNR*BY%c0y zWd_jX{Y8`l%z+ol1$@Qa?Cy!(0CVIEeYpKZ`(9{z>3$CIe;pJDQk$m3p}$>xBm4lb zKo{4S)`wdU9Ba9jJbVJ0C=SOefZe%d$8=2r={nu<_^a3~>c#t_U6dye5)JrR(_a^E f@}b6j1K9lwFJq@>o)+Ry00000NkvXXu0mjfWa5j* diff --git a/documentation/html/sync_on.png b/documentation/html/sync_on.png deleted file mode 100644 index e08320fb64e6fa33b573005ed6d8fe294e19db76..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 845 zcmV-T1G4;yP)Y;xxyHF2B5Wzm| zOOGupOTn@c(JmBOl)e;XMNnZuiTJP>rM8<|Q`7I_))aP?*T)ow&n59{}X4$3Goat zgjs?*aasfbrokzG5cT4K=uG`E14xZl@z)F={P0Y^?$4t z>v!teRnNZym<6h{7sLyF1V0HsfEl+l6TrZpsfr1}luH~F7L}ktXu|*uVX^RG$L0`K zWs3j|0tIvVe(N%_?2{(iCPFGf#B6Hjy6o&}D$A%W%jfO8_W%ZO#-mh}EM$LMn7joJ z05dHr!5Y92g+31l<%i1(=L1a1pXX+OYnalY>31V4K}BjyRe3)9n#;-cCVRD_IG1fT zOKGeNY8q;TL@K{dj@D^scf&VCs*-Jb>8b>|`b*osv52-!A?BpbYtTQBns5EAU**$m zSnVSm(teh>tQi*S*A>#ySc=n;`BHz`DuG4&g4Kf8lLhca+zvZ7t7RflD6-i-mcK=M z!=^P$*u2)bkY5asG4gsss!Hn%u~>}kIW`vMs%lJLH+u*9<4PaV_c6U`KqWXQH%+Nu zTv41O(^ZVi@qhjQdG!fbZw&y+2o!iYymO^?ud3{P*HdoX83YV*Uu_HB=?U&W9%AU# z80}k1SS-CXTU7dcQlsm<^oYLxVSseqY6NO}dc`Nj?8vrhNuCdm@^{a3AQ_>6myOj+ z`1RsLUXF|dm|3k7s2jD(B{rzE>WI2scH8i1;=O5Cc9xB3^aJk%fQjqsu+kH#0=_5a z0nCE8@dbQa-|YIuUVvG0L_IwHMEhOj$Mj4Uq05 X8=0q~qBNan00000NkvXXu0mjfptF>5 diff --git a/documentation/html/tab_a.png b/documentation/html/tab_a.png deleted file mode 100644 index 3b725c41c5a527a3a3e40097077d0e206a681247..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 142 zcmeAS@N?(olHy`uVBq!ia0vp^j6kfy!2~3aiye;!QlXwMjv*C{Z|8b*H5dputLHD# z=<0|*y7z(Vor?d;H&?EG&cXR}?!j-Lm&u1OOI7AIF5&c)RFE;&p0MYK>*Kl@eiymD r@|NpwKX@^z+;{u_Z~trSBfrMKa%3`zocFjEXaR$#tDnm{r-UW|TZ1%4 diff --git a/documentation/html/tab_ad.png b/documentation/html/tab_ad.png deleted file mode 100644 index e34850acfc24be58da6d2fd1ccc6b29cc84fe34d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 135 zcmeAS@N?(olHy`uVBq!ia0vp^j6kfy!2~3aiye;!QhuH;jv*C{Z|5d*H3V=pKi{In zd2jxLclDRPylmD}^l7{QOtL{vUjO{-WqItb5sQp2h-99b8^^Scr-=2mblCdZuUm?4 jzOJvgvt3{(cjKLW5(A@0qPS@<&}0TrS3j3^P6y&q2{!U5bk+Tso_B!YCpDh>v z{CM*1U8YvQRyBUHt^Ju0W_sq-?;9@_4equ-bavTs=gk796zopr0EBT&m;e9( diff --git a/documentation/html/tab_s.png b/documentation/html/tab_s.png deleted file mode 100644 index ab478c95b67371d700a20869f7de1ddd73522d50..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 184 zcmeAS@N?(olHy`uVBq!ia0vp^j6kfy!2~3aiye;!QuUrLjv*C{Z|^p8HaRdjTwH7) zC?wLlL}}I{)n%R&r+1}IGmDnq;&J#%V6)9VsYhS`O^BVBQlxOUep0c$RENLq#g8A$ z)z7%K_bI&n@J+X_=x}fJoEKed-$<>=ZI-;YrdjIl`U`uzuDWSP?o#Dmo{%SgM#oan kX~E1%D-|#H#QbHoIja2U-MgvsK&LQxy85}Sb4q9e0Efg%P5=M^ diff --git a/documentation/html/tab_sd.png b/documentation/html/tab_sd.png deleted file mode 100644 index 757a565ced4730f85c833fb2547d8e199ae68f19..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 188 zcmeAS@N?(olHy`uVBq!ia0vp^j6kfy!2~3aiye;!Qq7(&jv*C{Z|_!fH5o7*c=%9% zcILh!EA=pAQKdx-Cdiev=v{eg{8Ht<{e8_NAN~b=)%W>-WDCE0PyDHGemi$BoXwcK z{>e9^za6*c1ilttWw&V+U;WCPlV9{LdC~Ey%_H(qj`xgfES(4Yz5jSTZfCt`4E$0YRsR*S^mTCR^;V&sxC8{l_Cp7w8-YPgg&ebxsLQ00$vXK>z>% diff --git a/documentation/html/tabs.css b/documentation/html/tabs.css deleted file mode 100644 index 71c8a47..0000000 --- a/documentation/html/tabs.css +++ /dev/null @@ -1 +0,0 @@ -.sm{position:relative;z-index:9999}.sm,.sm ul,.sm li{display:block;list-style:none;margin:0;padding:0;line-height:normal;direction:ltr;text-align:left;-webkit-tap-highlight-color:rgba(0,0,0,0)}.sm-rtl,.sm-rtl ul,.sm-rtl li{direction:rtl;text-align:right}.sm>li>h1,.sm>li>h2,.sm>li>h3,.sm>li>h4,.sm>li>h5,.sm>li>h6{margin:0;padding:0}.sm ul{display:none}.sm li,.sm a{position:relative}.sm a{display:block}.sm a.disabled{cursor:not-allowed}.sm:after{content:"\00a0";display:block;height:0;font:0/0 serif;clear:both;visibility:hidden;overflow:hidden}.sm,.sm *,.sm *:before,.sm *:after{-moz-box-sizing:border-box;-webkit-box-sizing:border-box;box-sizing:border-box}.main-menu-btn{position:relative;display:inline-block;width:36px;height:36px;text-indent:36px;margin-left:8px;white-space:nowrap;overflow:hidden;cursor:pointer;-webkit-tap-highlight-color:rgba(0,0,0,0)}.main-menu-btn-icon,.main-menu-btn-icon:before,.main-menu-btn-icon:after{position:absolute;top:50%;left:2px;height:2px;width:24px;background:var(--nav-menu-button-color);-webkit-transition:all .25s;transition:all .25s}.main-menu-btn-icon:before{content:'';top:-7px;left:0}.main-menu-btn-icon:after{content:'';top:7px;left:0}#main-menu-state:checked ~ .main-menu-btn .main-menu-btn-icon{height:0}#main-menu-state:checked ~ .main-menu-btn .main-menu-btn-icon:before{top:0;-webkit-transform:rotate(-45deg);transform:rotate(-45deg)}#main-menu-state:checked ~ .main-menu-btn .main-menu-btn-icon:after{top:0;-webkit-transform:rotate(45deg);transform:rotate(45deg)}#main-menu-state{position:absolute;width:1px;height:1px;margin:-1px;border:0;padding:0;overflow:hidden;clip:rect(1px,1px,1px,1px)}#main-menu-state:not(:checked) ~ #main-menu{display:none}#main-menu-state:checked ~ #main-menu{display:block}@media(min-width:768px){.main-menu-btn{position:absolute;top:-99999px}#main-menu-state:not(:checked) ~ #main-menu{display:block}}.sm-dox{background-image:var(--nav-gradient-image)}.sm-dox a,.sm-dox a:focus,.sm-dox a:hover,.sm-dox a:active{padding:0 12px;padding-right:43px;font-family:var(--font-family-nav);font-size:13px;font-weight:bold;line-height:36px;text-decoration:none;text-shadow:var(--nav-text-normal-shadow);color:var(--nav-text-normal-color);outline:0}.sm-dox a:hover{background-image:var(--nav-gradient-active-image);background-repeat:repeat-x;color:var(--nav-text-hover-color);text-shadow:var(--nav-text-hover-shadow)}.sm-dox a.current{color:#d23600}.sm-dox a.disabled{color:#bbb}.sm-dox a span.sub-arrow{position:absolute;top:50%;margin-top:-14px;left:auto;right:3px;width:28px;height:28px;overflow:hidden;font:bold 12px/28px monospace !important;text-align:center;text-shadow:none;background:var(--nav-menu-toggle-color);-moz-border-radius:5px;-webkit-border-radius:5px;border-radius:5px}.sm-dox a span.sub-arrow:before{display:block;content:'+'}.sm-dox a.highlighted span.sub-arrow:before{display:block;content:'-'}.sm-dox>li:first-child>a,.sm-dox>li:first-child>:not(ul) a{-moz-border-radius:5px 5px 0 0;-webkit-border-radius:5px;border-radius:5px 5px 0 0}.sm-dox>li:last-child>a,.sm-dox>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul{-moz-border-radius:0 0 5px 5px;-webkit-border-radius:0;border-radius:0 0 5px 5px}.sm-dox>li:last-child>a.highlighted,.sm-dox>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted{-moz-border-radius:0;-webkit-border-radius:0;border-radius:0}.sm-dox ul{background:var(--nav-menu-background-color)}.sm-dox ul a,.sm-dox ul a:focus,.sm-dox ul a:hover,.sm-dox ul a:active{font-size:12px;border-left:8px solid transparent;line-height:36px;text-shadow:none;background-color:var(--nav-menu-background-color);background-image:none}.sm-dox ul a:hover{background-image:var(--nav-gradient-active-image);background-repeat:repeat-x;color:var(--nav-text-hover-color);text-shadow:0 1px 1px black}.sm-dox ul ul a,.sm-dox ul ul a:hover,.sm-dox ul ul a:focus,.sm-dox ul ul a:active{border-left:16px solid transparent}.sm-dox ul ul ul a,.sm-dox ul ul ul a:hover,.sm-dox ul ul ul a:focus,.sm-dox ul ul ul a:active{border-left:24px solid transparent}.sm-dox ul ul ul ul a,.sm-dox ul ul ul ul a:hover,.sm-dox ul ul ul ul a:focus,.sm-dox ul ul ul ul a:active{border-left:32px solid transparent}.sm-dox ul ul ul ul ul a,.sm-dox ul ul ul ul ul a:hover,.sm-dox ul ul ul ul ul a:focus,.sm-dox ul ul ul ul ul a:active{border-left:40px solid transparent}@media(min-width:768px){.sm-dox ul{position:absolute;width:12em}.sm-dox li{float:left}.sm-dox.sm-rtl li{float:right}.sm-dox ul li,.sm-dox.sm-rtl ul li,.sm-dox.sm-vertical li{float:none}.sm-dox a{white-space:nowrap}.sm-dox ul a,.sm-dox.sm-vertical a{white-space:normal}.sm-dox .sm-nowrap>li>a,.sm-dox .sm-nowrap>li>:not(ul) a{white-space:nowrap}.sm-dox{padding:0 10px;background-image:var(--nav-gradient-image);line-height:36px}.sm-dox a span.sub-arrow{top:50%;margin-top:-2px;right:12px;width:0;height:0;border-width:4px;border-style:solid dashed dashed dashed;border-color:var(--nav-text-normal-color) transparent transparent transparent;background:transparent;-moz-border-radius:0;-webkit-border-radius:0;border-radius:0}.sm-dox a,.sm-dox a:focus,.sm-dox a:active,.sm-dox a:hover,.sm-dox a.highlighted{padding:0 12px;background-image:var(--nav-separator-image);background-repeat:no-repeat;background-position:right;-moz-border-radius:0 !important;-webkit-border-radius:0;border-radius:0 !important}.sm-dox a:hover{background-image:var(--nav-gradient-active-image);background-repeat:repeat-x;color:var(--nav-text-hover-color);text-shadow:var(--nav-text-hover-shadow)}.sm-dox a:hover span.sub-arrow{border-color:var(--nav-text-hover-color) transparent transparent transparent}.sm-dox a.has-submenu{padding-right:24px}.sm-dox li{border-top:0}.sm-dox>li>ul:before,.sm-dox>li>ul:after{content:'';position:absolute;top:-18px;left:30px;width:0;height:0;overflow:hidden;border-width:9px;border-style:dashed dashed solid dashed;border-color:transparent transparent #bbb transparent}.sm-dox>li>ul:after{top:-16px;left:31px;border-width:8px;border-color:transparent transparent var(--nav-menu-background-color) transparent}.sm-dox ul{border:1px solid #bbb;padding:5px 0;background:var(--nav-menu-background-color);-moz-border-radius:5px !important;-webkit-border-radius:5px;border-radius:5px !important;-moz-box-shadow:0 5px 9px rgba(0,0,0,0.2);-webkit-box-shadow:0 5px 9px rgba(0,0,0,0.2);box-shadow:0 5px 9px rgba(0,0,0,0.2)}.sm-dox ul a span.sub-arrow{right:8px;top:50%;margin-top:-5px;border-width:5px;border-color:transparent transparent transparent var(--nav-menu-foreground-color);border-style:dashed dashed dashed solid}.sm-dox ul a,.sm-dox ul a:hover,.sm-dox ul a:focus,.sm-dox ul a:active,.sm-dox ul a.highlighted{color:var(--nav-menu-foreground-color);background-image:none;border:0 !important;color:var(--nav-menu-foreground-color);background-image:none}.sm-dox ul a:hover{background-image:var(--nav-gradient-active-image);background-repeat:repeat-x;color:var(--nav-text-hover-color);text-shadow:var(--nav-text-hover-shadow)}.sm-dox ul a:hover span.sub-arrow{border-color:transparent transparent transparent var(--nav-text-hover-color)}.sm-dox span.scroll-up,.sm-dox span.scroll-down{position:absolute;display:none;visibility:hidden;overflow:hidden;background:var(--nav-menu-background-color);height:36px}.sm-dox span.scroll-up:hover,.sm-dox span.scroll-down:hover{background:#eee}.sm-dox span.scroll-up:hover span.scroll-up-arrow,.sm-dox span.scroll-up:hover span.scroll-down-arrow{border-color:transparent transparent #d23600 transparent}.sm-dox span.scroll-down:hover span.scroll-down-arrow{border-color:#d23600 transparent transparent transparent}.sm-dox span.scroll-up-arrow,.sm-dox span.scroll-down-arrow{position:absolute;top:0;left:50%;margin-left:-6px;width:0;height:0;overflow:hidden;border-width:6px;border-style:dashed dashed solid dashed;border-color:transparent transparent var(--nav-menu-foreground-color) transparent}.sm-dox span.scroll-down-arrow{top:8px;border-style:solid dashed dashed dashed;border-color:var(--nav-menu-foreground-color) transparent transparent transparent}.sm-dox.sm-rtl a.has-submenu{padding-right:12px;padding-left:24px}.sm-dox.sm-rtl a span.sub-arrow{right:auto;left:12px}.sm-dox.sm-rtl.sm-vertical a.has-submenu{padding:10px 20px}.sm-dox.sm-rtl.sm-vertical a span.sub-arrow{right:auto;left:8px;border-style:dashed solid dashed dashed;border-color:transparent #555 transparent transparent}.sm-dox.sm-rtl>li>ul:before{left:auto;right:30px}.sm-dox.sm-rtl>li>ul:after{left:auto;right:31px}.sm-dox.sm-rtl ul a.has-submenu{padding:10px 20px !important}.sm-dox.sm-rtl ul a span.sub-arrow{right:auto;left:8px;border-style:dashed solid dashed dashed;border-color:transparent #555 transparent transparent}.sm-dox.sm-vertical{padding:10px 0;-moz-border-radius:5px;-webkit-border-radius:5px;border-radius:5px}.sm-dox.sm-vertical a{padding:10px 20px}.sm-dox.sm-vertical a:hover,.sm-dox.sm-vertical a:focus,.sm-dox.sm-vertical a:active,.sm-dox.sm-vertical a.highlighted{background:#fff}.sm-dox.sm-vertical a.disabled{background-image:var(--nav-gradient-image)}.sm-dox.sm-vertical a span.sub-arrow{right:8px;top:50%;margin-top:-5px;border-width:5px;border-style:dashed dashed dashed solid;border-color:transparent transparent transparent #555}.sm-dox.sm-vertical>li>ul:before,.sm-dox.sm-vertical>li>ul:after{display:none}.sm-dox.sm-vertical ul a{padding:10px 20px}.sm-dox.sm-vertical ul a:hover,.sm-dox.sm-vertical ul a:focus,.sm-dox.sm-vertical ul a:active,.sm-dox.sm-vertical ul a.highlighted{background:#eee}.sm-dox.sm-vertical ul a.disabled{background:var(--nav-menu-background-color)}} \ No newline at end of file diff --git a/documentation/html/tank__drive_8h_source.html b/documentation/html/tank__drive_8h_source.html deleted file mode 100644 index 5c60811..0000000 --- a/documentation/html/tank__drive_8h_source.html +++ /dev/null @@ -1,165 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/subsystems/tank_drive.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    tank_drive.h
    -
    -
    -
    1#pragma once
    -
    2
    -
    3#ifndef PI
    -
    4#define PI 3.141592654
    -
    5#endif
    -
    6
    -
    7#include "vex.h"
    -
    8#include "../core/include/subsystems/odometry/odometry_tank.h"
    -
    9#include "../core/include/utils/pid.h"
    -
    10#include "../core/include/utils/feedback_base.h"
    -
    11#include "../core/include/robot_specs.h"
    -
    12#include "../core/src/utils/pure_pursuit.cpp"
    -
    13#include <vector>
    -
    14
    -
    15
    -
    16using namespace vex;
    -
    17
    - -
    23{
    -
    24public:
    -
    25
    -
    33 TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom=NULL);
    -
    34
    -
    38 void stop();
    -
    39
    -
    50 void drive_tank(double left, double right, int power=1, bool isdriver=false);
    -
    51
    -
    62 void drive_arcade(double forward_back, double left_right, int power=1);
    -
    63
    -
    74 bool drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed=1);
    -
    75
    -
    84 bool drive_forward(double inches, directionType dir, double max_speed=1);
    -
    85
    -
    96 bool turn_degrees(double degrees, Feedback &feedback, double max_speed=1);
    -
    97
    -
    107 bool turn_degrees(double degrees, double max_speed=1);
    -
    108
    -
    120 bool drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed=1);
    -
    121
    -
    133 bool drive_to_point(double x, double y, vex::directionType dir, double max_speed=1);
    -
    134
    -
    143 bool turn_to_heading(double heading_deg, Feedback &feedback, double max_speed=1);
    -
    151 bool turn_to_heading(double heading_deg, double max_speed=1);
    -
    152
    -
    156 void reset_auto();
    -
    157
    -
    166 static double modify_inputs(double input, int power=2);
    -
    167
    -
    179 bool pure_pursuit(std::vector<PurePursuit::hermite_point> path, directionType dir, double radius, double res, Feedback &feedback, double max_speed=1);
    -
    180
    -
    181private:
    -
    182 motor_group &left_motors;
    -
    183 motor_group &right_motors;
    -
    184
    -
    185 PID correction_pid;
    -
    186 Feedback *drive_default_feedback = NULL;
    -
    187 Feedback *turn_default_feedback = NULL;
    -
    188
    -
    189 OdometryBase *odometry;
    -
    190
    -
    191 robot_specs_t &config;
    -
    192
    -
    193 bool func_initialized = false;
    -
    194 bool is_pure_pursuit = false;
    -
    195};
    -
    Definition: feedback_base.h:11
    -
    Definition: odometry_base.h:33
    -
    Definition: pid.h:24
    -
    Definition: tank_drive.h:23
    -
    bool pure_pursuit(std::vector< PurePursuit::hermite_point > path, directionType dir, double radius, double res, Feedback &feedback, double max_speed=1)
    Definition: tank_drive.cpp:411
    -
    void drive_tank(double left, double right, int power=1, bool isdriver=false)
    Definition: tank_drive.cpp:34
    -
    bool drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed=1)
    Definition: tank_drive.cpp:77
    -
    bool turn_to_heading(double heading_deg, Feedback &feedback, double max_speed=1)
    Definition: tank_drive.cpp:344
    -
    void drive_arcade(double forward_back, double left_right, int power=1)
    Definition: tank_drive.cpp:56
    -
    void reset_auto()
    Definition: tank_drive.cpp:14
    -
    static double modify_inputs(double input, int power=2)
    Definition: tank_drive.cpp:406
    -
    bool turn_degrees(double degrees, Feedback &feedback, double max_speed=1)
    Definition: tank_drive.cpp:143
    -
    bool drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed=1)
    Definition: tank_drive.cpp:198
    -
    void stop()
    Definition: tank_drive.cpp:22
    -
    Definition: robot_specs.h:12
    -
    - - - - diff --git a/documentation/html/trapezoid__profile_8h_source.html b/documentation/html/trapezoid__profile_8h_source.html deleted file mode 100644 index ef76ce2..0000000 --- a/documentation/html/trapezoid__profile_8h_source.html +++ /dev/null @@ -1,129 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/trapezoid_profile.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    trapezoid_profile.h
    -
    -
    -
    1#pragma once
    -
    2
    -
    6typedef struct
    -
    7{
    -
    8 double pos;
    -
    9 double vel;
    -
    10 double accel;
    -
    11
    -
    12} motion_t;
    -
    13
    - -
    35{
    -
    36 public:
    -
    37
    -
    44 TrapezoidProfile(double max_v, double accel);
    -
    45
    -
    52 motion_t calculate(double time_s);
    -
    53
    -
    59 void set_endpts(double start, double end);
    -
    60
    -
    65 void set_accel(double accel);
    -
    66
    -
    72 void set_max_v(double max_v);
    -
    73
    -
    78 double get_movement_time();
    -
    79
    -
    80 private:
    -
    81 double start, end;
    -
    82 double max_v;
    -
    83 double accel;
    -
    84 double time;
    -
    85
    -
    86
    -
    87};
    -
    Definition: trapezoid_profile.h:35
    -
    motion_t calculate(double time_s)
    Run the trapezoidal profile based on the time that's ellapsed.
    Definition: trapezoid_profile.cpp:35
    -
    void set_endpts(double start, double end)
    Definition: trapezoid_profile.cpp:19
    -
    void set_accel(double accel)
    Definition: trapezoid_profile.cpp:14
    -
    void set_max_v(double max_v)
    Definition: trapezoid_profile.cpp:9
    -
    double get_movement_time()
    Definition: trapezoid_profile.cpp:113
    -
    Definition: trapezoid_profile.h:7
    -
    double vel
    1d velocity at this point in time
    Definition: trapezoid_profile.h:9
    -
    double accel
    1d acceleration at this point in time
    Definition: trapezoid_profile.h:10
    -
    double pos
    1d position at this point in time
    Definition: trapezoid_profile.h:8
    -
    - - - - diff --git a/documentation/html/vector2d_8h_source.html b/documentation/html/vector2d_8h_source.html deleted file mode 100644 index ccd8da4..0000000 --- a/documentation/html/vector2d_8h_source.html +++ /dev/null @@ -1,173 +0,0 @@ - - - - - - - -RIT VEXU Core API: include/utils/vector2d.h Source File - - - - - - - - - -
    -
    - - - - - - -
    -
    RIT VEXU Core API -
    -
    -
    - - - - - - - - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - - -
    -
    -
    vector2d.h
    -
    -
    -
    1#pragma once
    -
    2
    -
    3#include <cmath>
    -
    4
    -
    5#ifndef PI
    -
    6#define PI 3.141592654
    -
    7#endif
    - -
    14{
    -
    15public:
    -
    16
    -
    20 struct point_t
    -
    21 {
    -
    22 double x;
    -
    23 double y;
    -
    24
    -
    25
    -
    31 double dist(const point_t other)
    -
    32 {
    -
    33 return sqrt(pow(this->x - other.x, 2) + pow(this->y - other.y, 2));
    -
    34 }
    -
    35
    - -
    42 {
    -
    43 point_t p
    -
    44 {
    -
    45 .x = this->x + other.x,
    -
    46 .y = this->y + other.y
    -
    47 };
    -
    48 return p;
    -
    49 }
    -
    50
    - -
    57 {
    -
    58 point_t p
    -
    59 {
    -
    60 .x = this->x - other.x,
    -
    61 .y = this->y - other.y
    -
    62 };
    -
    63 return p;
    -
    64 }
    -
    65 };
    -
    66
    -
    73 Vector2D(double dir, double mag);
    -
    74
    -
    80 Vector2D(point_t p);
    -
    81
    -
    89 double get_dir() const;
    -
    90
    -
    94 double get_mag() const;
    -
    95
    -
    99 double get_x() const;
    -
    100
    -
    104 double get_y() const;
    -
    105
    - -
    111
    - -
    117
    -
    123 Vector2D operator*(const double &x);
    -
    130 Vector2D operator+(const Vector2D &other);
    -
    137 Vector2D operator-(const Vector2D &other);
    -
    138
    -
    139private:
    -
    140
    -
    141 double dir, mag;
    -
    142
    -
    143};
    -
    144
    -
    150double deg2rad(double deg);
    -
    151
    -
    158double rad2deg(double r);
    -
    Definition: vector2d.h:14
    -
    Vector2D operator*(const double &x)
    Definition: vector2d.cpp:116
    -
    Vector2D operator-(const Vector2D &other)
    Definition: vector2d.cpp:101
    -
    Vector2D normalize()
    Definition: vector2d.cpp:58
    -
    double get_x() const
    Definition: vector2d.cpp:42
    -
    Vector2D operator+(const Vector2D &other)
    Definition: vector2d.cpp:84
    -
    double get_mag() const
    Definition: vector2d.cpp:37
    -
    Vector2D::point_t point()
    Definition: vector2d.cpp:67
    -
    double get_dir() const
    Definition: vector2d.cpp:32
    -
    double get_y() const
    Definition: vector2d.cpp:50
    -
    Definition: vector2d.h:21
    -
    double dist(const point_t other)
    Definition: vector2d.h:31
    -
    point_t operator+(const point_t &other)
    Definition: vector2d.h:41
    -
    double y
    the y position in space
    Definition: vector2d.h:23
    -
    point_t operator-(const point_t &other)
    Definition: vector2d.h:56
    -
    double x
    the x position in space
    Definition: vector2d.h:22
    -
    - - - - From 4201ac54559aa6d76bd17f009a324fcf8f01ea9e Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 12 Mar 2023 20:11:39 -0400 Subject: [PATCH 186/243] fixed typos --- .github/workflows/main.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index c033af1..4dbeddd 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -6,7 +6,7 @@ name: Doxygen Action # events but only for the master branch on: push: - branches: [ master ] + branches: [ main ] From a93641f5d9657c8f388d7fc3564f853462595932 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 12 Mar 2023 20:14:40 -0400 Subject: [PATCH 187/243] fixed typo 2 --- .github/workflows/main.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index 4dbeddd..c033af1 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -6,7 +6,7 @@ name: Doxygen Action # events but only for the master branch on: push: - branches: [ main ] + branches: [ master ] From 9b87fb1b019b0c90f5569baa93b64388069bad08 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 12 Mar 2023 20:20:42 -0400 Subject: [PATCH 188/243] Doxygen excludes image files so it doesnt fail --- Doxyfile | 2741 ++++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 2741 insertions(+) create mode 100644 Doxyfile diff --git a/Doxyfile b/Doxyfile new file mode 100644 index 0000000..1101dd7 --- /dev/null +++ b/Doxyfile @@ -0,0 +1,2741 @@ +# Doxyfile 1.9.6 + +# This file describes the settings to be used by the documentation system +# doxygen (www.doxygen.org) for a project. +# +# All text after a double hash (##) is considered a comment and is placed in +# front of the TAG it is preceding. +# +# All text after a single hash (#) is considered a comment and will be ignored. +# The format is: +# TAG = value [value, ...] +# For lists, items can also be appended using: +# TAG += value [value, ...] +# Values that contain spaces should be placed between quotes (\" \"). +# +# Note: +# +# Use doxygen to compare the used configuration file with the template +# configuration file: +# doxygen -x [configFile] +# Use doxygen to compare the used configuration file with the template +# configuration file without replacing the environment variables or CMake type +# replacement variables: +# doxygen -x_noenv [configFile] + +#--------------------------------------------------------------------------- +# Project related configuration options +#--------------------------------------------------------------------------- + +# This tag specifies the encoding used for all characters in the configuration +# file that follow. The default is UTF-8 which is also the encoding used for all +# text before the first occurrence of this tag. Doxygen uses libiconv (or the +# iconv built into libc) for the transcoding. See +# https://www.gnu.org/software/libiconv/ for the list of possible encodings. +# The default value is: UTF-8. + +DOXYFILE_ENCODING = UTF-8 + +# The PROJECT_NAME tag is a single word (or a sequence of words surrounded by +# double-quotes, unless you are using Doxywizard) that should identify the +# project for which the documentation is generated. This name is used in the +# title of most generated pages and in a few other places. +# The default value is: My Project. + +PROJECT_NAME = "RIT VEXU Core API" + +# The PROJECT_NUMBER tag can be used to enter a project or revision number. This +# could be handy for archiving the generated documentation or if some version +# control system is used. + +PROJECT_NUMBER = + +# Using the PROJECT_BRIEF tag one can provide an optional one line description +# for a project that appears at the top of each page and should give viewer a +# quick idea about the purpose of the project. Keep the description short. + +PROJECT_BRIEF = + +# With the PROJECT_LOGO tag one can specify a logo or an icon that is included +# in the documentation. The maximum height of the logo should not exceed 55 +# pixels and the maximum width should not exceed 200 pixels. Doxygen will copy +# the logo to the output directory. + +PROJECT_LOGO = + +# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) path +# into which the generated documentation will be written. If a relative path is +# entered, it will be relative to the location where doxygen was started. If +# left blank the current directory will be used. + +OUTPUT_DIRECTORY = documentation/ + +# If the CREATE_SUBDIRS tag is set to YES then doxygen will create up to 4096 +# sub-directories (in 2 levels) under the output directory of each output format +# and will distribute the generated files over these directories. Enabling this +# option can be useful when feeding doxygen a huge amount of source files, where +# putting all generated files in the same directory would otherwise causes +# performance problems for the file system. Adapt CREATE_SUBDIRS_LEVEL to +# control the number of sub-directories. +# The default value is: NO. + +CREATE_SUBDIRS = NO + +# Controls the number of sub-directories that will be created when +# CREATE_SUBDIRS tag is set to YES. Level 0 represents 16 directories, and every +# level increment doubles the number of directories, resulting in 4096 +# directories at level 8 which is the default and also the maximum value. The +# sub-directories are organized in 2 levels, the first level always has a fixed +# number of 16 directories. +# Minimum value: 0, maximum value: 8, default value: 8. +# This tag requires that the tag CREATE_SUBDIRS is set to YES. + +CREATE_SUBDIRS_LEVEL = 8 + +# If the ALLOW_UNICODE_NAMES tag is set to YES, doxygen will allow non-ASCII +# characters to appear in the names of generated files. If set to NO, non-ASCII +# characters will be escaped, for example _xE3_x81_x84 will be used for Unicode +# U+3044. +# The default value is: NO. + +ALLOW_UNICODE_NAMES = NO + +# The OUTPUT_LANGUAGE tag is used to specify the language in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all constant output in the proper language. +# Possible values are: Afrikaans, Arabic, Armenian, Brazilian, Bulgarian, +# Catalan, Chinese, Chinese-Traditional, Croatian, Czech, Danish, Dutch, English +# (United States), Esperanto, Farsi (Persian), Finnish, French, German, Greek, +# Hindi, Hungarian, Indonesian, Italian, Japanese, Japanese-en (Japanese with +# English messages), Korean, Korean-en (Korean with English messages), Latvian, +# Lithuanian, Macedonian, Norwegian, Persian (Farsi), Polish, Portuguese, +# Romanian, Russian, Serbian, Serbian-Cyrillic, Slovak, Slovene, Spanish, +# Swedish, Turkish, Ukrainian and Vietnamese. +# The default value is: English. + +OUTPUT_LANGUAGE = English + +# If the BRIEF_MEMBER_DESC tag is set to YES, doxygen will include brief member +# descriptions after the members that are listed in the file and class +# documentation (similar to Javadoc). Set to NO to disable this. +# The default value is: YES. + +BRIEF_MEMBER_DESC = YES + +# If the REPEAT_BRIEF tag is set to YES, doxygen will prepend the brief +# description of a member or function before the detailed description +# +# Note: If both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the +# brief descriptions will be completely suppressed. +# The default value is: YES. + +REPEAT_BRIEF = YES + +# This tag implements a quasi-intelligent brief description abbreviator that is +# used to form the text in various listings. Each string in this list, if found +# as the leading text of the brief description, will be stripped from the text +# and the result, after processing the whole list, is used as the annotated +# text. Otherwise, the brief description is used as-is. If left blank, the +# following values are used ($name is automatically replaced with the name of +# the entity):The $name class, The $name widget, The $name file, is, provides, +# specifies, contains, represents, a, an and the. + +ABBREVIATE_BRIEF = "The $name class" \ + "The $name widget" \ + "The $name file" \ + is \ + provides \ + specifies \ + contains \ + represents \ + a \ + an \ + the + +# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then +# doxygen will generate a detailed section even if there is only a brief +# description. +# The default value is: NO. + +ALWAYS_DETAILED_SEC = NO + +# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all +# inherited members of a class in the documentation of that class as if those +# members were ordinary class members. Constructors, destructors and assignment +# operators of the base classes will not be shown. +# The default value is: NO. + +INLINE_INHERITED_MEMB = NO + +# If the FULL_PATH_NAMES tag is set to YES, doxygen will prepend the full path +# before files name in the file list and in the header files. If set to NO the +# shortest path that makes the file name unique will be used +# The default value is: YES. + +FULL_PATH_NAMES = YES + +# The STRIP_FROM_PATH tag can be used to strip a user-defined part of the path. +# Stripping is only done if one of the specified strings matches the left-hand +# part of the path. The tag can be used to show relative paths in the file list. +# If left blank the directory from which doxygen is run is used as the path to +# strip. +# +# Note that you can specify absolute paths here, but also relative paths, which +# will be relative from the directory where doxygen is started. +# This tag requires that the tag FULL_PATH_NAMES is set to YES. + +STRIP_FROM_PATH = + +# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of the +# path mentioned in the documentation of a class, which tells the reader which +# header file to include in order to use a class. If left blank only the name of +# the header file containing the class definition is used. Otherwise one should +# specify the list of include paths that are normally passed to the compiler +# using the -I flag. + +STRIP_FROM_INC_PATH = + +# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter (but +# less readable) file names. This can be useful is your file systems doesn't +# support long names like on DOS, Mac, or CD-ROM. +# The default value is: NO. + +SHORT_NAMES = NO + +# If the JAVADOC_AUTOBRIEF tag is set to YES then doxygen will interpret the +# first line (until the first dot) of a Javadoc-style comment as the brief +# description. If set to NO, the Javadoc-style will behave just like regular Qt- +# style comments (thus requiring an explicit @brief command for a brief +# description.) +# The default value is: NO. + +JAVADOC_AUTOBRIEF = NO + +# If the JAVADOC_BANNER tag is set to YES then doxygen will interpret a line +# such as +# /*************** +# as being the beginning of a Javadoc-style comment "banner". If set to NO, the +# Javadoc-style will behave just like regular comments and it will not be +# interpreted by doxygen. +# The default value is: NO. + +JAVADOC_BANNER = NO + +# If the QT_AUTOBRIEF tag is set to YES then doxygen will interpret the first +# line (until the first dot) of a Qt-style comment as the brief description. If +# set to NO, the Qt-style will behave just like regular Qt-style comments (thus +# requiring an explicit \brief command for a brief description.) +# The default value is: NO. + +QT_AUTOBRIEF = NO + +# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make doxygen treat a +# multi-line C++ special comment block (i.e. a block of //! or /// comments) as +# a brief description. This used to be the default behavior. The new default is +# to treat a multi-line C++ comment block as a detailed description. Set this +# tag to YES if you prefer the old behavior instead. +# +# Note that setting this tag to YES also means that rational rose comments are +# not recognized any more. +# The default value is: NO. + +MULTILINE_CPP_IS_BRIEF = NO + +# By default Python docstrings are displayed as preformatted text and doxygen's +# special commands cannot be used. By setting PYTHON_DOCSTRING to NO the +# doxygen's special commands can be used and the contents of the docstring +# documentation blocks is shown as doxygen documentation. +# The default value is: YES. + +PYTHON_DOCSTRING = YES + +# If the INHERIT_DOCS tag is set to YES then an undocumented member inherits the +# documentation from any documented member that it re-implements. +# The default value is: YES. + +INHERIT_DOCS = YES + +# If the SEPARATE_MEMBER_PAGES tag is set to YES then doxygen will produce a new +# page for each member. If set to NO, the documentation of a member will be part +# of the file/class/namespace that contains it. +# The default value is: NO. + +SEPARATE_MEMBER_PAGES = NO + +# The TAB_SIZE tag can be used to set the number of spaces in a tab. Doxygen +# uses this value to replace tabs by spaces in code fragments. +# Minimum value: 1, maximum value: 16, default value: 4. + +TAB_SIZE = 4 + +# This tag can be used to specify a number of aliases that act as commands in +# the documentation. An alias has the form: +# name=value +# For example adding +# "sideeffect=@par Side Effects:^^" +# will allow you to put the command \sideeffect (or @sideeffect) in the +# documentation, which will result in a user-defined paragraph with heading +# "Side Effects:". Note that you cannot put \n's in the value part of an alias +# to insert newlines (in the resulting output). You can put ^^ in the value part +# of an alias to insert a newline as if a physical newline was in the original +# file. When you need a literal { or } or , in the value part of an alias you +# have to escape them by means of a backslash (\), this can lead to conflicts +# with the commands \{ and \} for these it is advised to use the version @{ and +# @} or use a double escape (\\{ and \\}) + +ALIASES = + +# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C sources +# only. Doxygen will then generate output that is more tailored for C. For +# instance, some of the names that are used will be different. The list of all +# members will be omitted, etc. +# The default value is: NO. + +OPTIMIZE_OUTPUT_FOR_C = NO + +# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java or +# Python sources only. Doxygen will then generate output that is more tailored +# for that language. For instance, namespaces will be presented as packages, +# qualified scopes will look different, etc. +# The default value is: NO. + +OPTIMIZE_OUTPUT_JAVA = NO + +# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran +# sources. Doxygen will then generate output that is tailored for Fortran. +# The default value is: NO. + +OPTIMIZE_FOR_FORTRAN = NO + +# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL +# sources. Doxygen will then generate output that is tailored for VHDL. +# The default value is: NO. + +OPTIMIZE_OUTPUT_VHDL = NO + +# Set the OPTIMIZE_OUTPUT_SLICE tag to YES if your project consists of Slice +# sources only. Doxygen will then generate output that is more tailored for that +# language. For instance, namespaces will be presented as modules, types will be +# separated into more groups, etc. +# The default value is: NO. + +OPTIMIZE_OUTPUT_SLICE = NO + +# Doxygen selects the parser to use depending on the extension of the files it +# parses. With this tag you can assign which parser to use for a given +# extension. Doxygen has a built-in mapping, but you can override or extend it +# using this tag. The format is ext=language, where ext is a file extension, and +# language is one of the parsers supported by doxygen: IDL, Java, JavaScript, +# Csharp (C#), C, C++, Lex, D, PHP, md (Markdown), Objective-C, Python, Slice, +# VHDL, Fortran (fixed format Fortran: FortranFixed, free formatted Fortran: +# FortranFree, unknown formatted Fortran: Fortran. In the later case the parser +# tries to guess whether the code is fixed or free formatted code, this is the +# default for Fortran type files). For instance to make doxygen treat .inc files +# as Fortran files (default is PHP), and .f files as C (default is Fortran), +# use: inc=Fortran f=C. +# +# Note: For files without extension you can use no_extension as a placeholder. +# +# Note that for custom extensions you also need to set FILE_PATTERNS otherwise +# the files are not read by doxygen. When specifying no_extension you should add +# * to the FILE_PATTERNS. +# +# Note see also the list of default file extension mappings. + +EXTENSION_MAPPING = + +# If the MARKDOWN_SUPPORT tag is enabled then doxygen pre-processes all comments +# according to the Markdown format, which allows for more readable +# documentation. See https://daringfireball.net/projects/markdown/ for details. +# The output of markdown processing is further processed by doxygen, so you can +# mix doxygen, HTML, and XML commands with Markdown formatting. Disable only in +# case of backward compatibilities issues. +# The default value is: YES. + +MARKDOWN_SUPPORT = YES + +# When the TOC_INCLUDE_HEADINGS tag is set to a non-zero value, all headings up +# to that level are automatically included in the table of contents, even if +# they do not have an id attribute. +# Note: This feature currently applies only to Markdown headings. +# Minimum value: 0, maximum value: 99, default value: 5. +# This tag requires that the tag MARKDOWN_SUPPORT is set to YES. + +TOC_INCLUDE_HEADINGS = 5 + +# When enabled doxygen tries to link words that correspond to documented +# classes, or namespaces to their corresponding documentation. Such a link can +# be prevented in individual cases by putting a % sign in front of the word or +# globally by setting AUTOLINK_SUPPORT to NO. +# The default value is: YES. + +AUTOLINK_SUPPORT = YES + +# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want +# to include (a tag file for) the STL sources as input, then you should set this +# tag to YES in order to let doxygen match functions declarations and +# definitions whose arguments contain STL classes (e.g. func(std::string); +# versus func(std::string) {}). This also make the inheritance and collaboration +# diagrams that involve STL classes more complete and accurate. +# The default value is: NO. + +BUILTIN_STL_SUPPORT = NO + +# If you use Microsoft's C++/CLI language, you should set this option to YES to +# enable parsing support. +# The default value is: NO. + +CPP_CLI_SUPPORT = NO + +# Set the SIP_SUPPORT tag to YES if your project consists of sip (see: +# https://www.riverbankcomputing.com/software/sip/intro) sources only. Doxygen +# will parse them like normal C++ but will assume all classes use public instead +# of private inheritance when no explicit protection keyword is present. +# The default value is: NO. + +SIP_SUPPORT = NO + +# For Microsoft's IDL there are propget and propput attributes to indicate +# getter and setter methods for a property. Setting this option to YES will make +# doxygen to replace the get and set methods by a property in the documentation. +# This will only work if the methods are indeed getting or setting a simple +# type. If this is not the case, or you want to show the methods anyway, you +# should set this option to NO. +# The default value is: YES. + +IDL_PROPERTY_SUPPORT = YES + +# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC +# tag is set to YES then doxygen will reuse the documentation of the first +# member in the group (if any) for the other members of the group. By default +# all members of a group must be documented explicitly. +# The default value is: NO. + +DISTRIBUTE_GROUP_DOC = NO + +# If one adds a struct or class to a group and this option is enabled, then also +# any nested class or struct is added to the same group. By default this option +# is disabled and one has to add nested compounds explicitly via \ingroup. +# The default value is: NO. + +GROUP_NESTED_COMPOUNDS = NO + +# Set the SUBGROUPING tag to YES to allow class member groups of the same type +# (for instance a group of public functions) to be put as a subgroup of that +# type (e.g. under the Public Functions section). Set it to NO to prevent +# subgrouping. Alternatively, this can be done per class using the +# \nosubgrouping command. +# The default value is: YES. + +SUBGROUPING = YES + +# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and unions +# are shown inside the group in which they are included (e.g. using \ingroup) +# instead of on a separate page (for HTML and Man pages) or section (for LaTeX +# and RTF). +# +# Note that this feature does not work in combination with +# SEPARATE_MEMBER_PAGES. +# The default value is: NO. + +INLINE_GROUPED_CLASSES = NO + +# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and unions +# with only public data fields or simple typedef fields will be shown inline in +# the documentation of the scope in which they are defined (i.e. file, +# namespace, or group documentation), provided this scope is documented. If set +# to NO, structs, classes, and unions are shown on a separate page (for HTML and +# Man pages) or section (for LaTeX and RTF). +# The default value is: NO. + +INLINE_SIMPLE_STRUCTS = NO + +# When TYPEDEF_HIDES_STRUCT tag is enabled, a typedef of a struct, union, or +# enum is documented as struct, union, or enum with the name of the typedef. So +# typedef struct TypeS {} TypeT, will appear in the documentation as a struct +# with name TypeT. When disabled the typedef will appear as a member of a file, +# namespace, or class. And the struct will be named TypeS. This can typically be +# useful for C code in case the coding convention dictates that all compound +# types are typedef'ed and only the typedef is referenced, never the tag name. +# The default value is: NO. + +TYPEDEF_HIDES_STRUCT = NO + +# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This +# cache is used to resolve symbols given their name and scope. Since this can be +# an expensive process and often the same symbol appears multiple times in the +# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small +# doxygen will become slower. If the cache is too large, memory is wasted. The +# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range +# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536 +# symbols. At the end of a run doxygen will report the cache usage and suggest +# the optimal cache size from a speed point of view. +# Minimum value: 0, maximum value: 9, default value: 0. + +LOOKUP_CACHE_SIZE = 0 + +# The NUM_PROC_THREADS specifies the number of threads doxygen is allowed to use +# during processing. When set to 0 doxygen will based this on the number of +# cores available in the system. You can set it explicitly to a value larger +# than 0 to get more control over the balance between CPU load and processing +# speed. At this moment only the input processing can be done using multiple +# threads. Since this is still an experimental feature the default is set to 1, +# which effectively disables parallel processing. Please report any issues you +# encounter. Generating dot graphs in parallel is controlled by the +# DOT_NUM_THREADS setting. +# Minimum value: 0, maximum value: 32, default value: 1. + +NUM_PROC_THREADS = 1 + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- + +# If the EXTRACT_ALL tag is set to YES, doxygen will assume all entities in +# documentation are documented, even if no documentation was available. Private +# class members and static file members will be hidden unless the +# EXTRACT_PRIVATE respectively EXTRACT_STATIC tags are set to YES. +# Note: This will also disable the warnings about undocumented members that are +# normally produced when WARNINGS is set to YES. +# The default value is: NO. + +EXTRACT_ALL = NO + +# If the EXTRACT_PRIVATE tag is set to YES, all private members of a class will +# be included in the documentation. +# The default value is: NO. + +EXTRACT_PRIVATE = NO + +# If the EXTRACT_PRIV_VIRTUAL tag is set to YES, documented private virtual +# methods of a class will be included in the documentation. +# The default value is: NO. + +EXTRACT_PRIV_VIRTUAL = NO + +# If the EXTRACT_PACKAGE tag is set to YES, all members with package or internal +# scope will be included in the documentation. +# The default value is: NO. + +EXTRACT_PACKAGE = NO + +# If the EXTRACT_STATIC tag is set to YES, all static members of a file will be +# included in the documentation. +# The default value is: NO. + +EXTRACT_STATIC = NO + +# If the EXTRACT_LOCAL_CLASSES tag is set to YES, classes (and structs) defined +# locally in source files will be included in the documentation. If set to NO, +# only classes defined in header files are included. Does not have any effect +# for Java sources. +# The default value is: YES. + +EXTRACT_LOCAL_CLASSES = YES + +# This flag is only useful for Objective-C code. If set to YES, local methods, +# which are defined in the implementation section but not in the interface are +# included in the documentation. If set to NO, only methods in the interface are +# included. +# The default value is: NO. + +EXTRACT_LOCAL_METHODS = NO + +# If this flag is set to YES, the members of anonymous namespaces will be +# extracted and appear in the documentation as a namespace called +# 'anonymous_namespace{file}', where file will be replaced with the base name of +# the file that contains the anonymous namespace. By default anonymous namespace +# are hidden. +# The default value is: NO. + +EXTRACT_ANON_NSPACES = NO + +# If this flag is set to YES, the name of an unnamed parameter in a declaration +# will be determined by the corresponding definition. By default unnamed +# parameters remain unnamed in the output. +# The default value is: YES. + +RESOLVE_UNNAMED_PARAMS = YES + +# If the HIDE_UNDOC_MEMBERS tag is set to YES, doxygen will hide all +# undocumented members inside documented classes or files. If set to NO these +# members will be included in the various overviews, but no documentation +# section is generated. This option has no effect if EXTRACT_ALL is enabled. +# The default value is: NO. + +HIDE_UNDOC_MEMBERS = NO + +# If the HIDE_UNDOC_CLASSES tag is set to YES, doxygen will hide all +# undocumented classes that are normally visible in the class hierarchy. If set +# to NO, these classes will be included in the various overviews. This option +# will also hide undocumented C++ concepts if enabled. This option has no effect +# if EXTRACT_ALL is enabled. +# The default value is: NO. + +HIDE_UNDOC_CLASSES = NO + +# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, doxygen will hide all friend +# declarations. If set to NO, these declarations will be included in the +# documentation. +# The default value is: NO. + +HIDE_FRIEND_COMPOUNDS = NO + +# If the HIDE_IN_BODY_DOCS tag is set to YES, doxygen will hide any +# documentation blocks found inside the body of a function. If set to NO, these +# blocks will be appended to the function's detailed documentation block. +# The default value is: NO. + +HIDE_IN_BODY_DOCS = NO + +# The INTERNAL_DOCS tag determines if documentation that is typed after a +# \internal command is included. If the tag is set to NO then the documentation +# will be excluded. Set it to YES to include the internal documentation. +# The default value is: NO. + +INTERNAL_DOCS = NO + +# With the correct setting of option CASE_SENSE_NAMES doxygen will better be +# able to match the capabilities of the underlying filesystem. In case the +# filesystem is case sensitive (i.e. it supports files in the same directory +# whose names only differ in casing), the option must be set to YES to properly +# deal with such files in case they appear in the input. For filesystems that +# are not case sensitive the option should be set to NO to properly deal with +# output files written for symbols that only differ in casing, such as for two +# classes, one named CLASS and the other named Class, and to also support +# references to files without having to specify the exact matching casing. On +# Windows (including Cygwin) and MacOS, users should typically set this option +# to NO, whereas on Linux or other Unix flavors it should typically be set to +# YES. +# Possible values are: SYSTEM, NO and YES. +# The default value is: SYSTEM. + +CASE_SENSE_NAMES = SYSTEM + +# If the HIDE_SCOPE_NAMES tag is set to NO then doxygen will show members with +# their full class and namespace scopes in the documentation. If set to YES, the +# scope will be hidden. +# The default value is: NO. + +HIDE_SCOPE_NAMES = NO + +# If the HIDE_COMPOUND_REFERENCE tag is set to NO (default) then doxygen will +# append additional text to a page's title, such as Class Reference. If set to +# YES the compound reference will be hidden. +# The default value is: NO. + +HIDE_COMPOUND_REFERENCE= NO + +# If the SHOW_HEADERFILE tag is set to YES then the documentation for a class +# will show which file needs to be included to use the class. +# The default value is: YES. + +SHOW_HEADERFILE = YES + +# If the SHOW_INCLUDE_FILES tag is set to YES then doxygen will put a list of +# the files that are included by a file in the documentation of that file. +# The default value is: YES. + +SHOW_INCLUDE_FILES = YES + +# If the SHOW_GROUPED_MEMB_INC tag is set to YES then Doxygen will add for each +# grouped member an include statement to the documentation, telling the reader +# which file to include in order to use the member. +# The default value is: NO. + +SHOW_GROUPED_MEMB_INC = NO + +# If the FORCE_LOCAL_INCLUDES tag is set to YES then doxygen will list include +# files with double quotes in the documentation rather than with sharp brackets. +# The default value is: NO. + +FORCE_LOCAL_INCLUDES = NO + +# If the INLINE_INFO tag is set to YES then a tag [inline] is inserted in the +# documentation for inline members. +# The default value is: YES. + +INLINE_INFO = YES + +# If the SORT_MEMBER_DOCS tag is set to YES then doxygen will sort the +# (detailed) documentation of file and class members alphabetically by member +# name. If set to NO, the members will appear in declaration order. +# The default value is: YES. + +SORT_MEMBER_DOCS = YES + +# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the brief +# descriptions of file, namespace and class members alphabetically by member +# name. If set to NO, the members will appear in declaration order. Note that +# this will also influence the order of the classes in the class list. +# The default value is: NO. + +SORT_BRIEF_DOCS = NO + +# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the +# (brief and detailed) documentation of class members so that constructors and +# destructors are listed first. If set to NO the constructors will appear in the +# respective orders defined by SORT_BRIEF_DOCS and SORT_MEMBER_DOCS. +# Note: If SORT_BRIEF_DOCS is set to NO this option is ignored for sorting brief +# member documentation. +# Note: If SORT_MEMBER_DOCS is set to NO this option is ignored for sorting +# detailed member documentation. +# The default value is: NO. + +SORT_MEMBERS_CTORS_1ST = NO + +# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the hierarchy +# of group names into alphabetical order. If set to NO the group names will +# appear in their defined order. +# The default value is: NO. + +SORT_GROUP_NAMES = NO + +# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be sorted by +# fully-qualified names, including namespaces. If set to NO, the class list will +# be sorted only by class name, not including the namespace part. +# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. +# Note: This option applies only to the class list, not to the alphabetical +# list. +# The default value is: NO. + +SORT_BY_SCOPE_NAME = NO + +# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to do proper +# type resolution of all parameters of a function it will reject a match between +# the prototype and the implementation of a member function even if there is +# only one candidate or it is obvious which candidate to choose by doing a +# simple string match. By disabling STRICT_PROTO_MATCHING doxygen will still +# accept a match between prototype and implementation in such cases. +# The default value is: NO. + +STRICT_PROTO_MATCHING = NO + +# The GENERATE_TODOLIST tag can be used to enable (YES) or disable (NO) the todo +# list. This list is created by putting \todo commands in the documentation. +# The default value is: YES. + +GENERATE_TODOLIST = YES + +# The GENERATE_TESTLIST tag can be used to enable (YES) or disable (NO) the test +# list. This list is created by putting \test commands in the documentation. +# The default value is: YES. + +GENERATE_TESTLIST = YES + +# The GENERATE_BUGLIST tag can be used to enable (YES) or disable (NO) the bug +# list. This list is created by putting \bug commands in the documentation. +# The default value is: YES. + +GENERATE_BUGLIST = YES + +# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or disable (NO) +# the deprecated list. This list is created by putting \deprecated commands in +# the documentation. +# The default value is: YES. + +GENERATE_DEPRECATEDLIST= YES + +# The ENABLED_SECTIONS tag can be used to enable conditional documentation +# sections, marked by \if ... \endif and \cond +# ... \endcond blocks. + +ENABLED_SECTIONS = + +# The MAX_INITIALIZER_LINES tag determines the maximum number of lines that the +# initial value of a variable or macro / define can have for it to appear in the +# documentation. If the initializer consists of more lines than specified here +# it will be hidden. Use a value of 0 to hide initializers completely. The +# appearance of the value of individual variables and macros / defines can be +# controlled using \showinitializer or \hideinitializer command in the +# documentation regardless of this setting. +# Minimum value: 0, maximum value: 10000, default value: 30. + +MAX_INITIALIZER_LINES = 30 + +# Set the SHOW_USED_FILES tag to NO to disable the list of files generated at +# the bottom of the documentation of classes and structs. If set to YES, the +# list will mention the files that were used to generate the documentation. +# The default value is: YES. + +SHOW_USED_FILES = YES + +# Set the SHOW_FILES tag to NO to disable the generation of the Files page. This +# will remove the Files entry from the Quick Index and from the Folder Tree View +# (if specified). +# The default value is: YES. + +SHOW_FILES = YES + +# Set the SHOW_NAMESPACES tag to NO to disable the generation of the Namespaces +# page. This will remove the Namespaces entry from the Quick Index and from the +# Folder Tree View (if specified). +# The default value is: YES. + +SHOW_NAMESPACES = YES + +# The FILE_VERSION_FILTER tag can be used to specify a program or script that +# doxygen should invoke to get the current version for each file (typically from +# the version control system). Doxygen will invoke the program by executing (via +# popen()) the command command input-file, where command is the value of the +# FILE_VERSION_FILTER tag, and input-file is the name of an input file provided +# by doxygen. Whatever the program writes to standard output is used as the file +# version. For an example see the documentation. + +FILE_VERSION_FILTER = + +# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed +# by doxygen. The layout file controls the global structure of the generated +# output files in an output format independent way. To create the layout file +# that represents doxygen's defaults, run doxygen with the -l option. You can +# optionally specify a file name after the option, if omitted DoxygenLayout.xml +# will be used as the name of the layout file. See also section "Changing the +# layout of pages" for information. +# +# Note that if you run doxygen from a directory containing a file called +# DoxygenLayout.xml, doxygen will parse it automatically even if the LAYOUT_FILE +# tag is left empty. + +LAYOUT_FILE = + +# The CITE_BIB_FILES tag can be used to specify one or more bib files containing +# the reference definitions. This must be a list of .bib files. The .bib +# extension is automatically appended if omitted. This requires the bibtex tool +# to be installed. See also https://en.wikipedia.org/wiki/BibTeX for more info. +# For LaTeX the style of the bibliography can be controlled using +# LATEX_BIB_STYLE. To use this feature you need bibtex and perl available in the +# search path. See also \cite for info how to create references. + +CITE_BIB_FILES = + +#--------------------------------------------------------------------------- +# Configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +# The QUIET tag can be used to turn on/off the messages that are generated to +# standard output by doxygen. If QUIET is set to YES this implies that the +# messages are off. +# The default value is: NO. + +QUIET = NO + +# The WARNINGS tag can be used to turn on/off the warning messages that are +# generated to standard error (stderr) by doxygen. If WARNINGS is set to YES +# this implies that the warnings are on. +# +# Tip: Turn warnings on while writing the documentation. +# The default value is: YES. + +WARNINGS = YES + +# If the WARN_IF_UNDOCUMENTED tag is set to YES then doxygen will generate +# warnings for undocumented members. If EXTRACT_ALL is set to YES then this flag +# will automatically be disabled. +# The default value is: YES. + +WARN_IF_UNDOCUMENTED = YES + +# If the WARN_IF_DOC_ERROR tag is set to YES, doxygen will generate warnings for +# potential errors in the documentation, such as documenting some parameters in +# a documented function twice, or documenting parameters that don't exist or +# using markup commands wrongly. +# The default value is: YES. + +WARN_IF_DOC_ERROR = YES + +# If WARN_IF_INCOMPLETE_DOC is set to YES, doxygen will warn about incomplete +# function parameter documentation. If set to NO, doxygen will accept that some +# parameters have no documentation without warning. +# The default value is: YES. + +WARN_IF_INCOMPLETE_DOC = YES + +# This WARN_NO_PARAMDOC option can be enabled to get warnings for functions that +# are documented, but have no documentation for their parameters or return +# value. If set to NO, doxygen will only warn about wrong parameter +# documentation, but not about the absence of documentation. If EXTRACT_ALL is +# set to YES then this flag will automatically be disabled. See also +# WARN_IF_INCOMPLETE_DOC +# The default value is: NO. + +WARN_NO_PARAMDOC = NO + +# If WARN_IF_UNDOC_ENUM_VAL option is set to YES, doxygen will warn about +# undocumented enumeration values. If set to NO, doxygen will accept +# undocumented enumeration values. If EXTRACT_ALL is set to YES then this flag +# will automatically be disabled. +# The default value is: NO. + +WARN_IF_UNDOC_ENUM_VAL = NO + +# If the WARN_AS_ERROR tag is set to YES then doxygen will immediately stop when +# a warning is encountered. If the WARN_AS_ERROR tag is set to FAIL_ON_WARNINGS +# then doxygen will continue running as if WARN_AS_ERROR tag is set to NO, but +# at the end of the doxygen process doxygen will return with a non-zero status. +# Possible values are: NO, YES and FAIL_ON_WARNINGS. +# The default value is: NO. + +WARN_AS_ERROR = NO + +# The WARN_FORMAT tag determines the format of the warning messages that doxygen +# can produce. The string should contain the $file, $line, and $text tags, which +# will be replaced by the file and line number from which the warning originated +# and the warning text. Optionally the format may contain $version, which will +# be replaced by the version of the file (if it could be obtained via +# FILE_VERSION_FILTER) +# See also: WARN_LINE_FORMAT +# The default value is: $file:$line: $text. + +WARN_FORMAT = "$file:$line: $text" + +# In the $text part of the WARN_FORMAT command it is possible that a reference +# to a more specific place is given. To make it easier to jump to this place +# (outside of doxygen) the user can define a custom "cut" / "paste" string. +# Example: +# WARN_LINE_FORMAT = "'vi $file +$line'" +# See also: WARN_FORMAT +# The default value is: at line $line of file $file. + +WARN_LINE_FORMAT = "at line $line of file $file" + +# The WARN_LOGFILE tag can be used to specify a file to which warning and error +# messages should be written. If left blank the output is written to standard +# error (stderr). In case the file specified cannot be opened for writing the +# warning and error messages are written to standard error. When as file - is +# specified the warning and error messages are written to standard output +# (stdout). + +WARN_LOGFILE = + +#--------------------------------------------------------------------------- +# Configuration options related to the input files +#--------------------------------------------------------------------------- + +# The INPUT tag is used to specify the files and/or directories that contain +# documented source files. You may enter file names like myfile.cpp or +# directories like /usr/src/myproject. Separate the files or directories with +# spaces. See also FILE_PATTERNS and EXTENSION_MAPPING +# Note: If this tag is empty the current directory is searched. + +INPUT = + +# This tag can be used to specify the character encoding of the source files +# that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses +# libiconv (or the iconv built into libc) for the transcoding. See the libiconv +# documentation (see: +# https://www.gnu.org/software/libiconv/) for the list of possible encodings. +# See also: INPUT_FILE_ENCODING +# The default value is: UTF-8. + +INPUT_ENCODING = UTF-8 + +# This tag can be used to specify the character encoding of the source files +# that doxygen parses The INPUT_FILE_ENCODING tag can be used to specify +# character encoding on a per file pattern basis. Doxygen will compare the file +# name with each pattern and apply the encoding instead of the default +# INPUT_ENCODING) if there is a match. The character encodings are a list of the +# form: pattern=encoding (like *.php=ISO-8859-1). See cfg_input_encoding +# "INPUT_ENCODING" for further information on supported encodings. + +INPUT_FILE_ENCODING = + +# If the value of the INPUT tag contains directories, you can use the +# FILE_PATTERNS tag to specify one or more wildcard patterns (like *.cpp and +# *.h) to filter out the source-files in the directories. +# +# Note that for custom extensions or not directly supported extensions you also +# need to set EXTENSION_MAPPING for the extension otherwise the files are not +# read by doxygen. +# +# Note the list of default checked file patterns might differ from the list of +# default file extension mappings. +# +# If left blank the following patterns are tested:*.c, *.cc, *.cxx, *.cpp, +# *.c++, *.java, *.ii, *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h, +# *.hh, *.hxx, *.hpp, *.h++, *.l, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, +# *.inc, *.m, *.markdown, *.md, *.mm, *.dox (to be provided as doxygen C +# comment), *.py, *.pyw, *.f90, *.f95, *.f03, *.f08, *.f18, *.f, *.for, *.vhd, +# *.vhdl, *.ucf, *.qsf and *.ice. + +FILE_PATTERNS = *.c \ + *.cc \ + *.cxx \ + *.cpp \ + *.c++ \ + *.java \ + *.ii \ + *.ixx \ + *.ipp \ + *.i++ \ + *.inl \ + *.idl \ + *.ddl \ + *.odl \ + *.h \ + *.hh \ + *.hxx \ + *.hpp \ + *.h++ \ + *.l \ + *.cs \ + *.d \ + *.php \ + *.php4 \ + *.php5 \ + *.phtml \ + *.inc \ + *.m \ + *.markdown \ + *.md \ + *.mm \ + *.dox \ + *.py \ + *.pyw \ + *.f90 \ + *.f95 \ + *.f03 \ + *.f08 \ + *.f18 \ + *.f \ + *.for \ + *.vhd \ + *.vhdl \ + *.ucf \ + *.qsf \ + *.ice + +# The RECURSIVE tag can be used to specify whether or not subdirectories should +# be searched for input files as well. +# The default value is: NO. + +RECURSIVE = YES + +# The EXCLUDE tag can be used to specify files and/or directories that should be +# excluded from the INPUT source files. This way you can easily exclude a +# subdirectory from a directory tree whose root is specified with the INPUT tag. +# +# Note that relative paths are relative to the directory from which doxygen is +# run. + +EXCLUDE = include/splash.h \ + include/intense_milk.h + +# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or +# directories that are symbolic links (a Unix file system feature) are excluded +# from the input. +# The default value is: NO. + +EXCLUDE_SYMLINKS = NO + +# If the value of the INPUT tag contains directories, you can use the +# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude +# certain files from those directories. +# +# Note that the wildcards are matched against the file with absolute path, so to +# exclude all test directories for example use the pattern */test/* + +EXCLUDE_PATTERNS = + +# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names +# (namespaces, classes, functions, etc.) that should be excluded from the +# output. The symbol name can be a fully qualified name, a word, or if the +# wildcard * is used, a substring. Examples: ANamespace, AClass, +# ANamespace::AClass, ANamespace::*Test +# +# Note that the wildcards are matched against the file with absolute path, so to +# exclude all test directories use the pattern */test/* + +EXCLUDE_SYMBOLS = + +# The EXAMPLE_PATH tag can be used to specify one or more files or directories +# that contain example code fragments that are included (see the \include +# command). + +EXAMPLE_PATH = + +# If the value of the EXAMPLE_PATH tag contains directories, you can use the +# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp and +# *.h) to filter out the source-files in the directories. If left blank all +# files are included. + +EXAMPLE_PATTERNS = * + +# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be +# searched for input files to be used with the \include or \dontinclude commands +# irrespective of the value of the RECURSIVE tag. +# The default value is: NO. + +EXAMPLE_RECURSIVE = NO + +# The IMAGE_PATH tag can be used to specify one or more files or directories +# that contain images that are to be included in the documentation (see the +# \image command). + +IMAGE_PATH = + +# The INPUT_FILTER tag can be used to specify a program that doxygen should +# invoke to filter for each input file. Doxygen will invoke the filter program +# by executing (via popen()) the command: +# +# +# +# where is the value of the INPUT_FILTER tag, and is the +# name of an input file. Doxygen will then use the output that the filter +# program writes to standard output. If FILTER_PATTERNS is specified, this tag +# will be ignored. +# +# Note that the filter must not add or remove lines; it is applied before the +# code is scanned, but not when the output code is generated. If lines are added +# or removed, the anchors will not be placed correctly. +# +# Note that doxygen will use the data processed and written to standard output +# for further processing, therefore nothing else, like debug statements or used +# commands (so in case of a Windows batch file always use @echo OFF), should be +# written to standard output. +# +# Note that for custom extensions or not directly supported extensions you also +# need to set EXTENSION_MAPPING for the extension otherwise the files are not +# properly processed by doxygen. + +INPUT_FILTER = + +# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern +# basis. Doxygen will compare the file name with each pattern and apply the +# filter if there is a match. The filters are a list of the form: pattern=filter +# (like *.cpp=my_cpp_filter). See INPUT_FILTER for further information on how +# filters are used. If the FILTER_PATTERNS tag is empty or if none of the +# patterns match the file name, INPUT_FILTER is applied. +# +# Note that for custom extensions or not directly supported extensions you also +# need to set EXTENSION_MAPPING for the extension otherwise the files are not +# properly processed by doxygen. + +FILTER_PATTERNS = + +# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using +# INPUT_FILTER) will also be used to filter the input files that are used for +# producing the source files to browse (i.e. when SOURCE_BROWSER is set to YES). +# The default value is: NO. + +FILTER_SOURCE_FILES = NO + +# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file +# pattern. A pattern will override the setting for FILTER_PATTERN (if any) and +# it is also possible to disable source filtering for a specific pattern using +# *.ext= (so without naming a filter). +# This tag requires that the tag FILTER_SOURCE_FILES is set to YES. + +FILTER_SOURCE_PATTERNS = + +# If the USE_MDFILE_AS_MAINPAGE tag refers to the name of a markdown file that +# is part of the input, its contents will be placed on the main page +# (index.html). This can be useful if you have a project on for instance GitHub +# and want to reuse the introduction page also for the doxygen output. + +USE_MDFILE_AS_MAINPAGE = + +# The Fortran standard specifies that for fixed formatted Fortran code all +# characters from position 72 are to be considered as comment. A common +# extension is to allow longer lines before the automatic comment starts. The +# setting FORTRAN_COMMENT_AFTER will also make it possible that longer lines can +# be processed before the automatic comment starts. +# Minimum value: 7, maximum value: 10000, default value: 72. + +FORTRAN_COMMENT_AFTER = 72 + +#--------------------------------------------------------------------------- +# Configuration options related to source browsing +#--------------------------------------------------------------------------- + +# If the SOURCE_BROWSER tag is set to YES then a list of source files will be +# generated. Documented entities will be cross-referenced with these sources. +# +# Note: To get rid of all source code in the generated output, make sure that +# also VERBATIM_HEADERS is set to NO. +# The default value is: NO. + +SOURCE_BROWSER = NO + +# Setting the INLINE_SOURCES tag to YES will include the body of functions, +# classes and enums directly into the documentation. +# The default value is: NO. + +INLINE_SOURCES = NO + +# Setting the STRIP_CODE_COMMENTS tag to YES will instruct doxygen to hide any +# special comment blocks from generated source code fragments. Normal C, C++ and +# Fortran comments will always remain visible. +# The default value is: YES. + +STRIP_CODE_COMMENTS = YES + +# If the REFERENCED_BY_RELATION tag is set to YES then for each documented +# entity all documented functions referencing it will be listed. +# The default value is: NO. + +REFERENCED_BY_RELATION = NO + +# If the REFERENCES_RELATION tag is set to YES then for each documented function +# all documented entities called/used by that function will be listed. +# The default value is: NO. + +REFERENCES_RELATION = NO + +# If the REFERENCES_LINK_SOURCE tag is set to YES and SOURCE_BROWSER tag is set +# to YES then the hyperlinks from functions in REFERENCES_RELATION and +# REFERENCED_BY_RELATION lists will link to the source code. Otherwise they will +# link to the documentation. +# The default value is: YES. + +REFERENCES_LINK_SOURCE = YES + +# If SOURCE_TOOLTIPS is enabled (the default) then hovering a hyperlink in the +# source code will show a tooltip with additional information such as prototype, +# brief description and links to the definition and documentation. Since this +# will make the HTML file larger and loading of large files a bit slower, you +# can opt to disable this feature. +# The default value is: YES. +# This tag requires that the tag SOURCE_BROWSER is set to YES. + +SOURCE_TOOLTIPS = YES + +# If the USE_HTAGS tag is set to YES then the references to source code will +# point to the HTML generated by the htags(1) tool instead of doxygen built-in +# source browser. The htags tool is part of GNU's global source tagging system +# (see https://www.gnu.org/software/global/global.html). You will need version +# 4.8.6 or higher. +# +# To use it do the following: +# - Install the latest version of global +# - Enable SOURCE_BROWSER and USE_HTAGS in the configuration file +# - Make sure the INPUT points to the root of the source tree +# - Run doxygen as normal +# +# Doxygen will invoke htags (and that will in turn invoke gtags), so these +# tools must be available from the command line (i.e. in the search path). +# +# The result: instead of the source browser generated by doxygen, the links to +# source code will now point to the output of htags. +# The default value is: NO. +# This tag requires that the tag SOURCE_BROWSER is set to YES. + +USE_HTAGS = NO + +# If the VERBATIM_HEADERS tag is set the YES then doxygen will generate a +# verbatim copy of the header file for each class for which an include is +# specified. Set to NO to disable this. +# See also: Section \class. +# The default value is: YES. + +VERBATIM_HEADERS = YES + +#--------------------------------------------------------------------------- +# Configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- + +# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index of all +# compounds will be generated. Enable this if the project contains a lot of +# classes, structs, unions or interfaces. +# The default value is: YES. + +ALPHABETICAL_INDEX = YES + +# The IGNORE_PREFIX tag can be used to specify a prefix (or a list of prefixes) +# that should be ignored while generating the index headers. The IGNORE_PREFIX +# tag works for classes, function and member names. The entity will be placed in +# the alphabetical list under the first letter of the entity name that remains +# after removing the prefix. +# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. + +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the HTML output +#--------------------------------------------------------------------------- + +# If the GENERATE_HTML tag is set to YES, doxygen will generate HTML output +# The default value is: YES. + +GENERATE_HTML = YES + +# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. If a +# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of +# it. +# The default directory is: html. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_OUTPUT = html + +# The HTML_FILE_EXTENSION tag can be used to specify the file extension for each +# generated HTML page (for example: .htm, .php, .asp). +# The default value is: .html. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_FILE_EXTENSION = .html + +# The HTML_HEADER tag can be used to specify a user-defined HTML header file for +# each generated HTML page. If the tag is left blank doxygen will generate a +# standard header. +# +# To get valid HTML the header file that includes any scripts and style sheets +# that doxygen needs, which is dependent on the configuration options used (e.g. +# the setting GENERATE_TREEVIEW). It is highly recommended to start with a +# default header using +# doxygen -w html new_header.html new_footer.html new_stylesheet.css +# YourConfigFile +# and then modify the file new_header.html. See also section "Doxygen usage" +# for information on how to generate the default header that doxygen normally +# uses. +# Note: The header is subject to change so you typically have to regenerate the +# default header when upgrading to a newer version of doxygen. For a description +# of the possible markers and block names see the documentation. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_HEADER = + +# The HTML_FOOTER tag can be used to specify a user-defined HTML footer for each +# generated HTML page. If the tag is left blank doxygen will generate a standard +# footer. See HTML_HEADER for more information on how to generate a default +# footer and what special commands can be used inside the footer. See also +# section "Doxygen usage" for information on how to generate the default footer +# that doxygen normally uses. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_FOOTER = + +# The HTML_STYLESHEET tag can be used to specify a user-defined cascading style +# sheet that is used by each HTML page. It can be used to fine-tune the look of +# the HTML output. If left blank doxygen will generate a default style sheet. +# See also section "Doxygen usage" for information on how to generate the style +# sheet that doxygen normally uses. +# Note: It is recommended to use HTML_EXTRA_STYLESHEET instead of this tag, as +# it is more robust and this tag (HTML_STYLESHEET) will in the future become +# obsolete. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_STYLESHEET = + +# The HTML_EXTRA_STYLESHEET tag can be used to specify additional user-defined +# cascading style sheets that are included after the standard style sheets +# created by doxygen. Using this option one can overrule certain style aspects. +# This is preferred over using HTML_STYLESHEET since it does not replace the +# standard style sheet and is therefore more robust against future updates. +# Doxygen will copy the style sheet files to the output directory. +# Note: The order of the extra style sheet files is of importance (e.g. the last +# style sheet in the list overrules the setting of the previous ones in the +# list). +# Note: Since the styling of scrollbars can currently not be overruled in +# Webkit/Chromium, the styling will be left out of the default doxygen.css if +# one or more extra stylesheets have been specified. So if scrollbar +# customization is desired it has to be added explicitly. For an example see the +# documentation. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_EXTRA_STYLESHEET = + +# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or +# other source files which should be copied to the HTML output directory. Note +# that these files will be copied to the base HTML output directory. Use the +# $relpath^ marker in the HTML_HEADER and/or HTML_FOOTER files to load these +# files. In the HTML_STYLESHEET file, use the file name only. Also note that the +# files will be copied as-is; there are no commands or markers available. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_EXTRA_FILES = + +# The HTML_COLORSTYLE tag can be used to specify if the generated HTML output +# should be rendered with a dark or light theme. +# Possible values are: LIGHT always generate light mode output, DARK always +# generate dark mode output, AUTO_LIGHT automatically set the mode according to +# the user preference, use light mode if no preference is set (the default), +# AUTO_DARK automatically set the mode according to the user preference, use +# dark mode if no preference is set and TOGGLE allow to user to switch between +# light and dark mode via a button. +# The default value is: AUTO_LIGHT. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE = AUTO_LIGHT + +# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen +# will adjust the colors in the style sheet and background images according to +# this color. Hue is specified as an angle on a color-wheel, see +# https://en.wikipedia.org/wiki/Hue for more information. For instance the value +# 0 represents red, 60 is yellow, 120 is green, 180 is cyan, 240 is blue, 300 +# purple, and 360 is red again. +# Minimum value: 0, maximum value: 359, default value: 220. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_HUE = 220 + +# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of the colors +# in the HTML output. For a value of 0 the output will use gray-scales only. A +# value of 255 will produce the most vivid colors. +# Minimum value: 0, maximum value: 255, default value: 100. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_SAT = 100 + +# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to the +# luminance component of the colors in the HTML output. Values below 100 +# gradually make the output lighter, whereas values above 100 make the output +# darker. The value divided by 100 is the actual gamma applied, so 80 represents +# a gamma of 0.8, The value 220 represents a gamma of 2.2, and 100 does not +# change the gamma. +# Minimum value: 40, maximum value: 240, default value: 80. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_GAMMA = 80 + +# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML +# page will contain the date and time when the page was generated. Setting this +# to YES can help to show when doxygen was last run and thus if the +# documentation is up to date. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_TIMESTAMP = NO + +# If the HTML_DYNAMIC_MENUS tag is set to YES then the generated HTML +# documentation will contain a main index with vertical navigation menus that +# are dynamically created via JavaScript. If disabled, the navigation index will +# consists of multiple levels of tabs that are statically embedded in every HTML +# page. Disable this option to support browsers that do not have JavaScript, +# like the Qt help browser. +# The default value is: YES. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_DYNAMIC_MENUS = YES + +# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML +# documentation will contain sections that can be hidden and shown after the +# page has loaded. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_DYNAMIC_SECTIONS = NO + +# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of entries +# shown in the various tree structured indices initially; the user can expand +# and collapse entries dynamically later on. Doxygen will expand the tree to +# such a level that at most the specified number of entries are visible (unless +# a fully collapsed tree already exceeds this amount). So setting the number of +# entries 1 will produce a full collapsed tree by default. 0 is a special value +# representing an infinite number of entries and will result in a full expanded +# tree by default. +# Minimum value: 0, maximum value: 9999, default value: 100. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_INDEX_NUM_ENTRIES = 100 + +# If the GENERATE_DOCSET tag is set to YES, additional index files will be +# generated that can be used as input for Apple's Xcode 3 integrated development +# environment (see: +# https://developer.apple.com/xcode/), introduced with OSX 10.5 (Leopard). To +# create a documentation set, doxygen will generate a Makefile in the HTML +# output directory. Running make will produce the docset in that directory and +# running make install will install the docset in +# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find it at +# startup. See https://developer.apple.com/library/archive/featuredarticles/Doxy +# genXcode/_index.html for more information. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_DOCSET = NO + +# This tag determines the name of the docset feed. A documentation feed provides +# an umbrella under which multiple documentation sets from a single provider +# (such as a company or product suite) can be grouped. +# The default value is: Doxygen generated docs. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_FEEDNAME = "Doxygen generated docs" + +# This tag determines the URL of the docset feed. A documentation feed provides +# an umbrella under which multiple documentation sets from a single provider +# (such as a company or product suite) can be grouped. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_FEEDURL = + +# This tag specifies a string that should uniquely identify the documentation +# set bundle. This should be a reverse domain-name style string, e.g. +# com.mycompany.MyDocSet. Doxygen will append .docset to the name. +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_BUNDLE_ID = org.doxygen.Project + +# The DOCSET_PUBLISHER_ID tag specifies a string that should uniquely identify +# the documentation publisher. This should be a reverse domain-name style +# string, e.g. com.mycompany.MyDocSet.documentation. +# The default value is: org.doxygen.Publisher. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_PUBLISHER_ID = org.doxygen.Publisher + +# The DOCSET_PUBLISHER_NAME tag identifies the documentation publisher. +# The default value is: Publisher. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_PUBLISHER_NAME = Publisher + +# If the GENERATE_HTMLHELP tag is set to YES then doxygen generates three +# additional HTML index files: index.hhp, index.hhc, and index.hhk. The +# index.hhp is a project file that can be read by Microsoft's HTML Help Workshop +# on Windows. In the beginning of 2021 Microsoft took the original page, with +# a.o. the download links, offline the HTML help workshop was already many years +# in maintenance mode). You can download the HTML help workshop from the web +# archives at Installation executable (see: +# http://web.archive.org/web/20160201063255/http://download.microsoft.com/downlo +# ad/0/A/9/0A939EF6-E31C-430F-A3DF-DFAE7960D564/htmlhelp.exe). +# +# The HTML Help Workshop contains a compiler that can convert all HTML output +# generated by doxygen into a single compiled HTML file (.chm). Compiled HTML +# files are now used as the Windows 98 help format, and will replace the old +# Windows help format (.hlp) on all Windows platforms in the future. Compressed +# HTML files also contain an index, a table of contents, and you can search for +# words in the documentation. The HTML workshop also contains a viewer for +# compressed HTML files. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_HTMLHELP = NO + +# The CHM_FILE tag can be used to specify the file name of the resulting .chm +# file. You can add a path in front of the file if the result should not be +# written to the html output directory. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +CHM_FILE = + +# The HHC_LOCATION tag can be used to specify the location (absolute path +# including file name) of the HTML help compiler (hhc.exe). If non-empty, +# doxygen will try to run the HTML help compiler on the generated index.hhp. +# The file has to be specified with full path. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +HHC_LOCATION = + +# The GENERATE_CHI flag controls if a separate .chi index file is generated +# (YES) or that it should be included in the main .chm file (NO). +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +GENERATE_CHI = NO + +# The CHM_INDEX_ENCODING is used to encode HtmlHelp index (hhk), content (hhc) +# and project file content. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +CHM_INDEX_ENCODING = + +# The BINARY_TOC flag controls whether a binary table of contents is generated +# (YES) or a normal table of contents (NO) in the .chm file. Furthermore it +# enables the Previous and Next buttons. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +BINARY_TOC = NO + +# The TOC_EXPAND flag can be set to YES to add extra items for group members to +# the table of contents of the HTML help documentation and to the tree view. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +TOC_EXPAND = NO + +# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and +# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated that +# can be used as input for Qt's qhelpgenerator to generate a Qt Compressed Help +# (.qch) of the generated HTML documentation. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_QHP = NO + +# If the QHG_LOCATION tag is specified, the QCH_FILE tag can be used to specify +# the file name of the resulting .qch file. The path specified is relative to +# the HTML output folder. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QCH_FILE = + +# The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help +# Project output. For more information please see Qt Help Project / Namespace +# (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#namespace). +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_NAMESPACE = org.doxygen.Project + +# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt +# Help Project output. For more information please see Qt Help Project / Virtual +# Folders (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#virtual-folders). +# The default value is: doc. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_VIRTUAL_FOLDER = doc + +# If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom +# filter to add. For more information please see Qt Help Project / Custom +# Filters (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom-filters). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_CUST_FILTER_NAME = + +# The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the +# custom filter to add. For more information please see Qt Help Project / Custom +# Filters (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom-filters). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_CUST_FILTER_ATTRS = + +# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this +# project's filter section matches. Qt Help Project / Filter Attributes (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#filter-attributes). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_SECT_FILTER_ATTRS = + +# The QHG_LOCATION tag can be used to specify the location (absolute path +# including file name) of Qt's qhelpgenerator. If non-empty doxygen will try to +# run qhelpgenerator on the generated .qhp file. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHG_LOCATION = + +# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files will be +# generated, together with the HTML files, they form an Eclipse help plugin. To +# install this plugin and make it available under the help contents menu in +# Eclipse, the contents of the directory containing the HTML and XML files needs +# to be copied into the plugins directory of eclipse. The name of the directory +# within the plugins directory should be the same as the ECLIPSE_DOC_ID value. +# After copying Eclipse needs to be restarted before the help appears. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_ECLIPSEHELP = NO + +# A unique identifier for the Eclipse help plugin. When installing the plugin +# the directory name containing the HTML and XML files should also have this +# name. Each documentation set should have its own identifier. +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_ECLIPSEHELP is set to YES. + +ECLIPSE_DOC_ID = org.doxygen.Project + +# If you want full control over the layout of the generated HTML pages it might +# be necessary to disable the index and replace it with your own. The +# DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) at top +# of each HTML page. A value of NO enables the index and the value YES disables +# it. Since the tabs in the index contain the same information as the navigation +# tree, you can set this option to YES if you also set GENERATE_TREEVIEW to YES. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +DISABLE_INDEX = NO + +# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index +# structure should be generated to display hierarchical information. If the tag +# value is set to YES, a side panel will be generated containing a tree-like +# index structure (just like the one that is generated for HTML Help). For this +# to work a browser that supports JavaScript, DHTML, CSS and frames is required +# (i.e. any modern browser). Windows users are probably better off using the +# HTML help feature. Via custom style sheets (see HTML_EXTRA_STYLESHEET) one can +# further fine tune the look of the index (see "Fine-tuning the output"). As an +# example, the default style sheet generated by doxygen has an example that +# shows how to put an image at the root of the tree instead of the PROJECT_NAME. +# Since the tree basically has the same information as the tab index, you could +# consider setting DISABLE_INDEX to YES when enabling this option. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_TREEVIEW = NO + +# When both GENERATE_TREEVIEW and DISABLE_INDEX are set to YES, then the +# FULL_SIDEBAR option determines if the side bar is limited to only the treeview +# area (value NO) or if it should extend to the full height of the window (value +# YES). Setting this to YES gives a layout similar to +# https://docs.readthedocs.io with more room for contents, but less room for the +# project logo, title, and description. If either GENERATE_TREEVIEW or +# DISABLE_INDEX is set to NO, this option has no effect. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +FULL_SIDEBAR = NO + +# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values that +# doxygen will group on one line in the generated HTML documentation. +# +# Note that a value of 0 will completely suppress the enum values from appearing +# in the overview section. +# Minimum value: 0, maximum value: 20, default value: 4. +# This tag requires that the tag GENERATE_HTML is set to YES. + +ENUM_VALUES_PER_LINE = 4 + +# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be used +# to set the initial width (in pixels) of the frame in which the tree is shown. +# Minimum value: 0, maximum value: 1500, default value: 250. +# This tag requires that the tag GENERATE_HTML is set to YES. + +TREEVIEW_WIDTH = 250 + +# If the EXT_LINKS_IN_WINDOW option is set to YES, doxygen will open links to +# external symbols imported via tag files in a separate window. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +EXT_LINKS_IN_WINDOW = NO + +# If the OBFUSCATE_EMAILS tag is set to YES, doxygen will obfuscate email +# addresses. +# The default value is: YES. +# This tag requires that the tag GENERATE_HTML is set to YES. + +OBFUSCATE_EMAILS = YES + +# If the HTML_FORMULA_FORMAT option is set to svg, doxygen will use the pdf2svg +# tool (see https://github.com/dawbarton/pdf2svg) or inkscape (see +# https://inkscape.org) to generate formulas as SVG images instead of PNGs for +# the HTML output. These images will generally look nicer at scaled resolutions. +# Possible values are: png (the default) and svg (looks nicer but requires the +# pdf2svg or inkscape tool). +# The default value is: png. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_FORMULA_FORMAT = png + +# Use this tag to change the font size of LaTeX formulas included as images in +# the HTML documentation. When you change the font size after a successful +# doxygen run you need to manually remove any form_*.png images from the HTML +# output directory to force them to be regenerated. +# Minimum value: 8, maximum value: 50, default value: 10. +# This tag requires that the tag GENERATE_HTML is set to YES. + +FORMULA_FONTSIZE = 10 + +# The FORMULA_MACROFILE can contain LaTeX \newcommand and \renewcommand commands +# to create new LaTeX commands to be used in formulas as building blocks. See +# the section "Including formulas" for details. + +FORMULA_MACROFILE = + +# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see +# https://www.mathjax.org) which uses client side JavaScript for the rendering +# instead of using pre-rendered bitmaps. Use this if you do not have LaTeX +# installed or if you want to formulas look prettier in the HTML output. When +# enabled you may also need to install MathJax separately and configure the path +# to it using the MATHJAX_RELPATH option. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +USE_MATHJAX = NO + +# With MATHJAX_VERSION it is possible to specify the MathJax version to be used. +# Note that the different versions of MathJax have different requirements with +# regards to the different settings, so it is possible that also other MathJax +# settings have to be changed when switching between the different MathJax +# versions. +# Possible values are: MathJax_2 and MathJax_3. +# The default value is: MathJax_2. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_VERSION = MathJax_2 + +# When MathJax is enabled you can set the default output format to be used for +# the MathJax output. For more details about the output format see MathJax +# version 2 (see: +# http://docs.mathjax.org/en/v2.7-latest/output.html) and MathJax version 3 +# (see: +# http://docs.mathjax.org/en/latest/web/components/output.html). +# Possible values are: HTML-CSS (which is slower, but has the best +# compatibility. This is the name for Mathjax version 2, for MathJax version 3 +# this will be translated into chtml), NativeMML (i.e. MathML. Only supported +# for NathJax 2. For MathJax version 3 chtml will be used instead.), chtml (This +# is the name for Mathjax version 3, for MathJax version 2 this will be +# translated into HTML-CSS) and SVG. +# The default value is: HTML-CSS. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_FORMAT = HTML-CSS + +# When MathJax is enabled you need to specify the location relative to the HTML +# output directory using the MATHJAX_RELPATH option. The destination directory +# should contain the MathJax.js script. For instance, if the mathjax directory +# is located at the same level as the HTML output directory, then +# MATHJAX_RELPATH should be ../mathjax. The default value points to the MathJax +# Content Delivery Network so you can quickly see the result without installing +# MathJax. However, it is strongly recommended to install a local copy of +# MathJax from https://www.mathjax.org before deployment. The default value is: +# - in case of MathJax version 2: https://cdn.jsdelivr.net/npm/mathjax@2 +# - in case of MathJax version 3: https://cdn.jsdelivr.net/npm/mathjax@3 +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_RELPATH = + +# The MATHJAX_EXTENSIONS tag can be used to specify one or more MathJax +# extension names that should be enabled during MathJax rendering. For example +# for MathJax version 2 (see +# https://docs.mathjax.org/en/v2.7-latest/tex.html#tex-and-latex-extensions): +# MATHJAX_EXTENSIONS = TeX/AMSmath TeX/AMSsymbols +# For example for MathJax version 3 (see +# http://docs.mathjax.org/en/latest/input/tex/extensions/index.html): +# MATHJAX_EXTENSIONS = ams +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_EXTENSIONS = + +# The MATHJAX_CODEFILE tag can be used to specify a file with javascript pieces +# of code that will be used on startup of the MathJax code. See the MathJax site +# (see: +# http://docs.mathjax.org/en/v2.7-latest/output.html) for more details. For an +# example see the documentation. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_CODEFILE = + +# When the SEARCHENGINE tag is enabled doxygen will generate a search box for +# the HTML output. The underlying search engine uses javascript and DHTML and +# should work on any modern browser. Note that when using HTML help +# (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets (GENERATE_DOCSET) +# there is already a search function so this one should typically be disabled. +# For large projects the javascript based search engine can be slow, then +# enabling SERVER_BASED_SEARCH may provide a better solution. It is possible to +# search using the keyboard; to jump to the search box use + S +# (what the is depends on the OS and browser, but it is typically +# , /
  • +``` + +@note Both the default overflow scrolling behavior in this theme and the interactive editor enabled by `INTERACTIVE_SVG` are unsatisfying workarounds IMHO. Consider designing your graphs to be narrow enough to fit the page to avoid scrolling. + +## Disable Dark Mode {#tricks-darkmode} + +If you don't want the theme to automatically switch to dark mode depending on the browser preference, +you can disable dark mode by adding the `light-mode` class to the html-tag in the header template: + +```html + +``` + +The same can be done to always enable dark-mode: + +```html + +``` + + +@warning This only works if you don't use the dark-mode toggle extension. + +## Choosing Sidebar Width {#tricks-sidebar} + +If you have enabled the sidebar-only theme variant, make sure to carefully choose a proper width for your sidebar. +It should be wide enough to hold the icon, project title and version number. If the content is too wide, it will be +cut off. + +```css +html { + /* Make sure sidebar is wide enough to contain the page title (logo + title + version) */ + --side-nav-fixed-width: 335px; +} +``` + +The chosen width should also be set in the Doxyfile: + +``` +# Doxyfile +TREEVIEW_WIDTH = 335 +``` + +## Formatting Tables {#tricks-tables} + +By default tables in this theme are left-aligned and as wide as required to fit their content. +Those properties can be changed for individual tables. + +### Centering + +Tables can be centered by wrapping them in the `
    ` HTML-tag. + +
    + +- Code + ```md +
    + | This table | is centered | + |------------|----------------------| + | test 1 | test 2 | +
    + ``` +- Result +
    + | This table | is centered | + |------------|----------------------| + | test 1 | test 2 | +
    + +
    + + + +### Full Width + +To make tables span the full width of the page, no matter how wide the content is, wrap the table in the `full_width_table` CSS class. + +@warning Apply with caution! This breaks the overflow scrolling of the table. Content might be cut of on small screens! + +
    + +- Code + ```md +
    + | This table | spans the full width | + |------------|----------------------| + | test 1 | test 2 | +
    + ``` +- Result +
    + | This table | spans the full width | + |------------|----------------------| + | test 1 | test 2 | +
    + +
    + + + +Read Next: [Example](https://jothepro.github.io/doxygen-awesome-css/class_my_library_1_1_example.html) + \ No newline at end of file diff --git a/doxygen-awesome-css/doxygen-awesome-darkmode-toggle.js b/doxygen-awesome-css/doxygen-awesome-darkmode-toggle.js new file mode 100644 index 0000000..40fe2d3 --- /dev/null +++ b/doxygen-awesome-css/doxygen-awesome-darkmode-toggle.js @@ -0,0 +1,157 @@ +/** + +Doxygen Awesome +https://github.com/jothepro/doxygen-awesome-css + +MIT License + +Copyright (c) 2021 - 2023 jothepro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. + +*/ + +class DoxygenAwesomeDarkModeToggle extends HTMLElement { + // SVG icons from https://fonts.google.com/icons + // Licensed under the Apache 2.0 license: + // https://www.apache.org/licenses/LICENSE-2.0.html + static lightModeIcon = `` + static darkModeIcon = `` + static title = "Toggle Light/Dark Mode" + + static prefersLightModeInDarkModeKey = "prefers-light-mode-in-dark-mode" + static prefersDarkModeInLightModeKey = "prefers-dark-mode-in-light-mode" + + static _staticConstructor = function() { + DoxygenAwesomeDarkModeToggle.enableDarkMode(DoxygenAwesomeDarkModeToggle.userPreference) + // Update the color scheme when the browsers preference changes + // without user interaction on the website. + window.matchMedia('(prefers-color-scheme: dark)').addEventListener('change', event => { + DoxygenAwesomeDarkModeToggle.onSystemPreferenceChanged() + }) + // Update the color scheme when the tab is made visible again. + // It is possible that the appearance was changed in another tab + // while this tab was in the background. + document.addEventListener("visibilitychange", visibilityState => { + if (document.visibilityState === 'visible') { + DoxygenAwesomeDarkModeToggle.onSystemPreferenceChanged() + } + }); + }() + + static init() { + $(function() { + $(document).ready(function() { + const toggleButton = document.createElement('doxygen-awesome-dark-mode-toggle') + toggleButton.title = DoxygenAwesomeDarkModeToggle.title + toggleButton.updateIcon() + + window.matchMedia('(prefers-color-scheme: dark)').addEventListener('change', event => { + toggleButton.updateIcon() + }) + document.addEventListener("visibilitychange", visibilityState => { + if (document.visibilityState === 'visible') { + toggleButton.updateIcon() + } + }); + + $(document).ready(function(){ + document.getElementById("MSearchBox").parentNode.appendChild(toggleButton) + }) + $(window).resize(function(){ + document.getElementById("MSearchBox").parentNode.appendChild(toggleButton) + }) + }) + }) + } + + constructor() { + super(); + this.onclick=this.toggleDarkMode + } + + /** + * @returns `true` for dark-mode, `false` for light-mode system preference + */ + static get systemPreference() { + return window.matchMedia('(prefers-color-scheme: dark)').matches + } + + /** + * @returns `true` for dark-mode, `false` for light-mode user preference + */ + static get userPreference() { + return (!DoxygenAwesomeDarkModeToggle.systemPreference && localStorage.getItem(DoxygenAwesomeDarkModeToggle.prefersDarkModeInLightModeKey)) || + (DoxygenAwesomeDarkModeToggle.systemPreference && !localStorage.getItem(DoxygenAwesomeDarkModeToggle.prefersLightModeInDarkModeKey)) + } + + static set userPreference(userPreference) { + DoxygenAwesomeDarkModeToggle.darkModeEnabled = userPreference + if(!userPreference) { + if(DoxygenAwesomeDarkModeToggle.systemPreference) { + localStorage.setItem(DoxygenAwesomeDarkModeToggle.prefersLightModeInDarkModeKey, true) + } else { + localStorage.removeItem(DoxygenAwesomeDarkModeToggle.prefersDarkModeInLightModeKey) + } + } else { + if(!DoxygenAwesomeDarkModeToggle.systemPreference) { + localStorage.setItem(DoxygenAwesomeDarkModeToggle.prefersDarkModeInLightModeKey, true) + } else { + localStorage.removeItem(DoxygenAwesomeDarkModeToggle.prefersLightModeInDarkModeKey) + } + } + DoxygenAwesomeDarkModeToggle.onUserPreferenceChanged() + } + + static enableDarkMode(enable) { + if(enable) { + DoxygenAwesomeDarkModeToggle.darkModeEnabled = true + document.documentElement.classList.add("dark-mode") + document.documentElement.classList.remove("light-mode") + } else { + DoxygenAwesomeDarkModeToggle.darkModeEnabled = false + document.documentElement.classList.remove("dark-mode") + document.documentElement.classList.add("light-mode") + } + } + + static onSystemPreferenceChanged() { + DoxygenAwesomeDarkModeToggle.darkModeEnabled = DoxygenAwesomeDarkModeToggle.userPreference + DoxygenAwesomeDarkModeToggle.enableDarkMode(DoxygenAwesomeDarkModeToggle.darkModeEnabled) + } + + static onUserPreferenceChanged() { + DoxygenAwesomeDarkModeToggle.enableDarkMode(DoxygenAwesomeDarkModeToggle.darkModeEnabled) + } + + toggleDarkMode() { + DoxygenAwesomeDarkModeToggle.userPreference = !DoxygenAwesomeDarkModeToggle.userPreference + this.updateIcon() + } + + updateIcon() { + if(DoxygenAwesomeDarkModeToggle.darkModeEnabled) { + this.innerHTML = DoxygenAwesomeDarkModeToggle.darkModeIcon + } else { + this.innerHTML = DoxygenAwesomeDarkModeToggle.lightModeIcon + } + } +} + +customElements.define("doxygen-awesome-dark-mode-toggle", DoxygenAwesomeDarkModeToggle); diff --git a/doxygen-awesome-css/doxygen-awesome-fragment-copy-button.js b/doxygen-awesome-css/doxygen-awesome-fragment-copy-button.js new file mode 100644 index 0000000..86c16fd --- /dev/null +++ b/doxygen-awesome-css/doxygen-awesome-fragment-copy-button.js @@ -0,0 +1,85 @@ +/** + +Doxygen Awesome +https://github.com/jothepro/doxygen-awesome-css + +MIT License + +Copyright (c) 2022 - 2023 jothepro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. + +*/ + +class DoxygenAwesomeFragmentCopyButton extends HTMLElement { + constructor() { + super(); + this.onclick=this.copyContent + } + static title = "Copy to clipboard" + static copyIcon = `` + static successIcon = `` + static successDuration = 980 + static init() { + $(function() { + $(document).ready(function() { + if(navigator.clipboard) { + const fragments = document.getElementsByClassName("fragment") + for(const fragment of fragments) { + const fragmentWrapper = document.createElement("div") + fragmentWrapper.className = "doxygen-awesome-fragment-wrapper" + const fragmentCopyButton = document.createElement("doxygen-awesome-fragment-copy-button") + fragmentCopyButton.innerHTML = DoxygenAwesomeFragmentCopyButton.copyIcon + fragmentCopyButton.title = DoxygenAwesomeFragmentCopyButton.title + + fragment.parentNode.replaceChild(fragmentWrapper, fragment) + fragmentWrapper.appendChild(fragment) + fragmentWrapper.appendChild(fragmentCopyButton) + + } + } + }) + }) + } + + + copyContent() { + const content = this.previousSibling.cloneNode(true) + // filter out line number from file listings + content.querySelectorAll(".lineno, .ttc").forEach((node) => { + node.remove() + }) + let textContent = content.textContent + // remove trailing newlines that appear in file listings + let numberOfTrailingNewlines = 0 + while(textContent.charAt(textContent.length - (numberOfTrailingNewlines + 1)) == '\n') { + numberOfTrailingNewlines++; + } + textContent = textContent.substring(0, textContent.length - numberOfTrailingNewlines) + navigator.clipboard.writeText(textContent); + this.classList.add("success") + this.innerHTML = DoxygenAwesomeFragmentCopyButton.successIcon + window.setTimeout(() => { + this.classList.remove("success") + this.innerHTML = DoxygenAwesomeFragmentCopyButton.copyIcon + }, DoxygenAwesomeFragmentCopyButton.successDuration); + } +} + +customElements.define("doxygen-awesome-fragment-copy-button", DoxygenAwesomeFragmentCopyButton) diff --git a/doxygen-awesome-css/doxygen-awesome-interactive-toc.js b/doxygen-awesome-css/doxygen-awesome-interactive-toc.js new file mode 100644 index 0000000..20a9669 --- /dev/null +++ b/doxygen-awesome-css/doxygen-awesome-interactive-toc.js @@ -0,0 +1,81 @@ +/** + +Doxygen Awesome +https://github.com/jothepro/doxygen-awesome-css + +MIT License + +Copyright (c) 2022 - 2023 jothepro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. + +*/ + +class DoxygenAwesomeInteractiveToc { + static topOffset = 38 + static hideMobileMenu = true + static headers = [] + + static init() { + window.addEventListener("load", () => { + let toc = document.querySelector(".contents > .toc") + if(toc) { + toc.classList.add("interactive") + if(!DoxygenAwesomeInteractiveToc.hideMobileMenu) { + toc.classList.add("open") + } + document.querySelector(".contents > .toc > h3")?.addEventListener("click", () => { + if(toc.classList.contains("open")) { + toc.classList.remove("open") + } else { + toc.classList.add("open") + } + }) + + document.querySelectorAll(".contents > .toc > ul a").forEach((node) => { + let id = node.getAttribute("href").substring(1) + DoxygenAwesomeInteractiveToc.headers.push({ + node: node, + headerNode: document.getElementById(id) + }) + + document.getElementById("doc-content")?.addEventListener("scroll", () => { + DoxygenAwesomeInteractiveToc.update() + }) + }) + DoxygenAwesomeInteractiveToc.update() + } + }) + } + + static update() { + let active = DoxygenAwesomeInteractiveToc.headers[0]?.node + DoxygenAwesomeInteractiveToc.headers.forEach((header) => { + let position = header.headerNode.getBoundingClientRect().top + header.node.classList.remove("active") + header.node.classList.remove("aboveActive") + if(position < DoxygenAwesomeInteractiveToc.topOffset) { + active = header.node + active?.classList.add("aboveActive") + } + }) + active?.classList.add("active") + active?.classList.remove("aboveActive") + } +} \ No newline at end of file diff --git a/doxygen-awesome-css/doxygen-awesome-paragraph-link.js b/doxygen-awesome-css/doxygen-awesome-paragraph-link.js new file mode 100644 index 0000000..e53d132 --- /dev/null +++ b/doxygen-awesome-css/doxygen-awesome-paragraph-link.js @@ -0,0 +1,51 @@ +/** + +Doxygen Awesome +https://github.com/jothepro/doxygen-awesome-css + +MIT License + +Copyright (c) 2022 - 2023 jothepro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. + +*/ + +class DoxygenAwesomeParagraphLink { + // Icon from https://fonts.google.com/icons + // Licensed under the Apache 2.0 license: + // https://www.apache.org/licenses/LICENSE-2.0.html + static icon = `` + static title = "Permanent Link" + static init() { + $(function() { + $(document).ready(function() { + document.querySelectorAll(".contents a.anchor[id], .contents .groupheader > a[id]").forEach((node) => { + let anchorlink = document.createElement("a") + anchorlink.setAttribute("href", `#${node.getAttribute("id")}`) + anchorlink.setAttribute("title", DoxygenAwesomeParagraphLink.title) + anchorlink.classList.add("anchorlink") + node.classList.add("anchor") + anchorlink.innerHTML = DoxygenAwesomeParagraphLink.icon + node.parentElement.appendChild(anchorlink) + }) + }) + }) + } +} diff --git a/doxygen-awesome-css/doxygen-awesome-sidebar-only-darkmode-toggle.css b/doxygen-awesome-css/doxygen-awesome-sidebar-only-darkmode-toggle.css new file mode 100644 index 0000000..d207446 --- /dev/null +++ b/doxygen-awesome-css/doxygen-awesome-sidebar-only-darkmode-toggle.css @@ -0,0 +1,40 @@ + +/** + +Doxygen Awesome +https://github.com/jothepro/doxygen-awesome-css + +MIT License + +Copyright (c) 2021 - 2023 jothepro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. + +*/ + +@media screen and (min-width: 768px) { + + #MSearchBox { + width: calc(var(--side-nav-fixed-width) - calc(2 * var(--spacing-medium)) - var(--searchbar-height) - 1px); + } + + #MSearchField { + width: calc(var(--side-nav-fixed-width) - calc(2 * var(--spacing-medium)) - 66px - var(--searchbar-height)); + } +} diff --git a/doxygen-awesome-css/doxygen-awesome-sidebar-only.css b/doxygen-awesome-css/doxygen-awesome-sidebar-only.css new file mode 100644 index 0000000..f58fcbe --- /dev/null +++ b/doxygen-awesome-css/doxygen-awesome-sidebar-only.css @@ -0,0 +1,115 @@ +/** + +Doxygen Awesome +https://github.com/jothepro/doxygen-awesome-css + +MIT License + +Copyright (c) 2021 - 2023 jothepro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. + + */ + +html { + /* side nav width. MUST be = `TREEVIEW_WIDTH`. + * Make sure it is wide enough to contain the page title (logo + title + version) + */ + --side-nav-fixed-width: 335px; + --menu-display: none; + + --top-height: 120px; + --toc-sticky-top: -25px; + --toc-max-height: calc(100vh - 2 * var(--spacing-medium) - 25px); +} + +#projectname { + white-space: nowrap; +} + + +@media screen and (min-width: 768px) { + html { + --searchbar-background: var(--page-background-color); + } + + #side-nav { + min-width: var(--side-nav-fixed-width); + max-width: var(--side-nav-fixed-width); + top: var(--top-height); + overflow: visible; + } + + #nav-tree, #side-nav { + height: calc(100vh - var(--top-height)) !important; + } + + #nav-tree { + padding: 0; + } + + #top { + display: block; + border-bottom: none; + height: var(--top-height); + margin-bottom: calc(0px - var(--top-height)); + max-width: var(--side-nav-fixed-width); + overflow: hidden; + background: var(--side-nav-background); + } + #main-nav { + float: left; + padding-right: 0; + } + + .ui-resizable-handle { + cursor: default; + width: 1px !important; + box-shadow: 0 calc(-2 * var(--top-height)) 0 0 var(--separator-color); + } + + #nav-path { + position: fixed; + right: 0; + left: var(--side-nav-fixed-width); + bottom: 0; + width: auto; + } + + #doc-content { + height: calc(100vh - 31px) !important; + padding-bottom: calc(3 * var(--spacing-large)); + padding-top: calc(var(--top-height) - 80px); + box-sizing: border-box; + margin-left: var(--side-nav-fixed-width) !important; + } + + #MSearchBox { + width: calc(var(--side-nav-fixed-width) - calc(2 * var(--spacing-medium))); + } + + #MSearchField { + width: calc(var(--side-nav-fixed-width) - calc(2 * var(--spacing-medium)) - 65px); + } + + #MSearchResultsWindow { + left: var(--spacing-medium) !important; + right: auto; + } +} diff --git a/doxygen-awesome-css/doxygen-awesome-tabs.js b/doxygen-awesome-css/doxygen-awesome-tabs.js new file mode 100644 index 0000000..8e725b2 --- /dev/null +++ b/doxygen-awesome-css/doxygen-awesome-tabs.js @@ -0,0 +1,70 @@ +/** + +Doxygen Awesome +https://github.com/jothepro/doxygen-awesome-css + +MIT License + +Copyright (c) 2023 jothepro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. + +*/ + +class DoxygenAwesomeTabs { + + static init() { + window.addEventListener("load", () => { + document.querySelectorAll(".tabbed:not(:empty)").forEach((tabbed, tabbedIndex) => { + let tabLinkList = [] + tabbed.querySelectorAll("li").forEach((tab, tabIndex) => { + tab.id = "tab_" + tabbedIndex + "_" + tabIndex + let header = tab.querySelector(".tab-title") + let tabLink = document.createElement("button") + tabLink.classList.add("tab-button") + tabLink.appendChild(header) + tabLink.addEventListener("click", () => { + tabbed.querySelectorAll("li").forEach((tab) => { + tab.classList.remove("selected") + }) + tabLinkList.forEach((tabLink) => { + tabLink.classList.remove("active") + }) + tab.classList.add("selected") + tabLink.classList.add("active") + }) + tabLinkList.push(tabLink) + if(tabIndex == 0) { + tab.classList.add("selected") + tabLink.classList.add("active") + } + }) + let tabsOverview = document.createElement("div") + tabsOverview.classList.add("tabs-overview") + let tabsOverviewContainer = document.createElement("div") + tabsOverviewContainer.classList.add("tabs-overview-container") + tabLinkList.forEach((tabLink) => { + tabsOverview.appendChild(tabLink) + }) + tabsOverviewContainer.appendChild(tabsOverview) + tabbed.before(tabsOverviewContainer) + }) + }) + } +} \ No newline at end of file diff --git a/doxygen-awesome-css/doxygen-awesome.css b/doxygen-awesome-css/doxygen-awesome.css new file mode 100644 index 0000000..e8399cb --- /dev/null +++ b/doxygen-awesome-css/doxygen-awesome.css @@ -0,0 +1,2522 @@ +/** + +Doxygen Awesome +https://github.com/jothepro/doxygen-awesome-css + +MIT License + +Copyright (c) 2021 - 2023 jothepro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. + +*/ + +html { + /* primary theme color. This will affect the entire websites color scheme: links, arrows, labels, ... */ + --primary-color: #1779c4; + --primary-dark-color: #335c80; + --primary-light-color: #70b1e9; + + /* page base colors */ + --page-background-color: #ffffff; + --page-foreground-color: #2f4153; + --page-secondary-foreground-color: #6f7e8e; + + /* color for all separators on the website: hr, borders, ... */ + --separator-color: #dedede; + + /* border radius for all rounded components. Will affect many components, like dropdowns, memitems, codeblocks, ... */ + --border-radius-large: 8px; + --border-radius-small: 4px; + --border-radius-medium: 6px; + + /* default spacings. Most components reference these values for spacing, to provide uniform spacing on the page. */ + --spacing-small: 5px; + --spacing-medium: 10px; + --spacing-large: 16px; + + /* default box shadow used for raising an element above the normal content. Used in dropdowns, search result, ... */ + --box-shadow: 0 2px 8px 0 rgba(0,0,0,.075); + + --odd-color: rgba(0,0,0,.028); + + /* font-families. will affect all text on the website + * font-family: the normal font for text, headlines, menus + * font-family-monospace: used for preformatted text in memtitle, code, fragments + */ + --font-family: -apple-system,BlinkMacSystemFont,Segoe UI,Roboto,Oxygen,Ubuntu,Cantarell,Fira Sans,Droid Sans,Helvetica Neue,sans-serif; + --font-family-monospace: ui-monospace,SFMono-Regular,SF Mono,Menlo,Consolas,Liberation Mono,monospace; + + /* font sizes */ + --page-font-size: 15.6px; + --navigation-font-size: 14.4px; + --toc-font-size: 13.4px; + --code-font-size: 14px; /* affects code, fragment */ + --title-font-size: 22px; + + /* content text properties. These only affect the page content, not the navigation or any other ui elements */ + --content-line-height: 27px; + /* The content is centered and constraint in it's width. To make the content fill the whole page, set the variable to auto.*/ + --content-maxwidth: 1050px; + --table-line-height: 24px; + --toc-sticky-top: var(--spacing-medium); + --toc-width: 200px; + --toc-max-height: calc(100vh - 2 * var(--spacing-medium) - 85px); + + /* colors for various content boxes: @warning, @note, @deprecated @bug */ + --warning-color: #f8d1cc; + --warning-color-dark: #b61825; + --warning-color-darker: #75070f; + --note-color: #faf3d8; + --note-color-dark: #f3a600; + --note-color-darker: #5f4204; + --todo-color: #e4f3ff; + --todo-color-dark: #1879C4; + --todo-color-darker: #274a5c; + --deprecated-color: #ecf0f3; + --deprecated-color-dark: #5b6269; + --deprecated-color-darker: #43454a; + --bug-color: #e4dafd; + --bug-color-dark: #5b2bdd; + --bug-color-darker: #2a0d72; + --invariant-color: #d8f1e3; + --invariant-color-dark: #44b86f; + --invariant-color-darker: #265532; + + /* blockquote colors */ + --blockquote-background: #f8f9fa; + --blockquote-foreground: #636568; + + /* table colors */ + --tablehead-background: #f1f1f1; + --tablehead-foreground: var(--page-foreground-color); + + /* menu-display: block | none + * Visibility of the top navigation on screens >= 768px. On smaller screen the menu is always visible. + * `GENERATE_TREEVIEW` MUST be enabled! + */ + --menu-display: block; + + --menu-focus-foreground: var(--page-background-color); + --menu-focus-background: var(--primary-color); + --menu-selected-background: rgba(0,0,0,.05); + + + --header-background: var(--page-background-color); + --header-foreground: var(--page-foreground-color); + + /* searchbar colors */ + --searchbar-background: var(--side-nav-background); + --searchbar-foreground: var(--page-foreground-color); + + /* searchbar size + * (`searchbar-width` is only applied on screens >= 768px. + * on smaller screens the searchbar will always fill the entire screen width) */ + --searchbar-height: 33px; + --searchbar-width: 210px; + --searchbar-border-radius: var(--searchbar-height); + + /* code block colors */ + --code-background: #f5f5f5; + --code-foreground: var(--page-foreground-color); + + /* fragment colors */ + --fragment-background: #F8F9FA; + --fragment-foreground: #37474F; + --fragment-keyword: #bb6bb2; + --fragment-keywordtype: #8258b3; + --fragment-keywordflow: #d67c3b; + --fragment-token: #438a59; + --fragment-comment: #969696; + --fragment-link: #5383d6; + --fragment-preprocessor: #46aaa5; + --fragment-linenumber-color: #797979; + --fragment-linenumber-background: #f4f4f5; + --fragment-linenumber-border: #e3e5e7; + --fragment-lineheight: 20px; + + /* sidebar navigation (treeview) colors */ + --side-nav-background: #fbfbfb; + --side-nav-foreground: var(--page-foreground-color); + --side-nav-arrow-opacity: 0; + --side-nav-arrow-hover-opacity: 0.9; + + --toc-background: var(--side-nav-background); + --toc-foreground: var(--side-nav-foreground); + + /* height of an item in any tree / collapsible table */ + --tree-item-height: 30px; + + --memname-font-size: var(--code-font-size); + --memtitle-font-size: 18px; + + --webkit-scrollbar-size: 7px; + --webkit-scrollbar-padding: 4px; + --webkit-scrollbar-color: var(--separator-color); +} + +@media screen and (max-width: 767px) { + html { + --page-font-size: 16px; + --navigation-font-size: 16px; + --toc-font-size: 15px; + --code-font-size: 15px; /* affects code, fragment */ + --title-font-size: 22px; + } +} + +@media (prefers-color-scheme: dark) { + html:not(.light-mode) { + color-scheme: dark; + + --primary-color: #1982d2; + --primary-dark-color: #86a9c4; + --primary-light-color: #4779ac; + + --box-shadow: 0 2px 8px 0 rgba(0,0,0,.35); + + --odd-color: rgba(100,100,100,.06); + + --menu-selected-background: rgba(0,0,0,.4); + + --page-background-color: #1C1D1F; + --page-foreground-color: #d2dbde; + --page-secondary-foreground-color: #859399; + --separator-color: #38393b; + --side-nav-background: #252628; + + --code-background: #2a2c2f; + + --tablehead-background: #2a2c2f; + + --blockquote-background: #222325; + --blockquote-foreground: #7e8c92; + + --warning-color: #2e1917; + --warning-color-dark: #ad2617; + --warning-color-darker: #f5b1aa; + --note-color: #3b2e04; + --note-color-dark: #f1b602; + --note-color-darker: #ceb670; + --todo-color: #163750; + --todo-color-dark: #1982D2; + --todo-color-darker: #dcf0fa; + --deprecated-color: #2e323b; + --deprecated-color-dark: #738396; + --deprecated-color-darker: #abb0bd; + --bug-color: #2a2536; + --bug-color-dark: #7661b3; + --bug-color-darker: #ae9ed6; + --invariant-color: #303a35; + --invariant-color-dark: #76ce96; + --invariant-color-darker: #cceed5; + + --fragment-background: #282c34; + --fragment-foreground: #dbe4eb; + --fragment-keyword: #cc99cd; + --fragment-keywordtype: #ab99cd; + --fragment-keywordflow: #e08000; + --fragment-token: #7ec699; + --fragment-comment: #999999; + --fragment-link: #98c0e3; + --fragment-preprocessor: #65cabe; + --fragment-linenumber-color: #cccccc; + --fragment-linenumber-background: #35393c; + --fragment-linenumber-border: #1f1f1f; + } +} + +/* dark mode variables are defined twice, to support both the dark-mode without and with doxygen-awesome-darkmode-toggle.js */ +html.dark-mode { + color-scheme: dark; + + --primary-color: #1982d2; + --primary-dark-color: #86a9c4; + --primary-light-color: #4779ac; + + --box-shadow: 0 2px 8px 0 rgba(0,0,0,.30); + + --odd-color: rgba(100,100,100,.06); + + --menu-selected-background: rgba(0,0,0,.4); + + --page-background-color: #1C1D1F; + --page-foreground-color: #d2dbde; + --page-secondary-foreground-color: #859399; + --separator-color: #38393b; + --side-nav-background: #252628; + + --code-background: #2a2c2f; + + --tablehead-background: #2a2c2f; + + --blockquote-background: #222325; + --blockquote-foreground: #7e8c92; + + --warning-color: #2e1917; + --warning-color-dark: #ad2617; + --warning-color-darker: #f5b1aa; + --note-color: #3b2e04; + --note-color-dark: #f1b602; + --note-color-darker: #ceb670; + --todo-color: #163750; + --todo-color-dark: #1982D2; + --todo-color-darker: #dcf0fa; + --deprecated-color: #2e323b; + --deprecated-color-dark: #738396; + --deprecated-color-darker: #abb0bd; + --bug-color: #2a2536; + --bug-color-dark: #7661b3; + --bug-color-darker: #ae9ed6; + --invariant-color: #303a35; + --invariant-color-dark: #76ce96; + --invariant-color-darker: #cceed5; + + --fragment-background: #282c34; + --fragment-foreground: #dbe4eb; + --fragment-keyword: #cc99cd; + --fragment-keywordtype: #ab99cd; + --fragment-keywordflow: #e08000; + --fragment-token: #7ec699; + --fragment-comment: #999999; + --fragment-link: #98c0e3; + --fragment-preprocessor: #65cabe; + --fragment-linenumber-color: #cccccc; + --fragment-linenumber-background: #35393c; + --fragment-linenumber-border: #1f1f1f; +} + +body { + color: var(--page-foreground-color); + background-color: var(--page-background-color); + font-size: var(--page-font-size); +} + +body, table, div, p, dl, #nav-tree .label, .title, +.sm-dox a, .sm-dox a:hover, .sm-dox a:focus, #projectname, +.SelectItem, #MSearchField, .navpath li.navelem a, +.navpath li.navelem a:hover, p.reference, p.definition { + font-family: var(--font-family); +} + +h1, h2, h3, h4, h5 { + margin-top: .9em; + font-weight: 600; + line-height: initial; +} + +p, div, table, dl, p.reference, p.definition { + font-size: var(--page-font-size); +} + +p.reference, p.definition { + color: var(--page-secondary-foreground-color); +} + +a:link, a:visited, a:hover, a:focus, a:active { + color: var(--primary-color) !important; + font-weight: 500; +} + +a.anchor { + scroll-margin-top: var(--spacing-large); + display: block; +} + +/* + Title and top navigation + */ + +#top { + background: var(--header-background); + border-bottom: 1px solid var(--separator-color); +} + +@media screen and (min-width: 768px) { + #top { + display: flex; + flex-wrap: wrap; + justify-content: space-between; + align-items: center; + } +} + +#main-nav { + flex-grow: 5; + padding: var(--spacing-small) var(--spacing-medium); +} + +#titlearea { + width: auto; + padding: var(--spacing-medium) var(--spacing-large); + background: none; + color: var(--header-foreground); + border-bottom: none; +} + +@media screen and (max-width: 767px) { + #titlearea { + padding-bottom: var(--spacing-small); + } +} + +#titlearea table tbody tr { + height: auto !important; +} + +#projectname { + font-size: var(--title-font-size); + font-weight: 600; +} + +#projectnumber { + font-family: inherit; + font-size: 60%; +} + +#projectbrief { + font-family: inherit; + font-size: 80%; +} + +#projectlogo { + vertical-align: middle; +} + +#projectlogo img { + max-height: calc(var(--title-font-size) * 2); + margin-right: var(--spacing-small); +} + +.sm-dox, .tabs, .tabs2, .tabs3 { + background: none; + padding: 0; +} + +.tabs, .tabs2, .tabs3 { + border-bottom: 1px solid var(--separator-color); + margin-bottom: -1px; +} + +.main-menu-btn-icon, .main-menu-btn-icon:before, .main-menu-btn-icon:after { + background: var(--page-secondary-foreground-color); +} + +@media screen and (max-width: 767px) { + .sm-dox a span.sub-arrow { + background: var(--code-background); + } + + #main-menu a.has-submenu span.sub-arrow { + color: var(--page-secondary-foreground-color); + border-radius: var(--border-radius-medium); + } + + #main-menu a.has-submenu:hover span.sub-arrow { + color: var(--page-foreground-color); + } +} + +@media screen and (min-width: 768px) { + .sm-dox li, .tablist li { + display: var(--menu-display); + } + + .sm-dox a span.sub-arrow { + border-color: var(--header-foreground) transparent transparent transparent; + } + + .sm-dox a:hover span.sub-arrow { + border-color: var(--menu-focus-foreground) transparent transparent transparent; + } + + .sm-dox ul a span.sub-arrow { + border-color: transparent transparent transparent var(--page-foreground-color); + } + + .sm-dox ul a:hover span.sub-arrow { + border-color: transparent transparent transparent var(--menu-focus-foreground); + } +} + +.sm-dox ul { + background: var(--page-background-color); + box-shadow: var(--box-shadow); + border: 1px solid var(--separator-color); + border-radius: var(--border-radius-medium) !important; + padding: var(--spacing-small); + animation: ease-out 150ms slideInMenu; +} + +@keyframes slideInMenu { + from { + opacity: 0; + transform: translate(0px, -2px); + } + + to { + opacity: 1; + transform: translate(0px, 0px); + } +} + +.sm-dox ul a { + color: var(--page-foreground-color) !important; + background: var(--page-background-color); + font-size: var(--navigation-font-size); +} + +.sm-dox>li>ul:after { + border-bottom-color: var(--page-background-color) !important; +} + +.sm-dox>li>ul:before { + border-bottom-color: var(--separator-color) !important; +} + +.sm-dox ul a:hover, .sm-dox ul a:active, .sm-dox ul a:focus { + font-size: var(--navigation-font-size) !important; + color: var(--menu-focus-foreground) !important; + text-shadow: none; + background-color: var(--menu-focus-background); + border-radius: var(--border-radius-small) !important; +} + +.sm-dox a, .sm-dox a:focus, .tablist li, .tablist li a, .tablist li.current a { + text-shadow: none; + background: transparent; + background-image: none !important; + color: var(--header-foreground) !important; + font-weight: normal; + font-size: var(--navigation-font-size); + border-radius: var(--border-radius-small) !important; +} + +.sm-dox a:focus { + outline: auto; +} + +.sm-dox a:hover, .sm-dox a:active, .tablist li a:hover { + text-shadow: none; + font-weight: normal; + background: var(--menu-focus-background); + color: var(--menu-focus-foreground) !important; + border-radius: var(--border-radius-small) !important; + font-size: var(--navigation-font-size); +} + +.tablist li.current { + border-radius: var(--border-radius-small); + background: var(--menu-selected-background); +} + +.tablist li { + margin: var(--spacing-small) 0 var(--spacing-small) var(--spacing-small); +} + +.tablist a { + padding: 0 var(--spacing-large); +} + + +/* + Search box + */ + +#MSearchBox { + height: var(--searchbar-height); + background: var(--searchbar-background); + border-radius: var(--searchbar-border-radius); + border: 1px solid var(--separator-color); + overflow: hidden; + width: var(--searchbar-width); + position: relative; + box-shadow: none; + display: block; + margin-top: 0; +} + +/* until Doxygen 1.9.4 */ +.left img#MSearchSelect { + left: 0; + user-select: none; + padding-left: 8px; +} + +/* Doxygen 1.9.5 */ +.left span#MSearchSelect { + left: 0; + user-select: none; + margin-left: 8px; + padding: 0; +} + +.left #MSearchSelect[src$=".png"] { + padding-left: 0 +} + +.SelectionMark { + user-select: none; +} + +.tabs .left #MSearchSelect { + padding-left: 0; +} + +.tabs #MSearchBox { + position: absolute; + right: var(--spacing-medium); +} + +@media screen and (max-width: 767px) { + .tabs #MSearchBox { + position: relative; + right: 0; + margin-left: var(--spacing-medium); + margin-top: 0; + } +} + +#MSearchSelectWindow, #MSearchResultsWindow { + z-index: 9999; +} + +#MSearchBox.MSearchBoxActive { + border-color: var(--primary-color); + box-shadow: inset 0 0 0 1px var(--primary-color); +} + +#main-menu > li:last-child { + margin-right: 0; +} + +@media screen and (max-width: 767px) { + #main-menu > li:last-child { + height: 50px; + } +} + +#MSearchField { + font-size: var(--navigation-font-size); + height: calc(var(--searchbar-height) - 2px); + background: transparent; + width: calc(var(--searchbar-width) - 64px); +} + +.MSearchBoxActive #MSearchField { + color: var(--searchbar-foreground); +} + +#MSearchSelect { + top: calc(calc(var(--searchbar-height) / 2) - 11px); +} + +#MSearchBox span.left, #MSearchBox span.right { + background: none; + background-image: none; +} + +#MSearchBox span.right { + padding-top: calc(calc(var(--searchbar-height) / 2) - 12px); + position: absolute; + right: var(--spacing-small); +} + +.tabs #MSearchBox span.right { + top: calc(calc(var(--searchbar-height) / 2) - 12px); +} + +@keyframes slideInSearchResults { + from { + opacity: 0; + transform: translate(0, 15px); + } + + to { + opacity: 1; + transform: translate(0, 20px); + } +} + +#MSearchResultsWindow { + left: auto !important; + right: var(--spacing-medium); + border-radius: var(--border-radius-large); + border: 1px solid var(--separator-color); + transform: translate(0, 20px); + box-shadow: var(--box-shadow); + animation: ease-out 280ms slideInSearchResults; + background: var(--page-background-color); +} + +iframe#MSearchResults { + margin: 4px; +} + +iframe { + color-scheme: normal; +} + +@media (prefers-color-scheme: dark) { + html:not(.light-mode) iframe#MSearchResults { + filter: invert() hue-rotate(180deg); + } +} + +html.dark-mode iframe#MSearchResults { + filter: invert() hue-rotate(180deg); +} + +#MSearchResults .SRPage { + background-color: transparent; +} + +#MSearchResults .SRPage .SREntry { + font-size: 10pt; + padding: var(--spacing-small) var(--spacing-medium); +} + +#MSearchSelectWindow { + border: 1px solid var(--separator-color); + border-radius: var(--border-radius-medium); + box-shadow: var(--box-shadow); + background: var(--page-background-color); + padding-top: var(--spacing-small); + padding-bottom: var(--spacing-small); +} + +#MSearchSelectWindow a.SelectItem { + font-size: var(--navigation-font-size); + line-height: var(--content-line-height); + margin: 0 var(--spacing-small); + border-radius: var(--border-radius-small); + color: var(--page-foreground-color) !important; + font-weight: normal; +} + +#MSearchSelectWindow a.SelectItem:hover { + background: var(--menu-focus-background); + color: var(--menu-focus-foreground) !important; +} + +@media screen and (max-width: 767px) { + #MSearchBox { + margin-top: var(--spacing-medium); + margin-bottom: var(--spacing-medium); + width: calc(100vw - 30px); + } + + #main-menu > li:last-child { + float: none !important; + } + + #MSearchField { + width: calc(100vw - 110px); + } + + @keyframes slideInSearchResultsMobile { + from { + opacity: 0; + transform: translate(0, 15px); + } + + to { + opacity: 1; + transform: translate(0, 20px); + } + } + + #MSearchResultsWindow { + left: var(--spacing-medium) !important; + right: var(--spacing-medium); + overflow: auto; + transform: translate(0, 20px); + animation: ease-out 280ms slideInSearchResultsMobile; + width: auto !important; + } + + /* + * Overwrites for fixing the searchbox on mobile in doxygen 1.9.2 + */ + label.main-menu-btn ~ #searchBoxPos1 { + top: 3px !important; + right: 6px !important; + left: 45px; + display: flex; + } + + label.main-menu-btn ~ #searchBoxPos1 > #MSearchBox { + margin-top: 0; + margin-bottom: 0; + flex-grow: 2; + float: left; + } +} + +/* + Tree view + */ + +#side-nav { + padding: 0 !important; + background: var(--side-nav-background); +} + +@media screen and (max-width: 767px) { + #side-nav { + display: none; + } + + #doc-content { + margin-left: 0 !important; + } +} + +#nav-tree { + background: transparent; + margin-right: 1px; +} + +#nav-tree .label { + font-size: var(--navigation-font-size); +} + +#nav-tree .item { + height: var(--tree-item-height); + line-height: var(--tree-item-height); +} + +#nav-sync { + bottom: 12px; + right: 12px; + top: auto !important; + user-select: none; +} + +#nav-tree .selected { + text-shadow: none; + background-image: none; + background-color: transparent; + position: relative; +} + +#nav-tree .selected::after { + content: ""; + position: absolute; + top: 1px; + bottom: 1px; + left: 0; + width: 4px; + border-radius: 0 var(--border-radius-small) var(--border-radius-small) 0; + background: var(--primary-color); +} + + +#nav-tree a { + color: var(--side-nav-foreground) !important; + font-weight: normal; +} + +#nav-tree a:focus { + outline-style: auto; +} + +#nav-tree .arrow { + opacity: var(--side-nav-arrow-opacity); +} + +.arrow { + color: inherit; + cursor: pointer; + font-size: 45%; + vertical-align: middle; + margin-right: 2px; + font-family: serif; + height: auto; + text-align: right; +} + +#nav-tree div.item:hover .arrow, #nav-tree a:focus .arrow { + opacity: var(--side-nav-arrow-hover-opacity); +} + +#nav-tree .selected a { + color: var(--primary-color) !important; + font-weight: bolder; + font-weight: 600; +} + +.ui-resizable-e { + background: var(--separator-color); + width: 1px; +} + +/* + Contents + */ + +div.header { + border-bottom: 1px solid var(--separator-color); + background-color: var(--page-background-color); + background-image: none; +} + +@media screen and (min-width: 1000px) { + #doc-content > div > div.contents, + .PageDoc > div.contents { + display: flex; + flex-direction: row-reverse; + flex-wrap: nowrap; + align-items: flex-start; + } + + div.contents .textblock { + min-width: 200px; + flex-grow: 1; + } +} + +div.contents, div.header .title, div.header .summary { + max-width: var(--content-maxwidth); +} + +div.contents, div.header .title { + line-height: initial; + margin: calc(var(--spacing-medium) + .2em) auto var(--spacing-medium) auto; +} + +div.header .summary { + margin: var(--spacing-medium) auto 0 auto; +} + +div.headertitle { + padding: 0; +} + +div.header .title { + font-weight: 600; + font-size: 225%; + padding: var(--spacing-medium) var(--spacing-large); + word-break: break-word; +} + +div.header .summary { + width: auto; + display: block; + float: none; + padding: 0 var(--spacing-large); +} + +td.memSeparator { + border-color: var(--separator-color); +} + +span.mlabel { + background: var(--primary-color); + border: none; + padding: 4px 9px; + border-radius: 12px; + margin-right: var(--spacing-medium); +} + +span.mlabel:last-of-type { + margin-right: 2px; +} + +div.contents { + padding: 0 var(--spacing-large); +} + +div.contents p, div.contents li { + line-height: var(--content-line-height); +} + +div.contents div.dyncontent { + margin: var(--spacing-medium) 0; +} + +@media (prefers-color-scheme: dark) { + html:not(.light-mode) div.contents div.dyncontent img, + html:not(.light-mode) div.contents center img, + html:not(.light-mode) div.contents > table img, + html:not(.light-mode) div.contents div.dyncontent iframe, + html:not(.light-mode) div.contents center iframe, + html:not(.light-mode) div.contents table iframe, + html:not(.light-mode) div.contents .dotgraph iframe { + filter: brightness(89%) hue-rotate(180deg) invert(); + } +} + +html.dark-mode div.contents div.dyncontent img, +html.dark-mode div.contents center img, +html.dark-mode div.contents > table img, +html.dark-mode div.contents div.dyncontent iframe, +html.dark-mode div.contents center iframe, +html.dark-mode div.contents table iframe, +html.dark-mode div.contents .dotgraph iframe + { + filter: brightness(89%) hue-rotate(180deg) invert(); +} + +h2.groupheader { + border-bottom: 0px; + color: var(--page-foreground-color); + box-shadow: + 100px 0 var(--page-background-color), + -100px 0 var(--page-background-color), + 100px 0.75px var(--separator-color), + -100px 0.75px var(--separator-color), + 500px 0 var(--page-background-color), + -500px 0 var(--page-background-color), + 500px 0.75px var(--separator-color), + -500px 0.75px var(--separator-color), + 900px 0 var(--page-background-color), + -900px 0 var(--page-background-color), + 900px 0.75px var(--separator-color), + -900px 0.75px var(--separator-color), + 1400px 0 var(--page-background-color), + -1400px 0 var(--page-background-color), + 1400px 0.75px var(--separator-color), + -1400px 0.75px var(--separator-color), + 1900px 0 var(--page-background-color), + -1900px 0 var(--page-background-color), + 1900px 0.75px var(--separator-color), + -1900px 0.75px var(--separator-color); +} + +blockquote { + margin: 0 var(--spacing-medium) 0 var(--spacing-medium); + padding: var(--spacing-small) var(--spacing-large); + background: var(--blockquote-background); + color: var(--blockquote-foreground); + border-left: 0; + overflow: visible; + border-radius: var(--border-radius-medium); + overflow: visible; + position: relative; +} + +blockquote::before, blockquote::after { + font-weight: bold; + font-family: serif; + font-size: 360%; + opacity: .15; + position: absolute; +} + +blockquote::before { + content: "“"; + left: -10px; + top: 4px; +} + +blockquote::after { + content: "”"; + right: -8px; + bottom: -25px; +} + +blockquote p { + margin: var(--spacing-small) 0 var(--spacing-medium) 0; +} +.paramname { + font-weight: 600; + color: var(--primary-dark-color); +} + +.paramname > code { + border: 0; +} + +table.params .paramname { + font-weight: 600; + font-family: var(--font-family-monospace); + font-size: var(--code-font-size); + padding-right: var(--spacing-small); + line-height: var(--table-line-height); +} + +h1.glow, h2.glow, h3.glow, h4.glow, h5.glow, h6.glow { + text-shadow: 0 0 15px var(--primary-light-color); +} + +.alphachar a { + color: var(--page-foreground-color); +} + +.dotgraph { + max-width: 100%; + overflow-x: scroll; +} + +.dotgraph .caption { + position: sticky; + left: 0; +} + +/* Wrap Graphviz graphs with the `interactive_dotgraph` class if `INTERACTIVE_SVG = YES` */ +.interactive_dotgraph .dotgraph iframe { + max-width: 100%; +} + +/* + Table of Contents + */ + +div.contents .toc { + max-height: var(--toc-max-height); + min-width: var(--toc-width); + border: 0; + border-left: 1px solid var(--separator-color); + border-radius: 0; + background-color: transparent; + box-shadow: none; + position: sticky; + top: var(--toc-sticky-top); + padding: 0 var(--spacing-large); + margin: var(--spacing-small) 0 var(--spacing-large) var(--spacing-large); +} + +div.toc h3 { + color: var(--toc-foreground); + font-size: var(--navigation-font-size); + margin: var(--spacing-large) 0 var(--spacing-medium) 0; +} + +div.toc li { + padding: 0; + background: none; + line-height: var(--toc-font-size); + margin: var(--toc-font-size) 0 0 0; +} + +div.toc li::before { + display: none; +} + +div.toc ul { + margin-top: 0 +} + +div.toc li a { + font-size: var(--toc-font-size); + color: var(--page-foreground-color) !important; + text-decoration: none; +} + +div.toc li a:hover, div.toc li a.active { + color: var(--primary-color) !important; +} + +div.toc li a.aboveActive { + color: var(--page-secondary-foreground-color) !important; +} + + +@media screen and (max-width: 999px) { + div.contents .toc { + max-height: 45vh; + float: none; + width: auto; + margin: 0 0 var(--spacing-medium) 0; + position: relative; + top: 0; + position: relative; + border: 1px solid var(--separator-color); + border-radius: var(--border-radius-medium); + background-color: var(--toc-background); + box-shadow: var(--box-shadow); + } + + div.contents .toc.interactive { + max-height: calc(var(--navigation-font-size) + 2 * var(--spacing-large)); + overflow: hidden; + } + + div.contents .toc > h3 { + -webkit-tap-highlight-color: transparent; + cursor: pointer; + position: sticky; + top: 0; + background-color: var(--toc-background); + margin: 0; + padding: var(--spacing-large) 0; + display: block; + } + + div.contents .toc.interactive > h3::before { + content: ""; + width: 0; + height: 0; + border-left: 4px solid transparent; + border-right: 4px solid transparent; + border-top: 5px solid var(--primary-color); + display: inline-block; + margin-right: var(--spacing-small); + margin-bottom: calc(var(--navigation-font-size) / 4); + transform: rotate(-90deg); + transition: transform 0.25s ease-out; + } + + div.contents .toc.interactive.open > h3::before { + transform: rotate(0deg); + } + + div.contents .toc.interactive.open { + max-height: 45vh; + overflow: auto; + transition: max-height 0.2s ease-in-out; + } + + div.contents .toc a, div.contents .toc a.active { + color: var(--primary-color) !important; + } + + div.contents .toc a:hover { + text-decoration: underline; + } +} + +/* + Code & Fragments + */ + +code, div.fragment, pre.fragment { + border-radius: var(--border-radius-small); + border: 1px solid var(--separator-color); + overflow: hidden; +} + +code { + display: inline; + background: var(--code-background); + color: var(--code-foreground); + padding: 2px 6px; +} + +div.fragment, pre.fragment { + margin: var(--spacing-medium) 0; + padding: calc(var(--spacing-large) - (var(--spacing-large) / 6)) var(--spacing-large); + background: var(--fragment-background); + color: var(--fragment-foreground); + overflow-x: auto; +} + +@media screen and (max-width: 767px) { + div.fragment, pre.fragment { + border-top-right-radius: 0; + border-bottom-right-radius: 0; + border-right: 0; + } + + .contents > div.fragment, + .textblock > div.fragment, + .textblock > pre.fragment, + .contents > .doxygen-awesome-fragment-wrapper > div.fragment, + .textblock > .doxygen-awesome-fragment-wrapper > div.fragment, + .textblock > .doxygen-awesome-fragment-wrapper > pre.fragment { + margin: var(--spacing-medium) calc(0px - var(--spacing-large)); + border-radius: 0; + border-left: 0; + } + + .textblock li > .fragment, + .textblock li > .doxygen-awesome-fragment-wrapper > .fragment { + margin: var(--spacing-medium) calc(0px - var(--spacing-large)); + } + + .memdoc li > .fragment, + .memdoc li > .doxygen-awesome-fragment-wrapper > .fragment { + margin: var(--spacing-medium) calc(0px - var(--spacing-medium)); + } + + .textblock ul, .memdoc ul { + overflow: initial; + } + + .memdoc > div.fragment, + .memdoc > pre.fragment, + dl dd > div.fragment, + dl dd pre.fragment, + .memdoc > .doxygen-awesome-fragment-wrapper > div.fragment, + .memdoc > .doxygen-awesome-fragment-wrapper > pre.fragment, + dl dd > .doxygen-awesome-fragment-wrapper > div.fragment, + dl dd .doxygen-awesome-fragment-wrapper > pre.fragment { + margin: var(--spacing-medium) calc(0px - var(--spacing-medium)); + border-radius: 0; + border-left: 0; + } +} + +code, code a, pre.fragment, div.fragment, div.fragment .line, div.fragment span, div.fragment .line a, div.fragment .line span { + font-family: var(--font-family-monospace); + font-size: var(--code-font-size) !important; +} + +div.line:after { + margin-right: var(--spacing-medium); +} + +div.fragment .line, pre.fragment { + white-space: pre; + word-wrap: initial; + line-height: var(--fragment-lineheight); +} + +div.fragment span.keyword { + color: var(--fragment-keyword); +} + +div.fragment span.keywordtype { + color: var(--fragment-keywordtype); +} + +div.fragment span.keywordflow { + color: var(--fragment-keywordflow); +} + +div.fragment span.stringliteral { + color: var(--fragment-token) +} + +div.fragment span.comment { + color: var(--fragment-comment); +} + +div.fragment a.code { + color: var(--fragment-link) !important; +} + +div.fragment span.preprocessor { + color: var(--fragment-preprocessor); +} + +div.fragment span.lineno { + display: inline-block; + width: 27px; + border-right: none; + background: var(--fragment-linenumber-background); + color: var(--fragment-linenumber-color); +} + +div.fragment span.lineno a { + background: none; + color: var(--fragment-link) !important; +} + +div.fragment .line:first-child .lineno { + box-shadow: -999999px 0px 0 999999px var(--fragment-linenumber-background), -999998px 0px 0 999999px var(--fragment-linenumber-border); +} + +div.line { + border-radius: var(--border-radius-small); +} + +div.line.glow { + background-color: var(--primary-light-color); + box-shadow: none; +} + +/* + dl warning, attention, note, deprecated, bug, ... + */ + +dl.bug dt a, dl.deprecated dt a, dl.todo dt a { + font-weight: bold !important; +} + +dl.warning, dl.attention, dl.note, dl.deprecated, dl.bug, dl.invariant, dl.pre, dl.post, dl.todo, dl.remark { + padding: var(--spacing-medium); + margin: var(--spacing-medium) 0; + color: var(--page-background-color); + overflow: hidden; + margin-left: 0; + border-radius: var(--border-radius-small); +} + +dl.section dd { + margin-bottom: 2px; +} + +dl.warning, dl.attention { + background: var(--warning-color); + border-left: 8px solid var(--warning-color-dark); + color: var(--warning-color-darker); +} + +dl.warning dt, dl.attention dt { + color: var(--warning-color-dark); +} + +dl.note, dl.remark { + background: var(--note-color); + border-left: 8px solid var(--note-color-dark); + color: var(--note-color-darker); +} + +dl.note dt, dl.remark dt { + color: var(--note-color-dark); +} + +dl.todo { + background: var(--todo-color); + border-left: 8px solid var(--todo-color-dark); + color: var(--todo-color-darker); +} + +dl.todo dt { + color: var(--todo-color-dark); +} + +dl.bug dt a { + color: var(--todo-color-dark) !important; +} + +dl.bug { + background: var(--bug-color); + border-left: 8px solid var(--bug-color-dark); + color: var(--bug-color-darker); +} + +dl.bug dt a { + color: var(--bug-color-dark) !important; +} + +dl.deprecated { + background: var(--deprecated-color); + border-left: 8px solid var(--deprecated-color-dark); + color: var(--deprecated-color-darker); +} + +dl.deprecated dt a { + color: var(--deprecated-color-dark) !important; +} + +dl.section dd, dl.bug dd, dl.deprecated dd, dl.todo dd { + margin-inline-start: 0px; +} + +dl.invariant, dl.pre, dl.post { + background: var(--invariant-color); + border-left: 8px solid var(--invariant-color-dark); + color: var(--invariant-color-darker); +} + +dl.invariant dt, dl.pre dt, dl.post dt { + color: var(--invariant-color-dark); +} + +/* + memitem + */ + +div.memdoc, div.memproto, h2.memtitle { + box-shadow: none; + background-image: none; + border: none; +} + +div.memdoc { + padding: 0 var(--spacing-medium); + background: var(--page-background-color); +} + +h2.memtitle, div.memitem { + border: 1px solid var(--separator-color); + box-shadow: var(--box-shadow); +} + +h2.memtitle { + box-shadow: 0px var(--spacing-medium) 0 -1px var(--fragment-background), var(--box-shadow); +} + +div.memitem { + transition: none; +} + +div.memproto, h2.memtitle { + background: var(--fragment-background); +} + +h2.memtitle { + font-weight: 500; + font-size: var(--memtitle-font-size); + font-family: var(--font-family-monospace); + border-bottom: none; + border-top-left-radius: var(--border-radius-medium); + border-top-right-radius: var(--border-radius-medium); + word-break: break-all; + position: relative; +} + +h2.memtitle:after { + content: ""; + display: block; + background: var(--fragment-background); + height: var(--spacing-medium); + bottom: calc(0px - var(--spacing-medium)); + left: 0; + right: -14px; + position: absolute; + border-top-right-radius: var(--border-radius-medium); +} + +h2.memtitle > span.permalink { + font-size: inherit; +} + +h2.memtitle > span.permalink > a { + text-decoration: none; + padding-left: 3px; + margin-right: -4px; + user-select: none; + display: inline-block; + margin-top: -6px; +} + +h2.memtitle > span.permalink > a:hover { + color: var(--primary-dark-color) !important; +} + +a:target + h2.memtitle, a:target + h2.memtitle + div.memitem { + border-color: var(--primary-light-color); +} + +div.memitem { + border-top-right-radius: var(--border-radius-medium); + border-bottom-right-radius: var(--border-radius-medium); + border-bottom-left-radius: var(--border-radius-medium); + overflow: hidden; + display: block !important; +} + +div.memdoc { + border-radius: 0; +} + +div.memproto { + border-radius: 0 var(--border-radius-small) 0 0; + overflow: auto; + border-bottom: 1px solid var(--separator-color); + padding: var(--spacing-medium); + margin-bottom: -1px; +} + +div.memtitle { + border-top-right-radius: var(--border-radius-medium); + border-top-left-radius: var(--border-radius-medium); +} + +div.memproto table.memname { + font-family: var(--font-family-monospace); + color: var(--page-foreground-color); + font-size: var(--memname-font-size); + text-shadow: none; +} + +div.memproto div.memtemplate { + font-family: var(--font-family-monospace); + color: var(--primary-dark-color); + font-size: var(--memname-font-size); + margin-left: 2px; + text-shadow: none; +} + +table.mlabels, table.mlabels > tbody { + display: block; +} + +td.mlabels-left { + width: auto; +} + +td.mlabels-right { + margin-top: 3px; + position: sticky; + left: 0; +} + +table.mlabels > tbody > tr:first-child { + display: flex; + justify-content: space-between; + flex-wrap: wrap; +} + +.memname, .memitem span.mlabels { + margin: 0 +} + +/* + reflist + */ + +dl.reflist { + box-shadow: var(--box-shadow); + border-radius: var(--border-radius-medium); + border: 1px solid var(--separator-color); + overflow: hidden; + padding: 0; +} + + +dl.reflist dt, dl.reflist dd { + box-shadow: none; + text-shadow: none; + background-image: none; + border: none; + padding: 12px; +} + + +dl.reflist dt { + font-weight: 500; + border-radius: 0; + background: var(--code-background); + border-bottom: 1px solid var(--separator-color); + color: var(--page-foreground-color) +} + + +dl.reflist dd { + background: none; +} + +/* + Table + */ + +.contents table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname), +.contents table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) tbody { + display: inline-block; + max-width: 100%; +} + +.contents > table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname):not(.classindex) { + margin-left: calc(0px - var(--spacing-large)); + margin-right: calc(0px - var(--spacing-large)); + max-width: calc(100% + 2 * var(--spacing-large)); +} + +table.fieldtable, +table.markdownTable tbody, +table.doxtable tbody { + border: none; + margin: var(--spacing-medium) 0; + box-shadow: 0 0 0 1px var(--separator-color); + border-radius: var(--border-radius-small); +} + +table.markdownTable, table.doxtable, table.fieldtable { + padding: 1px; +} + +table.doxtable caption { + display: block; +} + +table.fieldtable { + border-collapse: collapse; + width: 100%; +} + +th.markdownTableHeadLeft, +th.markdownTableHeadRight, +th.markdownTableHeadCenter, +th.markdownTableHeadNone, +table.doxtable th { + background: var(--tablehead-background); + color: var(--tablehead-foreground); + font-weight: 600; + font-size: var(--page-font-size); +} + +th.markdownTableHeadLeft:first-child, +th.markdownTableHeadRight:first-child, +th.markdownTableHeadCenter:first-child, +th.markdownTableHeadNone:first-child, +table.doxtable tr th:first-child { + border-top-left-radius: var(--border-radius-small); +} + +th.markdownTableHeadLeft:last-child, +th.markdownTableHeadRight:last-child, +th.markdownTableHeadCenter:last-child, +th.markdownTableHeadNone:last-child, +table.doxtable tr th:last-child { + border-top-right-radius: var(--border-radius-small); +} + +table.markdownTable td, +table.markdownTable th, +table.fieldtable td, +table.fieldtable th, +table.doxtable td, +table.doxtable th { + border: 1px solid var(--separator-color); + padding: var(--spacing-small) var(--spacing-medium); +} + +table.markdownTable td:last-child, +table.markdownTable th:last-child, +table.fieldtable td:last-child, +table.fieldtable th:last-child, +table.doxtable td:last-child, +table.doxtable th:last-child { + border-right: none; +} + +table.markdownTable td:first-child, +table.markdownTable th:first-child, +table.fieldtable td:first-child, +table.fieldtable th:first-child, +table.doxtable td:first-child, +table.doxtable th:first-child { + border-left: none; +} + +table.markdownTable tr:first-child td, +table.markdownTable tr:first-child th, +table.fieldtable tr:first-child td, +table.fieldtable tr:first-child th, +table.doxtable tr:first-child td, +table.doxtable tr:first-child th { + border-top: none; +} + +table.markdownTable tr:last-child td, +table.markdownTable tr:last-child th, +table.fieldtable tr:last-child td, +table.fieldtable tr:last-child th, +table.doxtable tr:last-child td, +table.doxtable tr:last-child th { + border-bottom: none; +} + +table.markdownTable tr, table.doxtable tr { + border-bottom: 1px solid var(--separator-color); +} + +table.markdownTable tr:last-child, table.doxtable tr:last-child { + border-bottom: none; +} + +.full_width_table table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) { + display: block; +} + +.full_width_table table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) tbody { + display: table; + width: 100%; +} + +table.fieldtable th { + font-size: var(--page-font-size); + font-weight: 600; + background-image: none; + background-color: var(--tablehead-background); + color: var(--tablehead-foreground); +} + +table.fieldtable td.fieldtype, .fieldtable td.fieldname, .fieldtable td.fielddoc, .fieldtable th { + border-bottom: 1px solid var(--separator-color); + border-right: 1px solid var(--separator-color); +} + +table.fieldtable tr:last-child td:first-child { + border-bottom-left-radius: var(--border-radius-small); +} + +table.fieldtable tr:last-child td:last-child { + border-bottom-right-radius: var(--border-radius-small); +} + +.memberdecls td.glow, .fieldtable tr.glow { + background-color: var(--primary-light-color); + box-shadow: none; +} + +table.memberdecls { + display: block; + -webkit-tap-highlight-color: transparent; +} + +table.memberdecls tr[class^='memitem'] { + font-family: var(--font-family-monospace); + font-size: var(--code-font-size); +} + +table.memberdecls tr[class^='memitem'] .memTemplParams { + font-family: var(--font-family-monospace); + font-size: var(--code-font-size); + color: var(--primary-dark-color); + white-space: normal; +} + +table.memberdecls .memItemLeft, +table.memberdecls .memItemRight, +table.memberdecls .memTemplItemLeft, +table.memberdecls .memTemplItemRight, +table.memberdecls .memTemplParams { + transition: none; + padding-top: var(--spacing-small); + padding-bottom: var(--spacing-small); + border-top: 1px solid var(--separator-color); + border-bottom: 1px solid var(--separator-color); + background-color: var(--fragment-background); +} + +table.memberdecls .memTemplItemLeft, +table.memberdecls .memTemplItemRight { + padding-top: 2px; +} + +table.memberdecls .memTemplParams { + border-bottom: 0; + border-left: 1px solid var(--separator-color); + border-right: 1px solid var(--separator-color); + border-radius: var(--border-radius-small) var(--border-radius-small) 0 0; + padding-bottom: var(--spacing-small); +} + +table.memberdecls .memTemplItemLeft { + border-radius: 0 0 0 var(--border-radius-small); + border-left: 1px solid var(--separator-color); + border-top: 0; +} + +table.memberdecls .memTemplItemRight { + border-radius: 0 0 var(--border-radius-small) 0; + border-right: 1px solid var(--separator-color); + padding-left: 0; + border-top: 0; +} + +table.memberdecls .memItemLeft { + border-radius: var(--border-radius-small) 0 0 var(--border-radius-small); + border-left: 1px solid var(--separator-color); + padding-left: var(--spacing-medium); + padding-right: 0; +} + +table.memberdecls .memItemRight { + border-radius: 0 var(--border-radius-small) var(--border-radius-small) 0; + border-right: 1px solid var(--separator-color); + padding-right: var(--spacing-medium); + padding-left: 0; + +} + +table.memberdecls .mdescLeft, table.memberdecls .mdescRight { + background: none; + color: var(--page-foreground-color); + padding: var(--spacing-small) 0; +} + +table.memberdecls .memItemLeft, +table.memberdecls .memTemplItemLeft { + padding-right: var(--spacing-medium); +} + +table.memberdecls .memSeparator { + background: var(--page-background-color); + height: var(--spacing-large); + border: 0; + transition: none; +} + +table.memberdecls .groupheader { + margin-bottom: var(--spacing-large); +} + +table.memberdecls .inherit_header td { + padding: 0 0 var(--spacing-medium) 0; + text-indent: -12px; + color: var(--page-secondary-foreground-color); +} + +table.memberdecls img[src="closed.png"], +table.memberdecls img[src="open.png"], +div.dynheader img[src="open.png"], +div.dynheader img[src="closed.png"] { + width: 0; + height: 0; + border-left: 4px solid transparent; + border-right: 4px solid transparent; + border-top: 5px solid var(--primary-color); + margin-top: 8px; + display: block; + float: left; + margin-left: -10px; + transition: transform 0.25s ease-out; +} + +table.memberdecls img { + margin-right: 10px; +} + +table.memberdecls img[src="closed.png"], +div.dynheader img[src="closed.png"] { + transform: rotate(-90deg); + +} + +.compoundTemplParams { + font-family: var(--font-family-monospace); + color: var(--primary-dark-color); + font-size: var(--code-font-size); +} + +@media screen and (max-width: 767px) { + + table.memberdecls .memItemLeft, + table.memberdecls .memItemRight, + table.memberdecls .mdescLeft, + table.memberdecls .mdescRight, + table.memberdecls .memTemplItemLeft, + table.memberdecls .memTemplItemRight, + table.memberdecls .memTemplParams { + display: block; + text-align: left; + padding-left: var(--spacing-large); + margin: 0 calc(0px - var(--spacing-large)) 0 calc(0px - var(--spacing-large)); + border-right: none; + border-left: none; + border-radius: 0; + white-space: normal; + } + + table.memberdecls .memItemLeft, + table.memberdecls .mdescLeft, + table.memberdecls .memTemplItemLeft { + border-bottom: 0; + padding-bottom: 0; + } + + table.memberdecls .memTemplItemLeft { + padding-top: 0; + } + + table.memberdecls .mdescLeft { + margin-bottom: calc(0px - var(--page-font-size)); + } + + table.memberdecls .memItemRight, + table.memberdecls .mdescRight, + table.memberdecls .memTemplItemRight { + border-top: 0; + padding-top: 0; + padding-right: var(--spacing-large); + overflow-x: auto; + } + + table.memberdecls tr[class^='memitem']:not(.inherit) { + display: block; + width: calc(100vw - 2 * var(--spacing-large)); + } + + table.memberdecls .mdescRight { + color: var(--page-foreground-color); + } + + table.memberdecls tr.inherit { + visibility: hidden; + } + + table.memberdecls tr[style="display: table-row;"] { + display: block !important; + visibility: visible; + width: calc(100vw - 2 * var(--spacing-large)); + animation: fade .5s; + } + + @keyframes fade { + 0% { + opacity: 0; + max-height: 0; + } + + 100% { + opacity: 1; + max-height: 200px; + } + } +} + + +/* + Horizontal Rule + */ + +hr { + margin-top: var(--spacing-large); + margin-bottom: var(--spacing-large); + height: 1px; + background-color: var(--separator-color); + border: 0; +} + +.contents hr { + box-shadow: 100px 0 0 var(--separator-color), + -100px 0 0 var(--separator-color), + 500px 0 0 var(--separator-color), + -500px 0 0 var(--separator-color), + 1500px 0 0 var(--separator-color), + -1500px 0 0 var(--separator-color), + 2000px 0 0 var(--separator-color), + -2000px 0 0 var(--separator-color); +} + +.contents img, .contents .center, .contents center, .contents div.image object { + max-width: 100%; + overflow: auto; +} + +@media screen and (max-width: 767px) { + .contents .dyncontent > .center, .contents > center { + margin-left: calc(0px - var(--spacing-large)); + margin-right: calc(0px - var(--spacing-large)); + max-width: calc(100% + 2 * var(--spacing-large)); + } +} + +/* + Directories + */ +div.directory { + border-top: 1px solid var(--separator-color); + border-bottom: 1px solid var(--separator-color); + width: auto; +} + +table.directory { + font-family: var(--font-family); + font-size: var(--page-font-size); + font-weight: normal; + width: 100%; +} + +table.directory td.entry, table.directory td.desc { + padding: calc(var(--spacing-small) / 2) var(--spacing-small); + line-height: var(--table-line-height); +} + +table.directory tr.even td:last-child { + border-radius: 0 var(--border-radius-small) var(--border-radius-small) 0; +} + +table.directory tr.even td:first-child { + border-radius: var(--border-radius-small) 0 0 var(--border-radius-small); +} + +table.directory tr.even:last-child td:last-child { + border-radius: 0 var(--border-radius-small) 0 0; +} + +table.directory tr.even:last-child td:first-child { + border-radius: var(--border-radius-small) 0 0 0; +} + +table.directory td.desc { + min-width: 250px; +} + +table.directory tr.even { + background-color: var(--odd-color); +} + +table.directory tr.odd { + background-color: transparent; +} + +.icona { + width: auto; + height: auto; + margin: 0 var(--spacing-small); +} + +.icon { + background: var(--primary-color); + border-radius: var(--border-radius-small); + font-size: var(--page-font-size); + padding: calc(var(--page-font-size) / 5); + line-height: var(--page-font-size); + transform: scale(0.8); + height: auto; + width: var(--page-font-size); + user-select: none; +} + +.iconfopen, .icondoc, .iconfclosed { + background-position: center; + margin-bottom: 0; + height: var(--table-line-height); +} + +.icondoc { + filter: saturate(0.2); +} + +@media screen and (max-width: 767px) { + div.directory { + margin-left: calc(0px - var(--spacing-large)); + margin-right: calc(0px - var(--spacing-large)); + } +} + +@media (prefers-color-scheme: dark) { + html:not(.light-mode) .iconfopen, html:not(.light-mode) .iconfclosed { + filter: hue-rotate(180deg) invert(); + } +} + +html.dark-mode .iconfopen, html.dark-mode .iconfclosed { + filter: hue-rotate(180deg) invert(); +} + +/* + Class list + */ + +.classindex dl.odd { + background: var(--odd-color); + border-radius: var(--border-radius-small); +} + +.classindex dl.even { + background-color: transparent; +} + +/* + Class Index Doxygen 1.8 +*/ + +table.classindex { + margin-left: 0; + margin-right: 0; + width: 100%; +} + +table.classindex table div.ah { + background-image: none; + background-color: initial; + border-color: var(--separator-color); + color: var(--page-foreground-color); + box-shadow: var(--box-shadow); + border-radius: var(--border-radius-large); + padding: var(--spacing-small); +} + +div.qindex { + background-color: var(--odd-color); + border-radius: var(--border-radius-small); + border: 1px solid var(--separator-color); + padding: var(--spacing-small) 0; +} + +/* + Footer and nav-path + */ + +#nav-path { + width: 100%; +} + +#nav-path ul { + background-image: none; + background: var(--page-background-color); + border: none; + border-top: 1px solid var(--separator-color); + border-bottom: 1px solid var(--separator-color); + border-bottom: 0; + box-shadow: 0 0.75px 0 var(--separator-color); + font-size: var(--navigation-font-size); +} + +img.footer { + width: 60px; +} + +.navpath li.footer { + color: var(--page-secondary-foreground-color); +} + +address.footer { + color: var(--page-secondary-foreground-color); + margin-bottom: var(--spacing-large); +} + +#nav-path li.navelem { + background-image: none; + display: flex; + align-items: center; +} + +.navpath li.navelem a { + text-shadow: none; + display: inline-block; + color: var(--primary-color) !important; +} + +.navpath li.navelem b { + color: var(--primary-dark-color); + font-weight: 500; +} + +li.navelem { + padding: 0; + margin-left: -8px; +} + +li.navelem:first-child { + margin-left: var(--spacing-large); +} + +li.navelem:first-child:before { + display: none; +} + +#nav-path li.navelem:after { + content: ''; + border: 5px solid var(--page-background-color); + border-bottom-color: transparent; + border-right-color: transparent; + border-top-color: transparent; + transform: translateY(-1px) scaleY(4.2); + z-index: 10; + margin-left: 6px; +} + +#nav-path li.navelem:before { + content: ''; + border: 5px solid var(--separator-color); + border-bottom-color: transparent; + border-right-color: transparent; + border-top-color: transparent; + transform: translateY(-1px) scaleY(3.2); + margin-right: var(--spacing-small); +} + +.navpath li.navelem a:hover { + color: var(--primary-color); +} + +/* + Scrollbars for Webkit +*/ + +#nav-tree::-webkit-scrollbar, +div.fragment::-webkit-scrollbar, +pre.fragment::-webkit-scrollbar, +div.memproto::-webkit-scrollbar, +.contents center::-webkit-scrollbar, +.contents .center::-webkit-scrollbar, +.contents table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) tbody::-webkit-scrollbar, +div.contents .toc::-webkit-scrollbar, +.contents .dotgraph::-webkit-scrollbar, +.contents .tabs-overview-container::-webkit-scrollbar { + background: transparent; + width: calc(var(--webkit-scrollbar-size) + var(--webkit-scrollbar-padding) + var(--webkit-scrollbar-padding)); + height: calc(var(--webkit-scrollbar-size) + var(--webkit-scrollbar-padding) + var(--webkit-scrollbar-padding)); +} + +#nav-tree::-webkit-scrollbar-thumb, +div.fragment::-webkit-scrollbar-thumb, +pre.fragment::-webkit-scrollbar-thumb, +div.memproto::-webkit-scrollbar-thumb, +.contents center::-webkit-scrollbar-thumb, +.contents .center::-webkit-scrollbar-thumb, +.contents table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) tbody::-webkit-scrollbar-thumb, +div.contents .toc::-webkit-scrollbar-thumb, +.contents .dotgraph::-webkit-scrollbar-thumb, +.contents .tabs-overview-container::-webkit-scrollbar-thumb { + background-color: transparent; + border: var(--webkit-scrollbar-padding) solid transparent; + border-radius: calc(var(--webkit-scrollbar-padding) + var(--webkit-scrollbar-padding)); + background-clip: padding-box; +} + +#nav-tree:hover::-webkit-scrollbar-thumb, +div.fragment:hover::-webkit-scrollbar-thumb, +pre.fragment:hover::-webkit-scrollbar-thumb, +div.memproto:hover::-webkit-scrollbar-thumb, +.contents center:hover::-webkit-scrollbar-thumb, +.contents .center:hover::-webkit-scrollbar-thumb, +.contents table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) tbody:hover::-webkit-scrollbar-thumb, +div.contents .toc:hover::-webkit-scrollbar-thumb, +.contents .dotgraph:hover::-webkit-scrollbar-thumb, +.contents .tabs-overview-container:hover::-webkit-scrollbar-thumb { + background-color: var(--webkit-scrollbar-color); +} + +#nav-tree::-webkit-scrollbar-track, +div.fragment::-webkit-scrollbar-track, +pre.fragment::-webkit-scrollbar-track, +div.memproto::-webkit-scrollbar-track, +.contents center::-webkit-scrollbar-track, +.contents .center::-webkit-scrollbar-track, +.contents table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) tbody::-webkit-scrollbar-track, +div.contents .toc::-webkit-scrollbar-track, +.contents .dotgraph::-webkit-scrollbar-track, +.contents .tabs-overview-container::-webkit-scrollbar-track { + background: transparent; +} + +#nav-tree::-webkit-scrollbar-corner { + background-color: var(--side-nav-background); +} + +#nav-tree, +div.fragment, +pre.fragment, +div.memproto, +.contents center, +.contents .center, +.contents table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) tbody, +div.contents .toc { + overflow-x: auto; + overflow-x: overlay; +} + +#nav-tree { + overflow-x: auto; + overflow-y: auto; + overflow-y: overlay; +} + +/* + Scrollbars for Firefox +*/ + +#nav-tree, +div.fragment, +pre.fragment, +div.memproto, +.contents center, +.contents .center, +.contents table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) tbody, +div.contents .toc, +.contents .dotgraph, +.contents .tabs-overview-container { + scrollbar-width: thin; +} + +/* + Optional Dark mode toggle button +*/ + +doxygen-awesome-dark-mode-toggle { + display: inline-block; + margin: 0 0 0 var(--spacing-small); + padding: 0; + width: var(--searchbar-height); + height: var(--searchbar-height); + background: none; + border: none; + border-radius: var(--searchbar-height); + vertical-align: middle; + text-align: center; + line-height: var(--searchbar-height); + font-size: 22px; + display: flex; + align-items: center; + justify-content: center; + user-select: none; + cursor: pointer; +} + +doxygen-awesome-dark-mode-toggle > svg { + transition: transform .1s ease-in-out; +} + +doxygen-awesome-dark-mode-toggle:active > svg { + transform: scale(.5); +} + +doxygen-awesome-dark-mode-toggle:hover { + background-color: rgba(0,0,0,.03); +} + +html.dark-mode doxygen-awesome-dark-mode-toggle:hover { + background-color: rgba(0,0,0,.18); +} + +/* + Optional fragment copy button +*/ +.doxygen-awesome-fragment-wrapper { + position: relative; +} + +doxygen-awesome-fragment-copy-button { + opacity: 0; + background: var(--fragment-background); + width: 28px; + height: 28px; + position: absolute; + right: calc(var(--spacing-large) - (var(--spacing-large) / 2.5)); + top: calc(var(--spacing-large) - (var(--spacing-large) / 2.5)); + border: 1px solid var(--fragment-foreground); + cursor: pointer; + border-radius: var(--border-radius-small); + display: flex; + justify-content: center; + align-items: center; +} + +.doxygen-awesome-fragment-wrapper:hover doxygen-awesome-fragment-copy-button, doxygen-awesome-fragment-copy-button.success { + opacity: .28; +} + +doxygen-awesome-fragment-copy-button:hover, doxygen-awesome-fragment-copy-button.success { + opacity: 1 !important; +} + +doxygen-awesome-fragment-copy-button:active:not([class~=success]) svg { + transform: scale(.91); +} + +doxygen-awesome-fragment-copy-button svg { + fill: var(--fragment-foreground); + width: 18px; + height: 18px; +} + +doxygen-awesome-fragment-copy-button.success svg { + fill: rgb(14, 168, 14); +} + +doxygen-awesome-fragment-copy-button.success { + border-color: rgb(14, 168, 14); +} + +@media screen and (max-width: 767px) { + .textblock > .doxygen-awesome-fragment-wrapper > doxygen-awesome-fragment-copy-button, + .textblock li > .doxygen-awesome-fragment-wrapper > doxygen-awesome-fragment-copy-button, + .memdoc li > .doxygen-awesome-fragment-wrapper > doxygen-awesome-fragment-copy-button, + .memdoc > .doxygen-awesome-fragment-wrapper > doxygen-awesome-fragment-copy-button, + dl dd > .doxygen-awesome-fragment-wrapper > doxygen-awesome-fragment-copy-button { + right: 0; + } +} + +/* + Optional paragraph link button +*/ + +a.anchorlink { + font-size: 90%; + margin-left: var(--spacing-small); + color: var(--page-foreground-color) !important; + text-decoration: none; + opacity: .15; + display: none; + transition: opacity .1s ease-in-out, color .1s ease-in-out; +} + +a.anchorlink svg { + fill: var(--page-foreground-color); +} + +h3 a.anchorlink svg, h4 a.anchorlink svg { + margin-bottom: -3px; + margin-top: -4px; +} + +a.anchorlink:hover { + opacity: .45; +} + +h2:hover a.anchorlink, h1:hover a.anchorlink, h3:hover a.anchorlink, h4:hover a.anchorlink { + display: inline-block; +} + +/* + Optional tab feature +*/ + +.tabbed ul { + padding-inline-start: 0px; + margin: 0; + padding: var(--spacing-small) 0; + border-bottom: 1px solid var(--separator-color); +} + +.tabbed li { + display: none; +} + +.tabbed li.selected { + display: block; +} + +.tabs-overview-container { + overflow-x: auto; + display: block; + overflow-y: visible; +} + +.tabs-overview { + border-bottom: 1px solid var(--separator-color); + display: flex; + flex-direction: row; +} + +.tabs-overview button.tab-button { + color: var(--page-foreground-color); + margin: 0; + border: none; + background: transparent; + padding: var(--spacing-small) 0; + display: inline-block; + font-size: var(--page-font-size); + cursor: pointer; + box-shadow: 0 1px 0 0 var(--separator-color); +} + +.tabs-overview button.tab-button .tab-title { + float: left; + white-space: nowrap; + padding: var(--spacing-small) var(--spacing-large); + border-radius: var(--border-radius-medium); +} + +.tabs-overview button.tab-button:not(:last-child) .tab-title { + box-shadow: 8px 0 0 -7px var(--separator-color); +} + +.tabs-overview button.tab-button:hover .tab-title { + background: var(--primary-color); + color: var(--page-background-color); + box-shadow: none; +} + +.tabs-overview button.tab-button.active { + color: var(--primary-color); + box-shadow: 0 1px 0 0 var(--primary-color), inset 0 -1px 0 0 var(--primary-color); +} + +@media (prefers-color-scheme: dark) { + html:not(.light-mode) .tabs-overview button.tab-button:hover .tab-title { + color: var(--page-foreground-color); + } +} + +html.dark-mode .tabs-overview button.tab-button:hover .tab-title { + color: var(--page-foreground-color); +} \ No newline at end of file diff --git a/doxygen-awesome-css/doxygen-custom/custom-alternative.css b/doxygen-awesome-css/doxygen-custom/custom-alternative.css new file mode 100644 index 0000000..e66c1ae --- /dev/null +++ b/doxygen-awesome-css/doxygen-custom/custom-alternative.css @@ -0,0 +1,54 @@ +html.alternative { + /* primary theme color. This will affect the entire websites color scheme: links, arrows, labels, ... */ + --primary-color: #AF7FE4; + --primary-dark-color: #9270E4; + --primary-light-color: #7aabd6; + --primary-lighter-color: #cae1f1; + --primary-lightest-color: #e9f1f8; + + /* page base colors */ + --page-background-color: white; + --page-foreground-color: #2c3e50; + --page-secondary-foreground-color: #67727e; + + + --border-radius-large: 22px; + --border-radius-small: 9px; + --border-radius-medium: 14px; + --spacing-small: 8px; + --spacing-medium: 14px; + --spacing-large: 19px; + + --top-height: 125px; + + --side-nav-background: #324067; + --side-nav-foreground: #F1FDFF; + --header-foreground: var(--side-nav-foreground); + --searchbar-background: var(--side-nav-foreground); + --searchbar-border-radius: var(--border-radius-medium); + --header-background: var(--side-nav-background); + --header-foreground: var(--side-nav-foreground); + + --toc-background: rgb(243, 240, 252); + --toc-foreground: var(--page-foreground-color); +} + +html.alternative.dark-mode { + color-scheme: dark; + + --primary-color: #AF7FE4; + --primary-dark-color: #9270E4; + --primary-light-color: #4779ac; + --primary-lighter-color: #191e21; + --primary-lightest-color: #191a1c; + + --page-background-color: #1C1D1F; + --page-foreground-color: #d2dbde; + --page-secondary-foreground-color: #859399; + --separator-color: #3a3246; + --side-nav-background: #171D32; + --side-nav-foreground: #F1FDFF; + --toc-background: #20142C; + --searchbar-background: var(--page-background-color); + +} \ No newline at end of file diff --git a/doxygen-awesome-css/doxygen-custom/custom.css b/doxygen-awesome-css/doxygen-custom/custom.css new file mode 100644 index 0000000..23b91c8 --- /dev/null +++ b/doxygen-awesome-css/doxygen-custom/custom.css @@ -0,0 +1,101 @@ +.github-corner svg { + fill: var(--primary-light-color); + color: var(--page-background-color); + width: 72px; + height: 72px; +} + +@media screen and (max-width: 767px) { + .github-corner svg { + width: 50px; + height: 50px; + } + #projectnumber { + margin-right: 22px; + } +} + +.alter-theme-button { + display: inline-block; + cursor: pointer; + background: var(--primary-color); + color: var(--page-background-color) !important; + border-radius: var(--border-radius-medium); + padding: var(--spacing-small) var(--spacing-medium); + text-decoration: none; +} + +.next_section_button { + display: block; + padding: var(--spacing-large) 0 var(--spacing-small) 0; + color: var(--page-background-color); + user-select: none; +} + +.next_section_button::after { + /* clearfix */ + content: ""; + clear: both; + display: table; +} + +.next_section_button a { + overflow: hidden; + float: right; + border: 1px solid var(--separator-color); + padding: var(--spacing-medium) calc(var(--spacing-large) / 2) var(--spacing-medium) var(--spacing-large); + border-radius: var(--border-radius-medium); + color: var(--page-secondary-foreground-color) !important; + text-decoration: none; + background-color: var(--page-background-color); + transition: color .08s ease-in-out, background-color .1s ease-in-out; +} + +.next_section_button a:hover { + color: var(--page-foreground-color) !important; + background-color: var(--odd-color); +} + +.next_section_button a::after { + content: '〉'; + color: var(--page-secondary-foreground-color) !important; + padding-left: var(--spacing-large); + display: inline-block; + transition: color .08s ease-in-out, transform .09s ease-in-out; +} + +.next_section_button a:hover::after { + color: var(--page-foreground-color) !important; + transform: translateX(3px); +} + +.alter-theme-button:hover { + background: var(--primary-dark-color); +} + +html.dark-mode .darkmode_inverted_image img, /* < doxygen 1.9.3 */ +html.dark-mode .darkmode_inverted_image object[type="image/svg+xml"] /* doxygen 1.9.3 */ { + filter: brightness(89%) hue-rotate(180deg) invert(); +} + +.bordered_image { + border-radius: var(--border-radius-small); + border: 1px solid var(--separator-color); + display: inline-block; + overflow: hidden; +} + +html.dark-mode .bordered_image img, /* < doxygen 1.9.3 */ +html.dark-mode .bordered_image object[type="image/svg+xml"] /* doxygen 1.9.3 */ { + border-radius: var(--border-radius-small); +} + +.title_screenshot { + filter: drop-shadow(0px 3px 10px rgba(0,0,0,0.22)); + max-width: 500px; + margin: var(--spacing-large) 0; +} + +.title_screenshot .caption { + display: none; +} diff --git a/doxygen-awesome-css/doxygen-custom/header.html b/doxygen-awesome-css/doxygen-custom/header.html new file mode 100644 index 0000000..7f37e6f --- /dev/null +++ b/doxygen-awesome-css/doxygen-custom/header.html @@ -0,0 +1,90 @@ + + + + + + + + + + + + + + + + + + + + + +$projectname: $title +$title + + + + + + + + + + + +$treeview +$search +$mathjax + +$extrastylesheet + + + + +
    + + + +
    + + +
    + + + + + + + + + + + + + + + + + + + + + +
    +
    $projectname +  $projectnumber +
    +
    $projectbrief
    +
    +
    $projectbrief
    +
    $searchbox
    +
    + + diff --git a/doxygen-awesome-css/doxygen-custom/toggle-alternative-theme.js b/doxygen-awesome-css/doxygen-custom/toggle-alternative-theme.js new file mode 100644 index 0000000..72c3731 --- /dev/null +++ b/doxygen-awesome-css/doxygen-custom/toggle-alternative-theme.js @@ -0,0 +1,12 @@ + +let original_theme_active = true; + +function toggle_alternative_theme() { + if(original_theme_active) { + document.documentElement.classList.add("alternative") + original_theme_active = false; + } else { + document.documentElement.classList.remove("alternative") + original_theme_active = true; + } +} \ No newline at end of file diff --git a/doxygen-awesome-css/img/screenshot.png b/doxygen-awesome-css/img/screenshot.png new file mode 100644 index 0000000000000000000000000000000000000000..f40c6e1246e814ebb1f431c0c4738d5befbbb360 GIT binary patch literal 216518 zcma&NbyQqi&^$W0!{7vh1}C@$_u%dj+}+)SyK8U{!QEXF2p-%axCdvDcXIDf?)Uz9 z>&+V03PU*ioZj8NtE-AgB?U<|WI|*R2!tjrC9VPjAq0a!FvE!Oz$b?*{AC~zs;iZl zn3A}ai=(ZP7YL*kTB7OkN%aR_uC9u-We}niQWp|MmlRTg1UP|y5mA~f2y7w>t}BX0 zu7<-!(Qs84pPs`_XfoEsgY)szQc|9m(6cS?L_*TK?Yf)f>)BX^?0#V{TVv<;08LTJ z-g_ad;Ro_tb@P+6rEqdF=16!$gY)6adr2~`?vdZ{2@1jsziAC%cBm1vqt*PR*8IZr zDkNb*rgi}(JS>*YtaNcj){P44&Sg&ChY?N@UiY@{mJ3Z6u_X(K677@^ZJ28n31y#a zZ8M;u3xaXt1DO)W(@eq(ccA>Kg!boZED{S|l&1&Fl9M1gfei++h52E&jl8^))jeqj z(UlC~Sz{3H&HYW-A$*X`;9IZG6Oqb^ZwB9uj6>!6zi=h6zX^e2RRX<90Fe+BzXtqB zrbX~w?i0cOQG}&-6Uf<>$;YD;YIG)*&cV*5pzaf~5e;{=4+6>H(iJ7mJ(klM^ab6( z%0;ZfcGg-($dkt<$QYY&_?oAE_>97OLei*|Jt_Zr5pg?IRKm0HqeX+S^XFlFoph@G zTFxh)+|G@f(FH#jn!zxZq;I#ilz{dK2Efq83Uo=n5Ao|t^xss4pK6*4PyYGCtH)2{e zD@e)VHDgrh8cdY$%8n zdVLVM)iNUp_vc5>ax6vk?l7 zCXtQaR;bU2IM8jfnhw5ROaupG?4f8Xc749UEw(*w+2~^aacbe zM10v4@dS~;)Q~&2?sT_q2$LAxASohNg@lLLgt+%tNpBlJU?|7IpHBIQl;UM>%tN;X zb9G%P@q=~3)10X7p+7k)9)!mth)wDz>{@PXsE6JJpPsYb?^#)1)7s;tu!UfWI^8>! zG$%JNzn*+3eT4Rme^JKPjUeuwFs7-!S~RL8sjW59f|-vY zR^IA6^IqN1gIULV-1!me4m{Gx?7f=0%9h5?{Nb&%KsxjLpPF|36Q)ZXZ69<~CXL5T zvB;wtc015b+B(`gVDcZ&m3z9^Ss<^f;JwhAPnQ}X=-|i4NA!T*LO#%kDYTZ?u9|F^ z)!Ah`P`2(5%~6zJZ>!tEo4TS1XB;Mm=#@b*KSzi?gF#^E{ythTLXt3H2I9B(pZ%B+ zRQpg_@KXZWYEdhpk9(=BvQVknv$r5rMx>%V3gwg!{Cg_6O=8flc@V0 zrWo5R)>oW0C5$lNyquW#?Ty5eB}Z0>f^fq$oh2qOsov*mk#AFLmc-uBT@m_XE7SOv z81O8NF_GHFOc~6>ecQFJ?@^LX8fsN4p}+N8*L}Rtt}#5-!oP*0*+$I{?dV01>rZwP z6oktQWgcGG;=AO1!tsX-2=v%7Ky>{~*O$4exQR84Rga{KL=}SE@7^!cZ`GR4i|7z3 zPLXV>cpc=!8k-@Ot?)^1Rd`jFU%{42km5E$iqa&Boh|`Kay#*lG*xj^@mjG-F_#L$ zp@4R@t%y5~WWwwZ6=&AA&z;e}DXSm-WzI?tRBY*9Qa(flvc=Y?)W^<9wTU0*U#r}d z-~JM|#^Ma;O>Ym=krj~dlJzSpDKRVAE#v$sTgfSD6FVMiJp)RpC*AE?i zW4T{+Ghe58@?E6MWYY_6%EqR54<}}-ehC!&h_y(@7jTO*D=;fM)U7jhU3pJlOFz0l zZaqRjKRoK*C>{wJ8=~64hxb|hG_f_wHg_ceqn)6&!t=nJ!TX@L?bjLL9Xe{}Xo{&< z)3L9!tvhL|Z;@%HZ(g=>o6NF4waGE-nrZ*hzB1fz-Z+l>h49NtGmfr-ZsMu+N<;Jc z$;qk8Dc<7Tia-N*{r)ok(!%0~TRtBwpPW;$TfYx7AJ0B_y{$&R9I^yn4F0c1iW1ZThMdf54`30lJ2| zW^!F{-T7SST!EA*4>j*bklPo{cgGJOl6&>;KJ;1HL#R3+jDO0zAAo8iey$)ug#^yP2N+L)69H#pT64iZy>F|f4?M;R${4APL`SZ~#1C{%n%gVIQ^h6H9!bPWsXyfDcanyT zIIncyN?pf_c2{sCj6WBWZ-D%Nb2AX92+@(^z~ZXmb>?NU-3S-x7c|y-Wz9B9%;w@r z;5@St=S}3Ta|}2SufD-BueY$z4E;HpJ;$-)efzXT>_V}Bk}aF_h3_ujxMlm#cF%sv zgiW>sSHQ%Rq>#jmnrfjQ1#?>+nPFdP=)LG=f0_hI^gPp}3O#L?(w>Hf@~stXz-4Hj z2C9k=fO2IE=l zBkSFxTTWIR!ujP&z2@6l-syIm)Phu>g)h|xjW28PePPY9(dSL2L{ zxuwZ~!J<-Wc@Kp+ z0k4~18LEtBMT&WR*iL)DwQrY9_Ms<<1#?+STv!WW3cmzWII3?GV#5?XT*1wZ!cuvPb3^Pf8==wR0kYh{AuYCeX%|xSy{W3d8s(R+2$U0aDO^|@K9Cs zoqTTba`4$m?dJCHxe7iHZy;3_5H7M*^JsmqfPQLuz`JxDgiq64+ z61czz$}fZJ4czBD`f#&UYXH9SY90(Vq@S*WCfw=#_y z%8;8_QT78##r^c3sYgi9g>gk*|D2z_!c)U0^R8v+DFR~%lB1Ni3kZZq_4f-(T7~ig z1R?`Ti;JjvW}mEixqjMB<$Bx~C^JumA4~hKOmgwwl*r-$HIN*gof1Afff)uY<;*92 zciJ(pm+r7OC*6KUmE*d9ydo_{Xqyl7At)rH4a%gKi!1nzz)HQXb`m2-R!Nc!XRgaS zWaLf7?os3)tfVVHI>5?k8?)HOIQ#FNC-q4XbciLuE!6we%5S=y8|W6 zKf8jWZkk{XwbJJ*Yho*#aE=9!q(>|^4945z{kp8HnCs7cns0Ekef)Mfj%Bm`{7|nR z_q|^}M=Ly0Ll@%S06+Q^8s~}An>Jf0rELA zx-}kOm@d!>BzmI1UmCy1W;z9KL%q%kSGzZ+|YXWgGt_(#;7Kk`GXe?S0-065wvQA)9*s!3pJ zYO$P{$C;9{WEEx8?l{i_>e|>*6p}sIhT-H1QiG<=5%6)}1%gmyBY4*~madqm|BMu0 z;q9gu4u*~@1c`!X2(DvAQW&19DgN)PFwvb{x=FOaig5e#1Aw-{u^%xb#iwRxgR85V zTpK;|yNZY}Jy&`35sl`0v#iwVs7|~WPkuKglX0?_1+pYpD&R?(CrxCoz!O~)+&<1b znb+U;FQi-O1vsKABt56xuuJdu9b0VR2hVHbz(vuMg+QyT{~U{ony9Y6hnxpYwYcmv z$uHcvfw*8iG0mGUyh?sf>_ap_1Q_|I!!d8>dLU~K=UUAt6*V~F13M)tQ)t9d1koEW z;{SaW>GI}$3BQU-MaM5FQ@m_XMPF- z$wWmf>uA8|O=9$HU?6_KTleX)8B1$H;E>lv*rWrUgQW6oVqMIfa6#%I`hd&mJcDPC zfIE*@k5*cKbz125Qnb;0Y|Q_>lwazwyK{1KEP0$^ZxGN8@6PlVJ1j7;yS=28aqfKu zL!zRTbacX^kajSUaYdAIc7F8m&&{v;-ZO%Zp`PG`Pi*7enr*8QdIyzg)oy;WPd+{0 zEa>@^*&oQgV*O_w%-uHwEK>^$;c;>9jg5_)n?b>gO*Z(qCrfDZv#aRwOrOEf6%`b3 z(Tf@zQL$+h#A($+PWe3CyB?1o?Lb^0Pq6UD8`2%r1qM*5LN348a=Y8{%jHZ~D0hZm zO(rt+|4j`F3g=`af`h}uzO8}r#WoWJE{FA)U<8bIVmvf#a#(&6jM1^N@#2eOX-hks z^MF4;gnG)XmZ?EKLvQFq6w}vmSr|T-b>7VDzSE zt*u$w+xOqvt<;%~nR9S+cM#*X^;TmsF%X5*sg~w9bhJ2(XK|hnWRrKomt~Tl@Qm-I zz?6G#h3BOIfjC%Ki7U96x6cIojLX9S^3+Z8w_H9JfLd!M$;Z!j5lar?s?`Z^D91*@C1Tm_ddwojlmLrz>|41K}7R zFpE(6+>rZZ_O9eoxlFbm`}17Rt?dgnI;x2OzAP<)G9)Cz*jn>w+1^cmAtELwwhtFC z%BZLy5Hf-u9UWyc5)Hllvhh+q#1fMS<%tt$M4GPm<^+!AtcS$^o}o|4@<8w;uw>zi{u& zxz&)7#CH&5#j>i%h!;K6($R_J&Cpoe*rep}c`(CV@CI@uNW=R;g{13somgwY{*OX5 zlcEDUn384-#uqNTew*WkcR30`LSee(*{C zm(S4Gdq!HI_#byQiVXt;v)JK*F<<3_OT^s?^|!(z4{%gu28~$>W&$_%QIN^;r0B}F zicK9aRy@|!iz+JOQ~yV(IOe73rk9taJU09g6rXn|Ke(T?u8?Eqq>EDodGe!^!&ZFz zrW%exS`A-I{9OiqGDj#NuKHLBXQ)dm^1qq!QHnmbKL`e)_G~x(a%POV?lJu%72V%6 zCn_q6#cb4c_hM@x8q^5_9;jrtRH6FXlb;23;Qw`%Fl7%9Zo$V3u}VL0#@o}iWA_i@ zJc%-;Afy-uhASv7OM~;Ds6gFuD=)YqlCMT4{Pz}UM}UlRQN`x6Ukz-s$s6t!{&kuV z;jAz_UU9qaxQJj_;n$Uesu3j{#egdTWdZ-+ZJD;jJ3Swn(CfH(a+w6Od&7zEZJ|+_ z4IvpQZ{rw_Wxab{0UlDOkjWO$Soq%uw`@#Q*}lKr@q|<{-jAs&7IamO1FL>asXk6n z5ygzc@0Eji^Syb`DIZ)&dnPXV-!yfFDo**}eNC&ccZZzoxs6mjYth{XR` z=c9^DV{^0d^W%-@wqk(zdpsB5*PbYYlB0ujOfTrHjDcJ)WPP8b@Geu1B2|VwRYqji z?SPPb;-ALeCVx|Y0US(%q`>>hU#L^RX2nPkhmI=bLsL%CN-@VI?!K0q0*lP(1OH64KJFpZg5g zHF3dzA2U|s_M<%H%9|n)*gDDgcw&?@;cE1;NlDwC5Pkzh>Apl?bRdq%20#`3JL4=2)W#YpAx1u?CVWFY+^IrU2lFO=X zXc-wLXmOnR_$eqxv7(1+&92P(ucxdVo0{5)(UrF_YiD~W;wa1Hujyt({w6eXwl=1% z271VVQA%3cZ!7y2xTvMv%-@FVCq=D_7#^*pp@FQfzJ?zCPtk_;?p)?q zR^kMTbMOXscMFzPH4-87JaGT7%N`ya^ak|YQ;-Bau>zR_MB5~mooMj|$JBHI?QiAc zwp(&UdGZGtvP8_NP=EfXCXqucDuCw>ttN^X*@^gAM9aY7!uK9XZ6KqKj_0d9FZvLs zoPS5GY=L9VqMk!%sdbcb3EKU`cK(TgB(N_WgrSABv`pv?oE(35OgZS%lOOo@Z($I| z^0J3UM$q0Br&#j4A_hFpl3p&`)Bxd}UUW~(>5vQ-xWlH5e}Jzj7%5pXViWFc_n z`)9`}2;ut-!CQ`)0Eoqm9?C$arWmbTU)QfRc%>)tx;Fx9qGf=*urJ$vO52P@4i+1? z;^l=Fl;8T{#FHDeUKM}Mf2o)t4FMiyp zVp=!JCMDq*7;1!SNp#d*r@b~hP`9Da>DBrxQs z_i^UA7&&YR7!h79<3n8(>F>x0XWC3T(FL>+QSz4pMIaR7YMVgEfDQr~*AXQBFcqN+ zE=h?Hr#Lt`5Z2Vh$BO)4FilxoJMzyTXWA&|GX#3a*x17-Uf4;>Xpu`5 z^Wvyv(+m%1N=^WdTS6wXNHTu=Ygul;%cS7nT6D#uxN;cio=||7B|ouc#e~{Z=-bcr zLq{M)M_r~Nhx*W_Z4n;&y?wg-J$VTF>z@mP=tG5MOZgP<9X8$Bv*ND4^>W0{ig8)OpG-tF!?4=jrL`g(rV`dAYE`8-_TggU_Fqu zO;w^d(gDTI-Q7+>I7xpb_J}etB0$bMYVw6x&X*bx*7Vjcyamej8WE|er~n-3s&ME^ z2->`1d-D&%rNaWi^DoUcW%`2e6?Qm-9`W@3O>`Iz}+g4BOIUO-tv5wB=JWi z;<9z*!=Y$L{8Owj1)LhYa!7?Su|(Xwk%sE(wT6A7G0e;eWZ7Lf&>GPeh~gAoi*+Ul zuz^c1%zY_zs+C6uTR&|QXXIYCi|@2c-5T`-ZM&ss4>{0D1!GJ`;-En8XN!?$V`&BL z?cS97(Cvso9e&fS`lu_(7or9}jLt7BLjWGzm9Nog7XJ_iHesIQWVH=D8lTx*G~M!C{3}QBi?h9qTG7i9q7@8xuIncou-?MNc>I z=SgGIi`w4aW?x@mK?NoTL!eJCcKL9F@@r}^Fod31syohjKe>!^4v+*0vZBI}`d*Mz zQUZfRxD@5*nHiOqfkLBVE5c^`wWy7ky@d}>+aW-EodzSKPKYg8h=eNP+(uH@|5{l1 zVj#7d>vJZsf7Vkv{Lyx!4Mr526UD}H2v_qrB|05d?$cHBVz(Uv8RgOOaVF}7Dlm6x zHCc1EcXU+x_6(MArsKI%5P&Ky_~ z!r#U{ZQ1O7BL?(K0NCOKgP_afVpO3p;*~?tG)1D6;rV)(MUImXHSnvzAu*86;{wDp za(;eZn+#hw^8hb$8-ySSSzY`cgkZ~85F%+%EnjIPMJ#j)&()D_?r`Y-{^?r3~ zWd%jp_>cTe#$GbxuezT|&V z%Y(_w)5E>z3K##&J>ja~ogR<85`7f()nwqbDx%9~Z&0)htc9xjoE2J*9QE}2dK}P5 z%En!RX=A<1=MtELZySHiOcw)z#1ObnNJb|aC35Q1tF01euhI) zSb6arO`*Hr!U%}a)c1n>!tDSL`a5&d($f>V;PwY{SZpYZB&rm4`wRKMLN-hw&31pg zYa4aLOKc_AbngKqNU+ue-+RLsCXtay`RJ;Mc2n}}0s?EvvTv9Up^oaiBsa*^<#jS` zhcnM;wN9MUcp+va^LjJ(b8JmfkJUSwD7O^YrwesY@;PT0?!q)--Zq5G()j86eI%U8 zPjNHa3lvH`Y?r6UtD)Rq7Ivxz9E8Kv?}MQ{={pJbtDuXQc*~fy!*dwG z<}00&_JNjuztZyzD10IIc6OmDSR?VILOZM#729dL_99MBtoq)ER3P)vi$<$imVlS1 zRl!JpN&sK5Fa!@BEJ=x2q{~s)84VEKuRZrj7;H>&WrLOdljap2GF+sgfN4@m-At_s zbm0F0=h}UbDx*p#SDlSmzUNZk-jHRduv=re8f!o} ze@}5USzvK)pp17k@aqU1QYg9%!6@N;r*YFyblaziBYx;fe7P=f>E}Z=_r>Mb zcRsEi-WR+Qiz_tcl6Lj*C~9iL4Rl?%8SI;}PKUUG%;4X6L`Pj$j|MWpa z=o$>L9>?L|dMyMYZ&uw`>`bUJZNKok(W|Ks^*zF{fCy%K*9Cl70{WoU)YaRFN&YrH zOw3&#a@g+c5?!*8-saPlI`eT-rv*KaxFuHc0k7QV@^Zw~)YOCHV;Gjll~?=q&Lyk; zx9H)QYv=xVm64k$Zgc9I1wB0*U%@ZO2Cq@TNskdEOlD#8`yE}0TeV&m97|E-H`+`c zUERx(5z>(>X8v<`T5*n_3c2{Gz)m=GP<`f`7Yv%GAsPDhL$x3U4+d=Bf-EJ)fcgHk z%;a201qW6}Rw;GH@wxy~AOTUnoO3{x^%d}W35l}{5Wcx~0(aLwpr}H#oV;&Z%Ejsj zaTqvhNgt}#I%+o#8GE$ui-2`PjUr2-e@`H5Uf8Z)2P#v z01L7b*6GPUkrB8uXK$nN)tAfRC6;`B`tZw$?qE$VgZQuKzs_d@-Oi@RKl)TBvPJc92RWa>o$uucpo3{|OIaIpL^0942xQRaH%P zS=zZYyxbm|p9YbUh3yDXhBO624-l;JaiU15y0E_-Cx$0VQI3b9K({_td_#GO54=)V z*M^gzT?BZunFJQHx`0=Ig0P?;$uu4RC-njP>*580bTg-ALxex^!;X_cSJz^#(L4K& zswuu-(?iRhUhFeg4Wnk$g%Shv-P-Evm7m(MdR}g7pg`xHSLoHM?xY$6&x+C%NG`OSx;x z4Q9fogb0jGR#IzidzDWR+d>r-i&+#j5mLr_>kXV`UC5| zcKvTuNtnPkOrsBiZp)}w-PB;64J+Cq1DRLD0o&umhd7Qen?q%7mqBA-GLe-|q zuFA<;$AYa5RZuVjdM^tqkU(>%7yq6M-zD_)^zO$Daz!mP@zo^yp1iJDEY9Ah#4|{; z5D4>DZFSwP53Kt^^68PSZCqT|ciC{Q&h**h@y*w@q!4TH&FTm!zN~-OX8SPHN@7-kn2#qys4-?uXQZho zOGj4uJ251cEY01<1~~G}SJ0pk=c4~8F+UO-jA^rZUL`JIq78#@@htY@qy`Rk?A*n< zm=Qa&mUGddKGd*NZeBiMqDj;~e7AwiL~TZ}&2!K-ryI|~Q-KOIX|4INi{d=+^61U~ zvS=b@V`Tvg8Q1vcNND?Xe_38tHI%#NlP^oGf(+nnAe?HNn*S$z+w!Zb(Bg%<;V;FZ zUCbwkZx#%~|NQwQGIFxif$!$#ri2T}pjkbb&C{S4mG);1U|NAO69j57A16%2RL^@p zv8eO8vj_D8zUo>@PBvlC7%ig~&Y|2dp1 z-}a*uH6A+)yT(2;4e2S)dRA2i70!No#Tyf{x8jmJ@F}01VW4q2#iDAuZJ3+idch3M zj*d4^hGi0YAP+V0*)h1geS08Wu`3?`oeo8ST+9J}&orF&&S4XU-M;q;DIJ}zyYn6H zRR^uj%1W}LV5Artn)!-@gs?i!sz2m3Lnxp-^P4H%X!7;^^__{?x%g)|3AXU@%f7i&aO{jA(+<#0ZtdU($#_de}*RokS>DB(4h8 z#?2P!Sg+`9$_ty_)q)nK-NSbu)&ha)Wu64ZJse1#**>hd6H`%Xe5!TnnW<=o`+2JB zzP&7?Bb%6MhT6cUNo(F=^A%B8S(%Uv?6AW6+w|h>_7p6EjH4dPfyxJCNA;b3L^V)L z>3@3xG9#TE{2Ck0H)T3LFYyZNNZUxLll9ZzHlEYAn${L(AU&VRV_kZ_oes+2?APqy zxfGt|0A=oEpSQim5)~$N|8|z>6W{&k&o=^s2&2~*nAY7iB37IEm{}4{g8(ovV}_^n zMq=9mXwo4@E9RZq{)C?AcBD|>6xwlB<>oho2V}wLL&XkaoplC)$UH5i0#rmAfUN~h zt@;wQm+mAjrMLd?&L5i~|Ani78>_Eyd3l!lv&ZRr?0%jPNmRo_Zlob^2f!5Z8cb$! z+KA7q;lQz5Oo;305d%964ACqudp|L?`7{A_XXemVgIl(tp=A7pH&te-Ni-o$7@%QM z2OQ5VNNt3|3NuWI1xRoKyI?R$vNH`~>~@W!K&T|?vsfvF22&Z2e2~tI-om`LqC9~u zAi#6*7!XNNd89QGb9@^Z*s6|JPNH=Ag3K-YPl@IGM|+1q@#JMh-&o52oYS9&(vY;gb{4?o%vnB!I*!ZO;DI~E~VmN zQ(mGPpumn^GUHd3d0%;C?9dwzBLE2_(0gI6H|JY91A1`7>VPkKD2{NP(1BFuLmo#` zUV&%<7#`l31r>(5s}sGYx)pA=6fO5|d2umD)4*>{IxJkYFA>EtS z9To-(5HN4b1kBeMjwSR9@cf8U_XiN!zuG3i@Ajb3CjurKT6lO*WV7 zkaH1Mh!F3-5LM+>7IGy$O{Nutm0QNACTmkmoj%rX*hF=MSEKC$xXjP{_+oXb}zarYxxGb z#fN48_KB-{_CYL_48B}`LFR47@bI?=6=g{4Ncs$k*3FX%w+?D$Dm)Eiqk$pYgO=kQ z%}GO1#)8ZM$Ppw}$&nX}J9kvX=Ev@wr(&S9^AnT$X04;ubAP(<-QLV@j&~rCh3>|UQG%htbPAE@$$&s6EqZ!;-GNrh!Q@a zRqx5#?684urT&YQ&l@M1M)4!S|MT$v3rh(VeC|$z$*ErU90dJ_)7o3sy%_*zwp6i( zWb44Pv3?&8^6c-~wJy?f*d8ZE={)RW1x$4KUG^W|3Q~nl8;{%)1N`A+>;Ro+J#u*E zRrjA__@YedSnv#i>-;alZ??I26F47ES6c87T_00knO(R3%EUr1J3_U7D_p<{Ua0(A z&aQCx$0^w#`Svd2(O*`z9`sOwuKp-y?&O(v>8ICJC*33SMOy6Wm4n2f-W`df#l(UU zd>aJ*ol1kWOs~G%N31xoVAy#W(M5*Til-r!r{=`>t>Al=fgu{QLxTbab-EfKgO6 z?=j^HN=Zw1*ZEnno>bA)PXKFlRHp9FEv{C_t@fa?Q}HYzz+OpIe)3`f2n`hGPE@^F zDA3T55db2gw;ZPNhDXFBjoL`Q6?ATJtxa{1XfAs6|7m zW7UIUu|)aD@US>iR>JiCyngn1$5@%-PPbNWtoQsS+DPxSS5AD8p?q)I^LBai$btIi zb3f^=@xO7fwb)UC7aonmkKyA zX!|QDH7Ln|&5RExBn^2cnwEP+K8&Gh#-0kBvl>Xiib`#4-v7hv5>tY!dHa6jEoDwf zQyRrjo?%hb(X>-ahdp)NU~kD4&H?xnOcgGQOYB0RqG)bN)1#r?^OBM!!Mg&r2 zv!KAjLa;{lrywjBOZUEqJ?@^!xo?^UE!@y_ffyUF;6pV+V2yo^70F=;@Qwk$g>nB7N7@~ zt-5#bx6#OFx%M5K*X-XxnD1Zg+t1pM9Z#DUL}wdk@pw%qp%uzz@2BGfPO_%s)NH-4*7vS?v25oS4a&&DxL%9Jco?*;kAdOzwpWrL$TS$P6b;} zYBgbNLY$hBuN9ohz1nuMMl|D_jZs`HBm>r@c9ZB6SvKUKs^?#GiNoe_fbLqX06TJQEn;|PNT*8`<@z>A#t9AR=*~7k@Jh^VpEN|{eqmi z#Z0%m=!)P+tyxMO0u^CgXe)ux%Ywu&KUh^LVaeb%AN=?EHu~yzMsnWQ9Vsg})WQcg zF-$xLRHKRwm22ZxqGmA)s8Gvg1g_Xa*mAx0yeO0D03mn3*^ni0#law`zP>&Y!#3pa z=zt(}Pp(m=6MB|Q0>a{Rx0mG28P4%o|AEo6zx6$Fz|yvH<%cY-sNr-;6D^Tu>jw9~ zyOIJ-eSq>CwrcjRqk|~EMmu;}mU+moWi6`+Xj1e55}-(Q)DcZjOXF?v18!Et!{bg{ zvKon8A$gU*rMkLWgf)gsG~#MGJMWOvT4SiZg14ML%bA8Ge&=C7cOV!;kmaaiJd*Y` zyBakA6?I}?oCS1WCLiwKiqyXolw+8Bd+iOWSH(r8F|yEv|FWQc%6!6upaRTC141VA zQ#(XLD2Ko7?|t=M_CEj2LbkQgEyl93sAb({}3EZd%cjG=%kPPV!qVJ2|)ogJAJ z)w3q$*Eg7di^$+)&rEj$ztS&*y`ma&`i>3vXTSG&lPRIg=)~%_#dVU#x0IgmOCa>pFT@eg zwY$6f53{NMjYM2hlBQU#)?-qi|MtM7_4usgUgZ9L)|W5SzkC-D=g%*_m34Lb=wG$| zJsAq4cW%6axKH?P@?7731Z`F#3GxapA(c(@B7Xy913SCD`*r|Bq4O@}SJ2bbhv^%- z@Q%b06XA#zu=OziEF`B(RfhN_O#(#y<-JM#_F-9`JD{%6Q)coPT?PI40b-Ex*K7&h zV-#m2;SM;YonM9aq3FtiBH- zM(OPL^jjG)hT;b69nm%HF)ku$(qSr=VtyB4^K@VGEyk8+SGKFMYl@s`+<;F=&Bs&8 zYC-y@vUE7cn2&gMuSOBc!xOOu>+udnH_1VM4XfSk657`$w|lag~86 zAkzcg-U)Kbprp*&*A@6t%gTzb`}LVLzrwmuo4iKq*WAKZq9ln3eX28GXQyj<0o3^T z_{8zIk#hM3Ij?FwV)yY;t9fUz)&ME7*xqiRgeb>PW2zhMm z9y|*jzbT7vUPqqq4pQinozA;FwpKP?@PPce8#v2MNlE$J5(KFgv!KbxNxz_>AzWSz zVC1c)=G}F@ESRAvG7oChbqa+2dVRb>qB@z_kkoR29sA;q@;A=DSJb~YqmFhXBp?NdaNtZC!vZa7SE+{7rdsFO z+Pq+O0b2uR*bsW~F=;RE+!(9F)6~uw_wC6cO3t*+ne_K(ns*&=yd8C|H2{gb@!EIC zTGhVXDT>I!#bpf8B!J)H3_hLa_IxAWL^59I904kCGI}gcKg{vNiM!>$&Gq-^hpX}8 zrEpST&uPY7K0dzbsj0w1CB)e>&3(4cPBjfK-?>QutN=!jK(AbrM(SXIsgKWOACH9x zpy2)ePJFnVfZoF8ysiUJy3oT9Mf78D`!O|m-645oMLB&`Ix4{B8C>Icitc;IcelL> z<{koL=3rPnmJfYJ6O-7!^gaQAXlYp_^hGjqIZf@)3_pu!ca!fKKaYuuTm>= z(G?lf0Ayy+N^Nn8JJ|^@P^S{nXiu#h%AT_zhiuV=>CUB2$CBLOUL3UquWQZgZCpZ| zo7r)nrfv|O$>?-^9SPdpx)#DSY0Nxf(VxG#1Vl^Us@csH-ck~-}^9&+NoS=6A4Gh>uSXo#$ z-94)lRg5>f{VeV5;6MZk7Z1-`^}pEwvqO5(yMLQ$3m}EyvRnKVmb9Q*f87j5>F!Cv zI$r337nAWlyUGhL%r>BDnYL|R#<0oaDlhrtI6g;Ar>W$M4<)@za5~Emkdti@HviXYHq*YuX{}YHMEdpPHP#z zTuj6uH}@zBJP5E8fTFCeSzppt98VUVgcrz4KsX&08W~7(AgnMR`~?M19rYF!ty5n# zG|70>>P0ofs!h1CgsOd&IRsHHp&C+KWimy=VOILjn`#2jP4aYQcfk zMQv?FW+<8zT1_7;F6Y#kh8bNn3-_gnIP}7melGRQSS#CUpy;kZhiJ2&dFTcEY@CDKR&q%=-|#uz&wzgFIQqMtI} z!?=IB_FiChVl|7-MnWO&YgKz78t`ESJ`TF!AEbFdZ=JmV^0M3!WF$PHW zwGNM>qOO6n@9{u$NY`_J^SLj7W$RykNtq<$gA;}Q!wlmT8jPaA4bHmH>$8i!x8lE! zjk=qzJ4{sAi>8`2sQ3|fQOpj9v(+{pNQbwfA!w!9&SgRqk-XM%t6%xm8=1V;c~_>q zLi+%4Zjc&{r7`m8{k1;F3qH~U_GpkHz%XR+dDtr~e3vwb>%Ji|^Bd)nrn}qUc#^ zY`AKdju!nZW>^vqV)NIgST8$-gm*Q2cx*3I7yMCD^Im-3p8t8bjt^ICG+fv#_n5V$ z*bNK?*=nk)R!yOR+XL&2yVfVAc7N6`ZRJQ`$bD|(Yf|4547N%0=U{hg+ zOOU#HkP@zxm0^Av2JrI@-A4?qwhP?>pzT~dJb@Dc&$?iZ^(XdBCi0NPtE08EGyC4< zMZh@(m=ri%^=t4wHlFQ1>8PU62I64l04)3Sc|iO`HB-v~k$Zc!$z8SH-rd)mciaT1 z0B`0TT9KybhkJQfZqnt=!(mq#fJ$N)G{V5`p?8DlK{uv`T7F6 zpGmjxd%eMUr2%*!z@Z#5+&=r%+T7wF+wMH@=Zi+KkO`hQcUREFKdSmWFlz74ji`60 zd8$5dtSfz_DO;ozTTs2(80$j?b78spbnQR2b3d&2xqJBLz;-nvsW!-P3L}04X2@i3 zy~G^o^yFz$MKz?fxovM#WvfLjx08(G&xe;0|`s@ zZ+UDpv0^`7KHAiLk^X2kEb$` zX`zOtx~ky9UFC^}Jj2fC2&R5_BA?P#i9U#;0rZ8yE!iO~7H+aPnb^QDmTCimT?yoLbXajhM<=YFUse<6!XUOdGjd%gv5O-)u4kuXMC;}w*fV~*Ce zkxc9HfrXU9?-K{4TAGAqdJVLpHh#*2vs%Cn*6Cy{4t){B_?4eR40kC~#=DW~=1&if zSHn#u*&98HC_xUjSlv!n;EX!ZEHz_jfarL{u%>Dq0Vi(sW#}7jL&Xtvj_Y3qZ4H=u zmt0bG%9s^{R6Bbn6OC|MYE3v-!|}Gh_B!>ZNO8n`=;VQ#20p|NT{m2#!>J;)Q4b1< zKxeOp zy8#BJ3VJ2oFCA|dQgovVH;*^&;nivoNc}D_i$MUx`PVW8%xi7L>$QicKN<&^knl|a zQM0If2=;7#`g@989*iB&XaB*=n*gep#@tEFc9L*H~ z`SDjGnl6%@{`JdsqRt%nOOUp6*>eg0*4aoYPlD2jxr1vVNkXEbvDS8nQLH~7p z8MlayqJ$Z30%Q3wbHIbF`0!N52MWT}Y-GufkjpWZqe-InGZlXE2dW%}ogf5K;j#aR zs;_{nYH7a)Nhzfp1f;tgBm@OPTBJj|yF-o$NJ)dFAl=<1QX+9cq`SMjzB$}`-@o7f zAUZ6>}<_4dwAS-9wrcrp2-0rOm15B7Q+3c;v;u(*dMPeqf&7I=1FY_ zakM7OM_|YTm420=deCv~r3G!DXIx3nC1+PRiQHyb0I}eR{@SowTs!++p1m1SbW6t# z&`#o6-UfIat-{Ix)FAG)9v%fL011(hlENBkph1V>*|fQ73EVk#I+3Fb2xt0}=YFvJ z9mxN~Y!6-!TV>aTdof?m>nDe>51+&{%Bm%FVMImG63iA0>Wm5#bl2_a_X81%Ph%{e z5v^X&Zr6U|VfO2nF7r@#P4#gV8)rlvXgFOiFt`#cc#Qh-6Nk&BnvO>&ej>l!>~nEK zI!H(`R|JJHvhD~c5K!0}+(U;X2mn$lH}3xG37X4Xojdl9nV@qRghejN6eqOA>3ZmO zdAzZvi?7W9bM)MFUlLisLfhF9OMm3sO8F%R0BR|&6eVL@oxEc@5WrFluOEx#0_~8l zaMFFdyUWsnX&dTH@Ax4ch*rAt!b& zJ*=v&rFpy$o+ck28tcD&Y(a@PAufrpnj z_3Q?8B4BMEu`~e0D9)v^CQ2z^1DL=sy^5o3`{j$pu@coX<2=k%Qemxbdadt zo@Hgq0c-&pc<9*-So<$>Rbd|vT;cE=Rc}SL%_|+%)jNMBadTP>KLu~}wXza-!JY_o ze%{F&C&oc}d3p2l^CbWQ8AynR#>ayJr3`?Q-&7bGJ_RT-04W?A=yc;(nhkaVX!h;H z`ws?EYUkbA-d%(=^#VZgqzPF@Vh9ElIf1q#uxvFM#?{2YVqumXe4 z-IJ6y9fmUFhDT_$o6o6!6dIq z^$)-K6JXK9lo9K2*S?f;a?>|q?Aa{iwqYFy)90SbY|p8&uXk^+%57(uZG$AGd5r$$ zNkxYkfH9I-0b0DAoZRCOX`pKTx<&FSG*nRPeoteL_X%+C_x5B(()zBUi3o0g?Qz3qfrJ;c7X`+&WV*y&9zP>nE5>QNo zA3+hnMIUj$Q0voxcn|&uumK(gz}Aok@R#@?Za8PY8X9Q$J*Dt9ufD&rjHKiXLtl&X zn0B(yFy)f5#*@eX-AfWYo6muU7~CDKHsS+cV3$Ba3TCP1^F46$6Cg2Q`G7wGqkW3= zk_aYY2I|rPfOaLM&!B%**nc60(xT_w0zz3RdrR=#^`&^mRs-M-W7lt5+hkTpVFtns zsuec#ad9v+0kRy5*Wf!1K_~*;`I#`xa+Pm;Z0*+%+?CYuBpL92ZduMtzCepuhRJo- zjEIo=tlbgrF8lNW-?xq&3tM^CkqI(E1+(CuA{;El2cVk(ll=hkPqxaCGkHT7dDlHq zVyi03BvOC|d>MQJ`EBXgmaC>TkL0&l_r2!gbA9m}v*VMKM%XR&qCV%Up#UI%<})(h zt{Tj8AHcac>!m5d{t2$1G$>ePZIQPJcby<+!)%s;{UKFF4pMT;PXl#js%*|h3D{8n zyHa0*6n?t`Ok9@IXBqS{r7sk|jJ8hzq8ASar1D?x&HXAeumfAZzCCO001d%4*h{mz zk|w3)8EH`_|B|*v6@qpZ_n=5PU}y8+n_&ZLNfK$8Wgzmd+0h#fA$aAoob@u|du1n;>6Eyq8jy#G$pNJ4_OD0_DvX>MWR z0CRZdtz`n}GYu1te+5eSvn$OL4RgGs^g9en-~IP6I}7(s;)5zynhO(S+{@Q`Q2v&$ z8Os5C_q$#5TdX%rzrXKyDwuK&d;3oqHN}Z=e6Zo&=4Nw#L?n@a{M!9at97@n9>rR}44jR)uIN@+2nbM)g#fQ)_%b}`oD{$0f^JDx6Q;mf+(9{3`uF@ zZek_~=IJW^e=h;C>Z{yS96+8%&}?)qzMlow2d*UJ77uOcA)~4}5C2+1>{R*=jxyhy z!t)h&U-;BipuCiswHR)8YncACcz#?Dn!BV@HL=rL}uDE21QY zjs7jLd@%_M;sZe4V_@j1JyQt|evwj7R(1G?2;pxT>r*yfUZlG-zq_FEL?SPC5Im%b z!rS@<%ARm*zWsv#EA8(WJIjOWujOu6yGXPA`>Z?=?l8Zry|v&7PYP&9PWpw%`j?Sp zejG68G1~gW>b^JQ_H|@qyBVmtDpH?tj~l#u`nQF^=``8Hm$qD@mFNTUG#HRFEm5C( z03Q+rUnUDXJNxf3cLLf2iL-R;xS; z*fi(+9gzo1uf^fvep@2H4+-8xh?5IH%x}#xD0~0@FL%kjgwYTaISg?Q(b4W_qrgZe z)`Gx0rv6pcD>~z(zo)~KfuEm{+f*zFNIxdL7=gYlJdEJ3L7iR8FsS-oWBE@cRp#X) z!T^Z1$@*`>SnzI{A3IW>SpUTMGhspXw;5ux>B_a8Kg5mt{Mq1s)i6K9M~gyMSg;lT z?`3LdaiD)Ob8&RA#V-HPCzSZ(iA)+ML-VfUF!?VJ%qs!#B0HTpH&S3=;He%OHuflo zRZ=@zpd>t`U8zI<{}vW3MqFxYxLK}ZH{kN!-?Rd^TxiH~gs)joKgQ~xg}8rxrtmus zqJ4k{Q1cWq!^|EtMHACJKIAVmEr2X8E*%_?EZOg9RWv6^N=sMAGIDEvRbwjNeer(- zkv@H+qZ9UKZJ_frRR>E(_{uqA|UgJ1mLRoxC4p}YL*H!l^WvqnSiBZiIfzpH{W3mOcVV#b$YNkf*^ zr+Qdmc_jF=+Ez8%fl(@dReA>8$?zX{`ezz2wJj}~=oHcd*4NGd`5$pf*X`74z=*21{uur# zni$$}{%1r|{FM-e;sCq25Df;rp)F$EzowwTa;${bc=20raCmt2{oAK8jc{w4l5jr{ zJZVDz+mbCeoQ1p(H*$m5XM$kvTEMt^+P<3B&Xx4a`^|q-3jQvr0+Ki5=?@`wQ8C8% zW`baVN6d``iQ`JbkjWZn`)iWk6*gUaH*r|;@!3rn{qtHU?wc{PW8SzBzHvj=zg~Ls z5o-S9Qyeq2-iZNb^X~{(ypWT*Aeg`YJ_Dpd^ySMp9KP3xKlJPF{TDkai3_rV@wc{L zJwh?J17KT`EjO3kk3k-+jsUJfm(VxC{g)l}$bdr*y6PNoKkF;~b0>HPRmw{`rzCSo zJ6uxHwdr4DW|Gf>&UYrP8thEE+sr6sZ*)v{WCjR_j(Thhj4T3TCTF)jr9!%=NZ0rW*xeh^7d**viGGAAr}?zoO&5GXjC<1@m_^ve1gh-j!YFBL!_EF8`J zR#znldnq`(Vkl3UrmnGZ%F6>Jn@%v%dhUjNf9!%QVD1xats*vQC1;`f`&e?@#?PBA z=az&W6%nDWyze6MTAnPk6mQ(nPQ$>VGl@FP9X;r@q&1b!VIov$NX zQAtT5TVtjCb)-8Ww^sUGon<+_xUY)TazP;@)L4@Fk=BG@DU~;5XfxYSf|-eP-tSIN z#xt!3`He>F#)+r*$&$)1pEd4V$5+*9tnX)2y&g%Z>gXU8g52Zvv%f!3ChPqxx}an) z8t}&ca@iGU6(Bef*em4^^>iSFPm_X_kqlGB=h-qdF@67?KeB(mWUTya&lkK53tRpT zM?#1#L%SdZ8hkcJ`!(;|B8444noDBqDwh~3E(X$7z!%KzDO|a16aAGG()t(jgVL5V zbU?LMMA7Op=Id-ZNAgd;_E*pk zudlC%8I_Y;P+?(Va{_R*>d&Et%wZhVXI+?}AeGEkDG%bnRwl1@n-dG86pxaC1+}u?y7g5`@MJ?!JE%82i!w6cfW3pWzA(T6 zFj49yCALFb&I}9;&wPEwARwZ-yaI_U&CigJPsZjx6$INRV`z9HGvl4K+Sr#5`0JnL zs9n~zMy$}VisI7J{^8bpsKkIrG+s;J;(6!deY&etCm)I(zZ#@J2dzImL|0Pz z&NT~Xz(ewNbo5oV8>HQTy2+c!GULlL2Zx7f=%EESA}h~r@Z*DBm6)J~UWo?RZBX2v z`Y3JOz5?t~4<8pHQQPHJiQJJl7t?gS7xnhSr7`X1Me$>`baM&Pm?1J*5{8CUcxbdK zDXBZKTDSlqB~>>=jY(Na2`*g5cy9%i^5K975c+wD4K{G)RQglQaz^g)ys@niU;%PT zl^MhVmp`^u?lJ~%J>G!+rX>3bEibuNDwaa>d8R@k!8*w#cH}fa4igFrTw6ulmi>ZC zW+xd4=T4@tVt*a-F*2}x{}Mh`?zBgx^IAdH(v$AkQ#4i%$(z)xV{Q-ygvj}l1%!o7 zqnpsf)GI7wV95ao2gVf744$dRnpclk7*pO(mEk{pIrd9JgVK(@%5s9NSQ}}vS9Uir zvNmD#XgUO}=eDr34hO|7FQQu{*$1iaOx7;2Y&F}{k+Qp_j6(X0aqn0ztl|usWD^F6 zM6Laog-*#tK9PH2J?!chaps?_vZV5uj&9YUI*_aAOjODL!91w&QH8N-BbTYv&ZB&d z-Ds^vYTWM}FY50JGCCO%d7^szslp%)>DlWV9!41sJZKT=)K<=S(o;OZQOOolc_}ab?1OjP`TrdX%pYo z+vD|N;wd-EAHCdWNLR0u_v=QZ=jK?oKH^*PWtP2gmu*zcm35RO0n1^}B7{80c1<2R zD^9{q7arGSxajU2wr<7yw1PiYj@Gn4Ir78P1zx$qUy`1t1X$#uU6bL$`-e_39F{M> ztqbn{u9-o3URe}`u^#T*+#r?h`1oC#jLj4)F~%P}!ceibABDXdkajQ!A9b&=(7Te) z`QkBBsrquZ9SB?@m5hn8>Fwb1o4TAW{B>6fX#yUB4`U0tE!XQy0SWH&sZ zWahLsp!}64q{ow}rKj%07HhV%rkcgr<#aSFWvUU;$*17JX*AGDv#KM)XEPUCUzua@ zW8QbwMx6ZyrS+~7*|XV%uWI8&_f{Y8R=X8Hz2%DO@`GFPe*K#@7aD3R)kuzNIh(aO zu*cS2%uqo(C64n^>NZNhuG1NxebvJ><>PvD$B;jg*cVz1=E%81!t{)@z zV9PNw2oqe9f(&uztqD0&Y=pD>pPgt3#qVl#oJ+vkdpGVsg4#Tq=EV?gaFzjg<2gOW zn=u<~H^wjFKb=N`J}aw?p+P>zswL8{^`JLxy?t-~q^{{(VQ=E?p|*hcwR7NAd;)mq zwbho;Y`;5t5_=rgZ;V~QOAS{G_db~_YsaJ|1s-s(enJlD{BzoR){4_#Q;epp?e?&1 z*-;Sr_+b!u18PrHgyUSJ0UAMC1?QHUcGiWB1vVmaQa9xaoeE&{2kS&o8`;-sQ9543 zqg$D!KH!svJ~MF9n?rvXLL_cn^6rV|&-m0UPTMXW9fcabpRG*dgw`%AlP)6MSAGG{ z>^(d#klcN42?ZQ8k44WWz4Q%w^$QW-&mRK8=`W9^EVQ{o-kX-EncD3JabG|h1W?JL zDJdJI-2k>+QHkHbOTPMYjL{`_fCnq;)%Jp)Prrh~H@#f}0dQ^$t$P&AF>C ztwdvO+~wrQ-O{a#Qtpmedf|e(%axx_qQA+qZ=G91KQ($%Rg*VU+0c2EtL`) z0e4<4A5z@e-)~-=NcJn8^am3haFE^ihK83_ieqx=^D5z(Xdkr8UEv!QbHrV}VXK63m|E~2pWITU?r<|)s|g)GI2LHX>>9@-M`;J|9( zr6phKWw)H4uNS62M_ByBa=kHL-`R|4BIiRdkOx7ErqGOa=~68ICuZgx>Eb)r@~7wVzzbvxWch?>GAfk=eN+ z8>)(W;G><7Jx{frZ&AUmhd?8D)jfJP@1edm*BE5pssi^yfe?96Opr0TtPUtOk${-`ZC5KmQ%WG7%LCz9{$`K}VOJu+tYIxw^{ z=Hg)e>mqIF>+UY~#PHfRfA==`<(Et& zgZ*Zj{p;A={bS=ZnhXnE=nV+D`)7Wn(zWViYm(2Iu8xR7IN0;4$x!Kr1LwxSDZ$@U zeiwO0i`{;G_u+C@4%W2@&THW|K@h+AEui7^6cmCA+uAHnHs*nn%K2d(4ez=q$d;|X zrB4mH)&_V&CIuF1X%^cXV?{)bO0A&1bMS(Kg67kjL~2hRc5O?{NvCl@LPo2J8{8Ek zb;AbHQOlVk?kD`9=n)=8lU1Ui72k#>7s2%*J;?v;|l$@d4rr@k%}$iQg@e3>-L?gr)KjemcB zaej3%?tKdal>?~X)}g$Jx4vR^DbD!d7LPz^D`kbVo^yI^*TOZjdcjOhFcjBkLiD>d z;i4R5UM&6H=oOiGl)P9G1$)^KXTuG4-Igz%FcK{Y*4OQb3h#R zYu@zM*L-ykCF8Pm52QiqHQ)1DYF6~iVtMQ`kI4PY26m#{X^FL6cRDEVGzYoj`%K&~%deo~nJ58}2iU+cNNcvg7o04* zJ+Yhed0Z-HH!(LcyZ0~Vm)T%FR-&88;lKrHla~Jdgop|QHF@~GiP41pN#~cCVcN_Y z@)guaP3oU&{mMwN&^ERscMh_%CFSLQ^i@Syb?GhoxN!Hyap+Y#2xA~0q<6nbOAh0F zG;5+PCJ4Mx?0il>Q-T*RSkw1nA|$Yo9@9U~3D|6DF(O{a0+o-b z@BsB=jM&*9Fb94-TwXk%2y$A0_4MYgPF|002g>5jofkH!I6L}Bky3@L+PCwUIDHm1 z3%mPMd6Bs3#Y4dQE^ID_l~9rIUxun4%+GX4pAG&Tz>e*$S-S$@_q}VEFtLE+Q9@#p zFaeN+sd!;G+%F2*veMWOtfKy*#~eE?mQkJce1A-VRaW|Qv>dBb$-W6y%%P$$s`u0;K^aPb+C^y&quBU(Mto@0DaX8~rQ_*rPkA(PIr9*;}ri7nX zxsTDH{^J`#ZWG!!XD7Tw;hFrsJsIKyW=j2pey*VAy4WIhNY>iwmxTkUg&<&5>P<4>{n zeLE?W#O;XG!>Q~$UjOH@F+FoD#TRBseQ+4IG}kzHv$n%4+%CulBlW{iUP(x_lb4oK zIoKGp`nKypA=P9<1eT_~^_bF6O|b!NakW zp|!=ZlX}ub05XG`w7n%?i=alu`DahFz zU7T{GVylF0U|nUEmvKu=&NA@m%@5FWijnrWE_*>xmK!A85a@~*mTP9Zu>SA>XRziJ zlc4XC{Ay^1AQBi-24b0Je7O#rtb6U};hj-$pB1ho^N{Um9M-h-Gm2rZ3hA}o-z}IF zUIta2>4)tzUoLe%4~rIY;fq`(T=8snbVr8j9p^CIJW3fg#Wtp5e1cM`fC4| zwuyOue%BL%w&vpI)H(h34@41;!&CFAVj6b*`Ha_o z;uClG<7HxK+K&#D)9N0MfnPXx#8{RSI$Sj6MM_azO-3cUgpUgJUMqA&GzZyUomU;d z3bkU%QN8+uKQLDmQo3HJ=(d)wO|RHV4J#05%XO`IqEN>%Bf=i<>@+$|*&a6$`?D5m zYtl2sp|yLy?(8yrHkY>Ay|RV@*78dBQ76CvSh^xpM8bWsXZj;wcc&4)_2Zb<(S`f{ z>tu&u65DK`3;k4(fE)r&n~@m%9I-yvh$1OmEd?M8=}L{~W15h3bR&=>D;q>%1;-QL zHLOJmqnL~~(@b$UlZhjrf4dQC3D$Eh2r=nN-=Bci39tJKHw1JGA!@`^Ag|PuGBCvZ z>PbyLM6h6EWBc6aAJjp*RMo@eLuYY0{{#X`3oME>7B+gde01_x;ByDk3as83(!=V8(yoK z8~YXEaz4h6;NfNJuBbcS;A@Y9=|p$-g$mkC_$R81E>_wS8W}H@`c^X~dJegs1`L4h zwfjYXq>WI*dQ;Mb|4AazWG#VdZ2a2W@b`t7Dzuq2fwY+l$R}HYuUpm5Xdx{N@PtWDgkm8$qTZnn~kL95yt3*aQ*%w~UD|VJJ42S)5m^PlCa~EM1_6)FdB6=b`9D? z4je{WKEw3g3Tl8DsFM=K99YC|Y|EFy$q<3_Y1j~Jq1MJ^=F8(vuz6?c8`J|S1Vn2d z)|eS40t{PdQ+~#8+f&Q~1N*}GejBYAh)PJCe@>nA#i!AmZ+ch4Ch~$>)mrKY(xYm< zEufBs)kw9hmp({*d*k#TMdNFx5{B5WlmgURDk7O)iBE{UPfbhp>vbX$oeqZZv`s^k zA2f(I1{vL~rmh~G%O~`||5ez_m}wHr8qm&b?;|B#(-CC%t9{x{tayJF0n`X1S!FE)VJ!O;;>`T@C$ALI6@R8vA> zh&C;EtL&q2JVeO*;rYF+v&aYb%mO;I!Rp`ca3E)AV-8aOrmDLYeW~@=P3-&eGj-o%c&JO7ujhub+?|7F(&LV zC-gzHr^&WcW5qR|ce}lCl0I9s7Mk4v=3lk1Krd1FYs zH*NAY3WxXvdalQ(RGaY1)HEDCXtj#pQ7V;lbpWQrk@!{nX3CT+Wm`MwP3Ao@w;l!s zvW{*_l)jQVXUp2WvJ;2!iqPsgJ}8?>Juo^|rJg?VO7 zN?$D8c?FTarm~#bO#aASd_JlCo9_Sz>SlEJbt!WtXsQDKevfUuypY3lwv1;>gF zw^)fG1Dy1nScct3#|)Nnl&c9pF8n*rRb1EYmA%j|+L5GxLc?O}Rvp+(6=_x~J8RFS z&9Gcr#t;2?k$#7F?N~4%2sJ+m%=XZb*&wh&&vH7VqL2kvr zJqlYBw|d6tdc2ni&*Ia<@mrG91p<66OfW~u=>*}+-db6@u8h)2! zwj#Rx0Yxt@F2Gro0a;nb&7L<3V7bI@J*iwNAG3#SFXzd$2JaFWe@&f~Vv%poC_@d3 zcpi#8{Bx2H`+S>ZSc2p9c1=9^bSCxsH;v|Xx10ps0;o+mjO@jo%}K3YFyV$+i*UVt znxf*bq1TRC5U zlrt~!qX;iW4&TM&x8J^*WQ5omhaMafH^O~(-f4KEJ>IJv{@F1b_~Ik5oi3^-y0W>j zY`^Lp>n4?W4^Ln`>f<9XSCz@{!{g`{sKZuE6w~((b!Qway;Yd-wTQ5675fp`<`a<- z!)KWO|Fg{1%g)eNIjGpVJL7fFtH~6SV8Q=$jM-e#f=Cldw`_cr)PRj~YR^S2EKE8v z;bPnzhwa2hF{0;*4jOz>(`Ep|T39xJ>pC&gLB60X9J+hA@<<*)bg2hEpxm^c@_FVw z6)bVXLQy)`gnJd4@_2hpvvnxZaSjN!6@Va^^%1m&{d z^z9QqN9^0MP^2g`;00vVzXYJZUiw|2xvSOoMX38)%pS8&VMszQN<)wfPM8^JW|2~Q zV`jzCO@o#;dlMh!nK*C9;-IK;E;V~=+bZwxZ=j$h6UV1%u<7xiXt~%=WG6L;h^F339Nd`Tu-420ZzK=IPTg7!@Q_u7UV~*U!WHvPO6ORXJAg z$a?wdJ33_V$KeUL4XDlSEwmXnR0;4t0dig|mOLbQgoINb&ubb#e>Oj$zg3}*NE3lz zYP%XP*xecY;$}CR4y)JjIyl`X2$0>Qq;0TS{`>+8Du@tw-&wEBW|>D6;a#D3S4zhM zgl6=i{;C?TSYlVVgzdgy`{HD(_yF!z>VBPh&CUh-!*k~VfVvo&nM!5dreZcH@$EHr@g$m@pLJa zGCtV0kDcL1W4d<`Zf@XMqqezhU44U^B_^-Q(rGhCu(t-!(V0}^ABngxRxj>Qp$824 zDp1iPvx*0c#6Kb|dA|$Q)-GrsTmW?O6Vea(`7!akxNDXnJVN6+kh`X|;+Z4$WW?XY*{^!|?SlV<=~x z+cpmd={O2NA?)py7SHoF$s!2`_YwVxW77TQTnb}1W%b$dSnIEcL_454>gaI(Aid@& z5J4haZr_&8MatiH&EI09nos`NJhC1sK+-}%T9lNG9=!qm&5s(NLncdH9#i-k@WdDE z&^L(EaFd4KX8)Vq zk*Me0y0D(AOVs9uuqJhxRsVbs>UEWKy}`ASBo3&PzW9~AqHYKZF+Gl_CBR@Kf7Ahu zF?$*r)BA3HLg9LRv#AAiDvk>AZyV%Q&;e(P?uNd`SE z{jz9OG*i`)b992W2MoM1?tPQbpae9!JZIkS?V}lPvb&P0FktNjOP!sx?suV-2RHO~ z8t%8y4&?c*bl=LBE(%>*uiJQDm+wR=f`pN(oNLU}wM9L%qJXLtyp(IiJUs^RohhgE z?vW8aY{V1);a{tOT0+aM*GIxv_K5oG!yC(D-W4OsXmbP1x@H6WtqcNG4D(O0=7PgTDvB}3dMV||Y6H>!KGLDMz}C)Wy7Ut5#38B>}CyC}8lMK(Q|?Rxk1W6vr~ z+mIne{5OO!ZevBl^|kja4_A`YZNry<;h9-rS|H3E!z7`d{0@J8|01U_u}T2TYq5a+ z@pi`N_P)0f1bT8G&I^a=UxXX(q|O&bW5o*#!3K;Esn&4` zRog*o^?e4e1^C(Zc}55yv!k;n^c@`bS3p#`3is(ku^~2F+M8fo zij>}@p8rfybM4gqteTL?B}+D0gLVIOdTp1%imS;A6;zbyhgzPH-maa+R?YKE_bjI% zzFOY3`P*jcZvLHd=Jl=3%|+`Ik>;mdUho+{QyLm}6rY)}ZB$an&XRH|@ptUBi49Yy zmM$FIonki6b@G@=zQfSS0>$ahJ|g}d6Yu?%$n)joK=;+ayN+2%_jWT2jH#v!j<=S1 zVNM9+4+R&zxUlnANNV>4BvfW@hzl}J{H{W0v`_x1D;7#1MlmTfv^)f%0Woi=q5M2y zr=`U4+M(*1v-Velx>!~zX@BhJ&!596TQLv}MJ%qiiOY*oOI|W^aLlpAZ#lqzfHm@4 zq9Dwv;e3E}aecWHlz6l%Tj!{tDfj2gl?-NkVP)F;p9_DguR#MK(?nGpgpLI-nc#sD zP?UVc+=j3UpP|?Il+V98-kDI~LdS&zev}2GE?Er2o2@(zV}QEgi;{C!YXuI@df#_PYurIZ{eIO*}B$hwA-QUI^&`|bNB-d#M9wwaE&>=_iH*`R4Z(s zEdY?S{N~a9GW`ir<>ZLHy4&9vKUyb*&L}b$cs_qlQZ!cq+GseR(~`o&ezCwpQ)|X! zHnsut<=u}NZE(}vj`q!-vtYMz0w_1_VZ?)mpme;a8Y(v%Rh_>{;)1$r$_JL1;xDC+ zh6tpqsI5482|SqjBAlu1#4B_q{H(Z00FI|F99KhzP%;buk^Qz@6F!EklM{jx$vmKK zXI_Cqx2~?Pt+R9GH2npyNj%a|RD1d;l2kk?(`-q{U!X@{H3$eB+TWqRB0eL! zzVUu~7W31xigrr57>B*Mq~u-B^2u*!odkE$kJBB0fZ-uL0wH%p*Byu1=RCyfw$ z`go6g7U{K^BfC(ImCeXxAt;xcrfx1`#Rfcu;mViZaS@XhAr=;HH2|5?O>{E-wV$2u z`{TRFt?2C((sQR3AuxlL%X6HLw#(FOGHf`dIvs!!vfn#ZTA}a&{0^(r;*W4sT#HhFvK{H(m_qK)rVxf|XDO{Mj^89A zY9pk`mLLTv&1?xv2?+dUr_O21Ek}E&(#&?WY6IbAVsw;2>?>4)jYK|^;9>1-Y33Wn z0k7yFujndCf@vH;pZ!Hk+Q;9=AWz5x!w5_-<%jvC2lt&Y6Q#Cp%f*Eo%Y}R*CmNjo zuk@f>Y|(;~>w1q1BJVqa_PWqYT-V~8nN<&!5$?|^(GkEAj}#vCBV0qN+bBW(pSCLV;CWQMOcv@R%8uOmDd6kAq@=;c|=6S{@Gb=9|SNYqt(R`TjwdfH-OW0VafXWpj}ST-p`B1lb8FugtE};yKI(9 zmHZD{#e8>+SLn;QH`8UezXT;Fcw-dILY0(^+9rO#!i%5wR2WPB_5E_4#T)czbsuDd z!?s++X7%JqB!$!PG= ziSj>UbGxCMb3w4UMLi| zxcY-&hnb2!48#{)Nku9*EL}6S0WIN}hOyf}mMZIp|$JdWA;izjF*>o20x}^q|%D=q261sZ?y8AW*!QjNv zK=b^K`aSQD{Q7C{Tbe&etN_USy2)AakL@It&>BGXtcCbN`$^eFz>lhZ@c_i56FMU6 zy){0-vZ~n;^Jg9_=`aV64N4OKh_$Y2yjF_E?|4*ZGX@{Z35arGlt)iKVyt7%bv3{yZVd+uIizsL-&zT!RR_@(g2gGoLdLiJQRG=(lL=xHwt9=_st2z>s8 z2#(Co6sd63Qb1U^0}3ryS;>+K^n8g7Va7>N30_<@%2Q)%j4R6AjEatbPpFst2n7X2 zN3Mx_ol{4{*zUE6_a18UT8q{Av+GJBG-Sxi6*aRkN~Kd=i-#T~FEU7b{4F0hjLG{CGiEO7mr4 za8E=8e?ZtwCAQs%Ugg&rXDz#CI4}i1RYr_dTrDHV0!i^en zt2tjdVWkn-+Y8~jbg$KyBF>RJ6F-c|V&$5+&pa@;r;Z|4?{!86FFh^-2_m(t&24kz zhEg@l&R?%Pdmb5s*06~En^AQZ6()T59}C7%byqAv{Y?a=3Fw7$u1w^^ zsJ<|*lPKgwCaYW{j@5QyCwOf4;g9R;mqVl<;8p2Sh&>St%EcvUFdXLaR?R*nB$I&i z8kLyj(+esqcP0|yGDb-c7Sjm}i-O7-i7>$9k3&O4`%Mb-eUA=KzdNa>eP90?RqN6u z`Lzu+a5LmzcwINW6O1m=E&YAqa;jw65>YNQ&Bx6#Ki$#2XFWK5x@-^FPw(|=#pb z{(yn}HY}V%C_@E5#`>U5x1;R*%nwG*jr6&kp}wwOXD%EI0=tK17d-ke}o| zhXcxvp=Nn{fr3#t?=)p8YEC01@oiCe43x;{OPbCY(WSYWFH|wIRp3(<9|8A|l-WfE zeOb_o#hz$H(W-uTiU>l}%PAPE`r3`vXh8Sz3>z;N+!YqN)Ebt}P?mh~s1p$e^7?W1 z+xI4w2=LFeGo?Z_tWMmsCEpFE#2z_wz7P8XMkY-F(0>UzP&MM z%3I7!wAReD*%nHp9tQAW7r)yNGP|~MY5K2@lbpZ?;S9unmT_13_)-TzFmss8`x*?k z@HUN);NX1qF8TS2ub&^TzBi^HG?-Z>@A>tUGqN+58TaO_;6%Xv_}encs3kt~Nod=; zA%b+R-9-7LyR%!u%&C@}bA=CX__r*rU<*eqEzeJV z=_7%qFcKj+fJ#_X$b-y<5EPkZSGue2D@IMtls&Ss|3`bzpm#X?pWO(AE?(T~l63&k z`>oVX%U)*GlDwa7aj$EnA08R$Uy`9Iqfw;s(5aL`bGEc3e&=Fu&tZl-wK+t)A-ruD z)LLkA`~?tbB6AeH52gYlt(J8Fs0YjxdxCyiL?aU@air0K{)+!ig4TsEOvv_iT9W)& zhDJn}Y}?TnWX9L6y1{@bGXoV_V}BZq4B_qUOgtMf6L4VaqE;;x$#2tn3v_7Mq7Cz* z7o`)|ZmDzecR_Z3w=+3D3P3Nh-^-8gaQwr<`+T)8`fB2;9v_cDod^}#9}p-&LuyZe zNJmri!yds+M4T1>)buXhfgD%MZSSG{Lcn+GZ#gDUK%#5E1$As`>zQDM-Lh6HKX7Q! zm(w_#@S1062z0^e|0HIA{9)PQfRH^D8FEG$FNO@qrrSbYzq8)Uow)=ygWg9YDuBqz zeC*l0E=Jd_nASed$iA3hCoTzWrg&FdLqVtZ6VMZML@fcJW)iVhx{z&pxPDD!Di5Ge0A8c;734XCP6r(Jk5t%{sd zirMmNS~7zbLy%RRSNr9W968bCQ#!h%7-88vTrPY{@jVSe_Gx7GnUj+PTk$JZ+>+cJ z!(ZH$qqM&+23*48&x>Fk9%O^ewm0&sZ(dex6ygOOOIcR|iEq1uzOk&zCsi(bA3EAxIX3w2V*EpS0@4$vPyoDi%DjmlY_&1x$FRt^&-%RZ&b+f zxTKNM<=KS=1p$F>rtOqsoFG~CAcF7Esd#dp3xpo*Q3YZT+QgGB3!Pq;2XG>HTNd7; zVu%VNmL-9~K;JmrdRs|!WU(FSrtbx>DDh_rak6JI4t9}*X-A%DrFh8e@X`kxz zG-xQA&mbV6%}{4TIgVU^ZwSOH0A2!xi*n}Z;?L2o^OeCkfUTx?9;Ex$5`ne~A?pGt zS&`x9ypNHw$OPYmOh&L2>Z|{rv|j!HQS}yJRYlAD@S%}z5T!#xI;B&P?v{`S0qF*% z8v$t$C8SHbyQM_B8>GA8TLYv4`RGyQbfnoXXP}OqQFQL>Vg7(C9rheWaic0w{xn=x}j~}$;Z>%W{2dtxd;s?4(SmiwDCM`O1ozc*jZB~l3DjF;ZdP76!pYoZVUYb% zWNr2tC}BWFWYKCw16fgo)egk7uHAfGc$nShrjKlx^O1mbzI4Yz@U6BsTV?av#U&h+ zW1*zvwsQwI)$7~Cf#R4{*?IDix|JC)0K8IMu!=tvpQ8ej;Y+Q?UjhpSk{{RDFcH!Z(hy}lnZE!{^pDcLqA*5cAfyL4ysT$90`~V6iVnua4g=$iOKY##A zVAdUlc*0uIA(G7$1MoJr&PJ~pj^I4!}P2neQKx3yk<230zyqZDhgaZ>{=1OM)hB>Zp zY0J&r;Kv~8C>og{F}zgp>_bkul6CTvUk#g35-Tx*HCP{2ky=_0;x}LIUTE3GC zX!Zy&ZANf68bnH*Pxk(h0y3>SiEJScX~P3^pGaAscUF*=fI_{MAdy~biSGM3gf=Zu zKNYj zpvE(WgUro_5YR$Q2{mKp$EzaK_o@j)VgQ~AcKMr8D{H#xyjS7 zG%iZzC--gx;oFiFjqPFt3%^F!ykLHzozNczs67dve#fH$!ayvjW7oB7@~4qa{1*{4 z$@*_s1cMhcG{yYM^mT)x6ygsW>Y9`~au%qHUPno2rKR;@YtP~tlXDm^{!Ru?rb0zv zU(Xb_jn-85wWhfUZ>A^F{p<(Ej;w5n@NwnYGCr$RLj!;U-P}D|X9wVlb>PVxb?GQQ zoIV*dHTNC;UT4(0o@97GT~*p1TLTJ$Ks-QIoU!m3PCvqLz8X76-Sy-}H&fb#Vy*DX z2syO<#b$)kG7d0ucTP?J@jm}^*6;9-f2%?1BI z3}f|37Ez{|ix5i5iUlni8kyl~D^Q%K2s0S#nlw?l^u`m0L5x$)9nqH27t@RDb?8H} zOnaSL@nFyRz2;+ef5FTiyq~;^otm$R8wfnry1nZAaXbR<8WjGCti)SGLw*21wt=*l z>Wc{MFXhFcB}lWMxxO386#{7C(GTsJvn-FVN7TBQI_-4O#q7xvL*t3M0ugFO$mCV} zu=3jed*+IMEe~joFD`PdV4KG`;^I4I$O=e<&Ov~Oao*lqx89UjRk5mh z$UGF@|>xvW1mX6tJ19DX4+S7)N9ZJ5JSa$N(k%h^S&by1oeK6_ zTJ!ievx=+V=1U&2eJ@uI;D&T1f^TF;D7w#AlE{${FI)|7%0+x>^i%#2AC$=VEC%l# zxRfwA%rN|G63At%5(@FnsXWKG{;ncT5no$6ET?1$S@3q~SEIC>tqsk8 z%j|W>#|ED5)r;1vUxxXmi&s7+O2MdI9=Xvq5uc~4j5PAqY!z$!*VzReY+&E{u^+CN zQ2tS>MYF7e%TM;mb`v$?MjIUW3N z16{&FYq%@=Y%K>}LV@FX>@)#i_i+oRtlOjgh!SLt@dcUc=9wDHz$?cCSV)o_EnXql zNJ6}L?qtV%Zt*O7$#NZk;0;2N9^K1&UQ{(ZR&uuO5z`m`vd=4Hi=+SAl-|4@hbv`C zGswN_F1bfr{=2zBj}rJC=APk;6^lm7k00i4Y?Q-vER*Awf(FH`XE`Ud*zkZ`of=Tq zXChXouogubJ{GkUo@gIlJlw`c49OWPG>q8owF0}zpx zPh1T|olM-)t7YZ*A`%yFv8LU%kSO{Hq0yK*9)cs~_3wblDN2JI`?f#uo; z{uEPUUv>x@rnr+DJfi+QY6sHANpB!tfv|sDi24pU9OT+yKCTZy8b*oFGA`3kjASW! zUyhvZeg72Z{vn!0FJj*Fp`+EOsobJ1>$6%ESBy*!GA3%EKXV}wcOIGTS0|GFq#HaG zl<=Yf#ji4jC*`K&wh=E?3Rw=`@P4DG@0xbpv`Luf+1cQ0G3WC+c4~?`7~0&he9Kqe z@%0X=c#-T?Oa#aza$4hTcID|6Udz`LI;8pjDEuqoP{7}A|HOdLj-pMpx36mNINm@h zfYzSPR=7HASXK1XCtG1=Y-RDEzP>m=j zA!GTd}d z+O1FrdUd})bE$jeS65nWM=SI-eS5)VfIIM zde_iEQo3F|e@1HV+p*G`!3&Qjn9|0xBbs5g1f!Y5e{D1sunCv13X(h$F!WdxYBM?$jh` z6Cx`U2H`qwMinLlY42BTmTV=uyaWp)urU2$W$P+1Su=$nWbF>r5j1%+bzl0_7UI)7 zUr6Q2__6vv>2^|E&L1^WqPJmLyZVjr`LCJ}VIi$Xkq%~D{`n1pgTo1ES0LmX0SWVv4`G&Bs`uyg{pr9$*km_COqOqIRip`>g7bd9j!;T5%|Wv_@ny44;NNBAK3=C&lgL@G zvkr&n0uJrzM&scu=`~nL91$m|C@k*6i5<%9ye~OBsd{KBk4?9?x3^|Xg`4m8`RzcP zO$iBRTHedw4g>Xl7Mx;O1&Z@$f*pK8??h$|v)|GM{VobrF(a#xp!}4Paj^m6ibUz2 z@4!!*%eqEVoJIK*ba;aJF|85y{d^T>N6EJCs)sLF>56IlXLj{oPnc4cukERJ6NK3} zF>ZgpLtnUDLWQ&@3f~6l&+~n^JJ@&G0j%K|yFA%}EsfE8H}lt;0SIm-1CfC`s(zlN zJ_M*6i_xFFJtu4TgNhrP4>DTNOV7`Bk<&g9AR_Z;C** zdm~}2iYYL|!oiLdNUBDVupx_nI*(t=nPD%|sd<`7_wI7Z=QA?S?i;=UxZtQZ3(l3R z92eSQK*8MSr&$^ST^!ws(k)(0-=@wV=q!zpBPB{KyUeMoxl{ z4O48P9j!ywW^)rPrcW+%_XWYfrl>@aHd%#OnYM-G)bd_J=Txp;WT!2fX!t zu?7Epk>zv5({0O|QmP(B?Lycfv_@iJD|dMIAWEaLL({jVO#C?Z6fZD8!Q2xGd*lro z(_5OC8_n9L4fhANw4m(GR<_q-`%}cdIoip1fIv$2=h2H(c${kwWM9>k2$|=O4H-W8 zO4+ac>8i5_A-dOE(yS1}e)QF%6T-sZ+ozWYz4p{3d_i*{Gikes2pShi>}U+`O*GAI z>fAXOeI6)(v5j?3!V8-t7G;~xZwRWiCl-^TSKS%%=5^c`c$Y;rTCD1Mx;;L=!KISn z2HdrcfHEH3HiEz|D}m$P!mZ!sB-iKrQPoeFz``M0Ew5Or=pps+LD#H2fdQe(^SVZ~*IiIUVcq(ng z`Cmscak7WSx1?v zxJa+z34&zTgz3{{ZSI}jsknewCxm=+`uR%a0x#it6zfYSF4Q4dWX~dpNM@F{Lc=RE zRfkQM&Tlr1m0Ai%GPQAgP1w`=dOMrpf|a#)-JTDP#^oMP`Av@e1Y%6ag;%Vj=e6h| z@Ct!ZqgcwQoOt_bGWV=t!;scjOgN7A4%KQ5->UUxAa6H`V0787{%EL8o# z{$Whx*J$nEd^D%KR<}!V!=!g@xM@3Li`d z{{ox;v%wx*9yu~HD(ZD$c^a z*|2uGK@#eAokKJ749#U$N-|)z!c|{v>{1JYzen<*-|*yxLXH@4il#U1X45WWRhTw} zTZrne5G>{kUfHIxq7ci|FI;aiCJmaIm~O6o_cWg(=`rMdx4eQ0g?hkZPEq>{-+4S0 zy4lxkuxY;Zd8O~U&t`pg;&^gUBa3J-ROfv5>gM3^iFE`)hNinv+>0off~u9t?bBMj zd$Cl40N>(iWC+OECfB+jJG=DcAMEh5Q=-WV-4jo%Z#;cCy2OPZ)P2{S-EgdGONX$3zl%+2R*NodB6sY1?w9ytk#xiv(Axp1%QXHlgev=7xO( zirQqJ+du~NRn=+KeYj_8ZFqvvYG*ve)9J$8?&cNkDSD33yJuYwkRZDYzF38c-iU$i z=dQsohIQrZU2W}Z-fw=TPLdp5Mvp6TSULp$S2d3;=wkLm)C=PUr9)NAqyMb218FfzDk^LuBIJ0Pz_Kz{fMPEH1oP*pgicLq1q24REiRH# zP*8+KMFoj13)pYV2BGcx_lB^BWQHtSSp-(!9)$G|g7!?ArYE!*lWeJjZrAHH6A~Y^ zELdNolYG4Q_RzwuTfA?C6@K|JYpd%&8ghk7sEgb7ouZ9MaF_UWf8nW0KK#JFR^a$f z4X;26T^Jy%B25IS%Q;bZM-oNYrq7Bq#Ea=_L`e}gMmcV>@Ot~Oyu61xu*!0fwG^cgH!%dT!1h^}w;24d4T|8WV%%DpOL7fL zq~T?$VWH~zNmg*Cc3jw+ovjZHsoM&T^?INjZCALWAabA>M$^Ja&4ueJGhZ^VdqIa2 zR1ixz`W<)j?ehROHfb1mGzjE={^yucMCc7@V5fot;l{^goV2N?^~+JA2ejso)>7!A zdU8N%^tP>{67qX5oC(&H@R^g$(ipDPE<Rj{ zkQ=jkufCp^o%4JmuJ=ncc7y=qHJHnFDP}aG$7lTB=7Y*Ov#3TK!Qjf#kuJ+plV*l< zN;VDLoqYD*RtR6Rd?K3{V!=r> zaWOsa{nDaJGB8kA$eR?6hd>VCi0E%38xNVRib3$hxzZz~_ zc8q)CR9SDnBhYDBANKl99u5#5@XiHKzwb7_7;djj?dHGJ-bP1+b|K7Yyn?;GV;pj> zQwXk8Yy@C2+IS#JVr>my3-?3GpZxhQY7>QpE}7GJRfw3vHw>p9Z~%564F;FaR<7tb z*z+me0voY&0nC9ekkSNDrrnd)xOa~ zo1v}j1YpKW-c2S)1&YWyau)+O5~p3%DUsc-wu9MBTF14{Zy25n+V@-juCw%d8Kgf( z2nfc7j?RlqFy4nJga<3>ip|{#{TJV(B!J}&I-;__0gsW+YMbgpm2lUL!o;n&UH|;oeXE95a)U^oB=5csJMEcBsmyAf(A`ovu#LgcQl}<5;WaC z`8_;SgFy%nGnm@FywQhiKc8eY@+?ByViXPF-S-pLIE4OB$D_P=zU&g!DePEy0Gr+By=%1}pRbgdk&ft;noM`2Cj)5O`wWGnY#;BsW{; z%mZ2at3S``T5W^+7o>_-kLp~PyLf~ptUM5b`hLE^CTzcZNDTahQeol66g7B=a1M^^ z0v`gVfO3q9pyz(0Zfx6NN_X3$0YYla|4tOrNa=;~56A9m_BB>yrFGVrJBi8~rQ zC_G$THU=Te4uf?hNRp5xEGTFV_I@B~axbYWY7-({xIGHPZZj-(ga z3i18&#p>uFA)UL=P}Tt#0&xG7$2|y9*cRWq?OpZk>aaf?T-)=edmy%y>Kz=qH>}Kg z?4+ITFHF;7qd`b!XhARBd#xHv{wU4Vtc|cuzU_K8?uQbPwFNc=`Q_CXBcxT3BUc-@ z4T44TGz#R#-c6Ggeqg6TSAWR(ASnQd8EuOCo?YJ>dQDWk9{N(D*Gl0E?I^Rp7Nsqe zmLVi4j7f1JsJjZJV_*)_Q4RYD!Cx`X1fFjsh}y@&4y{?aKC zzEI4Wp*g)d-`BVPofeYE#tNcp`*mOv;zc623RKLAS%4P;03y1T8LPX3lL;?i-ug$* zx)@&>JOB_4`eJI7%)>)!?c3?3bD|h^&|Xt13$)F#n^5Izh)Zrq1m zlQ8ExeLIosX*o!1-gmg7VyD8tfR&4*!`YSphl6_{@-?nP&JVaei=5r9px|ar=L#Qh zfmis-cYARfcO?Z)=~_-EwH;SKfp_*k^(~k3jtq|I$D(6%yOQIBOD%`4VdeGQPN2h{ z+wucoa0@^<2!#UWD_Lrr4$(4;80@NSAPxGFjaM^&0S_X zdZX*Szr=%t|N5zBvHt$XH}(z(xK9eX!69MII3;0#-sdF_9G749ra$M8%RU>P?vHk5 zl>^jL&!jy@&5S6&@{YC4&aP&+g?r!2b^(tVCtyLa-tD$(#n$LM1u`mnzAC<(_}caf z0WN;%C(Vm?0I7=x6mq||)twNIa4xv>qz|0AuABcUC?Vr%U+Kx{j1;5!RolPdj(M2O?(kyh+pYG zqDr^*@aw0T_wOd{2f!Z0mhKE+d?mJ1zPWfxwo++(L3Js-Ji;b#XkVg-=WIBu=soI(K zO$79l)f6qJ=eAo8G?-FEvETvRUIomECmmB;(gH#kC1KhX@l1Q9jhil-);Ol)=PM676idWRP`{M-hYwXz?XfHJfD zHJ+r`^|ngm&n@+TUb&D+Mqm*(-!|^|Hy+9UG1p^{y8~3K!!|vPjlB`7|)^IaA6& z5C_s4FxpW-(vUg$wYmsx=!;bqM&dvDd=d*Tf3~($OVKS3BtWA1pn&u(Tak{~`9W2x zlFHx9yZd#WhEbpH<1}ralMPo&t4a`rU~`#sdz`hM$7hYxK4YiJ5I^(lfTBPK3tsLk zFM*x+B@Hm5_?Ywja3J);>#>3d0$yjv)^p7^I|LJ@V;nu|q_icvRM>5Nd)VqW@B8K2j_FjHGa+fc zDJrN3+9_@!vuG9F({I^=FzCsN_8HfM)vy% zHV_nxq<1^+zP3m+_WehKNc-2b~o`0jo6d*em*eGUQEp)7apswPlgun^@D*!JSFIJ zKIblQJ-6d_S~qFGHPy!_NN50>misgwb_Zj1g*_A47-}B;ai`tmf-fuu!o}AOvU}B& zRs)9%zwKZk_xB9ej32&bR$W-f&qh4;LErdQ{}i_e0}0}FbXUr|O`T5$falkE$KZ$Q zGW1keYFJ2jH1WHdeRaWla;S@aIGQND(zEVM^`aDFR`FCSDx)2jrO|Q>wt>%pzveeX z{GfW=ZpqUBS-<7;e4d%PRu2k(LR|)7jz5#pEq692cm5Z@B!Eds+)WMX)y&S#%^DuR zD_a>BZhB0>U(uD%TqOKL@N`p2*P0PEH_;c-uESsurs<9*)ycIvNb z>w0ilp->8DDN2`C6in9smPZ7Q2JY}2NQf%4{Q>zR(3$%}_?{Bvqa;@D{Vhg07q)#G z*Yz~G!4}hfct2PDO!&SU=R&X=3wUD%XUx|iyr2_zMnEz{W7ykT2m>j6m=EhZ@Qnh2 zchN$oj-gI!f%DsU*%`$agWkgt`P`vvi3``rT~_E&9^Ten1q6b*;K<)D=5NHAayVyw zAZo|j8uKK6(+;3IV3x=MdjkYEOl$O^L<0A9OL)XfaXd+=bEn7e%zYi59+ZqJ5K7`1 z3k_!}_;NS9*cxY16&tYJ7~?|&mOQ1q4p%ddXH_7E4x;ErpZl`4PIt4o57IA4dG!wN zQU=XZQ=?wI3i?MzzK9dm&BisS{|;%O~eRXL;$0H zlkKVIb!dF2aabGUk4>~>kZaQbf+3n;-H8+%4-o+@EH@l&aM=k6L|na_Bp`qJr#k(^ z;==sVh+vIzUylJ52jjD0W{;kYBT$ffx;>2#iY2ON&4)`!j@si+4o?SUKgYPkC^nrY z%=4+_kCwXn~(?)(iUGUg`(|A6lvNLBM*9V`k7WS+sx)b=gM!nAG zJrJ*hxoR*pqkJ?5&^JJ6Uty`ahd_)HyUcTs1!I%K0L8$wq?rIZI}e-d`KU7XrBk2m zn9-X*05T>p2)T4FOw-DM*X?AmN%evg1HTb}{SL9qr zj=bfn?)s}~M}yOPr8aUBD0%-;lXg&S5Ssa}%GteiKb`I26MwnU4s$R-1w>p<5Q))< z;g%cxeDfjgL=Z=VW?DSW6`++3Hr3eF&erM7@e_i5uJjeEISR4C;1$JS8-;{Mw0+dYDJ(&n6lnEOr1`UxlAs<10 z6Po&bf6imuX?S}#OiN8m((c+))Cz=a1ayl?b-uk*CldIEIbl%jR7DP8xkY%1ievdeFZI<^5d!GvG6rRan@p zG9kmli+-dFQ+P=4wc`ECuixX4+*qPGO!Ekiuwn2|{4>C`jjyQ>A3H9t5?6b2Wc7ZM zQBoQ_vKSOnG2X7DUqJ0Ampv!P)bX8KlYUEtqkmr^tL3tfkU|F&7Xu z1{MhTkW@n4^+WM}6RQLS6fI>$4#{ZpE5^+9(~~1045ZiFC$6piN=)1j3m;qmAWYqS zXA#csc@*XH6k8(nn~F=v;gl7UFYzDqm^6+Gy39I8?k~ zDB@m+0ZJSggmVTi4rGVN30EmHgP5qO;2UWG?f2o+5&>>ih+4-8Qo+MmpZ4!LT~H;K4xC^jcsO>$`F(I_wm9VD z?7eH#*ck|5Z3tempCZBm*$-t|&^3wUl^046np`Np9Ki)a*Xm;32{%0hz8aLe=O|a} zn)4IgiC-C)Jpa8Ou!q##udb3fE!kC6$NurQxLBjEMSx$Q*=ORQZB0vA&+dIUMkdYg ziJ|KPOc}_vuo|7R=I%(n4p^R17B72u)*`L&rf2Jo>o?JXRJWa#e+LKaG4XO^u@nU~%NHTcrKQ zU7J*%(34&P9vWfJ!t0Vsp|?^A|^1$wicd{HUve=m(8&r4xJI1AKZJBB1@5z4u{{5e~?+`z&Z>=z; z^7N$<(f7|C!Cy%LQuhHs&566D4mq z_mseIZlS0&u}{UKai?Fi5YWvo@u!wLgD)_ZR$kOzIR-k?70|IlAUDZv2{=ai zbQ->oANuc)zcRpkIz8$kVta@8IG%FNKI&%^JJP`a&e_7T;3S@N*sN zxko1wMiTlBF;JmQ$$v*Z8o%ql*ad0RBh`npw6F-HdhH`ib!dW2jy^K*vHx@A8L<<~ zLuo-td^UV&i2l$4mEacBmX>5?Q!U~~Edt1q$^Uy%%FGl~Q&YenqNU(CX?%Pd%7P(2 zp(#F&q{roYJaLkag+)q7C#9x?oRVj{+6GDJehnAd4<3xjIC}&IYeqoBdH9neHbKkl z5t~S9E9%bC=jEKre#N3CJn@4lJ5@r7mH#=Oq9Hb(>^Fc%{`T)9Sz={!l-{T-UFAa{ znRH@><6^}c9VYDVT-E)@1`Yj&2e}3R-7>_yfhwVwv_&}7RuQp^>D}qB^TDyPIRAA{ z1CT}W09)bPu_`4wIfNlzI4leW3}R{`BK*j};ZGCqo2rcu#pnMH6It+r?z<+F`1ZIT zeLmpOK#*~Wm-q z_-_jw8{veay~b5i)ARfMStKARpw)u)TVvzg?00QOe}qs8mDRBSezt^!X4rfKE}PdH z?>~2Q2tE|e%31P7%;6!c8`XnO)9Iwj)A#JDgO7uZ|GlwH#uUI;VGJi&jmG!=&#nuB ze=1Y84oIou7SePmD5wG+ZlfEe3^tj9#0dXgaqO7rx(~~+W()Q#KOKMm1KC`L9{$+( zl;4guMGF$zOxQj6;6vvLRr3Fgi9(|T|BkBweBYAJ+9RIFgp0%(ZA|aC@dOa1fQP^I z+^tpj5Sdj+1Usan2llbb_whE55%|(Eq6MzuUG`^IA2(AT_UN-nWXMwPsXwt*^mEmK zljJrWQ7oWk{wuaXO~CgkrggrpIPlld-T3!gqxoC?FEx7wJ^uWi)|X{Z68ztU%dId& z?$q+r3YMeo-z@)804g|dx+?WW^YjaMv_WLLCzk+PHvaE$PkF8CH+}J|tuHS3-{~>3 zPs&Qs6148k!v8n@(dyUvf$+y=svfpSH!e~|9yGztr1NM3VaWd;z2m>kI2PP5#Jw)= zqW@{fUYqCYh`Q!bqX-i2n8E*h$!kJgpjyy*vPoKA{^BtbC1Jashgq2;UunUfEbtWd zzc+{-qr10|9)g|K{m+BcgqITh#sqlC)&Cp9nAzR>p4<3nh34{Va`8V;p{YG90fs*O z-?I>l%gT^B%;){Vbn$=eD9Y%9eECYiRr6pc_97PVxC><(Ytu3i zd$pJR-x&rb?8%4ynO&ggnZbXa)Ea(D6A2huVC-3w<-SJdeFbe7fbx{1jq4E3+{z<@ zj{7Bs11~pThU6YJp#xL1sty7k7mpas+3@<6#`P>YS^GbiE0j>94k-MoM}to+wxWh7 zx#h(7B{4Cps0i)74XCVeTE~&Zew{VCeFKv$hZrw|AS^6Q7cT>hL5=9+BL5k&nW}vn zJ?Ps%YXlYBD>T5}rUe$Lg7A$zEiRa)24-m+ai7+&zz zyY3Jiz2n4ZQKbV;1w=`atkG}T+3+whFvu7fW-5y8>T}k@`4i*-RfMBEY zFVu|Xaf5D8%F4>f=;)H5pEP)V#q(0_?d{)G@*7Dg|Gk7((Ef1SoN#5)m*<~=XHY8# zij7)9zA)X0;}GrbeP|RTh=FKJz(RkJ*o=Bzna-Ms@6P`+8fVGNtn81goziyacYVe@lxnxC8PSX{*I2k9Xky=juee z*1J2smxb>1Q4ECMEM)V4DGnAPot>WjehL4^kW=k#N$|^`=uY&yhP?t?d!Gfmm8&&3 z43m3+0bE;O2V_7oEck$6Fr12aYSsw)7N~N-DgTRlU@|9II zl{8OxtBl$b!k$-5qXmk60%Jz?18BhWMgvI;lF1QMP{08D*TKO7>*>?JA?n9%rT=4c z=crQ^waon_-f=krz#)~ZDl&u?1zhspyGD|*;aGSHv2hz5_+*^*7n7d+&!h7I9;p_o z^rDED$sxsj4H`s%DY{^ZfkcNyN1Hz)G65N|wn9Rr;AgCbUQ zhu)n|?Ic5~%mtr*o*B~m?MQ#VX)7Irr_;qeccHU=0XVk+kpcJ`jcCkC9Fv-gs*DE+ zEg|5Uko}Zyf}j^-rbUL$%*ulDT$J&krzp1YJZiN1-=Ucy>jMw1=sfb0_VzK4$mm%6 z_|o=phczg4NftcX(xegE+R;3C!d$H$B%skf*|8bJGOM^Mfe2(~W(v5xhhEDZ{1ez8 zfGlDX6N8hIl3v?aq}0(p>EEJp&AhmO105Smpd$JZd1bWv2zzn+2{zE3Y5|Wal-<5#m zgRz&3v&*#sZ0mv{G<{gIu|{(4!_c|*;FtzxrlWTh_You(z)2Q<`rPAur&^W9T>=IRT$_l2f7xddD+<5K#r@*4!VSE6zYpvU*hAxXJ>cLQjDi+ zeO*7aeta4`ppJ!aYtiC<%+1j)xB>-Qm&(aY8kTU^MDp4{*J7IN_mZ1k@G^J2wqZkZ zo0+nc8t<+Ss9l$o#6J-Nt41EzXEhDYs`Z`#+fwEEMp+pfpw#~?mX#i~7UQA`b7`<< z;a}ngJ*e@GtF-^SMv|a`Q`@Hjx=5Xr4AT3ft1|xY$nAd5XZ4)Yg8bY{sL2OWQ5Xqj z2_+@0+q=7Y9|3T~nFH$w2hpIT6G*Cn4P_Vnh~xiQP`}7%4^f_cx7bYmh#dcXK#qMq zPO3v6w-mW;^Ig+#|D`BBoWluUr;4u8KoYTPXF3g+3@ z-O%Oqc4kj98{@n3<-V_%$0bppktc?_Sd%3!obgrPbFKgI=<&!miLoIMx7|Ei_3%^L z^OVgni<^EQM6TvL#U)3J`^Sn4Le9<}>j-VZmnRC|U`RwnCursKO`~x6-~cmU?eBP! zgg1r6nJDrn67tKg3Cm|~EJJ*ZT8H6nBmB39t}K|23jHA-wYMD3I1I=H*`I3FFD_cP9AT#W!1cWFJcgVMnRuJ~iUN z#j<=cvMV5_b(AD^P`XiavLrTq`|zVM^K;e&m~J_ribNqG64b5&_xt4i;tNhx%}m!q zLu!e_&)VNQj!trz6^R?J&How~)fvdL6MK4Qu^nf4iN#U{Nk)-b0 z_PBLAw)!w2rVNZZK!`EAhg=F0k%53~SAQz&_4CxxE?9*TSOL-|4{|y> z$Ds{v_9@XzJZox*FQ~8&|2Q+Tmgok|8xOdcuil+)j&RC_O7(EnFh^r(EREU^0wJIv zxJ^KTB>CDn&W-T*+mbaX60Rn%=hN{d9kmo@jTV}IJ}a-wVu&rZtn2xlpc|BW)AP+S z4$@eC93jts+4qF$!`or$2JZ()I#Qe$YTgPp!_?9i(`X=IR?|^H zDF22YTEfF*x4=mX+7ar9i|w@G8Y~j>Ro4>Dh%RHQ1ZimpHEBM%+E(_l7A@0)~@5~W_c1)z<1ada@$ciic zC$mDue#N0n9h)*AUaE#;*xzq02w>gK1Q<$evKC#lkdfVbVoaVzbVkPS_|$Qs(pH2} z7Pnb?aUgX8uE>juN?xC4Jd#zo5uqV6;|57`np`yD{eG9e;dXUlRRhX)P#qXbj*KOV zT|y1)9s@5mb!W~EGz@W^{rNK%)Lwwc2Q*QvfWLNybBc%I{*8O9)qOgn@Qy!1Jt&sqkMM|Rgktj>>h$&3bDbc+@j-FNWj1dR&_ zsR~*i20gG40wrArg5Qo2mI?|lqGEF~J9|g+bWak*G#p+eY?27L5xLF_A_0G3uO}=b zOu}B74GnRVFn)(JyB|Gcp)u-}#UZ&|gFA7iaVBVNey(e0ym_8Z8r6RR)*Q$WY+qj= z>8r0G4n9-NsG^XoRqBfi4A?ic0`DBYt%b%Fv)boXq{9zi5h0iEirl2n$Iuw+;J@Fq zCrKJ!Ej-st$BNj%_Tlv^fj6)l__F#xkyWEQ@ZQ5ksxtCSs>bY- z)|r8jf|(`Ens!{<;$E$iwfcd)rg~8Wk9wq(k3eAm+ttBsn~@fISqDv_VC(Mmd&9T z0x~TQP3JUWl%OXw2ya3l`O%sPa3W4$z>H5tJv`SMz*`7@gWuG4Hw;FuiGs=(_-`we z?*V&qw8qsnc&B8(7Cl#GSOiZ}ng%E0DH}2fXS>$!=g^HO7+qype`B`yS?1wog~XMT z1w(wtY4&bZ^j9N~s+@B;lI1S1qQ`q(4-X1yn;KlZKNju?VXVlk4KC_N##cNn4w`WY z-EOIRU5(d}f(+|ve$s7A9~gSwDUKI_@?d)RNlPvTvzn2-fa<(ra_C3#e99$K(seK@VIesabx1+1Jlx;Z=De$SqBFOQqa;O&euDO>&?aM z+GLGd6uIuv1Muh{3LFJ6CEZ={DH?FK@e6*it``MTm-(-n6i-7Ok6=P*at)c^1Zg>- zK*-^%!T-GNTBHzUoKeuEh-|{}6F@T?w3p73YTz7|`9fK3nE6t->Sm$Ib2J zLc@4{>%p~3$A9`_E_!WEl{7p{`@{_LkybuMgfixvknthLy(?BRjt;aoYti|ko}p8g z-DB6nnv!?j2_@m-=W~QB1Y|T62`4#Dpw?aXrq<)9ywt-Jm_8h&d4m4pF&T*m<*OST zYhW2f*Gt>uh6O^U$UN|fBfE`zUSu-H<&D*5$2zZ;i|I{r;H0O*f72Ww-;rC4)7J5- z5Jc5g_~YZ4nW5*`Q(_aP{I;DUuC~Nee`hP4=g*JLnT>lHXWFzOX2#;T@f zW$_?Iz^@~*U)tvZLCF1*EY{|QH|BSS?Yll##1O~+35|MV1sKrU@m5Ay@k!{vxuYtv<&-E zWh`pgcbSxh9-OpC7cVs5Gzthl0J^S>l=>2nkcVbi1bwCat`5w9YtOBIw zK7fL`O4E`i@(C^X9UvX*cMlg$o)@dlH)H{QCIyxpH4c*OmrK4#Z;3{8tS6gEK87j4 zgd6Ba_}#*mcCYS$Dv!qC4N?6oJI}lNGg5vRZSAMrc5@MItKH-;1<)qn`jYtEHlL?< zg@pX=(9?j=M~!XE;ltg(`%7J7OA=v3A~srKij@*TKMD+Rshnk``yve$ebWZ@b{e*P zkz;U0_?fiKM){r%{~t|f9TsK#ynQT0K#))xL`u55 zq@|^$k?vkPL7;HOyYN9V({#& z*5ki|0s)t$tsIB#%5D-~&S} zXkP+4GKU=>Af{v-Jj2(nnOfPtsft@`NIM;LL0qZPq4l@IY=OZ-%7)cy=Sybk{%Aix z28}`ao zF(J;ahFgG9jK{G-FxvQzr17Y}^{i@tHu!3=X+L~&+g+!(2f`H{fu?{B&lMr)qP5Zg zNJj%4n{t0aLq7Gc%WApZbtMBY9s-iu^GTO3n{AvRrhhQl;^2-(NS2h>&{sj067 z-8b-X#b6gpCel4wYQmWBNl(#)+!)iMXup053i=qN-{4fd=4SQ%ZE5g(eW7+a1@j!m zjMz{3Tab|(SKz11ael)oWxBz6QQm zuV2HajfV(6%g9(Nzt+dW!D(q}-NYRCTU^wmp{3~>7+6|v4_?i4*b@9B$PypoU^1wn z_6d4*^?{MISO|!UwoLN^S=Svrh0vcrpXYkU%YePswpw)S9IiF49743fywh=O_(e?% zTegg>Y-W8y(msFfNV*C7(`V1R2YM(eDgE1e0}GuP@LLv1eYY@;X`TQ*W@1}mM3d7d zI<2NS*^a*H?wA0Gn1$xPpWa_S_%(82`N?k>SEWbw9y%%6^VIw#I}$?>^>;t+sNb*V z>BgJt?-fUNf|TjFSLfy9ASmFVxa7zI_864ynbkb{9&woopD*Gq-Izm{Pzo6uX_=tap`z?a0VO> z-<>QKF?a8YqLztc@_`cZYV5^EN4JA>ezL(G?1Jzo;&pn1i~D(@(UZtn+LKVg<16Nm zXekPVPADw!wtsNYiUlpU2-aC_mq#?yWCGatEL8 zxn|nn?b}s`kF5vhPx7D3lCts!402fNONaTh73 z12@r^g>n-6(S9QBEQB#galRqVx|f5iX}?)PusS zh|4zY{0(Af&bK3!VVQsa#5Dv!?GKi(=yYrid}pkX!Gx>F&B{B5c5O-yU~y_<;^v3~ z=2z!uJ?=tyUibmF>ZJSHCQx1`D=*K@vbru8ceIHUeXjgh(YNI7-31J*3JT-II}gu~ z4Ai8g)P6tPuxlag^oR$%jv+LKF=#&bt2rkH(7-_X)j%9ojZmt1RG#OEhiBO~l26Bc z<(vAhf=h8v#|$zpzEX`hG(D~HO@2?v-tpJWz+&*ewZ73UR5=@0Z@nUr?`mky&?sO1 zVNd=Ra!hE3r;Y#|N37#nBLiaQt;gh`JYnb)o~@~!a?>6--}9+Lm%`l--v1k%SZDQx zcX@_2{L7r&79$5{<1e^v9f>4?f}wmx}z*<7e)PP=`FQ9$xRfS=oy zBSCH9`uA-8_6xRnt&TL;iJ94l1bgkK8&_Hj4v#R^d=W}t(q}hz`}%Yg6qN3KvvXg| zw^hb%ZUgt+(LQ%VP!3vVithuUL^4lTr;9m``q2~NAk43_5Z7)vWrdKm$1Xhd_yyaw zQIebt*I8o}9kzByOBOC6J^xQ=I{`)7m_KzatW$TBIf$VLNu^ zIi5Nv7jq-6$y6ljJ&pYCaSpA7`IV@M&m_VKDR^mTie4LZh8cD9OPkX-D5`37OtV{X zmpp)FiGgAUO-cpdm8j7KnIetsb~*69u)QdOeFG=E`FqJ@fPDjpS2 zJ?O7Y5NM7e`g}TkK=J&B?}#_Q>$Dz*ygc9imwZ*ZWH%UBiuTO#ovK16>*6+fwz86^ zAbmbdLnF;Bil8&qaj(pv>NPFI-E%Ja3wJNvG<24Y?)Nv0%9C*W;Pb5WleJhZb934o z%}mxei7IlbZ=CNvtxQ;u*^;E`Gc|t)sabFP7uQ7$c!@!=d{IWW7q)Et8PZfGd|$PdFeKu$^(%))=6YD!*tjffDyccml{Z{4%FI;L56Ac=PG4usG!Qp z$;Ie|5pY6%p1qvj1-=cPvo#LtRn|mr-@XM-b)dZciA(ne>G@M3-VVMhGntG}7J47K zpaPzeXX5dgV*gxhQ6%>DHNLW&+W+Ny<+<<0q{W?mAK*AEv~;d7Tu?n|;^Oy1N4<4J5vLa(H)xTC=BgT2)!AW$$7Nr;=Ew_SXx}yWV}1 z?fR!>W0hxLB9&OpVf~oC&HwUkyxU^-6r2PZX^R&(=*OsEFlq(ae5sRNJG~0FoPnW3 ziXav8#!hHA54XYeylE~+xdEGVtvvJv;!5qo#Z8?lcjsg}GVqdY;2J>}yskaSAG|)b zyYh=;`dI?4+2Eb0=jKd4!OO5Dy_=M0balNIiwzD3LI}n>{NaO5S4Ta}S?*3=LVxFu zq7qUh&CKu`)zb1YBNeF`tK=F8yt(6hf~07_wPCP1ha{S9Pxf^6{QZ+NX*>hmVO{sf zoIg_2mtV_dkCY#E_Rre4qUPr`t1aCB0`Yjld|@C*ggiUrq#cYV@^uoNB4T1H<%}w$ z3`gU?=B~LaxOaR8%#q8@Cai-sVN}vQrInEx?eP9X-%w- zqUPHvu_`uI6eL|aKg?tm{>;D@xc4Aq6gYd25J+tn6%#F;`cP(tW6?A#YVGBtqPbn~ zanI)zWL0;5vaEzYoNZF2v1dgio*o{ZFSr(4SXUs*6x|aY6eI;gOZI@6!;PoB{X#NI z^<4}%q{8^xD#81rNm7#aF4gDM2mOy`q_e9b&l`!qY};2=mu#9)3J^ZpSdB$aC1OC&^?nCrRT8i+xR!=K6wuRk8J4?a_ed!Q|a;iu*yh zsE~WLdv*D4vk^Ht`R{NYPr=jE)7AKmlu~yYrQH&`{BMCu&&V1MYHt{dlI^StQvnT- ze}FehIwXa#H=2vp;5NfZt7qeBdm0Ciz_pbBeO6+7Tz)}x`|Q@LatwRu=DfVgizc!= zj@becfLgnAnXtx}& zSw}}U1noK}qu~rmNLE{9@0v^kTOe2m0i=^aC{(;q6${t&xZ-9#(PpyF*(TXjE{QAr z1G85Mmi)k|%vgQdC@Bh&0JOChKa@{*!F_(gGWPnp<0+0UiMn z6;}_7NIMc}G0Q6}-TnO(f`TM|!a{m_??FZmN~gsgi=EQg@bKmuhYf_ysd6gtY49Qu z2?8{kc--H1wi@8loTl3 zl$?tz4&>Nwr<+S(UOodk-y0)Huv=)p~#N zoqrz{rspwOowfd|5o2!c!VY?iYM6F!s9Cl&lS)B)S)^&B-z+<^v}B#9=DDrKMyu*c zLqCddA#(thb^h)(k8EFu+rj z*Bez4IlMSoy3OQr+PjI2tKK$kizzDhSihzChmGfamcjfJ0$wK(BwpU(AZF>?;{z`a z%muGXWN)zGyxLjdUJKKXpMSRIp-2;t+wzUi{e6a!;c@5wGt0|;97i60i>7NIInw67 z>gif#DA}|rdR)3ka#EB`B3lfAwM)ph-(1Yqd|!@Ggr;x>_l)_0u>M)!HhSDqTSA9D zjy+#zY2|Fee)-fD!8(OC`HJ(tSL%!A$v!QZBaT@+@Id{SQA*~rI?qeU@Lc4ivpPNt zT3Az_&6?v)5)>podAK*2RAU=BvXRE^dj1q&_AOWkFN4dP1k7&jz-yjAT;VKf3%@EL z{TTNUc5}8r5cMh@kL3>|#!|ART)*C!#LnaQmA;a+4CCoKrCuq7s?fYGc+jK3i=QIT zHac9tv3TNg9$nSV$TW7iJ(JHH*%>ODKT^uN{l+X_9W|IO5P=?|-E=$8GvlvQyb-W) zzX--x%nl)Tq69HX+};?z@XspIG1l6xE;rF8NL#puu)&oJ#--`*74^F<#0aI4CvkRX z&y5G!#`+tbdbmbiuRN;HEfD-A&^aj+wzB05AsUhZt6wzRS1OLn#1*&ng;<$Efl^MV(v z5*4%=}6YIt^n&! zAg+|uLC3!Gf^V1SzsLTz^sS32Q@PP~zW=p3j^1icxazVASP`u0H6v`V$f7f^gG$Kt z8wg8Z3#)pJ#x3+?8Fh_&Z8S3=4PE&kG9l$Folwoa{E?ks)7pEp??`Y4S>**oLkxQ;7`pMg<{(SiuSEZK{C09dfQ{)j@a>$h8xukBE2sbsnA(`R!*kqE*jBrI+ zho@(65i`3FSQ0Q#Vr-<9%A~NUyCvrjPzV$m5nY?Fv;|_tO^kt??(XI3M%NOVm3}a& zH8;|G1I1zq!dU*emrqaG)8J%kbtJF&9$naeXq$M^(A6h0Tl zVJeD6=V=I^Z_a}JWOrvhRHcsR_=j$iNobN8GFf2HkP&NlH}ok{Krpmt5u~usU3pgy zmPEg2WBIM|(7-4=>3XOC1#Tm!TymteulV9kPCYZpMDG%;~FS{AG8Jl`4#a6L&_e|50E9Rw^d27~~uKuio{w0%v)6ZKalVEnp9HQ#6? zOO}J3AAm~TJv|?IcoG!S#hE>-t=teAbOzz+65L+5)uEkwUS0x#u>i7cNIa{_aAxpX z1`{i5q;#wd3UW$H3L%&6_a8sZ!`}3|bs6(|UoO3*-h*W(o0(<3=p9JrWi{vs;TbXC zpRG~ao{#~c1CS83s%?FCikpZ{Og1#aa6n4z^M`_Y&`N{%g}V0U*bS4ahUl*z?2ol{ zl^8$h!>Rcd9MwY@mb964)DQFfM2qJG(psZpIMlzqw0lKatPGTZ{aQ$o%3T}jv+J^@ z)(O{Jzqdd?efNMLJO}KYD9lgPz`_<9TH1K-!HV~{n`P~NNgUl-jOAUHVbRc@=bFO*EIhdj0`r#RR6WEI)rtbP;|DAr1Nq(#}+?m9?Flxct~8dnhm zgQ4+;Edx(XuOu}fvN}RZ{IdNbea?fvTjI+%xE}7$RIl7;BUIxie)`;rrV0!oAn)(X zw!9VoemPv^uNqs5hZNAc$NxW{5gC2`P!Jb{s1J=yousTaJ#AlAkTc5LkL!WDE z1>gP<=Husg+1d)gs9gfa&KvM-eFV)B7wvA0v zX$s$g`g^)J7Wy*9BM_v^m3y-i7r&U^%{vmsE;F38M_Xb5%d(}= z*pxh&j+;_ZeqCY^2zAplCus}6;(TeX;qa} zGBZo6LA#U@>}tRjaD21BZ>@OhHfX(6e|~G=i1s?hlA4-+1?DVZ3=Z}z=KFno)yBzc z>>UWWb=o_3WXyCuJ?pPllVi8A6&onmww4A8IR_~})U$^1R}lj3q}Rsl-?+`hD8A#; zu3??3F%#}bdRm(j+}Wto==f+dF-^uK_hgk(ut>W{MB2vW@Vfxt#Wb%en+nHC2r!~b zxY>9AT|8byIyB+iEQ0u~WED!mq3!^-WGJuq6A$vA5Q1%S*y@ISPn3d|$83t%L!IXl zN^&>yN4BaD_HQyi`FIQ79~e*l9Z*OgU@okBi;d0p6&2W)&N}GA4v8J8{iBNuGcq!G zlHEr4KkDo2SMTgkOP2z$tMT#{W$TW>rb!4$p5So!T2p_Yuy|y5)Yj29{ni)Q$Z@;2 zV8;u78~&-$z6jtYFvC%TihX^WE%UReeX|ar*?JnY0vQ_`1}LdE5sBJze$ zzN$7mUv+ZX4{yU_?G(EJ(4^>QS~%ZzOy6B!O7HhY5J!sUR1tZLvnq440t-_5Jtz1@ zwN@bUxK=K~?NID_`($};=IzZ6R}wZ0pLTSV+7`vqq=G5ypa{LX@cqDOG^IxI$kuk~ zq$TS5E1&dffDrWmuofwqohW-(rEleMt+EP(dgaV<#FyEoOpYh*R_bU*bX=n;9FfVrB zF*L;X8Y+4-Fi=tn0OXaNAfa_$L;}7gGk|un02`7*;#gT;?wes0Y}H182mp$wGQAec z>{z>B?8C{ge*LEMax8g)>Yu^PM{R9XWd}pd$0*20CuiRtQpX&QsEF(9RR8Mf0fp7= z#IkYn5^HVk@eqhnpNLCBAcQ|g#fC!Vj|w%lOxC9=yP&>>=J;yK$-U5RoLkp$^g$vBf>VppNgA&NiQTR#^p~;J z@468chgqf?9+-^Q-k$EvB|Ga}$rlPUajn-TjHo|5Js5cwFXImiEPFlOx*M<;bEeR9 zXLq+Pe~{mt;<@iu)wZ`hzo@W2OLs2bF27?G(2WvLr)1YQ16h@|YXa!B*#@PMDh*E$ zKl`H-wE?xHyO)uioj;Nxc{f-%-TyV|N2Y%?4OhSZ`r@k;H&7eo8+`c_C1f};FSs>F z_9JDkP9xOkC_SKbDV-BIOIFm%6Y^i<^b)&>COp$bE?{R}Wq;nFBM(xR^iC)xm~eSO z@CIAss2ORgIIFJfFRy0qb+*pj%w!8{oYbG& z3(95+W-c!B>Xe2TAk}a+9T{9C6hQXNHb_wjqH)Al8GX1h!wj-A5>IaaY;WCquw{%< z{nzwNT++~q{5rz2V#|bZ-r8L(2-PX$jb%r;S+?d=PEJl@m&GSBjJgc6ANptL{06cB ztVb#<9ohsWknbH#U%&T)IzPN&z)rwW7+aLVNkDt!6!{#8GC+<*T3$wO8IdMQ|x zGVkf=Q03+2^FOZu;zDywl337-ufgrCrN2KE3>AS7Fr$P3z6bE|3|iHn3=K16NdV01 zC)~_Fp#`uTz|TKTmg@vsC71g-ogQXXZ%>b{b1{G6-^Y^tIenljMtLR^c8X~1Eq8~a z#lh!z3HhjR!QnSwAN=v93oWd=>tC{0Gsa)MFL~o@0n`}x=luq^o8LTcBB{kzG)W3p z3em@bFm0<;v%IqB2ePJT*XR1<6_U>{+3Cdel|Dk=T$|OEkT)IesMQ86V8=f?wKZ8) z@hvnDO;D27v>!~<b&>jWBKm*yS4Im!bG&Lj?b9zmDyxDG< z=}g?vae*EdEme{rCYU!TgjbEg+V|)3$;#3gMWx~G=a=_02eK41tH^SxmKy5;556y+3iYNj4*a3nV#<5s zFg+dB#I7P40LPio8D2h+(PsB89LBGbptJB9m5J5DiMg51r_zT$^}3jIegaP3+-MVZ zrNEF7khO?n8oWk)2CAcolAX0Rv23~I&9Qu(WM1b=+9c4fv|E>fnY4`NDs9cxRh`by z%p{tPWC4RdaSaW8w}uqpDk+INzH{cdGyWRPl;r2rg5$N^?eO^Q%;ru*EAtY%e-@>-#le*qe@!3^C^dk>#ZQ^bB?pTqCmtL&5=ojT zn9aJmxs9rm;K?YMp={_(EOU(E1Wr!rlL~UPCu4}b43A8FsTH`H*BMw9DaHn*;j{AJ zk58Mj1Y%-a3Fw1$jEwk3&~7PEL5X}K70upqn-{-x1c|c@K4%2~4Z6eite9L%&8O8r zUO5gYS9=$8fXp*yX%_0ovGJa+PloB<{p&Nsa$O31nJ|~apTJUS-a6A;t}rmCYjYhs zmTLWb{$g(|S%<%Nd1Vb0Y23_qfm*);BR`xG1QpA-dJpz-UDuv(P4!DvSR(hEi7-TJ zW^NzA>60QN6saT1D+&lf9#a=SY|O_$>$-c-TeI``;q#0*8iCed+K*#q~)>6k9-GbBw~EI(H3Z*DN$vZEvmR-{}mG#WcC`*iwNqi7cLGG5^KK2kp`X z&_AV0=erXUu^8zRbHytlIIS-`Yfcg@2@hr#gZ{V`^)U{_{B;}LLr z=pP^nKSxANQ_Yu@lKMbPn?GOMtgfyOp3f&)j&S4f3d)!>pPSRI6{bWgnYi!S*;L>R z%gpJjMU=9$V+NJGsD#AI(o*wpQW48GI3ORWk;wqc3{p3;*j`|68A86Pk!9utff#L% z=0c`TcV}63g!=+8ZSh2x|;s1q678dUuphB%B6p}!F~%nZtiGsBP7;# zScy6D3kz5B$h#4_P_P?=k`()G?C-*Xc0IOnJc{Uel{>!0Ed~A!CsBgE7YP_0Tm1G;{J@a@qrH+@Szg8F~=f7+olo=Epq2Lb=-Q2xXu=p80~gf)dS8naS9>YGe02t zu?E$O6LjD~*4+1q6KJR{1p+jTI5HxpIg+u_8n)Ma;MF`QtFlvL8a4r&XSP17DXub5 z6!nE5?|^g}iTKQrT8U=$^6L8Q*ou|Bi(B={Iql#VMU9STvd$V?>Xe`!sR|7uKQXZB z6j$2S^~L>@M#I${0`li|)zxfVJbd*Q)!3363JT46RjQH@EBdR$5p)6-%A!&yw%EQ9 zbBXRh(7o)a?`7{g-?(Q^6N+gjq13cYm&#__%+RsN>}*Sk?G11PrepCVYIM6P=K0^l z?O(I}f9{_>$Mi4LVtaMNq&$r%avPaL&+@f+VrK@{sSUago;T-4030Ewq{Mvtww=Ce zRxw|#u32xflf*mfgB<`zG&jiYm)ipAzj1_zhlBaDh?JCpOzBuKI|Re00%n3x#*tFpUS)#GXRD%$MsFb#Tuih;p(FkPvlqM`~@+5W)BRxv(^Oy96z zjuFyKu7ysd;XK_?n^x9;Ch@P)r0KtO=m9%wjyR8%-a*z-P6rn@c7l>#i5ssp2YXL{ zQ8=aQu!q4GrdzqEKLc&3zdRLziQfXm;?m` zy1e*hz5{q7O6OvC{;X%gmO(2>Bt3U|GLSW--rTlu?||P?*^NI(7si_V7>+-irO|g> zg668-UewX$wTmo|0)WsxAj<6NfKS^AkDar2WlJN9$6PZ#>p9B#LE?rI| zOYR?W)uP=~EAzY?GYux-U{M^lVwI`DhSnAV;>P1>Z*X_o8OfQGvnYkjza7P-xC~z$7JTj<`&2In)5bg2Bc;R3f&@u^?j2VBI;}ph}~Cx5e0D(#~5@yA}Wr&VSlEW z5o7K{wN|h#SR04S=|w0cL^N4zl&G9Hps-0#xc~I2)nKAxE_s?}?+fLM_L?r0jkJlK z%uPL;mptFuUi4Ze6v<$tRMp* z4Q$SY(YeuJBWr1E<$%_ApnOH0Jiv;cNkB)aGtwbFle9{Opc?(JnuqDQG=b<8Ch(9Y zw9skUB$rJ^O5L7ypACWlD96b&GngHwGu%dEIQ&b=z=oA#?>0TQ<9#Y!CPPs6<~l|y zj;MnLDxhQ2e+h4OS@D+V?(lPJagl>seiyzpDIkW zpT(GffNCSd-Ac!c)S_uxbVIILCY7a8WhUo!`B%*u2QPq6TnHY0*q-%xdh6k8vxY(` ztV2MHz8{-lptWQT^Qj;d;hlDuH=$e;k3Rk=*Ng=CGG z_PLPn%WxwFM!Y}Hsq-PJOeu@M^}J?J$uR z5X8CO$+mbIO5teT3}F7S<;R6ZD~sC*MV2%b%9?>$^P&t>jgygbIGo+LAAJtd_wRgy z^6N~Sg+`e~j!+V>%O|1Yt^0Fz+@M&#ySa${pvcO~%I$q$KPCzq-XVQ`GN6fabeL0T zENubCy&sDWP>q8OD_Gb2F1n{j3PDj(k({|YH`l5!yoDzjaFb4NaBwzoTP>Q8o69R5 z*`Qes+3b(KkY+)gUccz`AAEWr5J4K0T8AEgp=T%uaql94iETPuOjS^rYND#GbAxJ; zu6{!y#pTf2Yza65Vi93=zD)I`*c1E{R`}f}%Uu+AgRuj6?d#r_L8!=z@I_VS7_tY% z9hOgD$fa6e>Y##5evJpAauC>Y3Two8hH;8jmHN|ka>Wbo|3kOYcNUeS!EhN|4` z8hMESc1>!Hjsa+ged4oR%s!S>dHRDBYE{ zUEh6mnh>UK9>lQvF6j{jf>RGulr`0##RjVjP}zb#?GwInmO!huN^i zs+HZNvle&z&qRB)16t;6;+d7Qe8c6_cl>)0iIn@ z503oa`rGxF!!B;ie<_9^%JYL!1_hi*Q1N5CF;Y@71~Geu~DC9I!+S>N)h&l4{f_bHxW5`H^>S7-hfP}sfN ze)H*@!Yd%FkODN8iQ9+o;qp%Pq+)%(>iS}<`>ecZeS@A?Qg(3l+z9YW%U7s)qv)Uy zgB&cy<+{%2z03U%40UBJbOPp+#jV=Yq_!25UBV^tVDl)b5{9bOoa;JAGpJWa^z4dV z?_nxQJOurZy_XDwmzbCg<@fnEpsg$*r#8H6Vq&DAWhv;VZ*O0AdR;kV(>gH$SY4B+ zyw8WLbaiQunAMVL153Ik$2uXec3OB38d|$os6a`7N;0`X8Anzk@^YOqNglxE?iag| zIHE?cMwuiw3{I5hMuX06OJ_2P(6$DD5uH=N;3OVbuqNhRfetKTt(Z|FR~d7fI;u*w zp}jH36B`FdNk>Pn>HZEE(~L+mCBkw~3utG6Yx2j|!oW1gJ4P~(McMbBxMW-izLvW#nWFf_kH2)WJ<>A|3rNj+1bCKC<#l4& zBc3~-eZW#3ltNW$Q&ZDqg-lse8k!)$G^xL8Jhydrt_spfW;H=u=?t^M`B6ggh?UQp z9S>g|9xfKu?LXB6SqdmMpE21kek!Wn&O?N4?C(Q?+yXL}NB(?zK3xJG=%|P1=N)5X zZvnoqrKNSb=!*{Ckm~Ac+k=J+shdCf}(B(nppqg7m zAnf76r&(qF;*a;ky-Yky`@UDqMlSW;W0&O9A`vAUxHlz-mV;Gb`)q5G;RXIF93mLrwVa zA-Tfo1F{F#=vMFKvT0!Oa(Hr<1!_SW4U6IG@B){mBaImzyKBBM{-&g$o?2<&z7zq! z2R^sdQvpCrYsLzQtGn)<$-X>0=#M{%EvV$bJ5(%6g}}x*K$BkS!9DVs)4M|YqvO-X zl`5Sw%$;`(o*|dL-4H^fUQUbo${>O9ZAZR`X&R89o(ImD4URk+haA8~LT z0`I&F7uLpko!g_R{)ZpF@94m-zj89%4h^$>PjNMhdqRhkL9F10VD z_flxx3*2p9+_}vltJrv!#DE1v4dW}IZG3ogM9IyrJ^c>IE8_>_2ql2i&geS3#^v`w zI;g+4^gXxggTOjLFZbledgn#D`@8-XK#G}%a{wye7+yw2Fk6WS0DgC`J4~iIhwQoP zxM7x=(for#my{(SbH(a*K~Q3+N9`|;&Q~vFcQO)|WgChjJHsm6XT6CV!lp*DnVhcq zB$3X}k5|J;#>3;HdcYdH=yM{_Ee0<_{G9-Y|C5IJJ0KWSNhC`EWK(tqID65C&APvI zFqVN$?{{u#8vlP5;Ma{RsKe3uPgpk63Z;!l-+g6vb0MeIaRGAG&CWMaNzFQT`l>?r z0e*FReb)J!L1ifF$Q7Kv&H|SqW58*yV|K@c$vx}rpbBofS~#(=ycwQ8DYBNe?Dx>{ ze(a$zG%t^4{_7E9wtR9-CI87Rt0-C_|4xW%e)MxQ=@!g`# z)HhR8Q+&1u&s1k9zg@lPg~_JZ{5=S z&u{jd!n&2HIIELSD;$Yk4>1r_8>)hayZb5X%E)|JqOA%4sblbZ}R-7PvNT}K| z@w-x|mz9-Nop2)LiEN7iXwz&j)c75qvx!+{XO8L2w}+z=G9i#1-c-_S{KLy5^L-12 zRw&a%19zGVjl$OUMaf7?c&0QCl#sgx&@P!d8mwS$Cj^)IhmbE~ctk`CW7F-^f8dWF z&3bx|ssjy@ZoP|wl)_xG?jt+-W#c{uLQiL*UQ?&$&a0-ZJQ^=NMI1994(v`1uTQr) zZh%(~J8#eUvDW(f`gl#TYJR&Z+lSa*P5Pk!$y*Zo1OMPfUY&+gQ5fidLcP$+M^a1k z5VUV;u%E0n(-YPNck_<^>GnG&KdrfGHpL77AcA-FDG{alDH8JOOPSzf;{E*$6Jy{g z1G;rl=SOEp#!Ipf`tzaX+m;rai}wXOM^A0)tNeSrb5&6unuUns*sPzc$rBo2`C$*2 zKFil}hXPa>hM8x`f|o4fTVn#J*W$NBz2HCBl}iB&-D_)dk&sH>s)NQF?ZXWhc>I89 zAdzWG$CP3!mvOoao}0&b1Jhl z>S-Sz65i@>I|7+tGXCkg(YZcUXo0iJ5>H+!ODq`S%Gsyio+tlHUM8j}5D<*uXg{93 zbB0s5jlbpql&<~F`2)g?!izKLGyEmsAXdfDFm;vBXY7tB}y@`n*QeF<2 zoLKrT>}{^>ctA`7Bvn%^sAtVSQNW{~@95$}EZKq{*Tvm+S~m3cp9uo;*ewEMZKZ5I z+}YA+#QWAx?Ul7a*%L+Ewty9K8_Z%DJf^EqAsRbu|0g)@!F%DqS7A zx_Xu@9Z{wHegLg}eVw~Xi zexPoz_%z-=&|on6`w3n377vHV4J#-c9tT~p0+Y&pLN=d%O0w{ z5+5$4o@-?mk~JOvCiN4L@q8!fLdDZnth87`7DjO`%qG3B-ttfAnH5V$RCG+K&4ECr z)toV>r>(InB^b}Ue0e$Jp^7D&*z@x+cVt=h_!7CDKwuQ6=WFY&+@7*FZK=Nu2#+ithItHDnBrdzBOk=a! z)wZMvU@PqHVJrG~$;A{w@5VWN643PmL(ozO{bpG}ng1l@({12%zB>ipi5Wuo+er{BVg#U~iFYiltWyq)$SbKB50 zIGCN2g9LCE+JK_-?+j-2*QW=Gjs+i1jiZ*FxhK=Ijvn|~s=){z52cR)|A#NRS^%md z1K7cEnLQZqBLaDNsmOb&%sYH9*x#|O&oXkYrc6W3ABU{3`xAiJt~kOXDLMF0J2TDX zq6iiw^qPXR>3c{YA%NwOkWo!fFH9LIGL71(D3z48ggeoEKm&lgLe9=0CvVuEoBJ(i zG;Ol5Z=q=1HJA$_qozm(ZXd$FzDPURiWbi`q$`i)m#!vMOUbt11Cs9ccI_nxr0l_( z&BT&D0I<54kxJc+bZHi`1CINnZk{u(3KOuBoacVR^9AmHK!T;6zOGFm^Tp|}OEGe$ zkE#R!P{B(DhRnwy&&`yGc@Gh2zsdtirw{q`+@x1`acAWM5IvY^FzczR6EN)}l$ zT45YpVi80H1-li*en81Zj+@^6*;S0YX1msxLnCOM z2dB6R7Ey#jY2pt{Em{j(c(66SdA$^vouYTywS=%cT@x%XaGNn^1#aaZ2_Nf4?2w6m zDjgz3-D8}Q9HI-yI^$Wbb4PONMCm*{Dg0z1fryUFgn(CKHS_NEBJx;xGnDq7#|sCk z-w6tJP)a7IFPL6?z%i&9(7EBgYaAFY;I8fHFLVu7KL_hDBij~%SX*g1)w0?hxfe8; zEuXr6y0xv$tzD~}U4ioIRWoSXrloxVROi*zMrzH~dZL25C@(N!1a~c2U^5t0h`=Sp z#r+uA403o5eOpUQItl1#DnqdVkJIk2;$lY72mo}|BayW}m}>L3y8v!_xe_Lr@o}|M zXZG!58Sp1JZiC}2Q_unh+^irc5IC6-C(1@jvEor3Vz7nSk=pA)PXA;FxclzB9QTV< zlmtD_P@WF#!neX-O*+TEp&XuAIXb40JrW09-y6>kCXqqn3$K$HA?^dXKi*K4N%^(2 zD8a*X%*c^R*u?64_Z7&*?Vg{W>HMTQ8p!idcPHxZi8P-`=%|q#bQo=!=WKEhK!z4l&*ww+Y#|lWKcw z#xinBx+u-7>340hfdUn^8f84uVukkD2Z6-TJl+5c-c{goyCQ!#8_9;%;_j}mcPw@_ zfA1DD0_?U1%o~hrsJK3-Bz z4#L9_E!7TMk{K6(#@{KbgB~Hy;r3<3+O*O2Q|Gesq(SLo;xf4}^WkEa%!#%)gb5mkTFYtaa9AV|-w>Vumy%wK>P}?^t6dI-i z@v%a1-0~6)?3Dzm&5U*Y$oM)E;m_)#r#|#xVEQGoThvOYd?k$fsgDSk*DhCJEY=o2 zJo*uy2ChH@N!ASszb6K&Ri)UywpXc#N2Vp7Cx93IjO%Dxo(4A-tAbJdP!;tjN0e@i zR5UD+%P!BOhVKp((M71Lsw(Q}%x}6?L9>j1+5&^Q`}?zr6;m3eEScuHxnzS*8OVnU z4SG8}JJ>!6E^b$WdbwpLnRoKmEPPDzENc1Uh-_d+=s)~5 zBs0tPS6})|`>>R(rg@Q1`^xFx`2A<^aHSakZrZ+Pxp>gs`uQlGrcTV?|2o0RPwi)* zN=#9wp<(B{-n9U@cX(n^U1eb(78{10_Jix~`Hgku{;YIIw8nv;)m(QoSr(>dmtM!{ zD?ktKa#S21w6FCB(rI|0g8_UitDsMdUpTxP!XNk^NDz#*IrGQb^Z@$_8%QbQ&XEcFyrRESOSu7r3)L7zzs%o6adO)d$=fc zd~(8!i^_3RQ&)#YOg!-O6_zbfqDCSlO&jj7cetH)`M(gG@Yuj56D_85M9(g7*;k`Qj)2 zsLROs34FFeI)8M2ZVmqhhVf~Ff`h>|$x+U8T0;GgK@f7t$;V=ulr7>5^W*Hvnyo&#%%=kLiYloF>w@<-SU zIFRrNW5LiyEe4aeAtBM9&elfx&-=x+CcKGrx8e!;>|2Tq8nhUw0Ke%56SCTE!b-@a zA@)3#yyx?%D3rxO(ntbxj9qW-p(MQXGqf*cl5^4{CkntzIerxyiXtz+>8KhV}TLc;?feB@%z&{^WW^nr}w6>!CM9HbQd=_ zFb6n7$$?ADn#%*>#H|=3FhWkcE*9Nq|3~VH8#MTr{~;=RGGzAE2C2pG8bscVu%Urs8P`BOwCHOq4QG zK|>=*HNWry;lHc;{D+gjYJMg#X^WQ`&zfRDZO5_nTTGGXl|e%M?f&{-?#75J`!8lw zSx=NljSgI!Y5u0$viP0#zPG~v_cQn)^1Ih& z1!XAMBDa;(lz(n-D+1#fl*0uYK(HS7Pd~A=;G84G!{Z1e&eH1cqUe`YW&g&%KJyCr zl%@TqtzGQDp&Z18zw*F~hS*#V$!DnSGx#q(4!{czjSR_)JV zZf)HuBW4AMHOtjqi{s*mfM5Xipw(1V{N=K2zWDxmid^B@v)kY!kUs=0I5|T2wT!Ay zQmjMU73Zr=1V)bi7+t}4?XOG??v%BSv!;t+0Eep~B?k|<;1WNQd=gD-(Zu#oz1`W< z^Q&@dhnAx$6~!Lt4$2?%O8WI$rz1fMt6fNg@!`-fYj9MPZ6fZ^_cAz%u@;w?|Ds>1 zto(G3kH%&186{_<3ev0hsZ%ckdAKx*_oi9u(XBr;E;p^bXiO$4DHJ4gdQ>cX-gfHRt0iYf<9_~Wd#9r=f4zxASh^K z(NimN2b}3e_rSucDkcA=#p3b!0BK%ga#GUo-Q64Fg_;?|Yr6GHf0qAy`tX`EY!q^Q zeEf59apXJU-G3XTci)-l<{gGdEyMn8(Vv8-0)Z9VZN@8RLn16J4C>SXIRk{zvx`5| z+Pc>*_)#tk)Z5P}RIuTTMFx_o*`nh+fDpc*zUujoAAIi^zrP%%;;#q#&izx#cds(y z={>=8w%y!?D{M*ps#-&G}F$0No%k@r0r3|tW@;J1vbX*(N&UE^wJs}d8ZAI&8c+%x1oEP!7^2X#CGy!(e3A8vPRD69B+ZW*d?e!N}uG0e8%Fx-%!J?O(7=6@Q32=B1bX711@ zvhAPIY(^^Z-Swx9`h2uOu4rM|IQP|(elf`m>XQN=&I5^1ItB)Wf{rtIvzXR@Eo0)bcwgTE{+vdM9RSqVcUqoT~KreIK1ha-5< z{u~BqLVmxcx3xPXc*lzNX(7p`U)-=Qv2+8&%eJ<*n4}~CDrXfW$ElfdsIZ$*H8C+k zl7jxNYNs8lfbWn23N?s7183{1CroZYAgOn|dwWND7Z@1X>=P%_K%1#}cQr`JwYkSF zU!5M%lJ%MnpsTD2zXV_0_5Q5 zV_29*nMJR58!i}_Ho(U2?d_>+YctB0YO?|rtLE)ppGOsh;)7Ury`l|g)!2J%+@2_XzEebXKdYLfmy+QG32CT{?)5;H8%un?Azjt(C z=D(kDsB(63iAhXkfsN+>`0*U*%1(|IW+mA#ksFY=lk@v0i%8EU@U#2+uPKKr zJ#a~a1cg$8CJfaj5s}OTV$ffUY(SC?-T=SJ zJ%6qYrUsTmU0=TdxUz4ADFu@i%h~`3_UCwb)vPP_Ln7$TwJOkw*}h$+_9h{D=VA&AoslKyOR=F-Jja5 zvEuxn_pX4HLhTnZ6u&4dVYLmAIW`t*Wj9$|lV0GHh9=1-(z79~=;e2Zs(on=@ECZJ zmV@!l{Pw#V`M3n@!MP3I3a;^)m=#wXhssv)RbF#3cynMNE8AfJ?3N#EtXxkXf_Hds zoRv0fUfEs+nUqbuxC1sC#45f((-s*3eq%Nv4x073k~DCh(4c(>_$uKaXg`B2va!J4 zJf=m|PaHf0$t*7B1l&#%q(pc>!~_Cy`Uw`>;c|sSxBhj=HF29+rLDI|4Sp3>$?K}W z>NUQq)2%%1lSAahFKeykms%GMRS%h` z&3`1`58eiCioKVoxphG4X*szD~JQA%Qn)yJk9+S*p`0^k|WFa0Yjt}imN+CI0< z7a(kRyr@_P9!$>BPwK%{z~>O`B(UK@J7C`|Iz40-q95D*47$I$#LP69?4dAne&QET zaSuF5`t~)We5>8INp;CjPmyw%O>OUwcIAO>4reX0tAPS@joE-t20W>X>F!fV+ zulR{afE6+5MSSXt&O6+IcH~9V`c{z4pi0T!Nqtx0${b#I0SUR4>q`GUFOihfUNkw9 zdo9#L3E9kugG#x$H!h-*zzj{!=B^qCPl&=Ff$N(g5ZTE2eMV7sO~TOVOBxI1{7*Wrn>MDF3}WRntI{DL!DmYxWrp@E zD=LNqL16t#=NtsZlrR!CGf;El!2s1SKyeCH@G)4E=%_ZbX7Da=Q@>HFmf=@+SsOwk zYiAztq!r`!qAL6PHr5-$Yf7Sh@2a!kifmE8jbaXsefXoK_;|*+?ksT125=?#8TK0l zeB#!zfwVdGyUe(K|B?s28W2Oc7TxxP8u@9I2B^!FGTa}-EQ%B(vE#)GICKZiHQy+n zumhyi1X3Br$!~>XzkEsC?`u-7bKgSmpVaRKXN|gG!^GS~u>yD|+ia|0hj%sJRQ47a zQtBY15jbvyb$IG6${c`xWMC195{3FBL!Z4)ON-#Yz_&&|;2mVWNVLL#iGBn^8r@UC zY9QcT4npHL*L%OYrBrhqjA!{h>I>k-11a-6c@}_yjk?ww@>V+U1@7uSuq^>g^v|Oo zfh_NPHhBK@$3)JaQK327X#h*3(V}?tWyudttUsM8JOgx>4kIlLOXN$u=6k0fU6x)T zP`-wTecjSq`lX|jeO}|AkFR&8)A$}kfJnCVpYM<01H~poy& zJJc!<%t==YwKPD;ImJPt@IfMj0=JE^uh-ou!%+GkP$v=#3qQ?y3 zQM?@(Si4!;T>Gx(%tcKseGdEwM9I>$b!=@sL_}}%wQOr@((ti~L5~X(NhSttI zjmfTO0y^TcupKKJ{qZGZ$yKQLT1Mx3q>W+Wn7y^<)4PyH6A3c%R~zTSq%C~o6L%l= z^}^D3D_cLUW(D>~JLglkFK9wRNQ*$;!N8~YbuUzG?s~UDhGY7VF~+bCJsV23yH-A; z7w2sdlUo~x!RvWOaDo`k0t5eSb{}Fmw_frMYCdSWCIZ9?3+S4uoqCv>5`_dcN=Gu9 z8W9Qdjr4q4_Dy405^NF zS35-mF@&D4l@n`zwMB80)VKxl67HYJu-jy){L=A*u^Fz#n>w|6C4%xL6}qc|f2wC3 zW?c8#PJPFY&|8J)_1UBprtZ_Ts1{a2l<)w&k70gxNP$`%aJ2+_4aGBx;X>nc6rO&G zR=~=5ic$;UCH~CF_e6}si=k9{ z@jaB3@uV5Kd#no+t^tOGbguN+o(5z zO?G{z%r-2lr6@A8*}bG&!}b*gdp{AXH)TIz%82dy4N9NgcA`Iv<_XLU0>GOp1l~?S zS{hHS-0#asIhQewnHs7rw>ov)*PAe9f9x ztroqfh6ttVmQ9os@U|_XsbEyKvXuanfwiZIuTXbA6CYz^qGM-tKWaxy-|iD_=RE6B zfKuZ>(1?3>r~yI-T!EyY@$E=PbDNNI;{n157;q=v>KKU9g@`ryN=mgBV(#)S7*V%o z;b^@W;TmW)n0&`MX0;BwVlz64JsI;Q@5cwH3hPnTwqQz_#6|c$LCfy3t<#e#F=qA?6 zGIg>Y{P?EF+#^2|ovl;mHyoZ!(#653F6VsTZDUAcCHYlpLVJhCnKxgS{qRxQ3TPf{ zX?Y3OhG#!oXQ@RoT9zo}W~H?>O~*23g{;M%jE*h(B%-rEP!tBBsRgqlb%AyY!V8I1 zG0BNJ8n&u8&n~sA)o%yl$f|C{vbk=PFd$Avwr8WV;Fi5(%Y{=haYm``_PT4Uvm&lz zd2MD@Q~Ak8TJD=&10G^m^s=N}x$x72bwiV$z8SA_vlE*_!zLBIVUK)s=g3-j8+c=b zS8o3ok$2xIH_@!Y!v;K4U^D4I*F#xEso}&DMqTA0e2-%3)883%T!6eFFIpk7qm6ED8d#b#DrTai&w)C0mz-u7Se?-Ue z?gtAJI36=tpZbXnso_rN;YW}?-1|x#lqQo?U*Oo)YgF!fON zSYrsaVM9c}3z2&KhR1Mq38}})YU%>ihgY7g%I^Lozu)|WUL%0z0*7~TZ6vk^`P*EBPGpP3+LgkoUv;r%vTvDL{9`gjVI;u(0T&0;rhx2(ZLxhBVm%ILN;q!Mzs z_pdXt-m&C%a49o&o{2sD-QGjRyVhy# zkKpxbL{aK(cH6@4YG2*#X<-oQGNO`bpx+|vW z($dK>8^|A5o-wenJdufXos{j^_-@Ot7ECkwW9!grt&6wzDr6-lDltb#>?-?kYjU-g zrQ>~lUnGGott@{S70g8%OH0l<@*ag^@0D#x%4_%9q-X7?F1uU}$ERntZmk-R`oA=q z#(}GX-HzB6++JLX+DuS0StT!g73&$)qw4!i`|O$Y`j?QZ)oRmICT1?xx+Al-CaS)H zPmaFoDz8c$>KsdFeU{dm8|1Py`gVNwVrYS*ZTqVbVSRizAZCEo@T<-Q&{j>zO%_L3 zZZ*$X&3(eP#k3B&NZ+qVIYX6OpVbqzeJ(@JMqpk@-&H)d$q^1nZ)jNc0VDkjIQFeE0ltC{>}J;dJ>hOi%b|Ab2YRf&8P zn|3Zm9T!+}xv-RLhdFf(T-`8oo9L73>7gsyFvRf+VlG0NqLrnFPBS*c`R2w`(Bqg) zrK_r@hV8c*5hJEYv-vnOGr^93QxZ@91B~hnf zMZs4e(y3|auGysN@=Zg~j{NL)=Ohf;rM^o@RClmPMs>?@?$yF*?eERuXh3~cYu^?FAH8f#-?8zrYI zcOq#iMqysc)Y_4rN1ORMRJHObMbRhhrftlM+5?cK3y`8G<@`;2ZB~klaCJ2tYGDl1 z)P~2{n|frooAc?exOcw{R-fT@G|vMbWH@54N5 zQ9iqzqx9B}-&Y1%IiM2zC?ay5z25|TMnsnTF2pt;X4W~Vzi?F#bfK-XDth8jD-F*7 z=!gA+*|}tVeV&2E z6Yhuz$0Mq!CKo|dvNejGaGnoZehOmZeKY>81QZ6TT>fpNwmf@Ln0B$zy$mddP2Ju&1CNdy$+q_E7Rl~Iy99?Gg_-I6PW5VM z&4;xky{aFU^fS_#HA_yn*j#Yu`crZMGr;)93fG>f>u;)>nMnVQc zaEUN=7D(#qR{)dQjV%wCiA_>!Fj^|I}Pnt(XMqseTR;B5ns{j&P=1i zqBzdXX$Igo2bRl+l)mY*5>{9lCSbAavFYQV+zxzn#2*@3=xkVae9_^uf8WM?CjF&W z*vheY(7k&Uk+fA)6ysE6WCjZ^_H!|5Fvl7#j)vVvLUtXMjS%Ctft|-8*G3I?8qdqwN#0aG_;oZF0LzrRA6GCy(_f#--SG)=9w`6f(}U|( zP<}0JII|D;`*H_0fft$@=EdO7+}j#?>4!ZhK56x{L$U2Xo^D!FQq~n#Ps@&*i9zrb zKI?b#wvWg_7P-AFr%QSUoC+*E4<w>tNmsc zd#%@mF5@qGYcDgvFt8JcXl1u1%ZFC?6}1qG6eHA3D&PbOp>*EqMMP7@%U(~} zNU)?HBFE*ko+i#Qg~itfd2rSLHzpz;MU;PlfMW3h0l^x(7uY6%vN0PD`xyKYG>W2+ ziYf3ZvVct>n1nJ?K8A&;=x?@YeRP;qMN%1(@#WmE^m5%&U)ZmDp?J>@cq6%Pa^0l8 zj-#dRm)d-zn-NmMZFx&DdHgT#bq1h@K(21(^L$QrpOqrg5zC`9Tdy`Q6LMvK@v@)r?fuvw3P}D0@#XI3ioF zS5WFg*sJn;L{s=Ll>eFPe@BC4(-D6wL&0^+g^<8@XmO>2!4^)Nr{kT}Cv0vt5dSFP z^me7?)uCn9O4pC+f314|{TOhw2}Ys94Edh6p|3yC!CF7vfd7emz}NL{lE1jYcs`PO zN}t1^Ml&?7aHv$n_U4%)vG6~|7gJQB<)&KFKWcysbDNLhUpol>zP6soAQw57>2Ob7 zi^}gslN^4*{YzcX=A$x(vR^L3BVN((@VAV5&hv&&pgtEDH#&5UP}ch7NH1_NbZ{(H z0v8%;Jq9bZ!td747T4@$`sS|ON6pvj9IVwP@2m8p8Vlj;&`7HPK0|=LdtF19zkm~n z$+@g>jEwRtjhr_f!eK(YV;j-HF0D|5 z$42c8<;?zX?k<)p%Hn>@Rey#YYY*vc+C2M>=v3yJo1Qx zG#E_fi;g5gy7K-t0H?Li*79~6E(Gdzp(d_#N7Uf3^+$tH4Q6h5KL%t3SqCi zRHWd~g#w!(JE>l{H@WHg{kUlQ8z8DtMDm2$>hjxE5h8|vmIjW10YkoaHNnqje79pY zH)RIsR>F%CtFL@nG4y0@t(&!rtz~o|7j<`iHY;PyaXNkLiN{74+4f)_14RySDw*u3 z+$Iv17}l@sjVB(K>m_+`^(Wi$H+)=|nHV$$ zEfxi74wf;w!55Gn>E^Xtmkh2$y8&)y5k*~nouj}fTTSGW-Q2Tfruy;6=~P4oWEZ|0 z$n&BC1_K|CqgwbLwD2CS{4yU6mwjQCedY*FotKO#bnQ`C=wPOCfj3^PX%PVHuDf0g z*EZIK-`qvPmCun&;A7lbq#tI5VX+Y`+N|OC zBCUbP6fKZ$!0o4e&JzcWH`lo>d>&w*N}SbstmSrWH)sIwB~qV`4i!dFYCKnjMki7c zk!5u3G%2t}KDc@2kn9w*?fd#8IZn>dkjE;DXA`1;lT;?1lnHi70ncTIr<)pl+n}7! zEsEBD!?^9xdsqpt@}M7_jyVDidmi z1Z&=$+Kg@5bbvIZdLovh!=QeZpkAPOAz=ftf%}A-b`2DGctv%NjhZ0DacSJ@ zFO2p<7k(iY?I zH|DuHtLG+N!y8K1scB)St&P0Gtp#+{$`&p#>A;R0wYe)A*P9J~9jb#1XM9=tbVu;& zAWCUKk3(_Hnt?)V{>ni0<+~sX{^vUie)LvhCbFc$Kdl-Bx9(ER)CB|c>0LPX6Hp{Nw|glBr>dR<{pM!d?W>=RB`MM&MY*9cxJ$SMxCUDZD0 z53hRxD*HZK(dw|Nz?ih4$}N2r?X$hKK;|`A<9U|Fz?PC&xmrhOD7x!UM%Fx)vSKY0x8w`6p2tUR<> z`SG$OR{{2rHxzK|xmKA4rtU4J+WlNhkoduF@l802;^myQ}_I`^C03K{$ zP*b%0@&G>}&rQxbOjKK0UB6(4M2Fc`Xq36;netyH%pekHz4l~r_w{I_JxhDE4(w1I zc!hg=`yfY7fKS0zC*nE{Y;F+R1j^)dM(%T_PT5EJm)J2T#GrL~oe4qS@C$J$aN?G- za^l<dV zRtdL24){800LH~*?{#EhJF+@BS^p;VIyVXtxC0`i{=6?Q$S`a%&^Z7e1DECV{2Mnh z(MBC|$Yba_=I8>;ZyKm>w5%FQd-`9E^0$Klx*ci=}#a-WHDZ0*7K*%i)H83&9zG9b$ zfc)s5XXjn?gvg6Z%UpOo53KB`%O}veijh(-TMWJPv%g|mC?j$%Y0$BE@rHPQ$COiC z;^)^X2!Zq4vA8(Vcl20e2T-sE@EWjs(_kp_dq9%Z>m&xf*f^%rAACSA!#%W}y6q0{ zpCmVth;&f#LwQ#FbY%aYr?|jvcL$5gS~_ktTsV*}_QO@a)r2M0-97V&d9`nz~b{zaDK)R>-r* z$w$huJjlo(prkZ$R&So~2kAhIG8X2^qTE%hnCNQta=0A8hUwu1OM)V%d{17aw!}9X z`xjOJVxD}8T2uw?6X)9-jc`L~#C2}&E!f2SH$#3_AHU|6e@=^s6;CTH{IvJM1A;0z z_4txA6S!J@F&DBAVmBhEtEROFLnY{#IDOxpQ`KyR^1CIVRR}gHX{7Sc;6oxR`1rU$ z6wP1%F#RsmE{6MfX=@YP-pT0f0%)JrPtVmWxvYdStaj)6 zS*Z5Ch<`}1c+4)LDv>P$NhtbW9-A3>cV?k?hjQK?TY46keY*8^DtB{b|Aban6IPM% z1=6#4MS{HQ`71aPfN>3YmLGtn?n7@+9w(5QJZvgkq9Z}^2}6&e@dIHKfNH-SkK-D4-lxbF5lu z*f5Ev9eGffrT0Y)U;%{Q+%;DN!A}BCZ)wi?-bAb2T<$aGfSZCQAQNo^64umzlI)TI zy>xKEt;XX#^6XEaIfv%{H|1}GUdi|p71S}&q#H>Ay&5>LX&36(4Egol%TKbv5^-Z9-4nsgN0SZW&$jF%lEpp;t z8YQlZ%Uk(z#kar1ZI*YehZk&42c-BRuENwn`jSmry{5nE)DRd056SQib~=sYU{b)3 z3aS@{PF5-ox@m>y4W1)rPt>{n;%Q_j6O&>5*&>ESCf90083qoq<%e?AsI$j)|CznY zS$@F9Od1f#Aln;-kXNi`2G{?uDxg-rLD5oo92$ZFIYueJ0+JWh)t=A>Ube+cRD8V; zGbNJNKxmzO=FKoKl4Q&zN511QK@@57M|G#lfs^8+?L@<9hHoU)pdtbXk)~rbjlt{C}S{Q!Xi0$ah^zP{Ufz;eHi8y z_!yOFja-6NcwR``E6nA^cFL|#<~5uiZl{UL9Nr;)^8cG8oTmUfiw6hgJ{*TSR=lyT zRTO)ZD~%=AviX@bE9j8CtkmV;pd5k93C{Q~@Kzkw?NsY+YoxX1b$2Ae_xptd9n`G2 z?or@`QFztFvKydrbP#0;b6bov0L`1{v`K869|2eL<<{&I1qomFbr{)zTm#AvARr>c zckcO5KCJ_Pyvk}#4&_qrTI=}yiv>8{3FbaHkn}*vle?MQuhWC6bwp;a=Ki?X`P0!i zJ|ic^PXXk}Kkv&Vd)01N@7e&H;&~*fLKw^EFhR&;0V32WFPhd`d~TK&Wm?es@Y+_+ zUasDk9df)+nCH>&0MZdzohrPd*lU6o<||g`Y)3XnDXg+Xl@xV0OZDySabpE@jBT7e zClhOv_2!8VmNn!&H{|2kM~TtO+Dhu&KE04OU?T+t5)rd}OpG^dD|APS6h0P=T|m>X zF8Z5zFUQV+DYP5W9b>D;ds3qn@Sp{iMY}s?KjpC&j+vsK)~1v5Dt_srzi|x2As;@! zN!wOIzl1(yE|6auG`Sw(svXagbN2bz4_vSqcC2L3t--<}bL|<(^*e`76c3 zBr>ZH0HCtpuQYsumW%^Gj>}95VWZ3sTHQ9p9Q_Kg6RWN*UAH+3e4c}G3E<(uK$%Ze za*Wc?y;i^IfxV(UqTA6Y_er;RttdB(9tiP#lACsr9U6FalXspfF5j|B5rheKOXxL* z4Si%_V-C5)0zC&H(?=IW52s3g4eJv|erqln-QcrnO~%cy9?zO1WE}}NAVEzyiecuF z?CEj$4$uF}WL?amB=1el%bgoJWk3GR`08vPt5B!u@oyo)yc$K(SI-NRuYTR{AIh&d zi+lNXua!(F+m9-Xwko&67J@Bdk|t@&k%QJ$-_y>i6)(Gt;r$(@EpB-LivjgP`us$q zVl09*K`h$18&+repI7uC(W{xAjnmZ%c$2qktZ;6yH_$WRLHiLi-~o{wSp; zAP{t1Y-P{6Aee1GRa7OGfLFc~sbUFm;iHqhiWKhky0L2mYMah$HEWKD$rJw|SFry^*va zux>cRBGxh3P=~N4w~&=pRNc_*oUC}F2K?6A^V278hieQVK`J={5EOyIfnO=8K@T;a!Hr(p$ z(zF;eoUqfZuue{QFVxF3NYq?+F~gN-`3s8 zkQ?Vs?+%lFCS^f5ya;IiYo@qL;d^k+X;Y+a{7eq;{n$srDssX z#7F>Lfcdq!8>{&_wvaZ4)+0oQ&cP#Qe~T}%U@U>3bh6w$F(u_NAr@{(w08_hm%#0K zwc(;jRiszcBp1^A%htOPy4-`1G4jp;yERDIaKcwM;R-P)l&{5)y^hG~vW-WQOP=&k zQE7~OTz<_N>8j}t4GkOA$w|)Su(%{1uL5ym09la&j99E#bay0+fJM{l;2Dt`niMKr zC?NB-`33;81$Q;I^ot^!EB$a^7f1vP#vtd^DqREZ+j`sI2FsN+EEjET> zb+bMv);_1BtQVYKDWF;|Z4AgbSDOWblu#NIM`Ic&Hm=5iMQQ9@4u~+??cuq|i$(W+ z#3(N6Wt{wx=&2){L5WaqdRe_}6cl!-PZ$aUo5*1orD=xl8|v=}3F;0`>!7O(9E~v` z)OQ|Y#z{&5ETUiX9JXE2d1z=CBskN%5^*)? zqUVD-G(tr*t4sQ&irUFyyCe<5pI=H=ST_Hfi|Wg zpnm!&JVQprCZ51HEAyBEu4o|$>RxBKQayEU)79?wE+zav<=W~iY+^1afFW#KTIn?C zIdP*+h)+!iRSUHn8YfF|EWZ@h&$Ijdog)?{?0Esh4Ap0aXoPIg27nxn6i zcnL~tmU$}fT%KR&m9LBY= zGRM3L+qh={#3)EcSsyz3-9jNhF9cRR4BqSpx_R3FR0f`jYKC+~8d`0&J^c!zCBT2P z#xtl2f07O5X>dI|61y6k1y*KYuK16>&f#e>!rO+pg4ssKbutJ=-O`s~v}*v@u@(g5 zz$sbD&%MGR)ij5=XnR?@?AePQ?}KLpC7|FC?}DJF zIe_dU0V?a{u)_#BSqBAB8XKiVVOdSv-&Yf1 zdWTxv3=F)uLd%Y2Y_g%T81M{W$0-{?7~N6U+7V{eG-T{@ua61n!;w=8avg z@WJ2s;UbH+Ai?BmGifVvMory{+>v1jdT}cb1bcbs*X1kh&lE3&JtU0%6dh7#FOKDB ze1~}-t!zyk)fE_lRJ9y_i|@RN32>UUK~US~RF4Yd&|`a`Xh;xwLJli)_h~m*#lRJ) z?Sr$(cHmO}18hNPKhb#AOQh$n2R$iu&Tt+}QMDYX%ZEnsLUKVV1&k>>KD_~|?OdOu zSy73Ft2a=9yp-1}8f{;29NrDU%+*`LL1`CYlh77Z76b5%PnFW01hM~@d=d&D)xB_c z=Hg6wAvYwsjvI-BzfpMfycHGNkH&|QbMGbLdF}_005CO>TU;O~hcC2t+#*yeqXp8L z>nk<)4-~#i9Z%2%-R^ZX$|f}hkcqImB~ffDA#IUb_x#fKe}FA%pT~^1sRg||e_HA} zgFz6T7afzi0k4(viCBNryb=#!M<`7vv9VvITa`An%fuECC)f#)gk8LOz&sf3w3Mwq zEmip#5m@pDXa9ClRtjd9KAf(CxkTXX6sl(<*U_=AQEiHVD zMJf9x(tdP(lvL1}2kq#S$38{+A2I}huueBa<%TxYa0c0IaFx^9e<1^c{lNVW(vRw~ zC|jGID#ATk9{<1Oim+&1H>ksJqEK&ei{2u4eSrR`==`}z*z2}|)LIKf%tdu9489AL z2PwRvdkcW4+>Uw?`2f-R?vQE}mI$shORvbwBEV-ED?k9$CMqF_FpAeQTakDTnu0CGa??3tF;cTH*{2vBWoh;#Rot{ zojPtVkSMD?dz9?9&Pm~;uH?2gA^~t-*N6f;*Fcv~H9uLyYJL`wwp&#KeX2elH%-m- z?MLmGq-f%3tXR1?hesrzf>6f@xO{3;Jl9Fk@vgT*Y5=eiacF?qPx-4irz;6q*z42t zcN#7Ri4y9JRg`%v0SAUiVyvx~WQ^oQy1#L+Q&6L7kb&1DzgS#yqO78y+5iRUK+dnZ z@<~8;|MIj>aUu8Ps7(yeItpWHIJo!k+r|0N6m9y-l7ci5>A=x*ktY}Sh4M4BmV=i{ zE)2j$(~4lP-3s!{1)+pT3!aB1A*Y)gJIG#Km%r?bPmFLus9#s%L5r_B%X>1fr?1^= z?#(`^(nCxOmwaEDC}E*F7N&EspDtAZEP7AS_eXQ%>70icX4n--_2E%Kam#qN|LxuxC`G=$bt-OdbsrTJ zOJ%wb0;^M7?%|(${gSJ;i`vT1PR79|6Vt&2@`%09ab}{{BmQ{V8 zTN5(o#6j*movHwz8F&VN;T*b*l07p{Nb|1l{VS%gk+W+1Eqepmd#?)X&s+bd@jorI*wPIn7t~eE8AivqQu{PU=_faK zUxU=d26qZQhY+)BvJkm>`0tWeR$ zTmwGXvq3z}#?0sD>8(gI85f+2_jd{OLBj9oTtYBIOvH7#_2>HidD5X z!4fe6!NT@#4;qR0op5F&Ue5DftBSuBXv4#EAHs5-xk8L(pjgiB!6%n3DS zZ8pMZQtvV8-ZvP+KN=Ky>KzHdQ-7T{2bZ2>IdP)G{RY16G0t_k=QpXq7$Hv8oazaG zvv(We*galfSXc*diR0rFnIp=yD6=T-U)l;Ipm!8M6+#aO-1VFYz_m!eg-KPmIfoK( zHGT&bSqcUluv9a+B8B+IoKr*_bvMkVDkZ5Z_pUZPwFn-XAOuiFKTPIR|T3z`d#6SpxAz+3wV)oKWx-hAZ zE3qnjqw033I{#>h{FVP`0%OE!8^>bngwZs8dy=^B)pK0R2-vtB!Tjbg1hI_~@;I!{yP1j*gEdy>!kHtqPndTci| zod-T+5&h;dbt#_rBD=CN)Ce;yrBdv&7T+HsnNMH@ipcw(+7r?D>Aw2{@A=M<*odgv zYLgvsth)4H9nWWQEh`=M+D}MO_t~B~6^e){DIJK#>MIx%wUN~08vj0--!hq#Z9R8+ z@q1?o8(jW!iWB$&^;-SnbcOSt8I!e#q+l_r1zZy@C54oa`Mbyp$HY-a&092&#;%8y z53CbgqE{Xp18tV^%4`7f{&^Ycl*P*8uj8+w$49^K-kPhYiH6oV5%h{A&gZ=~eEKyj zP%ySHF`R$yLYq;IF-E&|kLHE1HI^aqW8xr;$p|e_&qHoN;oR$(HatZ*hp+wsdPUw` zts*(Uy{^Aj0`N&D-`_21mn^y+tPN(h+DD`aMcmhVH`=9JWoKwj#*B2MWEpOqx~cWf zAvY$=l25y6pPFp-WCcDpx~Kx~-^uoi9j}`HJJUU>*KJHgH^= znAZkth_ZJ1dTBo-2;uRpU}@3?&}ooVe!70oMoI6f_8gdSF(-f9w^ua3FF5@2VvK4@ zKgnwaxQ(c;tQrU3xbU77Uhu0F9tT=5`~3Q=Q_+ap<4VUu75D9z|2&kV`-T)|8>k?A^tp2+ zYH~}r3X(&UUYn`Tyt_YUuU+yot5Nb1sJuW;?MZ80SNCX4RT|BP1?S|g5l^YL&DXz` z5Cf2T#fG5JxXEc|$??`yzwt}EOgA$5`!058a}4n!OLW9!)^pih?v-QUu3Tc@nbI5m zB4^QkTXwL=T7^YY#oDy3@*KhuI#CSjPx?TC=GyV82^-o%?lKprjl&t64iy6;xD|bk zm-{~K$UScjT$0^9{t7?-4*m7W^1oellmIrC>BQ&!EN`45x5Fvw4j0Cf>x81Rwu|~+mpbAKBc=M8kNyJp{eh~jv?<$jpt%19 zKKpG$856p;M`UCqX@IYYg*hQ2wZ~6ci_X7la^QNz#}nT_b9Z_5w0qgGn!uANPj|VJ zO^N!;&xspKKSy^neyX&Ygm0V)ukUTXg?L|eLv740+4Utl+zV~$`|}07n3U~xSP2&< za{gMcP_Pkt7ZC7xIk1G0Ie&Iw?V7|=3WFDQxUIl$H3+(UFYuR^fr|!ea(KMa0G09;`)86r4zc!C{;<5LIJGs1i7g(c{Or9twnIx0CsUQCOP32@#2U~*I zFN7oChz=R<{RT4skg_>-mW|OuZc(GUg4s!L?Wf-4kc+G7)Y>d%#$r(4xa8FWy-)Dd z>lu$Qx~`Ao$w4qLXBci8L!viGSfe@xp!nCb&MPUa2udz=Yp9%GG{$AX^m5(#rI&N& z=Hd2zG48un^pv(vdZ#ySG; zf=cfDw#aMpHz&8_rV%FHEh9S#+xMZOe+WiX@UN=XGt zP=W7M6z}cUl*j6mhv;!hZ}}2xzn0T`j=>T$DTITbo{A~B_u#GUf=qtQ#pO{Gxaz}g z?0Y9S5gtY2KdgzwWb<3Mx!3KkMqB~fglxv^02Fh7xSEidT<&_ko7!tV%| z0{s1cDRWUhN!Tl|@36^d#js-O4Yy%n9n2+p3rgt+$^yo7nUgN}8l~S z@pD!}t?EbDD~-oXshW4oHjd+6Sw@4h`^jXO&_vbKwC0%)Rwi!_T>6a{izVDj9c@Tk zw`T+W5ZeN-$Ho7VQUxC~fU4$wi)EX8+5A@GM_<>FhX9%7pcmBUqNT9WM!GHyY#B!6MDJCVwyF2ChWB}%2ME?%W zFbBEmDJ>5|r2YbT6gU4_dOQ_V07`goJ#6{&TS(Nu=0R@f@E8)%PZJcF{vd_xLH?&} z>Y;}ZoXIj|A|wob8~4${Xn~>r)6bvA|B_7#cMxCVr6T1b{PU!ZR3EenVkGAG z?@UPXfayX_7|JsJ`48<9C~Ne?31FJ@?IjD!y1My0PUsJwV}6O{8s!}P{G1kSHEiN* zQwLC1qzhEWeC*j1`r*^3k$**z`dvC6{MP*K|HIT*hE@4|T^~US0V$LPS8i zq!B@+L%Lg}r5mKXySux)q`Tt~@1Q^b&-;PvvX1ATxo7rXd+k_Fr0H_AR3rbrx3TAY z_ZM21wp$(lEk%~>*u3MA;HJ6NJ6?eLjK5ExlL4L9Bzcu5 z4(A{9p93W|oB`ELOon4PY3Z3e|NDpT(2v^Vn?pj(D&1V3x$9lsR-9H$Xb?ubCd|#@ z_Db=y3gcT?#P_cmL&S@Xm;0`fL;tQZOBEbOmxUS>8l}AdTMJT+102osr`|*@U!4lz z7F!xTJ0C$d=%0M*tW0X2=*SsyaJ=L30hS{g2mjxpQ9$LaH0cM!esphN;iG|94FtLV z*~ZP#S5dvPa;hF9Kjpxrz2vgA$H(tpPEvcU$2aHDw_v0nFDoj<1oRo#HR_Z$w7&dr z^`VE~5&ELJkVr@>&;Fh1RFY6J09g>=aK-=C0>A)?yQ$gP*6H>q?Ck8|Z8-!=s8uNE zqzB|Ik6qDRLKn$!m_8@}J9CCV)#s<;%4@**c6QhLCyV!orT_b@@NgNSGzB5*7p-km z2>SZ^j7&^#m6Rw!KzoWcd8_lw+q5Squ{oZ$3X6aKhHM2R?2HiZuN{<49~os~v^=%@ zcg_q2AEUp-5T=ALu{sIWl6hRL@>oqxEm}=wldb?-@2SY8o${qfgf#RG{THb!@D2V& zmV4Nj`~DXs;A|Eq3+pSf4`|l-0Prg!(%v%E1j$#kOSMKayR07zS1k#`7&VObL;##Zo*8Z z=pcQAc~NCPV@J^;6#=Ki(<8+0uI_%%Fi$?!YrB=|FW0R-B`ZigB(I;iH&>d|oD%)g z#asfA7Hfg%&}0#haJGCxb)&EzJ~So*)=C}|h@m3`>16nzM4`ienKlaY=9W2RO(IjU z?Jw2i3AS%;BEi@i58+n>q?hZ2tY-qyM*S^L8QQ%k6h*dY@Mu#Hd{68j$2QiR4qA3AyZvcGz9~`+$Pa@#+_P z7zpp2M$y-K@hWbfocu;2j2~t$GmjwVMWyWwuKUgIWSL_X(5BS_NwEWdV}3 zn$^!_nT}endnZjF)T4?j%bOzy7d(Ay{Y9OC$;+K|^>zk$2hJ7e^15^JaQMetyI;!6 z`JI&)OBPP2S6D!<%|JuIaB5VAa|eJ5{OpMP%N;4Om#xDK&mPs+>Kyf0SK*`Q%id=$ z+UR!Ay~Y7r7OEFoqbIqRJhU)YQ4PMJwXpmc^J1r#lS{kRQDV5KQ{vsNd7s90gQzoP zsu-&E?c%^|aIyhb7#240Y%AuYont@TV@*_98UaUOOqO;Hg4rY%-5Sjt^G*IbMj$ey zdlc7ezTWropBX-#!thJ)>hAW8Nar#(F$sweN3Ire@Ijzv$DE zv5tN3gn&5@ZQTr%%WfArvfxUDPIha58@W*5G(^1j_zXzc+L;W@iit~&S0^pn9$;fM z(+@mjWSAU1>)2zgYg{&>RXqv~L9nr~bPFtxDEgo(N~uq;>iz52r$A?rXEihQ(}sn8 z9p8J_Mn_NI%yZ!C1I~M3P2){9e6GL(Ik`tY?;Mynjm^n5g*f{VGxiGH2yGO5g2^DYn}mFOEPwARP+GF%#+F}3;&*IJOb&%9W|%zFRiLf; zon?sVEij9;D(5Mx&hUSxo@+SGwpI$`)h*MI#+rK$H)w!7y)n{S9fx^+vEN>Nl&Qs4yTP8*ZU*v6%O;U^+P zU2Y=uVr#UOSU1rX%XRMx6+CF~q)X7=qOn_Os7}N-O@#Q(;f|D!{ahDGG`j_D9&P_4 zh+p?>m4O`IG{lv<|-m#r- zHJlqqEEy0O3YJJ*dC)dc?<=FC;B|G7*FMp|qiyzuY;3Xo01fhn7E7mp#QuQ}XsH46 zW;z|eBET)}$hL|?ONvJ3z|G%2 zJE`W@`4^*__JUci*DWv7GV~yj8=mskcQn|o6B)GbS_%pQ!3|R$&c0G_Qe-}L?zM;okrp~X@ajRi4MPBfw%W497XnK0)O=A^CA(%Exha-K||6vIJc}R zyS6q87zlTnNqQs#oZGpHs`h+NyWM`wot@1ax1xOZNUZg#qIJ4&XFHH=1sI6I)~ffo z#NwMBtOZEV&&t{hV)X5?^P9V)LD%nr4F27~H|;3ViTYO10T=i(RBY*Bmgu0Kg_wRo zuRiTSRD^7EeGmTZp5M(elnML?)d%%_(p5^x$Z4DVi-`CWbx+7zOMKy7W~-(1Z{;`W zkqR^Gctt_!uUm03`U8cgtVs|A_N(~~^^?Co8z2i`yV+m0$Z%|18nSf5z^=g z{O(GU%~%$dX3b`{FUH1R7Ym8Llj{wzz@G}-U!gv#ugN|`8*lIHD;rseC)%fHWMLC@ z5hM{hc)K-M@I_gGb7uByI22mZDgYk@0|7KI0*wSxpvg>yDM?+BpKC}+y&VP4)zuS- zn@fFdirFANo^|^t^z{#}Z=(e+q^3NVe<;4!g@}ns3R)W0%p49uhCqyb{q17XUY*)Z zGAYYiN{dWbxDL8b5RlY>02%YiDcHN>b2zR$bZB3h2DH>@mYLzFfM8`hbf53+9F9f( z#iOX(3^6>4I5X9CQhREt_n3T#i^HS9@yqWJYTVs`Isn07`UXSmz`#I8vyQf>!NGr= zXl!IX^jvo>=i(pOkquKK4QobrD-LC{43XbDKYJSyg8?kf0KPgBV5OQ){TNnuh+SbJ zd76!gjjk6l6KzI%PyK&{B!v0ic)IwLj3K zoY`9_J5+tb`YsK_@9^42r78q@f37$`r0f1Jsu9iU1Bbh7bzVdCb7#M z3cqS~mAJL1*+O&Teb6$XZ2=^k%(^|U7qiYbZ4uz(lefDCZv;@HTjDz+ogJxJSvX)J z5V!JP>`wz~2P6WG5TLj|bvMaxd~ZY?fQ+&{n}Py|irnPprpd@QOxWn|4rokM?n%&< zW9L}4YNNsl#6UtqWAfS4EI$mGiR!aI|4}mN zmDoQ+hTfB*^&}@LE;rv-O&%bu!mQ5Mih(M$9kI6Si0}K!UJdFlreMC9kfn~8x`r-B zS7<-E<1#Pn@LRf;Q&CXg<9_OmQEh+KV%b@dUv!phjl*M!kk@+_PEY^38F*5a+apR| zXv_2X`sZ0zN&1wOExgS&;RoIc31LXdHXD^`WeRpCrkb}$b4dP%Hkd$PQrZr5#1^mb zaTIO$b8Ui`J7WU?<^$NNW7TECqP<6JZ>L~0{Cm>z7`%ntgC|{oyf6Hq`(LE}UBL z$bUZFNKMbd=eL7MB{X`3ePMVwnz<7u9zq4TbBVRzKG^YDcDwMPh*hrnkW60x@2%YNys$Cd4z_vN&`g^9IlE$~5Bg>-Y>B!!lr3AeJ96o6eAVD|8=XDW`H$CNeEB7s}m znY$mThqo@6tv@I_tceJYI;^SKsIA1?g{Wel7&RNnSRALn+k<)VjcD>zcxy-Yoa*?zCo5Z9*d~0v-z}Hk-zr3Mm#qS7vcWGI*GRyEo!`PCa7!P4An*;Quus)PS)ZgEEDU|_Ws=x)+fdSR|`u*}*O`w`N#b$=+Eg%c})XT&#v6G@6P_qLVE(j!4%xjV| z0Ao9dfE!`)z6KK@^$iAiox2j$p+Z~RGNXAI+?bCKDEpj|?Y|LIk6OR+~fB;dDDGKo7%^;v1u{qkTn(MXKU0fpOv8l^jPvj*9$>90?06_|b^ zc3+y2!B>-qb4|^DS~&Hay4+(2@~`p02AL3Py#V7MX=7MkxDd`51~!98nal^dDKg)6 z$?%Xazy7mY9$`g*jG9iIoM#CM6L58_;^za@8w{H;aO>>CGjtH9?ic zrw0QPGe9{Q5d;mZQ(H)!HmX)#n;`jE>~a=os8<+7?1xX1f>4j`2dwl>oi2yVLa|zE z0f?9LT#O1PF8`1eSw}yDrJIc8^-0;-6#viC6wJjp!{|gCC=QC|L@UVEON{}?Z+EbF z6*5=&#lRrBVgXP<03J7kR|k?RnH2*aGf&M15`H`>)$~qre?BAD_G!7?U2v_KZ_ee4 z)9cn?IwK+&o4wE#8$eYdS|wsRb<)rWuE==)hDr1pVVbOMOSI1A*HPcY3lmg%Ox<$p ziAXFE2cfEQ6t;dRfu#;`en=5&Ps2R091#-fa>$Mu0{r(&ggCgkh6Ktc0}K$A=s2Cx znuurtD-88`Le?46wN-C>7RpZ`4#4ZoECE6OLkvZ*x5qlcH8ZQzoTq%W8b#dFGa_V? zP@2l;a%V`GQO65cFc3r~5ML`o`oQZ%pUv3a9E8~}YZp3xH~9-S)E`*N`&9;HN0IxJy>&QxU!9eMKy4l|IjDd{~_I>u(qS9iY(o|2;l{4885YMHBD?ESxyaj9)fG|QO zwGZ_2``2Fqe)J0SOqlp>U@zSH;hm)+H+aayg9A0MV?fq`xTa;Kg}{_Ph>>X`(aTxI zWUx>!Tg1=-Ze)Z-=Ve4oZ!00(3-X`D88YGH(t}-IV&opVrC~EgBN4BuXoZZONJU7| zLFCxdHB@vg4#K`bNn_(_1oDN21&2T~W@Ze?()N16BWSz-{A&(d6!W5dp*a_<^$u6$5E;JaV*={^o`A(1Yc#`i3yX48eHg zfDZtHubY3E@EX2y)51iC=*jBD`OOazQqCFW#I}jIv{=pE%~GjRmWna4IDksLUBG$u zu)V*){JIsrK6_n~&&&hs|1sC&sU`#lfGK|+)!Ur-Uk*bAMH;A0++GN@2smE+k9#&u zE9=Jv6g3TaM`8c_m$a0WSYercZyZGbZ(W@Mmv{FV*=5@&i5P6pi&fOG{wAnJ0z*J9 zhoSM#XPHdv^FQ2WnEy-X*BTJ7^5by$eRH-d8s76+JIVUbfpCZiY8{^@c23N9CQSY@ zPa?rg;DK9282Nq#1R(2t{+xBd_?PA0?u#kiV03Mc13do!Fgp?1i+)^WKamyzk^gcJ z+wTDfuT&4^e|BU0KSVpMD~4zgP>~Bb_;7KPRI$Ir7rLy;TM>~@$79o70|O)fk^rYT zj-0Exc=)OVn*TP!S|VFvrIWbw(<##blHk7_Y#YB6glvq0IkS`@dBH zqz+DiY}cOtG0tiEJNkd8i&FG4$V34Y=O=e{Nd0F!Nl9~ZifS(yO|FeWZQ%C5tb(CO znVw_1YR}(I{GRm#Q05J{=kIRJdTsx=jj>hGRuLp&pFMk1Tn9{A zFz^cfTM2r$1H8XtZw@xdBmMIIFUj&9FSGSs(8~YEcKv$iA=WDa$Z<(ZPcd?szo9z% zmXe&DN9BU1JLW5?|K&$WO}w@|y}ABJl#%94B@8i2Ca@!c!1{krC>AIu5d(6({|K|c z8#q?>`uS7iI|rnO`{ghHJ3?ure`%K&4&VPmhVOBhGg`M>DU~O*NDl|Mg&3ZO6U$td&u+q5aRXWCG;o_UkgdsS;u&m;( z`AUwtxjEJzGBPrYwUHNmVA%>R{k*X$Y8R#;Nuu{eoPu7x>ibl*$}QYPTL9rbX(BNb z0mS@z?5pvOacUwNI2F-g+mxsy;yM0i9jU{CMcvSf_51l#E~O9fH9W2hX`NZI8B1}M zk09AwxLpJNo`DhRiDV9S51F9hpOqHpyH{{Vqb)5$blGMmCiyJ5H`jBM%j2`N_i?oMf@^^sDQk*gK)YKFXB_(B7pYcuo^e*9UXhK9FP<8L&C?K=30YI`; zSVcv}vwT|Na3*gmZIZHia!@&6(h#UAx!mRt%-AVxt(F$}N0gs=PAVxm1b9*F8t6aK zm2mt``Bo^~xDNI=u!zw-_JW$K0UoDb4n{y_1`)ifDxe=yUoLo^0xo*nC#DVLKbO)W zpsw){UJ zu+bfGPl49?s+BDd%K~B>Uv5E9+|5nv;J6e9&`lAhk3y<<{+wPTp!T3O(5-EF0~FpF zPtIZ(Sy*zF>cJytOQ`@|ygxW|q>?m2JZCjew2V4Z-_kHz#yl-Pu<`moL*9hQ(JO;ucaL7ixYh zQeSq`lUtblZjgx6`uKUn%}uYvS5Lf-)KY-D!zaJ8VnSF2B~tP zDI5411t<6VZlMDAiT7K8F^K``vA{ijkXq0%@Z|$2>Z)UOVl-W7@UO^s(*CMbFlmR^ z(?K_D&Os`!vQTVAe0TGeOg(;VF&Hp`x@*2#SrK}l^>nX(O~2UJq72j7d$&{UctMmf z`|bQ7Kq+5M5zi>fR3j$|d7!s51|+n9|Mt49x_r7pb+;QfSY$t{e{(#`FmC8cq+v2! z{w0_7L;<ec6Xv*zm*4lGVCMU({3Qbtsd`Y{73JjQGNFJ-23)7RU-5oo zXmH#$ZxY+t^;pyyp^#@Bs|z`h*3(jNRAeWx%$D@=>>PL~uNteEb=~xuIc{>PXL34h zdV1k}p~;!?A<1)hH}7d>t=%0dQ2o+2)PG7tL$j=JEhzZt7ilU45)%_s<#c4p7PRaB zK}*58>ud$e*Sd9t_WZe*{41&EfrV##JZ0ED!lvE^^9%j`C`uE0!t#~_hdm%Gm0DG` z%ObD(>z+iE_(e-yYOwpY6xze7VY)|IPVs21O@Ew=!)*M$$XHhw7F8NG0EZ0*{+zf8b@4X2bF=3=3i5a)1u7i})~7AuPLlk_ zRnBjRXre(xh<+j-vbv%xo6BTf{r&ls=UEGguH=9cd`L>)lRO|n5fRkq*ikRJ*if>+ z;xe+bde!D)f_xajbZA5`V2K$}DIqz_vI0pD7*$MMa8`*QCDuS1{L1MQb8K~W)AVpd z^Gv>d<092i``Sh zQfD?lPJf&R0(>GsgL1;T>KSBdZO!{EDIXpZ&u#H^(G}`k9{e5@n~jcQc2IU0uEpTS zh)GEmoZmshH5U8l9(3uvE+2y+Fkx0aUCz$lQIPtDDe6l;I>PL1R38ts^~-7aYoZ_V=lC;2{c33qU#_y+>SJ9PI_} zlkqHb@FzuJf<`VjAz`2pop7r1g)vR-cz8Pp$CmkdLYs4&uD&i2bz_2-18*|E`mblt^Y^MBPC`;6F##c=j;=0BjAYR7 zw9jqr9fF20AB>Ip+VP8JL44t*A^>w43xM7O-Osui9HuOsoX=-|= zWvmYw=u3)8iHiye!2lS9hu>=@bAX06>5OG5==yJVW#k!Sy}w+7yr!{R0+@fHYYPA}J}!xO=7Z;gi&HXCOk2BOJ|tc_Rl_a>~r5 z+I-iQp(7S5`^^rI!15PupU_8GN*FD65ds%dz-0y$iLlPHXB@(jUpGR1rVFg}pR&$| zmSt}VJ?5JRBY_9jcmB}e_ZnbUgRy7IPMdofc(w9%e|G=obX~(Uop10@)VN)mP5Drs znVr4Gf9lL1oWLC%%;7@QcYp*DPIAF8YhXfo-<^H=wUb``S)F^87dgaDfx3ALUHGUY zz|Rnh2&z0Oa`{Eih5e#5=Wh;&b0}UUdJ?8R(lKvl{^Sp-RnEjrN)BqSD=vg4zcqA$?a`F7k=tU@8+!bM1v zzfAV5<_7(Q@?9I7tGIFX<-@)^wrDf!fBLcdFf@TtN zV`yOjP6A8vU6RYAsoM)8k#}!fM@BI2q5H0?#K_SsR#JhOWi`mordbnSn!rU+)~9{c z40UsPgu~?E#pp!}36G2<1&2t@b>;_8<$=Li47W2i95PG z%B)ImzVv&k=9}u1aZ{&rluiHa(ai1m19kxhVqgXNq>{MviwA&viEEtBJF;IWa)Bjn zA!F2?KrTBN(oBt-;?Q#SB=Zf@J{)ScGwCr>oz$>2BgM0?N`Vj3=a?_mAPBFEWX?Zq6yn=uOUsbs1r@S zvl1$<0Jy8yJH60-72sW3T54VoEOnd6yVXo$mx*cr8hTICsM_fG+mh@2 zt`y$&wpf1CT|E?hPqNm%%i;NXM?XG?#mW?-$lJGyT#4J7YM`cSbD@+69DlF4GssYP zB_`0lGy9yGnQnAj2V-qTpNMz(Tr=^sq(c}H)o3w=PpMEnUuk`@UF(vT)$DFbm6*xU zt79$!6bNB6sEb(2?YY_j!yJ8hy}MOv9l5(XQIDU|9}S1Eh977R*qOI)-?p?8_AY7$ z4e_Ml&7N(~BNa;7D{jn9fz7!*k24!5s)D$U9~3GH4pyu0h!%@7}H2beZT>(-(e#g@p}p{mKh-{RH8?NV2g) zh+3to&fsEAW|>_yf8!vySVmADpC4l6Em2y|h%8q92dzmimx$1deUN-@aA{C!FsxRc zUaY2ihE-t?IGzPxn^4o3ZcZA@fY5_GKHOU127cL36UZGDRFX`A&T<`8)b=0#y zV`oQoN!-0QQcievQWxilROspHanu}(3JK?9)ipBm2lJ{XzB-PRd3cAtk~B`xF-+yB z@N!0Sjh^ARd!vvNLc&9jOmQ{MeWCwp@4FK0tL6qp<@`natz|(3zSGo!<;?jT_!Rp^ zCdQJX8{EQ*ghhGI(k<(9W>{SomFh~5n1otUNhuRY#9nbK*`HC~c~dgsy|?32?#}RN zLtwrmqur+V?(G+bDM9o~;ZGPoyqcC)_FO{Ag|^S18q0rqdH=_0 zfaF6ymu07!IETq%+tvIIbfPG^-cS&okDApUf*;nNd|Em{tt|>tj}!PXfG&`Og4yqf zVrO2$LxHmhH5T~r!HFKVaaIvQ?^9&7Z_1v0_mcn>6;;l!;LdjfQ6m}hKy>;^?8BglrD3dS?Qk(7chH@C zbd|{ONPH>t`3^eO`#XP-zQ}8*Iob%uAD^K=7_08RTpI1~>TwAPr>CLLFqZ+G~U(`EX2o)~W zv-Y3>*Ic3~k$0tyayNa;;R4D+OzJCknudnZPO$of7u_0EXDz>3io9Bss&ZJ%kzoe{ z$K{Dxs4OfTt-IBw=tM+8UUp|jN|W{9ZT4n#CU#1-!JIzp+vH66<*pPmnJ#OAInB5W z>*Mfl!;PlNL2OY`QO=@!w}JC*U1Dm{4$({F)h_@WNAp@RkL=&`0-tKg=g^C4q?MTc zbsCyls+Fz}kK&rii7ckn!`+ZCY(37Zmra@8!4urT1bhz;R;J1Iw^|-; zfgklx!89c7Kzq;x<$nKP3t)Xb| zV4p)FHkgzfr`ar@@nQJ7Aq%{(^1)(4wSFrc*p4I=%woA!D3r;veQFp0Y&D^qZlvuhcGbz(-sA;6#iQ6Ev5}A99ryTDwhf7cTdtgRF10Uh4E%TF z)s5$i@tZ66Uv7#bz!WYDSy&)~{O?eqwCy+JNj%VawgN8u;jy`=XZ#p;Wf^y=9&C{b?mRcPvL3D2xS#Vbb1-6&g3($?~-mplq(nf(IFVVGf1gqQ*5`jqQF~ang)T zxrz46_R(AD%7Yd8c0;TGA<+$_#?|W_2q`;6Hy0~?Ly$oQmc+}4qAZ4q2G8FC$Yo}; zaFCGjXs_T27eGjq#PwX+U#XOsBX-m=idJpmVqy6JcRkq~xZw%^jFggFv}*ePxGk!D z;U+(4WJE5W&kD;A(XXhYLUeF}4@4HQAPWg@A1O2Q(~W_6%!);D#^ZS{FxDShD|BlZ z+mdo@l`JfnU<%<#Z!|e)%1k_M_GVLFHoi%XvT#!8RV_1izpS#0=W>Q4sT4vZe1QV) ztYiYyi~d+PPX+4sr4-MjTdcF?GL{jRB7-~9sp;vIFtb;@95-ALJw9{=5Dl4ctxy0U zbhfr>3SyiVgOf*iaCsy_vN! zc?1C@M@yg;k0XzIz2ysh{slL{$Cl%FB;`RL=c|^tgnyME!?1C@qnCi}T^nIvpYEYx zPnPV^QgXvRP%4Lx%XoW}znyQ7PZ*Zh_Pq6Iq7aV~xvb$P3p854hmsBTrN$K9V|Gd} zo#)R!7&&8Olcl942(~gddD|=PdEcF-tt~(BsqFSN87gzSL%g3DVcI6TD6X!q(b2JQ z$T4&PRs&Z-rnbXKf)-16|E9X7nwFNTtstS+Vz)~c(CbYzGkAk2#6Bs5D4rnW#S*L^ z&1=Hkuy9&F;B0d+EKG*@$wW7hUZZwtq+KGSLm|wFh9u<}-nZw0({pLKZWXt-rl+jq z6%@lG5^x}BG=;tZ(}jTn-&{!Lp_GoxEA=(f(IH`GVHtO*R}{%sP=ZdC+Z#5?x9pUS zu?7-Vunm_gOP7-y00s2(y=i6kSoa7DZtHC?e(6)$TBSD9Gk8@WWc*)|2o3l)*t4$F zL0#X)0Hyuw!z_FB<+jKa&y+AZ#&Wu{W=q1XtvSaoy<15VcB1BX5=*+ApXWVc+g0fX zNrX6)X$xnW@i+#A(W%Wmzk6w>F4Nk=WFlh1L^aiMa39j+u;g;M0FO|Q`P5tJ5ukn~ zovcY=5|M{gD+>w$!{=d-v?v4BczI~}a(})aURYQdaCOMi41?6fVF0BOd7pfoU1aJx zxX*7lYX)2#>Gvh@MzK5VRnn&l;I%qS(t8;{jUjy7S@=LDEiTz|z~l1HQjU4XcGInR zRm)3(+S}hBsmA&s<7mjwFB@@vAdZIILqc5Ke7}z?JUp`LjiDRZ5%-j3&+5!FBDxY&If`<3$e#b!S@#A{-?a6`caHbN56o znJORO$5m(zBhL#tVN9H8UL16B+R$HnAzNJ^f`l~1%VZX8y1s==KmO9W_*Q(A;!TR1 zZX8jOrCB-)y)cVJzTeUhm70pIu+NN;hXX%|>;m^@8UafZj>84er|Y_ue<-D~rG1~M z+am*A6K|kyl+6D5<3`Y4k@ZQZO5HITXbN~%>+55>H=2qRba4BGIfej0Y#eS=Zix2s z?j+;s)*YTn_Rn9a(9ff`LceU=h6GhkuRr5NI<7b$doiih=<}J*XU_!62*YNJ#t5an z(R2}v2y14W?@Tr44-7yaF4mYPz6PCkf`|D$Eg{3OFb+EHE0a2wt_7p$!f-;AVZx;7 zMss!#Cv>c#yvXVGp#%6l*1G=YLOb@lenwYcj}Pc7^|@FOwY`V;n?Y5h>qwR@{FPOO zLy|JHI9s0N?Cg5^1zoA03*Hkx=VG77{Pej}AyjVD8z>^c?i%Np@8xuWekj1e!#LRb z7Kfr^gvpzekt3taGJ%Yr9ceN)Z4b({hN|3Ca6%9_ zMcb>U*^TBy+s4~twfeI+KYQ1z>{m02csFAN*`(lJy`or7E#Dbi@4j{JJc#BoD=^2j z-7d>UXuzVK6JwyV3z;Hha|oYdOs^C+T^&73A_eV=ki)@!SFgl!)C&X6yK~EEwP>W1 z@ocZTr_CMG98axi1b8PC#f>FtKk0sY^rlJ{DV(CR5xUMpz~dlE1+|_nMDuSKLKO#% zU2zow39M{er=28nP8Fk2p+hC|x0}yV!Sp2s260ZQhlQdpT@J5;#UGv?KQG7yzt`?OC&Zh@#=7TWtZ68s?a`yxwJlq zg-AME=X8XWTUOVJx7sLo^xrnKX-0TC>ycw1W(>yC)A}wTw%3&Jc-a@bm!ugQ7*J(M z#{IG;&dA8HvtRMtqLWJC^)6(0p-_JZ2846E?(=#SJkdFW9<b%jG%7OkQ)?&wnCQw>u`|3T!3C*k zAg*G%?#RZ)G`NKBGq*vqnug-ka`JMI!kuk$Vv#}84gm>8Sj5gN1X=34bkhihgsh4R zdr9YfQLVYzI%Poo@_xY;bOiW3ZQFaDVIZcR=WGU~DZ;$YYHjvgczPGH8dl}yog3~Ad4cME=jovlo}V^=7w3b6vQS6b zt@W>7NmK4Ey9xkb0~7XUws}-%U*X)`N5#;MeNd_+B0m=bkt4&5<^tnx%}%}f#H!`l zy=+d~>&=ZvVe^w*P(-mRsKk`-6UwMw5pp43Xm6<=o$^tatiYuCXk?F6C|UqklmvHo zSB{+z{vDPn??ZJ2nvdT){`&``nC4nQ9|URf3VV0 zmtQHUd?}P&oa#bg^q7%pr|jt9#*9Gi?Hg!b#?+H;;kYpN0aclX$d0?9^@+`Fu+wV` zNmgB5Zj0a1dIuS_HJ6hFfdWwP$}i(dGX;MbIT~imsh6|~9KxyUvqkgP`Ht9HuCLk3InZg%G-{e?hH zswVQr8yhM8?Yc{C0oOS1Dh$xisPxFd;H>>K?nhKN@Ev6WMAXJs#3b z(>Ob)Rc2;^I}a z|79IFaoI?GCmo*%*jtXsdL4E&WR>+Q05^Yh((F6LUpnlbsT|#mXhr$^Z)u*-SlwWz z2K2?p6F6Po`Kr{LvZ-rmEQ9E+VsB=pC86=+dgMvWqopxFc~I-Ye&r&a!0mk`9f%Em z?^B7wfsf4ZbjV048Lu7E9AN{k5Nyh%w&tq@r4kUF&x+K~f8fCn(3LZQ3^p20+U;H9 z{frXPEnKSCuLS{61Np<^&GEN5j0SGq{6mK2ssyDjhnZmT{pY40j8n&H)s^++ z2eJunWCgIFwi*0dI;=QWw6R^MhLO+=HB49oH2 zT;{yMUXhYA|C%}bcmmCPy(?{H2*qz5skp0AM1H&j@{vl&aFuxqBnU%y{X2PDl?yM? zkPTP@1wPginKeRfU<0N?K-$IOeE&6nWpQzH?}=7NE|R9VT#Cp=);`YJ5EZCoS@M@| zG#G1K%bQ~1yc|9$vNjj>4V7P-&Zy|k>8BTzi`ex!62yCyw(HL8{8~^0zdFN-O(cK{ zH>`crL*r=}^n{t!lx5+e9KHUYjPZ_suOF^nK}6P#(@md~8yOtlS+_5*X69;Sf;dZB z%h?O|oiyqC49e-=I1133E41N~$ZMT}j>b#vwI0pHXO9m~y;1dri*c%V6nRI$?}C?O zxr$_beVgiwys2w5e}TF^ncS?cajzA}GrdB#kMC9w4gS=7-uMy$MqML*IP(j~^A|=8 z+-I8;Pe7^}1Gd@iTxgL&;NC-7)A4O>5Ij+n**%mH&>kSSx$@Q)GIevZ?hst9e4vSQ z*JMt><@6Z-f;i8`om=d^6chD)p1itx0GV&__i0cfNumhnd2(`mbeD5sB2 zZ~@sX9{AFXL73#dCzst{l7NQCb}V5WD954wSogSBnbx;5xbm__oxT&lcj1kxRKc_! z{z_HOSxMK5nNoPV67^|GbzdGe1x33tL@SY@bC~SiQInWS_k73@n*S5e)>);`zvp-k zHB0NuXhs=)H9mstsxKAi2QCN+EA8_rdd-#?`7eeM7P@{Xr4_X03{r`luk|~vH-`lK z*e9ZZ^#S08)q!#7dA7n+1~Y~u`?WU)8emHAZf`UVlcJ{f;?0RZsALnOj97O1*8as7 z`s~HH5Pf{D%vyuExTFwp=^nx!k02>JDU|n#KleXND`8<`lEFEC&=4>+?Hr3wYa>rf zPj4O^L~_{L zm{%{5D>u7{6B!vE{`pi@QnEb|0|QgbhlFIt3KW{)pFNudLLP6Wq@MBe1$uTze){so z*V`YvWpHqC$@(7RDw)WPn^bsD5SA(FQwYR?Od>ox_9^n@BHyIb3RbrirPT=~ddu0L zJ^B!g)_S*vk&Wz}skrEGBV z#lqOO;pzX}G~6AcVMGb781KP`d2;>cryg!AKjlE9A}J{3!Y)+r3~n^-{Eeu~v^RZ( zHScnh|HI#n-vOKd1LEmLwq*@J_Lo<@tWF3-%(9x*B$GOOw_k&5<8l?vI>s5I@&`LQ zst78j8Z?79bC^>#G`5r2G$MZVY4161j+WvBzae9nNq)HGc;KENi1IiP4oNfi$9`x+ z(b;6a=nj|jF)PLjCfWoyGNAPAE<=5fMmv&_OWrYP)O}|5%&zd66L>sdW9wO4tLFK{ z)5@wJ{)}4s;yCBptX4tRP{C!G00aZzCEz_qmY0{a*xP0UmB`J*!|2N_cnc@rB> zf`a|mKX*!hTfBJuNSR)%IigqDknfp9zA%|V8*+MHAML{@COWV_#(XRSrmE1<0hoFj zy+|u1eJuL;MmHTYAHTwgsEE|GDW^9XB*D2s;)>`v1@Fa4l4ie$VY)ApC*gnsgnccDJ>t>k5-DRHa47(94obzKDrRJx92KQ zZy=34Y&f`s0zg6v=YfRuG}MNtzb`hH9v^;GQ9OstfR&1-fXbGrbd}|stEEMRb3i(~ z&7t8WW`0ZU>Tbu2F6jnCn}rT?1eo8J)l-$TgNuWoIA&y9S#trr1{uBYS zJtFgc*3y;YY0h>|85GayzdOep9u<|Emi8RvjH~P=9A5#wdDG@0!P_B9+Nz$jY(v>? z$;LrLofM0!H_o^px!5!d**;piE_@L3q@n+$?(hFD^E?BptWobW`ghT*<9~xCY_YDlp$YqbK4EbX(}Y0->`y+i7G<;bZZixVbB$K zZEY?3^0!DSw(q-OT$2ZU^0A|L5sc*MRf?{AxiA()qpgxrS+iw7{`iv-7y~3xhgNf2 zxoB}EH|~xmh$aL2@w_g*s5fBC+>@3d#z(8!#SOZ9CJk;k@+*c41 za@)MQ$TBszwtgt&h>wp4n3k4kFgf|<>E2|e=p#}`M=0EDOuC5oD2bD-EREFH&FI97 zv5V@N(v2d<)~>`68^zy*WP}MuXX4``(-f$V)=M~+cXtCc>mB{_;f?ot#2ig}4JuwaY`P1X@(7eoe8pB=Coif-R z6o9DOmm3aQeA}B)bgDDy1?I2rN#X4U+v#pP9scbQ8LHptWPzqpg`NkS!axyQCiz9h zun`BU(k)b0CRZjp#;auI$2tBF4}$n>8+6sj)^B76;g^WU9#uRWpp1$V(=*^(ViLJO zRVrT{W#F3+IW?Qe-OkW4bjayJo+y%JeK4P)XSWqr#5Vg}Zfi&z$-1@dn^OgW!@LLi z(5GtmLy>{CPILpG59J!Qa_X9#lmzvb9d@|wcApdB+BbGz9shp9X|*pGI0?N-S)DrX zBvNm{^KYoHS?=y65}l;)pm%cjw{@}S#| zfkTDT%`ixXQuQEO(pjIEsLJ&vKqN=Y?~IN%l4_B~C#S(|&qJ&8zK?U?Yuyhkmd(F? zYwNLHbPq0M4_j`zLeiHwWP9u4;sR1Rs8R$1I;{C`{jqR3?UFC+CXWx_2#Hv2Q1n}c78rx ze0+k8!Aj{?voCSmXjmd#@*Z*hdMcaU`PCP6G&DB=9B5sQxE53l=Qyff6Dey6Xr0zp z5(g1->9h8CPIe}LKB7a4l#l|>z1C)iKae>FW#Da6?ge+c+-t153WzMNhXq%fol`j6ERq@mh?SwB2F>PX_T z`JoqSHlL&NE;x~IX>T<5c@*fC_TaVui`BsoS?o;H1v#4n7g%b z2hDS-$cko^j?zna^!Bmd-U{{m?oY7e zl0pBFuM?G^BS^i<62<@jQS}v2Rd3DP2SrdR=?;-lxOVArMp{7 zy1PM|Lw9}~^}YVTv({bfN*wmtzuB{Ao_Xe(h0Aw4&T3QO_D3bgj<0zJgu)iBDbtrP zkw&~ydh-d)Z}i!vk_%p*VW43^!m*}3j|n+#ln|q~0QlY6J(iOG?Q5^@4U|T`2Fti# z+xtyU+wBX=gEjbVvoZXV!tG+PcM0z@Ve|<&L@p=0>ymT9rEIWe zSXr@eBAb1(AucT~a+q{m4>*>#YyH48AGF_q!o|u>_9Y7fZFE@S^ZaD=U-7T8USriJBqI z=V(^sc;#~6yIgbnYMfWa+83tcIy-dsBU<2krnn~cFMBs1o6X^|>h|rGWfk-7Q8eA{ zIofDfJhAd&P04Rrk>(C-IYa7LS?SP&cA5=UYR=>;>%m-HU>ZhTEzA&ug#(oTd@HyJ zaZOxQw8RCjDpx{xpZmJ;$z$R}vNx9i!3=K-^0IAu^UHJXx!X_qjoV*(HjT?W3SWL@ z;?vC7jIxvyaUkz{L7!KY_<(cvX4e_VJ=^`0<%*V|%mC^Jw@W2QlMtzwv_CJ{<^5os z0LvBZmaY-vRdU~-VO+tJ?h7wAeLux!8 zqG$EDQqwnnB+}$+9U6k6ipFD{SSh~U4qd)RCG68SN46sL?ormaIX{1YeY&nSJ5ojs zdP!||^$`1$o4hv=VpCCJIbOeBY<7UYhMHR(9EKQ|*sZETrt_yjFSE|ZHxHAs;fGaG z@&_PckBm#CvdmUUZL1MyG+CfPlyY(Jw+l<*3_ldZzV8SGv0K)ZTx*P)f5jOkB*WNX z$)WaC%2e|k3%hpM27;esHy0OIs=HHMmjyOvED7B$7OZ4D-}W$b1y4keg0B zWr1M(x}o9fJ?XbADY&U>gvpwgjtKgrm88M;IqRxJt&@f#6=oWJ2MGMinIPeCxFB86`Yqx0kSS6yA5!27kIg^_U# z2d_T&Y`Cx}jn_$Aee(Agyi;@7=E8Qgu&@Xn&z5<4Fwx%xgz-Y|nPj%H{ct0ia~dU1 zn|c~`4wCgI(>1onlUxd4rmwHd2HHsgPlDDj6bCMx%PX{*-{O@uJw1K8MeM7d{fWXk z;Z-X16D9^9LGO~wm9YR`bU-r+q>I!9oT7e{8QE^_{Tl19u!#}_L%B7 zO*V>CpRqgu+(L^F#C@KIymC?U-(*baLn4(+VsWKu| zYOF#7tis2S5u5$Zc-vZT;ALfGK1M~M+3gPF&ZXDl)5LyJiS*3@!nR$t()*XC696b1 zY!r0Ozjb20yX_5p!dga^y-gIXOP`LR{$$Y2>#|f3Bcl@zlZXR~!cX#6k{i#Px}s7q5D?OVKi) zk}DNn{Md18g+F6=;$3cp;lOl9<#I5ie@D#i@)QsYnc_Ozr=9?g=%M$Up9oJG-RI?I z*^B9w=;E!)Z;3Q3uyIeyoHR8PQPD7T93+1GaAPG0x(M1hdI(R!=P366jpNMn+qF(ByMJL7o0&O8=qZqQwQ2QG^mtLFRLQHE2^`b*+fF zwSaGPP_=(t{%F}QlticFI&)*Nl9kQvGWom~5Q^4`3!0S|tU6Gdu8l@*8K_E`iE!=t zVv5v^Kjfd3TvR2g+)OzxA8jBg7hlhXml!MsPnMLCT8|XCvP&c|_UTN4be9|R5F;ok zsMzsLE8X5|t{yWuR>|O@`K@!=lno*wFNS_6t~Tr;%6@119izKV7X~ojM@4ksnew_u zFH1{Htv8yVgZDxL87SNc3m#I2T#oEFJ zRZnsVrG#S9>%hUnl8`j-@0HfqYt#>#>FfL4h1{S(7MFd4K_624FKminLzENyzzw}G zbDvXUwbOMNWa?JbQ~|_-hK@c2N)|p7C(M;J4PmaAvp(zDyjJ^P6{rfvoH3u_e2m4e zH$Qf%+MQ!C9esCQ>x@83`l5}$I1E6IM*YcwaXpMbfByVFVbk~XC&Pv$PmD8;0ug42&=^rFxzB8&7AI#grew ztnli2b%$Zo5k_BER#sA+?R9;oY!49!6|JeufntLxv~ze9pO4@^WbBq1cU0vrm#m+2J`pW4} z5<7#$3x~n_W7p~m;6hz**pzMa0dN9tfgNXQX{p$;xKlrz&*(#AX(a47Qu|=9K6EucaU2pcYG{2F)Pm1RyZo}1a z2lD`resOYYtDoLacR}mJHc`fA{lDoSRZ}?l1-u5&))Gq=^~@~bJOLced-aRCH;G-j zKAyVXg5$@`*QN_bG8R~X@q-R1)=R|lj4)et@rtli3f?%QxXFX4?onO4+q03!n?V--=l~CGxAxW=W^U> zgO1L`F}lL3RhqvqmI8a;lcl}CD2T#l5`O}1vgmXd+(Uo3uQjh#?HRW@{-#wJv6Xn{ zj^P~9LSi!(IrXF=yk)+^F#6~T9+D-&By6Y_=bCr9lg7;vf}N8NlYv7AJGXL{Z1i)> zyKu$+7m?k)aMnGT?e92B$977q!tVSWT9XSL2*^3BB3&%CD~=Sif#Y9Z0mGcrn~Y7T zbGL92<0XtLxLCfHm50!nPgg$dlu8yUS0R2eF_(}i9Lgb;jF=2t>#v%*8ef-&v;wnpR1u9 zZmC&pIVM+scc2^~E#W7oc;LD)(1|YyH|wM8bCuAWuUV>t<>C<-k? zNxAHsmoJ$2Th|s2W>Th`BLD-<`lF4rAms7!S-Y(?kDmpX!wYS#00wsf>OsN>`JCSGGugyDx)p9^KoOZf)}GrulJ@<|D2zvWf1 z@lqzO(75Q}_v8bLt^zqUfFaki0q?K3lb#*{;4-}L>h^6m)U(vo|RVT8X z`)cpBHf79k-q-?ncS=i7-Oc_}^wCjkO|seNhY@py5jWkThI3y&{-Ngo9Gp{dF;-bE z2rm~1T{l7ElotVuz1V~8RTu<5% z@H*juELUl&-ko{e1O2C`rxEKt2kT);a00bkqi5ILz`J#KcQf4P9KfaEeymKq z&iR~e4Srvv)~QQ}Q+x+Ob4?pu31Fusj0ivrm>#H9oiB{v;eLr={aTcPK^;@r+&jg5 zA7$-N(La7rsM+9m&(Pe6Oc!n_Ff?EdW$&iw(HHjTiR zFFEqhrdWqJYISU68IeIFeUj%c%N1_@O%;^G^^%67i2*mM&W=q@L{$|Rpmcu3Y}Yzp z?44QHas?Pvsw6eZy+Ab)C^m9zkT+~JHXVD)s~pCSpUjrS-rRgnNI+0lRzAqWb}yOG zKLCEn`ryagvhCb~8t1iR+aUX|K1U+v?0z8~84@s#K(>%dL>CBQEu(`*(l+y@>GEGWp`ho!zT_CGH=Yarc`D}A zxHrjS+X4DysWZa;4a&A;Ap@fBSvbq*@|gBDXq1f}kD&g1@O#MaZ8X|RrBM$II+Fzs zr{*ZGV6!z}2PA$%FyS(IP|tPh)jK|Kk_>`AgO21k!-0e^`*Y6mF<4ArBG|U`mw%HL zBxMb|d5nj|RFuSjy`(LhXmM$U1BsG?eo7;Ohx$o*`?#)FqCNQas^ncbr{CyC1DpV~ zc59?6EqZvU)xIe{C|~d+8%e(OnVYv-!Mw^vp(T^_Gg!AvsPyE1*}>d?G?=J|Zbj$P z^<4uNB9Ty~fCxuCSMlVuqW&8{fC=oXhE5m}5tudUs!BHK;LhQ3jEPyveB}b;w%LbD zEX+XO|E>5tPFK$RmsE6K3RGT2RoHF~4T#;E<3crJzMtAKz}ns1>ld|x>)J<{m~39~ zq7u>04i!q`?Bs4VsbN;Ah34;QoL`RSQ>KxR4`H0G&+T^7&Xnv1@4-M^tK8w)m9c{h z`KYP!<+J+VfS&0S=85}+cigj4YbXA4>smSTnfB2~efeLY!4mj^mzZKeh>~qObYYiv z78M8Qu`;`I#+;O(*oUAo%hy%EY{sIw3N`fVOD1$_$9W5zZugWS(>nVid!A&Cbdm3X zQf6)g#mF-?mr5ZW9TEUgM21y)9^(HQV)FmYmfeko-ti-?Sr%}Y)IE(QQ` z`)6nVVwrEm#GZoh;L*Iy7?J5L=Uq3_d;|;EJU>r#z`oLcGnMuh;me#Tq`SA5rP?Md zYsf%jf5p z&Fxc<`tI$#v*yeU*1BIS;V$B!ZjKZz<1RbW*^fJ$6Pqg7JF3vygPri+q;{29h z4KZxLc-hy(P=}0NM8e_vNHF;Wk|Fsc>w~9$No8E-1c|A#(E_p&p~LkOUt+PoYRnVh z!y9urpFcq3*Ub7@%79Ikx$4s5|H*F=fYy+~+bh@85TFgyT{(Gq7doq1!LFE@k-^e^ zN=jOuIqL|Wl|^nw9^A&wSIWz45cDf&!GjT3E@;>GB*xPI3{=}TCXsJF=HCtUcAQi@ zVZ@r;K~ME%T1Bkr-n^5!xeB^hjvbooX_+UIjl^8t2PG1-S>-CKN;Wo=35s&5 zp34iT)`9F>cYgyW)rJQx_NpTCvnh_u0?&$Viz>N6y9ts8mEroh^_F{b#E3GbxUBBAwh+yp|h#mIBXA6^DLI!wUFB)!UI2^_zWsll;iH zer;V-R*5O7l&Z82Vc1kTvx6WyZBlQWDf6xY(;{4oh_8#^n%SOmn)+5{{E<&4BJ9L$ z(TpQ5thYbXZaAkrHr$9-u7Yq>~s?*$M-hrRV=p7c(AR_s#xFUd!_dAaiw0< z62NxCY4At|q)VnPNy)y4;oEavvPGC5K{F8OwQgJgP%}%V+H$;Szcz{sdJstR?Qy{I z9js7S*5L4LnQkRb^Gv<((a_Hhdr3zn44OA)XXge1$l$~K(^v}sjE^EW%*W>;K-(yI z?^e$E@;UHw!@2GbQLi#Kyjvc)!c9nke3$oTjq>0^9|fiJM{E|Jp`v&u8X!S1)Y_Q@ z=N!e5uuF&SByxkvI974DJLerlZ1tS6U%cD6V|&&&FlVN)GI?SKIAyDl+qQn}?ET);*!;?XvAh7K-5 zxS2f=l{`-gAv$M#BBq2u`y+N`BgeMdnfl2=Rg|u=S@7wSt_d-b-}j$V6t1Y-phS=u z)c7gShTVpiji|ensT>*U%}nt##ElvBLd7o@bxFyAAXm3uy+k6TSn#WgrTo$AJyc=q zDr9G>y&4zY&9pP?_$;=l<2mgM1mshP{j-w}P%IJ{0Lmj8m5npM6=%}?46UqC>FViB!z3oX zOw-j4Os7nTfi%to3HT)fA$zEK`3`a2nf};U`c#&Yx-~u&q|SQWfgdd`^Cr_{lL<~X zOX@#kv2i4?Ev;dSVc3{cPZm7t(LihcOBxzsaTLc-zOc{9 z28mBk*UB(Vx7q^boenZDWO5X+a4dX*Hke!KE_!ucT|y!q2q(4cEQc)QT33KQ7HBqL z-A9AY4;x7y2Q=YY`O2cgG?`yM0zq*^cgEO&gph$QRrJ#yZS63CiCfz`K7?dsXTBgO ze*~^X#0T;X1Y92w*;g!=7rlJ)$!0_1FEIvh(mZnO>#sXI2qbL3(9<^;cTxlse^+l* z_aFRrIj6~OF)x?cVEqUv8ca}3Zbv&#-VC79c(_)yTzlO%7DskPM8!PU!Z|oL@j}{G zZc#2Wwy_a?)xpaSuR2u&fdJhDyT>R#Vgiv&VEZ=gR?lBhi@3S(H=Hf{uxqj6XoEpi$w>{5r)n^hCL7c$gmh&YF`j0g zPybAPc(9fh8*(b*UU^@AarFQ7%K*Z!q7tXr85t1)f$XC^F5lt^xRv~3XsA+Y{>WkP zVrKg905Z~Cc1LA+2tUx;NH?b^C4GPf;d0!Sd0-8pV)DUVF7oQ#(O`ULZe{Gh2x)?w zi6MD>e%e{Ed~~2MyyPn?9e~^Z9yi|UCaI#@`U3C6;i1jOIc|unT?WV961s64zqNt^ zWxiT1gqEk=QIr}(EMM)4++l|k5-Qw0a5odUTGWpfJ6EZX0q}X24Lf2P94T}_Dt<&kX7*%cu zOM>7I2KacC5CM7;Bz_uhKgBgVTwxDs0_Qv}f22xqcwn2y)h@xCiVZ>)OUE8WN zcQWMP(o5g7$hP<#tjbhiO9R&E46JqEG=BX;u|eqeGw z=9==}4{sKCegyz-oko*QkIvV0AD?rMOFhKh&7m=!TCi}fuWVf=NtZoyQawV#O2}^Y z+(>Ji3tUfcTt#qcuLhP@mRFRu67@<`J{YW@;xH`|U7wukf`Mna24~~OGrtRdqt|Vn zlsa4Gsy~O!nExu@37t?>qF|-lBf=^V47F&vB__~Y9YbTOFe0!qQmZpyec!eN3l^Bu!l1k5 z7J|q7Sa28W(@*#V+yG`DI75XQp1z|b`&#H}nI7xw0g8P%h=tpgf5beUhfG+`uY;}j z$0iokT>p+G6LLgqX)~+UDGmiPkXK7l?`hR5pAmPqQ?hll(Q7pNK|ODLnAhoFu+pY? z^n~KEJ*Mo}Xx6?XfP*A*dg6l8KOE%z!bw-ANz3Wn>uQjfyVqpOQ7grNs;D7wc^T~& zHpX%`E!X}?3}JCqncxH+A;X6a{#m|a`a}Y1Cg-EoM{qEkl-hC1={8!Sp`Cy`wpH<0 zN0S!_#~l0^RedMgU;+I*djNILemCPTNI+Y2L_IXnIR{NTJV?h{tC4`yh36BkB*?tL zwePgFN`CG>u~2bOt_B3;ptrWgJ7ZHDL_`Q1L0g=x$RKm^{@UCHW;i{oT~lmG?@p0?j{d=t-`m`0}I|wEe*2JW*ROcNVuf z{ecN-9@0zz!zJMP6S}zEZ;*0Oh`bp6MAH_ivw zZu?gq(tVbcJk0n**o7pQ%a}V{P6Th;$(PHYpUwN6EjW$+`mnl6rO}AxZyT#;{p(y+ zBcz5-s;r`-rD}T~ObWD+(U1!gK;c8;#}Bx5U%3Q0DW!-=_4Xt8?b7?rudO4aq6@1vQc#vh)c zJR{!YazgBsPAPJTr)Rr<;QQtY1T0Ob!V4&YXT(0b+VByS?6cJ|?IcnzX24Pe}3 zlTKur8Mu;;AMBc$S2{_!X>cIlb+zC4Azlk9mGOH22PRjm@x*y5NDYz}HX_I~m5 z)CGp$@!I{^aqaopjp~YHY_uLwH1R)=Qx1d+SA28IaQ+*(B@`|1X^*N?k@JldH#lhL z(~{t2@BlWAE4GMKA}eQ6X+EME@509gN9e{hxb z>kIK3N||!{)Ai(W94naIycgsph!u@L()0`r6k+um)SMxZ+gV!(x^caCAhTA>4@_eI zbkvZThR6tol0;+ig9D#d_~7sb%`@`;#3u7{bIW9ck#&0XJ8{V#jO?-ht=*2`wHtCeB4&uYM&|+FkWR|D+~~TrzT!K} z%?WM|JrKUVlW3%+J6qgud5rY*`w-jZ>6Rbu%-sV>{n^0;sIWb`adq?uHFdfUjm{KT zlr)v1y&_&?N|6veHXQZJyGH;anTTl$A4>Nl%{8Mex3(43xTbZxX)St5Lj?yp4hs^> zivb8m9K8Qh0&&%w0;QGn&7-)wa|^_+3H+pK{}+JV1SZL}g1|6%29MSJ+qsj@LUP>o zsQ&qBcEL+}W!>Fn$H5|H$K##xN0x%p{978t1-i;d^t*ao_Y?}eVK*^di`ltkr68Ht;V22HZ>sK zJhDQ>xYctXo-x{O-w|DJVrn$+u}e&D{o4_e)yo^HFDb8 z^6Uiy2teq*i1}9hoysXRN>*L>8uZo4<%UzLy)h7ig@u63@+G_uJfxIsp2(%#hUl}~H zjOjAKdHtOj!0DFR#(2krCnif_ob(cHN7CW#YYPr(AeaJ=!wKw5&`~u9m+tY;tLOau z!bX*Gp?T_#D(^@-!kwRquMIG4=@Ja(5bi=p0LjKmP)jD@LqoGU0=u$Z_|7NCSX%xj ztvSiv1Q>UhALHY2fC??#;Mt(=thdE1tur+Hp2C%K!twsb7`?{Cz<@wNqMZLa?E2ab z0=mr-fKweEjRr`5L6y?d+!>#@n#FCF)E}YSG*5hZSBpraxsyV_HR#I2Cm*Y;RggZi z!!-2jM2nq#Cc!x~$=r$t@!yT`kECxFPk@3M01fd!!NCW#%w2YO_rG;fV&mpfYo3@v zkjt^rsi7jzd`gy`C2-$o@l(5(zc7sCF~Dtv9W04J#IrQlUDh!(Y65Gp`iqp39R)2A z_O_AN+R--W;P6lQ#j4$lNMXvWr@z8re@XCj_2NG(mHj+28Q%i(YzQK=k3AUoXcUu* z2T1z@v0)ZNnffzuGk(f>F>slQW<6a)Fwj;rPXR^J$mW4g1P@-V3N6qA+T7WL&Z}jQ zu>4;4f1X$t)2>Bl{P6D%nF63nuNwitck%z6btKV~kKOj)>{&xH zX;A-=v4qx4Sn$lxZ$-GdU1%QuPw!YV;$sj|%j?=+oeGl25${YV{9}Hf!+>3noSZ5~ z{c(+w>^~zHz;IliEGD1!n?KchV8g>J2P5r;`uo|B(fEoRyL+Ieivj zD)9_9k=ywxv1cifH%ar{Sj)8FpSK}R6Sm8iC|5yK!$veJ`#aLtC?8DCA@(>%Ez}OL z_-_e6#dZzg#q9^$nTCM5nX>Bt_-!zkKYskk=YdV50&yp;dX?^c{lD{vy7>eV(R>uT z2}ZGQXrVLv0R9~rTHt})A5$A8GhF|rGn`>;vpG!u@9BL-E^#l8BmJK_$R2@)y2d-* z7qyOiEr0hN6%}SM7_vQN2sZ<2fZ!pk{0HujZ{S%oxOY>N4hHGL1Pc4j7$=4FL>|Ni|yi)TfT z5*x4wrWfjG@pqQ2{_p@d1JkZmTRyA{EhVxWaLw8 zJL~U5Ofz?v@ZcJUe9ZaWApjcXemzU508i=&?FJr$`{oeLId64a~0ji@u<-l`VW&{vLLYk+hp3K$SH3vLD)B82(WfTrg zaYbI-@uh}*>_R81%kyagKQ(`KZuXrO5BB_G(Kj%B!t{ck-Mk}g?g|FNS#xpj0#!$1 zl(;|D;MoZ@gAr?OJ5#nQ&VLU&IJk3{~ULRZ4OGhoX8&kVJaeUjw z2?9ls<}U87haUHuYlH`j++z-lKm;_7Wt-LQc#ZTE?1j47WZygpkKSr|zyP2u4iMLZ z3tgeu3+dmAAA?v4@pmH_E3-F=PS3bS9J^KHKksV5--~EOQhjl5e?{lRzhB&P!)UxE z1fYSyqW3Hyq2dZ~obd3K^L-H5RmEs=D`!5l{{#$I8kdektayUdVN6U@b;@vWH{YLh z^>?*ohz=|dXNvzj#5XQ!d!rx` zhY<6+qR{fp!a$}tozHJ$7x3)se_OfZ3(%T(cV+qT|MPCFPac%R=(>X#Adn<3mlRYr zh+R*ES5qF|xR>aRA4R;QA|8L5+5+Qbbd8gLyTb)(-t`RAxhz{TtLOvicv$jl|AeZj zXP(r!4waSn_&b2%1A=xG4C(d2eJ(!~Yt6b#QP|!gsH)^Qo+@C1kL3;H?)qb_eF`vi zMwn6Em!1}CGi<$G3*&&>P}nl}3nnuY;xI^zoqH@hn;TfX)q?FPBAcJfRomrLrO-TjXs;4r2N zI^ie){!QTmzjMvg&G@OfMjhP7yJH?ZlNmJ)hn1q4lC>kGQcPAg+-O+|h(v5caRy_~#!+skXQo)k)$gZ8r%_$s4DiLV zS-^b}%ltnFXguj<@g$WBHX;@v!i}0%VEPHMM#m>1XmVP)a&f`JpR-O@0(S#iEHP8U ziJ70$OSru0eJKTo3vPoMrM^8A5uanj1v>|HX47A^U!bIL0Gt@4n7U)bkM#EReBT5r znl-hB@xXr@dVCJ*6D8MUQ_H0@4m&X4kU|Po&d~rK`;i0MU4b9R<_X44kOOkO?`Sz9 z<2O@Ddt6(g?9+4im2AkzDcUBXin{C| z#kgExb|Y9B(YwVzED4L4@9tQI5u9&uN2r_+D>#)~i%4nlnp;qbX@bM>7EFkPd=u|< zfD=%>_n!oNbm|}7;ll(9hDctK_ieQ-u5lRMuQT_nT0zGIki)H-_vrl3Ym(-oKIuI} zjM-$8%GvCW#SRK@^?rzNrw+((a8tEeu<(~HQ(dUQOsYLrVp>>4;NcH!j@xl&N7D0J z?BL;D>sc(KhF+h<)+NORhU61~;nsM)BTbGNmuF$Qo9gea`)qpey^n!b?^s?OhYcDN zbJ>3gJZTypGbYrcdQ`5ILj>OSz{aw%eyB=2SB3;&d+b)^OV_J;93Pfxg6>ipuEO$4 zukSc+dDn~IKAJ_h*^72fh|h|SH*C!>H;-F=DOpz9>({6KzVcW-rm{TKsHSRd9-%$( z;UkzS>yAB?UokJ>VPV5pPTaU%oWi#o3kTe*mr&hyw{6KOM5E}EROd4U2=#&f#+1ui zyUo|5J-H-a^!ODVL$PR?n$k@(6p`d$rKW7H(N1l*yaKK>DpuNpk9*&BG{PAlg1TiM zkPSj2WP3ALJ0}3t`tM&Fv2>#stZ0t7%s#3#=dXbhzK%IDhuv{*NR9ghZ{LMu4!D^! z(X&ZExNC+N5}qt%K`$LQsYHjfEb7YN&(Mj=)i7m_mPp#pjom1X*0%RC#bilA9C;~saYY`|O&Lo?jd@?bC}bZYZH+`+n(-#NnD(s2MWFe=<`BJD|YyQYLaeja*dMKb(_10AY9yT6Z!v!S^nT1}k`X zV_2);E31<4p`k*(i7e*HnY^s0=iEUv$y;Oj(rI(H?Lx~Wd*!PB*X|T@>Xm!rF@$v$ zPVKMTDapj5lnQ1tlou}e-1paBW}Ep?M^F5GE^RV768;`c)t;`k4Oc3f$tQF@6$e5~ zQ76OO=qF7B^Rh`_$DXb-|IFKFG=e}rCPa^!j(m9~e+*hoYq$Wq0bU=yjcAAyBM~W3 z-3S@tCAJ2$YCKY^WTK9*>ff3Ul`k0<1&0KU^Mvze|N4dD?CfH?WOeu16Saw;NVQHk zuVk*S(*loYCx^zOzq6hC)J>yMk6yht!^IBz9duBcwk>*nJ(=M9dfbO7I-GmQM$O6j zmN$M}s2_+OrcxkneHZn4jdyNM3`Ig3Q74v?HJL=s%v7x~Ke;rcD{xewvzLBP<%@RKSy=s0hn`(|2S&C^NgZ-0K*VxmJ(`8Jv3d@zs9<8IXW9=`AiKL=i zLlv!t=q*v@M?cJ!L~FCxE$C+QXR0L~>Ueq%zKkkBk$5s1QvK~{t`%aAJQ{gjc3S3h ziR4tH3@X&@&nKUV4hPDkc2qnG6jd!OkT3h1yyMwa;#n~+)h{a0kr)y8s}uz+rex1g z?SEVVjT&I=JXbq9bI!{2Xf3~&y69*3e8udSFLP9jDzi&91*?UMa+RZ{*-jISWt!4m z)s*23Sj){q>d3?N>RX4CJ?uV<6bVU_v7A`JrW?OeV z@82c%tx$$; zyUfpvDpD!_9K$I{U?1P%yc3I>PhnBSuiR0X!IJ#7w3G^Lb$jnE^%ra1xdm~|gCoW8 z!Xy^g{-)9?bC-)yl+nCS3)AWEg%5%-N4x|@SWf&^gMy_a$SO>xWypPoKesfvI*gUa zH+316y`Sr_z+*eLus0uhV{fK7QL}+Vt5u?8i%rAa0c=39k+=18_P|yFO14I&=1~^X z=*{>kXXUGaIBLb0+2A|xqUN1EOJ7%+R8_?aBRk85 zZclWb@EBqdqUSZ;s(zSq;N_iUH0%5!`0CiY04L4j)N58Zox@hgBY?4c%H@ z1G6n45rJc-Vg(-=5YNF+cPj15@{vifRf>5E!(|VNhGU5vQ{~8$dMNnZ7LqP459`45 zPri0@Pwan$L7h9^hrfOG3f*2hoQ~7&jcR<~8h6wF;_BumMpfR*BUIZ?w!V|4g!Iv@ zx9IVG*!sUtfbaNNKU3~ph6g&V{$6vlc65EThC6%_U%y^5Gy4=tzkja;<#SS@lunU- zqn8G#_KMlUtcp1r0*|79@!>m5WrLxKLOLJ2W9U}D6!(UQ(1^l7 zLt7r_KqlsOlWg;v4Gs^V7)))gupT1)pOJkF!lV|90-bL~-A+h&ED>Zk%${1gWLB@_ z<2UlqV4nJBXZvqWaA3KLJbRw+SmPzAl(W8cN56{RD=Dg^ z4xO6l6lvt;jkS6Vp04O7{Yu|0)Un}s_}vuL!OI(RKw3hz#QKQJp%Id6Re{{3;g zyF|b9cv3%nTW9k5|5moBL?Ie>EGg1a5@JxC1k~q%dp=1F3>i+o(T&P5eIBit<2Ln% zc*N4tWHZ#D+I8M16?NzlU6MX@PGMJ7sE5D&nr`9M; z-*n+cwz<98WYUuV9++pbOh-^4Pf@l=eIYnXT!i#sC#EaSUEaFioh^9cF)Tg-x2c9K z-~F3HAnaeo%NlS`(rA^rp56ajd7`6$E5st9FAD@s7~LFQU9a$1cE)G|7pXDv@$)>w zk0);2iOEobX@OS+0*IChEJN>I1Al5=x;Xp|uT|=fgMSd_iSkTL6?g;JH?4MygR-Jg zT?WH*b5>)}q?uRMa?X!d(}l|CEGNSGZu1$7>g5Jg|G1Y~2BrdBbB1mqc~U&^rqv~L z!_|#zx98EPettRjWgQ?|diBNTbeGS>d?H6x(JIX2`GPy)YrA(h#Q5LzMZ&R!Ozsy3 zK3IO@IASF*&3K8}WH|5z>lZmPg&|a5sO7)w6THT=G|oRD^Cw?#Z_XZJ z0!kZrH6zhx$G2dCG2eA_9?^pL3tJR>^Cr#B-QAFF{mxg?zcuyzlMwLO(NpIAj(o3j za-swePfxoQT@(6@%wy>kNe5O6G-~9exi7v%eg2#j29*8s)K0djmiLPGS32!4M_;Wf zEd6YKaWg^a-@1e`k_jZ1z%ePYs!-ERE}Js%Z~_lr@y#2BS_xcVV!p!9lv33p2i4(5oc8P!rp@i4=^;yg|JY9!w7iuZDnOSD+e}hbCeot#bT&3!LT~$OkL+@S>NpG zhns1rgNF#X9l^zpqH)ua6p83CY0hQ@cYjzc@8ey`1V;5M6fnqlL&e#}<-6WRX>HwA z!Pd++GUlu0*wwFsB4K8;Z3ASYNZVuM_mSFelX%64Ibn<0T5-mbb$juZ%de-KGp`A4 zlwK@2X-6sWkg2Q)BXzOG^vyV$b>wqS*SI#NrRo2&=D@&E(Ky*29c^{rRmd|6O`0xR zsMq|Q-5){bn-anhCJk2NdEM|X>euRK&Yi1qK5#cSoNG0JeH7b$EdqJM3pCi&W<}XB9&Blha11$orqgx~B7`(GMOz3^fBXvn+Zo_kp3e=>| z8eCSzByXFfF@OjeA0OX|>oMa=ZB-R0zlE}iii%D**k<#(?P<2RwN=;e>9q%K=Clmt zI0s`<5iQoo*xK2Zzd3`Bd=X7~wS2ruGof`^Q-83fg5>%><132=)m_?Ka#3SaQkDbg zlgo`V(GL4PNhk51SUP*$a5DSd;kW5pxYVLS;lU#xMJ`{_(b3JE-amTCVp^gR+{`O< zB=G;$1Fk6^1u33)Gn*=EUlsks{kBJn8Yl9bZpV~~!<93it|m^CQIMOhC(DR#meF}8 z)bU%nbF|kSAuuz_%Z-FoGBOq#e+NN+!_5KqrTcsu&3gaaPSe%tP_-I|^xZ9wypB); zQk3vx)kMY;8{vicBo53}^lUl`|AEeSV^O#nsDt|z)X`<7??9^a=KA`0xhH+B(%m(- zUCgeFduAu6n z)TdT)ycIX}l*_u=kV`aIt|C{sfk_E`r~iZH!hAzeSQs1HI+V+yn-O=mQJ+$ui;gbr z_q_s~@ynHy58}d4SnnT&@&w2qUz2+aQYkA`M0878++Qd#1L3k7Zf`1YcBY84&UkO8 zC+U~h^Tbwr)@tj^$Qn*}vsKYrp0{8sR)~>j>)YOGf@wod94pMq)|-=f48cUppLsCpZn>JB^{%)*A7=?s^A1W6tJF$Q?(%q)ARD6plo&Vb?n{ zB2OPi1pV^3a?1QQ238hyrjm+nL}I!58%e|60cH2*S$o>sV6ZLn^78f+q;CLJ1Hxyu zN~aQ=LU1?^PfqNo!i!Q;EZ=+Bgl_IcUEOabh-?$Pg=X@VwlND{+}{l(o>D1+U&u~s z@)DAre(^@rtE)v}*szJ+XVpgiVkrW6xR?c^3%!HXtttJLMdd7cwGO7~0^z*hww|{* ztJylWPltYOGVv{0I69TWyF5;((q!U!kLygQMl6+_9rIeHl5 zXX-32C_0RfPPsX7vH7GqRhlo?b+4YMM+LYhmy?Q#;~x65($H+pE98#T-6XD)@#={r zF`~2TZMp^qw@+kUJu~WauE(Q0+8+HUH)|6E%*Li`XCr`k45*PA&s+U+)-@f)qYk(f z!MKunmm7PF*$Az}X}yw-=!s6;E(`EOUn@*En<~u82q_PDR2!H~Gr|aYs6=zYWiSuA z^&e@x+}yE$Uef3>_gd1;)w?9dx&aR9xc`dy=gf?HltP^pVYWw|!*&*0JlfFFdjFWR zJg;)M@9?A+7{jbLD8FUD*AO*4K~t!j7X!qMl2+DBZLb{MkH%tO+wFfFsqF!sb%PCO z3s%Q-rS@jAWj^W^mKL+00s67*OXl+%U8t7p=+*h1LVmm|2RVbUVBGAj>(7;@WSIW z`u>$I-;5xE)73J$BO>E%Fm|4Yk1!{NH#Izbo?Sds$1QPFUw`Q-^t#6OY|1}$9(3!5E2O|urWOwYC8)ND*nQIbUIhnLH&Gb zxp!BsBI$E^d}daL$xcr?_$C>!>+b`6H={Y4lPx}9_d7UVpweVg_8WWf%}o}e$&I}$ z729OCX67w(_Pog);JX@q2WuR1GxlY`e(RU$ii(eLznPG>>4+Z^-qqnt-`$z@FW^%N z>gs|sVYFjR_b5qqZKci;I=U&J{eb}ew~=$$p2U)*kH@y_MfMrh1uflwF@g-FE|LUi zQ9WWjAjGf=CoH^2dOo$0WoBi*@4KYkn$8LBX@oniqaP5}5q*vM|M+_AsHocS4-`94 zFhCkqLK^7?1q6of4r%EI$w3iNq@=q$1`vjZ0Vx6L7`nT=nYqvSe&6^0?mw5cSj&TF z&YY)qeD-JWZ7*JXqN_u2yj9v9eB{G^uzxtTnkJvO^R$@?0(>fUU={`9?bU7)no&|7 zEk?*&bVXaoSSQ#)&X%H!v@N&Rhk>q>Yeyt-9sTse&pdO~Ek39D2-bJEtvN{%U$ma#=|;rqXnwBMOlcyBHU!4*e}qpq5X*?4#r;85RxK%2aEmX3O- zlA(of1hrj#8?)6JNuM?=wRC{rT%k)45s)Pvt&kV~cC4aEE9<9#;NT2{taRD>htm$L z38}R*!yL~&zj!X|=mN0%pjr@b_k*qRqS}VUV`0JFzUF+bqIj9?x>t3@Dq33cA}2ep zZp?gq!xV@gHiI-YZli~CdaPHL9%E<2NPM(D0+MlL;}9$Ne)%`P24m# z7)SC=A4!I64Gu8V@Ka`_ms!We#-=`F(q01{z}-UDYRv~Z)}z#ehz5aztB~3BmOkO?Ph`bL z-`k?`a@FRxU{$^V&CZyJ*s$1z!uNE7nhkCX;_wf{QcCWS)ju1zT~~+tNA3 z7)>)tId8RSG66hBwhG5GAzQt(vva;J;qyj8-U{4@{OR!oQtI6K`V&0cc07yvEfV_B z;}B3?$LVl(njz5gs545d-XUv!xVRW6iND}&v-tgcdGyNJ&Og56v%t7%WcsQ~jo@wz zZ33YN4y9@b!B(Tvl*8511V%FkuB)s4lzeV4by!(TrM`x$d+H>D4t^@B3#dw$V4%8} zc6L};Y;7?U%n;3_3<9P>Px|{;ddv^9>!1(+O5`^+o4^{}a;YWxg}Jud?d$KV;CrcT+(b3saUD0{%x~`CLKBx6U{H|!;sIPhz#@|k-{$jg6m#lOf z@l8aiE|_iZ^Vu1AqdA-(Sxm~tfMfdD2qCo;I9AbJ95(yii=6ivEOT*DN8b{z zbp%D9VB7M z#mRDh0A_dS_yP=h!xy4lCWr=@`Kpf7d3*zq(`4fuVEYme<>i511Crsu!4|q&zp$F1 zp`uya3PtoK?8uM20)dW;bD`W&Aynp@g|*S@GNFWhKg{p6`-$M$>8Y{#f*p_3d$hOF z%;4bQ+GU#Wo!~7OGX73{;2k)-?o8jpJA(JNPfVE4BzG&l1?EL$ivDp~-ht&#@)U5B zm?8W7$0OLy62CV@WCC!>2GUAOu2cNgH9iR)er)~XV?{y6ufN~=>mnX*=%ZIFtFfKT zTa%&Dg+lQC0I?LlJdcUz z&MTI}@1(ml{xV`a4TI^9uZ_LEqK4?p#Akx^mFuA@K*Qpv{aqfM;xVY=458BW}LjTX#Hs-=LHr3GUIvXH&~kb zgj%Ke?G4pj4d5{p>on9UY|m*OotdSWYQCz{Ior=yEX)3JH-yJaYXe!t5V_YYCiY?F z7}y|Ow&SaZaLh3S%iBVGWLkGS<*dl+?`3E}z`GQLuv~MBo6ftdB&0cj5NqIG3|{Cn zF}S6hbhIT?^klD9x9r4E6Djlam8YD>eU$Vd%tMtY_U%pm(Yjr|z&sHM4t-cSKO*Kk z)$EQ%C3OjfhldAk#jdXEw7cekLQ?B%uWnm(r27R12K{kB>8M1afPdI4d{F-E>Y}(y z$UB8oT3x{SM3l# z#QCLwPP4y24lq;cnVEact!k%WX9vsXqhTwF4KDpLo@9;})y8Js>#A}W(ri&7|IEPI zf}K4h<&DW+3wTeJlOSf-&sy+%Ush4kQBk!NfeI9!qfGWZ0NNGs5;uF9vAD2R1h#Gm z;_HlR@C#7~hd`mr)2BsxW#SzW2%t?WwX6-=XzR5B*^W=IhB0b--o2xvp`npSV$d(K zj&ORd^4yn{l+Mib^j-14xiju#FkXTBIwv-PNpsn`U;B&fy{iokxRT+Zg3;mo6d@_5 zFAfWs<-w{_ZpB781_T7?N9_@Fe0Uy_33|I^N$p27!-%X9^p7$3{Ql8ltmNllqLQXV zRM|Rf$5U=MCnCtb=qI9y%Y*Sv;n0}|PyH0ICRqY(17`R2Wl`_GuODx_5?)9@V}AJ$ zr1|DrwNv+dN}@j`dzgoYkPGI2l7FD|;X`h%Xw$UWkTFHmRoN7B4+sdVetyB=4 z+Kj%Dq<JZ=kFQ!Aqi<-OOY{2pL+E7np;v*a)`l5e|QH`rp5pZ;f12o!0+7lKN7J@ldyUQ zfZjkFZo1TZ{IviSR>40_yOWC)GsF+jD9mU8@=6%-Glj@%CG;)0XbiUOovtV5*}a#< zV?QvJ_V*5~)JHs#SMg1z5gk+k%`g6bD5R>2CzzC13fhZq|L?Xi-T1BUTmtLr@lTkW zXa%?uWM{m&b)7djpZ^bnwu|Tl0cdASyhcvL?awCX9&--xx~w1MAetnTeb{lB^Rj2X z_v|}0M3!VkwM(10nq3A=IjQwTh3t*nLV3S`Oa2S(`xHn%?c8J)HIE8ZyP!3`1rJ%{U0I+OuDB27t+Oo z{rn$hZS;&PEC~aHPXAhJ^9F1K)hs1H9sQKZ#6rl-WhwxlAxeYdNB231>fA1Dy0uGW z!iV6>2?Er<%7X*OmHM7^FL|lqjq_kX(aL~OnR1TY;KU9vu@wH9|5+NC>1`6r+uDqb zBtdlvS4f1L1>*gh1?6MUqCBO%&&l4GZ!sYtuk9M$EiEo*S4r?WUI!jhtx`ijZ~(>r z7fhO^S;@z70y-j~+tkSP_5LOZXL2ldNGt**sNlG4KUSb&{Pqz--}iiG=kGRR-q@XM z#-OtQH>Bue`9_Z2cdL*n=n^EG^nErda2$3)PTv@Z?%KVOxCsnRBTS44TQs0Rw7utl z+yktzj35BgviRPr%(Sm|I)g%-lfm8_2Z#pB-(c2p;Zxmx(@* zG!$MaVGzBeD;vwKt#M{fAC*R|K+G zPM_(cSrV3NY|T*FU&|Efb$@=bKo(}3>AQ>GTYh@*FBd=!bjz5jm%d}f5592v;*bQy zq(|~XgSB0WCw%V+6@I!pU$jgFR2U4}j|pv$S*fkKFyRp@OfFq9Yu8Voj!zCQR9FcU zU|}inj1=k?Z!HcVagr#gCC9FA3d-SGH~1j+aKRCs*3VDJdyaLr!J}bsb8D zj>syV!^RT5J=gNlk-BU908m>!jFW^Ym9;%osc`D>Y)#PzCw1scXv6C#O(xPYPVx6h z0dCi<@5L>h&QtcKMJ(9+K$PHq_T?J@7-gb01>P!mozb_$HMwYRYe(HE*RM1fM$(4 zyjMJV@OTP_Y}Bs1G&KAvp^o&z&z`!#>9ncbKghNjbp!^6^jnintWI?7SS(G(X$hhwoDuN)%tPbTA4adJAfK+aa$X&L z(>g}tp6_jhmcJk2s6QTfAID5Jgib_I%`8m1dA!Ql%3=>=2M#vUpJ}b^2SX%7M%&TG z;@(p*V7I8Su-q8&5S0m+Ex6-KPnZ5b^2aA3Syc1sFQB}XT{@_qYtuw*?>Glg(NR;Y zf+`G-V^#|zNqo<|rNW)st;v>FHX^KJ;vyoxN1MsY@sZ*%X&$9eb%2nrE?;@4?V)<6 z=!Plr(Pc!wPH7@l$Has*2)Pb>6eDOsEMa|vVZ^Ghe>Y<67%W4N`w9H9g+fj?Fj9jS zVIaFPJ68f30w@w0LdmbSjx5xsHVPjaeAwX%v^EX65dIUJS97$!5uk&qo}6F8=^eD ze#$cvJOiwPU<&pjy1e+bw^Lf~tJBGCsD>K>Keux9Q}}g{UqA$FT?S73Sw38@5)7rv z$;McN18HFu;7`_pFJV{&fZJ79Y?1L7(4ez{2!7G6>4JF?{{kapAfjuMxS3$ z*pK&JlD88arJh|I+dDX7HT_O5=&eLj$rr;a0O$Y=BQ}v#7zPjEEOeF%Q&8AqUekUn z3w%M$*KN0257WHc>agc%?0a_V>%%Yus~zEwqb3O$DD6t*+ty^s#8zO)H`UXQ!EqAe z?1$PeAC902!3SKm8!@~N>~cWa1sU&wry2FOTP}>~hG&A^lq*urRvkiwg|*o8?dhxG zjbx9Zm4=4Epg;##o`0sfDn$49brR`Y9>%1V8jOZ6ulE;FwY3{aVe}8GD=ybh@!aO` z6EBQVh6~j-JKKq7x6G;vw9UHf6&&36_Tg>B@HlC)7;r+miMfAQg#J<~vxp+?MgETT zd?@&_#e_tkB8Aj!LuxIn5_*1RYd!i?bi#EussC-Z4l`1SCcr=c;2j_D4}cSoX942(lZ?Q4 z^F}SH55ts0{}*w>x*r4?D<-n4cCuD`&a#cDO`z(qfCB?+?cQwE2G^R5v3p*#o?y-I z=H~E%2H?ZHyKGT)RI4~GKWTHFo~}+6=`Cw+ms|XZ`n?y?=5iD^8S}Zv>hdDOdG;4y zBYs!Ra9<9^aOR2Lp!|$yp_{OG9=@a5>Jq{2r2<=ZzDiqau%93V!Yc>%d*db4^_#8% zT-}b0!9W>0m>n!L)nsX610yle`O~$(%dU{BW8%@x9CFQVq*|9D>cRa;sw-Y-DaI)6 z)qIX2L9S1gStg&?g0M`ROB-L4v>GgeYB*0*R+V0z)+hI1Wp*xuHyO9fsX^^1OyDF1 zh^wvI6X|debv-#+c4TZ!b1=Mu)Du=+@gS{yJqycbu0RKuS)#w_Q zT^Z;bFp^*!qF%Pl1UG2*|5qMk>3qU2^9{b&Bp&zSJGCpd=cmoX?J-qT$8$;ycazZa z$}}>pry$7L3ZrydH)sxh_6F5}jl-9njXgZ>XYh>3tmTh#$ zzoh^fwHOT8Av*{(82^UldO7+(fjW6phM7x{`O>ls6l%PF|92>$S>=i*ENeBm*Z;T+ zQ%OtI;;@b_M%iqPic`p;Qh+r8-)VdSQJRRB#aF1)fWgpfl?b@g5;Vs8WFYL*{?T5C zvemtN-`qWae}J3!i^&oX4Oho%6lo$fYmdppsN%Y5WC__h^fxx6?>op z2o#}ugOp-Iid2hT9+CmzP<4aLe50q{ZTrOGk7>kqRgrJQ#Tu?ry_blw*JL0fe;L+6*;_qqr^a1q?Mfmrc65f5Su+ zf7p7a0y-ucueZpc=^qz93WdVl?bUHb;VUkd8KWwPm93G#9Xu1IVfVC>SX(!PQK;!Dl^kyov& zxvdoei<-)o_EO^edL7RgwglPz-KvkWZAZz;$#Po)^~~D@M=a?q!k)@k7sug9>Mg0L z2LoTt?tB2Y^H`8sLmwib>wpNXUaomcLy`ZHg$YpxQ0?)@WBh=W${TReImHu`uT=fn zLKT+sgWu32+Rv5UL zap+_NwB(Vu(^t8~KwzbgT&5t@0M_ltMUI69BmEzx%^@z@598kOwiy8QxH%}!eIXbW z%9)AOu}v6Ofw=TA*uDesMM$M8P|5B(=Ji?~`_+c*09?XJ#OgfX<6a3_x(m-{f4>F)liSi|0S z20A*3C70DO!3>IuPVfw6jJ}v61xgp0JXPzuG1ep+q}lw>c4&k%QW9AK@d^~}v>@nm`Kmzl_CRq1NYX)iZi~n+leRSCAF5;S8{>GoG;;d&HbmfH)3gr@c=pg@# zYh&5z+S6We`gZ?E?rZF(61e=L_t7Ai%VvD>Unkv%!NI(O8_e_n(2s3UJR^sDnzUFS znzZ!aO(H*jJgBJQ#E`;g=^@h6gX;QTMc;Oyv;W<3J;J>Ey{{ro{F8ogQ`HZ!m9GS$ z4gR=LMZlK$Z|JlNynuNJsL*V2%z_xcj}Ds4b~-&L#Z3)pwQZcgTrl92;( zX-N{>-&dOkAzO?6m6VMLc_HV2nYca^L?-Ei0s^!c5|YnGc(>^w2>SL*Q%cY=F?CPP zfj7YXsO!p^q+5e!H7z@{Xu}|6I*-8;nRG>O_!%_glRRDcZ;31eS=nR%8a%L93EZ~* zj-vjnE#D&k8=_q;fMGCO0EEqJ9%GJ@8=m{DPcqay_jq$`;lGKs^cP*bH}?kw_h5FzBZ}KGKbID}O4yBBGII^Mse>`uG1OvjJJ)@u~4i!2VLtLJNZ?A?q*Bz+|?%D}M zluq{+s9Nj>XU76+Z{EDQ+8U!D9T1R1MF%2#7$`p>1M_*GL|z@zgQ`W0zdIWUiax9+ zr&`+_W9ReUj7^~I)ZF58UR+TZ3oi$S%ruKe zL?|N6(98CmDaDgPsuiAYfHVRDO)dPMVbU(J@G`Lx5VJTUD>EAmL<@@qJoaKl&j9~U z!>igP6G@-MA(*nn!i<}`(m6KX$w`fNUS6I}2)&0dIIDpE0|8Laws!X=%7a_t3rWYY zXM+R#2&&!#A4CD@)$*wzS|CR!trc^Yux`=Sf_c4>Q+Cidn#B0<>p+cr50Dsn7rB z5!~r`4=(;1dw}!Jc|42+{KvmXmG(7w+wlsM@3nuGjt@gP1|^q4_G+(!PuQ`5!_8?q zVga@$pDT0c)ZFBwz-LVP`}p*j7^~usAAn!>p}|a(fI&|O2mw_Eg?oVA38)HplfHco z>o)Bg7%?p6De8(JsM*(?l2ugvBu7CRcm87~wOh$(VG-s4FOh^(67< z7)gZC0!Ux!ocJdo2h;f{g7wd}I@`a0_pXAKOySFyavM4-J-t@qK{x@;YwQQRy9&Ya zaL`D#`01-(fb^T^86|qMyZgG$o^N}NE)+YZV@as%auS)<8O@LbSfPRZ6giXAq=cd{C4p zY-bFR>`XeNRpWk|fHW>Az@h`iKRZjE&Z4}F@mdb>A3aK)rGN4BqlVMs?wl0@cb{F& z##_&%VdYZ5!|&<S-oALn!tsLXL5cRqV1|)UH!lmE397zy?VD77ygu` zK|rf=+9jb>7?4-BDvTk~8};?|N5kj_)iH-9DhQ~-(F{E-HWj2jlx#4y zouZ4i&9)%{26lvGxT!a~9<$jObl~g5!_Y=7xYh9ZSs4ftS+w5wx@yIPTTN;GC4g!H z&wrZuq^8S0zS1i14#jqk`$J-5-b&jYy{q#as+{^2q{{3o!1EI&*(uq;1BH z+qrT{H6TLHH4e1c`iW*4$HB!K_^+_gqP^XxJc=>DrNSj> zz~q=0t5~Q}3hVWL^Tub}WB2XU^c4=+v47SQ0gG;gDS`7MM!(!-Fq`zkeEMhBw#V!> zPK(KwwW{Ix?B)O*%c*$IbMrP_%_pU}#~v8AB`qXg*fv?{;xxmm{o}$`<#63QX~;lf z3Us8r7{S&9-{?~`Y7dT}+L~<8HPR=~!mte8y43DJc)&5<+Sc-+GqbncaEuM2v_K)GM>LZ*=lW7VpYwWTZF98&hxLd| zaVS(;NJvPtC+-i8a}E5vR=GviE%arCk+5l*rf;&BTK&Z&pt3bKz7ZTPP8oOI%(XYt zR|MieJaZ>oR<(euXbB^#5C1rdmIKNSBm4aeT*CK&p-9w`OgROU+B|O0QCwdm?l`O83^>^BGM9V6J3lS5Brw(Q&qQ_jHo%8L}#_^ z78y&rl2zYSoXj6Kvcev`FZ9)0> zo3)YNwz9V7+1ZsGgQ3En#S{$}%w1+iY;hP$)cQrADD%bc?ygF3Jf~`gsqAo(x;%zK z4(MIX6Q(CR%c}oB6l)zC-mJr&f}ogJI@Dhnz~BKdW9P6wDGu;*x7P+GtjFPl1sVDy zr5O^s6}9nzM+e^Hhfy048$Wr5Ml~6;0ivHtk?xjf-Sg!7 z2gvc>zn&^m&@uXfMhUu4L~H2B@s!Tr=4c_PWGd1I_q}a*SlV< z=Hd1YAK&;S6JI6{at`OKyRJh4udZ!#4z!~AZBfqy+CjI6jJ1vZ<#J;@Dz&1>NIja5 zm;5`Xked?k#EBuG>Nks)%E^(}^9dC7TC$MWPbwJ(U~OI z6SgPpK*W#39RuW&1lESKL9#&2!L}anam3iCzN_&v57+3H@rHU2xY>!#)>yrEfjW$~ z?*bES*P}p3D~Fo{lDQV3t{!iXZK+(Z1i1;I9Y8S%0@1X6rOQyM#E=t-+SQ9RV86@E z9KF!D&Nc~v-g`>ZkU~vFKt@)SArbQ1z*VkJa1yOJ<>oq4?3U7iYYe%`zllS3_u(+g z>msr9gv+vDWXE&Ypod!%>;IC%q0u)F9a$a>V^ivJ9B1?<4T9SN(`9kU=69dLeR{=T zYq4M#OkeC~fD|Jj_vF|usPllrB1ZSr?)PvgA1R%k>2+)zfGoE>0*O!;DGW)R>^}D3 zv9&gSg8A0@|A^q?_f|i9M`N##brrt$o(88LtE$>K{xZSDv_uzYn!XioyFQRHj`z&* z%s(!YaXITA?hsw(R~xJLjPP>wVyiF@9QFg$d&Ke~>4i4AgC zX)!Vc2Ci~M%t@71jDNA(`03oe6AvY41%}SsMVHgQsl`m?X!iGlPI|8yO!@4?45atCdN4HGs9-DW*vbE*@FT!R-f^hxI;GwFX{0Jc)n9;Xw?rJbE}EqB^8%#a5pN-wrEN7Z~C&2T4) zUVcu;bEhKxN;$yHiJb6*Gdu$4t7S2Ai)g zHYW0v%Yr$JXBgbP8bHrNK#UI`{~s})dnEQ4Q0JcdCbK0cVZ0M?hA{{ClW-ThciKxr zLea$l3+lpMuPE|F=`Qsnk$dml?>r{aXoRIa#K)$6o=RH}`N90|N4n4R`;zzST}AFa z(t2KhqQ~8_?FnU!+ccKGZl%$Az#q`u^M{|^HF^xoV`UnNcakiWjdJ^^vakHJYc-Cy zyIN;Vtng%U5tgOARqinek$Fc3VN7YYZz3WhyX%d}-Q@&Z_QyK1q@-m1a1U2|UP?i- z!5kU!j~{YRm!K9>_q}y%#ANgc2X?Ag3=9nDn9~A2HkoP0qKpD_=X$--JZ% zmh}p<&^*I>KUe1#&ifW|cC4+Tt-TQS*0&||9u{NlMVTCYuj%Td6=_nG&S0^)KnXb| zpG4sL&@>&YTpZ7z$F6?3z|CRlqtsDYqY;DXf3+PZbA^B!s;Fz-&G)sr(cin#R`fHyBhS3fqkAK+HV=B6J3FOxrpxD8tR{ZGb4Ynb zL-qbRXw7ioF_xb9(Qs}3Wvz=H+WWH9B8x|&5ENQ6X}T^Z@eb0~oggSJbMr?0h0Ahz z-tXRC0wm`V1N6;EXXpLihTYFqr1(Ui)*@&i`3eyc;jgU+s9M@uzHTJDZM$_`_KcIa zn6-}d$kj>QsIYAxX#GwFrD>I-_SUXYaUeq#O-v3}(|>QqJJEZG+uTcnsVnl*{ZKVA zF`JR7uy5>d)ie3XzCMMzz2yYL!*P--uZxQ6X17A;)ltR5ftx;l2g@(nDMih6G;igk zRYR_Qje=r5a#*;{Wj&hesw3sV7R{u`$jr~fm#&(yPX&>4;d<6{rKtnk*bWKpFZl5< z7eH|)G)g6Ndko*_;M3B*9JZC7(K5I(k#F2}+>Fs54X7t^vi!66}PMYzMSzfr+HPydX~saBBP^Uvc1&N8G&85L8kdGUh{o-u$=LxcZHdSo1j4L zl7<=d{ml3_()Q1^oTdd0a6_In*jOKzA7BQBeFYE~_v39Q z8)+#Sya_3FK;H|b48Wa>`V>D>c&_#CWK%cUj^A_FhcL%dm)qV80{KSuEn`RE1-Gqa zxRwd1|3l1SMaxWpkN>OI+sn6|o{kR95>^`!&}3gJD)PWaT23ySQ9bbn5>Liimm8+r z`uzq66z1Y`tg+kmB$3bl`l}GKce@yT*6a0@lZ^AujYryAH{uufjx3Q6$fZFI+vQ-A zc@Om+IZ}seoqeJjV$ar9v(?cblsqnrUz@hFRe%ft4n4Wy1xmk2)<(EzhNM&UP5$ZnNd|*9EPoWWf^O|H2^XDY^b-9Y@sGav>Hi~rj zqv)$fO1SuF5V?5HmeUtd6!v#jg}hrlqp=O}Sgl84(aI0t&l_7ii0|`i_dR_qSZHWy z_}bu?SR%r%e=<$LzI-K41|m12{Ue8ojZMT>q|mfGem*e`>k&S_`5_M=^#b`2P+u>I zl?pOs_>9yTwf!sP;i9^(uJ%c(&vp+A<3N`Nj*pw77bo94W`C;nD}q9vKK{YPO@jr= zJZiN?<;Nb6pOUGXb6RM8h|TP*3Q`Ux4i6lJO?iAhAXLwePCiKsa``?PxF4)i6d#xe z+ZgJIAhbK6xr{g0x}~kDnI=EeusT@D0?ObysZfCqFQ0rbPF~Ql_Lmc+kwtvl_Il&) z1zz(uLuZ$mL^MFpZq7n))LsO7@uac9Urpy zFFfbf{?@+%dz;0KK%$X@BrFv_yxktfD1O;N)zG*J%_k6e_Ekg92-Jz(S~Z-hh+piv zeU)MoQ~b6pElu#sk^^QL$}DR!2bZhCr>TCIb!ytJN(*meIW3_^2|W8gSjqM%JoXM; z%O@lFmOH0w8?u-Cvv2UNK`W~vvw+U&2?m^`FUJ^1IKpxL@#Ova)BiF~`! zir+rVUc)N#QBhq|$+{$m+*IeI(76wmpX7oq=X{foW*1DMEVc|-Z;GCkpe^W8{4rm{ zzUV~ebJ!;9(1_kp=YOy{8*)v)x~Wq{uj2=3;QID!sC*;nQ)0hdzIVoxcRo5c@vS%* zF8HjSYJG&9jZvq<|yVP<8$CGW*(Oy?c=_O3RKA&A}0;uXo zPsy0n5J#KC(lWPCHm4*=T^Xpv!gn8)qpY(PR8Xn$etsf5?sx7?S?1AOS~la(=iNFI zr1*P;{chblwg2`T4|_Y~y?n z3ZIV@>Sr2x1FSB`$0cQD5rxw7vIU1cp*QZdUsM%a9YXamT5NorxEVp_mveDca14ZC zpa+Y#ytcU`y6y!=Yo$x1ly<)Nlj)&)C^)T?RH)e1bf18-6FpdOrGL}?d^lR=H|poB z>-~94sw@rLIIFYD$~r zE##dD3WhZ7X^A&N+NDAwv{eFqQjK+jyPG;+ShHS+7F0cEv7U;F)Bn7{J!sGRlH|Ma zaX^a1837+_-mR~43<&?-MbAHDj|2aBn*XWx%i;mw+HR9+w7((SU;B=%**5jsS*McB z`O34NFY7%=+0Sl@QLPy1y&+^4H#Hbf@DA(JpaacMm_ep&tbhq|2!*iCwnFm9v$L~# zOM=SI+Qbi)O3|b_B3ZEomP_pp_Rf#>HxfdJM@F7q>AP$G?3rr5ag_`uzjM6J>Ane0 zqrtA3D3+x5yOX|n(bHL!SGX5j`SSOol`ZQMLzv70O@lj<;6r^5)*}jnfU+EU5`hrM zB)*c$N(mV!4p4LBK?pmyvYz_ex7SQ%Q*b0CBo4jL&C54NA2Vs4H}{ubHi>}RjO6w1 zO?m!L+d_y<%1!p`Uk}&gO76_$lNK0y*n34qI}1*JvapGM9utQ~PoLp$7cikOjhs9I z4a|<0_O1o|{)Nj9tfw!CnAQEk`Qa7=Gq%OG{(eQtuc4x9YFzsV`(ZH&-$R8j3bht; zLp(zN*5~|CY`v(|<0X6!H@L7N^+W#Nwey_KT<- zX!T;mV+$f#WvJkj>r^uAjMi2tU_jSx)`nl#X5ekB8)})2ZIQ{6d#R!AWbtBJ-~BN} zQ_9z9KPv0ge&L}N*>L}CY*au-aGO@TlF>Zk#cA^r9ft#)ov$MOUV_LY!f4I4stn}d zYnJDKRxjR)i49}=)UcagegXZahEw=QuzEL(pn-gUYO&(`r<5=NuHg26bUe zyNiw|f1X#>)cop!)ul7Bi=G(3Ug&#Kn?KfF20drN6#f2yKbdyp&hFl;l(#f7--^;r zu&W<=pTyV(e0e_-v<4OvNwk5i$K3;tAmy64$X6}`bQRUpH`1deV6)~402*56PnFzFzzGd zWtELANsxCQYxDyfKgAnBXe37%qs!8wUO}#yJZ-{_8zo%x)$(5! zyM+Z#42Q*}#tzrpM~?`!QSUXSq0rw!PIJ4qOoH+;$dm)690J=l842%zi{fP>!u^#<7R1^=BX`uvhqMrlb}f zc)b&O9)k$T(Aez{)89|4c@FP8drY`ddPnri0_31IKHIh^(3s$F$PAs zKdgT0xvJo_KJZSbSa(gc^u9_$6r6KX&?zUvt*=}guC1YwURsO_^lh?h57OVhmV>HtphvueBUGZd-=55t6Z=9c8Z~^DnXE zxcNP1`-W9Yw;b}M8d*Fj`&uixUMh8_EZeMF1mJoMN02hGBW_v~4`HRc)ff)>w0-!P z6JBBMOT4x=vOaEECZA;`~59ZPi?z?iR^Y*3UPDk*E(zpTt-E`TaU$rTGP?IPNR2pI!27{Y1Ns`4?9W9g zh4&X{XkkCm%J$qR76eL5r>CRi?e0?7{LhRGO7ReKN@o3s4WHqbY8k1|^%I4wtZQ8e zclWzStG#NQKH_Z81muiY-bppbFG>;+s)8bVPJ<4eNcr6f>r+O`y^FRsgYtyCTl}3Z z?Ux3qK^0{V+x{mv^xTNZ_*@3Y^w0H3+xgKK6j-Uc0XVB@@K}&b*24n?KdTY+&7i3_ zmQUYAS}dnme7});Kp^g7O;z;^VUd%$x{G>dU~+iw?!7NJpLm8-WalfJ4@6(xiQXEy|uN~U!lvd zQ#w_q371^bkK_+Xla6VW^Tf^L0r!U)}w(~?q)UJ)UbD(-W;p4 zzpCk}x=`!5GEp|Lv4u-zoxJWvjOq_uo73x2B~qU9_*;`#EIYgSu(I%`B6aQ&S|V`O zo-(FuxA~2}27M=ko%~d1<7eHua8_Y8!W$o+bV=W-{58;2RAOw$!1`DxJ0ya0oHJal zpv8=^c=YPf+&s&HU`DH?GFpwYZhA}a_IbptYkv5yNCu`#LgYf{(+-E~2S$1WMU$ucxGYs8wCH&nzM@BaaZ&25 zPcbbldwSXyJCys2JmhIUQ#b&df+sKPQLbhg4UJ6PeS~Ru%VJ(_z#V@aiVznvK0?8f zPxT&(Iyxwy(b^qEsQPUjkzjuOa-e9KF0WY4$2lOXQw>wKX#-N(4@g*_z>|`$eHd?J zP8OyBHI_FJ=$A?iZ_hda7o^Ba03bp4cgm%K-N8ij*1^HSZhI57LH~n3Gn>4B?{SP5 zF?ZV+I_15c3bN4(4_wpUlu%$)ka$sG%{DgFhoAWec(aqTG#rK-%T12=^qhK6@(4^7 zQwY?r16PLpmxw5Xpo{bG+%O(@baUwJ+ENz#ws)~~mJ&v8?j9WgYk)#Lh&cEe3Ki}M zl(5n0?&EN0R>gt);#*?s?LA5TMH09gT56Jn>c0RMps4s5hm29)0-3L?y`llewKr0` z1N>j#7W-Sb&UhSFQ>#4R&tS6i(Ig)myNYL%(Dk@0{3&;;b#TBw+FNM(W(bmEDo_{2 zr+mQ8371S2^zrKEh@OR-`xT2?oG}goN}1Ibo0poZyd{E zUGq_%myhp-K%x8cC~Ol|W53|PXg1Y1*E~13M#l_Xuel`j6>hV*%1rCC@8i9DSGyrP63L*{T6eShy-WJTXX@ z-(_~8S7^{9@yqGQOZc(8=V3<<7RS9RTXFC2#S%ecRx%F&wjm%ONNsHZu(uMA9Gj>u z->^p%EOEsZ+M(pY`MCoK5O&Lp5Jvs|?>yVyFramBTFr#WBTldT(3o@C_8VqqWsBr7 zig@Y>T*hMC_Y8oW7*psVCOH0edvf%@->UT#+lj}@~m_vBEWzY+Z zMfQH!7LjJO!fZINCZJ}+ym-HQ`hGu1bf;u5yPVlH&&$)OpXYusEaea7`S@Ds^wj9L zG27zG%7&*uO!r}1H_6g)DR?drZ+u$iL*+M)VfqwZ>M$`U6%LTJIlHuU>yE?%8u77D z4OK%*#_udrG!DOp1rB@ZVI@AM-?@_E%gM<}s*{^omvEP&QNHP+d?mqOu1NH(%)ZesPyzLG0 zFuV{sF>)p>SXIcMZD#oS&T!qpKW%rUeP6%t(Y!3#yZvk%r@gbe|MbF1;QHtA9eQu= zf_$%SM!Xta%gOE=q`^85Dj|u<{<0^D0Y6ioVKa> zZE+luz#=s2`(`0yN5xPi9+)pCA&N^@Ha7Mkax+l6W%RO_rh_j|<~BI}ioKwU&TCnS zTpL(!yohC7EdzrWsENzs9(Uk0@bK|MMy7V0Z*7jk28nAzzGDNi2X;YEc;*ZUGro2? zqy>IN$Eme;<#Sm<#R-@D@C za_k-9KWze;!G;&x7ynmS#f4+ZifCwS(gd0`9ZKe#*xu_M=MsmSSH2xF%?oR8?a(r- zPrgpj@2_lsx*S??SH6dvZ`&Y)CC=)Dc3zDIL3aK;kMfSRnAjUFEn@Fedx09~oo@&< zYGQJ(&+Bf3ClRGTPHQQpgwqpSfT`X&-fE3W@yd@V%*$o$f4zON^9bOc(}7c9H(=xr zrN6hISkWSYBX3KNKV*p)mLCYO`m;WxE;&w&KpjuqrjVR-Ne>}gdakfz$d%A#I<+&D) zI>^j1TCznL{BEaME5aJGA+nOOw=a$DQz;n!-O~dz#?=K_vmY-z^w;n#1D3*cP32xc=I3RKeK19(}(3Eq}Tz>dFl`2_9j>wtxNo)eeO{=&H%gblugj zpr<5*!73nDH=Z&6`DK3oW2j#1+3vp7k9)qJd!8hf9(*HnmU*$ep(qyWnYCpc}5d1h#*=Uf14bv7fejD<Zfla_ywIrpHaSqL6SY3X(B^?t?KEo8EesdUn(;z|sB8Y5A+>dVb%xxAB5 zFNnv_91Xp8YN*W(5Ql;jEry1ih1=)ztrhVnhs6>08WqAylgElIww@#E%A90)ael=} z9sEkVMYh8Khpn#wt7_ZY-gHWXG!lZ+Dcwj2NSAaYNQs2BG*SZ6B`w|EEg{_O4uSa=^z4uyk%rQrg@!mETEjoP7A1@tF^qOhP;UcwmoKwfej5Uh3 z!#LktvfWqASJUeM3E-YzNvgAy@H^B9edl?%x4XQu0`tQJ_~t@?L0w`wXKA zw+=F&yymQeGUaHmSiPM6+V+wLJJ*Q39$$Xs3EBacjVw-^V{+lq#o>9Ws)W9_a|c>%prBt#DU#2azOTQ3%&jm`NmNucMq7R9z%g&aGE?TF@4G5} z^iL1VJ~#a$b?T?Qb+7Qdy7BPv<}b{ju~DuxpL-3f(&I-(N97A#I5_qw$K33A?yocm z{+C493nl#75ToNhF`Xe^-))p~7X^6ss*T18)ppcrkLL)GZ|Z3Ab$c(=y++jKY$S7} zTjEc?n-)bQH{+y))rMyLesoXXne})zt_d5&TBOSFbFFJ4RW$V+DdYN22Qv#J%z^3X zQ2p{NGlFZ|d=g%J-&tlHbv}B1TVu)*0Net|@HazoM(sLOkVb4P z`ht~3OP5()!Et@+fe4L2U0}n*z|7TX40U1s%S6T&%-H|B8@#vDSI+iZ$`V#JgC9d* zL0mQeh&Pthn(0u_nZ^EUU=Mw_DT<1je_C_7!1K{J0&in(_Ae#lm0oDFeLdH>_Lrp^ z01Y%PH}h9*+X(NpD>HUe62CZ>cZFd>JO!3bzAQ)G&rc}Q{Y>2|kE}!>cGv2NupLu$=aibo&Rh&38~{T8iW;o2oL))ybLye71$SzgmfHc!!GGz{X{<0Zx+1bX4673$wa zv=$LvK>&LLAwDO2!Po9ok~n-(nxpnE#PiW3o3YIln^Yb8v(@uG*r_;?ccB}Ijn)sgn*{>Giu=UNRH75nAy=1dkA((4B733xRivA+tKR$5*r&wZ006(nIyM#Oe8rh{`le=3$Vb2m2a zWY%g1gMhGvpFbrdCpz|up(1@u48^~(sDidoK5SyUu~DkVqN{Hc$(|0^#eG)3;ddCL zHN`jVdHL3~@5jB+YH};Y07M5&yeL91PZDdHd1#T$JJ^S_Wvm63X7L9xVl_RVpc={m zc=rD2_NK(CwzxauSOA>)$7!zfiL%cxP*Zp+~{( zR(PMmL~sz?T6ZWXqj4!|b51xvN8<5jd}OACo+(q%YHs;rXwKj+m}j^CYv}2`5t~ib z6A|XPbP$On9IX+0GwG0j>LMYbfGUb*x1#Kz3(B^iKx8CDRoh>NQV3(0*$42`V+o=j zzjruVi)W+dRhMw#p=zgC%;Ww`{ev&$X3okYMn1WWXy^MO910IHu_`8ZJt``0s^&Tp z5u~QU#4Ej5rIlYg3aTHyE5eI8IQ1S_B&U~gk099!c|2DS1Nr<)HRv^yMBW>3H+ie^ z<}s={JXK2=nVDBvW(g_)l6$etb7$|TF{nKj(UOp?lhZRJSz%OLc#_{;NPDdM6PcX zp;=Z^DEA-&J+t+gz)-rmplHqNRr!*XWCa-Q?`w-K+cru$1hoYh$hb%pP<&uCRlE?- zXN?HBZGa5p-;xg-TM%X+53-|*SfE7$g?jt&035&4vli=kUI&8DAt68ie5vTZ$)~Q) z5_NV>{S{Vh!OzXE#gvE_M+9+X)>^j;5~>RT;pm0+HInd93R27~DBu6*>NF|U!HP$x zb=BdS)odLJKrx`oKuQNlggcWZJsB@sM2ggt_(`FQ`q!nTRV@vMmHs3~22VPYNyET^ z)>5Jq%w=`Y>HIg=H+Wpg2RcM%S;PYP>c3zo^Hs&fU^iGa{Xk1v692!E;h`UhB6^&p zp0xE@%Lw`tz4OkwwOrB*GEvdE0kVH1(?aRQW+c0HEc0@PHW56yv=|n=POTkwG_8W9 zs%m9j$6tv?==-VIr4c(~+ANWOBT+yJIU+6%0Qi>MeB;?2`O3@7|D>-{HauY}hb9IQ z$xE;mBhm68TXM2dbop^#2Xt)xx#o-pDpgIe7={nkP{kxj38G@9u4lxBmmb-5;(y#c zq1?nSPb>2Y^g(>HvP>9tYO(m85J5cUuZM$v$+*ejGB5q!D9>*Y zUgxm+j}^-hCUIy!MV5nNp^dD8@PtnN2NYa7d62a7`^So(8^^SPh|0b9Uu4Ml1e_-o zPTB=HFETRH=FhFp_irB6N3$nk`0LJW8LISU0AzC@k&EP2_UQb|-%1x7Ta5vHrsZEd zm(e2%(opw04Hzx=*CYTg>L2$eDS9!23VFH_3I!zHN(Buw21hKirH(sZAZ-307Tfy7 zF-iO8>320ub^<63qJx4$I|tItR>!wF{_(nWDs{wz%i;2S%m$0o>bcA31e44d}@;5dy7-fGylfg+1qiN{2Gm zUzgzNzKL5`GE_AWO8oU0=&JNwgUP(UZ^z64INIc&G!1U9r-jf=UOoY6sNr!r#4;PW{9iG)RrWqt zzH%C;o{?yv*9Y+D_gNEDQ^PxblEa;nmQN}w|6ROV1ph?aak*)ke5F{r_p7dCC;<{) zOPJ7X4C#A!1V;RW>w6L>liSM69gR%w-oAZq!k)0N2VJH!AU-wgA!&|$TKMIle+20}EV!`y!0 z2GLm1tzt=I}4W$bK(7MYMF#xgVQfUR{5yE5X$Jn9lN> zXDUC|;b7Ja?{SF^5(M4zfa`?DH(I&W^3Dt*vONb!abwYC3XQYCzps3nkNOrj*nXo!tT@h$0=Yuh_~W}lK2!a>Ykh)G9>Bq7m7 zMa2g=I9nP3(rqriZuc9}H*BqF`bogCKvLIuOd;#;?f>Hg2%Uiylo_;%CG&Z7|GBLr zO}NpFfLos7p@LZ4iJ!RYOD~&QT3R2Fgkm+DrsE4_qUQkdco3N>%?~UpXP(I?Uoj#e0v!)t=#9{%V>kyH6v7cn=hk z+9v@Ny8M=E$S_U#qpC0J0HWFITmx&rct|0;ZUG&|-d=q)407 z-|HlYcIiMbrR4*DT!}vf^84d>*NKPQ7MU~iGeV8xC0GdO>3KUxQ~g#b3TpGG9m;g% zh|e$Izaswa_OW%S2K&t=muR%)*%`U>$)LxNfxb_^DNKtWtszlSD)s^a%Uf(t~m*^Jsup3t9M7hO0=6f?IHM341b zU>G!tR=;9Fb0$rf2(59d&o4 zt4nUo`JHwJ3!RrPJ553_?E`4A-`UzC0p7RgW#h&7ZMniWAJk}?IBV{pV{`hgBSSUa zpUF%-e&Xlvzd`gRzE;9rU>AwzY3}dcmir~Lcy{yP_+jhiz2N69o1V(J;*`p}7=RM&FPHroF4 zl^XXmNwBujQCP{1De8cNkQB-$1HU)T%oF6!*}WB zNlq9gvZYQPflteegU+(CO(oT=P5`twk}aO}Y7NAh3JxmU5WQ=VnuCUfT+q0ZIb$+{ zd!G|Nj8Q?~bUMIDD(nDb+kEZwi%=Wx9B#OBEtSuyHf!(r>AkR{dU&tG{wuStP| zU)kPw(!WV)&pl}Q6#YrG_9H)OI`)WW!&`o#=IAFv4)^TmCo78Nr0+tZJY zf`>1grnJtN+ceS|LqHRM$ImVz@QFP5gnmRPaZt!*a~7R$mX;FkH<5ZutsPfifNW;GwR=+&t`6Ift#-7)~jW_5b|HvLY- zx!|LiH(}ryyVN%rB)}`iD@9^TJX9>P(p|MS4Yj^tnAR|{^}Pm;&~16 zt{abGKFhwcTT>?ty_56Ytb!rDwfWd!iR8vFaPh$zWS4JwJcJ+y9kCGiqocXf>T>pL zAy_c-48>Eg{(A7NkIkXIW^1u7rM9Wqip>4tCsvlZ+1ggGNLE(%T5H)@)DF!Fu$4jc zkmhYa4k=$&3oguGPS9Up1Q$(M+09GE(hY8;U1{9U?@8>6)o@8(97w3XYpfLlsxlYW z*N&bQxusAi5W`w~#kWRJG}o!9fGZWqGMOl3X6oo()~lP6k%OwXXG}~lr7iqSZqkj- zJEw3Zy|QDFna$0ue0ih0gP1bNb{%_EO>AugdzT(@@O97ilbt(N|6qC6SycM0_l0)S z@yB>v9F;H0iOg?L&>;(aLjE>nY3#k8*I;a*8lR+oRE4OZg8SXfO?-n1{@1Rqcp+Qf zL~iR)zbrgR>le&LiLvfSj^{f|CEV8+JJzS}p3PyU7o|D%mrgEU+e{Aohb|_xHaAw$ z6`Z*{>1g2~*Jr=;-2^AqEyll*i-}QxiPQH6icluxH~YQ~Goj(P)r%RSh0=$u=cIx} z$iSWq`mV_d=JUDgLa)a0AQl@vlds|9BKu7Vg?@RIu?zol@*5;{Jp@4;401ld z1dh!o)YJ=q8nKZ?+dFW&vFHRKW5D3M9m!@PB8*Nvj5%c!KxOctl#EvIGkr<(wTfS( z00CaF(FZNA#IWx|e@8VhG0Llg7O{qxZ@L3e4j4H>veII}TH1YQ{Y||9n+O+8B-+Gk z+x(L7r@Ke~*I|yF((lLs;T#ZH#70l(_!#wzz9KS&5A#!P9ZyG7F&a*^a%5~|@I^pq zd&tnaSlWKdNP9`yYqh<*{oDwkJ6vk(h{;rj#&i#^YxF!|dKA)n>b@E1G`=VM%SXB7 zKIxJ=KrbAxG4Y$sz z91sG>=O`UUJmn^d+nO@Na8=oqng%O&~_AAYwC=~cDl;UiqyS8Z* zgNS&O3(VL2R|Ox6gSIrA91!DzCljY?3oR?ECv{4J^TBFrdf&w`RR%zjA&Ie_ET?;) z2KVM#$2uNyk&>-!86W|`@5aMPbKuRqa7hNn7}OOdJh}?3CBXSCt6{tRDwy6D`RIKs`5PYycSgax63w?wxy=7*>G zbXweIop!X)5F_;ZQP|mM06btrXJGA@dF=JG2!sJ6jh#=AA3HWdH}&*uf8W6wI(6@` zU)ERpE_?zaV@@Jc0wORVuC&HiO82KgEwKH7^Zjg4HtEY(SOw=A`jis(+#y{YeN6Ww zqEIq633IvEHss|6np~D|-+rpT|2aI_LWJ0ILu|8%(NkI1Z^tiy3j770_w0(c$`^VU z4f-;@d6yrzEg^}hhO)9~olj|u$EpRl#xgl(t86HV($e(38K$^`EkUtcp(d-EEx!Fb zv5a2hrpGIh-MGH#*h;HAIUpmr9be46K9v*`jdt;B!z$-DD7OHZ3mKUlyAgHk!Y4?ogZfh{qjVw5Q(4$JQOb(IABZKpIojWWqnV@5Fe*Dg zuvYuL<0?(K!K~{~A?ePnMG^PK?>RU~{rH=V`ye!OPAY%_xx8svIJ8~F8xma5W#7r>P*0&5{J-LP+I`#Q7;|q;s7%jA6G;_9rQig3MUWD^rQ}>ygW#<$S zkvI(N(yiR1Fa6oVe0}*TFs)s6=N^0JufRm>wkuf;7>L5fR;ZpXKLnz;JB0>ZF>xbh zdICm$-=oZCoQt=>&;SwC9C{8u4F8ueORLJTYYHY{q0jxS$Z2T0(U8b^Ocz;^Phlyf6kK_HZ ze-Z-Wt32yDu8Wp;P*QjTyt)F762so8r#z1J$AJPtTfJo-JL=HdNfTXP$*{w{EjCcQ z8(mmaQ6V)XSKaju4Vmc*#^bi%cxylz zJ-{KxCi2{z$Hso9{(Df3CAxPw&*3qT<=sM#a)JG2D~zV5<~Pt);gaux1bqZEGeoKm zYP+pv7!z~T;59N*(&1cNeNKyUWXGL)XdUEKG2)t~9q0`i4Q<>Zc3fB(sc^O(cf9Zp z2|-h}#2-~w#wH>01x^;V?2e8p@J)un-$4X%dS+(lo$XQ?_3!!yIEb=}iaqZ$Y4cFA zbP>>&I#T%2p|-ZZZDa%+q$EH}xf|2~Li?z$?@QEY+$KktC=|fVXiy~mW3aCsl=MfY zrLpkZ`UX52DOIB8eD}*2V38}*hhX6o<<)7lcSOct+I^7xce*Jfzu=O|hX?pp+3YjP z*%A}!z-(_kdE-?$mz9^OUAM0ftQOQeS7&h$|N5>rhB8uyQcI2#AQ%`fS~NMoU+kEC zbS*n16F!muQiW8=9+dnqPYGk;lSG_bzY$~lZVwy@fYKhg8Wly~m96-!)O6Ex9)y>m zp^7?nd0=YzsC*Lr(V&t(3(OWF&kL?zPtd5;2BLP$%WU#g7NfiRSfvlh_0Bd(b#mbj zqHV~HE-!D753)CJz6C^!XCHmo9!5-ZwrIvnJ?Vc1EY{C9WZL+BgL3DN83)+w;p{C|Q1M#fxK@X|UBh!=q#U0PZ{WzG*Qt@VM+K zn8*GcmMQ}b$eWy0kLUO}piAbk|MlQ-WJ>r6lOS&HAi_!tW#(|U2TA3jmCwNLJ5qi} z@=YHf7>j22`^yDU+LmHE&`QEr{chp2X}{;ovQNeE5)$|?UrHFv{*t-0KC?{mGak$F zj50Y?*_$=K{H|nIpslgVBj|QPpl^G3pZ zw|quXv$k!zVcr-_^*{OaX=|~94zw72dIN^eb)z4gjso2Ef7JrGtmA`nrh#~NEjoMM z?%rM$YRL%6xZ(xM=$(kW3YO+hFputNXY^^5$$14!qcPW}lU=4}U>sm%4Msuooa)c%Kb0N#A@1LF)-1~sC zwGZ!LK?rkd`BMF7lF{H-HoNyaB32x3#eeCA@b+VH- z2oOf?8nPZ|TZ8kEZIzbJ-IrF8ad8n_wJy87?onzH{t3?m(6_Q*q&UkbTu*2w^LZiU zy(QvtI3ga@Y0ObHTVWaFBxlj=Zd)WsQXlO3MRXDgoMaGpr>$j-=vZ04NXw1oH{*W( z6c6=iYs9#4>5vZ0HTkeWDke=96P1kq@Yr)}w1~v2J}ial252j0U8n-J&KlNQ z%yEHBk6jra!NYmi`6Fx$=zFX6gEFdHgyj=_FDsZ)qzg~|TC9*wmew)42(1%<+ZVB3 zF!jAqJYZ0FE+bZ;?@pj4i_1SO3uGy;TMngDe z{o9&kC)C5a#*eSup7(#)TZF6F9Q035H>`8SBzu9*^rpJ?me=7+VwAGYM=@kdKP>2% zt;L3CtQ@MPyZ(ON=(LV70GQ~pv7|vyeV4^zR{AJ};mM=ca3Wqj{wbDEVKLe5?&J}H zF=%Fnm*0d?^FA;!4X`Vk!pozvjw=5hQQq3ioOQH3Y1 zmIpKOr!&u{=gQp@G~dLpO;NP84J~ zf>|mF4E-Jrzt|mxaeGnZ-H=q#cU`Bm?VN7u^);8Vs4jFjfIYASCauKXZTgM&%5wDt z;fwE>DkY%~9#V`c{JNA2wV}HLLu*H^YxKn}GSnLHv>T8G8$KvXAN^cA8m^E<0?&p> zEll|B8V*NNXP%@`vkqr(*3GDI-1a$^9CBWH9gw<>ELXNemHVdB3-ZnBW4HLMY(=(cH znHIc2z7r=}A3~XLgQ0lu`~4Ok!RJ<8(A@Yy@#|V#@} zug`WgtoY4_QbIi85X*C(lW=I7^$+TzewrcCC^7okhaZ2uaB+D#rl56FUQuEHa}zZR z2WMq5i>>~{9wM%aih4p;r-a;PA?K6ZI|bqAS;4V%1R;^hU*R1b90Y2;FdM-9opj@# z^xWJY`puhLB0T{w3_$?hd3Y=a<{08nR@t1<>omPb@a9xISu!7_FXCWf!Az$t0YMlv z^T&^4tQnp?6WJ=zU}a?m9hN`wm4(p!pAufRAwB!ZjrSucLb%&m`1X5gYMiHMt(V5E zRUK$RvKT8)5li508SqIfVF80RLsAb$=`XgI^eJ2K_!!YC+u9)B+T6v|&seeCg(w2U zABw(=@__~|p*UtrdUn`in@4OGTZ;Z?2ng^7lc#Br?@ML_d=Brwq@`hM^YhDHy9?;d z&zD*d@mGDYSHcF!vcb6uz_w*EubzCgnE#=cu3__XX6_BcX+{yc1BXg{QbMf0A__(z z96!k(lDxHbA@GCLw%5VnFVa2h6$@K!PeUfgTq{@@iZGJ=<`JEwEfn~PNp)jtanAQ@ z3nYnOqoiq&(a<`=$r|jsdU9_OkSVip5FZg`R0i6Bp%)PEo=r+7rmzHNoZwQUUL#s8 z6bKyRqxQn3jnY`)Yam7R_)60#YkR$Zjd8D8h2z=W{EVI+Hn8K9$P@1-UpTPHCtuJI zTTV|p67l;fZ*Eq%(#5BpFN4G|b&#ZT-wR*Nfd;bMHOwD<1E5ig(}5rWgCs|hnThEU zm@p0_6Fj=d=H7`cmn7t?1`cv-lRa)DDu!!~AR-{{_(IGLUqC-y}18J-zB4}!_{E|)@IPwpR`lP^R}$5| zQm(-flQx~^=V@JRgMoZ2DZ!MYqdVQ2Ah|<)rZD2QImrZRJ^z_h=23A>-o;*HGvA8I z;Th1}EW{DkvEB-1PVIdxtgR)i@Vv$bZ3qLL!4f{Jt45t&-KzyhX?aB&RFSQl$ENPQ z_Ec8&Wo5tZtxcdV3vQh!M*Zrlfoc3fNg`=-S2A2U0##;FBf(-r1S6Y?&16F z;FQ4^#IhKldEy64TpCZjBIUJ@QkyJr*nB@%{Hi8Z5HBZ1*ew7bzy$yzU+OgbQBsr& z+k%NucJ~8BF*_|z>!<+w`_WaPhiOx~L%9Q9U(Lm7=OH$=-AVVOUmL$f7zvDLs18s) zX#b;c$H@=gXR~qhn6w$3>B2y@Fl?kIddp+a>Dsrrse*3BI~!PH_r842d!Gkix!Tg7 zoc0<^yp*I*F}F7M&H0(w)|*EjDj#ZS@(vvr7gzm>rV2Q|g(9VV07TJZBp-j53C910Xhp2 zG5&=IV)NaKl!RX(H6smtTbroM@gb$)uEgIa#<=LgKB}GRK?3JUVpbrvAC~foi;m5e zzjPI-F>OCuqdT11U-(c&<2R1lJd|db$K7y|lTgQ-<9;DH>*mV7#%v{Sr>IzG3T97* zv89Dcbp(Xrb^k76jFkS)Ntm}Qken8m%UV?XU3$H~s4xaIJ)Q9~|8sT>egSuRPGR9! zFYd%i>ms9%B78X&?v{t;fa4Euw^dx6cE7Vm^sJ@JjO9Qrtbi~=nDkQkp;V!+1eM(7 z&7A_JxxZI{m7z__+GenU_-Kp+94DWSk-;z$u%)vnZLN!23r)BX5q%puN#!O`RC~1C z1_#ai19+Z#8w^T6)>I+S(CkGtttREUN~=KLlZ}p7A)*EeK0dH9C*ZJo-d>rblL|=e zoT<}^i+9kM_zsoK2l1;FC9x>#mH?C@WwC;Cmo|477Tp}qCjQvk0J613avGv1KlUsHb7;50L&RrNU~i|bbt^k?dR<+vU_dCZPP>&7>y-n z>03A;2exc2aR`6D&Jj&4{R`K_roLGLIy@Lj2d$f`tK&U9-2FD;bhfpiZTf^qSQxWc zrWbU3iWW>-SH7`TGc`4Rp5l2hNR~aOtD_s4n%Yh5P@^dSMJHuf4%i`#PP0+cWOVCYMiN zfBmALkpG+fUw&u5TYjd+8b7pRry9=m68!#FLxu*Yv$Jz~x~#?i@&|TMmys@aFxD}7 zgZ&<{)4Q30M0G{QZ`C#CcZiRcw>rt;fSfSc=?-&oc_1Gh9fe4{9i{Sl!MMH|UNay{x-0lTEsSPYGt zfWo&u;pA;C0Qh$b9357rlvNAj9%^oHRRXgscRz`M#3%X-6CxD=5l8Wb*{)QBDL1#zOlWd z?nQOA#bO4+uYjwzwLnbG=j{ybz-@=h{+uSyJ7W8?GBDq+i;IFHJ|W4tXI~JtDQ=+; zzVtuJU70_Rm_t*p$p`%Ac4~cdb8RrCVY>1oM@FVG)YC#9K{ag(SeTzTcx&n(`r$36 z=0$fHo5Ohtm$I`|$!nMGO(c;-qsto#FR_Y^pH+I!YM}FJWqXb8FVF0{JzMsu|1=GY zgt|%6u1*IS#~At^caI97lLng!`2)D*pW!_p=Kw|vR4B17KLrT2K&ja*HGUdd>n`i7 z0#dq0_|`i`yM~>Jo|uQ#0<(y~!{V&8m0L zPlSY76yDPB3=D+6nvnUMH?bC?5Pa)!g8jN5(fVN>rvWqhXw{#>X?NB?5R?3OJ+B{D zhNCBoJAMukG11E5Q499{H5WMcIt%ly>+h@dYFbKIt}zH(6VJD&%eMFpAdAf(;T~&f z0K!@|=~?r*UE={=(05G&Qbg$d7yII1{1WKeTK>I($nWOnZ(5>PSIEkAzpxpzx%&I_ z#16o^feIW1hs`G->IrjyZ?RC#RInQqNs;-`DvJE*BZ7yZ2dDL7=!65&mmG8ruHrIU z^7)2bEcE?_8WtTLUF^eA3Iqg%t?Fb_4jWF3;-KHpa63o zWUY8UY_Yyh7RZL`E+ExiZU{hIajCPNf&Au?i^XiAR@LNP`$e4?DD*99*%3u1JHMJG=iSXo>-?#;9W*V&cPKylB|(d*d_u-RUNz07=Qh z?e6aGS7V<2@0JPLzPJ>0;7D{1ZeZ$3VTskZ={Ol1| zFnEb=GY%Ss9r@lUP1C-g!oT8B_kKIw^!Vh2&3sa>vn6=UC7~ZQf_I^9XyobrEff64 zNl|u$>o`aFEYN^$plr&^TL;>Qz#z>iF|_PEKQ_z>BkO4nnw9nZ&Ban-CbCW zn$xSXK+{?qYNQ;A&yboK+oqq77!mfB4%({O0ffgYlA#BF87h4lGEQpw7p98|?(@RPs zqM~q+;bHwD?=7T}bL3Nel+wbxz1w`jz`wi?DG}rXtzeo6*26}a*c{h_nd#1*=dp?V z*-vi3fh541X;7~4QVfk+%K6FGB&bG|ev`=ogPs}G z?6i&L4wahjytur&+J>G$rs(X)o+`ALYGc2rO7t0Km6V_^DGBEn#LLeikzc=Nv3uuP zOG-+XmRAR)r&BI=_h>xNE@O_@)@*HSgNcn*2OZlYpfLg9Lo0pDqAR66Jw1&VDX2g2 z?pbTg(-WMYo)x2t^zK-Ba{rSgi-u0)Mo|b@Mt1g&2*5iC&U?OUWDI;j32|iXzc>1g z;@CypY^BX36mO6a{t6j}d*y~00*wYxX1%}-=|X<=sOugM$?pEP~5xrtYlZjgzadw9sYxL*os-(YezV&Mbc$`2T%yWXgl5j&Czwf`g~S zTthntXqy#I&&c={(feYzP33cZGn0KW@H(KCYp(8>69S50}g3^#5g) zFRxr4@0l94mm9FgL6>ms+1uamTT;S;K_=t_@GJh$9r7}ql?;k^o4_`uv-zS>{%T!RPh-=6jRdq4ES~MNB4uE$2I!vRKAy( zdw;G8JegPY|V=FFi};>gZUt-!WUgD)KYc_iyr@Hg^u15y`29t$)7|%V-T~f z02OVw2d4-EF1N5Kz0W~p1Q7yU&~)7bGs5v){(#eiJof2_k|8F63rtvu9I^0kVKQ`P zdiw6fpAD2aAxc9dY;`IQCjd}xTcu+lvbVPPQRz@TAwxJ*g>5C^3wpQ(k3pHiA9DxA1Dq_xfC zMo~vqb>-}IdkPbnEuo+yTftb4`F_;2YR@yBQ z0{l)AZVCzz5k(OQ`C=|3pPz-;6RdB#ZkV;)Z(&t9R0v6kK!HC}gY)jNtL`k{YsZg* zlw1u%<6MsG7u{YdWo2xV5hO_DX%PdVa>)Xoa#QkD_!3iSV)=3TY`$F|M)LVPjZg@R zXM_5u4%o+B1jqrFCoG*5Kgc0cojTGSAEQAa&g4QJabunx*Vzs$qpdO;KWTq8X@C^@ z@GxsKuS0D215{l|7p*QYLtUS)Mq$ri(*AH?K_yoF*_`e234r>NWnj3y+*7rFp;9zr z++#RAoIY?1d+O_p>a&~QzAGJICOjr&R0ILR7v*_cYAQK&rcwk3ndaEo z*l7OK(%i5$)v2lI3tjmG4o7+2tEP1MG0#K{j6h!y*CFLAr9im40_W8AY%c_O`$&++ z;E+rMJF?SeJr*#}g4OBP#g0b@(z*h76PX&Dv!)(-@rjXeAV!*o)5ea>es%t-`V$wC z1DngYeUI%bYfN*3yKraR8{~u1da#}4vyWy zJshdvwJ<23->#Q|N{Np{zzXkJXkr5ygQrA5`A(?E`9|Y9P$NQgbae8Im`#D}P_fA0 zP&>Z$b0%?q((lVLm(?Pvq+~b5JMP{S3)P>`CelVOjZ2pDy9Uw0*ctqH?VE_|782_{ z4#!B^rG{cJ+pYG)2q7cAK>vVc;Aj+H)$`~*3s-V$vYiU~{CloMScveR^5i}(n(i5) zoTVRF>B{@MucH|l(lYWr)q+w97nuQ=oyprOc+8+X2dM+`T(ZC{jLmcdHp|?El8Xrr zDI%?{Mn9}*+YI-35jv|$Q4wn}Sug_aF|*=&L!nZXqJOV?x)A=kT zH!2s-&3+~s_kNCncxPl#x$~`xgQ$>3T}q!{v#US1z5Vy4ZvY~3cA{WHIf8zw4lK$5mH^Lb-l(pSukWu0WQD?>%_lAASqh&LSZv<6|!wQwGlN)rrgL zvZw!$!vCK%`Kj?^#tXB^5Xb$`SJ8kW?QaL3HZuOWNC(LkAe=y^dkAN6Lai!+ldlymR(#EPn4J zM!aAe4}Zys6MWdo4Jpx+dP2j9^RlZ8h(Ji#g3fTJEK+=f zO=(3{KtmG8Z1ua(lT3-~TO1avzpfa5{1^xbj->1kBMztxl@sv5_I}Lbi~TqanGQ*t z^Swh`pzlrl^bf^#S8z~m7Tx@$hHj5QW+Wg0(c;%E#P{ahJ4x0fY)(a0H8f<(hWc>A ziiRe;RYV{2HHH&3z{FQ+)kUwZqwLc`Hz-OI6;2^&B&`pU91O)3wS-cylLNOFc*fGu zDUd;)BWz9rFSyeP%>Q4VESlqS|Ah>=`@;gwU&>4cvVeg4}@7wVPTVFxFI3=`TITL;HZ$?iPKn^OT@|PYmWw^t^x*QgrP<_< zKI7InlV0!NW;hNLD5KQu3mWQqom|mjAzxa)lJ#JB$8xt>H1_!c65Xua93$VGt!gNY z&T?A5P)UVW$FX>Z>uU)1^25$Em2nn~WPI)=Y4t_ibrP^(S-Nd?00<7D) zOOY`tnTq>Af*mxkZ_q)XfR3RaNF(J8>I8k6iY(j)Pu<;|nag$`y#g|%N_EyB@d-Xr zY%+?QsaLl*8b9dx#YvIe)~z~kp=7;fJ%xvbM+{sU>@Xi)7w;(ZoYC<&y&x3|ZjyQp z1L6Bv-Nl{erEH@elrbl%>I8)Ts)_N8Wf}XIEMwDyEFuX~c$c=RsiIw>^;@ z|J5gLv&aO&2V{c2L?;Edw^Kn{ahKvWuX|pAv~0?A4%Op%@q!vhC9fe zo1^K5lw{A!vi{`CXXAjDcrE4j0_4DHMM=$CVe;=|7!&gXq2uBE3n^RcMW6N zjt7g7-Yl)`y)}XdE*eC{@HH{}T1QNAPhU1dp{{n@a67rHWX`j`UJ+4s_Nb0jYX0YM zGOG#WwL0e0DF;YN+Q%0WGFHV*=p-o_C}C%UN3aOiHDu@3kFG|A&w#pis~3UXH;`Z% zm1$vCqE=b3xYJ!hYN_O|i=IP!JAc4k8V>ElQLYPWzY7pNhLN{9|QtMD@0 z+Oo5=H}~|s0`Ly7_!h8{{W(LZywgZ%N=R4@wFueEHv?@IQYf^l)%@oojAeQPcV4=e zjxs`2DOnM?0sM_WR|5t&)7*WKt*oqsK;KO#HI3TtA&2~? z^0tv;5l5^UpP`HD&%H}kaj_>jZsF2WzvBGT)7woRczfiASHn2ykEV&9fF&L46n}6t z!`TIZZWgn#ClhRJ0Z%YRR7`Sbj&V7p&d$z;|IQP2Qc!%u!S`?X_5FSJ8wv3)34wd_SJsx@XD3NV&nzrp#+3`_<(=u z0y!DDD)=CRECjT%!pq0x-@c>BZIF_`u$Ln&x2})s8XJ27Fw&Nho@b!l5)c~rQAS24 zV?rTrk-leajj=E%o;{4pZa+tOGT3C6&A`CQ$_8l9;sT9mY(k>Y)>eVcyPW}S{VL7r zB?hvYX0IJka6WrH>E4~Q-PbLsDUCUB_ByYCE>NiTloZLcThpv z*QNA#-H}Tf5TlVG-0lbAPQ4F824C5J%8pna-{QL78*gjD>M&k+?ca4~sUYrI&}_74yM(IEx~FFBEU;7?qUR+q$tE#KPp`E% zs@xQ23;P<|M6^t^VjDKsrfvIn2`3A+`-9f0CK;XQ*iZNQAVAKn4?P-yV7`9e0kEkH zS`dw`Or{TW0U$93u#r|y6%-(_d0#q*yPq!J9limUl23urn?bD*`9~Ys=XAfhf+M@a z6)!WDTrj2cmFn;ySOnN!FiH=(H}<a~~=Eq&zTtopJUj-Z6I+sC>*v)-($dkj1F3U0l zogT-Xu-DuH zz)Zwge(-$WWod8aQHfH>q6d%xn^JP+ae8)rx{C?m#*eC?dFy`xTLsBrKv0N$4KFh@ zv&5DAD^6#pmbq4MR{A$@5Vgt3rYfCq0D{_U9t?KJr%+cA_4EQJw|%G6s|x$jx0i5 zW{LTl`z7DtS63s~_AU}#@WTwFbUWezcwbo$uoZf$%SRXdw;+95S26< zWlkd5h$$(5Ud`op|LF7-mpLb~PG05VirKK(ezenO_RF}fS_4q(J-abBnyzIH2^A;# z_E}2m`va<`*?e_GjTfDCyCS-`u?xHT`~dJy{$wn%TtKeQ7e*}N|V%jEk3PgSeQm41Ohy8+LF|{;+*uu6TzB- z_r2qxmMtdIpr z9EkLH?))Xk7Pq>YK;N6M5MQ-dSicD7R)4)3KXPs@KW+Y%un2!*w}=%>hXgIcoaZ@;`|R&tnFmc?wD zq320E4S%b+={z29$;a0O=}%y59YSbe(B2d6yLEp~T~VIaKvZuSgKXudiChxhbh7l} zW6gKhI+XrEP%GMuiehOA1Z~ex;^Ie2BKsb#tG5 zZNFJQZQN2Rr$=&)?_stQWQ6p3q-GQp)lVU$Scl7iQ??s@i|oe318IJcQrDtgtaG76 zBOF8VWRbk+OhiF|WYMd2^pYB5)p``sy&P%E+8|uzkx^25;_(opRATdvo0}`uu!uL7 z=LY)hF&wqDe;iY!xUE0Wi78UmZ90zZjnF((!0LQgjEm9FMLl3^9@@zFkimw9ChCF! zC1J-_Z&F6|N-_R5tDz3xJz|kr&Ex%{_Gy9ubkNWH8oSvLP*akJ2B7J(;Ih_JDfL>d zld#0Yow+#NkYBXAuqDr;EQyXDzKNE;IW=u3NshYet^9+a+@8up#U@@h^Vu*!OjCFg zjWA+;!~2T$8DW*VVyz?#C@UE4XIN-dD%G|nKSGLubI;V#YKiqO+nD7L|Nb>-E*-Un zBp(fD%RGaYBWz1n@>Q7$R}u3>(G>i4Ew1+}V^$+%lUJ^csN=$Ug8XHfaLm�WhOl z&zl_5V4ev1{0yY?$+Zr!Fm%<*)-*wsj9t*7_DpoSNO@@Xdgi6fUn|LFzwHfw+qBNm z@k;%}p_JIGT}z|2gF>d8NVeVG@hnVt&8<*S+EUNOzzN4}X4B8$xJHdVA$V5(&j3ji zbO1QNIcbmAo>7HY#7|YNOM<;9u2?AR97zI+XSEFT6OYy!S^HqZY-W7z79}#_vc)ItxvV* z5BdZ~u`Cp3YjB?gC5XS+w?^C0!Fl%3mAkOU<-?6m_L z>-)#v`uk_#nc!rj3-g&uGT6iIN5D^f@hj)dU5b<)~{{-kK>~IREeWy%_fg| zlE`ikqsI7ZHbo&%uKeVgKxXbN@{fBq7Z!_~FHmUSwPzrT06 zK!J<}!Fom9A8%-+)m%@S~v_19UG zG^jjQRu@-bIFv`g!5*x;0PEz?uH`ln>O`CGaInxm{1<4q6LBEEE;R6XesqRDY(3}t zQaRcnYuU=_@HH0-vO&C|Mv3X((<-SpsyPkG1`JeTt1nnOx;jduf*K71;Lm`5U*30k7mr4xuXb977-R-CYNb*3h-_=))M_V3EqP0%Usb9c z_Gfj+wuWC7sm8#Q0>W1W+T$dL`lHrUvB$th6_6K{VGGz!Vzvd4~(`t+`^%o_6< z%`E_~px}F&{f^->MfzX*E~h*F^>pvwH{aDcvgD@aOMeR2Mq*m*?4nK&WMN?Nycp3h zE;BSN15LnKRznP$g8W!x@`xu9*w}{`E?zV>3#HLtzbcivBT}y$C^y`k>-GcQf*|17 zwUb*{j6v6YwEG-y*?5ToW$8zNxFwW>lViDg_<`}`b3kedIJELxkSesWkQfwjQkbp+ z2}RthlzTED$?Ik=Hn^bzm$AP3@K2$w)q_o11yz7aHY^kIp6;Y-dCPkBu;malMapT> zpCZ?J4haS24g32ippMBeJ>JaNGCJp0$h8TBhYZ^TD!{t@qV=bhJ#U|z`*1#-&v*-Ibb$t99TU%6W+o=!%hk`R`KZ}Y(=||=B$u~Hz6)N3G|YoDeb8l_$!`&xV0$~? zG$10Pq?MzT#{ABGc%4y$K!GDHx3=G8^-MrRp)xcl=R}zuXC6FJ&h0$g*iSxi2z0S+??y$IzGfx zKo64%n{G>~1=|X>99U%GE-m0u}7cW>*fK~Y?`4F8R z%o3$kEP2JRU^vc3m%jd4uvSJ7P!?`oS#)o&YWgNf6RmY0#24puV(8Yjvwz#z4Iob~ zEv$hgE;!^l)DaE#>J?_URFJ@$4>QE`+WdxpFm`^HhP5?Z4ECDjknR$|5w@pA&!ipj zH}%OjruFq2(EV#7xzso@ypm*$i!d6!uxDJ^(ZexB<=mC)D!!NCav71)Q1LhW?Tcc# zAnQ`2usgndY$$z>=s!S&Otv@iKs9-8L!?1WXZiHxgoFfv!S< z(GrbYs>ffHHmkK}gn|$!)kOHd_h8*N{Yu5VxH$;#_GgBGa@FAentD{Q2hedr&Wv=v zzfd5P0ND<0JkoUUu8#?LH&w39bFk3p2c+8pmH^7&$9(<2kuDq?#E4!K9j&K}O;wmD z%-AnhJD|_9nd^0OmX}s`{&qSU&P+V@(gXxxAi(Q$#*_0iF)@@foH)hQaXWMZm~^Zz z@vi42yZl88f-Tmh9XY1=)G$9RtpT}HDJf*q{gku)a*|kL*6ZtQIHg*t@^6B&LGz!F z#g%k!-_};HPNr(isZYM-f@jf~#O)_mW^85_LLr$z&K{5$A)W+)=6%)5rIrSlzoOEH z{dr;6vU0MAH$`P}gpDBiEOG5uQL5jy&%dBc7zY%l66Y%>1Da)!-0OD4S4cFcf_c4X zyM;ZCcbCh8-0tt){yLAI6a5pa-Z(RzYS8r;P_J}why{}tHT&<|Ysd4f9uCw21P)K4 zTn3Y3c`h6?vxd??L|Sj2)9M-KG}5OX+`JEG3#;QOGkEmF0%lJLW!#NF8x6<3=c>-# zWCtY?Tv>ZR0UB4!!_B2N;Ef~^-i@K5fomdnL7Xu?;Qi=P@t6x4_4*~S^EetE95Mfs zRTSPL$kz<)ZF$S1YU?v9oMsz4o7Ue~sBnTBWW-Z?x6&MY38uLWYv7J- zy1|H!j_$hw!D*_|iJANjIq0To85n#A?+oM|7Mb-aB;$fmE)K{f`=`og>McxsDys+~ z688r#U-`M-lR{=I%|7XUV+Y+7fRG%5Ad=5A)?>7L5nLF4)RWt1ogVs+>Ofz?U>4Fm zhlDCqkNLk`cq7a2R~V@$=ZD(%chj^wn(89;}mVItg zbLtXWOQ|;o+cBGHg*7yInaXUfPS=oL^Ee?~J3AZA<`RJJWS~1wUGv{BXQLYm+Qt@z zOj~`+R(~k5{-pc5{lq}0cjGLLNI158!4yhJB~2C?_pAR|Zg>K>T-tf#vtS{BTquun z&s4TwO7pg-Gz~J1^1hnEoab^eDIa)v2F|IeDfYQqdoVHhT3A5fEFG5;^p^q-GP)kW z;rSFF(b<#nOMsvCa53@kH=Le$gZ+``6qS3Y2ISg|#0Lrfr%KzkD;jDd0z+*wUByyh3h;n$B%cv z7U`I;0=EU=di?JEHD_NsBwtbU^<>hj zuJylip$AJGkjdd9yATMNiGYuAaDS7LyQ!3T@bb|zGWuJ;Snkeaq0ux@PY*aq{kxNZ zrQH|uV5p}Ta=_!V0%F?dN#%tLnWP=g13UfIYx`%LY9LZuoeq6;<&xyQjRoS}fN!PL zFs5J)$cSf^51V6RekED-Nqm^VvYLV?E3-kD`ZM8;wD~o6EyeS|B_0oAjq9tDOwE&{ zk7anYu?x-sB3?SV>TBe+I@H=gcmaWMuW zV}ALHAVo2`vF`@pnKUQo25wm(9b|Vqew=TXA4lx_{rmT=(IP&ndpEUh=R8m=%*MvX z!|Q~;8}NnEsMZIZ@k;{QrGwf0BNP!4yPZ^LBRum&k=+$Wjp@~FHZ_-Ww}$t5rL&za z!x5}|BET%?EAah!RI^9{+_I;d4558shHMS-Y&yBef_f)kDA%W!(MR|NTH#$jt+-DM zL7cK^Z}z2_v>fPH!F!o&$@ohk%fJPd+Q{i!@s0b(Fij8sn~6P2H=LicR(r|8FZs^! zZ@E3*1qDq>&sJG1JVvQ1?2L^N)Fzt@uE?%_DebDMa}-be@^*W&`k}q*nB+_E8j5=i ziK;Szt=#$vD%F*cvx8LO$Tm-%gIh$!RXz2+OdU@(*o`ZEtLn;_+yFb5t=+HEE0 z;r4LaAlS^0vL=FZ^x7;R`az8~l8T6Zc1UCTDyGZdjd^>B=p9l}Q`cUCQ%i}yBgI`g z04vKLXuCquBb6V5j&os9Hw7?W(Ed!S=LJ6Q^0Lp!k@9>3%ka0v(j*#)mZ4>qo!ZD& z_Inx)29jX>zAkVclsni8{c~H+fX3@Ye|PBaM47ifQw;~lRGBH|$pY|64P88&8}@bm z-1cKh3$XO$jceA@-el4|Oblx>!+>>nrcL6y8_9Z3;i?q=@$vDJt=JV?gWD?duA44; z5v5bjo~cC^oqALltlDGH!k|eyKl27*X3E24baS`@UK)^whTPtRIXP|EQgc0Qq3qO^ z1ki8KVbf`LM3$?oCGPzuYS$N!=$Aqr<(y-7AkE9)&l8#s)~r-(%*~)-MDR_W!-$MJFedcB(a^6sFBr0YyJ= z@0vAF*-Ohw6>1^WQ)kAQ`s^&YgJpciFj)+g=mLkx@~UkMJB~323E$FAB>R^DdhUBF})pNtdRl0 zSAgu%I?4B>k>1B@|6FiwLrgl>k%YJH7S}^(e??Qdx0c1Kb&sU6Gb9HG>*et)`bXZ@ zuw~nNwCM8yxSka~s-i9|6BpjotT6KlvMMjr*AVGy5Z=VdrT3O8Ir^NX8XJ>Iyk=9w z?(!|~lRaVgT?!4nU%kFtS(a%&Z~K_1_FL=lf>esD`n%_W5kG!-8V)8eCyzcXZI|^t zw7@x=KQ6)pLs!ttzN_oW)D*i?GM{xNTzg~NT zfU^XH?3+6>yzxQ})gIp-B-5VHQZ#N~#-^r}R_&2dkQsCr2nYyt+cs!no#J(VG57cR z);1NA|JoM?WH*+7e*V-kaGfaaIp?*qvC%X(7fd%%|>4# za_x~JsL>x@pC~YwDIp=LZT63;oR0Uk! zpb=YDkLWA74O)(;M;8UUseT6~$9TbM$~F)r_+>9PE31-Rdo)6Q;`X;Hr#6gB{TtD% z+|oP1UjxF;29FHmHKf4|!;jb>%^@Fn0KUXxKJj|e&Gqn~qe5S|rzWB*&y#14olFqz zyDVj&*F^^HT?4kca+gH2xJSk8E||Bfb~`b^Rn3j3QAHp{S3%BU*L*bMZ>52R!h922 zyDMa`1~pB%*5~zD>W!i5-2kmfCT=xjELqjf;acYq#SQjc^nWe%ICDgZ14f1iVRTef zF>w;L`1=>+YYGge)u{UVdVsT%8(f+uhKCj%AVlt0QYyONx@KSS<$hn#~$27p;N{;$QOXLWpvk1n1I0tj)`>5`LZsD(Qhh1p@ z%>}45fJ%Z1R5;9wMl^)V+?4E#V@R)kqUnzS0o^YVZEb9{wN9aE>?fB-i?tjxRTg1l z$)T-z#ZPGNbO~F@Q)Ohy+xuO@O@$eh+(VWR{~A^3w<)AwvavDwmPC*N-V`Zbu(pmF znp|X$`dsB6hxZn{@z6AwI=;L{Ap=^8U|hYevSPvhTnRt8LsV3>{bY0SXfUqq+wEmZ zVFG*t>IY|EbKfWJ_~s!Y<0ZxIX8mC+roow5O1s*h)vmk;u@*od$yFL?4cE1A|IsgLv zTpSNpz#LD(h4YC1{CZAbWo2opPQzlUZA|BxvWm(t%_p9Ien@$npY80T;zvf3Dgkr8 z552b3JPL$c>b?M||wTmNd?-qSI;W}2czn_zx`n$45&LI4D>DT)JoDKkEts5If zx0ex20FD&eESw+8ROgz?sWDbc3JF0A?J>@4q+!)v@4=zk#zljCvGu8;I5#H%P3N!l z<-j+dA*ZvqK)mA~-RR!!y_|YiVqrE{6DVuJTt|tsjETuZ63^w?#Rwy3qPiM`^|2n{ zxe?UV)WD|>0l8?YJ56Lf8p!Q|)aR1B!mIW!!wmMB;Do75LQlwdVpakBc+vc`O=-`9 z4-=zIMprf9Tt9x~CGg2_r`}?M;&`$foO~I|WNX60!c^$Urn}rKil8WYEmE;OBd0!z zD!Kcm!W?qmNI;0AZUKSb+Oty=N-FDICAB;(+j0)m>ht*Mi_~1YIrZch63!K!rrPeG zBXYZ{xU1wPqJ*Ut7e9f3ML1}K*aE@AQsbnU79lxRRM}XT7T$t>oA@ zpN>8SMWi55gb+QwaMay><|mL@W#%gIyv$6)-K({jkxI3Am_z%IT46@0V~9C^Nbwk}km-}YvwBp_F$Peqk&T_~?ChCU zBD#r|P%?T?y`JfsyOq>%!%!qBC@{8wH6~a;wu|JMLnjlTo;~_cpY~jS8-K`|F_Fsnd!aP8b}1>Q9rM8j1Co0I z;P98-^FWSA+rjd`y~zRD=j_EjrXjr;ipHiD z`=#sYlh7UGwGD54gdzw8tdOC6Yr%C(+Lz&~;{JM3alJCO7dMh;9iXLqG$;OpTF5jjj&g^qc%P$$sTT#cGZs=(@95 ztOZSC55q;wf4|!;w!PDtz|jNE{L2m(R-9PH4Ii%t>$?F!aov%u`?Ay{Ae@+++NwV=!viTm%+pM}&W*kd z%FHID^nhIOXJq8j+$8?ypn7v+oumCfDQLI;xa;~YQ}KyZoLnDX)pURM7J5yWuckuE zQ_C{1`N`Edh@nI@Km-M^d8CFzjT54VCUHyeMInVBg;0LY|p@AtGkE)n_Xc={t)~O@GLgrtke~ars*POulx*7AcZKoLRLyE9ig>|7GKbZAQ=8 z)U;_S&u5>)<5^t*v5RspVrbcXq6^P%jSVS{k?y2#Bsoa;r>l&nnZ6As_-{%ln^d@)!}x0NxyJ*0WnPmgsP-J3U`T~|Vu)ZxT85h= z72$YZF9bf=A8&d{RwlacXiPYl+Y!4ZhgsL2XUEV%9qbVe4KsKy*K43(`7*76Ocn7$ zOs7N7{Q;Sf>R3h~-cvt;44;_D8N-bWoaGy)mq1np(6~E8oT!&TQ`6_#!5@GsBg~~( z#JD~Q7sPKU3hii;Fp7 z4ZXBeEe4py2PZWl<)Hd^FcxJQJfYJ*bbn|x`v}j#;2RM^=seJ8q*Qb+JvlZ)B&0TG z__l_ESiJf71IQk@U3dHmPNLHk73s^3cEV0WB;bUu&7!EVeMS&_KbyDh6x*~&NW`+C zfTewi>gp#=DJc>@K(w?m0wL4JuD-bB0AdhiScl51qJMX%GY~1<*q(uzM*+ZMW8Ns> zpA6d{PEn_hjf-Eh*F%#^Y-$au*#mkZqr3PJz?|^+eY+j0oD3MAnFk{!v}%dF+O1O& zQ*K+2LDsU=V8ZNRsaA+(RAj7E@)G#!9iF*)o#5Yh6sT6&%@Bh)>szn+tZWoF(@%ph z1nLf@Y8VKaQv4g>hSbDNsI4Q18I2y_)+i>zUa{T1BZdZ1BPN+BEQq+=(azY-%Y!>3 zg9&y(xWogbE_5InmgflEoGx`Up~ABc`^yu>DHC$MJEa!p-9PGpv`w_u;z3h+5+@5a zHL6ZYY>hN2pG6XrgM$MD6V<*l`C@0h-QA9Y#H}+EyBbC$RXpM!cSPeLBarvbLa97L zdaG+#<+&DzhOo{tF#2x#(2Rqm>0*L`=K>=b%M&Ozxnimh4OdhW0ieS_q=0yXm>v)> zH{+&%O1?{nqy*VL(Mo&fy-qVFMPn#(r#w^!YQH_lh3yYiZ1SgjK~q2INQIrB((-$r z{?Mo#=!1oeQPfS(>qVNCe&mHs2IJRptveYQ7&^R|z%~qK+cj^NUe@9^2r&aIZ`=A!V)AYxY-60<~6G_gS zKdUx)kXP^&43AwVc7ON~DrFfObZqlJNawBY=|16f%3A&4$Gh7Qi}JaW3l0rs<*O_@ z#D%C@m>B<}BO@bYC~}Xt8>auR?WqxG*VX)J^=6+E5jz_83?j0V@8Lf-sm9X4l?+WgF+7l9bqnUM&j)@TU zsb4iD`nbO?56di%mJJuL`yFosQoil9%!Y1$=uWiWl$>0uaOC|C=F?!N(CZLQwJwv2 zrTeA_5@0~P2c?z0KHUp5B&k8Y==(;To4c&#K+Jn(k~GMjh=XHwmVv)CUd8vUHc8d8 z`Vo?F$E9_PEc6AqR_9P!0DTgw-p{you!-&C}pl^R?+q8^$qLeIE0; z_}cd?xa?7p{pA6&8Y>NNC6j=GLNH6Zlxy{dPb-dV(!G2xTMtrP8Wv7h(b3fUtrL zTW(OPwNcxn*v)(VNSG@sW1?GLncdDpQMZ=WpT?>v$MyIyfl-#d`7#uji@lGXmFC}$ zrwv1m+eZAWjQJ~RXDxc&_SILW^qA5XJrSnjBCsdeSR@6{Qv|oh>!1)VC1*}wtdC_G zqav4KvyO*adf!h!@VdSvgywf0Q6@d%r^lrgx|1w6RV?}hQp>#AZI`{0fbek4+Cnfm zb6xJT^~1dn8ST}Yob&OxN7Hi#22-Xuh86aQ60C&0hFQ~sN@q(HP7+p0K``g-d_Lk| z{EAyoG;h|p;LUdZZond?f`Wol?KkXbTIG<*1y|HNl&xvyw(pphfqQ7|vR#)yISYeYy9`Bd=xgd*Z8@y3$q#K^^B3Uab$n@AW-DJ3EBIucx*(Ovjb z%`3un%t35nem6gg-9#U+dzPzEtv((?b8tiK`lL#_38};1t#?HHr>_XH$LmB+`ye4` zpeqZT!6CMXEU|g5y;uj>1;kYv9!NhUpCbUOBpX_t>EmDClBr}JRQHym zDd&1%D)kxEU$);>-v{Mv{rtIBCZUt{nA_^+VfkQtRErU%FmjQVm4Kx2h}@!jM8TGhnn`9TsdI?3&Y)7$plcl$4dTWlZPdt*0SxGa2W0gFzV7LVKJqQCQ` z%FyEgx?oj3j^u$)qZUwiP>ZtNCZaR4HfnXjbD=$)+JOeNNU>!ShU6bmJ>5P@epJha zS(fkh-+x>rej_dXAV+uR)c-0Wpk(yk>uJ?3A&!MR68wj9@%GuscS#83_qVGw_SO4v z*L!rHO^Rgu>iu8EG1uXYJNf4gB}`+D{<+J-zrXYxR3Jrm`|euSKP~Ea#ex51C0T!J zzN$2z-8q>vJ9?O3keRg@bZcqIA&x9j?S?LU`b)eZrF71Iy#gp%kN>G17c#|u4^_K-CG~GcXqa#vFWz| zT|GPuAz(Ki+xj$-UZzCDes(%)J$kAd!K)*r>W~@~sy?+Aq8Q?kTz{G z{Cv)pVrmj3qjA|aXn>@?p!bvUuC^EcBctoM^hJu;7i(*t8GVAn{Rzg-B7T{M)2sMQ zvZg}@jF_lY@z1i&OGeo%t2#$rtwr8a$rszIAG4fP*({~fMx_%Okh7#-`lPnKV^@=X zrW`$7C-N%)t6M^ygIG(guqLz?BT}prT~R$`w=gy+b>;bsm?(iKUgd@Az*cw{3O^^; zgB=t0Zp6AWpwkYfM)BXlw3yjKJrdvjDKoHwfV}(LfeZwZQ!8cd*--*{P_F8u#|&Re zHCeK$vHp5LRfD|C>w=*m4D{qG@YIpRj^iAsqExN=Vozj#SD;gfzmUBq!Yu2*fX3!! zK6fIxuGX%ZRs6HN#K=2(BVGUENIm@H(S5-eH3vIFXQrPw*AFF{&Q>D9*TlI$brusI z3L70>EqEB>*_4(EYKXAE5AqI-q)0J^@-SZ)y1)cMr?%3v0JFIhD3-t+7uL(>TJk3h zyUP`4_iKvwSy`1zjj#u}Z_FUq9k8tXBN~Iod(FMxJ{G!G$=@tbM=hHW0|T$o+i};| zrxFORm9kLXuaNLH&!MXV_qd9h@I;12z4Ya}zWxt=0wB88vhO&*9_hyUkd;h+?bzJ2 z-m6`d<3-Ck^LGp36gApZ(Z7i1=7{olz$~nmP!ljn)g?<5DC zij=&1dOkz=fe3&aT}+9zW!;HX{qczSr^><(ot80i`i_dpMXYGvN=KIh+<^;+l1UB@ zlfIWB$qWeKI6NoVv~0Q6v^vs{A;4d-tXq`=Ul~xOebtq3EBo9co|h<6s-TJNZj&Sd z%4=nNl>Zg&rThbr6U+y5WgTDR@M&`*iwO&bM7$oirC6uF%fI*W&G~^}rg0}a zt1G!YW|ks<6Cx2RuSt6w(V-{OGd zj7;n~IFo(B&G%AbUG&FjUKdbDtuDL-gh*jj&|Uhl`Dn-zBmQV?^xJOeWQpk}{My0B zWMAzovue?#XNu0t$?5zljH+6GC+Tz=NNIg6xQJ_DTZ=m+82J~vg$gdhvNWBQixW(H3`L~|BMuGsDV^tMo+v2cy39GP)L-a@#d z`yl2%Jx$~Xri9$x5h^X_gM@=)wC-=O(C(jurgT{)PnWJCFi3!L)}paLRY!i@r1Y!G z?Ol(}d3iM~1t?G*5r|s?g~FGBste}JOH4YR)n8qEBvdp;kFcQg^(6*B)UD$|oFO}! zMUCIvgoUj*iT-vEwESuD!A}06MPo}!jk-Ho;a*>UZc^89aaL#95Ga!-Lin*OWqbSE z>b`Pze!h^q263(3_DY!~tSwiLRH``s5S*8OI`dL8Bg?c_I$ zjf;#-3=Mz7eULl4-EP?%O@PqB*^5Vyaq}%?^S2}M00)fw1>Or%DykmKWUkj3^(Pw= zt2Mpb?SK#;!ZZOg$<@2?O;UO&K1kNsGhvJjtS8)-5-wHv7|YIiVt1Ur^y5$GR7D7JPK_g1lqCFIYh&y{RYQCXvP4oSPeYMd` zA3rbkpPh0Z|4PqnF)XF+l&K4T#3jHQgAtWcmK^Gafl$LA<-28v>g*@5L1)4$r};7a z{j zf}X1@;7U-)HRsRpxBky*C`FfrBh7pMUL)~}Lbl=aDykU&r@JG1n)l7&iyq;-7WIrv z&V2^Volc375Ws%TK|_{H$PPV!#kgEsE)(dbMQ-w0Umusva=}{}R_|jwSO;kndF|iy z+X?TW0p@=DV!7@C?iaALr^$-1PZn0PoBh5sNckc)^DTY)l|qM4zwN^=b7Ap{gU;3L zMQSQ3^&0QN%^lb6Q8%-D5i|>yQarnVc~1S%7c({{-#)GpWkS#A$~OrU5V86E3?vVM zGP<3Yj~&^}=K}l>>Y!$ALFFQ|`wd0Z)YM0Zh!<(a%~iMG)YM)B^}Z#1nuL>O|Ja*- zXurkgE?F`Pof6Qqv+{e6 zSX8ZccM%I~Yo`o?tnNH_vASV?WMs&r8S;if^+)pJmQr;8Fg%&6UYG?Q60Es-d2SkI z!XjznlZCwa2Ye5wa;|3`o4hAa$%gVAEl>Bxdkq&_y&u6>Xs6#%yhjuIqU+VW zp57kUOk7;NmB?`3*8WLN|DPj2Nlk~S@tneIFt)}e17-yFp{X*Q)pX2Ck@|67ugRIf z!48H>%;qc6gYoG*Z?8~YJ1yXri96Zy9X^W-^{Dgy$==8CZI|~3O&7%H`?LOKSrQ+w53$c2cU;sN z>^T#8*NF+`RAiHDWG6_2JG84%)ZyYv8Jo#%xr-iMi-q-%cwElT2}FigtylTK;<>Aq zzR+|%=W9CZj9;-5D%|G;83_WZ=_2nO?;W0+UH3coo8KSYKQal+6l>3O_FY-AIqc6( zr<&*1eQD4?F_36jlYQ;j`qbTx9@NEr0}1}H#(OHQANeI0!h-r5vvUmMJqsacX0xS8 zzkdA+$U_&^BjFrdal;bT(4e!ZS#}1|5Bax4r=}|%vT5#j+};@N0e_Me{;$!Cr5w}K z)w{5&<*+(fOTcQFAlNc{4qRqzgz^d<^n7=|;f5Zb#u^z3s%7*uWeq@}%npNz*TB|y zwLx80Eu_w(4%aZ*g-+_BHx88K&;c=+t=cF{{mq2xRH-ozUG17|2=@VdlRYjz{_1Q| zV=Ja@lTX|7VZy@iRqPzU1l1wS|tNO2oS4RWj=RYz3tp#mYsF2m%$r`J3rJ=T_c7oQS+P%xIxRV_M&W7LAm zG9`|tp`Q0VB@X>2@LfJt>r}RQtbMbPpVRUi({Odic=BVke!hCcs{}T)Crlv3h!&@r` zJ;P4ium=WT@-N;iTMo46Lk(N;h(dwEebfv5o7WfLll>OJR~D1(@f}1dY!DVeA{z_6 zsQYm(I;Mus?6W(t(aTLdX!sf$yR`*QQNR3rntY8iWWL)&90%9}(Ka1$rIyJpOjmL6 z?Rv2T4le&K6hD7GCc!69b637k{PmM06AKXA!B7==_ICQQ!qJ}{E4ICL;r`k`R0+Vh zW(4JD_oK-1?>*i$V^O$l4O-OK#6iGZMycQ{#MwZ!n#odC;OARAKs%S0fAK;=_#CKH z(JvErSI)X<_LhdMMZI{NmENpf)n-wZM#{&x2X*UeZzrt~#~1zSo1Ojs1s>jtm5fX< z;+FY4Iy#Jpn`_fIC-&zqu$3}tUSpk{&i-pHHs`YgbpFB0#EV4tqX9i8AbOZ2Dkb(2 z2(cgA*u?+hm}xk_=`<@Lg>u#PTeh0R&Q+*i!_1YVu}MfUB}bR+YP2lZEe#^`CDx;$RMO3%6oXK~JzBNoG@|9#mh{UrhD6&psTrR_33OePKr&K1 zd=#GSdafKoz=h%IZrg@$Ph>CDab$lDT~q`lh*WZdaxH1sHHN2YYyUd$y>l)!cFJ zDP+sGk1_V@z(uLf85e}lz*O%?c2b{P*G8qf#6b4i3+fA!je$`4n7|z-uTc5hS}g_? zREq1!FE5aQ5j0RHLyo3X|DNm-M{+3juaD*n1`F8rvS~1c(R;W0w^W}yZ2rkv5ZtpS z%o~xg>(-{rOiIwPfNzvSxbGYAMQAWim3e~E@-%>~jd)=<4So@AMRu2czzN|=1`J(An zzo&u}qT*;Cs`-YD3;|Ni{N|0>F8pbvhV_F)=uGj!C)qvL-^&L%%@C%sHJ%4mqoeHU z?Jc2a#))%bDzUVr_$_6aUMDUulINloLeR(0Ak($tPzTrzzVmgCy8AN~O4UZ#pw;qb zp7x*LFGf~w>GSY8508Y(qtSXN^ICWK-|tMF@6QLjxmscw4Z-y~i>iuJw`gu(wc$Wx6e@-T=96 z0s^jLoAu8$8l^8l42(Fy`^SU-*Kb72-k}8fOw_UO>j6HkpulQlQ(9s^>p-K~_`26! z6(gn>cf0VvUob55hwdefaeSw>PoRqED2u$j{L)g3&s3>CHCRhQVdNBXKjUHBsy8={X>fBr= z=GbfmVVN&#Y9Vf5hG+izOsU!mXn}*^ZSmiig?%;bdVfNNL*&(nW&biL^$$q+Kyfxz zMu|fRHSauLZz7|lgpR1gz2pD$%LL=ixhg)|cbeWW3am`?WG0kBxv8b8kKiwCaKU7= znDbqy{z^(uPyfF!Wb|5!YoS7HIWY@q>-gVK@t4O(I~OX)7peeC{qXBbO!QF)Yw+&cUI}Q2 zL`6k^sx|%RUijDVMA4J6Ey!sSEaF0PF2gM7Kn7i3Umre>54go(uQ=x`U2*mF^pMZ< z{O7rWKcv2q(gg@XeCEf1?~#EjpJZOhD=MZ{S3d@B5>s`S^k71~*kT?T&~SunUH;z( zdQgSxBlnil2r7&_96TrL20ec&YHBzY$Oi>e2mUxJ%?a7eXF_swb44A)|9c&6Wn*V! z*r_up$-VH4YgtPx{A~+A=T1&aJUsB29QK-{X%oQKr(59W|L>0+`^XYakY6fsI-FDZ z`($}VXHC!W4YMstrJAka)H%Xh zHbBv8ylODD&l+(+{@>p&c7?32ekyKw7oynDnKHhy&q2AZ+g9*32&}w-+NY3|1s#SS zQFBs5+*Cvf`~gQCQ2f6)5cZ4!fx`+OH?*r}Wi&Lrz!WxIoc7B(+1_l79|$Dik}>Bj zq|@uf{`=;Hi1@)5AsDUyK4_$ohx1uZ?z5O)znvYEs9(QQvbPxE9p0s81igcKe-JvX z@-_bZTO>EZLwDw%QU#CHNaYXJ$k=PJb22-_a&tcep!84iABcZxS&4@x9uVsT>&U@2 z){2$#BO3N^pmr?}5|ApAa{LAR?U#nn7t+-FCqJT*oyeKypoR-AlC>B+O zbTOzH{y0)uh+vbjvO0idIxRQ%6{tV5v-5@Y^^tmdslR;v`u*om*|oJbpjwzMc`XWV z)2(!KX4PwRzuRm!MjT@-_I+fosnJ1=QX$atRTt%F2Ntq(sHU zq~+(MW$5dJDBHH&*72U6o{O9*G*CtS=UdUAkHfogwhOVahm(I{LEb*;ek{rKQIvw8 z4e_S}<|A3{J+ockJJmAbSoj zX}!FsQ)qUdB_2cI!0&sSzn0;255^(M?ATDrCS1H=q-3}2ryK5f_UUzF+KKEYFX$Tg zEFqpiCU!Y8oG-`<1cfjx0SK0J^WJa_ob3dSFmc zD}iBBpe=nh1YG~Mq+^ZRRIvpS@AVST+WH2Pn#iK=4cR+ZB#2gp%1n7v#6*QEwC~$B zfsisSzzN&ctLE`WY+}^hIR-cZ_TKzcIGAy>ZMw6(N!=O=XuX<}Xa_bg%rL4zUX%j>>f@($(LIcgb3~J(}(1e90OV|E(iJ*vr zJ3j?Nq7C^ioH!CNfCz>cFFV06-{#|@xAA{(COj6l?oxkS)DYOyK_JNdE{W)w8Agwn zw4%v2iSZxTn)KMwcwESUP`L3uMZY)n_IRl(j7ULOm;Z17auAjCLEt&A4m&UPhvPV7 zW1m8v6Xflx;ayRkm^L{vF$oH|c!mjCPRV5MPC~sLBzj5#)aXL+t{BvS2}%oa)WVMf zq&AV@{K&BGP#eX8d*!3(f5GxUUwO#m)+2@;H>hgUsdzpGfBW$20~5G%gewaz2Upq% zO4Q4H%YlZ*PEFC4ELAKXH$&8pn=?@qldD2?i{~9-M9U4v=AWV0vUw7_49Ur@1jxX; zAyZ3H_cR4iZ6ZoW;p;^Q&0wYG*n)J>5ayP_Lki4E5E7xf36YFqq3ACIXpp-xf2I^+ zD^DN)_mTjJ*A4re-fCcbdMjo{(y-!2fNnkT2o+GK!@0fMu-@NQO25q^mEf=`uHv{` zHxFcUKx$@P(LvneekKe(@D(}ZRHtF<8_Zdp3s-pffr5AtvrcZ>7cd!c!`M*Z>QKUg z+u|f)p-zNA4ywaSK~u7^OM&ao1{8(v=KWvD;cXO-=y27*{D5WxeWdxf2>;svi9Nr; z`v8f@-sJ$mJAr=urfq*blHtFb2zF>$1qzk)`O4HzWvUUStQNmoNF|UCIYlLZ*J;$1 zn3;OrXGnUTOg9G9&Y9IpVKEm~4AJpU4y_+)U&!bkQIjp&Txx8BP?eY0ny5i!kRkLU zsq|i2R?dVWAD~6+!4o3zy8kaW6X~9Q5bGE*9JMBQHB6M}8}-oDQ;X4fzh%lXwEx5h z44vtIymq{6+6Mwc0anXtgnmQvs6_$G6dx%W#L zPCL!@opzv4^}wP^p`oM~FR&Vr!lcgQ#3w6N5D5G4K`*WR#%l&( z1Z+sX^HcZrnDW(|s$BoqM{|0e>c*jVR5Vva@OXOELW|CXA22~55X1`ne!yV>mj@L* zy->7~!-ANaE#&`yd@4hYp)-68ieg8sV!8*nk7|PaQ@L<}9yfA~_p>+#h89l_GavNb zo}R^?!Vx3{+)k5Apd+%#4RRsb{v7*OHa*%`>aU0QRwR@(44A@Li|VSQAU?Ra$q zsEnL>@7uGl`fc7u-84lT^Ev+g0Jju0d{}DFMFw^+ctIK(M|fDHD=G>;B@r$B6poha z@yF!lIfu#kd9F;(PC|zl=yHMxObP=z7{2>;92OTBdu)F9e@?oEzOj{(lT!69 zpx#<%>ey*G0n~;V*A#3VfJd4}B_J@DO`((`VL~tCQy;a20hKrJY0I{quy(jXBNIml z2E+VK4Yz?7Edxc)g2=p~)w5sv@)h_4fm@zi1zi@H|2}adl|nzo{W{ReO%x=o-N25B z$BPLvWXTAI4o*}_V0o;aj(Hn*kQ9wW}(`6@!xY$UMW z1iNAHPIrrgLxMYrO3Tcsx|)gsKqbe`(JIX4+T{eq(La>*KhG&;5bNZk3a zc2ood4aJo`X_G+EycvN1% zy8{0%YHxqvRvFhCEca`#QhxM6WS(%cDR-9qc7Gu7RQ$Iq&Okn%0feGtdhPIzOkYmW z55U|cDR&wKysD1dSOWiQG+4&L@t(2hXsTyvF-%8MVOY3ylTeeGX&E+|!r1E`SyqTb zO-cM8#f%oeVFHv1Q0;UCylyP6IYlRxo<#l&I}(L=&FwQEIA+hA^Ux5ng$J4rB*9#d zPBQeoespnnZ6+mUMoT3saAa3#H=&=m@?Zcc8x*kC=Di&#LGnra{tOg=AShOMXWU}>-XK@FeVbVf=H7fg{O9-v7uu1k>5UgI&>DB_Q;a4y$Up(pZ%$Ni z_e0blndlG}V)H(xJ}y}UnH?85k-V6=_$ELbvq|T=pC*Uuw>^_uzYG2iKR~6&LGm0h z(9EtI(&zqG!|#~T{R(pXGNCUjx9-!ApzvR}knBdG0NPMt53vcRk{W%`nsXR4%<;_~ zn>VB(6JgT=F-V{1Yy}o_Yci()2b+H7!=YXPS$YY+)pT%ikMzOJ&_Aa`k9gQ}DFZg=v!+GOfH-DK=KeBpx z{+aT(OylNo83$w-RiE4Z8~^aIC#KX0cs%>|rzuVOY4%dBHu!g+O;5nQ4~oc2B!w#$ zU&aB7D78p@7V=C#P2MjUI|9)fe|+8hnc?N>dc6O7C6n;w_-D$+2?A3d@RC0rlK^=d-Uk!oSNn^wrcN0LiR>a7+yoieT6X9-JdvcU-Vm7d;!8Oh2naJzYt)Tg8^waTaYn! zJXwLBMxl{{yM}0naG5RQFMSrj#A3;cNkEgOfjJ`rSPwOMN!Wqyd;;Uiotpif<$z#B z^Vy%x?*>lT!fUUZc|ceVOV}0Sg1sV+AwDZ>b+e~7 z98k>2hTAz3hmNjn=_R*f#EQf3;_`l-ijK7d{v}p>{GlL-?kWocJL_Z&2dH^brcBbbTCP+BP_z8bHnNdHwL(df}1Qkq1JdTKK z?IT(n8%57PG$eT*vW(;eB}T{)bgFH@&<>kCKr@pWCLH(QVJUKSZllGhi^rRQNx=?^ z1{Ydh{K7v9bGN4yrU#M9{spd)1nDjK6Z{i1g+b$DGq@R}p#Zrd=^p&=r~1t&+U5@s z&-JO()4GVX<>cxv8=aMvTk2Qy&6#cv79jvWJUli+MAn8rAt51nET_u1MG5)|05L4q zcQ!Vf9ms!Y^#FcQZjTGY&Zt@MyOY4>)6hkmP*lJX$s%oe` zGt8soEjNU*8_bvMO*DP8MWSRVYq@M3XYpm(4MG4POG#Z=^jOI^R{&frIi+j7KtBYe zrqey*62&Dcc`1(SATY!ISR#@6D$i*uo3+~FNw>T6Wf*ZdLSevV&q}OgHGm3zLqG~p z_mMd4*H_f4R|xdKaz(alBJQ2CUEU)g~a@80#+78**kij^561?!YBZ&{U~RBX~UC4OcMRXf~rY zvZcx5a(E#E4YMFXA8F}(fdEx$@#X{QAo#;gnexC6#&LZAghH^J2h{L}A{6OI13!pr zYJXL;N{>x&KyzC9Xtbh>g@xsD6Zrfo-F@knYa^&wC8O@G7kZoTeO-==t0|g(_+YVy z`p(SkNzR#@FotnC-55)nPu~;@FfRZjVVAc!fqZN;@5eMaRL?QJR_%m`f@eykytI6O zr%3Sat{zZT(%!1}Nnxp8N4@yqHouB)>H_A6=tJ;ZM)(Rxu80gx_W872n@0omDLHQ@~v z&wn}7-o%Chax>$sf^em}i^RU3C?3e`_Hf$F_5&5w)}#L`0zkkUMFm9xq{KM?BllX? zEhljG_qhZSu8PxEnAH;6!25Um(a!Cxj$^j_VJO6Aa}$ZyTr9 zsiR;SDl9aI@8rYaRQ9CMM#sgV4Nosm6W=K}Q zdlCiY#b)M0Xy8Sw!4nW+CtV^eq(b}XDaiUm3N-Pu@^0x3w8E(py*UoxI;%l>qrycW z19!OLvW!hN8PF-EkS_;*Ad=~jjj)i}eL&-&qNSys(j)yhSrqyfngVxBu8uw(#Mj=I zmZpf=H<)?~j9Hm*G$D{CVF6b@h1vuD4&(q#nBYEO_H}P>zaikH*-js3 zx*ob31=7)q^R*cFwe$#);4s632_sw%J3`=?w;f>v5Y@?Y2A;#orX(E`6BqGc5K^=5 zOI@(5op4ALYdo8DHT6{L0%ROBjCxA(>u<(aOQ&w7`nP=YY3z8yzQqTZ7z&(wT7S?d z#at-Al}%70K<<17?*jKyE{BZL5-n9DCDSGy17DyAmv4Y3I|^!gR^ED4~u zjt>d=Jro}TU!)T(p=3RPhFr}mC7f8cVH+a0X;ibQI7+biZ!G&2GXoWj1)|cQK3@1; z^1I4*7(1H#j2qOMguvJvcfH4gF-NVp6Vx)*tM}O&)?e%DO|31Rz zcO8w(!@ASH57g-bLIT46xP*@nKV#dAlPr$`i3ArFC-m#n{lJ-C%S*B|Z{|X)BL%1Z zO1Q$lPxK8itZ-oUo}5RV1j7Ac@EZ{;uCB7K4S#G@+%?TtBD+mN^}xSfZ>HHP6oCV~ zT_m{6(eYAJ_6U&-5}Am5VoQ0gi(ad70v0+>=+We*-lh1Pp1!(vD9|-DtWE&1V^W&X zu`eP@cKL@K1{&gVmW1?L1U7yI%Yds)huTqpaZ3bg%7QzBGY{e0n8AJE5ROsl+*U$8 z+13$;Hen;Z)ECWjsMIctr=&UQNc(ra4i2_C%qm5!E`(eiIvDh<_~m6~dt;`HxU`k0 zfXwRqygXaB{c0;7fG2ILv-I1J*c?)rbg&(=fkF}(pEm0TyT*ep8HdTfl#LezCU(}e zV?Z1+1oYZR-HRiD?Eo2G9TpJ`BjdC7+OO(x+4m=WML1gityiAESZfq~=>Y&dTviv0 z&c`hbbcb1v`K{m9MVr7+mx-01=OKXB0S;5m=zc7#|GK0+D-?kH9gp9$TmVrqN?^@{2|W5|ApHP&6(1lJ$#aYa?shN$P1DJF^DL^dL|G{=6j;Et&@0nF z^e$1lR7*)#!u4uF*Zm}HRKC&1%SdF9GUERZGgs0C9Qu_@CYB;csK8;qlPKbS zbZEY@216|N<%@ZTCk!yi>Am%mxB2HRjBE!2OBA5#$O7e$iPR5JE)}g$_y8D43K)h5 z)8(+mFK<8N)pg&NYkcd^c-h0_aLXL`=n(%31q#@t_`G#=T;4M~uNO9u?eVAR90Vkd zQ8(WxT9d6?qL=3uY8``>t`<#LH#hMVHd5PtefNM<^PkXHoT3+6oT49@NG)%nL|Vf! z@S7)@Uf+ga9>DJIE6z+doEd*@N!>_Xt2RkjbL>dg^QD%qEl9<{7)Y69-0|_2ji4t% zuhowL$3lr(jfYAF2@gGtZdf%K9+UhHotlgXJG>4y^>*{?@jgbtXeo@#cD`w^LrOxeLgZ4{&aN;<#4kKRA_2t` z{NL${_K|G?m#y*Jj`EQ(;C~o-Zx7u!cq>8+ClGQZm&a#=CYUdiFj6Ah!q}QDQXm1` zSIg8J&A!W=Ho6^*1#X;W265X8+-M*N!27&yca{*2H2sL0V8y2(8D-#Dzk@ zHN)gT=DBYKWFJ5tg7tkD>tMM>C6$IOua6QB<7ZGa(;q{Ubm4X2P`n{fy7&=FOXo@2&GGE7 zMh^IrLowv}C#gLUL6LbIQ3^tR)qO;4xQHNcHnz*F>+$VL>TKqqE6dduiZXBa4$qFa zD;fHi+j;D|=_O+~L3E-CAW8j69k4_xQYvX6JP7+Fg;-SBYzT|!YaMLEWXO3Hrx+UC zx(>^Li?I6LdX7-FnbgiwlKr7nJVgEVOKHOe;`Xaqh`kppT3z_`AtVTpDoSSI!+Ov* ziT~BfCcl+du>^Aj%-_UP0vEXlNF)ORPZ&IqZ1*3pb?F0y93Y)nsg5HGs4Xx9@mEXCw9-wAXVB zoAy|75UTI}t=2&hhb7)+ACv${_*E7| zG{^4SEuv8d&qc?_#B3~^`~EYOYx57#LOl>w<)Xe}V?K;begJ z8qMUif577;MEvyiYliU#dizOfc%VdKF?V*qX5Nwxu{OJ%!Y4|FP9J_Y5_v<*=qCmO zcG8UMuSjt5Sz!7AOv5tKotw6Ispy9xR$wM2z+)i*C3(ONMH-zAWvia+zNze5Of>C( zQHp@^=axD-F-%6~6bvv};RMnUNLT^b6&`g_>I~sbwazbAP8_z~WgreaBvTGr

    kk z)0rP4(;Z=ISm5|cK@*`l7Ucz$zLMcUPhCzeAti~aCTDXo35iciz{>@+YrcOuDHli? z1qB$;%gZ#19SHkJyKL=mC_IB$UcsX2z$`pGpu%s`%oY=Sr@`v+==af&wBi^gEGVF9 zQkhjtJ^)cgfs;F<;olvm2=rve#IBd|UIU!E;VM*eoY~{gcP(z`5NJvs7D#U}s%pW* z`Q4kzq%r~UU@{bot@t-n6Y1*Djd!k_9IMYws9u(-hFC_bNEg2Xddj-arZ!xxFMhS} znnHr8pfSFNO&^N6xUidOh4y{9EQ$W~?^~F`ckSBf{|$wXCax=O1s__7@>j>&+=;*- zv&zT)8%6q&jwx37$n&tLFoh)p)OBFARW`3cyR+bo4bUw*qOEeGK1sr=@rXucoF2zY z93La!Q%ToMzy_-Yp{oc@h~wZ@c{o&g*;NNfv;Syc%GoONpvaqg^p#KFgj2793u&+#_F3QvCGku(85Rw8n8co?-nDi9fjtI)J6 zmcws+OtoO;j8i&Nk-8(i?&^!tBQ6=L5e;gE@ex4Lu=0L7S8SX8Pnm&<@z z>EhE8($b#d|0bf<&4v~+K$`f$iYtpr1t__|6-l66u;B#cQi*1n|E_V!RKk23_UXALQzD7`5uN_!%YMf|}bUR@HLO6&7qs3a9EKBu9mVYYNQr?@vWuX3um;b5(Z`OZ4` zq@q?qEhlEQ>B0+OcffrId~aNO{AUCM96h2?!-(o>098b!)enSWtA68O#pR#1ENLPm zBY#{5M}@~aq;Cbq-^wnB-tSnZL&t&tN{1K6P~;Fse|lGEGfak}oH4ucx;fdvPl0#u zkzLakO)zA&WX@p!i250IA^#|FgEl4f3Li-g8B4z52n*J(l2|UdusERK5KE~Mu#5t$ z^cO|~ED7xYnIvLW>*n!dqP+W4yYw+4!g(`+5NoqkNj9}gN)At#%bhDCoEns(tFG30 zs;*dOb@7q)#Ez6jn{@7X7d-+jC_y+;Xb1AfW~-TH{usP#mJ#VEhcG}a^!)5RRm!F9 zn$H)3Qsw&5n94%^K}DTZ+W* zB7bf9qG^v2!;74_viXQ`86h0d58e``)*C=AF~^Yk=MYgU(b^&%sS;$eEO+YE!^lNO ztBYIuSg90R$%tDTAxr`P7rQEDOkz@#Qnu|l{QwiVX}WO?;lLtR6P|^nl$>A>w5Sm* zul)VhO~qh!TtFO(kht?~O7U<;(QaOGTQ%2Xrm%$30-ik%LDZ4m-8oM4azIYpC5L6g z3SxufStHl!xHUc{g?>_!=Ne5|5|s)8xaWuA^^leuMa^f6V^469urr_H!}T;7ll8G< zCNV5Dh>T3|l|RR@vhEmla54)7l6GYY?y?1306^*l_%*9ENrzc6e|~FW?G}!e`h2y+ z2O65W8PShSd4b9P)6ID_o0CX5ji+RJ*neHkLE=R64_WwCX*K42?OjHc)M{f<@{kLE zHL(;F(B{eUag7s2dkxlQhF zX;ITD99f0^*UrCr+@BK83sL@W^jKNARCL#l=CB7h=vA$ zBjJZo;lDkmyRsZpkR`hp! zMRC9YvRqZz+5y^FIx8r7r@h}<#Ro^#_8m^!m}W*l?^!OS?$|JAK7@w$#JAQB4;G}T zH`>ypRZL@h!&4^!xLlo@4C{_?J^}_SMLoUMLfb#}9-1vkws%gOe&_#VPwSH0<0q+6 z>EU3>NM+E^8f_5e30JTJI#KA@E^};!W}vk=UU|b&g-=JDT)7T8=j7vK58gRu*GZQR zA;o)UV(*&?tj0JaLDK|`B&AG91}K<{c8$cy2zbPSLC5qMf7bw$28bYzA}TAW)eP7D@iL+^W0MD zi|;)33}uCdgH@k{hy$<$BO1DbG6U=B74IB|8$^Op6V?S0YZWr4lP7RsE0N!iCFJUU z3SssepD(_$MiSIos(wJe@annsfax#Z1wZZDn}z)Ayvw_obEG`=?^JYM+R%mag zqVC;EMSTd#gaBx~$lodc$j#w}B1-Js?48?_H36%U@N!6(67_{(kqGHq0fmjAKCC4t zf90y+aabB$8>vGS8ReY%b49xEuPiX8{>-q1Qfu4LI%VpT37At*sSZ`> z+{|MC+1(!Ei#E92>_k#DG~p33;%cTJBCoC$<5R-&f?g!u&wn`{EvhhEX!6dLJ|G?Y z87%I+Xsmg#ec9e(IUgQ(ba-!fJIG~JlsX8FyB#qUAU)C3)G9$jn1>1>(CN5rwUZk4 zCVpj=suVW=_-elpWFU0}5?NLZ>UtAd@p^g^J8kxbSP~p>!$zJlAUnDbv*)pVKP}D} z;<`BN$bPcS)hjwmpCgKp8oKaUS*W3)C@=+)=Bki4-yeOo6Y%b)%uv+Ujehlh&uP0y zuGnrqZxu4P>o_11vxgL}yeG%z`0cLcM9=j>ersN8&adVev%)=5&O33`Yd(Y8+P=EJ zrrwk~9#q78!*7F_I{s9|ix^F7rY<{ljcr>->l$d4j9GLq&z1{BSik3D9u z-_MKrkI%lB4Gj(FHy4yXHr%+IcIJF+ykju*t&$dQasl zezf~A#g1x*c>_{*4%!1Bb^My*eH=5&{=o=Cn6!2WtjDG(t+1E(}cZ1wGp-#jQ!0;peVJ^M(k+!c5KB`{|rRe3R_e zhhqroJibMT)y>+yzePO~?0XoRx7YHnAtPku6S}X{U`;U>CnX#^wm+saYlz&()%b|{ z_vJk_jJ!Z0t-NmZs3%#H%Orz4JUy_uwbvni>KJqEgh_&mN{LTM{_Jf{*QS@nRmae< z?5lFzp(Gmx84DMG$=@X!bv}PGXo#j_w@qF|>bItvyuL_o#844X)1yrQUF$jW5K?9y9&;8CV3hpIZRe-yv-RId?hX#;cE~4d9Q*C` z+U-FMI_C;Y8Y&ubmg%jp{nnX$zE*ZPE{T#8M}cA)7GPU<85m0czH_b^cEoUKG(bd! zIZVGx@bBZ@OKov$4&dV=14c}I8XklcgGg4p3G>6tC9U&2HqE!>XoyQX;$zf_Vrz>( z8SRkpIl#17?0G2WGN(TtDzUsq4F5=nRF6-#J_A zWU}Gvf2-E+jZA_(og=64N|An z33Zzdj^-)Lrq63HB?P3D@?<|L@ne=Sm>aYa+qI{#g(5qAV%h{8?--~u++^ues;;=u z&sd^~p7FZwdhY7??h@N~;8vQ{8mosL3U&-XQ$--wqZ8SfUaeGwBi757aQ!sHD88Nh zf)G(~UMJLJ(1zx}%iAg*HMv3~HqZ=L-#T!xnerv)JL%6m`6=v`IJy$d%^OrAyC?w} zd*GLXl`$}$zWPxQxJ^QO6gxBRg9RhXQ!i*UdperPJMF+>nPXjLG(-L?zz)-%roG@xlusL{mi+Gh=K0z9q7Bz4t< zgmmeigr7S&*jI_?zBsR+KEg8T)@KHJiXTiK$l(MFeWZ*8O5j7Lqa+!+Q*?saK7SX}e&Ci$g~(@ZN`@&e061^vVSGAieptE@CyZN;CItL&7i_#=4V{8z%=?Mb&|C zUXZpes`y6HG?24K&IGHxLWMA)uiEv=RNL0}34GI=7P?Vp7M5Psiza@W*Xr}| zA2kb^c3$KikpwA-2#7j^emqW@V+Fse5nPN|S2jq*y*=Q23lbST(mvlitTzoOVeYIw zi@$t7PQ2q)cDnevvq5LjbFfLm;&srsGtExjK81B>W>WbzTCF3Hjl=%8SvJ z+Hp2@-P@X_fP*Ra_8X>&2J`oIZcNYX5f?p4&w!sXs3aJ1dWm zJFIx(jmZKL4JI^g6)zG_=da}L)oMeg)x(aaDcdEQpVqDYKf6#G1)V0C)2u8@Zsz+3 z^ZENJ6OGmSWLiExlyFVmFXf<}3GjvSrAGJUh<9!Khh0y3Z(ePV758STNJ*b&-Lzks zjtri*ND2ez5fJyklmkN{FD4QdwjH=}@rbvm*Pj`44X?UK)Q-6--KMdDjuyWRT0;^g zkjIrXwt7N#W6j{Y&bBx_exI9r`l6NKBr9cR{259HTN7}}ev7?6_(qBjru@lb3V8=h z{=Cy=VgjISPIH|-u}mr#a~vZto|TO0aF(Ut&hy+ zH?L(m+vR`kpmEXa>?)#==UxWwT8B z9M`}q$SQo$dr!t{bIXKnT8dRp-moc13-1HUv>~GQxHDCj)=<$@9@Jv=kabTE*W_8jm!P&;i5Jre78xwk*N`nI$XkR|(%d>UG!t;1G{}5Y_ zUpCO9?f2e%yZsjj@H-;8EB(fL_WA#z4$MgF&(f$=$|w|h#*$#7CIN043v5zEcu1Ob zYBBLxWG`g(;mEF8mAyJ)2w_YZ29H+Y49{lt8QLALN3C}h9x^EkbjG3muyrI=eVQ6( zaAVQrHroMzJ^l8vp4}M4$W@X% z(+f8*Jz&3za{Vkj{xIVj6fwOlX1f-H_IUEJF3b0C7+c3mtelP6kG3; z3-bhbV3;`ayy-HUJc_5zd&rtb2Y<^TE#zW`AeS}K*$ORu&J%q3NP^Zdw@=!R-K%l4 z|IJse;Q}V#tLpKNiA*4<4BWh&?^s!7gp%N~|lgD}XZf;5PvD~Vny^A~;3@OOQ6 zJN$QL&)KYjd2rje=rLj**F{2URFDvaOARSgkhuo!?exI_EQ-w#cKZs-dE-6k&;b zP0mU0R|=kp z*wETZs}KRusXn*Q-V1BKFrWABCUhTg{6hR+5+w%5FDL@J z?lSjhs#0Lxh<_OM?E{C&S$!Ul+>peZ2j*xl*=X@f7p#Lx(v?uhLnTqy^RxdmTRI9! zJ-G*wpbwqk@V-#fcRr0I@~JPgb5#3W~dc8Lu$Ej)d3oPf@P)6o<<3^1$Q%a%HI6hnkiAJ!eZ=;gR~WX+M+t-eYyKu{nrg{zV)TgdOf22`b@V`DGoQC z-ZgW(F1%?PUt$;(i1-p*=rQ4^mVB~5(5Wk_D)Sb#uOgyP>kRl;+2+~n7gGH1^oH*{ z>Akv7=M@VMfKErC0d0y|EIm)tSq51K5q}n=j-Qk&KnrZrR(>bwLyW<&SOj1jRp%c# z{zTl9v68MV6-#>scDo!UMCerh4hkC9d4sCZDq|r9+P{bGcO?^hnDljD|0~V`=&WyV zKny-5WnBoO?nq8rYH=`?LvjJOc2MV6z0_~R6@^IkMC3EB;JyVIVL}MS5|jMJ1#_#$ zDJ&Esq3-W&o7ta3rehjhpzwyXKVKJuZP4fkIe5i;dDNSk+0wB(1RglRl+#<2?lb5G zP7qG#wY_4gxD8IRn_))V1JL=3jC-PWxY~;Nv_8AIx#e;I2XI+exa^uz z*nRC0-{`iZ8ncnWM^naGQ2>tiyURvYLMx$eAUj|N@9~gH{?_!gedm1ohhF5mkXp~! zi9)?eai0Zzv}Izz>vF`JwC+rwuX%BEoYMW6Wb*kch0&V{W2j|6O3I%p=rjyZ=o0^1 zpxKJ&Yyp$^QvK2$HUqi!_Bm_q^)WE;?SH5GmRrxElajs`ROdH{a~5`PW@8?j56cGL z-_xJG5LZ+8GM&di#Vw$D8Aeng$)vDw@^;4=JRo<4)Y4r`OKZ0JKndt&m1=i%VQYc? zp)CPUplA~Rb3Q~AWUAXu?WKeBQ=`{CzRRc5gTV(cQMqZ4jfkROrBZI`#ieQEk*>#{ z&oT2SD@D6%9Q68vyUHq>y0S)&EP+Eqlq}p_9RWqzHF+N}D$HM#`4+E_-MOoUv}R~4 z$~QNQ1QSf)bd}h0LVpgY;^r`hj(=SW{W`-*UwceX%aHFki5?0K^KglYtX!lJyppK+-%JL>kLu;yssRkc`#U zVryQIKMCj1xI6{nba1|zE<}BZAsPFNOwPWL-g)&KPZ+f>F$q~`MXk&b zaWeUoLRtP#3JRBD@1sL~ouprC@#2~1M3)!yUwkBpP*#;-VEvwpT~7oi`xiE7R!lQI z@7}(f6goS8XmJdQ7J>24|XEYp5fcFXwj)uv{H2b;X#seC5dXCCz&seuR z>^oSAN~&SeyE_w+mU>g;7RRAnkiMs;Zw@y;;EmN>yDB|7u^hl)kxR^Z z?UcsjoDM>e)4cZR+IT)bzZrgWwsJXyqsu~XQ9-HVmJwN%i zG-!yBzHBZe1Im7Rgj_a@i-dJ0E;=9Ws9uJ1%^{z-BL1rIvZ`uuZS7dNm!~koUz`@s z*FbBTD+z=-h~@XSdNLGOLW(K(*r0(oAzdv~P{Bw?;y2%QrN`j^QCL2PLnD9s@x1p> zkJEU(IL3M(a2;U3lKkfdkU)_g-)!>g`K(hQ;CDcpWs5U3_{VJVh@-&VXc&ADnvvWJ7fSC{&RZ`s)*uX%ktSlCYcuP9FKmx#*J@1I>S($t2N(CGYQl2 z#~t<_Sb_qJ-8%slmDuwMPuGqs_|-R)-z!9sS<+QcfW!5+blnLjzo*A7$=1vb`Ci}( zR}?lB28PG=#PA!RfY$bd1Q7F4(ybGXQ)3PAf@-Dwd(Y$H$~mX(NKi zgQs8MaPd`PWyl~pY-mhoe{&Qe;y^w6)WF}EZ?iv#JenDnIW*nlTotDT2b<#OM)@rg z;c7?Z;9^vjPb+Yq4rLwVhaUuBw%+QqO`d%Mvi8^OkLACNAA?xCc>_%5H?i974YiGRM5E-UG%<>7_;obpRhZidfkUlyT&D>2Vp z1eXBLA=3r|$$EFtAAZ&;<;NQgf`<-@(F1dTt3^kO2|203%4!aw_Xn%b)IC0z9UXr< zH(=8RW6#DmoyW_~O+TgmoUlg5R>yJLFoFBxkdYealZGwfZ&=EapqMY#Q(BUppQ$hVP83EhQ2H_D51-YQnoxtPw~Z z{HW7Pawr5pUul%ep$7}}MNR6qht%80io0Y=Qhtf*0xEGEma|Mqd|Mog^=kQw61u71 ziAOW+uo`=bdB-lY?e**R+0aQB+)({zi9n64j2$Q5C%x8`)Ts%O%P7n#!(q0-~s&ci@bhX=>%bs_H5 z@Wx`u5O9%9PvKy6k9GVnz1&D7B_&tqPjYbDc61F?+mxIyz;>P)v?ZDxE-ku!qt1DT z{3_lDY^>3b^zC%tBDB-5>fAU`mN94#s245 z=#eb=^%bNG^rK!Fgv~fxl{Ovqak{#~JvlGB^}*OwgpHe*5qFItfRjE5GWKH)H8N<-E;jAQHWSjSZ=T$YGbR<}cO_Bsb%-I|kCvQPEeUV_rgj ze&UUqyS$m(bz?tm@OvU2xVHcvc|k+jmOXx~{ZTV_420K!vDc zslfZ-u}A%~+ED!f)OK$;ZO65E$B4dGVap^XqMj`blyqnh zCp3SFSJY4n7%Z)al!g<9V6YavRl5!sW5_u+IN|+z!WSyML9^UDjZ$89E^dB~yY6vl zd$YYRoT?bQAmMy}F4y29?=ZQMh=a@uHHtI&rNRC+Ay#j_n`IF# zN_zI8`4Z~wQb;JQCpR!;YRZ%F28)!+PCj-uHxMi+5G2@n09NnMGGJ4?dx<6RX3+>l!zJUDNpk-6Y(fuHe;ZG= zw5BipKzl{RH+|)3s`0~9d18ge!p>hdJV#X5jMDjM{Y?az=xUKIfj&UKEZib(9h<)H zswgd*u}fB-?jav^Z!!Z-?(gcy_ggr=RI*p3qUe(3c;=lcw;YJI99Cge=+CX;(MOrP z>m$V`5k9j4Y-2qtKMwipblFaHr-M^k*PNy4&E*?U0~(P{76&c=j4P|?02 zv5Oh@2is@5xhi1iTR<=Ud=#mnqOKS+1lN034U~NQON)~VA(P;0&L%l$5-x5c|^UA za!%;y=R&wH;RI0T;KT+fa7gNfhUPDaFfXv$??!cnQ0Cs7C=o}ws0KkO;1Q7i1huob zzkIjk`KbPA41)p$%uL_&GsB@jYHq!EvkrT`jykZh&My}t$z@tH+Fra(k5Gtr_r|!; za^~_i7LV{&M>q>#D(Cm}3t9;S`V%#X>6)(z7AmW|>iz6aiNBO~APsm#eRmqZ(*1Po z9hWFafQyTgc;u{;Q-o)*OvCK!nKU*G9hO*WC+>45;03nS@QGf5QBuqVx9u5~FRs*R znAX~+-AJ6FWlc}SW8$bHiL_t)z=pS*$!&bUyv`MN!?~jhFND%Yb8=Y7XItRrx`L8{ zd6ufh^6ma}~b0v<}y=%6Oif{Un9lv?yJ#(kV0@HFxxdGg@svGdQ&u zb2$N#ed+NDWCj<58FSch!J)%WA}uf(owD+q)r`Rv3>N#5ff}jpZcmPz+v1LDTOHhZ z6K&b)K~ThmsI2ilEGgk;22;1V2^WG(;U~ZI7B}5od49bSnO#FhO_4(GG4Jkopifyg zH*`zApiR>`7#&K3<<(e51xC!8z6e%5u8qIMzq=0eoMft243Cl=ypX+A&3g(V9U}yx z*is6cbAC26dY3+#H7X4 z>|0z=dT{jac)YUrKGyYuegs`T6lA)eZB&=zrNGp@m~LtuhK;AacF1vzSz&8eettez zom{}C@4C^;j`h4txhc*o#}&z2RKe?$CQ5$F!YAsjv0_T+)oTyjxmpVhV>%2izCa}8@TcVw0# zq5$pW)RRs$I@+=Z(@28R$m+@0&!X47GX(~?svS)^l+$fA>*5gx)D7!fBPi_Aj@3C( zBeX@=mY>Ja&lY4}A{@C_Q(?Ocg{3X*jwNJk^;l=V4Q^7!a_H{_GRS~Qu?zB}lM?AG ztGuR)Qj}(hxh7V{2bXfZ3+5urP$G-{@HXV960}y;z^tJwfp^}Cw(TS0gfw(&H^%K> zDrM2>7Kn*D+c5=nvsiC|GIP*6{EZ#80OG320|na7`@~-rb*B$qaz`qndv%fC>0DW@&u@?l zBCi}-{tS@Xci&tG&X;`eQYt=7&4*C?3nITK9o+eSHeEjxlW0jG?*SW5@JzPY1_-*r zwTH!Hj6i#qsm76O`}E`}QCURnv8G*b9OV7)2%}=9ME?nZ

    mUEY;=R5^z^$C&%XB z-t13LM@nr3-}rK%NYQn;4{sk&w>4T6y{Nbd`M$6O9$Ol79$_bpNKwF?Sr=)G(A)BV`$wG8k933v5eJ*IsMjDlBT5vZw=AL^tAiO5lx z_`T>}fSy>{aJ9MnLNWt}JOX&)#{Gp!_ya~6AtFdblVlt@r-pB({ zRMUW=!w?S8oh+JDl|~Hr0gqaj3gIRx3)*pLTB@|uF(bQ?{`y$YSUL)eWG*wk4wmT4 z;4t$dX;FFufyk9ECetDuZu=?a`h@Q}3d%UX;ldH)TX`b_^_c(ktdyPr*Aw;XOv4VY zTcai{;pKW?8f8Dp7b*!o-hlVJP+D0Dgy5d6wLdYGKGVC!kH=1CsqvjhOfs0yj4jnz zrWKEu$yh9OUr^gn+;XJy_WICNjb-SEbRSV3Qik~5)>VNDNFBLLF=X-j%<+zKODfvX zdB)==?s=U*$0BU7N>}c`^-D(_351+7*4hG5X;nqrTLW4n_$gYahOL#$*iFGTax*oP z*!s7-&wd~8J-L=N+pGY}q~OYH9w5b6){qqpGm7aDeQa50cn9(WyAg%;0Flume@pw- zy-l{T8>D9V_XL&}KR?j#nV1!M^m`|0;azm7`+ImSl!&v>bl{+kd+Fw=6!$MU1_+qy zn;PHis>fPo0!{sQCD*iA@61^4KjFMHv&BA0Zhoz~jcbL&VXD-Rr>=FV5i-G!m5Rkg zWhz&c&mcXcz`V#VLA)1M?~JO5g%YWOOQZiC;imm_x!x=wl$t2VJn|Z91~ysAi9yEH z!(n2khDpgOqN%iNNFYnJN+Ex-BFuI;t)tyY&nKn6Hc<${A3;Gwi%~JO zKJiSFQbsLJlN4AbK;bh*E1J2E&|p9t z=K0O*=Cjso17->-4!-Z#Cq?7R#2;WIf0 zXAjRTR{Ql0ge$Y1nW;U(1~^Yveij|Kh&=x?J(mjRF4!{>o?nsuZ{L0`i%Dv@y?XQh zvySWsD<-|;X@V*54iWr8XD^J)>!pM|KjAqTpjJo^SSK1feH;N$0fUwlv-68M&3^EA zvUer1+TSnwu48=KBiv@ywO~y#GCJH@fOQ1DH{Ubi1^x?YH>%h2heEvbYn>shume%CYdbM{LT zUS@c}Bo|r{6R>gPre|mC1W&>R7h<2+t_D&v2%_$T1BVpzs3N)O2=c}i`>Pwb6MEz( zf(y~&5RLEb5Jln$#?l6q6t}-~g?{P^mt)z&qe`rtr?7lX2Hi4R(VP`H{EhcDN8I;8QwZvAK3zQAfDlnZZ`Os!u}8JufjKd4Y-P39ewwz0EW2~>ghrX|L!wzZ|)%g2{L z>@?+iglwFA3hW*rKYnD4uVRWIbWgrKg|4+V#U(8$IXgUDB&4xs{%i2>S1|h3n=@PS zdTbEH^Fl1UYZG{=4G)k@b*SxG)~n5qXcBtsLpE*|v`T5l;CxhK%46V}jMH=Ul@=+S9SO#Uf&bo?H+NhH0X6Gdq;a_X{g z`Q8$vmdBsR%D{AE$$19=ksYu1J?@sE^uRIAl2nzRj9?$|1rZU~HBG09;Njkba744R zBA12D*lY=r5`K@3eemtzQ>z`)e$KjfH~p5;$@>&^yQgM}ahM@r{Z8c}8vX@AaaFE+ zF=TtFs)IkLQ--utsdmoaddYt*N#W0uD#LLUS|hj=Z0K`Nt9xHtV$QOwG)8Ch=&&dX zec1Xp#ijV9LeAg65RoEyTVo;m3rJUO4^5~Lybwc$pfzzxSq5<3xn!pcyRk8`3zI%^ zLKiHHEne3(=Lf_h=cT(|4~63&v^i3Gcdc6{?GWf0B4rBUKF!W9^9N0Ha(bQ(Wvs)) z_fn0twiL7y=dI_t9vQoE!M(de)vR+$vU_=ab>DoGFz5-4Qgf9sSTbzT3@2tKjd<9! z63WbT{d@9dgkPth6a6%3XLB19Nc zD395NxQWY!kCwZdDtvgT)_V_UI;-~ivx;U@fxgc@17+ggIZeEZ=t*X{*F!!?%2j+J zP_kq>BbqS8Ro>qpKPrt?JlR%-_`_g{;pms`BT?tDY7A^WwU3{_ZjKs?+X1)2nNcRr zTAKXD+K(^O?_Yq+!E9SLHd~gq$=Jbs=Wh8z1M*m|(-s{8zxe|XLh7I+HAqN=ip5hA zVf4|m$eY%DGIPtal+~@WOZ~WOYY8 zkjllD#6Aa;KwW_jRt^+sM!R!!SC%K z6_wQWRh9u^doFDBv=*3(#3jbJAjp@&T(N0xa5f+KN$+&awWav6-GH{JurZ@H69275 z_5Vch1IMv=i#BjZJ{t+9u#3*igT4{d=_(+QfLeK}0)-;Vn7z;Q1eR;cb4#khf5ZTc zneA7G@$oTgZ5No+?q`FVYz~eHY|@qkk^ABK_ztKCq3EMxL7!c-OPRdEgJq&4gL3fi zZrA1SEm%aBzcd2D}zC-H=erv5F$67I2;PCtvlN-LZR|&dOsyAePg)L^k(K9J&zX zpudN{nMvy0(gLDAcOot!ae%E@JUAAmbj=Sm!br8%% zsmn4q^8Xz2Dmz-RT~+7kW1OfwkdS(;JyT{it*NqO0bnTxP@+(?2k$Bwnfz|o^)|)% zC4-2xwl@+5tYW>fP~nk@DG=|S&wYQ*;lXx{Z67iJL(xY8IbKDB&jb>1(Y~UuEJuxNwI|9|6h7dQ zXaTN?YG>-_El3_tq|!K(@AV9d!f?gSvK*h%$Xzji69Jj+&R%5QjCxv7^3EUg%`sLJ z>hH+dd$l7(r73_z+;sM;AZ?V;O!!$-Ee~247y$eCwn|Nly=I^rxUjU+4in5y8 zlw|G?f(2l&$tP#%fEoNFCSNX(ITQ}v{yyCkv8B6LchqmWf(n$`z$iNl!x)9B)r28B6?;XZ}Sb+V%9B zu!NC4KK(@Xx6CB6vTq(;If9y$6Bl!dH5=l?iWlO&`AHRgSpfh9Rx2;gO3R)`oEMTj zR!=sDmX0HA&VbI@Lw|p7(V)Qmmg#N75rlwMPsSn(qSg>_)AlAUH6b@+NH*^o4XDcl z^~1#|mfn1jB{N>44&pi zfz7iLmRX6Iak-vMSYDbT`ESY-x^=)VxecVoi!H(1x@GT85M%)ukz%6)(x_bg#=uLL z%969lt}f$@gqzO31*k@4YaCoD>Is8e&tn}qh3Flz%*H{edEom&4jnXn3<9s4M<#R6 z7kNb3c(j9g+CD z@uo(nP|%q`WG#e6oHt(8WSeQo5Pt}B4+viIc?#}e^IQA~pxqMpdQ*L6d zvrd1sOkuW&d-BURk9^q@{5=Ji>l-e~ro@uW;*3uxGL7(OKuNGrws6!zGeVHwGcG2! z+6BflXSXI{@Bd{rjW7J>v~T<3!+bSX+OjZ6!1FZL06Qk6^hbuO|E3TpXT>Mx#}476 z<(A;a)Sb|D!N$iRIX)@rF<(y3I-snq6dhN0nA7w_Z$j*|-Ktp?6}Ir)Jg|pINPm6@ zKwA#kHaTk2%cn$;%qv+psbnJwV)*p6~F5OCNFSinAplx5ZV&jP1 zUk0~hMdF+YMP%ulj;WdDVabAe^Tz6 zf={O2#350d8(Hd99QX~q723e3ry_QC_R?cYO*GGCmuJ(xt+b*d{|8^*1%VF}b4|f9 zXylL(=W@=&6Q6J2OXWaR}BdYpOLtc%gR$;hDc zj*6ZYXPylGC3UOY=MP*|^n5iO#tA(&aeBPX)?|E7eq7Nz7A0jJF_BOXUlCCPurgiU z$?5*);Ms#092~`{yp;H-zfA%dxnB^_HaLI%`p5);6dkQRDI&p=Km}RgY-&LdQ~oI0GDpU0AD?z@;m)H%$3C1m?_*-hq?F@Qy-&FIlY#)Xe5+mZF?Pkqf}qzBXA-f?9H0*e9D;ahf~oc3rZBZZLpSoVla}Z~wiV(R2!)BQA``SbH?D_fX-&WKLI7C9cvE$q&1Pg#*$LD6q(~_E7 z8V0`KJCCAyb??1+JvZ+bc@&}{Req3d}$YY9nnvZw1F zlJ(%d%m#e4n_HRwSH-7yKu$F7sltt8w0mt(dw6`zmklOr$O`tk0Zzz}1D#HhuJziY zT)Ne0BSHXAYUkc@!NXKqik!dbXDPDGXR~gx1zW$hfZarm?f&(A!1juZhF~6zqyjj# z*~VcJ7d-q)I5maK)Z>Tq3QlrgLsYe(k;CnedA^y~u`#Y5H}7@Tq@eA-GO`SWgc(IY z*a@)Yv45xq*)D_I+71|5LDV!LyiI55ii_&RbX!Jal%1)$nVPz`)K}3|56#}JE?X5K%@3z*r3B@TE1J`s?-QOe@p=vAM&en zY@%iQ1ocI~9F4_zL$%km05f_zJr<7Z>bJHM0*=WqO20c$aiZD158eGQ>s%F!-1y>g zhM5%r>H~3YtH8yM8^%*Ikr4|2lfu+MkhC!fxY4D7(7+Jah1HL$o=wLyXq@oy#s+du zj)&o%!1wP1I}r2D352PT`E}1%UQQ(Glec;?0djIw#R&Qt)d4>Tn8IxO53k9GqA;la5+}t*6r;@O1=dIsH)M?RU&o>%R zhbw~KQIp(uzp{HiCiFnbRCew1(iHw%8qL5V$8&1iX4t31!1Q$4g-ROYdYN||%Q{3k ztMrVXP&l9ofx@rOkj2U-qhA`wWh7I455%I}Wj1ZP+=0PLWxCvQr)388E|5XF(k|Z8 zICIPBnxrZY|D)a1953frAfJnn^Rz>a^{fE-x%>5gjT-!LHm=f`Ng7f5iCSKHG#;9y z`I$K-1h%7rh6gJj!IkLwPBm)f~*7)nXtj8&FZ({7Y zb>Us{m^Qhe6sd+u=f}%t$AE3(9G{!_h@D|08rtP7jO;@gBeFKQ0L|la@+L{cX#4I2 zfnF_4=3(uN%HAh3KvP*Zr_faIEqM!N1B@Y+xh69;|Az0cP?+c>gI}VdW9UxbZJQKo zu)5}~{NO1{j*ijKNlLWJOxKvOquxB@o;+|?Qc==vnfMIUEedJ+G+5FSGl&29oXR4L zd&tVF#m==*eh=xSsn1;+tnw2%S!qX##H-Ny{6Wdg3`I?X5o@Q7?J=nJ!1(KH-WQ3@ z9JR?D@amXG*-s*D9eX=H;U~rQ&2S~fAGq1lw!CWEYo~BjXeN=n78;W(fB8)`%=;hC z|I9O-{&RKftB;T<#@Ac93ggH!5T~3B5>|32-TFPLtnmRt132l6RTe?0*d*XfGUMBjU;_G= zRv#pO-&;PtU5tcGb&-ZASB27s!tanpirVQEaY{nt+4E4oz@TiFbC+7&^HJ@fldNU; ziS=e&4o}~=YW&4eh5US~>Vi7DO~R`$CADhWkfePxtvO#tOi7Mc^7sF z1K>NQY(H3WBMM~*Kt+#?O#;G1N5}Teb4FdY4(SW!>cGn9pB(gNx4^Pn#|)X4+;@2D zULzO2q%I5(FeP(o22Ksp=!#rI{iC}#(0zE`slElz2mvr;ppaI$+B7Eo?}@_qjFkZK z(j(z_JiI_U$F7H|uBq8I_s?zs@jh^lEWQ3fTy1zxZT`LL2XPE7Eh{vPn5k*rerTU8 z%2h6HojLB+1!z7ewUOK#vpu5FK~x^vaH6E^MnP5fBlFVoH($N-@xcYiW< zq$I|WT_um3hBz108~&d-{*lV2?=-$S%;ji7)j^PoP%QHoXh`R$>SbTW*U_B$cv=J! z+?VRKe?XKX`S5eyB5z)=Cb~PkD#Cv3hIFUMB>y%%R4!cxKp!aU3ykRhXIS^{O;>gR zGz~z3UfrCuSW^*hN&G@S=sep+fU=0s@q5N(}SnS1?&5@0t z+0S6}H+Dq{MT{CWN|!rLivjtLKb5;n`4dz`C7SSGpu+bi#r7Rb^@nU2GLG(@ZO}GC@5VfqZq$csu;}8 zmO|4*(D{l-`#M)%W)LTx&q(%?o+hc@uJR^ z4XLq#;HLnShw8hjDK%PehNB=YC;Mv}*^RA)qQj_NUKRa1*7Cd!N;FKBl%|h|%_bhx zZy9KkBB1nT*%7BCG=h+&DPg8!$ChklLr(V6m)FDh&4j-8rkyabTL7Fmp#r-3tCe-xNubC3-bq*skd}H6Ji>zs)fKn~^Sh<(2?31jq zYZ^_CQEefg`lTV7tI*;w%qK2H710(5dbuu?B{OiV*LQ{7Ldh17RM`1--6?X9Sj77i z0pEc#F&D}SLjH3--iumH7P;3>xc1sh2_(?2tbI=tk$qyhzQD9d} zDwI{Fex-_qCOh#*RML7t1`9)R4>4qdrAJRYsDhqU4*r|?XeKe0F~R_FQ9TwuK0afancD68 zY?)Z;P5F2^|NAn#(+LeXj-P=8A1koc6if;=&dKJOP2p$fkq}QRgp&~I77F?(%m20j zpnLQd;THAa`T6=pP@wXBbo=(E!{euUQ9`*jk;eeyO%QV!oIN30wyET5ISQb3Qk0!d zdqf{^%AZ}`lYjJtE2-2=zj>68poGGQK$1=9NR?`*i>e|bJ=|n^U?H(#&@W@VB@73)Y1wYYGY}}(J`v{V_BwZ z(Ac4aEv;G$Q7@S*p%+>ftYLvsKc$(+P8PLEz-eE=sRJr-?7+T?d*9Jj@Zd4$5qtOrjlsaJGkVndMX(N#*gpePsb8AHsp zUS_g+7t>Jve0J2?Y9LE}ra}Fm!4~R~`u2O1J`<8e+I&ksS(9lG%;4Ghz*OJJk^B`u zAZa9hXm+&dDzc_mVN%$W&#QLtrmZ`@~QONwG9US{PF2$%wNJBGQAZ}1HjQ8dDZ~6H>D4%{c4Mg=ov=4t8GV-lJ zoV_0WMSBe23+VszCL`b{K3_~4@@}@9x$#VYc)Ag{3s%DRtDMrz84F(hpO;M~l{t5= zJR?96)uBM{l_^mBY5x{sVs$_pk9p>x|NbPQbya$ECLCd~B;aH%TSVUV;0_m}qElEX z8TawvH?&Z)qQSB&3y^a9l&tYB`AeU5aARLc+)1x>DLvs)QDbqU?sHasYDb2%P#_)( z)JhMp?-m_0d+Jj3;7qzkW%}yD6tULQ%D$kbG$q!Mu&xaMa6{(@xNznjDa{ts*1}u^ z_phiY=%}f zP3?8wcsS>qrN*}Uxp!j5tu42&NM3Yv(a{++o1Q0^@*f``0|Fh`k-sm7{#qPWfA{d% z7~;2|3b}YRV9b`57SE1JRa**S?@vz@^#6P!1d9RtS@h!#ci&sHHigW9<|^^Hq45_d zcecV6d-7fG5(BwSWf3ZeHUgxpho7cg+}$qObYx3%RGyO33o}l((eTLh%94B8^(;Mj zmQq4%TiTV~n?(42O*g8CEWD?vwwyU%sbe5BEY9He>U*2|8hgC1hpZw3U`NO5Xk#VEx9Lkzb%00hh48Vc4( zu)7ij!}C~Hq*0Xfv6}(90gGS60vj87dN=ra;qz$Lt?aLT6CC>2BK}VLqyd20cz6IxlAMnG zWY^#v!9FpjYG$*pA_(P~PQ}%ZauyF*vwCC879d?*KP_o!z#FMWs(mb=095A`Q$gDY zHdWuhRqury=f95#uw4f~Ke>bQ=6sj7`F}-&sJbXA;F^|aw?*;@q$R`8FT%;G1uc;6 zDnRYE_GE|pzR+Z_)8tBv??tYUBcERLD(llOba1iVYFf)0y67b0H~!Cqg597@1)ve? zH?Ps1ZT>Y?31sNs$`B_&b?Mz6XngUftI4uL^o74{{hutuBC0|%e#HvBe_rBluqQ`zS(#0|4)uS} z77>6{Y_)aeO_Z1<88$BKr>Ey4DcR@0VK*g%*cUlqh^mQtwA5&~yqWqZ)!je_2@pFo zH8(F7O4dQk?JdX`de|#OYcupT&Y8;uww?AaFD{DH^*qj>-Mcr??Yzh6!_Eh`;K>yi zb$x$w0zK}Mbr>dye0XMmdfYhbpJ(X5>*pTp54Sh_YWeR%!IHQf;8w1!tz`s6(04De z(cBvYZZ{kIq@udJ=(P`(CqKG1!Fv*VI`)NiWooc!aSor3T*7;HkP{OVM@muW?FZKl zl-~UjzKO^6`NQ0Oq9=Gamidm9-<7cj@O_oAsk9ce*|&iAV@Fe8btf@{-PCxD=Zafi zwOB2FW?ne&fjutY441uE$bsOa{C%c~3u)g^)ppAOm`UUs|6g;Y>c3N9O7WDbo66u{uJhXtLl6JLxqFqOD@m6(*%2gor3a&Z9D zr<{>3)~G>q{63cjy?#Km9SNq$nV13?f5`cp^ zZrtD2?Bj!2Wo(1zxFORPqea!0mU*xiT~=0u+S_^;m8S8;s}f9beIDAhP+^`;A3ON= zrdLe2=PR{|n zNXT`gd+zOQmD<;i{p;h!K7;wH-Qlt-B*WhR$lJ$^`i6#UL6=RsH1>d}7l2I9Ks9O@ zcBB-a?;h5x5zMnEpVJzb!C3t`G7jrEifJH=BLW3NVRIIhlBA!*Z!stYey^|jh1=;g zUV3I5WwIF51j&Caey^q`A#Q{{HZ}&#bHvM6!?)8ekomx8=8QH&s!-`rpfHe`l~ww)e5ZnUedjc5ZJ<_#uyj1T<)ZnI zqJad{KpP2fwZk}hs(wp$>9jeg@eXokEU(i>66e!d+q(1ZnGu}AubAz75(i`3AY<6tsD&tpj1kJ8fp3jyZg5v_Jpl#j*Ag`NwD3ypwi zfnL^L;g?p5e-;x`;t1r$j#tlrHX0&lMu-H!#g)1!^47!I`ocNUNL9i+AdffN2L}fj zSUJS^1ldJcXbfyfFMTEIDSa*M?2c;*41Dd+XG%ZDBqln2QR*@$sz>RPM;EeWIh=#vjURUNIdb8~B`Zcc1MH>63$N^~N84L>{? zUk%^0B3YQ3Io))u8=VB*F&!#To37kKqe(<_=|-wdkCSX}FUqQN9Us1@>4Eib*0Knp zSiHbHmWd|qDNtmCusO8%ES2QaCUb-I)hWAg0&WX&bH_=L5z;yBh=G@}ov6sRT{9b3 zZELqoa#;UPlQA zxsFH8(CrLvFHSgF(TdHmEPG=)dwpXccNLzx-BF|a(F~#6X&4c|^BV)$eGXHhQ#jg? z*;8-m-=$kF7O0``T{_pSNHz^ zELB2Az)M#&{I4^NxJWi4){1)P)C8~urIXah^{y39{=J1ml)xAUH&SK4)LN6fDR z9)p$&WpVH3*L}HM{*3iC+9^%ee3`7)etkaDUgu;|kmIrD#=HGXRj$6JCjZNyV*1yw zqt5R9A`cyG?6!OIL;}sE@7*40WTLlp0M49Zt8;lRfL{sz9QB+7Em&0K0_}OBvt#gy zjhrX?blroZ(F`{-4nxjc_QCzXq-7d)f)bvG7JEFp&lHS3)uKLEtg z=a(Ny*c4`i&Xif6G<(pfO`#9|c(6B)Cf06XAs=`jwkoO#nysUOx|Am%_08l4^eFM6Pp3@&CS_D0i8wLCm*93}$42xQT*|9?}s)E`q`rIkxcPJsVR;-H^Td z$#o=itBN%BPs!s|KNu+rlm7}6qY~g_d~RvsFCO3Z@D#ESm*JnNQF%|h_7J@Hd0@V9 z|55qZrOBt8`P;0o`>=jh64A|FCQ)WAxNdfImXWRL%*+{`6YldAHBD@0?PkR#hWMPZ z@FVl|9&3zjeJ9AZ03>o;U0o9m;>Ty_b^CTorwgV(8ngsu{(LL4 z)X@eD*BkK9uzb%5xF*kgUeynNML1@JEc%VnfB>|i7Cr#Pum1yt)8%>>w0U!%g4ITI zxxz{8TlpuS3x7oy|E#TT%c!{u7JXk_N|aIKzI#+oZc>x zd7RxI%*x;7^>Qn56Ehp$fa2V|3E^uy8(;aGU?XB+H4CgQp7Au!5k|r` z-MNYL#s@DmxE4Fj4*%C8+lN(`=cecDJ;lD;9@=%?-se6+b5#ISwcWKr?X*4DCyZm|dI0x3U%>=l8z+VQp*cYFTmkh0~C^ntTBxd+Ln|gG0{{ z1a3PpvYXw|`N)lDBg#%go(OtZfUa`%aVmAYN?zcX%2Mu{yFUYlWaRViT@^#1{G)t7hx literal 0 HcmV?d00001 diff --git a/doxygen-awesome-css/img/testimage.png b/doxygen-awesome-css/img/testimage.png new file mode 100644 index 0000000000000000000000000000000000000000..3f495a5033a1600a7874dbb73d12d488bd7af184 GIT binary patch literal 4792 zcmai22{@GN+aFuDQxq)-V`So3X0cDkI+B>k5@U&B#u$vTj3sNE7LsJiUZI4LEmT58 zWNAT!p|Xr6BSOUZUg}@xeCPbX@4Duhcb?~W-@oU6e)s*{?{&>(^J7Na`9%3ZAkcQ> zBNz+dNdN|thaLEqv6-9%fjBG4R<<--tSQQsN>RcSs4hgMV2TfbgFsq3!9I9bPa+NM zLL`yB(Gce2ItZ9dKtpU)v2d)90nwd&B*c$s8FI|ZHN?|ZlK|1t=FeM+B=XsVc!C+I(OwKY|;|0(1DMGcZF# z+-Wo)6bu#=6r>cStVH!A!4R67nlLyLhD0g?7K;9-ylMDgMQ?xUO^P2J7^1(cAK8aS zrh0=nIq@#k02&$s0dVk7a$+#~H@mn0&*K9^z%~&WLJ1E0t2vGA_Fv35k$;%`xKn9V ze|M_SuLJyTi(l|R90B?M-6a_B^KZsj?Eh^}q5SO_{xritK!~5B{w=2eY~XKo%7+NE zAo^1S{9K8Kfkbbb^p+Bvx}eO-!9*`x44Fdo_6O8OLlAKI|3YzpK~?_(8c@BcewIL0 z5dp6)pH1md#uPk>XhSB@+<%k(226?Gq)p@}(H5{7n^(YQa;?3|z-f@b$!vdPXoxxz z_LqHd{|f!e1ZpchER_I6r@Te@8!|R9F!!Unk-Y%S-@-^AY;0(thR{?~Q$#BL*a1iz z3h*VnoxqgR6>9&k+5|vfbIwCPj#aO z;r)nuBp}6Th@P7p8Ibc77`QxSk~h&0j8H2><)>U_XO{ZC<pr8Q7N9{}NlU3$bHFiyON>5d%x^=Gw*QzH#?TLpBFULCZv)CWD z*~vjrV#VB*K?ZYP zaz#-U(01db7$G97!dBoSyEApy(t!xyuY2W<(TWPNJmt(bd7b6blOIng`_&anh=S zp_W0>9jM*&T3ROm@SsFo<4c5!g6_-R-LRz4rSh)V;^*Iu7AoOMdmoL3eVSL#JL=AH zGw;v}@Xp}%IfC;Cf%t_s2OB6YV;>0ghnO)&&&vJG=d@G7i9NL~IwWX9)PaQ91LqH< z#U42VK3)&rWhwjtqF>n4Hm+!15$@nobgwopE<0E<#(lB(R}!6iZ%|T*UhkBA3p8r&ERsFQBYO^!M8QDJD)zB2xS_hukoGpx z%-1YnUp$xtLSlbzF7Q=8w%oe=ER~mDgYs#GO_U_Xm_bz_Pnz1!s8c5DFXup^u zRf4bH_vY%}1?RF@Ik2cNjFa72UvAD#pG)Cdlr88}g8)02%Xcs5z@v->LetrKE-Utt z7+W9J6qh3enfk?JZ3rG!3F}}@lAudL0umIDPuT8#QC^nYD`8b?HZarUuvk{>uD1>< zxo0Fn+u)(fq%!`h%FhZRj&Vt*NgN|_wmk84Q#3Ld^0F&Hs<_f5igMCa?yRHAA7>O~ z1X%d;gwRR>-mDjI9#giL@fOkBMMm{Y%6W^GV$-&rfO9#2aii~S6v7n;p26H&EO|5A zk@1vH3vAwJUqHT~EUi2yqZL2Ka+|x3t!6iBZ`gU|+w9odtxy_-X<;UCO>w%y^4=fuA{W5E^My9cpoAC6X) zcyo(WS2L=b)s~!}^U;%O-=r+R{q&I*B;)MGFC zB))y+VG}3=E_29m4iIz}n)yI|`#5ADetN{b(t{Eb*|M{&{Dt1iE|5^7?xV-tqP$Hb z)Z9bISv-A8YBKGw*ik$pzPnjnyws!AA;H;EmYJ)@MB=>iMR66;A~W4v^vEmPD##N& z_+f$<)vH)Bh*7e@&lC4lNtSTmfW+-EHCs@qVQ+u3Z+Libdg9J>6-_un7sPab`l>fr zVxQ1{HEqOD#7I=6ZF!D%n1hu=^g_rQ$D(hmWt!*9*w3-LwpL+H)ojawXs9dYxd_-? za%aM|=D8Ok>!l9Qk-^qNyKf+={pIC*ichFUT@3Obnwz_o8Ss?l+Hz3Iap9Q9iDCoG zP|J?-#lkx6nl7oMg!YuWwbY=->`{KmpV3!Yvr*iq8Q;1CB$EqMu(Yb*-aEhWTiA5SGQY&@fCdh; zH9JWOO6k|-<f;(GYw zjR*MEjOS(Pt*;)EhvsLMI7TKUHG(GJUY=AAqdiq6<^@p)d`fd_S_o?+NlC^cRp&8H zzz5R|t?IT0S<4(my0vo)8_JbRzZ@K}v<}mM<1xuBRMN)F$a{it^%M5*hP8rlw6KC3 z1hSXWi7Fhmttco?{AMnzJ*z6L;~9gcU4Fahc2Q}FmuYtR#H$y5sr)D2d%h{3Xbq3J zeZRhso+}WyjaBi5EP^@Pn4LurKH|8#UA?0->+xFb%}(!oN|OkYjjuO7BPs&L;8My) z*R63htLr^sx9{iF?3sJLvXmNn=FMB~1Gq)&38lr9)0a}t&oQR=OXPJ8e*aJ+5&p3Q zT@1GL3$#0~UNJQYNFv>VsvtYH5&44p zS7MD5OP}Q5RZ*2!N2=i@wLAOheXdBg-Y{|Tn|5|SAfA}$xM(wMdc;J0ms)CQC=gGc z+t^7u?igXH=3Bm*dhIK7M;9;Z;1~KrOypAX!c0!&Rb-%w)6D+SI}tZ-FSf^LlCI7u zXx1>pCgoZadyRsY3o7|-iju-b3runacOg2H)<@ve+}O`p)zgCd9hZ{~jk<1RUH=ZD ztnQb>ysywK%b%fTwf51iEcqCXEr!i^HBx$}!fq6wGHN?@^NFKn;QLckJ3rso6wng6 zCs1XpFa$NQF*2b%PklfC?3ux#Hop0+RqV;N^K4Fu+c={z&#?@zeC3K(0on_o5+^Oi z)>|AR&7mA&=K^cGqseTSIOn zrUeY#lG0L@4;purXR)dTgky*Uo;o$m*YCtpS1#S}AC7F-7PC`WXBIj7P1P^WDm9jN zsUNzQbS-e9i$2IP%KXk)zad%ibyTL}&Iy)KNhp9*{apEczNfg13~edSUs$D#nGdf+-A4!4NfKCg}QlGR$vZ|ytj zc)jF;)$W|h3!<@0&4Z!2YdyEciyvWcmIuF{3b3GWe2Ls&R_HA4YT4cHGuOq`i0c^M zI3Cx!deV7tQRt3fx>moAxqymQW}!wX#)BYrmJ+j=3KOTVWOe60IufPp<374f;a&bV zTXa=`;n6o|9x;AN_$z)^J1L`TMx;kio7K@J))lEpl+0uX&4ydGJ%0EkJBxYXy=cM4 z{H(u4R$vQ<)Xv@#Jrz+(+o(O8;qle)?R`AgkEBQB37a+t0{vVf0p8m2-i=;~B(~kx zOFuk%A#aD5z>Zk<)zuJKK#=twadhVLaGBguOo0k^LySAc4-+gOea zU#c=v6;*t|FoI>Se*Dzgy9y*=^#6SMX6NR6DH0uAiH8Xrr%WX8W-h zkBS(5N{e}4^)4s2<2(ZRatY%+v5yrYDrrQsjdw5Q%M{kbcVML<(+NQlhR>atXJw4R7_4(CtZGYx0rDT@ARIskQ zp}Q^+St_UESHFDCL!VQ{PV#$OeU}bg&h@V7gTZejV~Ypxb~%YjYh(8>V`<>sHF=FKXZpW#((z4; zI~MWQz+&}}i|x+Lq|V*Fw`?DLT)C9O$$cj#-J;5T+PRQ7w%KT6B4^?4%4*c%=7N}H z_(S!|UK@5cJ*mzH{i1N7V{)qgVGO9c*z j4(Dca6~~YL8Z2&NFQ)q7QJw6~Kb(vWk70`SozMOcDy?-P literal 0 HcmV?d00001 diff --git a/doxygen-awesome-css/img/theme-variants.drawio.svg b/doxygen-awesome-css/img/theme-variants.drawio.svg new file mode 100644 index 0000000..f905d7d --- /dev/null +++ b/doxygen-awesome-css/img/theme-variants.drawio.svg @@ -0,0 +1,250 @@ + + + + + + + +
    +
    +
    + + + 1️⃣ + + + Base Theme +
    +
    +
    +
    + + 1️⃣ Base Theme + +
    +
    + + + + +
    +
    +
    + + + 2️⃣ + + + Sidebar-Only Theme +
    +
    +
    +
    + + 2️⃣ Sidebar-Only Theme + +
    +
    + + + + + +
    +
    +
    + Content +
    +
    +
    +
    + + Content + +
    +
    + + + + +
    +
    +
    + Sidebar +
    + (Title + Navigation) +
    +
    +
    +
    + + Sidebar... + +
    +
    + + + + +
    +
    +
    + Footer (Breadcrumps) +
    +
    +
    +
    + + Footer (Breadcrumps) + +
    +
    + + + + +
    +
    +
    + Search +
    +
    +
    +
    + + Search + +
    +
    + + + +
    +
    +
    + + Title + +
    +
    +
    +
    + + Tit... + +
    +
    + + + + + +
    +
    +
    + Content +
    +
    +
    +
    + + Content + +
    +
    + + + + +
    +
    +
    + Titlebar (Navigation + Search) +
    +
    +
    +
    + + Titlebar (Navigation + Search) + +
    +
    + + + + +
    +
    +
    + Sidebar (Navigation) +
    +
    +
    +
    + + Sidebar (Navigation) + +
    +
    + + + + +
    +
    +
    + Footer (Breadcrumps) +
    +
    +
    +
    + + Footer (Breadcrumps) + +
    +
    + + + + +
    +
    +
    + Search +
    +
    +
    +
    + + Search + +
    +
    + + + +
    +
    +
    + + Title + +
    +
    +
    +
    + + Tit... + +
    +
    +
    + + + + + Text is not SVG - cannot display + + + +
    \ No newline at end of file diff --git a/doxygen-awesome-css/include/MyLibrary/example.hpp b/doxygen-awesome-css/include/MyLibrary/example.hpp new file mode 100644 index 0000000..75f4c75 --- /dev/null +++ b/doxygen-awesome-css/include/MyLibrary/example.hpp @@ -0,0 +1,157 @@ +#pragma once +#include + +namespace MyLibrary { + +enum Color { red, green, blue }; + +/** + * @brief Example class to demonstrate the features of the custom CSS. + * + * @author jothepro + * + */ +class Example { +public: + /** + * @brief brief summary + * + * doxygen test documentation + * + * @param test this is the only parameter of this test function. It does nothing! + * + * # Supported elements + * + * These elements have been tested with the custom CSS. + * + * ## Tables + * + * The table content is scrollable if the table gets too wide. + * + * | first_column | second_column | third_column | fourth_column | fifth_column | sixth_column | seventh_column | eighth_column | ninth_column | + * |--------------|---------------|--------------|---------------|--------------|--------------|----------------|---------------|--------------| + * | 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | + * + * A table can contain images: + * + * | Column 1 | Column 2 | + * |---------------------------|-------------------------------------------------| + * | ![doxygen](testimage.png) | ← the image should not be inverted in dark-mode | + * + * Complex [Doxygen tables](https://www.doxygen.nl/manual/tables.html) are also supported as seen in @ref multi_row "this example": + * + * + * + *
    Complex table
    Column 1 Column 2 Column 3 + *
    cell row=1+2,col=1cell row=1,col=2cell row=1,col=3 + *
    cell row=2+3,col=2 cell row=2,col=3 + *
    cell row=3,col=1 cell row=3+4,col=3 + *
    cell row=4,col=1+2 + *
    cell row=5,col=1 cell row=5,col=2+3 + *
    cell row=6+7,col=1+2 cell row=6,col=3 + *
    cell row=7,col=3 + *
    cell row=8,col=1 cell row=8,col=2\n + * + *
    Inner cell row=1,col=1Inner cell row=1,col=2 + *
    Inner cell row=2,col=1Inner cell row=2,col=2 + *
    + *
    cell row=8,col=3 + *
      + *
    • Item 1 + *
    • Item 2 + *
    + *
    + * + * A table can be centered with the `

    ` html tag: + *
    + * | Foo | Bar | Baz | FooBar | + * |-------------|----------------|---------------------------|-------------| + * | Lorem imsum | dolor sit amet | cenectetur adipisici elit | At vero eos | + *
    + * + * Embedded Graphviz graphs support dark mode and can be scrolled once they get too wide: + * \dot Graphviz with a caption + * digraph example { + * node [fontsize="12"]; + * rankdir="LR" + * a -> b -> c -> d -> e -> f -> g -> h -> i -> j -> k; + * } + * \enddot + * + * ## Lists + * + * - element 1 + * - element 2 + * + * 1. element 1 + * ``` + * code in lists + * ``` + * 2. element 2 + * + * ## Quotes + * + * > Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt + * > ut labore et dolore magna aliqua. Vitae proin sagittis nisl rhoncus mattis rhoncus urna neque viverra. + * > Velit sed ullamcorper morbi tincidunt ornare. + * > + * > Lorem ipsum dolor sit amet consectetur adipiscing elit duis. + * *- jothepro* + * + * ## Code block + * + * ```cpp + * auto x = "code within md fences (```)"; + * ``` + * + * @code{.cpp} + * // code within @code block + * while(true) { + * auto example = std::make_shared(5); + * example->test("test"); + * } + * + * @endcode + * + * // code within indented code block + * auto test = std::shared_ptr +#include "example.hpp" +#include + +namespace MyLibrary { + + /** + * @brief some subclass + */ + template + class SubclassExample : public Example { + public: + + /** + * @bug second bug + * @return + */ + int virtualfunc() override; + + /** + * @brief Template function function + */ + template + std::shared_ptr function_template_test(std::shared_ptr& param); + + /** + * @brief Extra long function with lots of parameters and many template types. + * + * Also has a long return type. + * + * @param param1 first parameter + * @param param2 second parameter + * @param parameter3 third parameter + */ + template + std::pair long_function_with_many_parameters(std::shared_ptr& param1, std::shared_ptr& param2, bool parameter3, Alice paramater4 Bob parameter 5) { + if(true) { + std::cout << "this even has some code." << std::endl; + } + } + + }; + +} + diff --git a/doxygen-awesome-css/logo.drawio.svg b/doxygen-awesome-css/logo.drawio.svg new file mode 100644 index 0000000..a506ee0 --- /dev/null +++ b/doxygen-awesome-css/logo.drawio.svg @@ -0,0 +1 @@ + \ No newline at end of file From 4e8b8037a5d8b3f65a9e2cbf080ec7c891476caa Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 12 Mar 2023 21:34:04 -0400 Subject: [PATCH 194/243] dark mode toggle --- Doxyfile | 8 +++--- header.html | 78 +++++++++++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 82 insertions(+), 4 deletions(-) create mode 100644 header.html diff --git a/Doxyfile b/Doxyfile index 64107c6..d4fb3dc 100644 --- a/Doxyfile +++ b/Doxyfile @@ -1292,7 +1292,7 @@ HTML_FILE_EXTENSION = .html # of the possible markers and block names see the documentation. # This tag requires that the tag GENERATE_HTML is set to YES. -HTML_HEADER = +HTML_HEADER = header.html # The HTML_FOOTER tag can be used to specify a user-defined HTML footer for each # generated HTML page. If the tag is left blank doxygen will generate a standard @@ -1333,8 +1333,8 @@ HTML_STYLESHEET = # This tag requires that the tag GENERATE_HTML is set to YES. HTML_EXTRA_STYLESHEET = doxygen-awesome-css/doxygen-awesome.css \ - doxygen-awesome-css/doxygen-awesome-sidebar-only.css - + doxygen-awesome-css/doxygen-awesome-sidebar-only.css \ + doxygen-awesome-sidebar-only-darkmode-toggle.css # The HTML_EXTRA_FILES tag can be used to specify one or more extra images or # other source files which should be copied to the HTML output directory. Note # that these files will be copied to the base HTML output directory. Use the @@ -1343,7 +1343,7 @@ HTML_EXTRA_STYLESHEET = doxygen-awesome-css/doxygen-awesome.css \ # files will be copied as-is; there are no commands or markers available. # This tag requires that the tag GENERATE_HTML is set to YES. -HTML_EXTRA_FILES = +HTML_EXTRA_FILES = doxygen-awesome-darkmode-toggle.js # The HTML_COLORSTYLE tag can be used to specify if the generated HTML output # should be rendered with a dark or light theme. diff --git a/header.html b/header.html new file mode 100644 index 0000000..37eec5e --- /dev/null +++ b/header.html @@ -0,0 +1,78 @@ + + + + + + + + +$projectname: $title +$title + + + + + + + + +$treeview +$search +$mathjax +$darkmode + +$extrastylesheet + + + + + + +
    + + + +
    + + +
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
    +
    $projectname $projectnumber +
    +
    $projectbrief
    +
    +
    $projectbrief
    +
    $searchbox
    $searchbox
    +
    + + From add4088e23dbc541ecf32e265ef612d987517937 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 12 Mar 2023 21:36:09 -0400 Subject: [PATCH 195/243] fixed goof in theming --- Doxyfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Doxyfile b/Doxyfile index d4fb3dc..3807b19 100644 --- a/Doxyfile +++ b/Doxyfile @@ -1356,7 +1356,7 @@ HTML_EXTRA_FILES = doxygen-awesome-darkmode-toggle.js # The default value is: AUTO_LIGHT. # This tag requires that the tag GENERATE_HTML is set to YES. -HTML_COLORSTYLE = DARK +HTML_COLORSTYLE = LIGHT # The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen # will adjust the colors in the style sheet and background images according to From 48c308f13f81d5524968aa32410b05045feb359e Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 5 Mar 2023 13:12:24 -0500 Subject: [PATCH 196/243] Screen stuff from CLU --- include/utils/command_structure/auto_command.h | 4 ---- include/utils/command_structure/drive_commands.h | 1 + src/subsystems/flywheel.cpp | 4 ---- 3 files changed, 1 insertion(+), 8 deletions(-) diff --git a/include/utils/command_structure/auto_command.h b/include/utils/command_structure/auto_command.h index 060dd12..fd44850 100644 --- a/include/utils/command_structure/auto_command.h +++ b/include/utils/command_structure/auto_command.h @@ -21,11 +21,7 @@ class AutoCommand { */ virtual void on_timeout(){} AutoCommand* withTimeout(double t_seconds){ -<<<<<<< HEAD this->timeout_seconds = t_seconds; -======= - timeout_seconds = t_seconds; ->>>>>>> refs/subrepo/core/fetch return this; } /** diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index 8e4ff04..fba33f2 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -176,6 +176,7 @@ class DriveStopCommand: public AutoCommand { * @returns true when execution is complete, false otherwise */ bool run() override; + void on_timeout() override; private: // drive system to run the function on diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 48ee49b..01a2c2a 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -22,11 +22,7 @@ using namespace vex; -<<<<<<< HEAD const int FlywheelWindowSize = 20; -======= -const int FlywheelWindowSize = 1; ->>>>>>> refs/subrepo/core/fetch /********************************************************* * CONSTRUCTOR, GETTERS, SETTERS From d06b2048c64af8b0f67400a6a8f48c98cd881f85 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 5 Mar 2023 14:40:01 -0500 Subject: [PATCH 197/243] Fixed reference to copy for spin roller commane --- src/subsystems/screen.cpp | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/src/subsystems/screen.cpp b/src/subsystems/screen.cpp index fd06524..4374ce5 100644 --- a/src/subsystems/screen.cpp +++ b/src/subsystems/screen.cpp @@ -87,10 +87,6 @@ void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char { bg_col = not_plugged_in_col; } - else - { - bg_col = bg_col; - } } vex::color border_col = vex::white; @@ -161,7 +157,7 @@ int handle_screen_thread(vex::brain::lcd &screen, std::vector pages, { int x = screen.xPosition(); - int y = screen.yPosition(); + //int y = screen.yPosition(); if (x < bar_width) { From 8935e9f5b307ed306dda120d115e7d22c136ef5b Mon Sep 17 00:00:00 2001 From: cowsed Date: Tue, 7 Mar 2023 00:03:11 -0500 Subject: [PATCH 198/243] Tunings ofr skills before the git god smites me --- include/subsystems/lift.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index 947c7a3..d04ddc4 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -296,7 +296,7 @@ class Lift /** * Enables or disables the background task. Note that running the control functions, or set_position functions * will immediately re-enable the task for autonomous use. - * @param Whether or not the background thread should run the lift + * @param val Whether or not the background thread should run the lift */ void set_async(bool val) { From ee24293bec3598b8bc38faa725dab913d4aa5902 Mon Sep 17 00:00:00 2001 From: cowsed Date: Tue, 7 Mar 2023 00:56:32 -0500 Subject: [PATCH 199/243] Skills tunint 63 second 65 point auto --- include/utils/command_structure/command_controller.h | 2 +- src/utils/command_structure/command_controller.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/include/utils/command_structure/command_controller.h b/include/utils/command_structure/command_controller.h index 3d270d7..75766be 100644 --- a/include/utils/command_structure/command_controller.h +++ b/include/utils/command_structure/command_controller.h @@ -8,7 +8,7 @@ */ #pragma once - +#include #include #include "../core/include/utils/command_structure/auto_command.h" diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index 691664c..0a83bff 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -59,7 +59,7 @@ void CommandController::run() { command_queue.pop(); command_timed_out = false; - printf("Beginning Command %d : timeout = %f\n", command_count, next_cmd->timeout_seconds); + printf("Beginning Command %d : timeout = %.2f : at time = %.1f seconds\n", command_count, next_cmd->timeout_seconds, tmr.time(vex::seconds)); fflush(stdout); From 0e64337949ebe0960679f74da9660a534200737f Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 12 Mar 2023 19:56:16 -0400 Subject: [PATCH 200/243] post WV --- src/subsystems/screen.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/subsystems/screen.cpp b/src/subsystems/screen.cpp index 4374ce5..45409ec 100644 --- a/src/subsystems/screen.cpp +++ b/src/subsystems/screen.cpp @@ -169,7 +169,7 @@ int handle_screen_thread(vex::brain::lcd &screen, std::vector pages, first_draw = true; } - if (x > width - bar_width * 2) + if (x > width - bar_width) { current_page++; current_page %= num_pages; From 02fd965f5e66c4b2c9ed45069061be68bd0ebab3 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sat, 18 Mar 2023 21:35:02 -0400 Subject: [PATCH 201/243] created gitattributes to handle line endings --- include/utils/vector2d.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/utils/vector2d.h b/include/utils/vector2d.h index 7d805c5..221cb84 100644 --- a/include/utils/vector2d.h +++ b/include/utils/vector2d.h @@ -151,7 +151,7 @@ double deg2rad(double deg); /** * General function for converting radians to degrees - * @param rad the angle in radians + * @param r the angle in radians * @return the angle in degrees */ From 2bb215b0902b1bb5021836bf651a72ce882572d4 Mon Sep 17 00:00:00 2001 From: cowsed Date: Mon, 20 Mar 2023 21:01:01 -0400 Subject: [PATCH 202/243] improved screen with imu unplugged info --- include/subsystems/screen.h | 4 +- src/subsystems/screen.cpp | 74 +++++++++++++++++++++++++++++++------ 2 files changed, 65 insertions(+), 13 deletions(-) diff --git a/include/subsystems/screen.h b/include/subsystems/screen.h index 891c57d..60a49ef 100644 --- a/include/subsystems/screen.h +++ b/include/subsystems/screen.h @@ -11,7 +11,9 @@ typedef void (*screenFunc)(vex::brain::lcd &screen, int x, int y, int width, int void draw_mot_header(vex::brain::lcd &screen, int x, int y, int width); // name should be no longer than 15 characters -void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char *name, vex::motor &motor); +void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char *name, vex::motor &motor, int animation_tick); +void draw_dev_stats(vex::brain::lcd &screen, int x, int y, int width, const char *name, vex::device &dev, int animation_tick); + void draw_battery_stats(vex::brain::lcd &screen, int x, int y, double voltage, double percentage); diff --git a/src/subsystems/screen.cpp b/src/subsystems/screen.cpp index 45409ec..4a4f5f4 100644 --- a/src/subsystems/screen.cpp +++ b/src/subsystems/screen.cpp @@ -9,7 +9,11 @@ void draw_battery_stats(vex::brain::lcd &screen, int x, int y, double voltage, d vex::color med_col = vex::color(140, 100, 0); vex::color high_col = vex::black; + + vex::color bg_col = vex::black; + vex::color border_col = vex::white; + if (percentage < low_pct) { bg_col = low_col; @@ -23,23 +27,26 @@ void draw_battery_stats(vex::brain::lcd &screen, int x, int y, double voltage, d bg_col = high_col; } + screen.setPenWidth(3); screen.setFillColor(bg_col); - screen.setPenColor(vex::white); + screen.setPenColor(border_col); screen.setFont(vex::mono15); - screen.drawRectangle(x, y, 200, 20); - screen.printAt(x + 2, y + 15, "battery: %.1fv %d%%", voltage, (int)percentage); + + screen.drawRectangle(x+3, y, 200-3, 20); + screen.printAt(x + 5, y + 15, "battery: %.1fv %d%%", voltage, (int)percentage); } void draw_mot_header(vex::brain::lcd &screen, int x, int y, int width) { vex::color bg_col = vex::black; vex::color border_col = vex::white; + screen.setPenWidth(3); screen.setFillColor(bg_col); screen.setPenColor(border_col); screen.setFont(vex::mono15); - screen.drawRectangle(x, y, width, 20); + screen.drawRectangle(x+3, y, width-3, 20); screen.printAt(x + 5, y + 15, "motor name"); int name_width = 110; @@ -52,14 +59,13 @@ void draw_mot_header(vex::brain::lcd &screen, int x, int y, int width) screen.printAt(x + name_width + 55, y + 15, "port"); } -void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char *name, vex::motor &motor) +void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char *name, vex::motor &motor, int animation_tick) { double tempC = motor.temperature(vex::celsius); bool pluggedin = motor.installed(); int port = motor.index() + 1; // used for flashing - static int count = 0; vex::color bg_col = vex::black; vex::color hot_col = vex::color(120, 0, 0); vex::color med_col = vex::color(140, 100, 0); @@ -83,21 +89,22 @@ void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char if (!pluggedin) { - if ((count / 16) % 2 == 0) + if ((animation_tick / 8) % 2 == 0) { bg_col = not_plugged_in_col; } } vex::color border_col = vex::white; + screen.setPenWidth(3); screen.setFillColor(bg_col); screen.setPenColor(border_col); screen.setFont(vex::mono15); - screen.drawRectangle(x, y, width, 20); + screen.drawRectangle(x+3, y, width-3, 20); // name - screen.printAt(x + 5, y + 15, name); + screen.printAt(x + 7, y + 15, name); int name_width = 110; // temp @@ -112,7 +119,50 @@ void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char warning = ""; } screen.printAt(x + name_width + 60, y + 15, "%d%s", port, warning); - count++; +} + +// +void draw_dev_stats(vex::brain::lcd &screen, int x, int y, int width, const char *name, vex::device &dev, int animation_tick) +{ + bool pluggedin = dev.installed(); + int port = dev.index() + 1; + + // used for flashing + vex::color bg_col = vex::black; + vex::color not_plugged_in_col = vex::color(255, 0, 0); + + if (!pluggedin) + { + if ((animation_tick / 8) % 2 == 0) + { + bg_col = not_plugged_in_col; + } + } + + vex::color border_col = vex::white; + screen.setPenWidth(3); + screen.setFillColor(bg_col); + screen.setPenColor(border_col); + screen.setFont(vex::mono15); + + screen.drawRectangle(x+3, y, width-3, 20); + + // name + screen.printAt(x + 5, y + 15, name); + int name_width = 110; + + // temp + // screen.drawLine(x + name_width, y, x + name_width, y + 20); + // screen.printAt(x + name_width + 10, y + 15, "%dC", (int)tempC); + + // PORT + screen.drawLine(x + name_width + 50, y, x + name_width + 50, y + 20); + char *warning = "!"; + if (pluggedin) + { + warning = ""; + } + screen.printAt(x + name_width + 60, y + 15, "%d%s", port, warning); } void draw_lr_arrows(vex::brain::lcd &screen, int bar_width, int width, int height) @@ -157,7 +207,7 @@ int handle_screen_thread(vex::brain::lcd &screen, std::vector pages, { int x = screen.xPosition(); - //int y = screen.yPosition(); + // int y = screen.yPosition(); if (x < bar_width) { @@ -175,8 +225,8 @@ int handle_screen_thread(vex::brain::lcd &screen, std::vector pages, current_page %= num_pages; first_draw = true; } - draw_lr_arrows(screen, bar_width, width, height); } + draw_lr_arrows(screen, bar_width, width, height); was_pressing = screen.pressing(); screen.render(); vexDelay(40); From 175c8b24e1cdb1525a34d5f8be8527b4b0e34244 Mon Sep 17 00:00:00 2001 From: cowsed Date: Mon, 20 Mar 2023 21:04:12 -0400 Subject: [PATCH 203/243] odometry imu fallback --- src/subsystems/odometry/odometry_tank.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 8dd3e25..404f865 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -60,7 +60,7 @@ position_t OdometryTank::update() double angle = 0; // If the IMU data was passed in, use it for rotational data - if(imu == NULL) + if(imu == NULL || imu->installed() == false) { // Get the difference in distance driven between the two sides // Uses the absolute position of the encoders, so resetting them will result in From ceecebef3205039295af6dfc44437eb762eb6e06 Mon Sep 17 00:00:00 2001 From: cowsed Date: Mon, 17 Apr 2023 18:44:38 -0400 Subject: [PATCH 204/243] removed intense milk :( --- include/intense_milk.h | 12 ------------ include/utils/graph_drawer.h | 2 +- src/subsystems/screen.cpp | 8 ++++---- 3 files changed, 5 insertions(+), 17 deletions(-) delete mode 100644 include/intense_milk.h diff --git a/include/intense_milk.h b/include/intense_milk.h deleted file mode 100644 index bb0980f..0000000 --- a/include/intense_milk.h +++ /dev/null @@ -1,12 +0,0 @@ -<<<<<<< HEAD -#include -// file: ritchie.png -int intense_milk_width = 400; -int intense_milk_height = 251 -;uint32_t intense_milk[100400] = {0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000a0a0b, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00242525, 0x00121313, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0038393a, 0x000b0b0b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00898989, 0x00a4a4a4, 0x00949494, 0x00868686, 0x007c7c7c, 0x00787878, 0x00787878, 0x00787878, 0x00828282, 0x00929292, 0x00a4a4a4, 0x00acacac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00333434, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00afafaf, 0x008c8c8c, 0x00707070, 0x00555555, 0x00484848, 0x00383838, 0x002c2c2c, 0x00232323, 0x001d1d1d, 0x001c1c1c, 0x001f1f1f, 0x00232323, 0x00242424, 0x00282828, 0x00323232, 0x003f3f3f, 0x00525252, 0x006d6d6d, 0x00848484, 0x00acacac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x002c2d2d, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009b9b9b, 0x008d8d8d, 0x00666666, 0x00474747, 0x002b2b2b, 0x00161616, 0x00050505, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00020202, 0x00131313, 0x00262626, 0x003d3d3d, 0x005d5d5d, 0x00858585, 0x00a8a8a8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00212223, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00adadad, 0x007e7e7e, 0x00515151, 0x002c2c2c, 0x000c0c0c, 0x00030303, 0x00050505, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00010101, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00070707, 0x00282828, 0x004c4c4c, 0x00727272, 0x00a2a2a2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000f1010, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00545454, 0x00838383, 0x00505050, 0x00212121, 0x00050505, 0x00050505, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00020202, 0x00010101, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00050505, 0x001c1c1c, 0x00454545, 0x00787878, 0x00a4a4a4, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00050505, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00979797, 0x005e5e5e, 0x001d1d1d, 0x00050505, 0x00000000, 0x00000000, 0x00040404, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00171717, 0x004e4e4e, 0x008a8a8a, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00aeaeae, 0x007f7f7f, 0x00383838, 0x00010101, 0x00000000, 0x00000000, 0x00050505, 0x00040404, 0x00000000, 0x00000000, 0x00040404, 0x00040404, 0x00000000, 0x00000000, 0x00010101, 0x00030303, 0x00050505, 0x00060606, 0x00070707, 0x00060606, 0x00060606, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00060606, 0x00030303, 0x00000000, 0x00040404, 0x00050505, 0x00000000, 0x00030303, 0x00202020, 0x006f6f6f, 0x00aaaaaa, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00666666, 0x00b2b2b2, 0x00aeaeae, 0x00a9a9a9, 0x00a7a7a7, 0x00a8a8a8, 0x00acacac, 0x00b0b0b0, 0x00898989, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00acacac, 0x00686868, 0x00151515, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00020202, 0x000c0c0c, 0x000d0d0d, 0x00111111, 0x00151515, 0x00181818, 0x00191919, 0x00191919, 0x00191919, 0x00181818, 0x00151515, 0x00121212, 0x000e0e0e, 0x00090909, 0x00040404, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00010101, 0x00000000, 0x00010101, 0x00000000, 0x000a0a0a, 0x004e4e4e, 0x009f9f9f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00787878, 0x00a8a8a8, 0x00a2a2a2, 0x00909090, 0x00808080, 0x006e6e6e, 0x00606060, 0x00555555, 0x004c4c4c, 0x00494949, 0x004b4b4b, 0x00525252, 0x00575757, 0x00646464, 0x00787878, 0x00888888, 0x00969696, 0x00a4a4a4, 0x00afafaf, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a4a4, 0x00515151, 0x000c0c0c, 0x00000000, 0x00020202, 0x00000000, 0x00010101, 0x00020202, 0x00010101, 0x00000000, 0x00000000, 0x00040404, 0x000a0a0a, 0x00161616, 0x00242424, 0x00292929, 0x002b2b2b, 0x002d2d2d, 0x00303030, 0x00313131, 0x00313131, 0x00303030, 0x00303030, 0x00303030, 0x002e2e2e, 0x002c2c2c, 0x00272727, 0x00202020, 0x00181818, 0x00101010, 0x000a0a0a, 0x00020202, 0x00020202, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00010101, 0x00020202, 0x00020202, 0x00030303, 0x00363636, 0x00979797, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00434343, 0x00a8a8a8, 0x008f8f8f, 0x006c6c6c, 0x00404040, 0x00181818, 0x00080808, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00121212, 0x00343434, 0x00545454, 0x00818181, 0x009b9b9b, 0x00b3b3b3, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009b9b9b, 0x00404040, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00030303, 0x00090909, 0x00131313, 0x00202020, 0x002a2a2a, 0x002d2d2d, 0x002a2a2a, 0x002d2d2d, 0x002d2d2d, 0x002d2d2d, 0x002d2d2d, 0x002c2c2c, 0x002c2c2c, 0x002c2c2c, 0x002b2b2b, 0x002d2d2d, 0x002d2d2d, 0x002e2e2e, 0x002f2f2f, 0x002f2f2f, 0x002d2d2d, 0x00292929, 0x00262626, 0x001b1b1b, 0x00080808, 0x00000000, 0x00000000, 0x00030303, 0x00020202, 0x00000000, 0x00030303, 0x00000000, 0x00040404, 0x00050505, 0x00010101, 0x00282828, 0x00848484, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00434343, 0x00939393, 0x00606060, 0x00282828, 0x00000000, 0x00000000, 0x00040404, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00040404, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00111111, 0x003e3e3e, 0x007e7e7e, 0x00aaaaaa, 0x001f1f1f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9c9c, 0x003b3b3b, 0x00020202, 0x00000000, 0x00060405, 0x00000000, 0x00030102, 0x00000000, 0x00010000, 0x00040404, 0x00111111, 0x00232323, 0x002c2c2c, 0x00292929, 0x00272727, 0x00282828, 0x00282828, 0x00282828, 0x00282828, 0x00282728, 0x00282828, 0x00282828, 0x00282828, 0x002a2a2a, 0x002a2a2a, 0x00292929, 0x00282828, 0x00272526, 0x00272725, 0x00292828, 0x00292929, 0x00292929, 0x00282828, 0x00282828, 0x00252726, 0x001b1c1c, 0x00080a09, 0x00030303, 0x00010101, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00030303, 0x00030303, 0x00292929, 0x00878787, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b2b2b4, 0x00888888, 0x00383938, 0x000d0f0c, 0x00000000, 0x00020403, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00202020, 0x00646464, 0x00a5a5a5, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a8a6aa, 0x00414042, 0x00020003, 0x00000001, 0x00000000, 0x00030000, 0x00020000, 0x00020000, 0x00050201, 0x000d0a09, 0x00232122, 0x00242424, 0x00252726, 0x00262825, 0x00262825, 0x00262624, 0x00262624, 0x00272526, 0x00282627, 0x00282628, 0x00292528, 0x00282628, 0x00272728, 0x00272728, 0x00262827, 0x00262827, 0x00282627, 0x00282627, 0x00292625, 0x00282724, 0x00292625, 0x00282725, 0x00272725, 0x00272727, 0x00242625, 0x00242728, 0x0026292a, 0x00232627, 0x00151716, 0x00040404, 0x00000000, 0x00020100, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00282828, 0x00909090, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00575456, 0x00b1b0b2, 0x00aca8a9, 0x00a8a7a8, 0x00aca8a8, 0x00acaca8, 0x00b6b3b0, 0x000c0c0c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008d888c, 0x00343337, 0x0008080a, 0x00000100, 0x00000100, 0x00000100, 0x00000200, 0x00000200, 0x00000200, 0x00000001, 0x00030002, 0x00010000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00030303, 0x00010101, 0x00000000, 0x001d1d1d, 0x005f5f5f, 0x00afafaf, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b2b0b3, 0x00444246, 0x00070508, 0x00000001, 0x00030104, 0x00030102, 0x00000000, 0x00000000, 0x00040402, 0x00141412, 0x00222220, 0x00222224, 0x00232425, 0x00242625, 0x00232724, 0x00222623, 0x00232422, 0x00242422, 0x00242324, 0x00252426, 0x00272326, 0x00272328, 0x00252426, 0x00242426, 0x00242524, 0x00242524, 0x00242523, 0x00252424, 0x00252424, 0x00272423, 0x00272421, 0x00272421, 0x00252421, 0x00242423, 0x00242423, 0x00242625, 0x00202424, 0x00202324, 0x00222526, 0x00232424, 0x001b1b1b, 0x000c0c0a, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00020202, 0x00000000, 0x00070707, 0x00383838, 0x00979797, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00666666, 0x00989898, 0x00787879, 0x0058585a, 0x003b3b3c, 0x00222224, 0x00141314, 0x000f0d0e, 0x000c0908, 0x000a0706, 0x000b0807, 0x000b0805, 0x000b0805, 0x000d0a08, 0x000f0e0c, 0x001a191d, 0x002d2e31, 0x00484a49, 0x00646563, 0x00848583, 0x00a7a8a8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a2a4a1, 0x00494448, 0x00140f14, 0x0007060a, 0x00000001, 0x00000100, 0x00000200, 0x00000000, 0x00000100, 0x00000300, 0x00000300, 0x00000001, 0x00030000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00020202, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00050505, 0x00000000, 0x00000000, 0x00030303, 0x00010101, 0x00000000, 0x00080808, 0x00262626, 0x00747474, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00625f60, 0x00130f12, 0x00050104, 0x00000001, 0x00010002, 0x00000001, 0x00000103, 0x0006090a, 0x00121715, 0x001d2220, 0x00222727, 0x001d2124, 0x001e2224, 0x001f2325, 0x001f2424, 0x001e2323, 0x001d2220, 0x001f2221, 0x00202123, 0x00212123, 0x00222023, 0x00222023, 0x00222023, 0x00212121, 0x00202220, 0x0020221e, 0x0020221e, 0x00212121, 0x00212121, 0x00222021, 0x00222120, 0x00222120, 0x00222120, 0x00212120, 0x00212120, 0x00212322, 0x00202423, 0x001f2223, 0x001d2021, 0x00212322, 0x00232323, 0x001c1b19, 0x0010100e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00030303, 0x00000000, 0x00060606, 0x00505050, 0x00a5a5a5, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00959493, 0x00626061, 0x00353233, 0x00221f20, 0x000f0d10, 0x0008090c, 0x0005080b, 0x00010508, 0x00000404, 0x00020603, 0x00000000, 0x00000000, 0x00020000, 0x00030000, 0x00020000, 0x00020000, 0x00010002, 0x00000002, 0x00000104, 0x00000201, 0x00030607, 0x000d0d0d, 0x00100c0d, 0x00150e10, 0x0030292c, 0x004f4a4c, 0x00807c80, 0x00a3a1a2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007d7d77, 0x00282821, 0x00080408, 0x00050308, 0x00000004, 0x00010204, 0x00040300, 0x00030000, 0x00000000, 0x00000000, 0x00000301, 0x00000605, 0x00080607, 0x000c0809, 0x00171516, 0x00191919, 0x001e1e1e, 0x00232323, 0x00252525, 0x00262626, 0x00242424, 0x00242424, 0x00212121, 0x001a1a1a, 0x00101010, 0x00060606, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00171717, 0x00444444, 0x009c9c9c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00747371, 0x001c1b19, 0x00000000, 0x00040304, 0x00000000, 0x00000001, 0x00000002, 0x0008090b, 0x00141818, 0x001e2122, 0x001c2121, 0x00171c1c, 0x001c1f21, 0x001c1f21, 0x001c1f21, 0x001b1f21, 0x001b2020, 0x001b2020, 0x001c2020, 0x001e1f20, 0x001f1f20, 0x00201e20, 0x00211d20, 0x00211e1f, 0x00201f1d, 0x00201f1c, 0x001f201b, 0x001e201c, 0x001e201f, 0x001e1f20, 0x001e1f20, 0x001f1f1f, 0x001f1f1f, 0x001f1f1d, 0x001f1f1d, 0x001f1f1d, 0x001d1f1e, 0x00202221, 0x00202123, 0x001b1c1d, 0x001a1a1a, 0x001e1e1e, 0x00201e1f, 0x001e1c1d, 0x00101010, 0x00040404, 0x00010101, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00020202, 0x00141414, 0x00656565, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00949496, 0x005c5a5b, 0x0030302e, 0x00191817, 0x00100c0a, 0x000e0604, 0x00080000, 0x00080000, 0x00080000, 0x000b0000, 0x00090000, 0x000b0000, 0x000c0000, 0x00100000, 0x00140000, 0x00150000, 0x00140000, 0x00140000, 0x00140000, 0x00120000, 0x000d0000, 0x000c0000, 0x00090000, 0x00080000, 0x000a0000, 0x000a0000, 0x000a0000, 0x000b0000, 0x000e0703, 0x0014100e, 0x00201f1d, 0x00404143, 0x00717475, 0x00a4a8a4, 0x00000000, 0x00000000, 0x00000000, 0x00313131, 0x005d5d5c, 0x001c1912, 0x00080500, 0x00000001, 0x00000004, 0x00000004, 0x00000000, 0x00020000, 0x00040000, 0x00080404, 0x000c0c0e, 0x00101817, 0x0018201f, 0x00242424, 0x00282826, 0x00292828, 0x00292929, 0x002b2b2b, 0x002c2c2c, 0x002d2d2d, 0x002d2d2d, 0x002c2c2c, 0x002c2c2c, 0x00282828, 0x00292929, 0x002b2b2b, 0x002b2b2b, 0x00272727, 0x001d1d1d, 0x00101010, 0x00080808, 0x00040404, 0x00000000, 0x00000000, 0x00010101, 0x00030303, 0x00000000, 0x00000000, 0x00030303, 0x00000000, 0x00050505, 0x00080808, 0x00303030, 0x00828282, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a8a3, 0x00313530, 0x00090d08, 0x00000100, 0x00000200, 0x00000000, 0x00030303, 0x000c0a0b, 0x00151414, 0x001c181c, 0x001e1a1d, 0x00201b1e, 0x00201c1f, 0x00201c1f, 0x00201c1f, 0x001d1c1e, 0x001c1c1e, 0x001c1c1e, 0x001c1c1e, 0x001c1c1e, 0x001d1c1e, 0x001f1b1e, 0x00201b1e, 0x00211a1c, 0x00211a1b, 0x00201b1b, 0x00201c19, 0x001f1c18, 0x001d1c19, 0x001c1c1e, 0x001a1d20, 0x001a1d20, 0x001c1c1e, 0x001c1c1e, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1a, 0x001c1c1b, 0x001c1c1c, 0x001c1c1c, 0x001d1d1d, 0x001d1d1d, 0x001c1c1c, 0x001a1a1a, 0x001a1a1a, 0x00111111, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x002c2c2c, 0x00868686, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00afb6b5, 0x00787c7c, 0x00404143, 0x00222222, 0x00100e0f, 0x00020000, 0x00030000, 0x00080000, 0x000b0000, 0x00100000, 0x00180000, 0x00240200, 0x00310800, 0x00421200, 0x00541d00, 0x00602504, 0x00682b06, 0x006e3009, 0x0070320b, 0x006f320a, 0x006b3109, 0x00683008, 0x00602a03, 0x00592400, 0x00491500, 0x00400e00, 0x00300300, 0x00200000, 0x00180000, 0x00150000, 0x000d0000, 0x00050000, 0x00080500, 0x00020100, 0x00040408, 0x00111216, 0x002a292d, 0x0050504f, 0x0084867d, 0x00adafa6, 0x00404342, 0x00131311, 0x00040000, 0x00050000, 0x00000001, 0x00000006, 0x00000406, 0x00000704, 0x00080802, 0x00110f0b, 0x001d181c, 0x00262227, 0x0029292b, 0x002b2c2c, 0x002b2e2d, 0x002b2e2d, 0x002c2c2c, 0x002c2c2c, 0x002b2b2b, 0x002b2b2b, 0x002a2a2a, 0x002b2b2b, 0x002b2b2b, 0x002b2b2b, 0x002c2c2c, 0x002c2c2c, 0x002b2b2b, 0x002c2c2c, 0x002c2c2c, 0x002a2a2a, 0x00272727, 0x00242424, 0x001b1b1b, 0x00111111, 0x00080808, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00080808, 0x00040404, 0x00202020, 0x00686868, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00505550, 0x000a100a, 0x00000200, 0x00000400, 0x00000100, 0x00000200, 0x00070806, 0x00131313, 0x001e1b1c, 0x00201c1f, 0x001f181c, 0x0020181c, 0x00241b20, 0x0022191e, 0x0020191d, 0x001e191c, 0x001c1a1c, 0x001c1a1c, 0x001b1b1c, 0x001a191d, 0x001b191c, 0x001d191e, 0x001d191c, 0x001e191b, 0x001e191b, 0x001e1919, 0x001d1a19, 0x001c1b18, 0x001b1b19, 0x00181c1e, 0x00181c1f, 0x00181c1e, 0x00181c1e, 0x001a1b1c, 0x001a1b1c, 0x001b1b1b, 0x001b1b1b, 0x001b1b19, 0x00191918, 0x001a1a1a, 0x001c1c1c, 0x001d1d1d, 0x001b1b1b, 0x0019191b, 0x001a1a1c, 0x00181818, 0x00181818, 0x000c0c0c, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x000b0b0b, 0x00444444, 0x00b0b0b0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a7a9, 0x00707473, 0x00383c37, 0x001c1d19, 0x00050401, 0x00050000, 0x000b0000, 0x00110000, 0x00190200, 0x00220400, 0x00421b01, 0x0058290c, 0x006f3918, 0x007f411c, 0x008a461b, 0x00964b1a, 0x009e4c19, 0x00a24c16, 0x00a84f16, 0x00aa5118, 0x00a95318, 0x00a85318, 0x00a65418, 0x00a45317, 0x00a15014, 0x009d4d11, 0x009f4e18, 0x00984a19, 0x008d451c, 0x007d3e1c, 0x00643011, 0x00461c00, 0x002e1000, 0x00230c00, 0x000e0000, 0x000a0000, 0x000b0000, 0x00080001, 0x00080004, 0x000f0a0a, 0x0022201c, 0x0032312d, 0x000a0b0c, 0x00000000, 0x00050000, 0x00070100, 0x00000003, 0x00000308, 0x0003090b, 0x000c130f, 0x001c1d19, 0x00222120, 0x0028242a, 0x002c262c, 0x002b2628, 0x00272624, 0x00222524, 0x00212624, 0x00242625, 0x00252525, 0x00262626, 0x00272727, 0x00282828, 0x00282828, 0x00292929, 0x00292929, 0x00282828, 0x00282828, 0x00272727, 0x00262626, 0x00272727, 0x00272727, 0x00262626, 0x00252525, 0x00272727, 0x00232323, 0x001c1c1c, 0x000e0e0e, 0x00010101, 0x00000000, 0x00030303, 0x00030303, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00060606, 0x00181818, 0x00595959, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007e7d81, 0x00262728, 0x00000102, 0x00020705, 0x00000300, 0x00000200, 0x00010804, 0x00090e0b, 0x00121514, 0x00191919, 0x001c181c, 0x001c171a, 0x001c1319, 0x001b1217, 0x001c1417, 0x001c1417, 0x00191418, 0x00181618, 0x0018171b, 0x0018181c, 0x0018171c, 0x0018171b, 0x0018171c, 0x0018171b, 0x0018171b, 0x0018171b, 0x0017181b, 0x0015181b, 0x0014181b, 0x0014181b, 0x0015181b, 0x0015181b, 0x0015181b, 0x0015181b, 0x0015181b, 0x00151819, 0x00171818, 0x00181818, 0x00191918, 0x00191817, 0x001a1918, 0x001a1819, 0x00181718, 0x00171518, 0x0018181c, 0x001c1c1d, 0x001c1c1c, 0x001c1c1c, 0x00141414, 0x00090909, 0x00020202, 0x00000000, 0x00010101, 0x00000000, 0x00020202, 0x00000000, 0x001c1c1c, 0x00757575, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b1bc, 0x007c787d, 0x00413c3c, 0x00201c17, 0x00090700, 0x00080400, 0x000b0000, 0x00130000, 0x00280800, 0x004b1c00, 0x006d330a, 0x00843d0b, 0x00964711, 0x00a44e14, 0x00ae561a, 0x00b35818, 0x00b85815, 0x00bb5b15, 0x00bd5a12, 0x00bc590f, 0x00bd5b10, 0x00bc5a10, 0x00b9580e, 0x00b95810, 0x00ba5910, 0x00bd5a12, 0x00be5b13, 0x00be5c11, 0x00b8560b, 0x00be5d14, 0x00ba5c1c, 0x00b0551d, 0x00a85422, 0x00a05428, 0x008b481d, 0x0070370f, 0x005c2d0c, 0x00411c02, 0x00240700, 0x00110000, 0x000c0000, 0x000a0000, 0x00080000, 0x00030000, 0x00010004, 0x00010004, 0x00030000, 0x00000000, 0x00000708, 0x00081114, 0x00111818, 0x00202420, 0x00242424, 0x00242325, 0x0024222b, 0x00242229, 0x00282122, 0x00282421, 0x00242827, 0x00242b2a, 0x00262827, 0x00272727, 0x00262626, 0x00262626, 0x00252525, 0x00242424, 0x00222222, 0x00212121, 0x00242424, 0x00242424, 0x00242424, 0x00242424, 0x00252525, 0x00262626, 0x00272727, 0x00282828, 0x00252525, 0x00212121, 0x00202020, 0x00202020, 0x001b1b1b, 0x000d0d0d, 0x00010101, 0x00000000, 0x00000000, 0x00030303, 0x00000000, 0x00080808, 0x00000000, 0x00000000, 0x001b1b1b, 0x00585858, 0x00666666, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0020201f, 0x00ada9a7, 0x007a747a, 0x00514c52, 0x002d292e, 0x00080709, 0x00000000, 0x00000100, 0x00000000, 0x00040400, 0x000c0c06, 0x0014140d, 0x00181411, 0x00160e0c, 0x00140a0a, 0x00180c0c, 0x001c0c10, 0x001a0b0c, 0x001a0e0c, 0x00190e0c, 0x00170f0d, 0x00181110, 0x00181414, 0x00181516, 0x00191617, 0x00171516, 0x00171516, 0x00171516, 0x00171516, 0x00161616, 0x00151618, 0x00131719, 0x0011181a, 0x00131719, 0x00141719, 0x00151618, 0x00151618, 0x00151619, 0x00141719, 0x00141719, 0x00151618, 0x00151716, 0x00171715, 0x00171614, 0x00161514, 0x00171614, 0x00181718, 0x00181719, 0x00161519, 0x00141317, 0x00161618, 0x00141414, 0x00161616, 0x00151515, 0x00060606, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00080808, 0x003b3b3b, 0x00adadad, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008e8c97, 0x00504c55, 0x00261d22, 0x00120704, 0x000a0000, 0x00110000, 0x00180100, 0x00331100, 0x005a2d13, 0x007b401a, 0x00944918, 0x00a95416, 0x00ba5c15, 0x00be5a10, 0x00c0580c, 0x00c05809, 0x00c15807, 0x00c45c07, 0x00c75e08, 0x00c75f07, 0x00c55d04, 0x00c86007, 0x00c76107, 0x00c76008, 0x00c8610a, 0x00c8610c, 0x00c6600a, 0x00c55e0b, 0x00c65d07, 0x00c85f06, 0x00c65c04, 0x00c35908, 0x00bf590d, 0x00bb5813, 0x00b75818, 0x00b4591b, 0x00b25c23, 0x00a0521e, 0x008e491c, 0x00743a16, 0x0058280d, 0x00371302, 0x001b0100, 0x000c0000, 0x00080000, 0x00050006, 0x00000003, 0x00040400, 0x00060a05, 0x000a1516, 0x00142022, 0x001c2020, 0x00212121, 0x00231f22, 0x00221e23, 0x001f1f28, 0x001f1f27, 0x00232020, 0x0023201d, 0x001f2020, 0x001c2020, 0x001f2020, 0x00202020, 0x00202020, 0x00202020, 0x00202020, 0x00202020, 0x00202020, 0x00202020, 0x001f1f1f, 0x00202020, 0x00212121, 0x00212121, 0x00202020, 0x00202020, 0x001f1f1f, 0x001f1f1f, 0x00202020, 0x00212121, 0x00212121, 0x00222222, 0x00202020, 0x00181818, 0x000e0e0e, 0x000a0a0a, 0x00010101, 0x00000000, 0x00020202, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00141414, 0x00676767, 0x00787878, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00060607, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009b9c9c, 0x00696b6a, 0x00404040, 0x001d1c1c, 0x00080607, 0x00020000, 0x00040000, 0x00050000, 0x00050000, 0x00080000, 0x000c0000, 0x00140400, 0x00180600, 0x001b0500, 0x001b0300, 0x001b0000, 0x001c0000, 0x001e0000, 0x001c0100, 0x001a0400, 0x00160700, 0x00140600, 0x00130500, 0x00100600, 0x00100800, 0x00110902, 0x00130b04, 0x00120c03, 0x00171008, 0x0019140c, 0x0017140c, 0x0014130f, 0x00141614, 0x00131615, 0x00111414, 0x00171516, 0x00161514, 0x00141314, 0x00141415, 0x00141418, 0x00121518, 0x00121516, 0x00141514, 0x00151514, 0x00151413, 0x00161310, 0x00161312, 0x00151414, 0x00151416, 0x00151418, 0x00141518, 0x00161618, 0x00141414, 0x00141414, 0x00141414, 0x000d0d0d, 0x00040404, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00020202, 0x001e1e1e, 0x00747474, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a7adaf, 0x006f7073, 0x00332f34, 0x000e070b, 0x000c0000, 0x000b0000, 0x00200700, 0x003c1700, 0x00642e0f, 0x008c431c, 0x00a7501f, 0x00b8581c, 0x00bc5711, 0x00ba5708, 0x00c05c08, 0x00c45d06, 0x00c8620a, 0x00c66006, 0x00c46003, 0x00c96507, 0x00cc6808, 0x00c96603, 0x00cb6700, 0x00cc6802, 0x00cc6700, 0x00cc6600, 0x00cc6a05, 0x00cc6a08, 0x00ca6808, 0x00c86709, 0x00cb680b, 0x00cc6405, 0x00cc6003, 0x00cc6407, 0x00c76408, 0x00c05f06, 0x00c05f08, 0x00c45d0c, 0x00c15808, 0x00c2570b, 0x00be550f, 0x00b9581a, 0x00a14f1a, 0x007f3e18, 0x005d2e14, 0x00301204, 0x000d0000, 0x00080004, 0x00030003, 0x000c0905, 0x00141813, 0x00132220, 0x00132121, 0x001b1e20, 0x00211d20, 0x0023181e, 0x0020181f, 0x001c1f28, 0x001b2228, 0x001c2022, 0x001c1e1d, 0x001e1e1e, 0x001f1d1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001e1e1e, 0x001f1f1f, 0x001f1f1f, 0x001d1d1d, 0x00191919, 0x00161616, 0x00080808, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00030303, 0x00141414, 0x00787878, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00050505, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009a9ea0, 0x00686c6e, 0x00383c3f, 0x00131617, 0x00000000, 0x00030000, 0x00050000, 0x000a0000, 0x00100200, 0x00130000, 0x00160000, 0x00250700, 0x00361100, 0x00421902, 0x004a1e05, 0x0054230c, 0x0059270e, 0x005c2910, 0x005f2b13, 0x00602c14, 0x005f2c12, 0x00552708, 0x00512707, 0x004c2407, 0x00482006, 0x00401c02, 0x00381700, 0x00301100, 0x002a0e00, 0x00200700, 0x00190300, 0x00170300, 0x00180800, 0x00180c02, 0x00140d06, 0x0014100c, 0x00171310, 0x0018100f, 0x0018100f, 0x00171310, 0x00161514, 0x00171718, 0x0014181a, 0x00121516, 0x00111214, 0x00141414, 0x00151413, 0x00161310, 0x00161310, 0x00141412, 0x00141414, 0x00141317, 0x00131417, 0x00141415, 0x00131313, 0x00141414, 0x00141414, 0x00101010, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00060606, 0x00484848, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00949894, 0x004f504e, 0x001c1816, 0x000b0000, 0x000f0000, 0x001d0300, 0x00391400, 0x00602e10, 0x00884822, 0x00a25325, 0x00b35723, 0x00bb561b, 0x00c35c19, 0x00c76016, 0x00c25f0f, 0x00c1600b, 0x00c46308, 0x00c66508, 0x00c86808, 0x00ca6a08, 0x00cc6a08, 0x00c86701, 0x00c96700, 0x00cc6c04, 0x00c96800, 0x00cc6a00, 0x00cc6b00, 0x00cc6a02, 0x00c96800, 0x00c86700, 0x00c86800, 0x00cc6804, 0x00cc6906, 0x00cc6400, 0x00c86400, 0x00c96802, 0x00c86904, 0x00cb6804, 0x00cc6404, 0x00cc5e01, 0x00cc5a00, 0x00cc5800, 0x00c85703, 0x00c05910, 0x00ae591e, 0x009a562a, 0x006d3a1d, 0x00260400, 0x000f0000, 0x00060000, 0x00100500, 0x001d1a10, 0x00101812, 0x0018211e, 0x001c1c1e, 0x001f1a1d, 0x00261a1e, 0x00241b1e, 0x00191c21, 0x00121b20, 0x00141c21, 0x001c2023, 0x00201e1f, 0x001e1b18, 0x001d1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001b1b1b, 0x001b1b1b, 0x001c1c1c, 0x001c1c1c, 0x001c1c1c, 0x001a1a1a, 0x00181818, 0x00121212, 0x000b0b0b, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00212121, 0x00888888, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00060607, 0x00060607, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a7adaf, 0x00788081, 0x003c4448, 0x000f1316, 0x00000003, 0x00000002, 0x00050100, 0x000c0000, 0x00140000, 0x001c0400, 0x002c0c00, 0x00461b04, 0x005d280d, 0x006f3110, 0x007c350f, 0x00924619, 0x009b4b19, 0x00a4501c, 0x00a9561d, 0x00ac581e, 0x00ac5c1d, 0x00ac5c1d, 0x00ac591a, 0x00b45b1a, 0x00b05817, 0x00a95317, 0x00a24f16, 0x00984914, 0x008c4310, 0x007f3a0b, 0x0074340a, 0x00682e06, 0x00572401, 0x00441800, 0x00330f00, 0x00240700, 0x00190100, 0x00170400, 0x00180906, 0x001a0b05, 0x001b0d07, 0x00190f0a, 0x00150f0c, 0x00100e0f, 0x000e0f10, 0x000f1214, 0x00141416, 0x00121212, 0x00131210, 0x0014110f, 0x00151210, 0x00141311, 0x00131313, 0x00121115, 0x00111215, 0x00111113, 0x00111111, 0x00121212, 0x00131313, 0x00111111, 0x000c0c0c, 0x00040404, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00232323, 0x009f9f9f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00878682, 0x00393933, 0x000e0b04, 0x00080000, 0x00140000, 0x00320c00, 0x00592300, 0x008c4211, 0x00a85118, 0x00b35518, 0x00b25417, 0x00a64c15, 0x009b4410, 0x009b4813, 0x00a35116, 0x00ad5a16, 0x00b76114, 0x00c16c17, 0x00c36d12, 0x00c46a0c, 0x00c26504, 0x00c86604, 0x00cc6c08, 0x00cc6b08, 0x00c46300, 0x00c76704, 0x00c76805, 0x00c56905, 0x00c66801, 0x00c96800, 0x00cc6a00, 0x00cc6b00, 0x00cc6800, 0x00c86300, 0x00cc6801, 0x00cc6b02, 0x00c66800, 0x00c86800, 0x00cc6b03, 0x00cc6602, 0x00cc6000, 0x00cc6000, 0x00cc5f00, 0x00c85c00, 0x00c86104, 0x00be5f0f, 0x00b8601e, 0x00a55324, 0x005c2000, 0x00160000, 0x00241410, 0x00220b00, 0x001e0800, 0x00170c01, 0x0018140d, 0x001c1c1a, 0x001a1718, 0x001d1414, 0x00201818, 0x001a191d, 0x0014181f, 0x00141923, 0x00171a23, 0x001a1918, 0x001c1a16, 0x001a1918, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00191919, 0x00181818, 0x00181818, 0x00181818, 0x00191919, 0x001a1a1a, 0x00191919, 0x00181818, 0x00191919, 0x00141414, 0x000a0a0a, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00373737, 0x00a2a2a2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00919598, 0x00515859, 0x0014181a, 0x00000001, 0x00020000, 0x00080000, 0x000f0100, 0x00150000, 0x00270700, 0x00441a00, 0x005d2e0e, 0x00753c19, 0x00904e26, 0x00a5582a, 0x00b25b27, 0x00bd5c24, 0x00bb5516, 0x00c05813, 0x00c25910, 0x00c25a0d, 0x00c05a0b, 0x00c05c0a, 0x00be5c08, 0x00bf5905, 0x00c45605, 0x00c65404, 0x00c35408, 0x00c1550c, 0x00c15812, 0x00bf5a17, 0x00bc5b1c, 0x00b85b1f, 0x00af5920, 0x00a85823, 0x00964f20, 0x00804018, 0x00683112, 0x0054230c, 0x003e1202, 0x002a0500, 0x001b0000, 0x00180300, 0x00160800, 0x00140c07, 0x00140f0f, 0x00111113, 0x000e1114, 0x000c1012, 0x000e0f10, 0x00101010, 0x0011100f, 0x0013100d, 0x0011100f, 0x00101010, 0x00101012, 0x00101012, 0x00101010, 0x00101010, 0x00101010, 0x00101010, 0x00111111, 0x00101010, 0x00080808, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00020202, 0x00111111, 0x00707070, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00bab6b3, 0x007b7774, 0x0028231c, 0x000c0400, 0x000c0000, 0x001f0500, 0x00441c00, 0x0072350c, 0x009d4e18, 0x00bf5d19, 0x00c2580d, 0x00c4580b, 0x00b44e05, 0x009b4000, 0x00863500, 0x00773000, 0x00722f00, 0x00783600, 0x00824006, 0x008a490a, 0x0094500a, 0x00a96016, 0x00bb6c1b, 0x00be6811, 0x00c06409, 0x00c4670a, 0x00c76809, 0x00c6690a, 0x00c56808, 0x00c46807, 0x00c56704, 0x00c96700, 0x00cc6700, 0x00cc6500, 0x00cb6300, 0x00c66400, 0x00cb6c05, 0x00c86b02, 0x00c46600, 0x00c76902, 0x00c96a04, 0x00c96603, 0x00cc6604, 0x00cc6500, 0x00cc6400, 0x00cc6200, 0x00cc6400, 0x00c15c00, 0x00bc5909, 0x00bc5c19, 0x00964b19, 0x00320d00, 0x00331a0a, 0x00522c1c, 0x003d1705, 0x002a0c00, 0x00170200, 0x00170c05, 0x001d1813, 0x001c1511, 0x001c1614, 0x00191615, 0x0018181c, 0x00181924, 0x0014151f, 0x00141412, 0x00181914, 0x00171715, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00171717, 0x00181818, 0x00181818, 0x00171717, 0x00161616, 0x00171717, 0x00171717, 0x00171717, 0x00161616, 0x00171717, 0x00171717, 0x00131313, 0x00090909, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00060606, 0x00010101, 0x005c5c5c, 0x00b1b1b1, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b2b4b3, 0x00787c7c, 0x00303334, 0x000e0e0e, 0x00030000, 0x00090000, 0x00140000, 0x00180000, 0x002f0900, 0x00501f00, 0x007c3c09, 0x009b5014, 0x00af5d21, 0x00b45c1d, 0x00b95a17, 0x00bc5810, 0x00c0540a, 0x00c45406, 0x00c85604, 0x00cb5703, 0x00c85602, 0x00c65500, 0x00c45700, 0x00c25802, 0x00c25904, 0x00c25804, 0x00c85806, 0x00c85707, 0x00c85708, 0x00c85508, 0x00c75409, 0x00c75409, 0x00c75409, 0x00c6560a, 0x00c25308, 0x00c1570e, 0x00be5714, 0x00b85818, 0x00b45823, 0x00ac5425, 0x0096451c, 0x00793717, 0x004c200a, 0x00301607, 0x001c0800, 0x00100300, 0x000e0805, 0x000f0f0f, 0x000c1012, 0x000a0d10, 0x000e0f10, 0x00101010, 0x0010100e, 0x0010100c, 0x00100f0d, 0x000e0e0e, 0x000f0f10, 0x000f1011, 0x000f0f0f, 0x000f0f0f, 0x000e0e0e, 0x000e0e0e, 0x00101010, 0x00101010, 0x000b0b0b, 0x00030303, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x003d3d3d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b3acaa, 0x0078706c, 0x001c1511, 0x000c0000, 0x00100000, 0x00280700, 0x00542000, 0x008c4817, 0x00b25a1c, 0x00bf5b13, 0x00c15608, 0x00c75808, 0x00c75c08, 0x00c8630f, 0x00c16414, 0x00a8550b, 0x007f3900, 0x00581c00, 0x003a0900, 0x00280000, 0x002f0b00, 0x003f1a00, 0x00623510, 0x00824c1b, 0x00985619, 0x00ad6119, 0x00bd6817, 0x00c1680e, 0x00c26408, 0x00c46404, 0x00c76404, 0x00c86403, 0x00ca6200, 0x00cc6200, 0x00cc6400, 0x00cc6704, 0x00c86807, 0x00c46807, 0x00bf6501, 0x00bf6501, 0x00c46908, 0x00c26705, 0x00c36405, 0x00cc680b, 0x00cc6407, 0x00cc6103, 0x00cc6203, 0x00cc6404, 0x00c96406, 0x00c56208, 0x00be6009, 0x00b2641c, 0x0068380a, 0x00290300, 0x006e3d27, 0x007c4831, 0x005c290f, 0x00380d00, 0x00190000, 0x001e1004, 0x001c170f, 0x00181511, 0x0016120f, 0x00171214, 0x0018141d, 0x0017141d, 0x00141615, 0x00121611, 0x00141614, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00151515, 0x00141414, 0x00141414, 0x00131313, 0x00151515, 0x00161616, 0x00111111, 0x00070707, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00111111, 0x00818181, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a8a8a8, 0x005f6061, 0x001b1c1d, 0x00000000, 0x00050000, 0x000f0000, 0x001e0200, 0x00310700, 0x00541e00, 0x00814118, 0x00a65a25, 0x00b45816, 0x00be5a10, 0x00bf580b, 0x00bc5303, 0x00c15501, 0x00c85902, 0x00cb5900, 0x00cc5800, 0x00cb5700, 0x00cc5800, 0x00cb5a00, 0x00c85b00, 0x00c85c04, 0x00c85e07, 0x00c75e09, 0x00c45d0a, 0x00c25b09, 0x00c35c0b, 0x00c65c0e, 0x00c75c0e, 0x00c8590b, 0x00c95808, 0x00cc5706, 0x00cc5704, 0x00cc5b04, 0x00cc5702, 0x00c85504, 0x00c5560a, 0x00c15812, 0x00bd581a, 0x00ba5821, 0x00ad5c30, 0x00966347, 0x006f4e3c, 0x00442b1f, 0x001e0e05, 0x00080000, 0x00020001, 0x0006090c, 0x000b0f12, 0x000c0f11, 0x000e100f, 0x0010100e, 0x00100f0c, 0x000f0e0c, 0x000d0d0c, 0x000d0d0d, 0x000d0e10, 0x000e0e0e, 0x000e0e0e, 0x000c0c0c, 0x000c0c0c, 0x000e0e0e, 0x000f0f0f, 0x000c0c0c, 0x00060606, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x001f1f1f, 0x00b0b0b0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b5b1ae, 0x00766f6b, 0x00100702, 0x000c0100, 0x00100000, 0x00340b00, 0x00713811, 0x009c521e, 0x00b86120, 0x00c35d11, 0x00c65a06, 0x00c55701, 0x00cc6008, 0x00cc6308, 0x00c96408, 0x00c5650b, 0x00be6811, 0x00b66a20, 0x00a46428, 0x00794418, 0x00491e00, 0x00290800, 0x001b0000, 0x001a0000, 0x002d0700, 0x004c2000, 0x00743e0c, 0x00955618, 0x00ac6119, 0x00be6918, 0x00c4670e, 0x00c76407, 0x00c96203, 0x00cc6306, 0x00cc6308, 0x00c86007, 0x00c25e08, 0x00b75c08, 0x00bc6712, 0x00c06a14, 0x00c0680f, 0x00c1660c, 0x00c3650a, 0x00c46408, 0x00c46106, 0x00c56005, 0x00c76107, 0x00c86007, 0x00c45e04, 0x00c86408, 0x00c96708, 0x00c26000, 0x00bc6410, 0x00a05f24, 0x004c1600, 0x00491300, 0x00834a30, 0x00935430, 0x00753c15, 0x00441700, 0x001d0200, 0x000e0600, 0x000d0e0a, 0x0017140f, 0x0016120f, 0x00140d11, 0x00171117, 0x00161718, 0x00101312, 0x00131414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00141414, 0x00121212, 0x00131313, 0x00131313, 0x00141414, 0x00141414, 0x00131313, 0x00131313, 0x00121212, 0x00131313, 0x00121212, 0x00131313, 0x00131313, 0x000e0e0e, 0x00060606, 0x00000000, 0x00000000, 0x00030303, 0x00000000, 0x00040404, 0x00000000, 0x00373737, 0x00a2a2a2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9c9c, 0x004c4c4d, 0x000c0c0d, 0x00020001, 0x000b0301, 0x000f0000, 0x001f0000, 0x00401100, 0x0075340c, 0x00a85722, 0x00bd6022, 0x00bc520e, 0x00c4530b, 0x00c75407, 0x00c95808, 0x00c85905, 0x00c75801, 0x00c75c00, 0x00c95f00, 0x00c75f00, 0x00cc6404, 0x00cb6606, 0x00cb6708, 0x00c9660b, 0x00c8640c, 0x00c86510, 0x00c66411, 0x00c06212, 0x00bd6718, 0x00b86518, 0x00b86115, 0x00b85e11, 0x00bb5c0e, 0x00c05c0c, 0x00c45d0a, 0x00c85f08, 0x00c45800, 0x00c55800, 0x00c55c04, 0x00c35d0b, 0x00bd5b10, 0x00b65714, 0x00ae5417, 0x00a15424, 0x00885434, 0x006f4a37, 0x00503425, 0x002e1b11, 0x00120803, 0x00030000, 0x00000104, 0x0003070a, 0x0005080b, 0x00090a0c, 0x000c0c0b, 0x000e0d0a, 0x000e0d0a, 0x000c0c0b, 0x000c0c0c, 0x000c0e0d, 0x000d0d0d, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000a0a0a, 0x00080808, 0x00000000, 0x00010101, 0x00010101, 0x00010101, 0x00000000, 0x00141414, 0x00838383, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b4b0, 0x0066625f, 0x00120b07, 0x000c0200, 0x000d0000, 0x00341303, 0x00803916, 0x00b45826, 0x00bb5f1f, 0x00b4550c, 0x00bb5702, 0x00c86006, 0x00cc6406, 0x00cb6001, 0x00cc6304, 0x00cc6404, 0x00ca6807, 0x00c06407, 0x00b96108, 0x00bc6816, 0x00bb681f, 0x00aa6024, 0x00784016, 0x00491c00, 0x00220000, 0x00160000, 0x00140000, 0x001b0200, 0x00422000, 0x00774618, 0x009e5c1f, 0x00b46218, 0x00c46611, 0x00c86308, 0x00c86109, 0x00c4630c, 0x00b95c0a, 0x00a85308, 0x009e510e, 0x00a05314, 0x00aa5614, 0x00b45b14, 0x00c05e11, 0x00c96410, 0x00cb6509, 0x00c66003, 0x00c66306, 0x00c8670c, 0x00c4640c, 0x00c3620c, 0x00c4600a, 0x00c66107, 0x00ca6303, 0x00c7630b, 0x00bf6721, 0x00904816, 0x00360000, 0x00572304, 0x00995829, 0x00a35c2a, 0x0084431c, 0x00491a02, 0x00180804, 0x0008080a, 0x000d120a, 0x0014170c, 0x00100c08, 0x00140d0c, 0x00151418, 0x00101014, 0x00111113, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00101010, 0x00101010, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00111111, 0x00121212, 0x00111111, 0x00101010, 0x00101010, 0x00101010, 0x000c0c0c, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00090909, 0x006a6a6a, 0x000c0c0c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009b9b99, 0x00393938, 0x00070603, 0x00030000, 0x00080000, 0x00120000, 0x002c0800, 0x00612b0d, 0x00995128, 0x00b45d26, 0x00ba5613, 0x00c15408, 0x00cc5809, 0x00cc5708, 0x00c75201, 0x00c85803, 0x00cc5f05, 0x00cc6004, 0x00cc6405, 0x00cc6808, 0x00c6690a, 0x00c26a0e, 0x00bd6c14, 0x00b86a19, 0x00b4671c, 0x00b36420, 0x00b16221, 0x00af5f22, 0x00a95c20, 0x009a5518, 0x00945010, 0x00944805, 0x00984700, 0x00a44c00, 0x00b05502, 0x00bc5e0a, 0x00c26310, 0x00c26414, 0x00c06316, 0x00b95f14, 0x00b05b16, 0x00a85b1c, 0x009b521a, 0x007c3a0c, 0x00592300, 0x002d0800, 0x00200400, 0x00140000, 0x000d0000, 0x00080000, 0x00040000, 0x00000003, 0x00000004, 0x00000004, 0x00030404, 0x00090807, 0x000c0c0a, 0x000d0c0b, 0x000c0c0a, 0x000c0c0a, 0x000d0c0b, 0x000c0c0a, 0x000c0c0a, 0x000c0c0a, 0x000d0c0c, 0x000c0c0e, 0x00080c0e, 0x00070a0c, 0x00070a0c, 0x00000000, 0x00010000, 0x00000000, 0x00010000, 0x00000000, 0x000c0e0d, 0x00585858, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b0b0b0, 0x006c6967, 0x00160f09, 0x000c0000, 0x00160000, 0x00341400, 0x00854e2f, 0x00b55828, 0x00c45616, 0x00c0560d, 0x00c25c0a, 0x00cc6910, 0x00c46102, 0x00c86404, 0x00c86101, 0x00cc6404, 0x00c55d00, 0x00c56101, 0x00c86807, 0x00c46505, 0x00c36405, 0x00c5640b, 0x00c06314, 0x00b46726, 0x009a5b26, 0x00673610, 0x00300e00, 0x00120000, 0x000c0000, 0x00100000, 0x001c0000, 0x00582701, 0x00884813, 0x00b2621e, 0x00bd6415, 0x00bd600c, 0x00c1640f, 0x00c16714, 0x00b86215, 0x009b4a0a, 0x00752700, 0x006f2000, 0x00903f08, 0x00aa581c, 0x00b35c18, 0x00b86012, 0x00c16811, 0x00c06409, 0x00c06308, 0x00bc5e08, 0x00c86713, 0x00c5610c, 0x00c05a02, 0x00cc6507, 0x00c65f01, 0x00c45f0f, 0x00b76224, 0x00622500, 0x00400b00, 0x00783807, 0x00a35c27, 0x00aa5d2c, 0x00904f29, 0x004c2515, 0x001a0800, 0x000a0400, 0x00131204, 0x00141004, 0x00130d08, 0x00121014, 0x000e0d14, 0x00100f10, 0x0010100e, 0x0010100e, 0x00101010, 0x000f1010, 0x000f1011, 0x000f1011, 0x000f1011, 0x00101010, 0x00101010, 0x00100f10, 0x00100f10, 0x00101010, 0x00101010, 0x00101010, 0x000f1010, 0x00101010, 0x00101010, 0x00101010, 0x00101010, 0x000f0f0f, 0x000f0f0f, 0x000f0f0f, 0x00101010, 0x000f0f0f, 0x00111111, 0x00101010, 0x000e0e0e, 0x000f0f0f, 0x000f0f0f, 0x00080808, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00040404, 0x00323232, 0x00949494, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009e9c9d, 0x002a2c27, 0x00040600, 0x00020000, 0x000a0000, 0x00190000, 0x00401000, 0x00803a1a, 0x00b4592b, 0x00bf581c, 0x00c0540d, 0x00c45506, 0x00c45804, 0x00c45a03, 0x00c25a02, 0x00c96409, 0x00c76407, 0x00cb6809, 0x00cc6909, 0x00ca6608, 0x00ca690d, 0x00bf6812, 0x00b36b1d, 0x00a16824, 0x00946430, 0x007a4d24, 0x00603415, 0x004e2107, 0x003b0c00, 0x00360700, 0x00320300, 0x00380000, 0x00550f00, 0x00833200, 0x00ab5304, 0x00bb610b, 0x00bb6410, 0x00b8651b, 0x00b26528, 0x00a55d2c, 0x00914f24, 0x00733913, 0x004a1b00, 0x00260200, 0x00110000, 0x000d0000, 0x00060000, 0x00050000, 0x00090000, 0x00090000, 0x00050000, 0x00020000, 0x00000001, 0x00000003, 0x00000000, 0x00000000, 0x00010000, 0x00070506, 0x0009090b, 0x000a080b, 0x000e0806, 0x00100807, 0x00100908, 0x000f0807, 0x000e0805, 0x000c0808, 0x00080a0e, 0x00050c14, 0x00040c14, 0x00040b10, 0x00020403, 0x00030000, 0x00050100, 0x00020000, 0x00000100, 0x00060908, 0x00262825, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00555455, 0x00727071, 0x00130e0e, 0x000b0000, 0x001c0000, 0x00421300, 0x00975224, 0x00b45921, 0x00c25414, 0x00c8540c, 0x00cc5c08, 0x00c75c01, 0x00c86409, 0x00c46307, 0x00c66508, 0x00c46004, 0x00c86005, 0x00c96007, 0x00c86007, 0x00c66205, 0x00c46401, 0x00c46402, 0x00c56008, 0x00c4600a, 0x00c0610b, 0x00b66012, 0x00b16c2c, 0x00855022, 0x00401a02, 0x001c0300, 0x00100000, 0x000e0000, 0x00170000, 0x00370e00, 0x00703810, 0x00a56027, 0x00b8661c, 0x00bf630e, 0x00c46007, 0x00c46008, 0x00c25f12, 0x00b96020, 0x007a3202, 0x00440800, 0x003d0b00, 0x00623008, 0x00945c24, 0x00a5621c, 0x00b46514, 0x00b96108, 0x00c2620a, 0x00c6600b, 0x00c45d08, 0x00c66008, 0x00c86307, 0x00c35d00, 0x00c75f04, 0x00be6315, 0x00974f1d, 0x004d1200, 0x00460e00, 0x00854617, 0x00ab5c22, 0x00b05d24, 0x009c5128, 0x00642b0c, 0x00250400, 0x00140300, 0x00140a00, 0x000e0c04, 0x00101014, 0x000c0b10, 0x00100c09, 0x00100c07, 0x000d0c09, 0x000c0e0c, 0x000b0e0f, 0x000a0e10, 0x000b0f12, 0x000c0f11, 0x000d0d0f, 0x000e0c0d, 0x00100c0d, 0x00100c0c, 0x000e0d0c, 0x000d0d0c, 0x000c0e0d, 0x000b0e0d, 0x000c0e0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000e0e0e, 0x000f0f0f, 0x000d0d0d, 0x00090909, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00030303, 0x006e6e6e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a9a7ae, 0x00202022, 0x00040500, 0x00030000, 0x000f0100, 0x001c0000, 0x00552204, 0x00984e25, 0x00b45824, 0x00c55818, 0x00c75308, 0x00c85300, 0x00c75500, 0x00c55a01, 0x00c76105, 0x00c86404, 0x00cc6c0a, 0x00c76a08, 0x00c3680a, 0x00c16812, 0x00c36e1e, 0x00b86c26, 0x00985818, 0x006e3a05, 0x00431a00, 0x00240200, 0x001c0000, 0x001d0000, 0x001e0000, 0x00260000, 0x003c0c00, 0x00683310, 0x0092542b, 0x00b36838, 0x00b26429, 0x00b1611b, 0x00b86b20, 0x00ae6925, 0x00985b23, 0x006d3814, 0x004c1c04, 0x002a0000, 0x00190000, 0x00130000, 0x000d0000, 0x00040000, 0x00000004, 0x00000004, 0x00000001, 0x00060000, 0x00080000, 0x00080000, 0x00070000, 0x00050000, 0x00050000, 0x00080000, 0x000c0000, 0x000b0000, 0x00080000, 0x00080000, 0x000f0807, 0x00100a08, 0x000c0506, 0x000e0909, 0x000f0a0a, 0x000d0907, 0x000a0706, 0x0006090c, 0x00060c12, 0x00040c13, 0x0001080e, 0x00030404, 0x00000000, 0x00020000, 0x00020000, 0x00000000, 0x00000100, 0x00191b18, 0x00aeb2ad, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0078787a, 0x001d1c1b, 0x00080000, 0x00190000, 0x004a1800, 0x00934c1d, 0x00b75a1c, 0x00c35810, 0x00ca570a, 0x00c85200, 0x00cc5c03, 0x00cc6204, 0x00c35e04, 0x00c05f04, 0x00c5650b, 0x00c46307, 0x00c76107, 0x00c96008, 0x00c96009, 0x00c86007, 0x00c56101, 0x00c56101, 0x00c66008, 0x00c86008, 0x00c96101, 0x00c66306, 0x00bb6113, 0x00b06325, 0x009c5f34, 0x00623318, 0x00240300, 0x00140000, 0x000e0000, 0x00100000, 0x00210400, 0x00512601, 0x009c5d26, 0x00b4641c, 0x00bd5d05, 0x00cb6308, 0x00c45b04, 0x00c16418, 0x00af612a, 0x00874a20, 0x004b1c00, 0x00220000, 0x00330900, 0x005b2b00, 0x0094571b, 0x00b06622, 0x00bc641a, 0x00bd5e0e, 0x00c86110, 0x00c45c05, 0x00be5800, 0x00c96406, 0x00c55e00, 0x00c56411, 0x00b56428, 0x00753407, 0x003b0400, 0x00531b00, 0x00904a17, 0x00ac5b21, 0x00b25821, 0x009e4c1c, 0x006c300e, 0x00270100, 0x000e0000, 0x00131008, 0x0006080c, 0x000b0d13, 0x000f0c0b, 0x000f0c08, 0x000d0c09, 0x000c0d0b, 0x000a0d0e, 0x000a0e10, 0x000a0e10, 0x000b0e10, 0x000d0d0f, 0x000e0c0d, 0x00100c0d, 0x00100c0d, 0x000e0c0d, 0x000d0d0d, 0x000b0e0d, 0x000b0e0d, 0x000c0e0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000d0d0d, 0x000e0e0e, 0x000d0d0d, 0x000c0c0c, 0x000d0d0d, 0x000e0e0e, 0x000d0d0d, 0x000c0c0c, 0x00090909, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00404040, 0x009b9b9b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a8abad, 0x001d2124, 0x00000004, 0x00080303, 0x00100000, 0x00200000, 0x006c310d, 0x009e4f1b, 0x00b95815, 0x00c25709, 0x00c65501, 0x00c75600, 0x00c85c04, 0x00ca5f06, 0x00cb6207, 0x00cc6808, 0x00cc6b02, 0x00c86700, 0x00c66804, 0x00c57019, 0x00ae6523, 0x00844c1a, 0x00562c0c, 0x002c0d00, 0x001a0000, 0x00190000, 0x00180000, 0x00270000, 0x004a1a00, 0x00763d0c, 0x009d5a20, 0x00b06221, 0x00b76018, 0x00b85f18, 0x00b76225, 0x00b46931, 0x00a4642f, 0x00804b1c, 0x00522803, 0x00301000, 0x001d0400, 0x00100000, 0x000b0000, 0x00080000, 0x00070000, 0x00040000, 0x00030000, 0x00040000, 0x00080000, 0x000c0000, 0x00100000, 0x00120000, 0x00120000, 0x00100000, 0x00100000, 0x00110000, 0x001a0000, 0x001a0000, 0x001e0000, 0x00200200, 0x00180100, 0x000c0000, 0x00060304, 0x00080a10, 0x0004080d, 0x0005080c, 0x000a0a0c, 0x000c0b09, 0x00080804, 0x00050403, 0x00060807, 0x000a0d0e, 0x00040708, 0x00000000, 0x00000000, 0x00030200, 0x00000000, 0x00000000, 0x000f0f0f, 0x008c8e8d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00858d8e, 0x00283434, 0x00000000, 0x00110000, 0x00481a00, 0x008d4114, 0x00bd5f25, 0x00bd5613, 0x00c35508, 0x00cc5b07, 0x00cb5b00, 0x00c95f00, 0x00c76104, 0x00c15c04, 0x00c4600a, 0x00c6620a, 0x00c25d04, 0x00c66004, 0x00c86006, 0x00ca5e08, 0x00ca5e08, 0x00ca5f06, 0x00c85f06, 0x00c46008, 0x00c46007, 0x00c45b00, 0x00c96004, 0x00c8600b, 0x00c45e10, 0x00bd5f17, 0x00ac5c20, 0x007d3d13, 0x003b0f00, 0x00130000, 0x000d0300, 0x00050000, 0x00140600, 0x00431f00, 0x00905424, 0x00b8641b, 0x00be5d08, 0x00c46409, 0x00bf6209, 0x00bd6213, 0x00b4611d, 0x0099521c, 0x00602500, 0x00280000, 0x00200000, 0x00310d00, 0x005d2f10, 0x00985628, 0x00b86326, 0x00c15e11, 0x00c96008, 0x00cb6205, 0x00c45d00, 0x00c35c04, 0x00be5b0b, 0x00bd641f, 0x00a45720, 0x00581d00, 0x00310000, 0x005b2809, 0x0090512b, 0x00ae5a25, 0x00b95e24, 0x00a34f1a, 0x00682b01, 0x00250800, 0x00070000, 0x0006080e, 0x00040c13, 0x00080c0f, 0x00090c0d, 0x000b0c0d, 0x000b0c0c, 0x000b0c0c, 0x000b0c0a, 0x000c0c0a, 0x000c0c0c, 0x000c0b0c, 0x000c0b0c, 0x000c0b0d, 0x000c0c0d, 0x000c0c0d, 0x000b0c0c, 0x000b0c0c, 0x000b0c0a, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000b0b0b, 0x000b0b0b, 0x000c0c0c, 0x000c0c0c, 0x000c0c0c, 0x000b0b0b, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00121212, 0x00737373, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a8a9ab, 0x002a3032, 0x00040909, 0x00040301, 0x000c0000, 0x00250100, 0x006c3313, 0x00a75423, 0x00bc5615, 0x00c45405, 0x00c95800, 0x00c75b00, 0x00c45c00, 0x00c56103, 0x00ca6609, 0x00cc680a, 0x00cc6909, 0x00c66702, 0x00c56b09, 0x00be6814, 0x00a25917, 0x006c380b, 0x00341100, 0x00100000, 0x000a0000, 0x00130000, 0x00200200, 0x00431800, 0x007d481a, 0x00a06227, 0x00a55f19, 0x00b16218, 0x00bd6819, 0x00bc6416, 0x00bc681f, 0x00a35820, 0x00743609, 0x00461800, 0x002c0800, 0x001c0000, 0x00140000, 0x00100000, 0x000e0000, 0x000d0000, 0x000f0000, 0x00100000, 0x00160000, 0x001e0500, 0x00280b00, 0x002f0c00, 0x00391500, 0x00481f00, 0x00532808, 0x005c3010, 0x0064381a, 0x006f4024, 0x00774528, 0x007c4624, 0x00844925, 0x0091542c, 0x0090572f, 0x006d3e1e, 0x003a1700, 0x00140200, 0x00090300, 0x0008080c, 0x0003070c, 0x00040408, 0x00060606, 0x000d0906, 0x000e0b04, 0x000c0804, 0x00070602, 0x00060807, 0x00000203, 0x00000001, 0x00030102, 0x00040000, 0x00030000, 0x0009080a, 0x00656468, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009ca1a6, 0x00384143, 0x00000601, 0x000d0700, 0x003c1500, 0x00854116, 0x00b85920, 0x00c05410, 0x00c3570d, 0x00c95c0b, 0x00ca5d04, 0x00cc6102, 0x00c05b00, 0x00c36004, 0x00c5610c, 0x00c56310, 0x00bf5a08, 0x00c45f09, 0x00c46005, 0x00c75f04, 0x00ca5d05, 0x00cb5c07, 0x00cb5c07, 0x00c95d08, 0x00c46008, 0x00c46007, 0x00c95e04, 0x00ca5c03, 0x00c75803, 0x00cb5d08, 0x00c85e0a, 0x00c15f12, 0x00b05d1e, 0x00894a1c, 0x00442004, 0x00120100, 0x00050300, 0x00040000, 0x00150100, 0x00401600, 0x00904e19, 0x00b6631c, 0x00b8600a, 0x00bc6004, 0x00c05f06, 0x00bf600e, 0x00b9611c, 0x00a0561f, 0x0067300c, 0x00310900, 0x00160000, 0x00200000, 0x00451600, 0x007c3c12, 0x00ac5b1f, 0x00bd6015, 0x00be5c08, 0x00c45f09, 0x00c45f0b, 0x00c15c0b, 0x00bd5b10, 0x00ba6223, 0x008b4719, 0x003e0a00, 0x002b0300, 0x00582810, 0x00954c22, 0x00b25821, 0x00b9591b, 0x00a3511c, 0x00572a0c, 0x00140000, 0x00070204, 0x00080c13, 0x00050b11, 0x00050b10, 0x00070b0d, 0x000a0c0b, 0x000b0c08, 0x000b0a06, 0x000b0a06, 0x000a0906, 0x000c0b09, 0x000b0b0b, 0x000b0a0e, 0x000a0b0e, 0x000a0b0e, 0x000a0b0c, 0x000a0c0b, 0x000b0b09, 0x000a0a0a, 0x000a0a0a, 0x000a0a0a, 0x000a0a0a, 0x000a0a0a, 0x000a0a0a, 0x000a0a0a, 0x000a0a0a, 0x000b0b0b, 0x000a0a0a, 0x00090909, 0x00090909, 0x000a0a0a, 0x000a0a0a, 0x000a0a0a, 0x000a0a0a, 0x00080808, 0x00020202, 0x00010101, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00535353, 0x00b0b0b0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00434344, 0x00444448, 0x0003070c, 0x00000000, 0x000c0000, 0x00250600, 0x0069310a, 0x00a25220, 0x00b75014, 0x00c6550f, 0x00c95607, 0x00c85b03, 0x00c46203, 0x00c36804, 0x00c46b06, 0x00c86c08, 0x00cc6606, 0x00c56207, 0x00bc6a16, 0x00b46e26, 0x008e4f18, 0x00501f00, 0x00220600, 0x000c0000, 0x00060000, 0x00120400, 0x00240300, 0x00653310, 0x00985823, 0x00b06622, 0x00b3651a, 0x00b46618, 0x00ba6b22, 0x00ac6320, 0x00985c20, 0x00693807, 0x003e1400, 0x002a0600, 0x001e0000, 0x00180000, 0x00200000, 0x00350b00, 0x00411200, 0x004c1a00, 0x005a2804, 0x0069370c, 0x00784211, 0x00844813, 0x008e4c17, 0x00944e17, 0x009d541a, 0x00a2581c, 0x00a55a20, 0x00a5581f, 0x00a4561d, 0x00a8551e, 0x00aa571e, 0x00af561c, 0x00b85b1c, 0x00b95818, 0x00b85713, 0x00b75b1a, 0x00b05f25, 0x0094501f, 0x00582701, 0x00200000, 0x000a0000, 0x00080708, 0x0008090c, 0x00040507, 0x00070400, 0x000f0903, 0x00100800, 0x00090400, 0x00040403, 0x00000404, 0x00000001, 0x00000001, 0x00030000, 0x00060000, 0x00080408, 0x003c3c40, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b2b3b7, 0x00484d54, 0x00101414, 0x00060000, 0x002b0f00, 0x00783b11, 0x00b0571e, 0x00c05410, 0x00c95609, 0x00c85c08, 0x00c65e06, 0x00c46002, 0x00c05e00, 0x00c05c03, 0x00c5630e, 0x00bc5b0a, 0x00b75709, 0x00b8580c, 0x00c66415, 0x00c25e06, 0x00c55d02, 0x00ca5c00, 0x00cc5b01, 0x00cc5a07, 0x00c95c07, 0x00c45f06, 0x00c45f04, 0x00c95b04, 0x00cc5c07, 0x00c85d0b, 0x00c86110, 0x00c15c10, 0x00bb580d, 0x00be6014, 0x00ab5b16, 0x008c501a, 0x004e2803, 0x00100000, 0x000c0400, 0x000a0000, 0x00140000, 0x00411600, 0x008b4d20, 0x00b1601c, 0x00ba5d0c, 0x00c05f0b, 0x00c3620e, 0x00b85808, 0x00b45c17, 0x00a65b23, 0x00703309, 0x00380d00, 0x00220000, 0x00190000, 0x002c0900, 0x005b2908, 0x00925020, 0x00b86224, 0x00bd5c14, 0x00bc5a08, 0x00c5600d, 0x00c3580c, 0x00bc5815, 0x00ac5c24, 0x006d3008, 0x00280300, 0x00280400, 0x00622910, 0x00954822, 0x00bc5e24, 0x00b15718, 0x008e4d1b, 0x00512707, 0x00110000, 0x000c070c, 0x00040810, 0x00030912, 0x0005090c, 0x00080a09, 0x000a0905, 0x000c0904, 0x000b0801, 0x000a0802, 0x000a0906, 0x00090909, 0x0008090c, 0x0008090c, 0x0008090c, 0x0008090b, 0x00090909, 0x00090908, 0x00090909, 0x00090909, 0x00090909, 0x00090909, 0x00090909, 0x00090909, 0x00090909, 0x00090909, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00090909, 0x00090909, 0x00080808, 0x00080808, 0x00090909, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00313131, 0x00909090, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0067666a, 0x0008070b, 0x00010004, 0x000e0200, 0x001a0000, 0x00643408, 0x00a2571d, 0x00b85815, 0x00c55510, 0x00c95409, 0x00c65406, 0x00c15901, 0x00c16604, 0x00c57008, 0x00c46e04, 0x00c46a04, 0x00cb6809, 0x00c46916, 0x00b06c2c, 0x007c4819, 0x00401700, 0x00190000, 0x000c0000, 0x00060000, 0x000b0000, 0x002a1000, 0x00734118, 0x00a15c23, 0x00bb671d, 0x00bc620d, 0x00bd640e, 0x00c06c1a, 0x00ac5c18, 0x00823f04, 0x004b1800, 0x00350c00, 0x002d0700, 0x003b1600, 0x00532c11, 0x00673b1c, 0x0079441a, 0x00874a1c, 0x00934f1c, 0x009c531b, 0x00a1581c, 0x00a75b1b, 0x00ab5b16, 0x00b05c15, 0x00b85d17, 0x00bc5e18, 0x00bb5f18, 0x00ba5e15, 0x00bb5c14, 0x00ba5910, 0x00be5a12, 0x00c35b14, 0x00c35a12, 0x00c4560d, 0x00c45204, 0x00cc5808, 0x00cc5704, 0x00c05002, 0x00bc560d, 0x00b85f1d, 0x009c5018, 0x0071380d, 0x00280700, 0x00130400, 0x00090100, 0x00080607, 0x00070604, 0x00040200, 0x00090200, 0x000f0901, 0x00060502, 0x00040504, 0x00000001, 0x00000000, 0x00030000, 0x00060103, 0x00050308, 0x001c1c23, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0067686b, 0x00171819, 0x00060000, 0x00270a00, 0x00642f0b, 0x00a85520, 0x00bf5815, 0x00c45309, 0x00cc5b09, 0x00c85c05, 0x00bf5b00, 0x00bf6001, 0x00bd6006, 0x00c16415, 0x00b75810, 0x00a04200, 0x00ac4d05, 0x00be5f15, 0x00bd5c0c, 0x00c25c07, 0x00c45c01, 0x00c85c00, 0x00c85b00, 0x00c95a06, 0x00c85c08, 0x00c35e05, 0x00c35e05, 0x00c85e0d, 0x00c1590c, 0x00ba590f, 0x00b65810, 0x00ac4d07, 0x00ac4b02, 0x00bb5806, 0x00bb5e0d, 0x00b16219, 0x00975921, 0x00583110, 0x00160000, 0x000e0000, 0x000c0000, 0x001c0200, 0x003c1000, 0x00914e1c, 0x00b5611f, 0x00b65b0e, 0x00bd5c09, 0x00c7610f, 0x00c36011, 0x00bc601a, 0x00a3541c, 0x00793c13, 0x00340900, 0x00140000, 0x00190400, 0x001f0300, 0x00401800, 0x0084441c, 0x00ae5f28, 0x00b86018, 0x00c05d0f, 0x00c55809, 0x00c2560c, 0x00bf601e, 0x009a501e, 0x004f2003, 0x00220000, 0x002b0000, 0x0060250e, 0x00984818, 0x00b05a20, 0x00b26429, 0x008a4b1d, 0x00401700, 0x00100000, 0x00080409, 0x0003060f, 0x0006070a, 0x00080806, 0x000b0803, 0x000b0800, 0x000a0800, 0x00090701, 0x00080804, 0x00070808, 0x0007080b, 0x0005080b, 0x0007080b, 0x00080809, 0x00080708, 0x00080806, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00090909, 0x00090909, 0x00090909, 0x00080808, 0x00080808, 0x00070707, 0x00080808, 0x00040404, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00121212, 0x00707070, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0088898c, 0x00151419, 0x00070205, 0x000c0000, 0x00180000, 0x00613008, 0x009c551a, 0x00b4590c, 0x00c45908, 0x00c45205, 0x00cc590e, 0x00cc6315, 0x00c8640e, 0x00c76b07, 0x00c46c00, 0x00bd6700, 0x00c06702, 0x00c46910, 0x00b86824, 0x00784319, 0x00371501, 0x00100000, 0x00080000, 0x00080000, 0x00100200, 0x00381b00, 0x00754410, 0x00a05916, 0x00b86110, 0x00cb660c, 0x00c86102, 0x00c25f04, 0x00b35808, 0x008c3b00, 0x00661f00, 0x006a2a00, 0x00743806, 0x00824515, 0x008e4d1b, 0x0098531c, 0x00a6591c, 0x00b3601c, 0x00ba631a, 0x00bb6015, 0x00ba5f12, 0x00b85c10, 0x00b95c0f, 0x00bd5f12, 0x00c15f14, 0x00c05b10, 0x00ba560e, 0x00b85a14, 0x00bb5c17, 0x00c05c12, 0x00c25a0d, 0x00c4590c, 0x00c85a0d, 0x00c6580c, 0x00c35406, 0x00c55203, 0x00ca5503, 0x00cc5704, 0x00c95705, 0x00c55a0c, 0x00c15b12, 0x00b75814, 0x00a5541a, 0x00753810, 0x003c1400, 0x00110000, 0x000a0100, 0x000c0c0e, 0x00040808, 0x00030200, 0x00080602, 0x00080602, 0x00080602, 0x00000000, 0x00020100, 0x00020001, 0x00030105, 0x00040309, 0x00090c11, 0x00acb1b1, 0x00000000, 0x00000000, 0x00000000, 0x007a7a7c, 0x001f1f1d, 0x00100a02, 0x001b0300, 0x005b2200, 0x00a04c1a, 0x00bd581a, 0x00c4550e, 0x00c75c10, 0x00c55c0b, 0x00c75f07, 0x00c46005, 0x00bc5f06, 0x00ba6214, 0x00a95419, 0x008c3804, 0x00903900, 0x00ac5310, 0x00c26014, 0x00bc5404, 0x00c45b06, 0x00c45b04, 0x00c45c01, 0x00c35d03, 0x00c35c07, 0x00c25c08, 0x00c25d05, 0x00c05d0a, 0x00b4550d, 0x00bc6322, 0x00a85316, 0x008e3c00, 0x009e4807, 0x00b85d14, 0x00bf5c0a, 0x00c4600c, 0x00b75804, 0x00b46016, 0x00915015, 0x005c2d05, 0x00240600, 0x00100000, 0x00080000, 0x00120000, 0x00481800, 0x00934f21, 0x00b46020, 0x00bb5b0f, 0x00c45d0a, 0x00be5401, 0x00ba5207, 0x00c0601d, 0x00ab5920, 0x007d3e11, 0x003b1400, 0x00110000, 0x000c0000, 0x00110000, 0x00351501, 0x00693817, 0x00a25b24, 0x00b85d17, 0x00c55b0a, 0x00cb5908, 0x00c65b0d, 0x00b45818, 0x007f3e14, 0x003f1100, 0x00170000, 0x00260400, 0x00511e02, 0x008e4a1f, 0x00ac5922, 0x00a8571f, 0x00824115, 0x00320700, 0x00110000, 0x00080306, 0x00090404, 0x000a0603, 0x000b0702, 0x00090700, 0x00080800, 0x00060700, 0x00070804, 0x00060807, 0x00060708, 0x00060708, 0x00070708, 0x00070708, 0x00080607, 0x00080607, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00070707, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00080808, 0x00070707, 0x00070707, 0x00070707, 0x00070707, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00010101, 0x00020202, 0x00545454, 0x000c0c0c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a0a3a5, 0x00343438, 0x00010004, 0x00080000, 0x00160000, 0x004f1f04, 0x0094501c, 0x00b35b15, 0x00bf5603, 0x00c75500, 0x00cc5b07, 0x00ca5c09, 0x00ca610c, 0x00c8650a, 0x00c96a04, 0x00c46900, 0x00c16b06, 0x00c07014, 0x00af6319, 0x00894b16, 0x00341000, 0x00110000, 0x00090001, 0x00060000, 0x000c0000, 0x00351800, 0x00754210, 0x00a8611c, 0x00c36918, 0x00c25e01, 0x00c95e00, 0x00ca5d00, 0x00c86004, 0x00be5c0c, 0x00a44d0c, 0x009a4a0e, 0x00a15317, 0x00ab5b1e, 0x00b46122, 0x00ba6320, 0x00bb6017, 0x00bb5c0e, 0x00bf5c09, 0x00c35d08, 0x00c15b04, 0x00c35d08, 0x00c35f0a, 0x00c05b08, 0x00bf5808, 0x00c0580a, 0x00c4590c, 0x00c15a11, 0x00a24404, 0x00ac5010, 0x00bc5914, 0x00c25910, 0x00c4570a, 0x00c45607, 0x00c55708, 0x00c45605, 0x00c85908, 0x00c85705, 0x00ca5503, 0x00cb5604, 0x00c85604, 0x00c45407, 0x00c4560b, 0x00bd5916, 0x00b05a24, 0x007c3a10, 0x00401400, 0x00180000, 0x00060000, 0x00000406, 0x00020508, 0x00050706, 0x00050401, 0x00060400, 0x00020000, 0x00040100, 0x00000001, 0x00000004, 0x0000030a, 0x0002040a, 0x00989b9a, 0x00000000, 0x00000000, 0x009e9697, 0x00343331, 0x000c0800, 0x00100000, 0x00482000, 0x00964a17, 0x00b75112, 0x00ca5711, 0x00cb570c, 0x00c3580c, 0x00c05a09, 0x00c35d08, 0x00be5d09, 0x00b86316, 0x00ab5b1c, 0x00803206, 0x006c1c00, 0x009b480f, 0x00b85c18, 0x00c0590c, 0x00c85d0b, 0x00c45a08, 0x00c45b06, 0x00c15c02, 0x00bf5e04, 0x00bf5c08, 0x00bf5d0c, 0x00bc5e10, 0x00b95e17, 0x00b26020, 0x00873600, 0x00883700, 0x00a04d11, 0x00b05814, 0x00bc5e14, 0x00c05b0b, 0x00c05702, 0x00c65d07, 0x00ba5804, 0x00b66017, 0x009c561d, 0x005b2c0a, 0x001e0200, 0x00080000, 0x000a0000, 0x001d0000, 0x00552205, 0x0098511e, 0x00b7601d, 0x00bd5a0c, 0x00c55c0b, 0x00c75c0c, 0x00c0570e, 0x00b85815, 0x00a7581e, 0x00763f11, 0x003a1800, 0x00120200, 0x00080000, 0x000f0100, 0x00260c00, 0x0067340f, 0x00a35820, 0x00be5f15, 0x00c45804, 0x00c45301, 0x00c25b12, 0x00ac5924, 0x006e3210, 0x002d0b00, 0x00130000, 0x00240400, 0x004c1c01, 0x00843c0e, 0x00b1602a, 0x00a15520, 0x006c3108, 0x001a0000, 0x000f0000, 0x000e0200, 0x000c0400, 0x000a0601, 0x00080801, 0x00050802, 0x00050703, 0x00050704, 0x00050704, 0x00060606, 0x00060606, 0x00070506, 0x00070506, 0x00070508, 0x00070506, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00060606, 0x00070707, 0x00050505, 0x00080808, 0x00000000, 0x00010101, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00404040, 0x00a9a9a9, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b1b5b8, 0x005a5c60, 0x0009080c, 0x00060000, 0x00100000, 0x00401100, 0x008a4618, 0x00b0571d, 0x00bb540d, 0x00cc5a0a, 0x00cc5902, 0x00cc5c02, 0x00cc6406, 0x00ca6401, 0x00cc6a04, 0x00c96500, 0x00c36604, 0x00bc6a16, 0x00ac6824, 0x00814b1a, 0x003c1800, 0x000e0000, 0x000e0400, 0x00080000, 0x00100000, 0x003d1800, 0x007e471b, 0x00ac5f21, 0x00bc6014, 0x00c5600a, 0x00c35a00, 0x00c85e00, 0x00cc6105, 0x00c65c06, 0x00c05b08, 0x00bf5f11, 0x00c06015, 0x00c05c12, 0x00c56015, 0x00c25c0f, 0x00bf5a08, 0x00c35d09, 0x00c46008, 0x00c25c04, 0x00c25c04, 0x00c45d06, 0x00c15c08, 0x00bf5a08, 0x00c0590a, 0x00c1590b, 0x00c05608, 0x00c25505, 0x00c25b11, 0x009a4007, 0x00863000, 0x00a64b10, 0x00bb5a19, 0x00bf580e, 0x00c15607, 0x00c65c0b, 0x00c15706, 0x00c1590b, 0x00c15607, 0x00ca5807, 0x00cb5500, 0x00cc5400, 0x00cc5301, 0x00c65003, 0x00c95812, 0x00bc5210, 0x00b65b23, 0x00843f14, 0x00411200, 0x00180300, 0x00080506, 0x0000040a, 0x00000409, 0x00000404, 0x00040300, 0x00020000, 0x00020000, 0x00000000, 0x00000003, 0x00000005, 0x0004060a, 0x00838182, 0x00000000, 0x00b9b1b8, 0x004c4549, 0x000c0805, 0x000c0000, 0x00381a00, 0x007b440e, 0x00af5713, 0x00c95c0f, 0x00c74f01, 0x00cc5508, 0x00cc5e11, 0x00bd5709, 0x00c05c0e, 0x00b55c14, 0x00b0672e, 0x00743306, 0x00510a00, 0x007d3007, 0x00b05619, 0x00c05e14, 0x00c25807, 0x00c85b09, 0x00c2580a, 0x00c05a09, 0x00bf5e04, 0x00be5e04, 0x00bc5c09, 0x00b95d14, 0x00ad581d, 0x009f501a, 0x00762c00, 0x00863800, 0x009f490b, 0x00b55613, 0x00c05c11, 0x00c25c0e, 0x00c05a0c, 0x00c1590b, 0x00c15807, 0x00c45d0a, 0x00c05b09, 0x00b55d18, 0x00985423, 0x0052270a, 0x00120000, 0x00080000, 0x00110000, 0x00240200, 0x005d2a05, 0x00a05a23, 0x00b05c17, 0x00bc5c10, 0x00c35b10, 0x00c3580e, 0x00c05a11, 0x00b85c18, 0x00a2581a, 0x0076400d, 0x00361400, 0x000f0000, 0x00080000, 0x00080000, 0x00240800, 0x0061300a, 0x00a2551a, 0x00ba5b10, 0x00c65909, 0x00c45708, 0x00b95816, 0x009a4e1b, 0x00582608, 0x001d0000, 0x00100000, 0x00200600, 0x00461600, 0x0083431a, 0x00ac622c, 0x00985424, 0x00461a01, 0x001c0000, 0x00120000, 0x000c0000, 0x000c0803, 0x00050704, 0x00010604, 0x00000807, 0x00020504, 0x00040503, 0x00060504, 0x00080404, 0x00080404, 0x00080405, 0x00060407, 0x00050507, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00050505, 0x00050505, 0x00040404, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x002d2d2d, 0x008b8b8b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x001f2020, 0x00858b90, 0x001f1e22, 0x00080000, 0x000d0000, 0x00270200, 0x007c3b0f, 0x00b05a1e, 0x00c35e1b, 0x00c35409, 0x00c95402, 0x00cc5800, 0x00cc6004, 0x00cb6707, 0x00c86907, 0x00c16708, 0x00c0680f, 0x00b8681c, 0x00985518, 0x00673409, 0x00361500, 0x00100000, 0x000a0000, 0x00080000, 0x00160200, 0x00442000, 0x0081471b, 0x00aa5c24, 0x00bd5f19, 0x00c75d0d, 0x00cc6008, 0x00c95d00, 0x00c75c01, 0x00c55c04, 0x00c45c08, 0x00c7600e, 0x00c5600c, 0x00c05906, 0x00ca5d0c, 0x00c45504, 0x00c45a08, 0x00c6600a, 0x00c05a06, 0x00bf5904, 0x00c45e08, 0x00c75e08, 0x00c35903, 0x00c25904, 0x00c05908, 0x00c25a0d, 0x00c45c10, 0x00c45b0c, 0x00c25805, 0x00bc570b, 0x00ac521a, 0x00792700, 0x00702000, 0x009d4c17, 0x00b15819, 0x00b85810, 0x00be5808, 0x00c25b0a, 0x00bf590c, 0x00bc5508, 0x00c45707, 0x00c55300, 0x00cc5100, 0x00cc5402, 0x00ca5206, 0x00cb540c, 0x00cc550f, 0x00c35514, 0x00b2541c, 0x00843e14, 0x00401700, 0x00110000, 0x00010004, 0x0000080f, 0x00000408, 0x00040504, 0x00020100, 0x00000000, 0x00000100, 0x00000102, 0x00000204, 0x00000406, 0x00626063, 0x007b787b, 0x00646168, 0x00181115, 0x000c0000, 0x002e1300, 0x006a3808, 0x00a05817, 0x00bb5b0d, 0x00c45300, 0x00cc5907, 0x00cc5403, 0x00c55508, 0x00c35c13, 0x00b95e18, 0x00ac5f24, 0x00743811, 0x00430c00, 0x005f1c00, 0x009d4c1a, 0x00b85a14, 0x00c35c0b, 0x00cb5e0e, 0x00c45707, 0x00c45b0c, 0x00bf5a0a, 0x00bc5c04, 0x00bb5f0a, 0x00b86018, 0x00ad581e, 0x00893c10, 0x00681c00, 0x00803600, 0x009d4c0e, 0x00ba5d18, 0x00c25c12, 0x00c05708, 0x00c3580a, 0x00c3580c, 0x00c1570b, 0x00c35808, 0x00c65a06, 0x00c55803, 0x00be580b, 0x00af5c1d, 0x00894c1f, 0x0047230a, 0x00130000, 0x000c0000, 0x00100000, 0x00300c00, 0x006d390e, 0x00a35c23, 0x00b8601c, 0x00ba570f, 0x00c45c10, 0x00bc5409, 0x00c35f14, 0x00b75c14, 0x00a05517, 0x00733c0c, 0x00300d00, 0x000a0000, 0x00080001, 0x000a0000, 0x00230600, 0x00602b03, 0x009f551b, 0x00bb5c16, 0x00c0580c, 0x00c05910, 0x00b65c1c, 0x008c481b, 0x00512408, 0x00140000, 0x00120000, 0x00200000, 0x00441700, 0x008a4c21, 0x009e5f32, 0x00784729, 0x002b0600, 0x00180000, 0x00100000, 0x00050100, 0x00000303, 0x00000507, 0x0000080a, 0x00010606, 0x00040504, 0x00070401, 0x00080401, 0x00080401, 0x00080405, 0x00050507, 0x00050507, 0x00040406, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00050505, 0x00040404, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00202020, 0x007b7b7b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a0a7ab, 0x0045494c, 0x00030000, 0x000f0000, 0x001a0000, 0x005c280a, 0x00ab5720, 0x00be5812, 0x00c25308, 0x00c85604, 0x00cc5d05, 0x00cc6105, 0x00ca670d, 0x00c06811, 0x00ba6c1b, 0x00a8641c, 0x00985a20, 0x00774518, 0x004b2406, 0x00260c00, 0x000e0000, 0x00080100, 0x00080000, 0x001a0600, 0x004a2300, 0x00864b12, 0x00b46425, 0x00c1631d, 0x00c35c13, 0x00cb5e0e, 0x00c85a01, 0x00cb5d00, 0x00c95e05, 0x00c55c08, 0x00c35c0d, 0x00c45e0f, 0x00c45d08, 0x00c05801, 0x00c85c08, 0x00c15807, 0x00bb5908, 0x00b85b0c, 0x00b4580d, 0x00b8590e, 0x00c05a0c, 0x00c45707, 0x00c95804, 0x00c95804, 0x00c75809, 0x00c3580c, 0x00bf580e, 0x00c05a0e, 0x00c15c09, 0x00ba580b, 0x00b75a20, 0x00914014, 0x00501000, 0x00581e00, 0x0089481b, 0x00a85a20, 0x00b5560c, 0x00bf5808, 0x00be580b, 0x00bc570b, 0x00c0590e, 0x00c25408, 0x00c75002, 0x00cc5406, 0x00c8540c, 0x00c6510c, 0x00cc560e, 0x00c85109, 0x00c95914, 0x00b85a1f, 0x007c3a12, 0x003c1400, 0x00120400, 0x00000105, 0x00000206, 0x00000406, 0x00010200, 0x00000000, 0x00000000, 0x00000400, 0x00000403, 0x00000203, 0x004e4d52, 0x00838389, 0x0020232a, 0x00080100, 0x00210500, 0x00602c08, 0x009e5318, 0x00b85c14, 0x00bf5808, 0x00c55701, 0x00cc5905, 0x00cc5704, 0x00c85508, 0x00be5914, 0x00ac6023, 0x007c4216, 0x003a0e00, 0x00310200, 0x00803808, 0x00b65d1c, 0x00be5909, 0x00c35703, 0x00cb6012, 0x00c1560a, 0x00c4590a, 0x00c05908, 0x00b85909, 0x00b35c14, 0x009e501c, 0x00772d06, 0x00651c00, 0x00762901, 0x00a85318, 0x00b45810, 0x00c15c0c, 0x00c45b0b, 0x00c3580c, 0x00c3540c, 0x00c3580c, 0x00c45809, 0x00c75906, 0x00c75804, 0x00c95804, 0x00c05605, 0x00b8580d, 0x00ae5f1e, 0x00834416, 0x00401500, 0x00110000, 0x000a0000, 0x00100000, 0x00341100, 0x007b4313, 0x00a75c1f, 0x00b85c16, 0x00be5a10, 0x00be580e, 0x00c45c11, 0x00bd5708, 0x00bb5c12, 0x00aa581c, 0x006a3005, 0x00270800, 0x000b0000, 0x000a0200, 0x00080000, 0x00200700, 0x00613516, 0x00974f1c, 0x00b55c18, 0x00bc550a, 0x00be580e, 0x00b0581b, 0x00844012, 0x00411700, 0x00130000, 0x000d0000, 0x001c0500, 0x00461f07, 0x00805033, 0x00926245, 0x0050250c, 0x001d0000, 0x00130100, 0x00040000, 0x00000406, 0x0000060b, 0x0000050a, 0x00000407, 0x00040404, 0x00080401, 0x00090300, 0x00080401, 0x00070403, 0x00040406, 0x00040406, 0x00040406, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00111111, 0x00686868, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0073787d, 0x0016171a, 0x000d0100, 0x00190000, 0x003e0f00, 0x00954f27, 0x00bb581b, 0x00c25108, 0x00c55605, 0x00ca5e08, 0x00c76008, 0x00c3640e, 0x00bc6818, 0x00aa631b, 0x0092571c, 0x00714013, 0x00502908, 0x002b0d00, 0x00150000, 0x000f0000, 0x00080000, 0x000a0000, 0x00200800, 0x00562e07, 0x00905317, 0x00af6019, 0x00bd6014, 0x00c15c10, 0x00c35b10, 0x00c85e10, 0x00c55c05, 0x00c45c04, 0x00c45d08, 0x00c45e0c, 0x00c25c10, 0x00bf590c, 0x00c25904, 0x00c55c04, 0x00c65a06, 0x00c15a08, 0x00bc5e10, 0x00ad560c, 0x009c4804, 0x00a64d0c, 0x00bb5917, 0x00bf560e, 0x00c55708, 0x00c85604, 0x00c75809, 0x00c3580a, 0x00bc540b, 0x00bc570b, 0x00c05b08, 0x00bc590b, 0x00bb5917, 0x00b15c2b, 0x00682d0e, 0x00300000, 0x00522000, 0x00844518, 0x00ad5818, 0x00b8570e, 0x00bb570c, 0x00bc560c, 0x00c05910, 0x00c2580f, 0x00c25206, 0x00c55107, 0x00c4540d, 0x00c5520c, 0x00c85109, 0x00cb5308, 0x00ca5206, 0x00c45610, 0x00af561f, 0x007a3c15, 0x00361403, 0x000c0000, 0x00050000, 0x00030304, 0x00030301, 0x00000000, 0x00000000, 0x00000200, 0x00010300, 0x00000000, 0x00282c2e, 0x0028292d, 0x0008080a, 0x00150500, 0x004c1d02, 0x0092491c, 0x00b95816, 0x00c6590a, 0x00c45705, 0x00c85a05, 0x00cb5604, 0x00c85407, 0x00c75812, 0x00b05517, 0x00884b1b, 0x00411700, 0x00220000, 0x00562408, 0x009e5319, 0x00ba5c10, 0x00c05805, 0x00c25602, 0x00c3580c, 0x00c2580d, 0x00c15809, 0x00bc5a0d, 0x00af5a17, 0x00924810, 0x00642300, 0x00500f00, 0x00752b08, 0x00ac5829, 0x00be611d, 0x00be5909, 0x00bc5403, 0x00c05605, 0x00c5580b, 0x00c5580c, 0x00c4570a, 0x00c55708, 0x00c75805, 0x00c45402, 0x00c85808, 0x00c45908, 0x00bc5608, 0x00bb5f16, 0x00ae591b, 0x00864617, 0x00391700, 0x00140400, 0x000c0000, 0x00180000, 0x004a2000, 0x00864718, 0x00b46023, 0x00b85611, 0x00c05910, 0x00c0560c, 0x00c15405, 0x00c0580d, 0x00b85916, 0x009f531c, 0x00643211, 0x001e0100, 0x000b0000, 0x00090301, 0x00060000, 0x00210c00, 0x00643410, 0x00a35925, 0x00b85916, 0x00bd560c, 0x00be5b13, 0x00a75215, 0x007e4118, 0x00391200, 0x00130000, 0x000f0000, 0x00170000, 0x0041200c, 0x007a5036, 0x00785037, 0x00290c00, 0x00130100, 0x00040000, 0x00020609, 0x0000080c, 0x00000308, 0x00000407, 0x00040404, 0x00070300, 0x00080200, 0x00070300, 0x00040402, 0x00030405, 0x00010405, 0x00030404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00040404, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00090909, 0x00585858, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009ca0a2, 0x003b3f44, 0x00060302, 0x00150000, 0x00280000, 0x00783711, 0x00b05826, 0x00c45616, 0x00c55309, 0x00c55c0b, 0x00c0620d, 0x00b86410, 0x00b0681b, 0x00965719, 0x00713c0e, 0x00471d00, 0x00280800, 0x00140000, 0x000d0000, 0x000d0000, 0x00140000, 0x00200800, 0x003e1c02, 0x006b370c, 0x0098541a, 0x00bb6820, 0x00bd6213, 0x00bd5c0b, 0x00c05f10, 0x00c06114, 0x00bc5f12, 0x00bd5f0f, 0x00ba5c0a, 0x00bc5c0b, 0x00bf5d0e, 0x00bf5b10, 0x00c05a0c, 0x00c55b08, 0x00c95c07, 0x00c85b06, 0x00c05704, 0x00c06214, 0x00b45c14, 0x008d3b00, 0x00863200, 0x00a34a13, 0x00b8591e, 0x00bb570f, 0x00bd5507, 0x00c25708, 0x00c55809, 0x00c3570d, 0x00c0560a, 0x00bf5806, 0x00bf5806, 0x00c55a0e, 0x00b45718, 0x00905027, 0x004c1c00, 0x002a0000, 0x004b1700, 0x008d4514, 0x00ae5618, 0x00b85712, 0x00bc550c, 0x00bc550c, 0x00bf560e, 0x00c0540c, 0x00c1530a, 0x00c4540a, 0x00c65408, 0x00c45108, 0x00cb580b, 0x00cc5404, 0x00c85306, 0x00c45a16, 0x00a8531c, 0x006c310d, 0x00361000, 0x00140000, 0x00080000, 0x00040304, 0x00020304, 0x00000000, 0x00000000, 0x00000100, 0x00000000, 0x00040807, 0x00020100, 0x000c0000, 0x00320f00, 0x00803d18, 0x00b85a23, 0x00c3520c, 0x00cc5808, 0x00cb5908, 0x00c05203, 0x00c85a0d, 0x00bc5410, 0x00b4581d, 0x00904818, 0x00471e00, 0x001d0000, 0x00300200, 0x0087471e, 0x00ac5c1a, 0x00b85b0c, 0x00c05c0c, 0x00c05908, 0x00be5609, 0x00c0580d, 0x00be5a10, 0x00ad5413, 0x008c4414, 0x00581d00, 0x003c0800, 0x006c2d0e, 0x00ab5624, 0x00b95819, 0x00b9550b, 0x00c05a0b, 0x00c25a0f, 0x00c05509, 0x00c35606, 0x00c75808, 0x00c85707, 0x00c45202, 0x00c8590a, 0x00c05504, 0x00be5706, 0x00c05a0c, 0x00bc580f, 0x00bc5810, 0x00bc580f, 0x00b15a18, 0x007d4410, 0x003c1900, 0x00170200, 0x000e0000, 0x00250700, 0x00582509, 0x009b4e20, 0x00b7571a, 0x00c05410, 0x00c3530c, 0x00c75812, 0x00c25a15, 0x00b75614, 0x00b45f20, 0x009b5219, 0x00592400, 0x00170000, 0x000c0000, 0x00040403, 0x00040000, 0x002f1301, 0x00703a1b, 0x00a45321, 0x00bb5a19, 0x00bd5a0d, 0x00b85a0e, 0x00a8581c, 0x007d3d16, 0x00370d00, 0x00140000, 0x00140000, 0x00160000, 0x00452410, 0x00785541, 0x00432a1a, 0x00150700, 0x00040000, 0x00000204, 0x0000060b, 0x00000207, 0x00020306, 0x00040203, 0x00060200, 0x00080100, 0x00050200, 0x00030301, 0x00010405, 0x00010405, 0x00020403, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00040404, 0x00030303, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x004c4c4c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0075797c, 0x00101216, 0x00050000, 0x001b0000, 0x004b1400, 0x00a55324, 0x00bc5719, 0x00c75510, 0x00c25308, 0x00c06114, 0x00b5681c, 0x009b5c18, 0x0076430a, 0x004b1c00, 0x002b0300, 0x001d0000, 0x00180000, 0x001b0200, 0x00240c00, 0x00311300, 0x00411c00, 0x00602f0b, 0x00884c1f, 0x00ab5e20, 0x00b86118, 0x00c06012, 0x00c35e0c, 0x00c45f0c, 0x00c15f0c, 0x00bc5f10, 0x00b86013, 0x00a75106, 0x00a65208, 0x00b35c14, 0x00bc6319, 0x00bc5c11, 0x00bf590c, 0x00c85b0b, 0x00c75805, 0x00c65805, 0x00c45a08, 0x00bc5a0b, 0x00b85d17, 0x00a45118, 0x007b2b00, 0x00722300, 0x00974514, 0x00b05a1c, 0x00b85c14, 0x00bd580a, 0x00c05606, 0x00c7580d, 0x00c6570b, 0x00c25506, 0x00c35606, 0x00c55706, 0x00b8540c, 0x00a95d27, 0x007d441d, 0x00320600, 0x00270000, 0x004f1800, 0x008c4419, 0x00b1581e, 0x00bd5916, 0x00bb530c, 0x00bc540c, 0x00c05810, 0x00c0560c, 0x00c45507, 0x00c35304, 0x00c45509, 0x00c05004, 0x00ca5506, 0x00cc5708, 0x00c55308, 0x00c05916, 0x00a34f1a, 0x006d3009, 0x002b0600, 0x000f0000, 0x00030000, 0x00000307, 0x00000104, 0x00000000, 0x00020200, 0x00020000, 0x00000100, 0x000d0400, 0x00240400, 0x006c3311, 0x00ad5627, 0x00bf5415, 0x00c95208, 0x00cc5605, 0x00ca5503, 0x00c35607, 0x00bf5a14, 0x00b55c23, 0x00954e21, 0x00572402, 0x00180000, 0x00170000, 0x00632903, 0x00a45824, 0x00b15914, 0x00bc5c0f, 0x00c05a0b, 0x00c05809, 0x00c15c0e, 0x00b85a12, 0x00aa581a, 0x00843d0d, 0x00491100, 0x00340100, 0x005e2708, 0x009b5628, 0x00bb5f1e, 0x00bb5408, 0x00be5609, 0x00c1590c, 0x00c45a10, 0x00c3580a, 0x00c45504, 0x00c45501, 0x00c55605, 0x00c45607, 0x00c35808, 0x00c05809, 0x00bc5909, 0x00bb580c, 0x00bb5811, 0x00ba5712, 0x00be5810, 0x00ba5d19, 0x00aa6023, 0x007d4515, 0x00462003, 0x001c0000, 0x00160000, 0x002c0400, 0x006b2f0d, 0x00a45423, 0x00ba5818, 0x00c45710, 0x00c3540d, 0x00c2550f, 0x00bc5814, 0x00b85a14, 0x00b15914, 0x00995018, 0x004c1c00, 0x00130000, 0x00040000, 0x00010000, 0x000e0000, 0x00371302, 0x007e3d1b, 0x00ac5821, 0x00b7580e, 0x00bb5809, 0x00b95b14, 0x00a8541d, 0x007b391b, 0x00401202, 0x00160000, 0x00100000, 0x00180000, 0x00442818, 0x00503c30, 0x0020130c, 0x00090502, 0x00000000, 0x00000406, 0x00000305, 0x00030105, 0x00040102, 0x00050000, 0x00050000, 0x00040301, 0x00030303, 0x00000403, 0x00000404, 0x00020403, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00030303, 0x00020202, 0x00030303, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00484848, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a0a2a1, 0x004a4d4e, 0x00000004, 0x00090000, 0x00300a00, 0x007d3c17, 0x00b5571d, 0x00c65810, 0x00c45608, 0x00bf5c0f, 0x00b26320, 0x008c511a, 0x00582e06, 0x002b0b00, 0x00170000, 0x00200000, 0x002b0500, 0x00401400, 0x00512100, 0x006a3401, 0x00884a0f, 0x00a05819, 0x00b16020, 0x00bc631e, 0x00c46213, 0x00c35e0c, 0x00bf590c, 0x00c25c0c, 0x00c45d0a, 0x00c05a03, 0x00bc5904, 0x00bc6110, 0x00994802, 0x00853900, 0x00904608, 0x00ac601c, 0x00b75f13, 0x00ba5808, 0x00c45908, 0x00c55706, 0x00c35606, 0x00c85d0e, 0x00bb5304, 0x00b85810, 0x00bc632c, 0x00904115, 0x00601b00, 0x00612100, 0x00894712, 0x00a45b18, 0x00b45c10, 0x00b95404, 0x00c55509, 0x00c8540a, 0x00c55108, 0x00c65608, 0x00c05301, 0x00c15b0a, 0x00b95b14, 0x00a1541c, 0x00642d10, 0x002a0400, 0x00200000, 0x004d1d0a, 0x008f431c, 0x00b4561e, 0x00be5410, 0x00c05209, 0x00c0580f, 0x00bd560b, 0x00c05504, 0x00c05402, 0x00c45808, 0x00b94e02, 0x00c05308, 0x00c5560a, 0x00c45104, 0x00cc590c, 0x00c35b16, 0x00a04a14, 0x00592200, 0x00240600, 0x00050000, 0x00000008, 0x00000106, 0x00000001, 0x00040100, 0x00060100, 0x00050000, 0x00170000, 0x00561c00, 0x00a45224, 0x00be5820, 0x00c0510b, 0x00cb580c, 0x00c85603, 0x00c45200, 0x00c75d0f, 0x00ae5514, 0x00985424, 0x005b2e10, 0x00200300, 0x00100000, 0x00331000, 0x00955021, 0x00b45c1b, 0x00b65812, 0x00bf590f, 0x00c55507, 0x00c35405, 0x00bf5d0e, 0x00a55615, 0x00753f19, 0x00441904, 0x00230000, 0x00491500, 0x0098511e, 0x00b35e18, 0x00b35402, 0x00c35d0b, 0x00c45d12, 0x00c0560c, 0x00c15304, 0x00c65706, 0x00c65704, 0x00c25403, 0x00c05606, 0x00c15c0c, 0x00bb5508, 0x00bc5808, 0x00c05c0c, 0x00c05a0e, 0x00b95811, 0x00b75b1a, 0x00ac551e, 0x009c4a15, 0x00aa5621, 0x00ae5e2c, 0x008c4621, 0x00581e04, 0x002c0100, 0x001d0000, 0x00371200, 0x006e3b16, 0x00a4571c, 0x00b95810, 0x00c05001, 0x00c55001, 0x00c5570e, 0x00bc550e, 0x00b85810, 0x00b36024, 0x00874720, 0x00390f00, 0x00140000, 0x00090000, 0x00050000, 0x00180200, 0x004f1f08, 0x008c481c, 0x00b05818, 0x00bc5a10, 0x00c25b11, 0x00ba5613, 0x00b25824, 0x0086401b, 0x003a0f00, 0x001c0200, 0x00100000, 0x00140200, 0x0034261e, 0x001f140e, 0x000c0604, 0x00040100, 0x00020001, 0x00020003, 0x00040004, 0x00040004, 0x00050002, 0x00040102, 0x00020202, 0x00010302, 0x00000402, 0x00000402, 0x00010302, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00010101, 0x00030303, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00484848, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0080807e, 0x0020201e, 0x00020000, 0x00140000, 0x00471700, 0x00a35626, 0x00bc5414, 0x00c6550d, 0x00bf5c14, 0x00b35f1e, 0x00884914, 0x00471700, 0x00230000, 0x00280500, 0x003c1400, 0x0058290e, 0x00804922, 0x009d5f2c, 0x00a86325, 0x00b1641f, 0x00b86518, 0x00b85f0f, 0x00bf600e, 0x00c15d08, 0x00c15b03, 0x00c45f09, 0x00c15d13, 0x00bd5a12, 0x00c15b0c, 0x00c15c08, 0x00c05c05, 0x00b95f0c, 0x00a35410, 0x00652200, 0x005d2200, 0x008d4d1b, 0x00ae5f1e, 0x00b65a10, 0x00c05a09, 0x00c55905, 0x00c55708, 0x00c45808, 0x00c45a0a, 0x00bc580e, 0x00b45719, 0x00ac5828, 0x00823b18, 0x00480c00, 0x00572000, 0x00884b14, 0x00ab5e1b, 0x00b4570c, 0x00c2560c, 0x00c75409, 0x00c25006, 0x00c55509, 0x00c45506, 0x00c35606, 0x00c05306, 0x00b85818, 0x00914c24, 0x00431500, 0x001a0000, 0x001c0000, 0x005e250c, 0x009c4c20, 0x00b85618, 0x00bd500c, 0x00bd540e, 0x00bb5209, 0x00bf5404, 0x00c25504, 0x00c05405, 0x00c05509, 0x00c1550d, 0x00c1530a, 0x00c45205, 0x00c95607, 0x00c8580a, 0x00bc5814, 0x00904415, 0x00481700, 0x000e0000, 0x00010005, 0x00000204, 0x00000000, 0x00010000, 0x00070000, 0x00110000, 0x002e0600, 0x0095491b, 0x00bc581d, 0x00c0520c, 0x00ca580c, 0x00c75708, 0x00c45506, 0x00c45808, 0x00b95a12, 0x009f5521, 0x006b3715, 0x00220400, 0x00100000, 0x00200300, 0x00653518, 0x00ad5c23, 0x00bb5810, 0x00be5610, 0x00be520a, 0x00ca570a, 0x00c2570b, 0x00af5814, 0x008a4c1a, 0x00401e0a, 0x00150000, 0x002c0600, 0x00753c1c, 0x00ab5918, 0x00bc5c08, 0x00c05a06, 0x00be5705, 0x00bb5408, 0x00c1570c, 0x00c65809, 0x00c75505, 0x00c65406, 0x00c45608, 0x00c05808, 0x00bc5705, 0x00be5c09, 0x00b95608, 0x00bc5911, 0x00b95a18, 0x00ab541a, 0x009c4f1e, 0x00783812, 0x00531000, 0x00984110, 0x00b4561f, 0x00b65a28, 0x009f4e24, 0x0062280d, 0x002e0400, 0x001c0000, 0x003c1800, 0x00844819, 0x00ac5817, 0x00c3580c, 0x00ca5504, 0x00c55508, 0x00c0540a, 0x00bc5810, 0x00b45818, 0x00ac5c27, 0x0072350e, 0x00320d00, 0x00100000, 0x00050000, 0x00080000, 0x001e0000, 0x005d2b0a, 0x009c521c, 0x00b45a17, 0x00bc540c, 0x00c4560f, 0x00c05412, 0x00b45822, 0x00904f29, 0x00441800, 0x00270500, 0x00110000, 0x000e0000, 0x00100801, 0x00040000, 0x00050404, 0x00000001, 0x00020204, 0x00040001, 0x00040001, 0x00040004, 0x00010004, 0x00010204, 0x00000302, 0x00000402, 0x00000302, 0x00010302, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00020202, 0x00010101, 0x00030303, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00494949, 0x00313131, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009b9c9f, 0x005a5956, 0x00040000, 0x000a0300, 0x00220800, 0x0074360c, 0x00b45a20, 0x00c65811, 0x00bf5311, 0x00ac5c2a, 0x007f421a, 0x003c0a00, 0x00280000, 0x004a1800, 0x00763b14, 0x00a15726, 0x00b76529, 0x00b8621a, 0x00bc6214, 0x00bc6110, 0x00bc600c, 0x00be600c, 0x00c0620d, 0x00be6309, 0x00bc6106, 0x00c06208, 0x00bc5f0c, 0x00b85c19, 0x00b75a1c, 0x00ba5816, 0x00b8550b, 0x00b85704, 0x00b85e0c, 0x00ac5f1a, 0x00763a06, 0x002e0300, 0x00451800, 0x00904d22, 0x00b05d20, 0x00bc5e0c, 0x00c05700, 0x00c65402, 0x00c85405, 0x00bf5807, 0x00bd5a0d, 0x00b8540c, 0x00bc5c1e, 0x00ad592b, 0x006f2a04, 0x00380200, 0x004e1c00, 0x00894814, 0x00ae5d1f, 0x00b6550e, 0x00c3580c, 0x00c05407, 0x00c05205, 0x00c6550c, 0x00c34f06, 0x00cc540b, 0x00c35613, 0x00ad531c, 0x007a3a13, 0x002e0e00, 0x00100000, 0x00290800, 0x00662e11, 0x00ac5528, 0x00bc541a, 0x00c05115, 0x00c1500f, 0x00c3540b, 0x00c05105, 0x00c05407, 0x00c15408, 0x00c3520c, 0x00c3510c, 0x00c2540c, 0x00c2570b, 0x00c35808, 0x00c15a10, 0x00b85a20, 0x007e3811, 0x00300e01, 0x00080000, 0x00040000, 0x00030200, 0x00000006, 0x000a0000, 0x00200000, 0x00753811, 0x00ad5516, 0x00c3590b, 0x00c85300, 0x00cc5805, 0x00c65407, 0x00c0560d, 0x00b65410, 0x00ac5d27, 0x00703b19, 0x00300c00, 0x00140000, 0x00190000, 0x00421300, 0x009e5b28, 0x00b05712, 0x00c1590c, 0x00c45309, 0x00c9530b, 0x00cb570e, 0x00b95515, 0x00985426, 0x0050260b, 0x00130000, 0x00120000, 0x00441c01, 0x00945423, 0x00b45912, 0x00bc5404, 0x00c2580f, 0x00c0550e, 0x00bf570a, 0x00bc5408, 0x00c1530a, 0x00c5540c, 0x00c4540c, 0x00c35408, 0x00c25600, 0x00c05600, 0x00c15802, 0x00be580c, 0x00b4571b, 0x00a65627, 0x00874424, 0x00481400, 0x001e0000, 0x002f0200, 0x00a0501e, 0x00b45111, 0x00bc5411, 0x00bb591c, 0x00a45425, 0x006f3313, 0x00360e00, 0x00200000, 0x00501d01, 0x00914d22, 0x00b85b1d, 0x00c2560e, 0x00c45406, 0x00c25307, 0x00c05910, 0x00b95611, 0x00b55411, 0x00ad5c26, 0x00582909, 0x00200700, 0x00080000, 0x00060000, 0x000d0000, 0x00280800, 0x006a3609, 0x00a75d21, 0x00b65812, 0x00c0520b, 0x00c64f07, 0x00c3530f, 0x00b45c20, 0x00a05927, 0x00662b07, 0x002e0400, 0x00140000, 0x000b0400, 0x00000000, 0x00000406, 0x00000507, 0x00000201, 0x00020100, 0x00040000, 0x00020007, 0x00000008, 0x00000204, 0x00000301, 0x00000200, 0x00010100, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00020202, 0x00010101, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004b4b4b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00909296, 0x003b3734, 0x00070000, 0x000f0000, 0x003c1800, 0x009c5422, 0x00b85818, 0x00c0510b, 0x00bf591a, 0x008c4317, 0x00420800, 0x00430b00, 0x007f4418, 0x00a6622f, 0x00b26429, 0x00bd621c, 0x00bf5d0e, 0x00c15d05, 0x00c46005, 0x00c46005, 0x00c25e06, 0x00bd5c08, 0x00bb5e0d, 0x00b66111, 0x00b46214, 0x00aa5b10, 0x00b26320, 0x00ac5d27, 0x0094420d, 0x00852a00, 0x00963800, 0x00b15202, 0x00b95e0f, 0x00af5f1a, 0x0080420f, 0x003f1701, 0x00200000, 0x00481300, 0x00935025, 0x00a75817, 0x00be6316, 0x00c4580c, 0x00c8580c, 0x00ba5404, 0x00c05a0b, 0x00c45a0c, 0x00b9510b, 0x00b2541a, 0x009d5022, 0x00592300, 0x002d0000, 0x00461300, 0x008a491c, 0x00ad5a20, 0x00b1510c, 0x00bd580a, 0x00c05405, 0x00c05008, 0x00c8540c, 0x00ca530b, 0x00c4500c, 0x00bc5718, 0x00a15320, 0x005b3010, 0x001c0200, 0x00140000, 0x00401802, 0x00843e19, 0x00b45827, 0x00b74d14, 0x00c35212, 0x00c0500a, 0x00c3550a, 0x00c05408, 0x00c05308, 0x00c4500b, 0x00c4500c, 0x00c0530e, 0x00be560b, 0x00c25807, 0x00c35808, 0x00bc500f, 0x00ac5423, 0x005f2c14, 0x00180000, 0x000c0000, 0x00050000, 0x00030001, 0x00100000, 0x004e1b00, 0x00a05420, 0x00b85911, 0x00cb5d08, 0x00cc5601, 0x00c44f00, 0x00c7580d, 0x00b95514, 0x00b25f26, 0x00804318, 0x003b1500, 0x00160000, 0x00120000, 0x00280300, 0x007a3b0d, 0x00af5d1c, 0x00bc5b12, 0x00c15608, 0x00c45005, 0x00c45006, 0x00c4540d, 0x00b2571e, 0x00723b1a, 0x002c0e00, 0x000c0000, 0x00190400, 0x00592800, 0x00a4571c, 0x00bf5b11, 0x00c15206, 0x00c15410, 0x00be5410, 0x00bd550a, 0x00c3580c, 0x00c4540c, 0x00c2510b, 0x00c2520c, 0x00c1530a, 0x00c15403, 0x00c35804, 0x00bb5405, 0x00b75b18, 0x009b4f22, 0x00682d11, 0x002c0300, 0x00190000, 0x00120000, 0x002f0b00, 0x00a85a26, 0x00be5812, 0x00c1530a, 0x00bd530a, 0x00b9591b, 0x00aa5a28, 0x00773c1c, 0x00441400, 0x00300000, 0x00632707, 0x00a15120, 0x00b65618, 0x00bc530b, 0x00c5580c, 0x00bc540c, 0x00bd540c, 0x00c3570d, 0x00b45515, 0x00905026, 0x003d1600, 0x00180300, 0x00080000, 0x000b0200, 0x000f0000, 0x003b1900, 0x007e4817, 0x00b05b1c, 0x00bc510c, 0x00cc540b, 0x00c74e05, 0x00bc540c, 0x00b05614, 0x00af5d2a, 0x008a4a23, 0x00421d00, 0x000e0000, 0x00080000, 0x00030301, 0x00000303, 0x00000606, 0x00020100, 0x00040000, 0x00010008, 0x0000000b, 0x00000305, 0x00000301, 0x00020100, 0x00040000, 0x00020100, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00020202, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004d4d4d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x006d6e71, 0x00181210, 0x000b0000, 0x001b0100, 0x00572806, 0x00ac5d28, 0x00bb5a19, 0x00bd5817, 0x00a24204, 0x00550600, 0x00732900, 0x00a9591c, 0x00b6611c, 0x00b45c10, 0x00c16617, 0x00c26513, 0x00bc5e09, 0x00be5e06, 0x00c05f06, 0x00c45f07, 0x00c35e0c, 0x00bc5f14, 0x00b5601e, 0x00ac602a, 0x00a66333, 0x008c4d26, 0x00632802, 0x00440600, 0x005e1800, 0x009a480f, 0x00b85e1b, 0x00ba5a0e, 0x00ba5a0e, 0x00b75e17, 0x009b5019, 0x00562707, 0x001c0000, 0x001d0000, 0x00380d00, 0x008b5433, 0x00a05c2c, 0x00af581c, 0x00bb5c14, 0x00bf580b, 0x00c45908, 0x00c15206, 0x00c0540b, 0x00c55e1b, 0x00ae581d, 0x00854618, 0x00481800, 0x001e0000, 0x00441900, 0x0090502a, 0x00a6541c, 0x00ba580d, 0x00c05605, 0x00be5408, 0x00c2560c, 0x00be4e08, 0x00be4f0b, 0x00bd5414, 0x00b15820, 0x0085481b, 0x00431a00, 0x00170000, 0x001b0000, 0x00511f00, 0x00995024, 0x00b4541b, 0x00c35715, 0x00bc4f0a, 0x00bf530b, 0x00be5408, 0x00c05207, 0x00c54f08, 0x00c54f0a, 0x00c0500a, 0x00bf5406, 0x00c25504, 0x00c35405, 0x00c5540e, 0x00bf5920, 0x0090481e, 0x00431600, 0x00120000, 0x000c0000, 0x00100000, 0x00280300, 0x0089471c, 0x00b45c1f, 0x00c05b10, 0x00c55706, 0x00cb5605, 0x00c85508, 0x00bd5512, 0x00b25920, 0x00924e20, 0x004a1c00, 0x00140000, 0x000e0000, 0x001c0000, 0x004e1f05, 0x00a85c27, 0x00b85714, 0x00bf5712, 0x00bf520c, 0x00c0540b, 0x00c0550b, 0x00bc560f, 0x00a7541d, 0x004d2006, 0x00120000, 0x000c0000, 0x002a0c00, 0x007c3808, 0x00b65715, 0x00c75810, 0x00c35307, 0x00bf540c, 0x00bd550f, 0x00bc550c, 0x00c3570f, 0x00c45208, 0x00c35007, 0x00c45610, 0x00c0550e, 0x00bd520b, 0x00bc5713, 0x00b4581d, 0x009a5022, 0x0056260b, 0x001c0000, 0x000c0000, 0x000c0100, 0x000d0000, 0x004a2206, 0x00aa5923, 0x00bd5512, 0x00c45710, 0x00c3540c, 0x00bf5009, 0x00be5915, 0x00b0571e, 0x00904618, 0x00581c00, 0x003e0500, 0x006f2d07, 0x00a65929, 0x00b4581c, 0x00bc5411, 0x00c0540d, 0x00bf5008, 0x00c4540a, 0x00ba5510, 0x00b46028, 0x00783b14, 0x002d0b00, 0x000e0000, 0x00080003, 0x00040000, 0x00120400, 0x004c2705, 0x009e541e, 0x00bc5817, 0x00c45310, 0x00c34f08, 0x00c15408, 0x00bd560c, 0x00b85414, 0x00b56028, 0x008e4f21, 0x00522704, 0x00230500, 0x000c0000, 0x00000000, 0x00000608, 0x00030000, 0x00040000, 0x00010007, 0x0000000a, 0x00000307, 0x00000303, 0x00040000, 0x00060000, 0x00020100, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00070707, 0x00545454, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00313132, 0x00545456, 0x00060000, 0x00100000, 0x00381300, 0x007f441c, 0x00b66025, 0x00bb5714, 0x00b04c0b, 0x00812400, 0x00a85413, 0x00b15e18, 0x00bf6115, 0x00c2600d, 0x00c8640d, 0x00bc5c04, 0x00b05701, 0x00c06a19, 0x00bc6517, 0x00b76017, 0x00b45d17, 0x00b4601f, 0x00ab6028, 0x00904c1c, 0x00662704, 0x00460b00, 0x00310000, 0x00450e00, 0x00723710, 0x009a5725, 0x00aa5a1d, 0x00b45a15, 0x00bf5c12, 0x00bc580e, 0x00be5d16, 0x00aa581a, 0x00773e14, 0x00280300, 0x00100000, 0x00180300, 0x002e0a00, 0x0079472b, 0x00a06031, 0x00aa591b, 0x00b8540b, 0x00c6590a, 0x00c35408, 0x00be5208, 0x00c05a11, 0x00b05714, 0x00a45922, 0x00773d15, 0x002b0400, 0x00240100, 0x003d1000, 0x008c4b25, 0x00b1591c, 0x00b55308, 0x00bc580d, 0x00bc570c, 0x00be530c, 0x00c15610, 0x00bc520e, 0x00b65717, 0x00a4571e, 0x00773e11, 0x00341100, 0x00160000, 0x00300900, 0x00713713, 0x00b15c25, 0x00ba5414, 0x00b9510c, 0x00bc530a, 0x00bd5307, 0x00c05207, 0x00c44f0a, 0x00c44e09, 0x00c15008, 0x00c05205, 0x00c05402, 0x00c35403, 0x00c95409, 0x00bc4f0e, 0x00b45b24, 0x007c3d16, 0x00240800, 0x000e0000, 0x001d0000, 0x00622b0c, 0x00af5c25, 0x00b95610, 0x00c1570b, 0x00c15304, 0x00c45207, 0x00c55a14, 0x00b15418, 0x009c5221, 0x00582605, 0x00210400, 0x000c0000, 0x00130100, 0x00310c00, 0x00814524, 0x00b45c22, 0x00bb510f, 0x00bd5110, 0x00be530f, 0x00c0580f, 0x00bb570d, 0x00b65812, 0x00934917, 0x003b1500, 0x00110000, 0x00100000, 0x00411800, 0x009b4813, 0x00bf540e, 0x00c6530c, 0x00c45108, 0x00c0550b, 0x00be570d, 0x00be550d, 0x00c0540c, 0x00c45207, 0x00c4540a, 0x00c0540d, 0x00ba5512, 0x00b65417, 0x00b05621, 0x0091451f, 0x00511a00, 0x001d0200, 0x00060000, 0x00030300, 0x00040000, 0x00190400, 0x006c3a19, 0x00b25922, 0x00bb4e0b, 0x00bc500b, 0x00c2540c, 0x00c25003, 0x00bf5004, 0x00bd550f, 0x00b5581b, 0x00964b19, 0x006e2c02, 0x00561400, 0x0081380c, 0x00b35c24, 0x00b85315, 0x00bd4f08, 0x00c8550c, 0x00bf5005, 0x00c0570f, 0x00b45411, 0x00a85824, 0x00562307, 0x00200400, 0x00060000, 0x00000002, 0x00040100, 0x00250d00, 0x00773910, 0x00b55c24, 0x00b74f12, 0x00c0500c, 0x00c45609, 0x00c25506, 0x00bf5007, 0x00bc5512, 0x00b45d21, 0x0094501f, 0x00501c00, 0x00180000, 0x00080000, 0x00000001, 0x00040000, 0x00050000, 0x00010004, 0x00000108, 0x00000307, 0x00000204, 0x00060000, 0x00070000, 0x00040000, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00101010, 0x00606060, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000c0c0c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00959597, 0x003c3a3b, 0x00040000, 0x00160000, 0x00451500, 0x00944c1c, 0x00ba5917, 0x00be540b, 0x00b8530d, 0x00b85810, 0x00b86013, 0x00b96211, 0x00be5d0a, 0x00c25e09, 0x00bf5e0a, 0x00bc610e, 0x00b96618, 0x00aa5d18, 0x00a85e24, 0x00a46131, 0x008c5128, 0x00602e0c, 0x003d1000, 0x00300600, 0x002f0100, 0x00300000, 0x005f2200, 0x008a4813, 0x00a45e20, 0x00ab5e1b, 0x00b46018, 0x00bb5f14, 0x00bc580e, 0x00be570e, 0x00c05810, 0x00b85c1c, 0x00874410, 0x00481f00, 0x000a0000, 0x00040000, 0x00120100, 0x002d0e00, 0x00704520, 0x009c5b27, 0x00b85916, 0x00bf5408, 0x00c1570c, 0x00bb540d, 0x00b1540f, 0x00b45c18, 0x00b55c1c, 0x00974814, 0x00693114, 0x001d0000, 0x001c0000, 0x00411b08, 0x008d4b20, 0x00b05b20, 0x00b35410, 0x00b7530b, 0x00bf560e, 0x00be550d, 0x00b85108, 0x00bb5811, 0x00b45c18, 0x009c531b, 0x005d2c09, 0x00270200, 0x00220000, 0x004a1900, 0x009f5224, 0x00b15416, 0x00b7520c, 0x00be570c, 0x00bc5408, 0x00c05108, 0x00c3500b, 0x00c34e0a, 0x00c0500a, 0x00c05207, 0x00c05304, 0x00c25204, 0x00cc5408, 0x00c54f08, 0x00c05818, 0x009d5020, 0x004c2910, 0x00190000, 0x003e0b00, 0x009c5124, 0x00b85814, 0x00c6590a, 0x00c45406, 0x00c7570b, 0x00c0510a, 0x00b55314, 0x00a55524, 0x006c3410, 0x00290900, 0x000e0000, 0x000d0000, 0x001a0300, 0x00572709, 0x00a45b2d, 0x00b45214, 0x00c25310, 0x00bf5312, 0x00be5412, 0x00bc530a, 0x00b6530b, 0x00b2591a, 0x007d390e, 0x00311002, 0x00110000, 0x001f0300, 0x005c2a09, 0x00af5518, 0x00c15209, 0x00c24f08, 0x00c3520a, 0x00c1550d, 0x00bf540c, 0x00c1550c, 0x00c05308, 0x00c4570c, 0x00c0550b, 0x00b55109, 0x00b25817, 0x00a85621, 0x008a4721, 0x00511c07, 0x001e0000, 0x00080000, 0x00090a0c, 0x00030400, 0x00080000, 0x00270500, 0x008b4c28, 0x00b55218, 0x00c4540d, 0x00c1530c, 0x00be510b, 0x00c4550c, 0x00c3550a, 0x00bd5206, 0x00b95208, 0x00b45413, 0x00af571b, 0x00833100, 0x00752400, 0x00993f07, 0x00b75214, 0x00c65410, 0x00c45008, 0x00c0510a, 0x00bc540c, 0x00ba5108, 0x00b85818, 0x0090471b, 0x00421300, 0x000f0000, 0x00020003, 0x00010100, 0x00100000, 0x00461900, 0x00944c21, 0x00b3551e, 0x00bc5311, 0x00be540b, 0x00c15304, 0x00c85508, 0x00c9570a, 0x00be550c, 0x00b3581a, 0x00883f13, 0x003e0f00, 0x000d0000, 0x00040001, 0x00050000, 0x00050000, 0x00010002, 0x00000006, 0x00000308, 0x00000205, 0x00060000, 0x00080000, 0x00030000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00181818, 0x006f6f6f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00121213, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00747472, 0x00252221, 0x00080000, 0x001c0200, 0x00632806, 0x00b46029, 0x00c25911, 0x00c45406, 0x00bc5206, 0x00c05e11, 0x00bc600d, 0x00ba600b, 0x00bd5e0c, 0x00c06316, 0x00b55f16, 0x00af621f, 0x00a8672c, 0x00874e1c, 0x006f3915, 0x004a1b00, 0x002c0700, 0x00250500, 0x001e0000, 0x001d0000, 0x00431400, 0x00773c18, 0x00a05820, 0x00a95814, 0x00b96218, 0x00bd6415, 0x00b6580c, 0x00b7570b, 0x00c15c11, 0x00c25910, 0x00bc5107, 0x00bf5d18, 0x00a4561a, 0x005c2a01, 0x00160800, 0x00000000, 0x00060000, 0x000e0000, 0x00280b00, 0x006a3811, 0x00a8571f, 0x00b85817, 0x00ba5712, 0x00bc5a15, 0x00b65b16, 0x00b15611, 0x00b85510, 0x00b85b1f, 0x008d481d, 0x004e1d06, 0x00180000, 0x001c0200, 0x00471700, 0x00904e24, 0x00b05c25, 0x00b45515, 0x00b9530d, 0x00bb5209, 0x00bb5308, 0x00ba5309, 0x00b7540c, 0x00ac581b, 0x0085451e, 0x004c1d05, 0x00200000, 0x00300100, 0x007e3914, 0x00ae5721, 0x00b65410, 0x00bc5409, 0x00bc5408, 0x00be510b, 0x00c1500e, 0x00c04f0d, 0x00c0500c, 0x00be520a, 0x00be5307, 0x00c05105, 0x00cc5408, 0x00c85109, 0x00c15514, 0x00a4521d, 0x005b3015, 0x00280400, 0x0076340c, 0x00b45c23, 0x00be560b, 0x00c65403, 0x00ca570a, 0x00c2520c, 0x00bb5411, 0x00ae5720, 0x0081431c, 0x00381000, 0x00100000, 0x000a0000, 0x00100000, 0x00341200, 0x00894c20, 0x00b05b23, 0x00b85011, 0x00c35210, 0x00c05413, 0x00be5410, 0x00b95008, 0x00b95814, 0x00ae5d27, 0x00682c08, 0x00260700, 0x00130000, 0x003d1400, 0x007c3c14, 0x00b95a1a, 0x00c2530a, 0x00c05009, 0x00c2540d, 0x00c0530c, 0x00bd5109, 0x00c35408, 0x00c05004, 0x00c0540c, 0x00b9540f, 0x00b25815, 0x00aa5d22, 0x0083461c, 0x004a1b00, 0x00220000, 0x00150000, 0x000c0407, 0x001f1d20, 0x000f0c08, 0x00160400, 0x003b0a00, 0x00a3562e, 0x00b64e11, 0x00ca560f, 0x00c55510, 0x00bc510c, 0x00bd540e, 0x00bc530b, 0x00bc5006, 0x00c2570b, 0x00bf540c, 0x00b8530f, 0x00b25518, 0x00973d04, 0x008e3300, 0x00af4c0f, 0x00c45410, 0x00c04c07, 0x00bf540e, 0x00bc530c, 0x00c3540c, 0x00b74f08, 0x00b0571d, 0x00713008, 0x00220400, 0x00060000, 0x00000000, 0x00070000, 0x00240500, 0x00642c0d, 0x00ae5c2c, 0x00b85618, 0x00b7500b, 0x00c05408, 0x00c04c00, 0x00ca5408, 0x00c65407, 0x00c35b16, 0x00ac5521, 0x00642808, 0x001c0400, 0x00080200, 0x00060000, 0x00050000, 0x00010000, 0x00000104, 0x00000206, 0x00000207, 0x00040001, 0x00060000, 0x00030000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00232323, 0x00838383, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000c0c0d, 0x00080808, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005d5d5c, 0x00110d0b, 0x000a0100, 0x00280a00, 0x007a3810, 0x00b85a1c, 0x00c15104, 0x00cc5804, 0x00cc5e0c, 0x00c45d0c, 0x00bf5e0b, 0x00ba5f10, 0x00b86019, 0x00b36326, 0x00985824, 0x00713c13, 0x004a2404, 0x00301300, 0x00180000, 0x00160000, 0x00140000, 0x00190000, 0x00320d00, 0x005c2c06, 0x008a4a1b, 0x00a95b22, 0x00b45812, 0x00c35d10, 0x00c55808, 0x00bf5202, 0x00bc550c, 0x00be580e, 0x00be5808, 0x00c05808, 0x00c05605, 0x00b9550b, 0x00b45b1c, 0x008b4b20, 0x00260c00, 0x00070000, 0x00080000, 0x000c0000, 0x00110000, 0x00280400, 0x00652c05, 0x009c501f, 0x00b05818, 0x00b45610, 0x00b65812, 0x00b85510, 0x00be5410, 0x00b65114, 0x00a85621, 0x0081441d, 0x00311000, 0x00110000, 0x00210200, 0x00471702, 0x00934c28, 0x00b05824, 0x00b75110, 0x00c0540c, 0x00c4580c, 0x00bb5004, 0x00ba530a, 0x00b8581b, 0x00a45328, 0x007b381d, 0x003b0900, 0x002b0000, 0x00581900, 0x009e5024, 0x00b75614, 0x00b85004, 0x00bc5209, 0x00bd500c, 0x00bf500f, 0x00bf4f10, 0x00bb5110, 0x00ba520d, 0x00bd530a, 0x00c05108, 0x00bf4b02, 0x00c45310, 0x00bd5a1f, 0x00934616, 0x00461600, 0x00431300, 0x00a45523, 0x00c05c1b, 0x00c6580c, 0x00c04d00, 0x00c9570c, 0x00ba4f0b, 0x00b25519, 0x00924a1a, 0x00491e00, 0x00160000, 0x00080000, 0x000d0000, 0x00290900, 0x0069330d, 0x00ac5e25, 0x00b55414, 0x00bb5212, 0x00bd5110, 0x00bc520e, 0x00be550d, 0x00bd500a, 0x00ba5a1c, 0x00955024, 0x004d1c00, 0x00200000, 0x00280400, 0x006c3010, 0x009d4d1d, 0x00b85818, 0x00bd540e, 0x00bc530c, 0x00bd540e, 0x00be530f, 0x00c05009, 0x00c45104, 0x00c25002, 0x00bc4f0a, 0x00b45515, 0x00a8591f, 0x0083491a, 0x00452301, 0x00160000, 0x00100000, 0x00180300, 0x0035231e, 0x003a2b25, 0x000b0000, 0x001e0000, 0x0068280c, 0x00ae5529, 0x00c05516, 0x00c25109, 0x00bd4d08, 0x00bb500c, 0x00ba5310, 0x00b85412, 0x00b85410, 0x00bd5510, 0x00bf540c, 0x00bd520c, 0x00bb5514, 0x00b04f11, 0x00ac4f14, 0x00ad4c12, 0x00b04808, 0x00c15514, 0x00bc5210, 0x00bf5511, 0x00c0540c, 0x00bc5009, 0x00b95410, 0x009c4a14, 0x004a1a00, 0x00180000, 0x00050000, 0x00030000, 0x00100000, 0x00391300, 0x008c461e, 0x00b25820, 0x00b45310, 0x00bd560d, 0x00c2580f, 0x00c05209, 0x00c25108, 0x00c15610, 0x00b5541d, 0x00813b16, 0x00301104, 0x00060000, 0x00060000, 0x00040000, 0x00010000, 0x00000100, 0x00000204, 0x00000305, 0x00010005, 0x00020004, 0x00010002, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00373737, 0x009d9d9d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00090909, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00acb4b3, 0x0050504e, 0x00040000, 0x00080000, 0x00431e0c, 0x00944718, 0x00bc5410, 0x00cc5908, 0x00cb5500, 0x00c25807, 0x00c36016, 0x00ba601c, 0x00af5f20, 0x009d5621, 0x0071340b, 0x00481900, 0x00301000, 0x00180200, 0x00100000, 0x00140000, 0x00130000, 0x00220500, 0x00482004, 0x00784319, 0x009b5824, 0x00ae5c1c, 0x00b55912, 0x00bc590c, 0x00c15706, 0x00c95405, 0x00c85508, 0x00c25710, 0x00c05910, 0x00c05908, 0x00bd5701, 0x00bf5601, 0x00bd5808, 0x00b95816, 0x00984b1c, 0x00552c1b, 0x00100000, 0x00080000, 0x00060000, 0x0020120c, 0x00190000, 0x002c0100, 0x005c2200, 0x00934c17, 0x00ac591c, 0x00b05414, 0x00bb5714, 0x00bd5110, 0x00be5413, 0x00b3561a, 0x009c5320, 0x00643713, 0x00230500, 0x00140000, 0x001e0000, 0x00501c05, 0x00975028, 0x00af541b, 0x00b8500c, 0x00c2540b, 0x00bf5005, 0x00c2550f, 0x00b64e10, 0x00b15321, 0x009c4d29, 0x00642915, 0x00330000, 0x003a0400, 0x00823f1a, 0x00b2571c, 0x00ba530a, 0x00bc5009, 0x00bc500b, 0x00be4f0e, 0x00bc4f10, 0x00ba5111, 0x00b95210, 0x00bc510a, 0x00bf5009, 0x00c04f0a, 0x00c05819, 0x00a34c19, 0x00702901, 0x00420b00, 0x007c3d16, 0x00b65b20, 0x00c0530c, 0x00c65608, 0x00c85508, 0x00c0500b, 0x00b85618, 0x00a45622, 0x005b2600, 0x001f0500, 0x000a0000, 0x00080000, 0x00160000, 0x004b1900, 0x00984e1d, 0x00b45814, 0x00ba5109, 0x00bc5412, 0x00be5414, 0x00bc500b, 0x00c0540f, 0x00ba5312, 0x00ac541f, 0x00703712, 0x00300800, 0x00210000, 0x00512000, 0x00934519, 0x00b65720, 0x00b85214, 0x00bc5310, 0x00bb530e, 0x00bc540d, 0x00bd520e, 0x00c0520b, 0x00c55004, 0x00c55308, 0x00bb5214, 0x00ad5620, 0x008d4c20, 0x004d2300, 0x00160200, 0x000e0000, 0x001a0400, 0x00392012, 0x00543c2d, 0x002d1609, 0x00110000, 0x002e0900, 0x00883e1c, 0x00b65422, 0x00bc500f, 0x00c05008, 0x00c2550f, 0x00bf5511, 0x00b65010, 0x00b95515, 0x00bc5718, 0x00b84f0d, 0x00bf520d, 0x00c1530c, 0x00bb500a, 0x00bc5411, 0x00b85414, 0x00b45214, 0x00be5a1a, 0x00ba5310, 0x00bb5310, 0x00c05710, 0x00bd500a, 0x00c0540d, 0x00bf560e, 0x00ac5215, 0x007a3810, 0x00310900, 0x00100000, 0x00030001, 0x00080002, 0x00220800, 0x005d2605, 0x00a65825, 0x00b65717, 0x00b9530d, 0x00b9530d, 0x00bc530c, 0x00c5560d, 0x00c4550f, 0x00bc5719, 0x00904318, 0x003c1606, 0x000b0000, 0x00040000, 0x00010000, 0x00000100, 0x00000200, 0x00000200, 0x00000104, 0x00000107, 0x00000105, 0x00000002, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004a4a4a, 0x00b2b2b2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00080808, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009ba2a1, 0x003d3f3e, 0x00040000, 0x000f0000, 0x004e220a, 0x00a8501b, 0x00c3540b, 0x00c95404, 0x00c75809, 0x00bc5f19, 0x00ae6027, 0x009d592e, 0x00723b1a, 0x00481c01, 0x00290800, 0x00170000, 0x00120000, 0x00140000, 0x00140000, 0x00260a00, 0x00482202, 0x00703e14, 0x0090501d, 0x00a8581e, 0x00b85c1a, 0x00bd5b10, 0x00bb5509, 0x00bc5d12, 0x00bc590e, 0x00c3540b, 0x00c05009, 0x00c05717, 0x00be5915, 0x00b95200, 0x00c25a02, 0x00bd5700, 0x00bf5808, 0x00be5812, 0x00aa501d, 0x007d4027, 0x00290600, 0x00080000, 0x00040102, 0x00241818, 0x0038231d, 0x00270400, 0x002d0000, 0x00511c00, 0x00854415, 0x00a8571d, 0x00b45415, 0x00bd5412, 0x00bb4f0d, 0x00b95815, 0x00ab5619, 0x0091501c, 0x00582a06, 0x00150000, 0x00130000, 0x00210400, 0x004c1e06, 0x009b5224, 0x00b35419, 0x00bb4c08, 0x00c45008, 0x00c2500c, 0x00bb4d0d, 0x00b85218, 0x00ac5222, 0x008b4726, 0x00531d06, 0x002b0000, 0x00582005, 0x00a95625, 0x00b25011, 0x00bc520e, 0x00bb4c06, 0x00bc4d0b, 0x00bd5110, 0x00bc5314, 0x00bb5210, 0x00bc4f08, 0x00c0510a, 0x00bb4f0d, 0x00b3541d, 0x00843d18, 0x004e1200, 0x005c1c00, 0x00a45521, 0x00c15a17, 0x00c8550a, 0x00cb580b, 0x00c15008, 0x00bf5618, 0x00ab5420, 0x00723810, 0x00301000, 0x00060000, 0x00040000, 0x000c0000, 0x00340e00, 0x007d3811, 0x00ac5117, 0x00c15810, 0x00bd5003, 0x00bc5210, 0x00bf5415, 0x00c0500c, 0x00c05614, 0x00b25620, 0x008c461b, 0x003e1400, 0x00240100, 0x00461b00, 0x00803f13, 0x00af511a, 0x00c05418, 0x00c05216, 0x00bd5011, 0x00bb510f, 0x00bc540d, 0x00bc540c, 0x00c0540c, 0x00c44f0a, 0x00c35212, 0x00b95520, 0x0095481f, 0x0055260b, 0x00210500, 0x000e0000, 0x00100000, 0x003c1c04, 0x00654127, 0x00513420, 0x001e0500, 0x00120000, 0x003f1800, 0x00a45528, 0x00b75214, 0x00bf530b, 0x00c05207, 0x00bb520c, 0x00bb5310, 0x00bc5311, 0x00bd5412, 0x00c05310, 0x00c15210, 0x00c1510d, 0x00c1510c, 0x00c2510b, 0x00c15008, 0x00c05108, 0x00be530c, 0x00bb5612, 0x00bb5613, 0x00bc530f, 0x00c0530c, 0x00c0530c, 0x00bd520c, 0x00b8500d, 0x00b55818, 0x009a4b17, 0x005f2604, 0x001b0000, 0x00080004, 0x00030003, 0x000e0000, 0x003b1200, 0x00904e24, 0x00af5214, 0x00bc540d, 0x00b8530f, 0x00bd5711, 0x00bf520c, 0x00c55710, 0x00c05614, 0x00a04d1b, 0x00421904, 0x000d0000, 0x00010000, 0x00000100, 0x00000200, 0x00000200, 0x00000100, 0x00000100, 0x00000006, 0x00000006, 0x00000002, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00040404, 0x00000000, 0x00010101, 0x00000000, 0x000c0c0c, 0x00646464, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008d9091, 0x00303133, 0x00050000, 0x00190200, 0x005b2708, 0x00b7581d, 0x00c9590d, 0x00be5005, 0x00ba5a15, 0x00a65c27, 0x00804823, 0x004f220c, 0x002c0900, 0x00170000, 0x00150000, 0x00140000, 0x001d0100, 0x00391500, 0x00552b09, 0x00724115, 0x008b501c, 0x00a45c21, 0x00b15d1c, 0x00b85813, 0x00bd550f, 0x00bf570c, 0x00be580c, 0x00b4580d, 0x00b7590f, 0x00c45a11, 0x00c45410, 0x00b85213, 0x00bb5613, 0x00c05908, 0x00bf5600, 0x00bb5501, 0x00bb5405, 0x00bd540e, 0x00ba581e, 0x009b4e26, 0x004f1e07, 0x000c0000, 0x00040100, 0x00160e0f, 0x00402c2b, 0x0053332b, 0x00350c00, 0x002c0000, 0x00491400, 0x00803c10, 0x00a3501b, 0x00b45317, 0x00bd5615, 0x00ba540e, 0x00b35410, 0x00a8581c, 0x007f4114, 0x003a1500, 0x00120000, 0x000d0000, 0x001d0300, 0x005e2807, 0x009d5020, 0x00b85517, 0x00bf500c, 0x00c04f0d, 0x00c35212, 0x00bf5111, 0x00b6541a, 0x00a15223, 0x00793c18, 0x003e1000, 0x00360500, 0x00803b15, 0x00b05a27, 0x00b75214, 0x00bd520e, 0x00c15413, 0x00bb4f0e, 0x00b44c0c, 0x00bb5110, 0x00c2520c, 0x00bd4f08, 0x00b85014, 0x00a04819, 0x0064280b, 0x00460e00, 0x00843808, 0x00b35516, 0x00ca5b10, 0x00c85204, 0x00c95409, 0x00bc4f0e, 0x00b1541c, 0x00904c20, 0x003c1800, 0x00140700, 0x00000000, 0x00040100, 0x001a0000, 0x0057230c, 0x009e481c, 0x00bc5414, 0x00c45408, 0x00c05002, 0x00ba510b, 0x00b9500f, 0x00be5010, 0x00b75118, 0x009e5024, 0x005d2403, 0x002d0800, 0x00371200, 0x0072390e, 0x00a65721, 0x00bb5314, 0x00c55110, 0x00c35012, 0x00bf4f10, 0x00bd5110, 0x00bc530c, 0x00bb520a, 0x00bb520c, 0x00be5113, 0x00b34f19, 0x00a35228, 0x0064280c, 0x00250600, 0x00100000, 0x00110000, 0x00351500, 0x006c4022, 0x00714629, 0x003c200c, 0x00140000, 0x00200400, 0x00633412, 0x00ac5824, 0x00b9510e, 0x00c05207, 0x00c25408, 0x00bf5610, 0x00bb5310, 0x00bb4f0d, 0x00bd4e0c, 0x00c04e0b, 0x00c04e0b, 0x00bf500f, 0x00be5010, 0x00be510e, 0x00bf520d, 0x00c0540d, 0x00bd550f, 0x00b45411, 0x00b0500f, 0x00bc5411, 0x00bb500c, 0x00ba4f09, 0x00bc530f, 0x00bc5412, 0x00b85718, 0x00ae5318, 0x008c4317, 0x00401705, 0x00130000, 0x00070000, 0x00090000, 0x00200400, 0x005c2807, 0x00ae5820, 0x00b8510e, 0x00b8520c, 0x00bc540c, 0x00bf4f08, 0x00c4530b, 0x00c4550e, 0x00aa531c, 0x004c2007, 0x000d0000, 0x00000002, 0x00000304, 0x00000200, 0x00000100, 0x00010100, 0x00010000, 0x00000004, 0x00000106, 0x00000002, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00212121, 0x007d7d7d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007a7a78, 0x00202124, 0x00050000, 0x00250800, 0x006e330d, 0x00b75615, 0x00c5580c, 0x00c05f1c, 0x00a45823, 0x00673818, 0x00341705, 0x00170100, 0x000e0000, 0x00100000, 0x001f0600, 0x003a1300, 0x00602b07, 0x00884315, 0x009d4f16, 0x00ac5b19, 0x00b35c16, 0x00b85c14, 0x00bc5812, 0x00be5611, 0x00be5611, 0x00bb5813, 0x00b85911, 0x00b35b0f, 0x00b4590c, 0x00bc5409, 0x00c1570e, 0x00bd5613, 0x00bb540f, 0x00c05608, 0x00bc5504, 0x00ba570a, 0x00ba560c, 0x00ba5109, 0x00bd5815, 0x00ad541c, 0x007b3d14, 0x00230a00, 0x00070000, 0x00060000, 0x002a1917, 0x00644339, 0x00603628, 0x00401502, 0x002c0000, 0x00421200, 0x006f340c, 0x00994918, 0x00b85a1c, 0x00ba500c, 0x00b85009, 0x00b45818, 0x00a25822, 0x006f3c18, 0x00230200, 0x000c0000, 0x00090000, 0x00240700, 0x00693611, 0x009c4f18, 0x00b15414, 0x00b84f0d, 0x00bd500c, 0x00c2520c, 0x00bc5210, 0x00ae5318, 0x009c5122, 0x00632f10, 0x00280000, 0x004c1800, 0x008e4c26, 0x00af561f, 0x00b85213, 0x00bc5311, 0x00bf5312, 0x00bc500e, 0x00bd500d, 0x00c2510b, 0x00bc500c, 0x00b25018, 0x0088390d, 0x00481100, 0x00541900, 0x00ac531a, 0x00c3570f, 0x00cc5606, 0x00cb5102, 0x00c8510b, 0x00ba5418, 0x00a05324, 0x005c2b0d, 0x00160400, 0x00000000, 0x00010404, 0x00090000, 0x00381100, 0x00813d1e, 0x00b65624, 0x00c15211, 0x00c04c02, 0x00c45205, 0x00be5409, 0x00ba5310, 0x00b85216, 0x00af5726, 0x00753814, 0x00340400, 0x00380d00, 0x00663212, 0x009c5120, 0x00b4561b, 0x00bf5410, 0x00c2510b, 0x00c1500c, 0x00c1500f, 0x00c25110, 0x00c0510d, 0x00bc5209, 0x00b85410, 0x00b2571f, 0x00a0542b, 0x00643014, 0x00260800, 0x000c0000, 0x000e0000, 0x00370c00, 0x006c3417, 0x008c5234, 0x0064371f, 0x001c0600, 0x000e0000, 0x00371000, 0x008b4d22, 0x00b0551b, 0x00bc510a, 0x00c05105, 0x00bc4e00, 0x00b94f06, 0x00bd520c, 0x00c0540f, 0x00c0500c, 0x00c1500c, 0x00c25312, 0x00bc5114, 0x00b95419, 0x00b8571e, 0x00b3551d, 0x00af5419, 0x00ae5419, 0x00b1591c, 0x00b65c1d, 0x00b65415, 0x00bb5413, 0x00bb5110, 0x00bd5411, 0x00bb5410, 0x00b4500d, 0x00b45111, 0x00a7501a, 0x00783614, 0x00370b00, 0x000e0000, 0x000a0000, 0x000e0000, 0x002e0800, 0x00954c1f, 0x00b45415, 0x00ba510b, 0x00c35307, 0x00c75004, 0x00c95306, 0x00c65407, 0x00b1581b, 0x00542409, 0x000c0000, 0x00000004, 0x00000207, 0x00000100, 0x00000000, 0x00030000, 0x00030000, 0x00000001, 0x00000003, 0x00000001, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00030303, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00404040, 0x009f9f9f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x006c6968, 0x0016171b, 0x00090000, 0x002c0b00, 0x007c3f17, 0x00b45b1c, 0x00b45410, 0x009e4d17, 0x00682d06, 0x002a0800, 0x00130000, 0x000e0000, 0x00130000, 0x002c1200, 0x00583113, 0x00844922, 0x00a35826, 0x00b45c22, 0x00bc5c19, 0x00bf5c14, 0x00be580c, 0x00be5408, 0x00c05408, 0x00c3540d, 0x00c15610, 0x00b85611, 0x00b1540f, 0x00b0550c, 0x00b4570c, 0x00b8540b, 0x00b9510b, 0x00bf5712, 0x00be5610, 0x00b85005, 0x00bd560b, 0x00b8550d, 0x00bc5913, 0x00bb520c, 0x00ba520d, 0x00b25110, 0x009d521f, 0x004a2407, 0x000f0000, 0x00080000, 0x000c0000, 0x00402118, 0x00764d3e, 0x00754734, 0x0054240c, 0x002f0200, 0x003c0b00, 0x00682a03, 0x00984918, 0x00b45417, 0x00ba5312, 0x00b15011, 0x00ac571d, 0x00965122, 0x00532406, 0x00120000, 0x000d0100, 0x000d0000, 0x002c0d00, 0x006b350b, 0x00a05721, 0x00b3581c, 0x00b8500e, 0x00be5009, 0x00bf500a, 0x00b4500c, 0x00ab551d, 0x0083461e, 0x00421400, 0x00290000, 0x00572408, 0x00994e23, 0x00ad541d, 0x00b35218, 0x00b75112, 0x00bd5110, 0x00be4f0b, 0x00be4f0b, 0x00b85012, 0x00a34917, 0x00702600, 0x00450b00, 0x007c3a14, 0x00bb581a, 0x00cc5808, 0x00c95000, 0x00cb5408, 0x00bd500f, 0x00b25724, 0x007a3c19, 0x002b0900, 0x000a0300, 0x00000100, 0x00040000, 0x001c0600, 0x00602c10, 0x00a05026, 0x00bc561d, 0x00c04f0d, 0x00bf4c04, 0x00c35409, 0x00bb5209, 0x00b65412, 0x00ad541f, 0x0090451c, 0x00430c00, 0x003a0a00, 0x00693114, 0x0098512c, 0x00b35723, 0x00ba5111, 0x00be510b, 0x00be5005, 0x00bf5009, 0x00c1510c, 0x00c0500c, 0x00bf500d, 0x00bc5210, 0x00b35518, 0x00a3572a, 0x00723c1c, 0x002b0e00, 0x000c0000, 0x000b0000, 0x00270c00, 0x006c3014, 0x00934c2a, 0x0080442b, 0x00461a09, 0x00110000, 0x00180100, 0x005c2604, 0x00a45523, 0x00b25011, 0x00bf520c, 0x00be5005, 0x00c05308, 0x00bf540c, 0x00bc540d, 0x00b9500f, 0x00b74f10, 0x00b65114, 0x00b5541c, 0x00ab511e, 0x009a4819, 0x00883f16, 0x007f3a13, 0x007b360d, 0x007a3104, 0x00803000, 0x00883100, 0x009e4006, 0x00b34e11, 0x00b85012, 0x00b8500e, 0x00ba520d, 0x00ba520d, 0x00bb5410, 0x00b45216, 0x009f491c, 0x0068280b, 0x00210000, 0x000e0000, 0x000b0000, 0x001d0400, 0x00652c0b, 0x00a95624, 0x00b64f0c, 0x00c45004, 0x00c95105, 0x00cc5407, 0x00c65402, 0x00b25817, 0x00562809, 0x000e0000, 0x00000004, 0x00000207, 0x00000100, 0x00000000, 0x00030000, 0x00030000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00030303, 0x00020202, 0x00030303, 0x00000000, 0x00010101, 0x000b0b0b, 0x00626262, 0x00313131, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00635e5e, 0x00101014, 0x00090000, 0x00341000, 0x007a421b, 0x00a95f29, 0x00994f18, 0x00602600, 0x002d0200, 0x00160000, 0x00150000, 0x002f0e00, 0x00522806, 0x007e461c, 0x009d5a27, 0x00b05e27, 0x00b55c20, 0x00b4561b, 0x00b55416, 0x00ba5616, 0x00bf5712, 0x00c5560c, 0x00c75507, 0x00c45304, 0x00c05306, 0x00b9550c, 0x00b85611, 0x00a54401, 0x00ab4608, 0x00bc581b, 0x00b95414, 0x00ba500e, 0x00c0570f, 0x00b95208, 0x00bc560d, 0x00b3510c, 0x00ba5613, 0x00bc5411, 0x00bc5310, 0x00ba5113, 0x00b15824, 0x007a3f21, 0x002c0800, 0x00110000, 0x00080000, 0x00160200, 0x00503021, 0x00855035, 0x008b4d2c, 0x005c2301, 0x003a0600, 0x00370800, 0x00592201, 0x0092461b, 0x00b25825, 0x00b2511a, 0x00af5017, 0x00ab541b, 0x008f4b1f, 0x00380f00, 0x00140000, 0x000b0000, 0x000c0000, 0x00331800, 0x0073431b, 0x009d5523, 0x00ae5115, 0x00b84c0c, 0x00c3510c, 0x00c0510d, 0x00b55416, 0x00994e1d, 0x0068310d, 0x00200000, 0x00270100, 0x00652c0d, 0x00985028, 0x00aa5827, 0x00ac5015, 0x00b64d0c, 0x00bc4f0a, 0x00b95010, 0x00ae5019, 0x00883c11, 0x00561300, 0x005d1a00, 0x00a45425, 0x00bf5410, 0x00cc5707, 0x00c65001, 0x00c4560f, 0x00b4531c, 0x00944a21, 0x00401400, 0x00140000, 0x00020000, 0x00080504, 0x000e0000, 0x00461d06, 0x0088441c, 0x00b05422, 0x00bb5014, 0x00c2500f, 0x00c0500c, 0x00bc510c, 0x00b4510c, 0x00ad5518, 0x009a5125, 0x005d1f00, 0x003e0400, 0x006e2f0c, 0x009d502a, 0x00b05428, 0x00b64c14, 0x00c15211, 0x00bd520b, 0x00ba5207, 0x00bb5308, 0x00bc5209, 0x00bc4d09, 0x00bc4f10, 0x00b7541a, 0x00a75423, 0x007c4321, 0x002e0d00, 0x00100300, 0x000d0400, 0x001d0400, 0x005a2c15, 0x00964c28, 0x009e522f, 0x0064301b, 0x00240200, 0x00160000, 0x00371005, 0x0089401a, 0x00b4531d, 0x00b64d0d, 0x00bf540e, 0x00b9500c, 0x00be5410, 0x00bc530f, 0x00b44f0e, 0x00b05317, 0x00ac5622, 0x00984c1c, 0x00803b12, 0x006c300f, 0x00552206, 0x003c1300, 0x00320c00, 0x00320800, 0x00400b00, 0x005c1800, 0x00782700, 0x00973b05, 0x00b04d14, 0x00b75114, 0x00b84e0c, 0x00bd5109, 0x00bf530b, 0x00bc530f, 0x00b85012, 0x00b24e18, 0x0096451c, 0x004c1f08, 0x00180100, 0x000b0000, 0x00140100, 0x00330c00, 0x008a4b2a, 0x00b05118, 0x00c04f08, 0x00c74e05, 0x00cc5406, 0x00c65501, 0x00b15915, 0x0057280a, 0x00130000, 0x00020001, 0x00000005, 0x00000000, 0x00000000, 0x00020000, 0x00020000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x002b2b2b, 0x00888888, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005c5558, 0x000b0a10, 0x00080000, 0x003a1903, 0x007b4a26, 0x00864e24, 0x005f2a04, 0x002d0500, 0x00190000, 0x00220000, 0x00401700, 0x00713b14, 0x008e4e1f, 0x009c5421, 0x009b4c18, 0x00a04f18, 0x00ac5822, 0x00b15c25, 0x00b0581f, 0x00b65619, 0x00bd5614, 0x00c3540c, 0x00c35305, 0x00c15304, 0x00c05407, 0x00bb570d, 0x00b95814, 0x00a84709, 0x00913300, 0x00a24612, 0x00b55820, 0x00b95211, 0x00bd540e, 0x00bc560f, 0x00b8530d, 0x00b85510, 0x00b6510d, 0x00bc5210, 0x00bf5311, 0x00be5010, 0x00b7541c, 0x00a0542c, 0x00602b10, 0x00190000, 0x000a0000, 0x00080000, 0x00220b00, 0x0069391c, 0x00945630, 0x00914e28, 0x006c2f0c, 0x00380900, 0x00300100, 0x00581d00, 0x008f4520, 0x00b05628, 0x00b8551f, 0x00b25014, 0x00ab5722, 0x00773c1e, 0x00270100, 0x000f0000, 0x00060000, 0x000d0000, 0x00371b04, 0x007a401a, 0x00a65320, 0x00b75014, 0x00c0500e, 0x00c0500b, 0x00b8500e, 0x00a8521a, 0x0088461c, 0x00350900, 0x001b0000, 0x002c0000, 0x00643016, 0x00904c27, 0x00a95624, 0x00b95414, 0x00b84f0c, 0x00b25117, 0x00a45021, 0x006c2b08, 0x004a0b00, 0x00803206, 0x00b85c21, 0x00c2520c, 0x00cb5408, 0x00c45408, 0x00b85412, 0x00a85829, 0x00632b0e, 0x001e0200, 0x000b0000, 0x00030000, 0x000a0000, 0x002c0700, 0x00713716, 0x00a35321, 0x00b8561a, 0x00b94d0c, 0x00c1500c, 0x00bf500d, 0x00b85010, 0x00b35717, 0x00a45720, 0x006c300b, 0x00400700, 0x00702c04, 0x009e4d20, 0x00b25423, 0x00b84e1a, 0x00bb4b0f, 0x00bf4e0c, 0x00bc510a, 0x00b95208, 0x00bb540a, 0x00b95208, 0x00bb500a, 0x00bb5518, 0x00ae5424, 0x008e4826, 0x00411601, 0x00140000, 0x00080000, 0x001f0b00, 0x0055260b, 0x008c4a27, 0x00a6562f, 0x00894323, 0x00411b09, 0x00130000, 0x00210300, 0x00562210, 0x00a74f28, 0x00bc521b, 0x00bc500f, 0x00bd520c, 0x00bc5210, 0x00b85011, 0x00b35115, 0x00ab541e, 0x009b5023, 0x007c3e18, 0x00572404, 0x003b1000, 0x00260000, 0x00210000, 0x00230200, 0x00310d00, 0x00481b05, 0x00662b0d, 0x008b3e15, 0x00a74f1c, 0x00ae4d16, 0x00bb5418, 0x00bb5214, 0x00bd5110, 0x00c0520b, 0x00bb4f05, 0x00b84f0b, 0x00b95012, 0x00ba531c, 0x00aa5326, 0x007c4428, 0x00341400, 0x000e0000, 0x000c0000, 0x00180000, 0x005c2b17, 0x00aa5628, 0x00bc5214, 0x00c44f0b, 0x00c85308, 0x00c55706, 0x00b35c19, 0x0054280a, 0x00130000, 0x00060000, 0x00020001, 0x00020000, 0x00020000, 0x00000004, 0x00000004, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00535353, 0x00acacac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00544f55, 0x0008050e, 0x00080000, 0x003c1c08, 0x006e4628, 0x00512f14, 0x00200400, 0x00110000, 0x00280c00, 0x0058280c, 0x008f4d25, 0x00aa5b27, 0x009b4712, 0x007c3005, 0x006e2b06, 0x00733818, 0x007a4321, 0x00884b21, 0x009a5421, 0x00ad571c, 0x00b95815, 0x00bf5811, 0x00bd560c, 0x00b9570c, 0x00b9580e, 0x00b95611, 0x00b35412, 0x00b0581a, 0x008c3c05, 0x007a2e01, 0x00954516, 0x00b25215, 0x00b7520f, 0x00bb5714, 0x00b6530e, 0x00be5810, 0x00b9500a, 0x00be510c, 0x00be510c, 0x00be5009, 0x00ba5110, 0x00b3581d, 0x00934e20, 0x00381000, 0x00100000, 0x00060000, 0x000c0200, 0x003d1e07, 0x007d4826, 0x00a65a2f, 0x00a05024, 0x0070300e, 0x00440f00, 0x00340400, 0x00561f06, 0x0090431f, 0x00b15425, 0x00b65015, 0x00b15018, 0x00a0542b, 0x00541f05, 0x001e0400, 0x00090000, 0x00030000, 0x00140300, 0x0052210b, 0x00944824, 0x00b4521e, 0x00b84d0e, 0x00bb500c, 0x00b54e0b, 0x00b25417, 0x00a05020, 0x00682c13, 0x00320500, 0x00160000, 0x002a0700, 0x00582509, 0x00944b20, 0x00b35115, 0x00b44f10, 0x00aa5220, 0x008b421c, 0x004f1a00, 0x00551a00, 0x00a34914, 0x00c15814, 0x00c4540c, 0x00c5540c, 0x00c0540f, 0x00ac5319, 0x00844422, 0x00320d00, 0x00100100, 0x00040000, 0x000c0000, 0x00170000, 0x005c240a, 0x00944920, 0x00b0571d, 0x00ba5512, 0x00bd4f08, 0x00c04e09, 0x00bc4d0c, 0x00b55014, 0x00aa5620, 0x00814013, 0x00410e00, 0x005b2002, 0x00a24b1c, 0x00b85117, 0x00b94f13, 0x00c05314, 0x00c35514, 0x00be510c, 0x00bc500b, 0x00bc500b, 0x00bc530c, 0x00b9510b, 0x00b9510b, 0x00b4551a, 0x008e441f, 0x0058230e, 0x00180000, 0x00190200, 0x001b0000, 0x0051240a, 0x00984b20, 0x00ac5528, 0x00974d28, 0x005c280c, 0x001d0800, 0x000d0000, 0x00391000, 0x007e3b1e, 0x00b05028, 0x00bc501b, 0x00bc540d, 0x00bc5107, 0x00bf520f, 0x00b85219, 0x00a65224, 0x00874622, 0x0055280e, 0x00290900, 0x00140000, 0x00140000, 0x00190000, 0x00300d00, 0x00522303, 0x00783b14, 0x009c5021, 0x00b55a28, 0x00ba571f, 0x00b84e13, 0x00bc5114, 0x00be5211, 0x00bc4c0a, 0x00c0500c, 0x00c0540d, 0x00b9500a, 0x00bb510f, 0x00ba5419, 0x00b05123, 0x00994821, 0x00844623, 0x005d3214, 0x00311600, 0x000e0000, 0x00100000, 0x002f0a00, 0x008f4828, 0x00b05120, 0x00c05218, 0x00c45410, 0x00c1590c, 0x00af5c1d, 0x0052270a, 0x00130000, 0x000b0000, 0x00080000, 0x00060000, 0x00030000, 0x00000008, 0x00000009, 0x00000001, 0x00000100, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x001c1c1c, 0x00808080, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00504c52, 0x0006040c, 0x00080000, 0x00341b0a, 0x0046270e, 0x00280c00, 0x001a0000, 0x002d1000, 0x0064391b, 0x00985429, 0x00b05e27, 0x00b4591b, 0x00b95c20, 0x00a34c1b, 0x00742a01, 0x00480f00, 0x00330400, 0x003d1100, 0x005a2704, 0x00874317, 0x00a04e19, 0x00b1581b, 0x00b45815, 0x00b2560d, 0x00b5560e, 0x00ba5613, 0x00b75615, 0x00b15818, 0x00a7581e, 0x006c2700, 0x006f2700, 0x009c4814, 0x00ac5016, 0x00b85a1b, 0x00b65412, 0x00ba520d, 0x00bc5009, 0x00c25711, 0x00be510b, 0x00bc5007, 0x00bc540c, 0x00b2500c, 0x00aa5820, 0x00703714, 0x00250500, 0x00080000, 0x00050000, 0x00190400, 0x00683a1c, 0x009d5024, 0x00af5523, 0x00a55628, 0x00763410, 0x003c0900, 0x00330100, 0x0064240a, 0x009a4a23, 0x00b45420, 0x00b35018, 0x00af5724, 0x008c4823, 0x00371000, 0x000c0000, 0x00070308, 0x00070000, 0x00220000, 0x0064280f, 0x00a44e21, 0x00b14e14, 0x00bc5615, 0x00b7500d, 0x00b85316, 0x00ac511f, 0x009b4f2c, 0x005b220c, 0x00240100, 0x00150000, 0x00270000, 0x00642c0f, 0x00924010, 0x00a8521e, 0x00a0582f, 0x006a2e0e, 0x00420e00, 0x006c2d0b, 0x00b5581b, 0x00c5580c, 0x00c5540b, 0x00c15410, 0x00b45314, 0x00a25525, 0x0050230b, 0x00140000, 0x00030000, 0x00030000, 0x00150000, 0x00360a00, 0x00803714, 0x00ae5323, 0x00b25014, 0x00ba520f, 0x00bf520d, 0x00bd500c, 0x00ba5010, 0x00b05119, 0x00954b1d, 0x00541500, 0x00501500, 0x0099522f, 0x00b4521c, 0x00bd4d0e, 0x00bf500f, 0x00bc500c, 0x00ba500c, 0x00b9510c, 0x00bb510f, 0x00bb510f, 0x00bc5310, 0x00b8500e, 0x00b25011, 0x00a1501c, 0x00622d14, 0x001c0000, 0x00150000, 0x00180000, 0x004f1e07, 0x008e4924, 0x00ae521e, 0x00ad5421, 0x007c3e1c, 0x00341000, 0x000c0000, 0x00200900, 0x005b2404, 0x00a8542e, 0x00b54e20, 0x00ba4c14, 0x00bb530c, 0x00b7530b, 0x00b45118, 0x00a64f22, 0x007c3a1c, 0x00411400, 0x00170000, 0x000d0000, 0x00140200, 0x001c0300, 0x00442006, 0x00713f1c, 0x009c582a, 0x00ac5824, 0x00b45015, 0x00bc4f10, 0x00c05012, 0x00bd4d0e, 0x00bd4e0d, 0x00be4f0c, 0x00bf4b08, 0x00c04f0c, 0x00bf520f, 0x00b85011, 0x00b45218, 0x00ab511f, 0x00984922, 0x00793410, 0x006d2c04, 0x00814820, 0x00623617, 0x00250500, 0x00130000, 0x00170000, 0x00662e19, 0x00984821, 0x00ba541b, 0x00c45410, 0x00c0580c, 0x00ad5b1d, 0x0051260b, 0x00150000, 0x000c0000, 0x00080000, 0x00060000, 0x00030000, 0x00000008, 0x00000009, 0x00000003, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000001, 0x00000001, 0x00000001, 0x00000000, 0x00030303, 0x00000000, 0x00000000, 0x00020200, 0x004d4d4c, 0x00a8a8a6, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0048494c, 0x0007040c, 0x00050000, 0x00190700, 0x00250900, 0x00200000, 0x00441400, 0x0084441a, 0x00ac5e25, 0x00ae5414, 0x00b95b15, 0x00b25a14, 0x00b15611, 0x00c05b18, 0x00b85819, 0x00944810, 0x005c2400, 0x00240000, 0x001a0000, 0x002f0900, 0x00643114, 0x00985028, 0x00ad5924, 0x00b25510, 0x00ba580d, 0x00b9520f, 0x00b85310, 0x00b85410, 0x00ad5414, 0x00a05627, 0x005d1a00, 0x00631e00, 0x0090451a, 0x00aa541c, 0x00b45717, 0x00bb5411, 0x00ba500c, 0x00bc5411, 0x00b8500c, 0x00b85106, 0x00bc560c, 0x00b3510f, 0x00af541c, 0x009e5626, 0x00491800, 0x00110000, 0x00080000, 0x00110000, 0x00482109, 0x0091481c, 0x00ac521c, 0x00b2541c, 0x00a64e1d, 0x007f3818, 0x003b0200, 0x00390600, 0x00662c12, 0x009e5225, 0x00ad541d, 0x00b0521a, 0x00ac5a28, 0x00693517, 0x00250800, 0x00080000, 0x00050000, 0x00110000, 0x00300900, 0x00783410, 0x00ac5420, 0x00b05013, 0x00b95418, 0x00b44d17, 0x00ae4c16, 0x00b05820, 0x009c5224, 0x00521c00, 0x002a0300, 0x00140000, 0x001c0000, 0x00582005, 0x00884a28, 0x007f4d30, 0x00542105, 0x00521500, 0x008d4217, 0x00b65915, 0x00c45a0c, 0x00c8550a, 0x00ba4f0b, 0x00ac541d, 0x007c4018, 0x001e0000, 0x00070000, 0x00000000, 0x000a0300, 0x00180000, 0x0063280c, 0x00a54c22, 0x00b84e1a, 0x00bb5118, 0x00b74e10, 0x00b54e0d, 0x00b85312, 0x00b14f11, 0x00a54e1a, 0x00642200, 0x004c0c00, 0x009d4a21, 0x00af5020, 0x00b8521b, 0x00b95014, 0x00b95010, 0x00b95210, 0x00b75310, 0x00b65410, 0x00b3510f, 0x00b55110, 0x00ba500f, 0x00b75014, 0x00a84f1c, 0x00733210, 0x001d0000, 0x000f0000, 0x00190000, 0x004b1a01, 0x00964a24, 0x00ae5424, 0x00ad531c, 0x00984d1e, 0x00492107, 0x00180000, 0x00120000, 0x00401804, 0x008c4018, 0x00b5531d, 0x00ba4d12, 0x00c05010, 0x00be5514, 0x00a84d13, 0x009d5229, 0x0070371d, 0x002c0400, 0x00110000, 0x000d0000, 0x000e0000, 0x002e0d00, 0x005d2b0f, 0x00934c24, 0x00a65120, 0x00b6541d, 0x00b95014, 0x00b94c10, 0x00bc4e10, 0x00bc4f10, 0x00bc4f10, 0x00bd5110, 0x00b84b0a, 0x00c4500d, 0x00c44c0c, 0x00bb480d, 0x00b8511d, 0x00a35027, 0x00864422, 0x00521e00, 0x00501a00, 0x007d3a0a, 0x00a45a28, 0x009b5226, 0x00602708, 0x001c0000, 0x00130000, 0x00280100, 0x008f4f31, 0x00b45015, 0x00c65208, 0x00c4540a, 0x00b0571d, 0x0052240c, 0x00100000, 0x00080000, 0x00040000, 0x00030000, 0x00000000, 0x00000203, 0x00000105, 0x00000003, 0x00000001, 0x00000001, 0x00000001, 0x00020000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010000, 0x00000001, 0x00010002, 0x00010004, 0x00000003, 0x00000003, 0x00000001, 0x00010000, 0x00000000, 0x00000000, 0x001b1c17, 0x00878881, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004a4d4e, 0x0008060c, 0x00060000, 0x000e0000, 0x00210100, 0x004d1d07, 0x008b4a26, 0x00ad581d, 0x00bb5a13, 0x00bc5409, 0x00bd580c, 0x00bb5d13, 0x00b7580e, 0x00bc4f08, 0x00ba510b, 0x00b45c1a, 0x00924f1c, 0x00532c12, 0x00180100, 0x000e0000, 0x00210400, 0x00491801, 0x0088451c, 0x00b05d1e, 0x00b5560e, 0x00b95210, 0x00bf5513, 0x00bc550c, 0x00b55412, 0x00a5531e, 0x00863e16, 0x004c0d00, 0x005e1f00, 0x00954b1d, 0x00ab551f, 0x00b35114, 0x00b8510f, 0x00bb530e, 0x00b9510b, 0x00b85209, 0x00b7530b, 0x00b4500e, 0x00b6551b, 0x00aa531c, 0x007c3b13, 0x00230400, 0x000c0000, 0x000c0000, 0x002c0c00, 0x0083421c, 0x00a54f1b, 0x00b24d10, 0x00bb581e, 0x00a04c22, 0x00783618, 0x002c0000, 0x00300300, 0x007b401e, 0x009f5324, 0x00b2541a, 0x00a54a12, 0x009c582c, 0x00491c00, 0x00120000, 0x000d0400, 0x00050000, 0x00180200, 0x004e1e00, 0x008c4416, 0x00ae541c, 0x00b55015, 0x00b94f19, 0x00b84d16, 0x00b65212, 0x00aa5118, 0x009b552b, 0x00501c04, 0x001f0000, 0x001c0100, 0x001c0000, 0x00461e0a, 0x004f2d1a, 0x003d1100, 0x00662300, 0x00ac5521, 0x00bf5e14, 0x00bf5404, 0x00c65408, 0x00bb5314, 0x009b5224, 0x00401400, 0x00120000, 0x00030001, 0x00040403, 0x00080000, 0x003f1700, 0x00843e18, 0x00b04d1c, 0x00c04f16, 0x00bb4c12, 0x00be5418, 0x00b55315, 0x00ac4f14, 0x00a8521f, 0x00782c01, 0x00490800, 0x00853f1a, 0x00ac501e, 0x00ba5216, 0x00ba5014, 0x00b85011, 0x00b9500e, 0x00b9510e, 0x00b7500d, 0x00b5500f, 0x00bb5516, 0x00b34e11, 0x00b35016, 0x00a84f1c, 0x00813b14, 0x00350600, 0x00120000, 0x000d0000, 0x003d1500, 0x008e4c24, 0x00b05322, 0x00b2501c, 0x00a45422, 0x0069310a, 0x00270c00, 0x00100000, 0x00280600, 0x006c3115, 0x00ac5220, 0x00b74a0c, 0x00be4c0c, 0x00bf5214, 0x00ab4d15, 0x00a95e33, 0x0066351c, 0x00210200, 0x00130000, 0x00130000, 0x00120000, 0x002a0c00, 0x00683418, 0x00995127, 0x00ac5119, 0x00b64d0f, 0x00ba4c0c, 0x00bf4e0e, 0x00bf4f10, 0x00bc4f10, 0x00bb4d0f, 0x00ba4c0e, 0x00bb4e11, 0x00bc5011, 0x00bc4c0c, 0x00bc4f12, 0x00b6501d, 0x00a44c24, 0x0076341a, 0x003e0a00, 0x003b0c00, 0x00662e04, 0x00a5541c, 0x00ae5115, 0x00ae4f1a, 0x009d4d25, 0x004e200b, 0x00160000, 0x001d0000, 0x005a2912, 0x00a95018, 0x00c3570f, 0x00c1570e, 0x00a34d15, 0x00461d04, 0x000c0000, 0x00050000, 0x00020000, 0x00020000, 0x00000000, 0x00000101, 0x00000103, 0x00000000, 0x00000000, 0x00000001, 0x00000001, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000200, 0x00000000, 0x00000000, 0x00000000, 0x00000001, 0x00000002, 0x00000004, 0x00010004, 0x00020001, 0x00020000, 0x00040301, 0x00000000, 0x005c5c58, 0x00b0b0ac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004e5152, 0x000a080c, 0x00080000, 0x001d0100, 0x004b1e02, 0x008a4924, 0x00b46330, 0x00b85815, 0x00be570c, 0x00c0580d, 0x00bc5408, 0x00ba5207, 0x00c15810, 0x00bf5415, 0x00ba5216, 0x00b9581a, 0x00a95a24, 0x00824c28, 0x003c1c07, 0x00080000, 0x00090100, 0x00130000, 0x00431c00, 0x008e4f19, 0x00b05b1b, 0x00b44e0f, 0x00c05312, 0x00bc540d, 0x00b8530f, 0x00b05218, 0x00ab5728, 0x00702f09, 0x003f0400, 0x005d2102, 0x008f4822, 0x00ab511c, 0x00ba5512, 0x00bc5107, 0x00bc5007, 0x00bd5411, 0x00b85010, 0x00b7500f, 0x00b75112, 0x00b35014, 0x00a55428, 0x00421501, 0x00170000, 0x000b0000, 0x00140000, 0x00622f13, 0x009a4f24, 0x00ae5016, 0x00b04d10, 0x00ad541f, 0x009b5228, 0x00632e12, 0x00240000, 0x00320800, 0x008b502e, 0x00af5522, 0x00b24f15, 0x00af5822, 0x00824016, 0x00310c00, 0x000c0000, 0x00060200, 0x00050000, 0x00200800, 0x00602c06, 0x00a6521d, 0x00b44c12, 0x00bd4e17, 0x00bf4e14, 0x00b84c0d, 0x00b35114, 0x00ac5826, 0x008f4c26, 0x0056250f, 0x00230000, 0x00140000, 0x00180000, 0x00180000, 0x00360d00, 0x0084380f, 0x00bc591c, 0x00c35808, 0x00c75602, 0x00c6530c, 0x00b1521c, 0x0070391a, 0x00170000, 0x000b0000, 0x00040000, 0x00030000, 0x00130000, 0x006c3714, 0x00a25020, 0x00b7511a, 0x00bd4d11, 0x00bd4d0e, 0x00bd5314, 0x00b04f14, 0x00a55221, 0x007d3b19, 0x00490b00, 0x00682100, 0x00a85828, 0x00b15417, 0x00b8530f, 0x00bc500b, 0x00bf4f09, 0x00c04f0a, 0x00c04f0c, 0x00c14d0c, 0x00bf4c0e, 0x00bf4c13, 0x00b64c19, 0x00a85328, 0x0084431f, 0x00340a00, 0x00170000, 0x00190000, 0x003c1600, 0x00925326, 0x00aa5621, 0x00ae4a15, 0x00ac5020, 0x00874b29, 0x00330d00, 0x00140000, 0x00190000, 0x00572309, 0x00944920, 0x00b65418, 0x00c0500c, 0x00bf4b0c, 0x00b64f18, 0x009c5328, 0x0068391e, 0x00190200, 0x000a0000, 0x000b0000, 0x00110000, 0x002b0600, 0x00753f20, 0x00a05426, 0x00b1571a, 0x00b9530d, 0x00bf530b, 0x00bd520c, 0x00b74d0b, 0x00b44c0c, 0x00b84d10, 0x00bf4f11, 0x00c15014, 0x00bb4a11, 0x00be5318, 0x00ac4b0a, 0x00a65116, 0x00934e25, 0x00592007, 0x002e0000, 0x002e0000, 0x00642500, 0x00a5541e, 0x00ba520f, 0x00c24f0a, 0x00bf4e14, 0x00af4f1c, 0x008d481d, 0x00401100, 0x00160000, 0x002c0800, 0x00904a1f, 0x00ac5418, 0x00bc5d18, 0x00964c14, 0x00371a00, 0x00080200, 0x00000000, 0x00000003, 0x00040001, 0x00040003, 0x00020004, 0x00000003, 0x00020000, 0x00000000, 0x00000000, 0x00000101, 0x00000100, 0x00000100, 0x00000100, 0x00000100, 0x00000100, 0x00000100, 0x00000400, 0x00000200, 0x00000100, 0x00000300, 0x00000000, 0x00000000, 0x00000000, 0x00000001, 0x00020003, 0x00050106, 0x00000001, 0x00302e30, 0x009f9f9f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00555658, 0x000e0b0c, 0x000c0000, 0x00341300, 0x007b4422, 0x00ad5f2e, 0x00b75718, 0x00bb5209, 0x00c45708, 0x00be560b, 0x00bc5409, 0x00c05308, 0x00c2540d, 0x00bc5114, 0x00b95318, 0x00b35114, 0x00ac5922, 0x00834b21, 0x00412208, 0x00080000, 0x00040200, 0x000e0300, 0x001f0400, 0x00522000, 0x009e541e, 0x00b4531a, 0x00bc5011, 0x00bd520e, 0x00b8500c, 0x00b65114, 0x00b35824, 0x009e552b, 0x005a1e00, 0x00370100, 0x005f2309, 0x00964a1d, 0x00b1581c, 0x00b95209, 0x00bb4f05, 0x00bd5012, 0x00ba5014, 0x00bc5112, 0x00b74e0c, 0x00ba5111, 0x00ac5421, 0x00683418, 0x00230600, 0x000a0000, 0x000b0000, 0x00371200, 0x00804422, 0x00ad5723, 0x00b25014, 0x00ad4f15, 0x00a85422, 0x0090502a, 0x00481800, 0x001e0000, 0x00461700, 0x009e5227, 0x00af531d, 0x00ad4f14, 0x00a45321, 0x005b260c, 0x001e0300, 0x00040000, 0x00020300, 0x00080000, 0x003a1800, 0x008d4217, 0x00b14d18, 0x00bc4d16, 0x00be4c11, 0x00b94c0c, 0x00b85012, 0x00ad4f14, 0x00ad5925, 0x00914b24, 0x00501c04, 0x00210400, 0x000e0000, 0x00150000, 0x004a1c04, 0x009e4919, 0x00be530f, 0x00c45200, 0x00cb5c09, 0x00bb5110, 0x009b481c, 0x003c1302, 0x000c0000, 0x00080000, 0x000b0101, 0x000a0000, 0x003e1e09, 0x008a4820, 0x00ac521d, 0x00bb5317, 0x00bb4b0c, 0x00bc4f0e, 0x00b44f11, 0x00a9511f, 0x008c431f, 0x00481000, 0x004a1100, 0x009d5126, 0x00ac5218, 0x00b25310, 0x00b75009, 0x00be5008, 0x00c05009, 0x00bf4d0a, 0x00c04c0c, 0x00c44c0e, 0x00c44b10, 0x00be4a16, 0x00b04d20, 0x008d4825, 0x00471800, 0x001d0000, 0x00170000, 0x003e1400, 0x008a4f28, 0x00a9581e, 0x00b05315, 0x00b45423, 0x00a04f2a, 0x00471904, 0x001c0000, 0x001b0000, 0x003f1701, 0x00854320, 0x00a74f1c, 0x00b85010, 0x00c0510f, 0x00b84c0f, 0x00a9501d, 0x00794325, 0x00200400, 0x00060000, 0x00050000, 0x000e0000, 0x002c0700, 0x00753b1a, 0x00994c1e, 0x00b5571d, 0x00b44c09, 0x00bb4f05, 0x00ba4f03, 0x00b84f07, 0x00b9510c, 0x00bb5413, 0x00bb5214, 0x00ba4c10, 0x00b4470d, 0x00b64e1c, 0x00a84c1b, 0x00a75f2c, 0x00743c0f, 0x00360c00, 0x001c0000, 0x00250000, 0x00622b12, 0x009c4e22, 0x00b35115, 0x00bd4a04, 0x00c34a03, 0x00c14d0e, 0x00b84f15, 0x00a8521c, 0x0089481c, 0x00340b00, 0x00200000, 0x006b300c, 0x009d5220, 0x00b35e21, 0x008a4612, 0x00321903, 0x00030000, 0x00000000, 0x00000003, 0x00030004, 0x00040004, 0x00020004, 0x00020001, 0x00020000, 0x00000000, 0x00000100, 0x00000200, 0x00000200, 0x00000100, 0x00000100, 0x00000100, 0x00000100, 0x00000100, 0x00000100, 0x00000100, 0x00000400, 0x00020400, 0x00000000, 0x00000000, 0x00000100, 0x00000000, 0x00050104, 0x00020003, 0x00111014, 0x00807f83, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005f5f5f, 0x00120f0e, 0x000f0000, 0x00381400, 0x0081441f, 0x00b45b20, 0x00c0550c, 0x00cb590b, 0x00c65608, 0x00b95106, 0x00bd570e, 0x00c0550e, 0x00bc500b, 0x00bb510d, 0x00bd5916, 0x00b05414, 0x00a45b23, 0x00613610, 0x00281000, 0x000d0000, 0x00080000, 0x002b140b, 0x00452413, 0x002c0000, 0x006e300b, 0x00b05928, 0x00b44e14, 0x00bd500f, 0x00bd500d, 0x00b44f0e, 0x00b25519, 0x00a24e20, 0x00904926, 0x004b1400, 0x00340100, 0x00652b0a, 0x00924b1b, 0x00b25417, 0x00bb510f, 0x00ba4c0c, 0x00bc4c0e, 0x00c05415, 0x00bb5110, 0x00bc5412, 0x00a75017, 0x0088502c, 0x002f1000, 0x00080000, 0x00040000, 0x00140000, 0x0050250c, 0x00964d21, 0x00ad5219, 0x00b95418, 0x00ae4c14, 0x00a04c1e, 0x00884525, 0x002a0000, 0x00240000, 0x00642c0d, 0x009c5428, 0x00a95016, 0x00ae5420, 0x00884426, 0x003b0e02, 0x000c0000, 0x00000406, 0x00000100, 0x001b0a00, 0x0064270a, 0x00a94e23, 0x00b84e1a, 0x00b94b0f, 0x00b85010, 0x00b84f0d, 0x00b9500c, 0x00b85110, 0x00ae5016, 0x00974c22, 0x0049200e, 0x001f0200, 0x00240000, 0x00682e0e, 0x00af5119, 0x00c6570e, 0x00c75805, 0x00c1590e, 0x00ab4f19, 0x00733113, 0x001a0000, 0x00050003, 0x00050004, 0x000b0000, 0x00220400, 0x00744020, 0x009e5121, 0x00b04f16, 0x00bc5311, 0x00bb4e0b, 0x00b85310, 0x00a94f17, 0x00924924, 0x00541800, 0x00370100, 0x00763820, 0x00ac5829, 0x00b25013, 0x00b8500c, 0x00b94e07, 0x00bc5009, 0x00bc500c, 0x00b84a0c, 0x00bb490e, 0x00c14c14, 0x00be4c14, 0x00b9531f, 0x00914014, 0x00582405, 0x00270200, 0x00180000, 0x00441802, 0x00904d28, 0x00aa541e, 0x00af4e0c, 0x00b15113, 0x00a4542c, 0x00652813, 0x002f0800, 0x001d0000, 0x00340f00, 0x006a3410, 0x00a05125, 0x00b04f1b, 0x00bf5419, 0x00b44a0e, 0x00ac5318, 0x008c481b, 0x003a1200, 0x000f0000, 0x00080404, 0x00060000, 0x00230200, 0x00763c18, 0x00a14e1d, 0x00b24f15, 0x00b74c0d, 0x00be5010, 0x00ba500e, 0x00b64c08, 0x00b74d09, 0x00ba500c, 0x00b9510e, 0x00b54c0b, 0x00b74d11, 0x00b5541e, 0x00a6552a, 0x008d502e, 0x00411c04, 0x001e0800, 0x00130000, 0x001c0100, 0x00602d11, 0x00914823, 0x00ad5020, 0x00b44b10, 0x00bb4c0b, 0x00bd4d09, 0x00bd500f, 0x00ba5214, 0x00b35117, 0x00a85524, 0x007c3a1a, 0x003a0200, 0x00450900, 0x008e4c24, 0x00a95b28, 0x0078380e, 0x002f1407, 0x00040000, 0x00020000, 0x00000000, 0x00000001, 0x00000001, 0x00000003, 0x00000101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010000, 0x00010000, 0x00020000, 0x00020000, 0x00040100, 0x00050300, 0x00040000, 0x00030000, 0x00020001, 0x00606261, 0x00b2b5b6, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x006d6c6c, 0x00181715, 0x000b0000, 0x00341000, 0x00773814, 0x00b75818, 0x00c85809, 0x00cc5708, 0x00c45304, 0x00bc550c, 0x00b8550f, 0x00b8540e, 0x00b9530c, 0x00bd560d, 0x00bc5a15, 0x00ab5314, 0x00904d1a, 0x00421f00, 0x00130100, 0x000d0000, 0x001d0603, 0x004c291a, 0x00734a34, 0x00320700, 0x00400900, 0x00914820, 0x00ae5320, 0x00b84f13, 0x00bf5110, 0x00b5500c, 0x00b35414, 0x00ac501b, 0x00a8542a, 0x0078381a, 0x003c0800, 0x00300400, 0x00602908, 0x00994c1c, 0x00b85921, 0x00bc5115, 0x00bb4b0d, 0x00bd5011, 0x00ba5010, 0x00b8500e, 0x00ac5117, 0x009a582e, 0x00472008, 0x000f0300, 0x00010002, 0x00080000, 0x00230700, 0x00612807, 0x009f5020, 0x00ad4f17, 0x00b45017, 0x00b15320, 0x00994c23, 0x00642b14, 0x00280000, 0x00280000, 0x0076401e, 0x00a45520, 0x00a9501b, 0x00a85533, 0x005f220f, 0x00210804, 0x00020001, 0x00000304, 0x00090000, 0x003d0f00, 0x00914423, 0x00b3501e, 0x00b74c0f, 0x00b85010, 0x00b64e0b, 0x00b84a04, 0x00bf500c, 0x00b64c0b, 0x00ad5725, 0x00824e36, 0x003a1503, 0x00340500, 0x007f3c14, 0x00b95719, 0x00ca5910, 0x00c25709, 0x00b25511, 0x00984c24, 0x00431100, 0x000f0000, 0x00030004, 0x00050001, 0x00110000, 0x00552307, 0x00985027, 0x00ab5420, 0x00b14e13, 0x00b8500c, 0x00b7520f, 0x00b0581c, 0x008f4717, 0x005a2006, 0x00330000, 0x00591b08, 0x009c5233, 0x00ac531e, 0x00b34f0f, 0x00bb4f0d, 0x00ba4d0a, 0x00ba500f, 0x00b85010, 0x00b74a0f, 0x00bb4d14, 0x00bd5219, 0x00b2501a, 0x00964718, 0x006c3008, 0x00270000, 0x001d0000, 0x00481a07, 0x008a4c2d, 0x00a64f21, 0x00b55218, 0x00b45214, 0x00ab5420, 0x007b3e23, 0x00340500, 0x00200000, 0x00280000, 0x00642e0c, 0x009c5827, 0x00ac521c, 0x00b65017, 0x00bb5019, 0x00af501b, 0x00964f1f, 0x00582804, 0x00160000, 0x000f0000, 0x000a0000, 0x00200800, 0x006c3817, 0x00954818, 0x00b45015, 0x00bd5010, 0x00c15011, 0x00bc4c0e, 0x00b84e12, 0x00bd5317, 0x00bd5012, 0x00b64c0b, 0x00b44e0f, 0x00b45419, 0x00ac5520, 0x009c5025, 0x006c3415, 0x00340e00, 0x00140000, 0x000c0000, 0x001b0400, 0x00532b10, 0x008f4a23, 0x00b05724, 0x00b44c16, 0x00c05318, 0x00bc4f10, 0x00bc500f, 0x00b84f0c, 0x00b64d0c, 0x00b85014, 0x00aa4b16, 0x00a45328, 0x00742e09, 0x00400000, 0x006a2b08, 0x009c562e, 0x006c3212, 0x00200802, 0x00060003, 0x00030000, 0x00000000, 0x00000000, 0x00000200, 0x00000203, 0x00000103, 0x00000001, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020000, 0x00020000, 0x00020000, 0x00030000, 0x00040000, 0x00020000, 0x00020000, 0x00040000, 0x00040000, 0x00020000, 0x00020000, 0x00000000, 0x004c4c48, 0x00aaaca9, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00817e7f, 0x00242422, 0x00080000, 0x00280b00, 0x006e3414, 0x00b75b1b, 0x00c55507, 0x00c35002, 0x00c05004, 0x00bf5811, 0x00b3530d, 0x00b75810, 0x00b5580d, 0x00b35307, 0x00b2540d, 0x00ac551c, 0x007a3810, 0x002f0f00, 0x000c0000, 0x00100000, 0x0034140c, 0x006c3b1d, 0x00844d2c, 0x004d1e06, 0x002c0000, 0x005e2208, 0x00a35730, 0x00b25019, 0x00bb5110, 0x00b75310, 0x00b45210, 0x00c05a1e, 0x00ac4d18, 0x009b4d23, 0x00692d0d, 0x002c0400, 0x00340c00, 0x00652d10, 0x00994e25, 0x00b4531d, 0x00bb4e11, 0x00b84b10, 0x00b84c0f, 0x00b84b0c, 0x00b45118, 0x00a45425, 0x006d3617, 0x00240b02, 0x00080000, 0x00070000, 0x000c0000, 0x00361000, 0x00602704, 0x00a05524, 0x00ab541c, 0x00a84b10, 0x00a9521e, 0x0098512c, 0x00410c00, 0x001c0000, 0x00381000, 0x008a491f, 0x009c4a18, 0x00ab5228, 0x00924527, 0x003a1004, 0x000f0000, 0x00000000, 0x00060000, 0x00230100, 0x00692d14, 0x00aa4f1f, 0x00b84f10, 0x00b74d0c, 0x00b84e0c, 0x00b84f0d, 0x00b74c0d, 0x00b84e13, 0x00a74c1c, 0x00884d31, 0x00461500, 0x00602301, 0x00974818, 0x00be5819, 0x00c1540e, 0x00b6550e, 0x00a2541b, 0x0070391d, 0x001e0000, 0x000b0000, 0x00060000, 0x000b0000, 0x00320e00, 0x00854019, 0x00aa501d, 0x00b2511a, 0x00b45014, 0x00b14d0d, 0x00aa5214, 0x008e4b1b, 0x00592504, 0x002b0000, 0x00400b00, 0x008d3c1d, 0x00b05024, 0x00b2541a, 0x00b04d0d, 0x00bc5011, 0x00b94b0f, 0x00b94e15, 0x00b94e15, 0x00b94b10, 0x00ba5215, 0x00ae5318, 0x00934917, 0x00673411, 0x00280300, 0x002b0500, 0x004d1e06, 0x00904b28, 0x00a85025, 0x00ab4615, 0x00b85421, 0x00ab5427, 0x00864422, 0x00340d00, 0x001f0000, 0x002c0000, 0x0072341e, 0x009a4e23, 0x00ab5218, 0x00b65010, 0x00b84e0f, 0x00b24b17, 0x00a45028, 0x00663417, 0x00220500, 0x00120000, 0x00140000, 0x002a0500, 0x00643010, 0x00984e20, 0x00ac5119, 0x00b64d0f, 0x00c35314, 0x00b6450c, 0x00bb4c16, 0x00b94a16, 0x00bc4d19, 0x00bd4c14, 0x00b64c13, 0x00b0531d, 0x00a05323, 0x00753b17, 0x00461e04, 0x001d0300, 0x00120000, 0x00130000, 0x00280700, 0x00602b08, 0x00985024, 0x00b0521c, 0x00b34a10, 0x00ba5014, 0x00b4490c, 0x00bd5414, 0x00b44b09, 0x00b64a08, 0x00c05314, 0x00b34b0f, 0x00b8551d, 0x00ad501a, 0x00a55221, 0x006c2400, 0x00551700, 0x00844826, 0x00542610, 0x00140000, 0x00060008, 0x00030003, 0x00000001, 0x00000000, 0x00000200, 0x00000203, 0x00000005, 0x00000005, 0x00020004, 0x00020001, 0x00020001, 0x00020001, 0x00020001, 0x00020003, 0x00030003, 0x00030004, 0x00030004, 0x00020004, 0x00040005, 0x00000003, 0x00000003, 0x00040307, 0x00000003, 0x00000003, 0x0009090b, 0x00363532, 0x00a4a5a0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00928f90, 0x00313130, 0x00050000, 0x00180000, 0x00642f13, 0x00b1581b, 0x00c6590a, 0x00ca580b, 0x00c15208, 0x00b9540f, 0x00b3540f, 0x00b0540c, 0x00b5580c, 0x00b5560b, 0x00b55816, 0x00ae5928, 0x00602102, 0x00220400, 0x000c0000, 0x00180000, 0x00401708, 0x008c4f25, 0x00945427, 0x00633014, 0x00250000, 0x00310600, 0x008a5032, 0x00ac5522, 0x00b44f10, 0x00b5500c, 0x00bb530e, 0x00b64c0a, 0x00b55012, 0x00b05720, 0x008f491f, 0x004f2208, 0x00220000, 0x00330a00, 0x006d341b, 0x009f4e21, 0x00b4521c, 0x00b54c14, 0x00bb4d14, 0x00bc4e10, 0x00b95014, 0x00ad511d, 0x008f4822, 0x00391301, 0x00100000, 0x00050000, 0x00080000, 0x00130000, 0x002f0b00, 0x006b3410, 0x009e5626, 0x00af561c, 0x00ac5117, 0x00a34e1c, 0x0086431e, 0x00300700, 0x001d0000, 0x00531d00, 0x00965026, 0x00a75023, 0x00a0502b, 0x005a2512, 0x00200300, 0x00050000, 0x00050000, 0x00120000, 0x00451a05, 0x009c4d21, 0x00b35016, 0x00b44a0e, 0x00b94f10, 0x00b44a0c, 0x00bc5216, 0x00b64d15, 0x00a94f20, 0x007c3e1f, 0x00480f00, 0x00702400, 0x00a94f18, 0x00c05614, 0x00bc540c, 0x00b45a18, 0x00945120, 0x00431b08, 0x00100000, 0x00060000, 0x000a0000, 0x00150000, 0x00602e15, 0x00a14f20, 0x00b44f16, 0x00b64d14, 0x00b55015, 0x00ac5117, 0x009b511f, 0x0060300d, 0x00250200, 0x00290200, 0x005a1e0d, 0x00ab4b23, 0x00b94c14, 0x00af4a0c, 0x00ba5614, 0x00bd5012, 0x00bb4a10, 0x00ba4b15, 0x00b84c18, 0x00b54c14, 0x00b0521b, 0x00954c19, 0x006d380e, 0x00310a00, 0x00280400, 0x004d1c04, 0x008c4a2a, 0x00a44f24, 0x00b0501f, 0x00b45325, 0x00a54f28, 0x00854225, 0x00471400, 0x00210000, 0x00300700, 0x00703118, 0x0095451e, 0x00ae521c, 0x00b45010, 0x00bb4f0d, 0x00b44c10, 0x00af5126, 0x00874022, 0x00371300, 0x00100000, 0x001c0000, 0x002e0400, 0x006c3011, 0x00994e24, 0x00aa501c, 0x00b14c10, 0x00be5010, 0x00bc4b0b, 0x00bc4c12, 0x00b94b17, 0x00b94d1f, 0x00b34a1d, 0x00b24c20, 0x00aa4f24, 0x008a401b, 0x00592304, 0x002e0b00, 0x00180300, 0x000f0000, 0x00120000, 0x002d0800, 0x0068300b, 0x00994b1a, 0x00ac4d15, 0x00b84e12, 0x00bd5011, 0x00b84d10, 0x00b94f10, 0x00b64c0c, 0x00ba500f, 0x00bc4f0f, 0x00b74a0c, 0x00b84f10, 0x00b54d11, 0x00b65015, 0x00b2541c, 0x00a34e1e, 0x00672000, 0x006b3318, 0x00361002, 0x00110103, 0x00030005, 0x00020004, 0x00020001, 0x00000000, 0x00000000, 0x00000000, 0x00000001, 0x00020001, 0x00030001, 0x00030000, 0x00030000, 0x00030000, 0x00030000, 0x00040001, 0x00040001, 0x00040003, 0x00040003, 0x00030003, 0x00050106, 0x00000003, 0x00000004, 0x00010005, 0x00000004, 0x0006080c, 0x00292a2d, 0x009a9a98, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00080808, 0x00060606, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a3a4, 0x003c3d3b, 0x00030000, 0x00160000, 0x004f1e05, 0x00ad581d, 0x00c4590d, 0x00c45207, 0x00c4540c, 0x00b4500c, 0x00b75712, 0x00b95610, 0x00b45008, 0x00ba5710, 0x00b25417, 0x00a8542a, 0x00591c04, 0x001e0000, 0x000c0000, 0x00200200, 0x00562811, 0x009c5824, 0x009e581f, 0x006f3c1a, 0x00220000, 0x001d0100, 0x005c351c, 0x009d5525, 0x00b15113, 0x00bd5110, 0x00be4e08, 0x00ba4f08, 0x00b8530f, 0x00b15113, 0x00a65420, 0x007d401c, 0x00421500, 0x00200000, 0x00351100, 0x00703417, 0x00a4542c, 0x00aa4a18, 0x00b95014, 0x00be4e0f, 0x00b84a0a, 0x00b44d13, 0x00aa5628, 0x00582408, 0x001c0000, 0x00100100, 0x00040000, 0x00060000, 0x00140300, 0x00341200, 0x00743c1b, 0x00a65723, 0x00ae5115, 0x00b04e14, 0x00a65121, 0x006b2f15, 0x002e0000, 0x002c0000, 0x00662f10, 0x00974d24, 0x009d542c, 0x00763d25, 0x00351004, 0x00080000, 0x00020202, 0x00040000, 0x00260c00, 0x007c3916, 0x00af5424, 0x00b14a16, 0x00bb4d14, 0x00bb4b0d, 0x00b84c10, 0x00b64c18, 0x00ac5428, 0x006a2b0c, 0x00490a00, 0x008c3502, 0x00bd5517, 0x00c6570e, 0x00bd540c, 0x00ac5819, 0x00773c12, 0x00240500, 0x00080000, 0x00040000, 0x000c0000, 0x003a1100, 0x008e4c27, 0x00a94d19, 0x00b74d11, 0x00b94b0f, 0x00b65018, 0x00a0511f, 0x0068310c, 0x002b1000, 0x00120000, 0x00350b00, 0x00843d24, 0x00b44818, 0x00c44c0c, 0x00bb500c, 0x00b8500b, 0x00ba4c0c, 0x00be4e0f, 0x00bf4d12, 0x00b44912, 0x00ad511f, 0x009d5227, 0x00673110, 0x00370c00, 0x00300400, 0x00582107, 0x008e421d, 0x00ac5326, 0x00ac4e1c, 0x00a85020, 0x009e542f, 0x007a4025, 0x00391303, 0x00240000, 0x00400c00, 0x00783414, 0x009f4818, 0x00b04f13, 0x00b65210, 0x00b34c09, 0x00b74c13, 0x00b14f20, 0x00984a28, 0x005a240d, 0x00200400, 0x001a0100, 0x00441400, 0x00783718, 0x009f4f27, 0x00ac5121, 0x00b14f18, 0x00b54d10, 0x00bf500d, 0x00c04f0c, 0x00bd4c0c, 0x00b94e15, 0x00b04e1f, 0x00a6502a, 0x008c4428, 0x00622913, 0x00380f00, 0x001d0000, 0x00100000, 0x000f0000, 0x00140000, 0x003c1000, 0x0074320c, 0x009f4b17, 0x00b45116, 0x00b85011, 0x00b74d11, 0x00b74d11, 0x00b84d10, 0x00b94c0e, 0x00bc4c0e, 0x00bc4c0f, 0x00bc4d11, 0x00bc4f10, 0x00bb4f0d, 0x00ba4e0d, 0x00ba4d12, 0x00b94d17, 0x00c05822, 0x00a0481c, 0x005e240a, 0x00280700, 0x000a0000, 0x00030002, 0x00010004, 0x00030001, 0x00080000, 0x00080000, 0x00080000, 0x00060000, 0x00050000, 0x00050000, 0x00060000, 0x00060000, 0x00060000, 0x00060000, 0x00060000, 0x00070000, 0x00070000, 0x00060000, 0x00070000, 0x00040000, 0x00060101, 0x00020000, 0x00020204, 0x00000002, 0x0006090c, 0x0046474a, 0x00a1a1a3, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000f0f0f, 0x00141414, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00313131, 0x00494c4c, 0x00040100, 0x00110000, 0x00441800, 0x009c4c14, 0x00c05910, 0x00c45408, 0x00c6550c, 0x00b6510d, 0x00b55411, 0x00bc5411, 0x00b8500d, 0x00b8530f, 0x00b05116, 0x00a75429, 0x00571b02, 0x00170000, 0x000c0000, 0x00270902, 0x005f3016, 0x00a35a22, 0x00a55a20, 0x007c4521, 0x00210000, 0x00110000, 0x00381c07, 0x00985628, 0x00af5216, 0x00bc5010, 0x00be4e0a, 0x00bb5008, 0x00b8520b, 0x00b4500d, 0x00ac5318, 0x009c5024, 0x006c3214, 0x002d0c00, 0x00180000, 0x00441805, 0x00783c1f, 0x00a9562a, 0x00b3501a, 0x00bb4e10, 0x00bc4d0b, 0x00bb5212, 0x00ac511b, 0x0083421e, 0x003a1100, 0x00120000, 0x00080000, 0x00040204, 0x00040000, 0x00180500, 0x004a220c, 0x00924d24, 0x00b0551f, 0x00b34c10, 0x00ae4c17, 0x009e5431, 0x005f2610, 0x002a0000, 0x00360a00, 0x00713713, 0x00985a34, 0x00884d31, 0x00502414, 0x00110200, 0x00020100, 0x00030300, 0x00180600, 0x005c260a, 0x00a75631, 0x00af5023, 0x00b44e1a, 0x00b94f18, 0x00b54c16, 0x00b04c1e, 0x00a6512b, 0x00591c00, 0x004f1000, 0x00963a04, 0x00c25614, 0x00c6580d, 0x00b8550f, 0x009c511a, 0x00562400, 0x00130000, 0x00090000, 0x00080000, 0x00150000, 0x006c3514, 0x00a45122, 0x00b35018, 0x00b94c10, 0x00bc4c10, 0x00b25019, 0x00823c14, 0x00441800, 0x00130100, 0x00140000, 0x0051200d, 0x00994a29, 0x00c04e19, 0x00c84c0a, 0x00bc4e08, 0x00b85008, 0x00ba4d0a, 0x00ba4d0f, 0x00b74d11, 0x00b0531d, 0x009c5027, 0x00652a0c, 0x00320500, 0x00340800, 0x0063280f, 0x008e4421, 0x00ac4f20, 0x00b14e1b, 0x00ae5220, 0x00a15024, 0x00793c1a, 0x00441500, 0x00260000, 0x00481b08, 0x007b3414, 0x00a04819, 0x00b75214, 0x00b8500c, 0x00b04d0d, 0x00b2541a, 0x00b35628, 0x00954320, 0x006c2c12, 0x00400f00, 0x002f0900, 0x0050250a, 0x0083411c, 0x00a85428, 0x00ad4d1d, 0x00b44c18, 0x00b95018, 0x00b84f13, 0x00b44b09, 0x00b54c0b, 0x00b44f11, 0x00a74d18, 0x0091481f, 0x00703519, 0x00441c0b, 0x00240700, 0x00110000, 0x000d0000, 0x00130000, 0x001c0000, 0x004a1e06, 0x00783917, 0x00a44f22, 0x00b4501a, 0x00b5480d, 0x00b84b0e, 0x00b85013, 0x00b74f12, 0x00bb5013, 0x00bc4f10, 0x00bd4d10, 0x00bc4c0e, 0x00b84c0f, 0x00b94d0c, 0x00ba4d08, 0x00bb4e0b, 0x00bb4e10, 0x00be5114, 0x00c15415, 0x00b35724, 0x00683117, 0x00280800, 0x00100000, 0x000b0000, 0x000c0000, 0x00100000, 0x00190000, 0x00200000, 0x00220000, 0x00260600, 0x00290c00, 0x002c1000, 0x002b0e00, 0x002c0f00, 0x002d1000, 0x002a0c00, 0x00260900, 0x00230800, 0x001f0300, 0x00190000, 0x00130000, 0x000e0000, 0x000f0000, 0x00080000, 0x00060000, 0x00040000, 0x00030000, 0x00212020, 0x00373539, 0x00545458, 0x00838288, 0x00acacb2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00101010, 0x00252526, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005f6261, 0x00100d09, 0x000f0000, 0x003c1100, 0x00863a05, 0x00bf5a14, 0x00c35305, 0x00c85609, 0x00b9530c, 0x00b55110, 0x00b95014, 0x00bc5114, 0x00b7500d, 0x00b15414, 0x00a95826, 0x00612505, 0x00190000, 0x000e0000, 0x00200600, 0x005e3219, 0x00a05826, 0x00a45620, 0x00844520, 0x002d0200, 0x00110000, 0x00220600, 0x00945326, 0x00ac5215, 0x00b65014, 0x00ba4d0f, 0x00b9500c, 0x00b85009, 0x00b4500a, 0x00b15212, 0x00ae5721, 0x008f471d, 0x0058280c, 0x00240200, 0x001c0000, 0x00401603, 0x00854321, 0x00aa5324, 0x00b24d10, 0x00b74d09, 0x00b64f0c, 0x00aa4d11, 0x009c5426, 0x00602a0b, 0x00210000, 0x000f0000, 0x00050104, 0x00000004, 0x00060000, 0x00240800, 0x006b3014, 0x00a6552a, 0x00b4501a, 0x00b44f19, 0x00a85024, 0x008e4828, 0x0051240e, 0x00290400, 0x00411800, 0x007c4928, 0x00925338, 0x00683420, 0x00240b07, 0x00080000, 0x00070000, 0x00130000, 0x003d1000, 0x00915032, 0x00a2512c, 0x00aa5125, 0x00a94c1d, 0x00a84c1f, 0x00a84f2a, 0x00974c2c, 0x00471200, 0x005c2201, 0x00a14814, 0x00bf5817, 0x00bf5813, 0x00b05818, 0x00814418, 0x00370f00, 0x00110000, 0x00100000, 0x00100200, 0x003b1905, 0x00975127, 0x00ad5018, 0x00b84f14, 0x00ba4c10, 0x00bb4c13, 0x00af5320, 0x00703311, 0x00310c00, 0x00100000, 0x00270b00, 0x0072361c, 0x00a54f28, 0x00bc4c17, 0x00bf4808, 0x00b94903, 0x00b84c05, 0x00bc500f, 0x00b34e13, 0x00ac551e, 0x00944f20, 0x005e2b0e, 0x00320700, 0x00370800, 0x00622815, 0x00944420, 0x00ac5020, 0x00b34f1a, 0x00b04f1b, 0x009d4a1e, 0x00722c05, 0x00480d00, 0x00370100, 0x005d2204, 0x0089431e, 0x00ac521d, 0x00b45010, 0x00b95210, 0x00b45214, 0x00a54d1b, 0x009c4f27, 0x007b381c, 0x00591c08, 0x004c1200, 0x00581d01, 0x0078340f, 0x00994e1d, 0x00aa531f, 0x00ae4d16, 0x00b95016, 0x00b4480c, 0x00b74c10, 0x00ba5216, 0x00b04f14, 0x00a95319, 0x00984f1c, 0x00763e14, 0x0049260a, 0x00200c00, 0x00060000, 0x00080300, 0x000f0100, 0x00140000, 0x00340c00, 0x0060280c, 0x00884012, 0x00a4501c, 0x00b75427, 0x00b44c1f, 0x00b24716, 0x00b74e18, 0x00b75215, 0x00b34d0e, 0x00b54b0d, 0x00b94b0f, 0x00bb4c10, 0x00bb4e10, 0x00b9500e, 0x00ba4e0c, 0x00bd4e0c, 0x00bc500c, 0x00b44e08, 0x00bc5810, 0x00ba530a, 0x00b35c22, 0x00592a0a, 0x00210300, 0x00280500, 0x00361000, 0x00471e07, 0x00522207, 0x00642607, 0x00722c0a, 0x0079320f, 0x007d3710, 0x00823a10, 0x00843c0e, 0x00883e0a, 0x00884008, 0x00883e08, 0x00843d0a, 0x007f3c0a, 0x00783809, 0x006e3206, 0x00642d06, 0x005c2c08, 0x00481e00, 0x003a1700, 0x00280c00, 0x00180000, 0x00100000, 0x000b0000, 0x00080000, 0x00060103, 0x0008070b, 0x00212025, 0x0045454c, 0x0072727a, 0x00a2a2aa, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000f0f0f, 0x002f2f30, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007b7c7d, 0x00262320, 0x000b0000, 0x002e0900, 0x00702c00, 0x00b85c1c, 0x00c15408, 0x00c75507, 0x00bc530b, 0x00b7520f, 0x00b74f13, 0x00ba5216, 0x00b45010, 0x00b35516, 0x00ae5720, 0x007c370e, 0x00340e00, 0x00140000, 0x00140000, 0x0046250f, 0x00894c23, 0x009e5728, 0x008c4c29, 0x00421200, 0x00140000, 0x001d0000, 0x008f4b1f, 0x00aa5015, 0x00af5018, 0x00b34e13, 0x00b84f0d, 0x00b84d08, 0x00b64e09, 0x00b4500e, 0x00b15016, 0x00a04d1c, 0x00884723, 0x00502109, 0x00160000, 0x001e0000, 0x004c1800, 0x0089431e, 0x00ac531e, 0x00b35213, 0x00ae4c0d, 0x00af5015, 0x00a4521d, 0x008a481e, 0x004e1f04, 0x001e0100, 0x00060000, 0x00050408, 0x00040004, 0x00110000, 0x003a0f00, 0x00884724, 0x00aa5324, 0x00ad4f1c, 0x00a54e21, 0x009e5734, 0x007b4f37, 0x00462612, 0x00290800, 0x004d2308, 0x00783b21, 0x00622815, 0x002c0c05, 0x000f0000, 0x000d0000, 0x00140000, 0x002c0400, 0x00632c13, 0x00733010, 0x007e3510, 0x00823813, 0x00883d1a, 0x008c4124, 0x0075351b, 0x003c0c00, 0x00653113, 0x00a35324, 0x00b75c24, 0x00af571b, 0x00a05723, 0x005d2e0e, 0x001f0000, 0x00150000, 0x00100000, 0x00200700, 0x00704224, 0x00a45423, 0x00ae490c, 0x00b94c0e, 0x00bc4c0f, 0x00b84c14, 0x00ae5224, 0x00773b1c, 0x003c1400, 0x00180000, 0x00401800, 0x008c4825, 0x00ac5024, 0x00ba4c18, 0x00be4c0f, 0x00ba500c, 0x00b75310, 0x00af4e17, 0x00a54f1d, 0x00904c1e, 0x00602904, 0x00310500, 0x00390c00, 0x00662c18, 0x008f472c, 0x00a74c22, 0x00b25020, 0x00aa4c1b, 0x00943f12, 0x00702802, 0x004e0d00, 0x00541500, 0x0079370f, 0x009c4e25, 0x00aa501e, 0x00b55111, 0x00b44f0c, 0x00ad5016, 0x00a15121, 0x0084401d, 0x0064280f, 0x004d1400, 0x00581c07, 0x00723014, 0x0090461f, 0x00a8521e, 0x00b05217, 0x00b24d12, 0x00b74d12, 0x00bc4e10, 0x00b7480c, 0x00b44e15, 0x00b0511e, 0x009c4c1c, 0x00814016, 0x005b2a07, 0x00301100, 0x00140400, 0x00080300, 0x00040100, 0x000d0300, 0x00240a00, 0x00491e08, 0x0074381b, 0x00984c23, 0x00ac5418, 0x00b25011, 0x00b54c18, 0x00b6481c, 0x00b84c1f, 0x00b8501e, 0x00b45017, 0x00b04d10, 0x00b65014, 0x00b84e12, 0x00b85011, 0x00b9500e, 0x00b84f0c, 0x00b84c0b, 0x00bb4b0c, 0x00b94c0b, 0x00b85108, 0x00c15c10, 0x00bc580d, 0x00a85718, 0x00491a00, 0x00391400, 0x00642e0c, 0x007d4016, 0x008c481c, 0x00984d1c, 0x00a8541d, 0x00b45a20, 0x00b95c22, 0x00bc5b20, 0x00bc591e, 0x00bd581b, 0x00bd5c18, 0x00bc5b14, 0x00bb5914, 0x00bb5c17, 0x00ba5f1a, 0x00b75e1c, 0x00b05b1c, 0x00a8581c, 0x009f541d, 0x00904d1c, 0x0081441b, 0x00743d19, 0x00602f11, 0x004e2308, 0x003c1400, 0x00220100, 0x00100000, 0x000c0100, 0x00080000, 0x00040000, 0x00181418, 0x00403d43, 0x006c6d71, 0x00a0a1a4, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000b0b0b, 0x002c2c2e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9c9d, 0x003d3a39, 0x00060000, 0x001b0000, 0x00572000, 0x00a85722, 0x00bf580f, 0x00c55404, 0x00bf5408, 0x00b9530d, 0x00b65212, 0x00b45417, 0x00b05315, 0x00b15417, 0x00b35115, 0x009e4816, 0x00612506, 0x002a0400, 0x00120100, 0x001d0c00, 0x00542e10, 0x0085502d, 0x008d5132, 0x005c2814, 0x00150000, 0x001c0000, 0x00884017, 0x00a85017, 0x00a9521c, 0x00ad5018, 0x00b94f13, 0x00bb4a0a, 0x00b94e0a, 0x00b64f0c, 0x00b25012, 0x00ab501a, 0x00a35225, 0x00783714, 0x00340c00, 0x001d0000, 0x00230000, 0x004e1a04, 0x008b421c, 0x00a65121, 0x00ab4f1b, 0x00b1521c, 0x00ac4d17, 0x00a85424, 0x0080401a, 0x003f1300, 0x00140000, 0x00070000, 0x00030000, 0x00090000, 0x001e0500, 0x005a2e15, 0x00915028, 0x00904419, 0x00843e19, 0x00703518, 0x00583018, 0x003c200b, 0x00200300, 0x00270100, 0x00470e00, 0x00440a00, 0x00330900, 0x00260800, 0x00250800, 0x00290c00, 0x00310c00, 0x003c0f00, 0x00431000, 0x00451100, 0x00441000, 0x00481400, 0x00511802, 0x00430d00, 0x002c0200, 0x004d2003, 0x007b3a16, 0x008d451c, 0x00975327, 0x00844d28, 0x003e1c09, 0x00130000, 0x00140000, 0x00190000, 0x004b2007, 0x0093562f, 0x00a8521e, 0x00b34d10, 0x00bc4c0c, 0x00bd4d0e, 0x00b44a13, 0x00aa5021, 0x00884626, 0x004c1a00, 0x002c0100, 0x005c2806, 0x00a05229, 0x00af5020, 0x00b64b18, 0x00b74c15, 0x00b15114, 0x00a75119, 0x00a1552a, 0x00854422, 0x00551e04, 0x00300000, 0x00410e00, 0x006f3410, 0x0094481c, 0x00a95427, 0x00ad5228, 0x009f4a24, 0x007f3613, 0x005e1c00, 0x00541800, 0x006b2a04, 0x008d4219, 0x00a65224, 0x00ac501c, 0x00ad4c11, 0x00b24d10, 0x00aa5018, 0x008c4921, 0x0066361b, 0x00441e0c, 0x00330900, 0x005c1c04, 0x008c3d1c, 0x00ab4f21, 0x00b05017, 0x00b35211, 0x00b34f0d, 0x00b54a11, 0x00bb4d15, 0x00b84a0c, 0x00b85014, 0x00ab501d, 0x0090451c, 0x00693116, 0x003f1904, 0x001c0500, 0x000c0000, 0x000a0000, 0x00150500, 0x002a0e00, 0x00441a00, 0x006a300d, 0x008f4822, 0x00a6532a, 0x00ac5020, 0x00b45214, 0x00b64d0d, 0x00b84c10, 0x00bc4c17, 0x00ba4c19, 0x00b44917, 0x00af4b16, 0x00af5019, 0x00b05218, 0x00b05013, 0x00b24e0c, 0x00b54e0b, 0x00b74d0b, 0x00b84c0b, 0x00b84c10, 0x00ba4c0c, 0x00c05004, 0x00c3580a, 0x00bc5b14, 0x00914308, 0x00451000, 0x00663210, 0x009e5121, 0x00b1581b, 0x00b85815, 0x00bb5a10, 0x00bd5c0b, 0x00be5c08, 0x00c05b09, 0x00c15a09, 0x00c6570b, 0x00c7580d, 0x00c0570f, 0x00bf5811, 0x00c05910, 0x00c15a10, 0x00c15a0f, 0x00c15b0d, 0x00c15b0d, 0x00c15c10, 0x00bb570d, 0x00bc5b14, 0x00b55814, 0x00b55b1c, 0x00b0591f, 0x00a04c16, 0x00913f0a, 0x007a3306, 0x004f2000, 0x00341200, 0x00200400, 0x00100000, 0x000b0000, 0x00070000, 0x00181516, 0x00464748, 0x00808585, 0x00a4aca9, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00070707, 0x00232424, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00797879, 0x00555253, 0x00070403, 0x000b0000, 0x003b1300, 0x008a481e, 0x00ba5a15, 0x00c45504, 0x00c25408, 0x00bc5209, 0x00b85310, 0x00b25112, 0x00b05315, 0x00b05214, 0x00b44f11, 0x00b4541e, 0x0090421e, 0x00582309, 0x001e0600, 0x000c0000, 0x001f0600, 0x0045220e, 0x00633620, 0x005d3425, 0x001a0403, 0x00180000, 0x007c3711, 0x00a7501a, 0x00aa5420, 0x00ac5119, 0x00b84f15, 0x00bb4b0f, 0x00bd4d0e, 0x00b84d0e, 0x00b65013, 0x00b05017, 0x00ab501d, 0x00964a1f, 0x00693314, 0x00280300, 0x00150000, 0x001d0000, 0x00481400, 0x00814020, 0x00a2542c, 0x00ac5121, 0x00b5521a, 0x00af4e17, 0x00a25325, 0x00753c1c, 0x003b1a0a, 0x000d0000, 0x00040000, 0x00050000, 0x00130100, 0x00280800, 0x005e2807, 0x00591800, 0x004d0900, 0x004d0f00, 0x00421000, 0x00441800, 0x004c1d00, 0x00541f00, 0x00652100, 0x006a2404, 0x00692d0e, 0x006e3619, 0x006c3618, 0x006b3415, 0x006e3514, 0x006b300a, 0x006e3007, 0x006b2e04, 0x005c2602, 0x00582001, 0x005d1f00, 0x00551700, 0x00481300, 0x00440f00, 0x004c1000, 0x00541500, 0x00602804, 0x004d2003, 0x00230500, 0x00100000, 0x00100000, 0x00321003, 0x007d492b, 0x00a0582e, 0x00ac531c, 0x00b75114, 0x00ba4c0c, 0x00bc4d0c, 0x00b4490f, 0x00ac4d1c, 0x00964d29, 0x00571c00, 0x00430c00, 0x0078380f, 0x00aa5324, 0x00b14e1b, 0x00b24b17, 0x00b14e1b, 0x00a7531f, 0x00964f22, 0x00753c1c, 0x00471600, 0x00300000, 0x00420d00, 0x0074330f, 0x009c5024, 0x00a9521e, 0x00a84d1b, 0x00954014, 0x007a2e0b, 0x00682a0d, 0x00683015, 0x00784020, 0x00915432, 0x009d5732, 0x00a05028, 0x00a85124, 0x00ac5524, 0x009d491c, 0x007d3710, 0x004f2004, 0x002a0700, 0x002c0800, 0x0051200c, 0x008a3d1d, 0x00ae4e24, 0x00b64d14, 0x00b44b08, 0x00b8500d, 0x00b85010, 0x00b64c16, 0x00b34b19, 0x00b1511f, 0x00a04d1c, 0x007f3814, 0x00551f03, 0x00300900, 0x00140000, 0x00100000, 0x001e0800, 0x00311100, 0x00481c00, 0x006c330c, 0x0090491c, 0x00a85424, 0x00af5320, 0x00b04f1c, 0x00b24e19, 0x00b14b10, 0x00b64c10, 0x00b84e12, 0x00b94e14, 0x00b64f18, 0x00b2501c, 0x00ad5323, 0x00a95424, 0x00a85323, 0x00a85220, 0x00ac531c, 0x00b0551c, 0x00b45419, 0x00b45017, 0x00b54e18, 0x00ba5014, 0x00c45108, 0x00c2560c, 0x00b55b1c, 0x00742a00, 0x00430900, 0x00804017, 0x00b3591c, 0x00c25a0f, 0x00c95d09, 0x00c95c03, 0x00c55c00, 0x00c45d00, 0x00c55e00, 0x00c75e03, 0x00cc5d04, 0x00cc5e0b, 0x00c56015, 0x00c4601a, 0x00c46016, 0x00c45e10, 0x00c15a09, 0x00c25804, 0x00c65903, 0x00ca5d05, 0x00c85902, 0x00ca5c06, 0x00c35502, 0x00c35606, 0x00c55b0f, 0x00c05810, 0x00bd5510, 0x00b95a1a, 0x00a25620, 0x00783b0c, 0x005b2400, 0x00431800, 0x00280800, 0x00130000, 0x00080000, 0x00070401, 0x001c1d1c, 0x00565b59, 0x00969d99, 0x001f2020, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x001c1c1c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00767478, 0x001a1e21, 0x00000000, 0x001e0700, 0x00643014, 0x00b0581b, 0x00c35808, 0x00c45607, 0x00c05004, 0x00bc4e08, 0x00b84e0c, 0x00b65114, 0x00b04f13, 0x00b24f14, 0x00b45420, 0x00a8502b, 0x00894324, 0x004c2005, 0x00280d00, 0x000d0000, 0x000c0000, 0x00221009, 0x0032221b, 0x00130802, 0x00170000, 0x006c2e0b, 0x00a14e1d, 0x00ad531c, 0x00b04d15, 0x00b54f14, 0x00b84b11, 0x00be4d14, 0x00bb4a10, 0x00b74c10, 0x00b04e10, 0x00ac4f17, 0x00a85424, 0x00944e29, 0x004f1c05, 0x00170000, 0x000a0000, 0x00140000, 0x00441f0f, 0x00763e21, 0x00994c21, 0x00b65319, 0x00b24c0d, 0x00ac531e, 0x0098532a, 0x0060351c, 0x00240b00, 0x000c0000, 0x000c0000, 0x00140200, 0x00200100, 0x00451100, 0x00531000, 0x00641800, 0x00792b04, 0x00843803, 0x00904306, 0x00a14f11, 0x00ae5618, 0x00b75c20, 0x00b85c1c, 0x00b55816, 0x00b95c1c, 0x00b85c24, 0x00b75c23, 0x00b85719, 0x00bf5d1b, 0x00be5e19, 0x00ba5d1b, 0x00b45f1f, 0x00ac591d, 0x00ac531c, 0x00a14a13, 0x00944304, 0x00792f00, 0x00672400, 0x00581c00, 0x00491400, 0x00370a00, 0x00220000, 0x00170000, 0x00170000, 0x0039180e, 0x00854b2f, 0x009c5024, 0x00a64c18, 0x00b14e13, 0x00b84e0c, 0x00bc4c0c, 0x00ba4a0b, 0x00b44e17, 0x00a25128, 0x00682300, 0x005c1c00, 0x008e4518, 0x00ae4f18, 0x00b74e16, 0x00b44e1c, 0x00ab4f21, 0x00934a20, 0x00713b17, 0x00320c00, 0x00240000, 0x004e1800, 0x00843f19, 0x00a04c20, 0x00ab501e, 0x00a34816, 0x00903b0b, 0x007d3008, 0x00732e08, 0x00804020, 0x008c4f32, 0x0083482e, 0x00743c22, 0x006f3922, 0x007c482e, 0x0081472c, 0x00774027, 0x0058281a, 0x00371002, 0x00220300, 0x002c0500, 0x005c2100, 0x0093441d, 0x00af4e22, 0x00b9501c, 0x00b54e0d, 0x00b8500c, 0x00b44c0c, 0x00b04810, 0x00b34e1d, 0x00ab5129, 0x00894727, 0x00622e16, 0x003c1200, 0x00240200, 0x001a0000, 0x00230100, 0x003c1201, 0x00582108, 0x00803817, 0x009d4820, 0x00b35424, 0x00b6501c, 0x00b24913, 0x00b44a10, 0x00b64c13, 0x00b44c14, 0x00b34d18, 0x00b34c18, 0x00b34c15, 0x00ac4c13, 0x00a44e16, 0x00994f19, 0x008c481b, 0x00844119, 0x00883f20, 0x00883c20, 0x00873d1e, 0x0088401c, 0x008a4117, 0x00924212, 0x00a44614, 0x00b54c14, 0x00c65714, 0x00c15a19, 0x00a55422, 0x00591700, 0x00551800, 0x00934c1a, 0x00bb5c14, 0x00cc6009, 0x00cc5d01, 0x00cc5f02, 0x00cb6108, 0x00cb640c, 0x00cc670c, 0x00cb680b, 0x00c96708, 0x00c4660c, 0x00bd641b, 0x00b45c18, 0x00b0570f, 0x00b3580b, 0x00bb5d0b, 0x00c3610a, 0x00c86308, 0x00cc6407, 0x00ca6103, 0x00ca5f03, 0x00ca5d04, 0x00c75b04, 0x00c65908, 0x00c35808, 0x00bf5408, 0x00c0580c, 0x00c15a10, 0x00be5e19, 0x00af581f, 0x008c4418, 0x005c2405, 0x00370d00, 0x001f0500, 0x000a0000, 0x00030000, 0x000d0d0c, 0x00383a38, 0x007f807e, 0x008c8c89, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00161617, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00949599, 0x0031383e, 0x00000406, 0x00100000, 0x00471e08, 0x00a35724, 0x00ba5814, 0x00c0580f, 0x00bb5008, 0x00b55012, 0x00b15019, 0x00b05420, 0x00a8501e, 0x00a65120, 0x009f4c20, 0x009e4f2d, 0x00985538, 0x007a4b30, 0x004b2c1a, 0x001a0907, 0x00050001, 0x00060000, 0x00040000, 0x00040000, 0x00180300, 0x005e280a, 0x009b4d23, 0x00b0521b, 0x00b14b0f, 0x00b54d11, 0x00b54a11, 0x00bb4d17, 0x00b74911, 0x00b64c11, 0x00b55014, 0x00b15014, 0x00a84d15, 0x00a44e21, 0x00844224, 0x00300e03, 0x000e0000, 0x000b0000, 0x000e0000, 0x00351100, 0x00743c1d, 0x009e4c1d, 0x00ab511e, 0x00964718, 0x0085451e, 0x00633219, 0x00381200, 0x00240100, 0x00320f00, 0x003c1400, 0x00623014, 0x007c3c18, 0x00a05328, 0x00b55d2e, 0x00b3551d, 0x00b85a14, 0x00c16313, 0x00bc590b, 0x00bc5608, 0x00c45d0e, 0x00c05706, 0x00c85c06, 0x00c15500, 0x00c35909, 0x00ca5f11, 0x00c25302, 0x00cc5f0b, 0x00c55602, 0x00c35804, 0x00bd5b06, 0x00bf5e0b, 0x00be5a10, 0x00bd590f, 0x00bd5a0a, 0x00ba5e15, 0x00b4612c, 0x00a0542b, 0x008e4a1f, 0x00743710, 0x00572004, 0x00401100, 0x00300a00, 0x00300700, 0x00602509, 0x00813b14, 0x0098481c, 0x00a14b18, 0x00af5119, 0x00b44f12, 0x00b84c0f, 0x00b85018, 0x00ac5124, 0x007b2902, 0x00782a00, 0x00a35120, 0x00ac4c16, 0x00b04e1a, 0x00a24c21, 0x008a401b, 0x005e2504, 0x002f0000, 0x002e0700, 0x00502204, 0x0086441e, 0x00a55123, 0x00af4d1b, 0x00aa4613, 0x00993e0e, 0x008f3e13, 0x00904d28, 0x00895030, 0x007f4a30, 0x005e2d17, 0x003d1000, 0x002b0200, 0x00200000, 0x00280a00, 0x003f1e0e, 0x00250600, 0x00160000, 0x00170000, 0x002c0800, 0x00602e08, 0x00984c1c, 0x00af4d18, 0x00b74b14, 0x00b6490e, 0x00b44c0a, 0x00b75313, 0x00af4b15, 0x00aa4b1c, 0x00a24e28, 0x007f3c1f, 0x004a1c08, 0x00260200, 0x001c0000, 0x002c0400, 0x00401403, 0x00612c16, 0x008c4528, 0x00a44e2b, 0x00b04c21, 0x00b54a18, 0x00b84912, 0x00bb4910, 0x00bc4a10, 0x00b94b10, 0x00b74d12, 0x00b14f17, 0x00ac5020, 0x00a44e23, 0x009c4920, 0x008f451c, 0x00783e14, 0x00603006, 0x004c2100, 0x00421600, 0x003e0900, 0x003f0200, 0x003e0100, 0x00410400, 0x004d0f00, 0x006a2100, 0x00943907, 0x00b54f14, 0x00c05413, 0x00b45419, 0x0086411c, 0x00450c00, 0x00703006, 0x00a95c21, 0x00c2610e, 0x00cc6103, 0x00cc6202, 0x00cc6103, 0x00ca6008, 0x00c8630d, 0x00c36712, 0x00bc6611, 0x00b4640f, 0x00ae6013, 0x009f5414, 0x00904404, 0x008a3600, 0x00983f00, 0x00b15600, 0x00c4660b, 0x00ca690d, 0x00c96507, 0x00cc6908, 0x00cc6302, 0x00cc6809, 0x00cc6409, 0x00c75e03, 0x00c96008, 0x00c65d08, 0x00c55904, 0x00c35200, 0x00cc5c08, 0x00bf540c, 0x00b8581b, 0x00ac5c2c, 0x0085441f, 0x0054230a, 0x002d0c00, 0x00150000, 0x000a0000, 0x00050100, 0x0023221f, 0x006c6967, 0x00b2b0ac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00161617, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b1b8ba, 0x00585e60, 0x00070604, 0x000c0000, 0x00341000, 0x007b3e17, 0x00ac5c28, 0x00b6591f, 0x00aa4f17, 0x009b4d23, 0x008c4924, 0x00864420, 0x00804220, 0x00783d1e, 0x0071391c, 0x00703c25, 0x0070432f, 0x006b4736, 0x0064493d, 0x003a2622, 0x000d0000, 0x00080000, 0x00080000, 0x00050000, 0x00100000, 0x00441603, 0x009a542f, 0x00a94e16, 0x00b84f0f, 0x00bc4e10, 0x00ba4d12, 0x00b04b15, 0x00b2501a, 0x00b25018, 0x00b04b10, 0x00b64c10, 0x00b74d12, 0x00ac4a14, 0x00a04f25, 0x0073381f, 0x00260000, 0x000e0000, 0x00080000, 0x000c0000, 0x00281001, 0x00653520, 0x007c452c, 0x005a2b11, 0x00401200, 0x00380700, 0x00470c00, 0x006c2800, 0x00934714, 0x00a45218, 0x00ba6224, 0x00b85c1c, 0x00b95814, 0x00be5609, 0x00c85d09, 0x00c05a00, 0x00c15e03, 0x00c26610, 0x00c0600d, 0x00cc630f, 0x00cc6009, 0x00cc6105, 0x00cc6808, 0x00c46200, 0x00cc6908, 0x00cc650c, 0x00cc650c, 0x00c96106, 0x00c66204, 0x00c46500, 0x00c26602, 0x00c46308, 0x00c46008, 0x00c85c04, 0x00c65a06, 0x00c0580f, 0x00bf5815, 0x00bc571a, 0x00b85820, 0x00b25624, 0x009f4c1d, 0x007c350d, 0x00581b00, 0x00430800, 0x003c0200, 0x00521800, 0x00743613, 0x00964e24, 0x00a3501f, 0x00ab4b18, 0x00b4501d, 0x00af4c1f, 0x009c3c10, 0x00993b0a, 0x00aa4d1c, 0x00a85020, 0x00954820, 0x00763c20, 0x00431700, 0x00230000, 0x00340800, 0x00672c06, 0x00984d22, 0x00a85220, 0x00ad4e18, 0x00b34c14, 0x00b7511c, 0x00a84c1f, 0x009c4f28, 0x0081472c, 0x005c3020, 0x002f1008, 0x00140000, 0x000c0000, 0x000c0000, 0x000a0000, 0x00080000, 0x000a0000, 0x000c0000, 0x00130000, 0x00340f02, 0x006c361a, 0x00964d21, 0x00ac5015, 0x00b85010, 0x00bb4d0f, 0x00b74a0d, 0x00b64c11, 0x00b1501a, 0x00a44c20, 0x00954e2e, 0x0067321f, 0x002d0600, 0x001f0000, 0x00280300, 0x00491600, 0x00763414, 0x00994b25, 0x00ab5026, 0x00b44c20, 0x00bb4b1c, 0x00b74814, 0x00b94b11, 0x00bc4f10, 0x00b84c0d, 0x00b8470d, 0x00ba4f16, 0x00b3541c, 0x00a14e1c, 0x00964d23, 0x007d4122, 0x00582919, 0x00331005, 0x001c0100, 0x000f0000, 0x000a0000, 0x000d0000, 0x00150000, 0x00220000, 0x002e0000, 0x00440500, 0x005c1a00, 0x00813604, 0x00a14408, 0x00be5714, 0x00c25713, 0x00b25820, 0x00582504, 0x003b1000, 0x00884815, 0x00b8631c, 0x00c86308, 0x00ca5e00, 0x00c55d00, 0x00cc6708, 0x00c85d01, 0x00c4620f, 0x00b86820, 0x00a05e1e, 0x00915720, 0x006c3403, 0x00501600, 0x00672400, 0x00a44e00, 0x00cb6e0f, 0x00c66702, 0x00c26200, 0x00c86a0f, 0x00c7660a, 0x00cc6401, 0x00cc6400, 0x00cc6808, 0x00c06000, 0x00cc6c09, 0x00cc6a08, 0x00c46000, 0x00ca6407, 0x00c76000, 0x00c55b00, 0x00cc5a06, 0x00c85508, 0x00c25910, 0x00b55818, 0x00ac5b28, 0x00773510, 0x00401000, 0x00240500, 0x000c0000, 0x00040000, 0x0014100c, 0x00585550, 0x00b0b0ac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00030303, 0x00181919, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00808487, 0x00262320, 0x000a0000, 0x001b0000, 0x00491f06, 0x00905737, 0x00965029, 0x00803c17, 0x00501d03, 0x00411803, 0x00370f00, 0x002e0900, 0x002c0800, 0x002a0c00, 0x00280c00, 0x00240c01, 0x00200a01, 0x0024120c, 0x0022140f, 0x00180d0b, 0x000c0404, 0x00040000, 0x00030000, 0x000c0000, 0x002e0c00, 0x008c4f32, 0x00ab501c, 0x00b84e0c, 0x00b74909, 0x00b4490c, 0x00b14f18, 0x00ac4d18, 0x00b04d15, 0x00b24910, 0x00b84c0f, 0x00ba4d12, 0x00b04a13, 0x00ac5121, 0x00944a27, 0x005c2812, 0x001a0000, 0x00070000, 0x00020000, 0x00080000, 0x00200000, 0x002d0000, 0x00330600, 0x004c1800, 0x00773411, 0x00a5562a, 0x00b35920, 0x00b75510, 0x00bf590c, 0x00c15c09, 0x00ba5403, 0x00c65f0c, 0x00c95e05, 0x00cc6507, 0x00cc6805, 0x00c96604, 0x00c1660b, 0x00c56810, 0x00cc6509, 0x00cc6204, 0x00cc6606, 0x00c66604, 0x00c36904, 0x00c16908, 0x00c56810, 0x00c4660e, 0x00ca6808, 0x00cb6905, 0x00c86a01, 0x00c76902, 0x00c96706, 0x00cc6407, 0x00cc6103, 0x00cc6002, 0x00cc5f04, 0x00cc5c08, 0x00c65809, 0x00c85a11, 0x00c45912, 0x00bd5815, 0x00b75e1f, 0x00a95a24, 0x008a4018, 0x00682704, 0x00400500, 0x003b0100, 0x004f1300, 0x00793613, 0x009d4d26, 0x00a85026, 0x00a84e21, 0x00a74c1e, 0x00a54d1e, 0x00a04f24, 0x008e4522, 0x0062270b, 0x002e0000, 0x00200000, 0x00441a00, 0x0078411c, 0x00a15223, 0x00ab4f19, 0x00b3521b, 0x00ae4c15, 0x00b2501b, 0x00a44919, 0x00974821, 0x00733418, 0x003d1101, 0x001a0000, 0x000a0000, 0x00040001, 0x00080405, 0x00050100, 0x00080000, 0x000f0500, 0x00110800, 0x00140200, 0x003c1809, 0x00753e27, 0x00994f2c, 0x00aa5220, 0x00b35012, 0x00b54c08, 0x00b94d0c, 0x00b64c11, 0x00ad4d1c, 0x00a04c24, 0x008a4826, 0x004e1a02, 0x00260000, 0x00260000, 0x003d1200, 0x00693517, 0x0096502c, 0x00a65328, 0x00ac4d1c, 0x00b74d19, 0x00bc4a14, 0x00b9430b, 0x00c04b10, 0x00bc4c10, 0x00b44b0c, 0x00b34c10, 0x00b5501a, 0x00aa4d1c, 0x0095481d, 0x00844620, 0x004d1d00, 0x002c0800, 0x00150000, 0x00100101, 0x00080000, 0x00060000, 0x000a0000, 0x00100000, 0x00200000, 0x00441408, 0x006e301a, 0x00944d2c, 0x00a25628, 0x00a8531b, 0x00b04c0a, 0x00c05814, 0x00bc5716, 0x009f4c18, 0x00390a00, 0x00572c08, 0x009e581c, 0x00bc6112, 0x00c35c00, 0x00cc6200, 0x00c76105, 0x00c05e09, 0x00c86615, 0x00b55f18, 0x00965521, 0x00703b10, 0x00380400, 0x003c0600, 0x00733608, 0x00ab6326, 0x00c36a16, 0x00c05e00, 0x00ca6901, 0x00ca6b04, 0x00c06407, 0x00c96c10, 0x00c45e00, 0x00cc6808, 0x00c96c0f, 0x00c86c0c, 0x00c76803, 0x00c66700, 0x00c56806, 0x00c46807, 0x00c06302, 0x00cc6d0f, 0x00c25100, 0x00c65100, 0x00c85603, 0x00c85c0f, 0x00b95512, 0x00b66026, 0x00954e21, 0x00562204, 0x00240400, 0x00120000, 0x00060000, 0x000c0806, 0x00464844, 0x00b0b4b1, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00181819, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009ea1a2, 0x00454648, 0x00080404, 0x00070000, 0x001a0700, 0x00391f11, 0x00270500, 0x00230200, 0x00281308, 0x00403129, 0x0064554d, 0x007f716b, 0x0090847e, 0x00978c88, 0x008f8681, 0x00837d78, 0x0075716e, 0x00555250, 0x00302f2d, 0x00131414, 0x00030405, 0x00000304, 0x00000407, 0x00020000, 0x00150000, 0x0075442e, 0x00a54e1f, 0x00b54c0e, 0x00bb5413, 0x00b14c0e, 0x00b35018, 0x00b44e18, 0x00b1460c, 0x00be5114, 0x00b85013, 0x00b04c10, 0x00b04c17, 0x00ad4f1e, 0x00a45125, 0x008c502f, 0x002f1301, 0x00070000, 0x00050100, 0x00110300, 0x00260000, 0x00551800, 0x008b4011, 0x00a55015, 0x00b85714, 0x00c45d18, 0x00b9540f, 0x00bc5a0f, 0x00c46310, 0x00c66810, 0x00c3680e, 0x00c3660d, 0x00c46410, 0x00c56109, 0x00c96402, 0x00c96601, 0x00c6680c, 0x00c96a0d, 0x00cc6300, 0x00cc6600, 0x00c96804, 0x00c06606, 0x00be6c14, 0x00b76818, 0x00b7681c, 0x00bc6a19, 0x00c46809, 0x00c06100, 0x00c86806, 0x00c86808, 0x00cb6509, 0x00cc6506, 0x00cc6501, 0x00ca6600, 0x00c86700, 0x00c66702, 0x00c96609, 0x00c9640c, 0x00c45e08, 0x00bc5805, 0x00ba580b, 0x00bc5c17, 0x00be5c1e, 0x00b65821, 0x00a4501e, 0x00702b00, 0x003e0500, 0x00340000, 0x00521800, 0x007c3d1e, 0x00985428, 0x0099582b, 0x008c522a, 0x00673415, 0x003e1000, 0x002b0000, 0x00390400, 0x00662810, 0x00914b24, 0x00a65322, 0x00b15019, 0x00b55017, 0x00ac4c14, 0x00ac5220, 0x009e4f23, 0x00783512, 0x00471300, 0x001f0000, 0x00100000, 0x00090000, 0x00090004, 0x000d0607, 0x001b100d, 0x00291b13, 0x00342014, 0x00372010, 0x00240c00, 0x00512c14, 0x008a472a, 0x00a7512c, 0x00af5325, 0x00b05119, 0x00b05010, 0x00b1500d, 0x00b74f12, 0x00b3511d, 0x00964923, 0x00743a1e, 0x00371100, 0x001f0000, 0x00330000, 0x005f2001, 0x00934c28, 0x00a35329, 0x00ac5327, 0x00a84c1c, 0x00a64c17, 0x00b0521a, 0x00b65318, 0x00b84e12, 0x00ba480d, 0x00b8470d, 0x00b84e14, 0x00b0501e, 0x00a04f24, 0x008e4c2a, 0x00612f16, 0x00240200, 0x00110000, 0x00080000, 0x00080000, 0x000b0000, 0x000c0000, 0x00110000, 0x00310900, 0x005c2105, 0x008c4123, 0x00a24e2a, 0x00a45128, 0x00a64f20, 0x00ab4c11, 0x00b7500d, 0x00c0500c, 0x00c55918, 0x00b45921, 0x00782d00, 0x003b0000, 0x00804415, 0x00b16218, 0x00c2650b, 0x00c45c00, 0x00c96007, 0x00c56010, 0x00bc611c, 0x00a75920, 0x0084471c, 0x00481802, 0x00280000, 0x00430500, 0x0090460c, 0x00b6631f, 0x00bc6114, 0x00c6660e, 0x00c96708, 0x00c56401, 0x00c56503, 0x00c66707, 0x00bf6307, 0x00c66d17, 0x00b9620e, 0x00b35a06, 0x00c46b14, 0x00c26506, 0x00c26705, 0x00bc680a, 0x00a95800, 0x00c36d18, 0x00c0640e, 0x00cc6a0d, 0x00cc670c, 0x00c85c0d, 0x00c0560c, 0x00c15b0d, 0x00b9570c, 0x00b85c19, 0x00a0501c, 0x006c3210, 0x00250000, 0x00140401, 0x00020001, 0x00030402, 0x003d413e, 0x009ba09e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00161717, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b1af, 0x005c5d5f, 0x000c1012, 0x00000004, 0x00040408, 0x00030102, 0x00181210, 0x00574e4b, 0x009b928f, 0x00c4c1c0, 0x00cacacc, 0x00cccccc, 0x00c8c8ca, 0x00c5c5c7, 0x00c8c9cb, 0x00cbcccc, 0x00cbcccc, 0x00c0c4c4, 0x00c9cccc, 0x00c4c7c8, 0x00acb0b0, 0x00818686, 0x003c4040, 0x00040b0c, 0x00000000, 0x00090000, 0x00502d20, 0x00954c24, 0x00ac4e17, 0x00b05013, 0x00ac4b0d, 0x00b34d14, 0x00b14710, 0x00bd4f13, 0x00b7490b, 0x00ad4508, 0x00b24c14, 0x00b4501c, 0x00ab4e1f, 0x00a25327, 0x00915534, 0x005d3a26, 0x00210a00, 0x00110000, 0x00371400, 0x007c3e1f, 0x00a45424, 0x00b45718, 0x00c75e15, 0x00c85707, 0x00c65403, 0x00c96116, 0x00c8681c, 0x00c06614, 0x00b86513, 0x00ac6218, 0x00ad641d, 0x00ad5a14, 0x00c56a1c, 0x00c86508, 0x00c46100, 0x00c36206, 0x00c56205, 0x00c86000, 0x00cc6c04, 0x00c36402, 0x00bd6810, 0x00a45913, 0x00864105, 0x00733400, 0x008e4907, 0x00bf6a12, 0x00cc6c0c, 0x00c76208, 0x00c96108, 0x00cc6108, 0x00cb6205, 0x00c86401, 0x00c56600, 0x00c26800, 0x00c26800, 0x00c46500, 0x00c66400, 0x00c86401, 0x00c86404, 0x00c76208, 0x00c45d08, 0x00c45808, 0x00c0560d, 0x00b85916, 0x00b5612b, 0x009a542f, 0x0064240a, 0x003a0000, 0x003a0600, 0x00582600, 0x00683b14, 0x00401900, 0x002e0700, 0x00280000, 0x004b1506, 0x00823e27, 0x00a45330, 0x00ac501f, 0x00b04a11, 0x00b84b0e, 0x00b0470c, 0x00ae4c18, 0x00a85428, 0x00692806, 0x00340500, 0x00190000, 0x00100000, 0x00050000, 0x00030104, 0x000b090c, 0x00181414, 0x00251b16, 0x002d1d16, 0x00372017, 0x003f2417, 0x00462a1a, 0x00663d28, 0x0088462b, 0x009c4b28, 0x00a65129, 0x00a65123, 0x00a2501b, 0x00a6541e, 0x00a6521e, 0x0094481d, 0x00672c10, 0x00280000, 0x001c0000, 0x00340d00, 0x00723710, 0x009d5020, 0x00ac5120, 0x00ae4b19, 0x00b04a18, 0x00b4511c, 0x00b2551b, 0x00ac5114, 0x00a94d0d, 0x00ac4c0c, 0x00b84f14, 0x00b34a14, 0x00aa4a1a, 0x00a04f28, 0x00793e20, 0x003a1000, 0x00150000, 0x000d0000, 0x00040102, 0x00000000, 0x000c0200, 0x000e0000, 0x00140000, 0x004d2309, 0x008c4926, 0x00a04b20, 0x00a94616, 0x00b7501c, 0x00b04e18, 0x00ad4a10, 0x00b84e0c, 0x00c4540d, 0x00ca540c, 0x00be5414, 0x00a25325, 0x00480600, 0x005f1b00, 0x009f541a, 0x00ba6310, 0x00c06103, 0x00c45f04, 0x00c15c0b, 0x00b9601e, 0x00a55828, 0x00733816, 0x00310400, 0x00200000, 0x00340000, 0x0099511f, 0x00be6620, 0x00c66314, 0x00c8610a, 0x00c66006, 0x00c56103, 0x00c56505, 0x00c66707, 0x00c4680c, 0x00bd6813, 0x00b46921, 0x00904701, 0x00964300, 0x00bd6310, 0x00c5680b, 0x00c5690a, 0x00b8680b, 0x009e5000, 0x00a05006, 0x00bd6a1e, 0x00c46c10, 0x00c76a0b, 0x00c05c08, 0x00c75d0d, 0x00c35a05, 0x00c35804, 0x00c05405, 0x00c25d19, 0x00a8541f, 0x00783a17, 0x002b0900, 0x000f0000, 0x00030000, 0x00010302, 0x00494d50, 0x00b2b6b8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00151516, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9792, 0x0044403c, 0x00080808, 0x00000104, 0x00000408, 0x0012191d, 0x00656c70, 0x00a8afb3, 0x00c3c7ca, 0x00c0c4c7, 0x00c5c8cc, 0x00c7c9cc, 0x00c8cbcc, 0x00c8cbcc, 0x00c9cccc, 0x00cbcccc, 0x00c8c8cc, 0x00c4c4c8, 0x00cccccc, 0x00c4c4c6, 0x00cccccc, 0x00cac8c9, 0x00c1c0bf, 0x00c5c4c3, 0x00a09f9d, 0x00535152, 0x0009050a, 0x00140000, 0x00653318, 0x009a5228, 0x00ab5421, 0x00b04f16, 0x00b54f14, 0x00b64c10, 0x00b5480c, 0x00b5480c, 0x00bb4e11, 0x00b85014, 0x00ab4810, 0x00a75020, 0x00904d2c, 0x005f2912, 0x00300000, 0x00390500, 0x006c3008, 0x00a05421, 0x00b6591c, 0x00bd5510, 0x00c0550e, 0x00c6580d, 0x00cc5e0d, 0x00cc5f0f, 0x00b8540b, 0x00a14500, 0x00b66015, 0x00965010, 0x003a0c00, 0x002d0000, 0x00490800, 0x00a85518, 0x00c46411, 0x00c86206, 0x00cb660e, 0x00ca650b, 0x00c86200, 0x00c46100, 0x00c2660a, 0x00aa580d, 0x006c2800, 0x00330000, 0x002f0000, 0x005f2900, 0x00b3641c, 0x00bd5d05, 0x00cb5f08, 0x00cc5e08, 0x00cc5e08, 0x00cc6008, 0x00c76306, 0x00c26503, 0x00c16700, 0x00c46700, 0x00ca6700, 0x00cc6800, 0x00cb6600, 0x00c56200, 0x00c56300, 0x00c96402, 0x00cb6205, 0x00c65e06, 0x00bf5e0b, 0x00b45308, 0x00bd5517, 0x00bc5b25, 0x00924517, 0x00541b00, 0x00280400, 0x001e0200, 0x00280400, 0x004e200b, 0x007f3f24, 0x009c4f2c, 0x00ac5123, 0x00b24e19, 0x00b74c13, 0x00bc4c10, 0x00b54405, 0x00ba4f14, 0x00ad511f, 0x009b5027, 0x00875236, 0x00442310, 0x00140200, 0x00030000, 0x00000403, 0x00000406, 0x0004080a, 0x00141415, 0x00282323, 0x00332b2a, 0x00302424, 0x00281817, 0x00220c09, 0x00150000, 0x001c0000, 0x00350c00, 0x0053200c, 0x007b3e29, 0x0094553b, 0x008f5434, 0x00774826, 0x00482000, 0x001e0000, 0x00240000, 0x00390600, 0x007c3d1f, 0x00a05825, 0x00a85117, 0x00b64d15, 0x00bb4a11, 0x00b74910, 0x00b3490d, 0x00af4a0c, 0x00ae4d0c, 0x00ae510f, 0x00af5112, 0x00ac4c16, 0x00ab5024, 0x009c4f2c, 0x00682e14, 0x00260400, 0x000d0000, 0x000c0204, 0x00020003, 0x00000003, 0x00040000, 0x00120000, 0x00381300, 0x0071391c, 0x009a502b, 0x00ac5022, 0x00b44b17, 0x00b94c12, 0x00ba4c10, 0x00b4490d, 0x00b84d0e, 0x00bc500b, 0x00bc4d04, 0x00c75408, 0x00bc5919, 0x006f2e0c, 0x00340000, 0x00883e08, 0x00b35e18, 0x00c0610e, 0x00bc5800, 0x00c2600b, 0x00b86016, 0x009d5523, 0x00693314, 0x00250000, 0x001c0000, 0x00380800, 0x00925228, 0x00b56325, 0x00ba590f, 0x00c35908, 0x00cc640e, 0x00cc6407, 0x00c46000, 0x00c46403, 0x00c16509, 0x00b8620f, 0x00b26721, 0x00703804, 0x00642800, 0x00964802, 0x00bf6410, 0x00c86808, 0x00c76805, 0x00c46c0d, 0x00b46310, 0x00762c00, 0x00a05718, 0x00b46811, 0x00c57210, 0x00cc6c09, 0x00c86102, 0x00cc650f, 0x00c45603, 0x00cb5703, 0x00c75404, 0x00c85d14, 0x00ab541a, 0x00733c17, 0x00250700, 0x000d0000, 0x0009050a, 0x00000004, 0x005c6063, 0x001f1f1f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00141415, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00948d8c, 0x00403a38, 0x00080402, 0x00000000, 0x00101315, 0x004d5456, 0x00989fa3, 0x00bcc5c8, 0x00bec7ca, 0x00c2cacc, 0x00c7cccc, 0x00c9cccc, 0x00c8cbcc, 0x00c8cacc, 0x00c8cacc, 0x00c9cacc, 0x00c9cacc, 0x00cbcccc, 0x00cccccc, 0x00cacaca, 0x00c9c8c8, 0x00c8c7c5, 0x00cbc8c7, 0x00cccbc8, 0x00ccc8c6, 0x00c4c0be, 0x00bbb9ba, 0x0098999d, 0x003a3231, 0x00210400, 0x004b1900, 0x008f4a24, 0x00a45022, 0x00a4430d, 0x00b95115, 0x00b84d10, 0x00bc5115, 0x00b04a11, 0x00ac4a14, 0x00a8501d, 0x008c4017, 0x00581d01, 0x00320000, 0x00551500, 0x008c401a, 0x00b15b21, 0x00b8550f, 0x00c65808, 0x00cc5b08, 0x00c65706, 0x00cc600f, 0x00c65c06, 0x00c5600f, 0x00ac500c, 0x008e3800, 0x00b96925, 0x00955722, 0x001e0000, 0x00170000, 0x00450e00, 0x00af632c, 0x00c46517, 0x00c75f05, 0x00c96109, 0x00c86006, 0x00c76201, 0x00c66403, 0x00bf640a, 0x00b06019, 0x007d3c12, 0x002b0000, 0x00190000, 0x00381000, 0x00a45e20, 0x00c46716, 0x00c96008, 0x00cc5d04, 0x00cc5e08, 0x00cc6009, 0x00c4630a, 0x00c16407, 0x00c36401, 0x00c56400, 0x00c65f00, 0x00ca6100, 0x00c96500, 0x00c86701, 0x00c56400, 0x00c36000, 0x00c86000, 0x00cc6405, 0x00c66107, 0x00c9600a, 0x00ca5806, 0x00bf5007, 0x00b25415, 0x009e5722, 0x0069380d, 0x00320c00, 0x00320900, 0x0055220c, 0x008d4a2d, 0x00a95830, 0x00aa4814, 0x00b0470c, 0x00ba4d12, 0x00b4470c, 0x00b85018, 0x00ac4e1c, 0x009e4e26, 0x00864a2a, 0x00572f19, 0x001e0800, 0x00140c05, 0x00252723, 0x00525957, 0x007c8483, 0x00a6a9a8, 0x00b1b3b2, 0x00b3b1b4, 0x00b9b5b8, 0x00bbb5bc, 0x00b8b0b6, 0x00b8abad, 0x00a29596, 0x007c7371, 0x004c3e3b, 0x00260c08, 0x00260300, 0x003f180c, 0x004c2818, 0x002c1502, 0x001a0500, 0x00190000, 0x003b0e00, 0x00854227, 0x009f4d27, 0x00a55018, 0x00ae4f0f, 0x00b6490c, 0x00bb490c, 0x00b94c0d, 0x00b84c0d, 0x00ba4c0e, 0x00b84f0f, 0x00b14f0f, 0x00a84d13, 0x00a65322, 0x00904a25, 0x00602912, 0x002c0700, 0x000f0000, 0x00080303, 0x00020005, 0x00020003, 0x000d0401, 0x00140000, 0x00421a04, 0x007f4225, 0x00a2502a, 0x00ac4b1f, 0x00b54916, 0x00bc4b12, 0x00b6490c, 0x00b44a08, 0x00b5480a, 0x00ba4e0c, 0x00c1520e, 0x00c0540d, 0x00c05c14, 0x00a04d13, 0x00360000, 0x00541f00, 0x00a6581c, 0x00bc5e12, 0x00c36010, 0x00c05e0f, 0x00bc6319, 0x009f571a, 0x0062300b, 0x00250200, 0x00160000, 0x00330e00, 0x0084481b, 0x00b06223, 0x00ba5f18, 0x00c76415, 0x00cc6211, 0x00c35903, 0x00c66003, 0x00c96708, 0x00c06408, 0x00bc6814, 0x00a45a18, 0x00723504, 0x00380900, 0x00582500, 0x00a85d17, 0x00c46910, 0x00c46402, 0x00c66400, 0x00c86b0a, 0x00c06a17, 0x00a55b1d, 0x00641f00, 0x00a05c10, 0x00b4680e, 0x00c06702, 0x00cc6904, 0x00cc640a, 0x00cc600c, 0x00ca5600, 0x00cc5800, 0x00c65000, 0x00c0580d, 0x00a65b21, 0x00794420, 0x00270500, 0x000b0000, 0x00020001, 0x00090c0d, 0x007c7b79, 0x000c0c0c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00131313, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008e8c8f, 0x003b3838, 0x00040100, 0x00000000, 0x00262628, 0x00767778, 0x00afb0b1, 0x00c6c8c7, 0x00caccc9, 0x00c9cac5, 0x00c4c4be, 0x00cacac2, 0x00c8c7c3, 0x00cbcac7, 0x00ccccc8, 0x00ccccc8, 0x00cacbc7, 0x00c8c9c5, 0x00c9cac6, 0x00ccccc8, 0x00c8c9c4, 0x00ccccc8, 0x00ccccc8, 0x00ccccc8, 0x00cacbc6, 0x00c8c8c4, 0x00c8c9c4, 0x00ccccca, 0x00c2c3c6, 0x00aba8a7, 0x006c5f57, 0x002c1102, 0x00441904, 0x00854728, 0x00a65425, 0x00ac4b14, 0x00b24a0d, 0x00b65015, 0x00a94d20, 0x009f4f28, 0x007b3914, 0x00430800, 0x003e0400, 0x006c2b07, 0x00a45624, 0x00af5416, 0x00c05910, 0x00c65908, 0x00c85902, 0x00cc5e03, 0x00c85d01, 0x00c45e00, 0x00c56504, 0x00b96009, 0x009d4c10, 0x00803401, 0x00ae6029, 0x00945629, 0x002c0b00, 0x001c0000, 0x00552101, 0x00a85d26, 0x00bb5c0e, 0x00c85f02, 0x00cb6004, 0x00c96002, 0x00c36000, 0x00c46404, 0x00c3660c, 0x00b56319, 0x008d4c1d, 0x003a0d00, 0x00100000, 0x00200400, 0x007e420e, 0x00b8641b, 0x00c26107, 0x00c86000, 0x00c86006, 0x00c56008, 0x00c2610c, 0x00c2620a, 0x00c56004, 0x00c85f02, 0x00cc650c, 0x00c65c08, 0x00bd5a0a, 0x00bf600e, 0x00c4620b, 0x00c35e04, 0x00c65c04, 0x00cc6107, 0x00c95d01, 0x00c85c00, 0x00c85c02, 0x00c45b04, 0x00c1590c, 0x00ba5a14, 0x00aa5419, 0x0091481b, 0x00521b00, 0x003b0a00, 0x00521d04, 0x00874527, 0x00a85026, 0x00af4d19, 0x00b14e14, 0x00af511a, 0x00a04f25, 0x00985534, 0x00632c11, 0x00360e00, 0x00281001, 0x0050453c, 0x00838079, 0x00adb0aa, 0x00b9bcb6, 0x00bcbfb9, 0x00c6c6c0, 0x00ccccc8, 0x00cccbc9, 0x00c7c5c9, 0x00c7c6cc, 0x00cccbcc, 0x00cac9c8, 0x00c1c0bf, 0x00b9b9c0, 0x00b7b4bc, 0x00a49c9f, 0x00726664, 0x00372923, 0x00130500, 0x000c0200, 0x00100000, 0x00381608, 0x00784028, 0x009c4c24, 0x00af4f1e, 0x00b24c15, 0x00b74f12, 0x00b4490c, 0x00b44b0c, 0x00b44f10, 0x00b84f10, 0x00bc480d, 0x00b9440c, 0x00b44811, 0x00ad5220, 0x00925026, 0x0058290c, 0x00280900, 0x000e0000, 0x00030000, 0x00000001, 0x00080001, 0x000f0000, 0x00170000, 0x0058280d, 0x008e4924, 0x00a54e21, 0x00b44d20, 0x00b74818, 0x00b34311, 0x00b84c17, 0x00b04e14, 0x00b05011, 0x00b44f11, 0x00b74e0c, 0x00c0510f, 0x00bd5818, 0x00a0511b, 0x005d1e00, 0x00360000, 0x0084481e, 0x00b56021, 0x00bc5a10, 0x00c05c11, 0x00ba5f18, 0x00995018, 0x00612f06, 0x001e0300, 0x00150100, 0x002c1000, 0x006a3a0f, 0x00af5f18, 0x00bf600c, 0x00bd600c, 0x00bc5f0b, 0x00c36010, 0x00c86410, 0x00c56207, 0x00bc5f04, 0x00bb6414, 0x00a9601e, 0x006f380c, 0x00310400, 0x00320b00, 0x006d3c13, 0x00b4671c, 0x00c76a0b, 0x00c46300, 0x00c66400, 0x00c86404, 0x00c0640c, 0x00b4641c, 0x00803a00, 0x00632100, 0x009e5a12, 0x00c06d11, 0x00c46804, 0x00cc680c, 0x00ca620a, 0x00cc650e, 0x00c05100, 0x00cc5800, 0x00cb5a05, 0x00bb5810, 0x00a3541d, 0x00743a1c, 0x00220000, 0x000c0000, 0x00020000, 0x00181816, 0x00989899, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x000e0e0f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a4a4, 0x003c3b3c, 0x00060405, 0x00080607, 0x00323234, 0x00828284, 0x00b7b7b8, 0x00cccccc, 0x00c7c8c4, 0x00c8c6c0, 0x00ccc9c0, 0x00ccccc0, 0x00ccc8bd, 0x00ccccc4, 0x00cccbc4, 0x00ccc9c4, 0x00c9c9c3, 0x00cbcbc4, 0x00ccccc8, 0x00ccccc8, 0x00c8c9c4, 0x00ccccc8, 0x00c8cac4, 0x00c8cac6, 0x00c8cac6, 0x00c4c8c4, 0x00c8ccc7, 0x00c8ccc9, 0x00c4c8c4, 0x00c8cac9, 0x00c8c8c7, 0x00b5b1ae, 0x00776b65, 0x00321a12, 0x003d1402, 0x0084411e, 0x00a35022, 0x00ab501c, 0x00a44c1c, 0x00944a28, 0x006f2f11, 0x003f0500, 0x00490d00, 0x00843f18, 0x00a45624, 0x00b45b19, 0x00be5b0e, 0x00c95d09, 0x00c85a01, 0x00c85c00, 0x00cb6004, 0x00c75e00, 0x00c56000, 0x00c06000, 0x00bd6710, 0x009a5018, 0x00752e01, 0x00a45924, 0x009b5c2f, 0x003e1808, 0x001d0000, 0x00642f0d, 0x00a95f27, 0x00c36414, 0x00cc6004, 0x00c75b00, 0x00cc6404, 0x00c56103, 0x00c26105, 0x00bf5f07, 0x00b86115, 0x009c5720, 0x005a2b09, 0x00110000, 0x001a0400, 0x005c2800, 0x00b06424, 0x00be620b, 0x00c46100, 0x00c46005, 0x00c46008, 0x00c3610a, 0x00c56008, 0x00c95e04, 0x00c95d08, 0x00c25b12, 0x00be5f1f, 0x00b45e26, 0x00ad5b1f, 0x00b55a13, 0x00c25f0f, 0x00c95f0b, 0x00c85a03, 0x00cc5d04, 0x00ca5d04, 0x00c86004, 0x00c66008, 0x00c75b05, 0x00c65809, 0x00c35610, 0x00b55518, 0x00934b1b, 0x00652c09, 0x003d0b00, 0x004b1400, 0x00843a1b, 0x00a55229, 0x00a8511e, 0x009c5020, 0x00894e2f, 0x004a1d09, 0x00300c00, 0x00543a30, 0x008c7f78, 0x00ada8a3, 0x00c4c4c0, 0x00c5c7c3, 0x00caccc7, 0x00cbccc5, 0x00ccc9c2, 0x00ccc9c4, 0x00cccbc8, 0x00cccccc, 0x00c9cacc, 0x00c6c8cc, 0x00c8cccb, 0x00c4c8c7, 0x00c6cccc, 0x00c8cbcc, 0x00c5c1c4, 0x00bfbbb8, 0x009a9693, 0x00615f5b, 0x001c1c1c, 0x00160b08, 0x0049281c, 0x00895038, 0x00a7522a, 0x00b04917, 0x00b84d14, 0x00b6490c, 0x00b74e10, 0x00b34f0f, 0x00ae4d0e, 0x00b04a0e, 0x00be4813, 0x00be4919, 0x00b34b1c, 0x009c4c22, 0x0064300e, 0x002f1300, 0x000a0000, 0x00020000, 0x00040404, 0x00040000, 0x000b0000, 0x001b0000, 0x005a260c, 0x008c451f, 0x00ab5320, 0x00b14c14, 0x00b84915, 0x00bb4916, 0x00b74817, 0x00b44d19, 0x00b04f16, 0x00ab4d0e, 0x00b4500c, 0x00bd5413, 0x00c05518, 0x00b0511e, 0x0084431d, 0x00380200, 0x00642900, 0x009f5924, 0x00b65c19, 0x00bc5c14, 0x00b65c1b, 0x009d511b, 0x00632e08, 0x00260400, 0x00110000, 0x001a0700, 0x00532e07, 0x009a5d20, 0x00be610a, 0x00c75f00, 0x00c26208, 0x00be610a, 0x00c0600a, 0x00c0600c, 0x00bd610c, 0x00ba6719, 0x00a45b1c, 0x00683001, 0x002e0700, 0x001c0000, 0x00441d03, 0x00885020, 0x00b56413, 0x00c96907, 0x00c56601, 0x00c86602, 0x00ca6407, 0x00c5650d, 0x00c06b19, 0x00a65d16, 0x005e1f00, 0x00642500, 0x00a0580d, 0x00b96910, 0x00c76c10, 0x00c9680c, 0x00c46209, 0x00cc6a12, 0x00c45400, 0x00cb5800, 0x00c65704, 0x00b85510, 0x00a45424, 0x00662c0e, 0x00180000, 0x000d0100, 0x000a0704, 0x00353839, 0x00a4a6ac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00080809, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00bbb8b0, 0x004c4944, 0x00100e0a, 0x00050403, 0x00323031, 0x00878788, 0x00bfbec2, 0x00c8c8cc, 0x00c6c6c8, 0x00ccccca, 0x00ccc9c5, 0x00cccac3, 0x00ccc7bd, 0x00ccc9c0, 0x00cbc8c3, 0x00ccccc6, 0x00ccccc8, 0x00cac9c5, 0x00ccccc8, 0x00cbccc8, 0x00c9cac6, 0x00cbccca, 0x00c8ccc9, 0x00c8cccb, 0x00c8cccc, 0x00c8cccc, 0x00c7cccc, 0x00c7cccc, 0x00c5cccc, 0x00c7cccc, 0x00c6cac7, 0x00cbccc8, 0x00cccbc8, 0x00b9b3b1, 0x0078706e, 0x00341d14, 0x004b1d06, 0x00834426, 0x00975332, 0x00874828, 0x005f2c15, 0x003c0800, 0x00561700, 0x008d4116, 0x00b0571d, 0x00b75712, 0x00bd590f, 0x00c15c09, 0x00c55d04, 0x00c76002, 0x00c45f04, 0x00c35e05, 0x00c85c07, 0x00cb5f08, 0x00c56005, 0x00bf6414, 0x00954c18, 0x006f2d00, 0x00984f14, 0x009e5f2a, 0x0050240c, 0x00250000, 0x00743912, 0x00ac5d23, 0x00c45f11, 0x00c85b00, 0x00c85c00, 0x00c86001, 0x00c15c04, 0x00c5610c, 0x00c45e0a, 0x00c06214, 0x00ac5f1c, 0x00774214, 0x001a0400, 0x00100000, 0x00340800, 0x00a3602c, 0x00b86012, 0x00c46004, 0x00c45e06, 0x00c55d05, 0x00c86007, 0x00c95e04, 0x00cc5c00, 0x00c75d0c, 0x00af551a, 0x007e3309, 0x00571c00, 0x005d2200, 0x0093450f, 0x00c0611c, 0x00cb5c0d, 0x00cc5a06, 0x00cb5a06, 0x00c75b07, 0x00c6600b, 0x00c25c07, 0x00c85d0b, 0x00c85908, 0x00c95405, 0x00c6580d, 0x00b05714, 0x009c5520, 0x006c3514, 0x00401000, 0x00440f00, 0x0074381f, 0x0098542f, 0x00824721, 0x003f1701, 0x002a1004, 0x00745e55, 0x00a49791, 0x00c4bdbb, 0x00cbc9ca, 0x00c7c8c9, 0x00c9cccc, 0x00c8cbca, 0x00c9cbc8, 0x00cacbc7, 0x00cbcac6, 0x00cbcac7, 0x00cbcac7, 0x00cacaca, 0x00c9cbca, 0x00c7ccca, 0x00c8ccc9, 0x00c7ccc7, 0x00cacbc4, 0x00ccc8c4, 0x00ccc6c0, 0x00c6bdb8, 0x00b8b5b1, 0x007c807d, 0x003b3834, 0x00281008, 0x005c2b18, 0x009d4c2d, 0x00ac481d, 0x00b84c14, 0x00ba4c0c, 0x00b44c0a, 0x00b04e0c, 0x00af5114, 0x00ae4d16, 0x00b5481c, 0x00b44823, 0x00a84d2a, 0x00713011, 0x00351100, 0x000d0000, 0x00020000, 0x00000200, 0x00030000, 0x000a0000, 0x00200200, 0x0051200a, 0x008e4824, 0x00a34e1e, 0x00ac4e13, 0x00b04b0c, 0x00b74c10, 0x00b54913, 0x00b04818, 0x00b34c1a, 0x00b14c10, 0x00b7500c, 0x00b84c03, 0x00c45c15, 0x00b5531c, 0x009c4823, 0x004e1200, 0x00410800, 0x009b5321, 0x00b05a18, 0x00bb5c16, 0x00b45a18, 0x009c5120, 0x00602b09, 0x00200000, 0x00120000, 0x00160100, 0x003e1f00, 0x008b541e, 0x00b26419, 0x00c66306, 0x00c75d00, 0x00bf5e02, 0x00bf6106, 0x00c46104, 0x00bc5e06, 0x00bb6820, 0x00a05b24, 0x00622c08, 0x002c0700, 0x00120000, 0x00190000, 0x005d2f08, 0x00a56121, 0x00be650f, 0x00c66402, 0x00c36405, 0x00c26409, 0x00c4640a, 0x00c5650d, 0x00be6107, 0x00ba6818, 0x00904e19, 0x00490f00, 0x00642900, 0x00a36020, 0x00b86712, 0x00c2690d, 0x00c56811, 0x00c4640b, 0x00c76202, 0x00c95d00, 0x00ca5600, 0x00c55507, 0x00b95411, 0x00a25220, 0x00481600, 0x00180000, 0x00060000, 0x00060b0b, 0x00666c70, 0x00b3b5bb, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040505, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00706c64, 0x001a1810, 0x00040200, 0x002a2926, 0x007c7c7c, 0x00bcbcbe, 0x00c6c7ca, 0x00cbcccc, 0x00cbcacc, 0x00c8c8c9, 0x00c8c7c5, 0x00ccccc8, 0x00ccc8c3, 0x00ccccc6, 0x00cac9c6, 0x00c9c8c5, 0x00cbcac7, 0x00ccccc8, 0x00c8c8c7, 0x00c7c7c5, 0x00c9c9c8, 0x00cbcccc, 0x00cacbcc, 0x00c8cccc, 0x00c8cccc, 0x00c8cccc, 0x00c8cbcc, 0x00c8cbcc, 0x00c8cbcc, 0x00c7cccc, 0x00c8ccca, 0x00c6cac7, 0x00cccbcc, 0x00c9c8c8, 0x00adacac, 0x006c625d, 0x003a1b0f, 0x00532918, 0x006d3f2d, 0x005b2c19, 0x003a1000, 0x00521f03, 0x0090441b, 0x00b3541c, 0x00bc540d, 0x00c85b0c, 0x00c25708, 0x00c55b07, 0x00c95c03, 0x00c85c02, 0x00c35d08, 0x00c45c09, 0x00c85a09, 0x00c85a07, 0x00c45c05, 0x00bc6016, 0x00944c1a, 0x006a2900, 0x0090470c, 0x009f5e29, 0x005c2d14, 0x00280000, 0x007b3c0f, 0x00ae5c1e, 0x00c45c10, 0x00c95802, 0x00c85c00, 0x00c85f06, 0x00c15b0a, 0x00c45e10, 0x00c75c0c, 0x00c46010, 0x00b65f13, 0x008a4c12, 0x00311400, 0x00110000, 0x00280200, 0x00844824, 0x00b7601a, 0x00c45f07, 0x00c55c05, 0x00c95c06, 0x00ca5d04, 0x00c85b00, 0x00cc5c00, 0x00c45d0e, 0x009a4815, 0x005a1f00, 0x00240000, 0x002e0600, 0x006e3005, 0x00b45f20, 0x00c85e10, 0x00cc5a06, 0x00c85b06, 0x00c45d0c, 0x00be5c0f, 0x00be5a10, 0x00c75c0c, 0x00cc5b09, 0x00cc5904, 0x00c85501, 0x00bc5608, 0x00b45c1b, 0x00985020, 0x00713412, 0x00491500, 0x003f1000, 0x005f3014, 0x00411c02, 0x002c1709, 0x00786b63, 0x00b4aaa4, 0x00c8c2c0, 0x00ccc9c8, 0x00c7c7c8, 0x00cacbcc, 0x00c8cccc, 0x00c8cccc, 0x00c8cccc, 0x00cacccb, 0x00caccc9, 0x00caccc8, 0x00caccc8, 0x00caccc8, 0x00c8ccc9, 0x00c4cccc, 0x00c5cccc, 0x00c8ccc8, 0x00caccc3, 0x00cccac3, 0x00ccc9c3, 0x00ccc7c4, 0x00c7c4c0, 0x00b8bfbb, 0x008c8d89, 0x00594c46, 0x00310c02, 0x006c2a17, 0x00a44d2c, 0x00ac4815, 0x00b1480a, 0x00b64f0e, 0x00ae4a0a, 0x00af4e14, 0x00b0501e, 0x00a8441c, 0x00a94c2c, 0x00813b1e, 0x00481801, 0x00100000, 0x00080400, 0x00000100, 0x00000200, 0x00090100, 0x00160000, 0x004d1d08, 0x00884426, 0x00a24c21, 0x00af5019, 0x00af4d10, 0x00b04c0a, 0x00b64d0f, 0x00b44b10, 0x00af4814, 0x00b14c16, 0x00b74d0c, 0x00b64c03, 0x00c65b0f, 0x00bc5814, 0x00a14c1f, 0x00682004, 0x003d0000, 0x007f3c21, 0x00ad5923, 0x00b45a17, 0x00b96424, 0x009b511d, 0x00582605, 0x00270700, 0x00100000, 0x00140000, 0x00321100, 0x00703e14, 0x00aa6020, 0x00bb6010, 0x00c25a00, 0x00cb6002, 0x00c46005, 0x00c16006, 0x00bb5d02, 0x00ba6515, 0x00985820, 0x00643310, 0x002c0800, 0x00170000, 0x000e0000, 0x002c0f00, 0x00773e0c, 0x00b26318, 0x00c1640a, 0x00c46403, 0x00c16407, 0x00c2640a, 0x00c4630c, 0x00c46209, 0x00c66508, 0x00c16814, 0x00a45c21, 0x00652b00, 0x00431000, 0x006c3508, 0x00a45f19, 0x00bc6c19, 0x00c06b14, 0x00c1660c, 0x00c56606, 0x00c86000, 0x00c95500, 0x00cc5601, 0x00ca5a0c, 0x00b55818, 0x00894821, 0x00330b00, 0x000a0000, 0x00020400, 0x001e2224, 0x0087898d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a2a49b, 0x002b2c25, 0x00030400, 0x00161713, 0x0070706f, 0x00b4b4b4, 0x00cbcbcc, 0x00c9c8cc, 0x00cac9cc, 0x00cacbcc, 0x00c8c9cc, 0x00c6c7ca, 0x00c0c1c3, 0x00b0b1b3, 0x00b4b4b6, 0x00c4c4c5, 0x00c4c4c6, 0x00cbc9cc, 0x00cccacc, 0x00c8c7c9, 0x00cccacc, 0x00cccbcc, 0x00c8c6c8, 0x00cccacc, 0x00ccc9cc, 0x00ccc9cc, 0x00ccc9cc, 0x00ccc9cc, 0x00ccc8cc, 0x00ccc8cc, 0x00cbc9cc, 0x00c7ccca, 0x00c8cccb, 0x00c8cbcc, 0x00cccccc, 0x00cccccc, 0x00b1aba8, 0x005a4843, 0x00311911, 0x00341912, 0x00300f02, 0x00441600, 0x0089471d, 0x00bc5a1c, 0x00c8580c, 0x00ca5708, 0x00c95705, 0x00c85707, 0x00cc5906, 0x00cc5904, 0x00cc5704, 0x00c85809, 0x00c95b0c, 0x00c95a08, 0x00c55904, 0x00c25c06, 0x00b95e17, 0x00954b1c, 0x00672200, 0x00843b07, 0x00a05e2e, 0x00673c20, 0x00280000, 0x00813d10, 0x00b35a1b, 0x00c55910, 0x00ca5806, 0x00c75b04, 0x00c75e09, 0x00c15a0f, 0x00c45c14, 0x00c85a0f, 0x00c55a0c, 0x00bd5e0c, 0x00a15815, 0x00542b0c, 0x00150000, 0x001c0000, 0x005c2811, 0x00b45d23, 0x00c55c0c, 0x00c75807, 0x00cc5c08, 0x00c95b04, 0x00c75900, 0x00cc5b00, 0x00c25d0d, 0x00a45823, 0x005c280c, 0x00140000, 0x00130000, 0x00502100, 0x00a76124, 0x00bd5f0f, 0x00c45c00, 0x00c45f04, 0x00c1600d, 0x00ac4f0f, 0x00b75519, 0x00c65913, 0x00c95806, 0x00cc5c02, 0x00c95800, 0x00c75a0b, 0x00be550f, 0x00bc5514, 0x00ac5118, 0x00823d0e, 0x00411400, 0x00200a00, 0x001c1207, 0x00766f68, 0x00c0bab4, 0x00c7c4bc, 0x00ccc8c5, 0x00ccc8c8, 0x00cccbcc, 0x00cccbcc, 0x00c9cacc, 0x00cbcccc, 0x00c9cccc, 0x00c8cccc, 0x00c8cccc, 0x00c8cccc, 0x00c8cccc, 0x00c8ccca, 0x00c6cccc, 0x00c1cccc, 0x00c3cccc, 0x00c6cccc, 0x00cacbcc, 0x00ccc9ca, 0x00cccaca, 0x00cccbca, 0x00cacbc7, 0x00c6cbc8, 0x00c0c4c3, 0x00999898, 0x00514040, 0x00330b02, 0x006c3019, 0x00a25124, 0x00ae5018, 0x00b44d11, 0x00b0480c, 0x00b24c17, 0x00ae501f, 0x00a34b24, 0x00904828, 0x00502007, 0x001d0400, 0x00060000, 0x00000100, 0x00000101, 0x00040200, 0x00100000, 0x003a1400, 0x00813e20, 0x00a34c25, 0x00af4c1c, 0x00b34d18, 0x00ad4c15, 0x00ae4c12, 0x00b54d10, 0x00b64c0e, 0x00b34a10, 0x00b54c0e, 0x00c1530a, 0x00bc4e01, 0x00c05912, 0x00ac541b, 0x00743110, 0x00460700, 0x006a1d00, 0x00ad582a, 0x00b65d1e, 0x00b46124, 0x00904f23, 0x00532608, 0x001f0800, 0x000a0000, 0x000c0000, 0x00260800, 0x00652e0d, 0x00a35724, 0x00c0611c, 0x00c45c0d, 0x00c55809, 0x00cc600e, 0x00c85c05, 0x00c05c06, 0x00bd6718, 0x009a5818, 0x0058300c, 0x00240e00, 0x000c0000, 0x000c0000, 0x00100000, 0x004a210a, 0x00984f16, 0x00be6414, 0x00c06408, 0x00c36404, 0x00c36405, 0x00c66308, 0x00ca620a, 0x00c75f07, 0x00c66108, 0x00c46812, 0x00b6671c, 0x0094521a, 0x00441200, 0x003a0a00, 0x00773f0f, 0x00a46321, 0x00ba6c1a, 0x00c0680b, 0x00c76808, 0x00cb6402, 0x00cc5c00, 0x00cc5800, 0x00ca5807, 0x00bc5713, 0x00ac5a28, 0x00642d0c, 0x001f0700, 0x00080200, 0x00000200, 0x00545557, 0x00afa7a8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00515550, 0x000a0e0b, 0x00040805, 0x004c4f4e, 0x00adafae, 0x00c9cacc, 0x00c9c9cb, 0x00c8c8c9, 0x00cbcbcc, 0x00bcbcc0, 0x009a9b9e, 0x00737477, 0x0054565a, 0x00484b4f, 0x004f5155, 0x00585b5d, 0x0078787a, 0x00a3a2a6, 0x00c1c1c3, 0x00cacacc, 0x00c8c8ca, 0x00c8c7c9, 0x00c9c8c8, 0x00cccacb, 0x00cccacb, 0x00ccc9cb, 0x00ccc9c9, 0x00ccc8c9, 0x00ccc8c9, 0x00ccc8c9, 0x00ccc9ca, 0x00c5c8c9, 0x00c7cccc, 0x00c0c5c5, 0x00c6c9c8, 0x00c9cacc, 0x00cbc8c8, 0x009b9392, 0x00413330, 0x00180500, 0x00321406, 0x00703d20, 0x00a45928, 0x00bc540e, 0x00c65000, 0x00cc5b08, 0x00c85300, 0x00cc5707, 0x00cc5805, 0x00cc5702, 0x00cc5604, 0x00c85609, 0x00c8590b, 0x00c85904, 0x00c65901, 0x00c35c07, 0x00b85d16, 0x00964c1b, 0x00611f00, 0x00772f00, 0x009f5f30, 0x006f4427, 0x00280000, 0x0087400d, 0x00b45815, 0x00c6580d, 0x00cb5807, 0x00c75b05, 0x00c45d0a, 0x00c1590c, 0x00c55b12, 0x00c8580e, 0x00c55708, 0x00c35c07, 0x00b25e15, 0x00743f15, 0x00200000, 0x00140000, 0x00391000, 0x00a85925, 0x00c05c13, 0x00c45609, 0x00cb5c0b, 0x00c45a06, 0x00c45802, 0x00c85b00, 0x00c15b0a, 0x00ad5c24, 0x00683311, 0x00180000, 0x000d0000, 0x003c1700, 0x009a5c23, 0x00b86011, 0x00c25f04, 0x00c06004, 0x00b45c0e, 0x007f2f00, 0x00903d11, 0x00b55418, 0x00c2560c, 0x00cb5a04, 0x00cb5900, 0x00cc5a0a, 0x00c45208, 0x00ca5710, 0x00bb5618, 0x00944f1e, 0x00462000, 0x00150c00, 0x00656a67, 0x00b8bcb8, 0x00c9cbc8, 0x00c5c7c4, 0x00cbcbc9, 0x00c7c6c4, 0x00cccacb, 0x00cbc7ca, 0x00cccbcc, 0x00cccbcc, 0x00cbcccc, 0x00c9cccc, 0x00c9cccc, 0x00c8cccc, 0x00c8ccca, 0x00c8ccca, 0x00c7cccc, 0x00c4cccc, 0x00c5cccc, 0x00c8cccc, 0x00cccbcc, 0x00cbc8cc, 0x00cbc9cc, 0x00c9c8c7, 0x00c6c8c4, 0x00c4c8c4, 0x00c8cccb, 0x00bcbec2, 0x009c989b, 0x0046322f, 0x00330c00, 0x00824624, 0x009b4c1c, 0x00aa4b16, 0x00b14a14, 0x00b14d1a, 0x00a64a1c, 0x009b512a, 0x00683112, 0x00270b00, 0x00090000, 0x00040402, 0x00000003, 0x00010101, 0x000a0000, 0x002c0e00, 0x00733c1f, 0x00a4502a, 0x00b04c1d, 0x00b44a16, 0x00b44b14, 0x00b04c17, 0x00b24c17, 0x00b54c10, 0x00b54b0c, 0x00b54c0a, 0x00b84f0b, 0x00c05509, 0x00c05910, 0x00ac5318, 0x00853b0d, 0x00460e00, 0x00541900, 0x00a3501f, 0x00b45a1f, 0x00b15e24, 0x00945120, 0x00502408, 0x00170000, 0x000c0400, 0x00080000, 0x001a0100, 0x00502106, 0x00964c1e, 0x00b85c20, 0x00c05810, 0x00c8590d, 0x00c7590e, 0x00c3580c, 0x00c25a0d, 0x00bc6118, 0x00a15c1e, 0x00603307, 0x001f0c00, 0x00050000, 0x00080304, 0x000d0000, 0x001f0000, 0x006a3312, 0x00ad5b1d, 0x00c26311, 0x00bf6208, 0x00c06403, 0x00c36301, 0x00c76202, 0x00cc6206, 0x00ca5d05, 0x00c45f06, 0x00c3660f, 0x00bc6410, 0x00b16522, 0x00703811, 0x00320300, 0x00401300, 0x007a4613, 0x00aa681b, 0x00bb6b10, 0x00c4680c, 0x00c96406, 0x00cc6203, 0x00cc5b00, 0x00c35400, 0x00be570d, 0x00b6591d, 0x00985124, 0x00431b00, 0x000e0000, 0x00080200, 0x0020201e, 0x00877f7e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a0a6a8, 0x00141c1e, 0x00000405, 0x00242a2c, 0x008f9395, 0x00c0c4c7, 0x00c8cccc, 0x00c8c9cb, 0x00c8c8c8, 0x00afadae, 0x00757474, 0x003b3b3b, 0x00131314, 0x00000004, 0x00010408, 0x00000104, 0x00000202, 0x00141b18, 0x00414646, 0x007d8280, 0x00b2b5b4, 0x00c4c8c7, 0x00c7c8c8, 0x00cbccca, 0x00cbcbc9, 0x00cbccc8, 0x00cccbc8, 0x00cccbc8, 0x00cccac8, 0x00ccc9c7, 0x00ccc9c7, 0x00cbcac8, 0x00cacbcc, 0x00c8cccc, 0x00c1c6c4, 0x00c8cccc, 0x00c5c9cc, 0x00c4c6cc, 0x00c1c0c2, 0x00756c68, 0x002c1a0d, 0x00482510, 0x00834a28, 0x00954714, 0x00b85813, 0x00c45707, 0x00cc590a, 0x00cc5808, 0x00cc5606, 0x00ca5503, 0x00c85702, 0x00c65a04, 0x00c45b0b, 0x00c45908, 0x00c65800, 0x00c65800, 0x00c65c05, 0x00b85c12, 0x00944e15, 0x005b1e00, 0x00682600, 0x009c5f2f, 0x00704123, 0x002c0000, 0x008c440b, 0x00b45810, 0x00c65909, 0x00cc5a06, 0x00c45b04, 0x00c35c05, 0x00c15b05, 0x00c55c09, 0x00c8590a, 0x00c45605, 0x00c65a04, 0x00bc5f12, 0x008c4c13, 0x00340b00, 0x00100000, 0x00200400, 0x008d4f1d, 0x00b4601b, 0x00bc590c, 0x00c35d0b, 0x00bd5c0b, 0x00be5c08, 0x00c75c03, 0x00c25808, 0x00b55919, 0x007b360f, 0x00280500, 0x00100000, 0x00300c00, 0x0088501c, 0x00b45d13, 0x00be5c05, 0x00ba5e08, 0x00a85914, 0x00440e00, 0x004c1500, 0x008c3e12, 0x00b75718, 0x00c85a0c, 0x00cb5500, 0x00c85603, 0x00c65608, 0x00c75c18, 0x00ad5622, 0x00743e1c, 0x00311805, 0x0048463a, 0x00b1bab4, 0x00bfcacb, 0x00bdc8cc, 0x00c6cccc, 0x00c7cccc, 0x00c4c7c9, 0x00cbcbcc, 0x00ccc9ca, 0x00cccaca, 0x00cccaca, 0x00cccaca, 0x00cccbc8, 0x00cccbc8, 0x00ccccc8, 0x00ccccc8, 0x00ccccc8, 0x00ccccc8, 0x00cccbc7, 0x00ccccca, 0x00cccacc, 0x00ccc8cc, 0x00cccacc, 0x00cccbcc, 0x00cccbc7, 0x00c8c9c3, 0x00caccc8, 0x00cbcccc, 0x00c6c8cc, 0x00bcbcbd, 0x008f8683, 0x00311c10, 0x00431f08, 0x00884f2d, 0x00a34d22, 0x00b04c1c, 0x00ae4d20, 0x00a04c22, 0x007d401b, 0x003a1400, 0x00110100, 0x00030000, 0x00000001, 0x00020004, 0x000b0000, 0x00210600, 0x00613018, 0x0098502c, 0x00aa4a1a, 0x00b84e18, 0x00b44a13, 0x00b54913, 0x00b84a16, 0x00b84915, 0x00b44810, 0x00b4490c, 0x00bb4e09, 0x00be540b, 0x00b9540f, 0x00b1591d, 0x0088441b, 0x004c1300, 0x00491400, 0x0083451a, 0x00b06021, 0x00b05d1e, 0x008f4e22, 0x004e2304, 0x001c0800, 0x00080000, 0x00050000, 0x00150200, 0x004c2000, 0x00894614, 0x00b35b1d, 0x00c15a17, 0x00c45511, 0x00c6550f, 0x00c55809, 0x00bc560a, 0x00b85d1d, 0x00a15928, 0x00592a0a, 0x00250d00, 0x00070400, 0x00000100, 0x00040300, 0x000f0000, 0x00401100, 0x008c441a, 0x00b95f1f, 0x00c36011, 0x00bf6209, 0x00c06304, 0x00c56200, 0x00c85f00, 0x00cc5f00, 0x00cc5e03, 0x00c46308, 0x00c1640c, 0x00c06007, 0x00ba6216, 0x009f5826, 0x00501a00, 0x00260000, 0x00482000, 0x0085510e, 0x00ae6917, 0x00c26817, 0x00c45e08, 0x00cc6206, 0x00cc5f02, 0x00c15802, 0x00c45d0e, 0x00c05912, 0x00b05920, 0x00743912, 0x00280400, 0x000d0000, 0x00030000, 0x00575350, 0x00aca8a6, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005a5d60, 0x000a0e11, 0x00000004, 0x00666a6d, 0x00b8bcbf, 0x00c4c8ca, 0x00c4c8c8, 0x00c8cac9, 0x00aeaeae, 0x00646361, 0x001c1b19, 0x00020100, 0x00000000, 0x00000001, 0x00040408, 0x00000003, 0x00000402, 0x00000100, 0x00000100, 0x00222724, 0x00727673, 0x00b6bab7, 0x00c9ccca, 0x00c7c8c6, 0x00c9cbc8, 0x00c9cbc8, 0x00cacac8, 0x00cacac8, 0x00cacac8, 0x00cacac8, 0x00cbcac8, 0x00cacaca, 0x00c9cacc, 0x00c6c9c8, 0x00c9cbc7, 0x00c8ccc9, 0x00c7cbcc, 0x00c4c8cc, 0x00c9cacc, 0x00a8a4a0, 0x00514338, 0x003b1d08, 0x00653312, 0x00803808, 0x00b85c1a, 0x00c35b10, 0x00c8580c, 0x00c95608, 0x00c95705, 0x00c75804, 0x00c25c06, 0x00bf5c09, 0x00bf5c0f, 0x00c25a0c, 0x00c95900, 0x00ca5900, 0x00c75906, 0x00b85913, 0x00944d1a, 0x00561c00, 0x00581c00, 0x00925c32, 0x0063381b, 0x002e0000, 0x00934a11, 0x00b55910, 0x00c55807, 0x00cc5b06, 0x00c45b06, 0x00c25c04, 0x00c25a00, 0x00c45b04, 0x00c55b0a, 0x00c45808, 0x00c75807, 0x00bf5b10, 0x009c5214, 0x004f1f00, 0x000f0000, 0x00120000, 0x0068360c, 0x00aa5d20, 0x00ba5a0e, 0x00c15b0a, 0x00b95b0b, 0x00bc5f0b, 0x00c45b02, 0x00c25804, 0x00c15c18, 0x008d4012, 0x00360f01, 0x00100000, 0x00280800, 0x00743f14, 0x00b45e18, 0x00be5908, 0x00b85a0a, 0x00a85e20, 0x00300800, 0x001e0000, 0x00581c00, 0x009c4b16, 0x00c05c14, 0x00c55706, 0x00c55804, 0x00c45b0c, 0x00bc5814, 0x009b4e1e, 0x004e2510, 0x0033231c, 0x00989894, 0x00c0c8c5, 0x00c4cccc, 0x00c6cccc, 0x00c4cbcc, 0x00c0c6c8, 0x00c9cccc, 0x00cacbcc, 0x00cccbcc, 0x00cccac9, 0x00cccbc8, 0x00cccbc8, 0x00cccbc8, 0x00cccbc8, 0x00ccccc8, 0x00ccccc8, 0x00ccccc8, 0x00ccccc8, 0x00ccccc4, 0x00cccac7, 0x00ccc7cc, 0x00ccc7cc, 0x00ccc9cc, 0x00cccbcc, 0x00ccccc8, 0x00caccc7, 0x00c6c8c4, 0x00c9cbca, 0x00cacbcc, 0x00c5c5c7, 0x00bcb8b5, 0x0070655c, 0x001b0500, 0x00683c24, 0x009f5029, 0x00ac4e23, 0x00a74f26, 0x00954c27, 0x004e2000, 0x001a0100, 0x000b0100, 0x00000000, 0x00000003, 0x000a0002, 0x00190100, 0x00502411, 0x008c4829, 0x00a44b1f, 0x00af4914, 0x00b4480e, 0x00b44a10, 0x00b34910, 0x00b84912, 0x00b94810, 0x00b5480d, 0x00b84f0d, 0x00c0550e, 0x00be5714, 0x00b3581f, 0x00893c10, 0x00551900, 0x00410b00, 0x007b4119, 0x00a1612f, 0x00a86022, 0x008a4a13, 0x004c2103, 0x001a0100, 0x00080000, 0x00070000, 0x000d0000, 0x003c1704, 0x00824315, 0x00ad5c1a, 0x00bb5c12, 0x00c15b0d, 0x00c65a12, 0x00c1550c, 0x00c55f10, 0x00bb6019, 0x00995222, 0x00623013, 0x00240700, 0x00080000, 0x00030301, 0x00000100, 0x00000000, 0x00130000, 0x00602801, 0x00a5541e, 0x00bf5f1a, 0x00c35e0e, 0x00c2600b, 0x00c06004, 0x00c56200, 0x00c55d00, 0x00ca5e00, 0x00c85f04, 0x00c16409, 0x00bc6005, 0x00c96409, 0x00c0600c, 0x00b46422, 0x007c3c0d, 0x00340c00, 0x00200100, 0x00512900, 0x00915818, 0x00bc6c22, 0x00c46310, 0x00cb6309, 0x00cc6408, 0x00c45d06, 0x00c35a07, 0x00c45707, 0x00b85510, 0x009f5423, 0x00501c00, 0x001b0200, 0x00060000, 0x0023221e, 0x0080817d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00aeacad, 0x00211e1d, 0x000a0706, 0x001d1a1b, 0x009b9b9c, 0x00c2c2c4, 0x00cacbcc, 0x00c9cccc, 0x00bbbebd, 0x006e706f, 0x001e1e1c, 0x00000000, 0x00000000, 0x00020200, 0x00000000, 0x00000000, 0x00000201, 0x00000100, 0x00000100, 0x00000000, 0x00000000, 0x002a2c29, 0x00808280, 0x00bec0bf, 0x00c7c8c9, 0x00c8c9cb, 0x00c8c9cb, 0x00c8c9cb, 0x00c8c9cc, 0x00c8c9cc, 0x00c8c9cc, 0x00c9cacc, 0x00c9cacc, 0x00c7c8c9, 0x00c9c9c8, 0x00ccc9c6, 0x00c8c6c2, 0x00c7c8c4, 0x00caccc9, 0x00cbcbc9, 0x00c3c2bf, 0x00747470, 0x002a1c14, 0x00381700, 0x00683006, 0x00b45c1c, 0x00c0570f, 0x00c25911, 0x00bc5409, 0x00c35804, 0x00c35d08, 0x00b95d08, 0x00af5408, 0x00b1500e, 0x00be5611, 0x00cb5804, 0x00cc5800, 0x00c8550c, 0x00b9561c, 0x00934c26, 0x00501a00, 0x00451100, 0x0081543a, 0x004b2714, 0x002a0000, 0x009a5220, 0x00b75a16, 0x00c35508, 0x00ca5808, 0x00c3590b, 0x00c25b0a, 0x00c35900, 0x00c35902, 0x00c3580c, 0x00c35611, 0x00c75510, 0x00c05715, 0x00a85819, 0x006c3809, 0x00100000, 0x000b0000, 0x00451700, 0x00a05522, 0x00bd5911, 0x00c55807, 0x00bb5908, 0x00bf5e0a, 0x00c35a00, 0x00c45900, 0x00c0570e, 0x00944311, 0x003d1809, 0x000d0000, 0x001d0400, 0x005c2d0c, 0x00b7601e, 0x00c45b0c, 0x00bd570e, 0x00ab5c26, 0x00320d00, 0x00130000, 0x00330700, 0x00804011, 0x00b2601f, 0x00bb5d11, 0x00be5c0c, 0x00bf5f11, 0x00b15610, 0x007b3404, 0x00361505, 0x00655c5f, 0x00c6c6cc, 0x00c9cccc, 0x00c9c6c7, 0x00cccbc8, 0x00cccbc9, 0x00c9c9c9, 0x00cbcccc, 0x00c6c7c8, 0x00c7c8c9, 0x00c9cbca, 0x00cbcbc9, 0x00cccbc8, 0x00cccbc8, 0x00cccbc9, 0x00cbcbc9, 0x00cacccb, 0x00cacbcc, 0x00cacccb, 0x00c9ccc8, 0x00cbccc8, 0x00ccc8ca, 0x00ccc7cc, 0x00ccc8cc, 0x00cccacb, 0x00c8cbca, 0x00c4ccc9, 0x00c8cccc, 0x00c7cacb, 0x00c8c8c8, 0x00cccac9, 0x00ccc6c1, 0x00b2a8a0, 0x003b2b22, 0x00320d00, 0x00904721, 0x00a55024, 0x009a4e28, 0x00703616, 0x00280900, 0x000d0000, 0x00070000, 0x00020003, 0x00060000, 0x00170100, 0x00401806, 0x007f4021, 0x00a54c24, 0x00b04918, 0x00b85118, 0x00b04a0e, 0x00b04b0e, 0x00af480c, 0x00b34b0e, 0x00b64c0c, 0x00b94e08, 0x00bf560e, 0x00be5714, 0x00ae5117, 0x00904019, 0x00601a00, 0x004d0c00, 0x0070320d, 0x00a15e2c, 0x00995a24, 0x0080481b, 0x00451e00, 0x00140000, 0x00080000, 0x000b0000, 0x00160000, 0x00411800, 0x007b4018, 0x00a75519, 0x00bc5d15, 0x00bc5a0b, 0x00be5c08, 0x00c05c06, 0x00bb5a06, 0x00b95e10, 0x009e5418, 0x00582e0e, 0x001e0800, 0x000f0000, 0x00050000, 0x00040000, 0x00040100, 0x00080300, 0x00270f00, 0x007b3f0b, 0x00b25d1a, 0x00c05e14, 0x00c45c0c, 0x00c85f0c, 0x00c25c06, 0x00c76209, 0x00c05e05, 0x00be6008, 0x00bf620b, 0x00be6108, 0x00bd5d03, 0x00ca6408, 0x00c56208, 0x00bd6412, 0x00a15a18, 0x00572c04, 0x00200000, 0x00280800, 0x0060320d, 0x00a35c18, 0x00c06915, 0x00c5650c, 0x00ca640a, 0x00c96008, 0x00c35600, 0x00c95800, 0x00c55a0c, 0x00b45921, 0x00753310, 0x002d0c00, 0x000e0300, 0x00040600, 0x00585c57, 0x00b1ada8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00989795, 0x000b0704, 0x00040000, 0x00585454, 0x00b7b4b4, 0x00cccbcc, 0x00c8c8c9, 0x00cacbcc, 0x00929493, 0x00383938, 0x00000000, 0x00020200, 0x00000000, 0x00000000, 0x00040402, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00040402, 0x00000000, 0x00020200, 0x004b4b4b, 0x00a5a5a5, 0x00cbcbcc, 0x00c8c9cb, 0x00c8c9cc, 0x00c8c9cc, 0x00c8c9cc, 0x00c8c9cc, 0x00c7c9cc, 0x00c8c8cc, 0x00c8c9cc, 0x00cacccb, 0x00c9c8c7, 0x00c9c5c3, 0x00cccbc8, 0x00c8c7c3, 0x00c8c8c4, 0x00cbcac7, 0x00c8c8c8, 0x0096999c, 0x003c3834, 0x001c0800, 0x004d2000, 0x00b05c24, 0x00bf5813, 0x00bd550f, 0x00c25a0f, 0x00c05803, 0x00c15d08, 0x00b15809, 0x009e4703, 0x009b440e, 0x00af5017, 0x00c4580c, 0x00c85504, 0x00c8540f, 0x00bb551e, 0x00984c27, 0x00501800, 0x00370c00, 0x0071503c, 0x00391c0f, 0x002b0000, 0x00a25826, 0x00ba5c16, 0x00bf5408, 0x00c65808, 0x00c4570a, 0x00c55a0b, 0x00c25906, 0x00bf5807, 0x00be5611, 0x00c05614, 0x00c65515, 0x00c05614, 0x00b35a19, 0x00844818, 0x00160100, 0x000a0000, 0x00270300, 0x00925228, 0x00bc5a18, 0x00c55708, 0x00be5705, 0x00c15c08, 0x00c25802, 0x00c45905, 0x00c0580d, 0x009f4b16, 0x004d2410, 0x00130000, 0x00170100, 0x00481d02, 0x00b15c21, 0x00c3580e, 0x00c25814, 0x00a04f1c, 0x002c0900, 0x00140000, 0x00290400, 0x00784115, 0x00af6427, 0x00b45c14, 0x00b95b0c, 0x00b4580e, 0x009f5014, 0x00582000, 0x003c251a, 0x00b0acb1, 0x00c3c4cc, 0x00c8c8cc, 0x00ccc9c8, 0x00ccc4bf, 0x00cccbc8, 0x00c8c8c4, 0x00c6c6c6, 0x00cbcccc, 0x00c8cbcc, 0x00c9cccc, 0x00cacccb, 0x00cbcbc9, 0x00cbcbc9, 0x00cbcbcb, 0x00cbcbcb, 0x00cacbcc, 0x00cacbcc, 0x00c8cccc, 0x00c8cccb, 0x00caccc9, 0x00cccacc, 0x00ccc9cc, 0x00cccacc, 0x00cccbcc, 0x00c7cccc, 0x00c5cccc, 0x00c5caca, 0x00c9cacc, 0x00cccacb, 0x00cbc8c5, 0x00cccbc6, 0x00c0b9b4, 0x007c726c, 0x00200400, 0x00743818, 0x00984f2b, 0x008b4c2d, 0x00421600, 0x00150300, 0x00060000, 0x00020003, 0x00080001, 0x00150000, 0x003b1604, 0x0077401f, 0x009c4f26, 0x00ae4c1c, 0x00b44814, 0x00ae450c, 0x00b44d11, 0x00b34c10, 0x00b04b0d, 0x00b44c0e, 0x00b8500e, 0x00b9550d, 0x00bb5b15, 0x00ad5519, 0x00944414, 0x005c1500, 0x004b0a00, 0x00733014, 0x009d5c36, 0x00985829, 0x007c4417, 0x003b1800, 0x00150000, 0x000a0000, 0x00080000, 0x00170000, 0x003c1200, 0x00783b11, 0x00a75820, 0x00b85a14, 0x00bf5b10, 0x00bb5c10, 0x00b85e10, 0x00b45d0e, 0x00ad5e14, 0x009a5215, 0x006a350c, 0x001e0800, 0x00040000, 0x00030003, 0x00080308, 0x00060000, 0x00080000, 0x00130300, 0x00442000, 0x00955016, 0x00b95f15, 0x00c25c0f, 0x00c45b0a, 0x00c75d0c, 0x00c05908, 0x00c76210, 0x00bf600c, 0x00bc600c, 0x00be6410, 0x00bd6412, 0x00bc600c, 0x00c25f05, 0x00c46005, 0x00bf6107, 0x00b6671c, 0x00774212, 0x00381300, 0x00190000, 0x00340f00, 0x00794310, 0x00af6821, 0x00bb6411, 0x00c56109, 0x00cc650c, 0x00ca5c03, 0x00c95600, 0x00c85806, 0x00c05a19, 0x009f4f20, 0x00481700, 0x00180100, 0x00000000, 0x002c302d, 0x00908e88, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005a5a5a, 0x00060504, 0x00000000, 0x008d8c8c, 0x00c4c2c3, 0x00c6c6c6, 0x00cacaca, 0x00c8c8c8, 0x00686868, 0x000e0e0e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00010101, 0x00000000, 0x00000000, 0x00030301, 0x00000000, 0x00000000, 0x00020202, 0x00191919, 0x00838383, 0x00c5c5c5, 0x00c8c8c8, 0x00c8c8ca, 0x00c8c8ca, 0x00c8c8ca, 0x00c9c9cb, 0x00c8c9cb, 0x00c9c9cb, 0x00c8c9cb, 0x00c8c9c8, 0x00c8c9c8, 0x00c8c8ca, 0x00c8c8ca, 0x00c8c8c8, 0x00c9c8c7, 0x00cac9c8, 0x00cbc9ca, 0x00b6b4b5, 0x00676360, 0x000d0000, 0x003b1700, 0x00a05524, 0x00bc5a18, 0x00c5570e, 0x00c65406, 0x00c55804, 0x00c15a09, 0x00bc5c14, 0x00974108, 0x006a2100, 0x00944920, 0x00b85b1b, 0x00c0580b, 0x00c2560c, 0x00bc5716, 0x009e4b18, 0x00581e00, 0x002c0d00, 0x004c3827, 0x00381b11, 0x003e0d00, 0x00ad5c26, 0x00c15e16, 0x00ba5308, 0x00c65c0b, 0x00c85703, 0x00c55507, 0x00bf5712, 0x00b65114, 0x00b34e11, 0x00b95010, 0x00be510b, 0x00c45b12, 0x00b65914, 0x0097511c, 0x00290800, 0x000f0000, 0x00170000, 0x00704220, 0x00ab5418, 0x00c4580b, 0x00c55602, 0x00c65704, 0x00c3580e, 0x00be570e, 0x00bf590f, 0x00a75217, 0x00633013, 0x00170000, 0x00120000, 0x00361200, 0x00af5e28, 0x00c05912, 0x00c05811, 0x00a95520, 0x00310c00, 0x00110000, 0x00280400, 0x007a441a, 0x00a75c20, 0x00b85d17, 0x00bc570b, 0x00b75d1c, 0x007a4017, 0x00381703, 0x00645650, 0x00c9c9cb, 0x00c4c7c8, 0x00c8cccc, 0x00cbcac8, 0x00ccc9c7, 0x00cbcac8, 0x00cacac8, 0x00cacaca, 0x00cacaca, 0x00c9cbca, 0x00c9cbca, 0x00cccccc, 0x00c8c8c8, 0x00c6c6c6, 0x00cccccc, 0x00cccccc, 0x00c7c7c7, 0x00cccccc, 0x00c8cac9, 0x00cbcccc, 0x00c8c8c8, 0x00cccbcc, 0x00c8c7c8, 0x00cccacb, 0x00cccccc, 0x00c8c9c8, 0x00c9cbca, 0x00c8c9c8, 0x00cccccc, 0x00cacaca, 0x00cac9c8, 0x00c8c8c6, 0x00ccc9c7, 0x00b0acaa, 0x00281810, 0x00431804, 0x0087513a, 0x0063331c, 0x00240400, 0x000a0000, 0x00010108, 0x00000004, 0x00160501, 0x003b1300, 0x00743a16, 0x009c5325, 0x00a4501c, 0x00ab4c17, 0x00b04a14, 0x00b34a14, 0x00b74d14, 0x00b54a11, 0x00b4480c, 0x00bc4f10, 0x00bd5615, 0x00b45816, 0x00a7581c, 0x00824012, 0x00531700, 0x00490c00, 0x0072321e, 0x00965438, 0x0097583a, 0x00723f20, 0x00371300, 0x000c0000, 0x00070000, 0x00100100, 0x00130000, 0x003c1000, 0x00834518, 0x00a9581c, 0x00b3540f, 0x00c05c14, 0x00bb5811, 0x00b35916, 0x00ad5d20, 0x0095511d, 0x007e461d, 0x00582c10, 0x00210400, 0x00080000, 0x00030200, 0x00010004, 0x00020004, 0x00070000, 0x00100000, 0x001f0000, 0x00733d11, 0x00ad5d1f, 0x00bb5b0f, 0x00c25c0a, 0x00c45c08, 0x00c15b0a, 0x00be5b0b, 0x00c05d0b, 0x00c0600c, 0x00c05e0b, 0x00bb5c0c, 0x00b4601b, 0x00a3500a, 0x00bc5f0e, 0x00c06008, 0x00c06007, 0x00ba6415, 0x00a05b22, 0x00602c09, 0x001f0000, 0x001a0000, 0x003c1b04, 0x00825126, 0x00b16522, 0x00c46713, 0x00c45f04, 0x00cc6105, 0x00c85b04, 0x00c25404, 0x00c7590e, 0x00ba5a1d, 0x006d2a05, 0x002b0400, 0x000c0400, 0x000a0f0c, 0x00666664, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000c0c0c, 0x00383838, 0x00040404, 0x00191919, 0x00a6a6a6, 0x00c8c8c8, 0x00cacaca, 0x00cacaca, 0x00b5b5b5, 0x00535353, 0x00050505, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00060606, 0x006d6d6d, 0x00bfbfbf, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c7c8c6, 0x00c8c9c8, 0x00c6c9cc, 0x00c5c8cb, 0x00c8c8c9, 0x00c8c7c8, 0x00ccc8c9, 0x00ccc9ca, 0x00c8c5c4, 0x007e7a78, 0x001b120d, 0x00331402, 0x00914d21, 0x00b75818, 0x00c5540b, 0x00c95303, 0x00c45503, 0x00c2580a, 0x00b85411, 0x0094400c, 0x00541400, 0x00773819, 0x00a75419, 0x00bc5b12, 0x00bf570c, 0x00bf5813, 0x00a44d14, 0x005d2000, 0x001f0600, 0x002b1d0d, 0x002f1208, 0x00511d05, 0x00b15b21, 0x00bf590f, 0x00c05a0e, 0x00be5705, 0x00c95804, 0x00c55708, 0x00b4541b, 0x00963b08, 0x00963400, 0x00b85315, 0x00c1570e, 0x00be5609, 0x00ba5910, 0x00a4561f, 0x00441900, 0x00130000, 0x000f0000, 0x004d2a0e, 0x00a2541d, 0x00c05910, 0x00c55300, 0x00c95704, 0x00c25711, 0x00bf5814, 0x00c05910, 0x00ac5717, 0x006e3512, 0x001c0000, 0x00100000, 0x002e0c00, 0x00a25623, 0x00b95611, 0x00be5610, 0x00ab5720, 0x00340c00, 0x00120000, 0x00240100, 0x00764119, 0x00a85c20, 0x00ba5c16, 0x00be570d, 0x00ab5315, 0x00613315, 0x00342118, 0x008d8883, 0x00c9cbc8, 0x00caccc9, 0x00c5c9c6, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c8c8c8, 0x00cccccc, 0x00cacaca, 0x00c7c7c7, 0x00c6c6c6, 0x00cbcbcb, 0x00c6c6c6, 0x00c9c9c9, 0x00cccccc, 0x00c8c8c8, 0x00c3c3c3, 0x00cccccc, 0x00c3c3c3, 0x00cbcbcb, 0x00cacaca, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00c9c9c9, 0x00cccccc, 0x00bdbdbd, 0x0057504c, 0x00200800, 0x0068493d, 0x00391a0c, 0x00160000, 0x00040001, 0x00040005, 0x00120402, 0x00341304, 0x00703412, 0x009f5020, 0x00a8501c, 0x00a54610, 0x00b3501a, 0x00b45018, 0x00ab440f, 0x00b1480e, 0x00b84b0c, 0x00be5211, 0x00c0561a, 0x00b85c21, 0x00a25621, 0x0076380c, 0x00481600, 0x00360700, 0x00612d17, 0x008b533e, 0x008f5840, 0x005e2d17, 0x002a0800, 0x00100000, 0x00040000, 0x00080100, 0x00130000, 0x00431600, 0x007f4118, 0x00a85920, 0x00ba5e1c, 0x00bc5d17, 0x00b35918, 0x00a9581c, 0x009b5424, 0x007b4018, 0x00502004, 0x002d0800, 0x00140000, 0x000b0000, 0x00060000, 0x00030102, 0x00000003, 0x00040305, 0x00040000, 0x00110000, 0x00481d00, 0x00904f1c, 0x00b75d18, 0x00c05a09, 0x00c25906, 0x00c35c08, 0x00c45f0d, 0x00bc5909, 0x00bc5a08, 0x00c15c0b, 0x00bc5a08, 0x00bb6017, 0x00aa6028, 0x00611800, 0x00a14b03, 0x00bd600c, 0x00bf5d06, 0x00c06312, 0x00b66524, 0x00844819, 0x003c1600, 0x00110000, 0x001b0500, 0x00512f15, 0x00a36028, 0x00b75f11, 0x00c66309, 0x00cb6205, 0x00c55b07, 0x00c25504, 0x00c85707, 0x00be5812, 0x00904114, 0x00410f00, 0x000c0000, 0x00010300, 0x00484848, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b2b2b2, 0x00121212, 0x00000000, 0x003a3a3a, 0x00b8b8b8, 0x00cbcbcb, 0x00cccccc, 0x00c8c8c8, 0x00a6a6a6, 0x00444444, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00020202, 0x00030303, 0x00000000, 0x00030303, 0x00010101, 0x00000000, 0x00000000, 0x00606060, 0x00b8b8b8, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c6, 0x00c7c8c8, 0x00c5c8cb, 0x00c5c8cb, 0x00c7c7c8, 0x00c8c7c8, 0x00c9c8c8, 0x00cac8c9, 0x00ccccca, 0x0094908e, 0x002f2824, 0x002c0f00, 0x00824014, 0x00b45718, 0x00c4550c, 0x00c85506, 0x00c45504, 0x00c45a0c, 0x00b6520f, 0x00984410, 0x00460900, 0x005c2104, 0x00974912, 0x00ba5d18, 0x00bf580e, 0x00be5812, 0x00a65016, 0x00672900, 0x001b0000, 0x00100200, 0x00260700, 0x006c3419, 0x00b25920, 0x00bd550a, 0x00c35c0f, 0x00bc5404, 0x00c55804, 0x00bf5810, 0x00984617, 0x006d2000, 0x00842800, 0x00bb581b, 0x00c45b13, 0x00bc5304, 0x00be580c, 0x00aa581c, 0x005c2c11, 0x00140000, 0x000e0000, 0x002c0c00, 0x0099501d, 0x00bc5913, 0x00c25300, 0x00c95705, 0x00c2550f, 0x00c05813, 0x00bd560c, 0x00b05817, 0x00743a16, 0x00210000, 0x000d0000, 0x00280900, 0x00954b1a, 0x00b75614, 0x00bb5610, 0x00ad5c22, 0x00360d00, 0x00150000, 0x001f0000, 0x00713c18, 0x00aa5920, 0x00b95914, 0x00bc580e, 0x009c4a0e, 0x00492105, 0x0044362c, 0x00bcb8b4, 0x00cacac8, 0x00ccccca, 0x00c8c8c6, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00cacaca, 0x00c8c8c8, 0x00cccccc, 0x00c6c6c6, 0x00c8c8c8, 0x00cacaca, 0x00c4c4c4, 0x00cccccc, 0x00c7c7c7, 0x00cccccc, 0x00cacaca, 0x00c8c8c8, 0x00cccccc, 0x00c2c2c2, 0x00c9c9c9, 0x00c8c8c8, 0x00cacaca, 0x00c8c8c8, 0x00c9c9c9, 0x00c8c8c8, 0x00cacaca, 0x00cbcbcb, 0x00c7c7c7, 0x008d8c8b, 0x00070403, 0x002e2825, 0x00100300, 0x000e0000, 0x000b0000, 0x00130000, 0x00401808, 0x007a3d20, 0x00a55226, 0x00ae4c18, 0x00b04a14, 0x00b24913, 0x00b04710, 0x00ab440d, 0x00ad4914, 0x00b95416, 0x00c05509, 0x00c0580d, 0x00b1571a, 0x009e5224, 0x0073381c, 0x00340700, 0x001f0000, 0x00391100, 0x004f230a, 0x005b3019, 0x00482516, 0x00210a00, 0x000a0000, 0x00060000, 0x00080000, 0x00160000, 0x00481800, 0x00914f24, 0x00af5c28, 0x00b2581c, 0x00b35918, 0x00a95818, 0x00985723, 0x0074431d, 0x00431d08, 0x00200200, 0x00130000, 0x00100000, 0x000b0000, 0x00070000, 0x00040001, 0x00040003, 0x00040000, 0x000f0807, 0x00030000, 0x00120000, 0x00643616, 0x00a05721, 0x00bc5a0f, 0x00c75a04, 0x00c45905, 0x00c05906, 0x00c35e0c, 0x00c05b09, 0x00c25b08, 0x00c45e0c, 0x00ba5c0f, 0x00b26121, 0x007e4419, 0x00360000, 0x009d4d0f, 0x00ba5c10, 0x00c15d08, 0x00c0600c, 0x00b46014, 0x00a05d20, 0x0060340e, 0x001d0000, 0x000e0000, 0x00280c00, 0x007f4214, 0x00b7641e, 0x00c66510, 0x00c75f04, 0x00c75d07, 0x00c55804, 0x00c85604, 0x00bd550f, 0x00ac5928, 0x00562002, 0x00100000, 0x00000000, 0x00282627, 0x0088888a, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a5a5a5, 0x00000000, 0x00000000, 0x00575757, 0x00bbbbbb, 0x00c9c9c9, 0x00cccccc, 0x00c6c6c6, 0x00a8a8a8, 0x00474747, 0x00000000, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00626262, 0x00b2b2b2, 0x00c6c6c6, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c5, 0x00c7c8c8, 0x00c5c8cb, 0x00c4c8ca, 0x00c7c7c8, 0x00c8c6c7, 0x00c9c8c8, 0x00cac8c9, 0x00c9c8c7, 0x00a3a09d, 0x00423c38, 0x00240b00, 0x00763509, 0x00b5581b, 0x00c2560e, 0x00c85608, 0x00c45506, 0x00c3580c, 0x00b85410, 0x009d4b16, 0x00430800, 0x00420d00, 0x0088400e, 0x00b65d1c, 0x00c05a11, 0x00bb540f, 0x00aa5118, 0x00713408, 0x00190000, 0x000e0000, 0x00250100, 0x00844828, 0x00b4571c, 0x00bf540a, 0x00c0580b, 0x00c05809, 0x00bf5708, 0x00b05414, 0x006e2b05, 0x00511200, 0x008a3505, 0x00bc5a1c, 0x00c25911, 0x00c05407, 0x00c2580a, 0x00ac5414, 0x00743e1f, 0x00180000, 0x000c0000, 0x001a0000, 0x00894518, 0x00b35614, 0x00c25506, 0x00c75505, 0x00c2540d, 0x00c05510, 0x00bd5508, 0x00b25918, 0x00793e18, 0x00240000, 0x000d0000, 0x00240800, 0x00854013, 0x00b55919, 0x00b95813, 0x00b05f25, 0x003c1000, 0x00190000, 0x001b0000, 0x006a3618, 0x00ab5720, 0x00b85611, 0x00b85810, 0x0090450c, 0x00391800, 0x00595149, 0x00ccc8c5, 0x00c9c8c7, 0x00cac9c8, 0x00ccccca, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c7c7c7, 0x00c2c2c2, 0x00cacaca, 0x00c6c6c6, 0x00cccccc, 0x00c7c7c7, 0x00c1c1c1, 0x00bebebe, 0x00bababa, 0x00c8c8c8, 0x00bfbfbf, 0x00c0c0c0, 0x00c5c5c5, 0x00cbcbcb, 0x00c9c9c9, 0x00c9c9c9, 0x00cacaca, 0x00c8c8c8, 0x00cccccc, 0x00c8c8c8, 0x00cbcbcb, 0x00c8c8c8, 0x00c7c7c7, 0x00b0b1b3, 0x00080f10, 0x00000000, 0x00090000, 0x00100000, 0x001e0000, 0x004d2013, 0x0087482c, 0x009d4d24, 0x00ac4c1a, 0x00ae450d, 0x00b44813, 0x00b74913, 0x00b3440c, 0x00b84b11, 0x00ba5419, 0x00b34e10, 0x00bc5510, 0x00bb5e1c, 0x00a05420, 0x00622400, 0x00340000, 0x00400f00, 0x00582105, 0x00491200, 0x003d0700, 0x00320100, 0x00200000, 0x00170000, 0x00100000, 0x000c0000, 0x00170300, 0x0034140a, 0x00895535, 0x009f5a2c, 0x00b05f2a, 0x00ab5720, 0x00a45821, 0x00864718, 0x00431a00, 0x00200400, 0x000c0000, 0x00080000, 0x000c0304, 0x00060000, 0x00030000, 0x00070202, 0x00040002, 0x00040000, 0x00050000, 0x00090000, 0x00080000, 0x00341b0a, 0x00885029, 0x00b26024, 0x00c35c0b, 0x00ca5903, 0x00c45c08, 0x00be5808, 0x00c05a0b, 0x00c45c0c, 0x00c25805, 0x00c05c0c, 0x00b9611a, 0x00a05923, 0x00441500, 0x00310000, 0x00a0541c, 0x00b85c13, 0x00c45f0c, 0x00c46009, 0x00b85d0a, 0x00b46820, 0x00844c17, 0x003f1800, 0x00100000, 0x001b0100, 0x004c1800, 0x00aa6026, 0x00bc6114, 0x00c56008, 0x00c75d06, 0x00c85a05, 0x00c85705, 0x00bc540b, 0x00b85f28, 0x006e300d, 0x00220800, 0x00080200, 0x00100c0c, 0x00686868, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00949494, 0x00000000, 0x00040404, 0x00727272, 0x00bdbdbd, 0x00c9c9c9, 0x00cacaca, 0x00c7c7c7, 0x00b5b5b5, 0x00515151, 0x00010101, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00707070, 0x00bcbcbc, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c5, 0x00c6c8c7, 0x00c4c8ca, 0x00c4c8ca, 0x00c7c7c8, 0x00c8c6c7, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00afaeac, 0x0054504c, 0x00220900, 0x006c2e03, 0x00b55c1f, 0x00c0570f, 0x00c45407, 0x00c45507, 0x00c05509, 0x00b85510, 0x009b4916, 0x00400c00, 0x002e0000, 0x0078370b, 0x00ac591d, 0x00be5b14, 0x00b9530d, 0x00ae551c, 0x007b3b10, 0x00180000, 0x00110000, 0x002b0100, 0x00975431, 0x00b65619, 0x00c25409, 0x00bf5507, 0x00c0580d, 0x00bb5a11, 0x00924109, 0x00451200, 0x004a1600, 0x00954617, 0x00b75617, 0x00be550c, 0x00c35607, 0x00c45607, 0x00b35614, 0x008c4f2c, 0x00200000, 0x000c0000, 0x00150000, 0x0070340d, 0x00a65015, 0x00c1590e, 0x00c55405, 0x00c4540d, 0x00c2540d, 0x00c3580a, 0x00b85c19, 0x007f401a, 0x00290400, 0x000c0000, 0x001f0400, 0x00733308, 0x00b05a1e, 0x00b85914, 0x00b05f24, 0x00481800, 0x001e0000, 0x00190000, 0x00643018, 0x00aa541e, 0x00ba5511, 0x00b75813, 0x00843e08, 0x00381d07, 0x006b6860, 0x00ccc9c5, 0x00ccc8c8, 0x00ccc8c8, 0x00cccacb, 0x00c9c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00cccccc, 0x00cccccc, 0x00c0c0c0, 0x00cccccc, 0x00c2c2c2, 0x00bbbbbb, 0x00828282, 0x00484848, 0x003c3c3c, 0x00383838, 0x00696969, 0x00adadad, 0x00c4c4c4, 0x00c8c8c8, 0x00c4c4c4, 0x00cbcbcb, 0x00c8c8c8, 0x00c8c8c8, 0x00cbcbcb, 0x00c8c8c8, 0x00cccccc, 0x00cccccc, 0x00c8c8c8, 0x00c3c3c3, 0x0020211f, 0x00090400, 0x00120000, 0x00290200, 0x00683320, 0x008f4c2f, 0x009f4c23, 0x00ab4f1c, 0x00ac4813, 0x00b44b14, 0x00b44816, 0x00b64814, 0x00c04b10, 0x00c14d0e, 0x00c05310, 0x00c25d20, 0x00b45a2a, 0x008e421c, 0x004c1000, 0x00320000, 0x00642404, 0x009e522c, 0x00b55b2c, 0x00b75924, 0x00ac581b, 0x009f5418, 0x00874714, 0x00672e09, 0x00441000, 0x00290000, 0x00230100, 0x00300f00, 0x0060381e, 0x00895837, 0x009c5f38, 0x008a4d26, 0x00552101, 0x00230000, 0x00130000, 0x00080000, 0x00070000, 0x00020000, 0x00000000, 0x00000001, 0x00000006, 0x00040309, 0x00050001, 0x000f0305, 0x00241918, 0x000b0000, 0x00160000, 0x00613619, 0x009f5724, 0x00b85b15, 0x00c15706, 0x00c45704, 0x00bd5a0d, 0x00be5c10, 0x00bf580b, 0x00c45b0b, 0x00be5401, 0x00bd5b10, 0x00b06024, 0x00783a0d, 0x002a0000, 0x00481800, 0x00a05420, 0x00bd5f18, 0x00c25d0b, 0x00c25c04, 0x00c26107, 0x00b9620e, 0x00a55c16, 0x00632f00, 0x00170000, 0x00140000, 0x00280100, 0x00793d11, 0x00b1601c, 0x00c56411, 0x00c75f07, 0x00ca5c04, 0x00c85705, 0x00c1550c, 0x00b85b1d, 0x00884217, 0x00361403, 0x000c0000, 0x00040000, 0x004b4a48, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00858585, 0x00020202, 0x00000000, 0x00828282, 0x00c0c0c0, 0x00c9c9c9, 0x00c8c8c8, 0x00c9c9c9, 0x00c2c2c2, 0x00686868, 0x000e0e0e, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00151515, 0x00848484, 0x00cacaca, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c4, 0x00c5c7c6, 0x00c4c7c9, 0x00c4c7c9, 0x00c6c6c8, 0x00c6c6c6, 0x00c7c7c7, 0x00c7c8c8, 0x00c8c9c8, 0x00b2b4b1, 0x005d5a58, 0x001c0600, 0x00602400, 0x00b35c20, 0x00be5611, 0x00c45408, 0x00c4570a, 0x00bf540a, 0x00b95611, 0x00964713, 0x003e0d00, 0x00200000, 0x00672d07, 0x00a1541d, 0x00bb5915, 0x00ba540e, 0x00b3591e, 0x00813f14, 0x00180000, 0x00160000, 0x00390a00, 0x00a45c33, 0x00bc5818, 0x00c35409, 0x00c3580c, 0x00bb570f, 0x00b35a1b, 0x006c2700, 0x002d0400, 0x0050240e, 0x009e5121, 0x00b65412, 0x00c0560c, 0x00c45405, 0x00c45202, 0x00bc5814, 0x009d5830, 0x002c0400, 0x000c0000, 0x00140100, 0x00542000, 0x009b4c16, 0x00bf5b13, 0x00c45406, 0x00c5540e, 0x00c4540d, 0x00c45708, 0x00b75a16, 0x0082421b, 0x002e0800, 0x000c0000, 0x001a0300, 0x00612801, 0x00b05e24, 0x00b75814, 0x00af5c20, 0x00582405, 0x00240200, 0x00170000, 0x00582815, 0x00a54f1c, 0x00bc5714, 0x00b45818, 0x00763503, 0x003b2413, 0x00767572, 0x00cccac8, 0x00cccaca, 0x00cccacc, 0x00cac5c7, 0x00c8c7c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c8c8c8, 0x00c2c2c2, 0x00c6c6c6, 0x00cacaca, 0x00bbbbbb, 0x009b9b9b, 0x002d2d2d, 0x00040404, 0x00050505, 0x00020202, 0x00030303, 0x00080808, 0x00161616, 0x006e6e6e, 0x00b2b2b2, 0x00c5c5c5, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c8c8c8, 0x00c5c5c5, 0x00c8c8c8, 0x00cccccc, 0x00c9c9c9, 0x00c7c6c4, 0x003c3836, 0x00140400, 0x00411807, 0x0080432b, 0x00954828, 0x00a24a21, 0x00ad4e19, 0x00ab480e, 0x00b04a11, 0x00b24c13, 0x00b54b17, 0x00ba4c16, 0x00c35014, 0x00c65617, 0x00bb5818, 0x00ac541d, 0x00782c05, 0x00410000, 0x00400700, 0x007b3e14, 0x00a55b25, 0x00b45a1d, 0x00c05714, 0x00c35610, 0x00c35d13, 0x00b85911, 0x00ad5614, 0x00aa5822, 0x00ab5b34, 0x0099502f, 0x006d320e, 0x00461400, 0x002e0000, 0x00350500, 0x004a1800, 0x00350800, 0x001a0000, 0x00160000, 0x00070000, 0x00020004, 0x00000000, 0x00000000, 0x00040000, 0x000c0100, 0x000f0000, 0x00100000, 0x00260c04, 0x00503830, 0x0054413b, 0x001e0700, 0x003a1100, 0x008b4e24, 0x00b25d20, 0x00be5a10, 0x00c45809, 0x00c65c0c, 0x00bc580e, 0x00be5c10, 0x00bd5709, 0x00c25c0e, 0x00c05c12, 0x00b8601f, 0x008e4b19, 0x003f0900, 0x00270000, 0x007a4321, 0x00ab5c24, 0x00ba5c14, 0x00c05e0d, 0x00c05c06, 0x00c05d02, 0x00ba5c04, 0x00b45f12, 0x00894912, 0x00311200, 0x000e0000, 0x00190000, 0x00401400, 0x00a45d27, 0x00bb6218, 0x00c45f09, 0x00c85c04, 0x00c85604, 0x00c6580d, 0x00bc5814, 0x00a15320, 0x004a1f08, 0x000d0000, 0x00060000, 0x00373433, 0x00a09c9f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00828282, 0x00010101, 0x00000000, 0x00848484, 0x00c0c0c0, 0x00c9c9c9, 0x00c8c8c8, 0x00c8c8c8, 0x00c6c6c6, 0x00949494, 0x003c3c3c, 0x00030303, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00090909, 0x004b4b4b, 0x00a2a2a2, 0x00c6c6c6, 0x00c5c5c5, 0x00c5c5c5, 0x00c5c5c5, 0x00c5c5c5, 0x00c5c5c5, 0x00c5c5c5, 0x00c5c5c5, 0x00c5c5c5, 0x00c5c4c3, 0x00c5c5c5, 0x00c3c6c8, 0x00c2c5c8, 0x00c4c4c6, 0x00c5c5c5, 0x00c6c6c6, 0x00c6c8c7, 0x00c5c8c9, 0x00afb2b1, 0x005e5d5c, 0x00170300, 0x00581d00, 0x00b15c21, 0x00bc5713, 0x00c4550c, 0x00c2570b, 0x00bf560d, 0x00b95512, 0x00944614, 0x003b0e00, 0x001a0000, 0x00552302, 0x00944c1b, 0x00b85817, 0x00bc5510, 0x00b75a1c, 0x00884315, 0x00270400, 0x001b0000, 0x00501a00, 0x00ac5c2d, 0x00bd5614, 0x00c45408, 0x00c2560c, 0x00b75614, 0x009c4f18, 0x004b1200, 0x00220000, 0x005a311a, 0x00a75826, 0x00ba5510, 0x00c65809, 0x00c65402, 0x00c45001, 0x00bf5814, 0x00a4572b, 0x00461500, 0x000f0000, 0x000e0000, 0x00390e00, 0x00924b1c, 0x00b85815, 0x00c45408, 0x00c6530c, 0x00c6540a, 0x00c25204, 0x00b85813, 0x00854319, 0x00340b00, 0x000d0000, 0x00160100, 0x00531d00, 0x00ae602c, 0x00b85815, 0x00b25a1e, 0x006a3110, 0x002b0500, 0x00140000, 0x004c2010, 0x009b4815, 0x00b95815, 0x00b0571a, 0x00713204, 0x003b2618, 0x00818181, 0x00cccbca, 0x00cccaca, 0x00cccacc, 0x00c8c4c7, 0x00c8c6c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00c7c7c7, 0x00cccccc, 0x00c8c8c8, 0x00c3c3c3, 0x00999999, 0x00232323, 0x00010101, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00060606, 0x000f0f0f, 0x00696969, 0x00b5b5b5, 0x00c8c8c8, 0x00c7c7c7, 0x00c6c6c6, 0x00c6c6c6, 0x00c5c5c5, 0x00c5c5c5, 0x00cacaca, 0x00cacaca, 0x00c4c1c2, 0x0041393a, 0x0030130c, 0x00804028, 0x00ad5430, 0x00a84314, 0x00b04610, 0x00b24c10, 0x00ac4a0a, 0x00ac4b0a, 0x00b24d10, 0x00bc5216, 0x00bd5015, 0x00bd5317, 0x00ba5c22, 0x008f4715, 0x00541800, 0x003c0000, 0x00622200, 0x00945114, 0x00ad641c, 0x00b35e0c, 0x00b95c05, 0x00c45f07, 0x00c25c04, 0x00bc5504, 0x00bf570a, 0x00c45914, 0x00c45816, 0x00bd5314, 0x00b85315, 0x00b05414, 0x00a65318, 0x00893f0e, 0x005c1d00, 0x00310300, 0x001e0000, 0x00140000, 0x000b0000, 0x00050002, 0x00000004, 0x00000103, 0x00080300, 0x00140000, 0x002c0200, 0x00521800, 0x00783711, 0x008c5230, 0x008c5d42, 0x003c1d0c, 0x00250200, 0x00662b04, 0x00a4541e, 0x00bb5c17, 0x00be570d, 0x00bc5409, 0x00bc550a, 0x00c1590c, 0x00c05809, 0x00c05708, 0x00bd5a12, 0x00b35e21, 0x00924d1c, 0x00542200, 0x00260000, 0x00491000, 0x00a15a2d, 0x00b55e1c, 0x00b5580c, 0x00bc6314, 0x00bc6110, 0x00be5d09, 0x00c3600e, 0x00b95b0e, 0x00a95c20, 0x005c310e, 0x00160000, 0x00100000, 0x001e0300, 0x00763e15, 0x00ad6022, 0x00c0600f, 0x00c85c04, 0x00c85705, 0x00c65608, 0x00c2580d, 0x00b35c23, 0x005c290d, 0x001a0000, 0x000b0000, 0x0024211f, 0x00837c80, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00868686, 0x00000000, 0x00030303, 0x00848484, 0x00bfbfbf, 0x00cacaca, 0x00cacaca, 0x00c4c4c4, 0x00c4c4c4, 0x00bcbcbc, 0x00737373, 0x00161616, 0x00000000, 0x00040404, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x00000000, 0x00232323, 0x008b8b8b, 0x00c4c4c4, 0x00c1c1c1, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c2, 0x00c4c4c4, 0x00c2c5c8, 0x00c1c4c7, 0x00c3c4c5, 0x00c4c4c4, 0x00c4c6c5, 0x00c4c7c6, 0x00c7cacb, 0x00afb2b1, 0x0060605e, 0x00170300, 0x00541a00, 0x00af5c21, 0x00b95512, 0x00c0540c, 0x00bf5309, 0x00bf560e, 0x00b65410, 0x00944716, 0x00340e00, 0x00160000, 0x00451800, 0x00884619, 0x00b65818, 0x00bc560f, 0x00b65819, 0x008e4616, 0x00381000, 0x00230000, 0x00662807, 0x00ae5a26, 0x00bc530f, 0x00c45408, 0x00bf530b, 0x00b5581b, 0x00813f14, 0x00390b00, 0x001f0000, 0x0063381c, 0x00ad5c24, 0x00bc540b, 0x00c85707, 0x00c85300, 0x00c55204, 0x00be5613, 0x00a85321, 0x00642a0c, 0x00140100, 0x000a0000, 0x002a0400, 0x008c4c25, 0x00b25616, 0x00c4550c, 0x00c45009, 0x00c85308, 0x00c55405, 0x00ba5814, 0x008b451b, 0x003a0f00, 0x000e0000, 0x000f0000, 0x00461400, 0x00a85d2c, 0x00b85918, 0x00b5581b, 0x007a3915, 0x00310800, 0x00130000, 0x003f190b, 0x00914213, 0x00b55818, 0x00ab541a, 0x0072340b, 0x00382317, 0x008b898c, 0x00ccc8c8, 0x00ccc9c9, 0x00c8c6c7, 0x00c8c7c9, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c6c6c6, 0x00c5c5c5, 0x00c5c5c5, 0x00a6a6a6, 0x00494949, 0x000a0a0a, 0x00000000, 0x00000000, 0x00000000, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00262626, 0x00848484, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c5c5c5, 0x00c8c8c8, 0x00c6c6c6, 0x00cbcbcb, 0x00cccccc, 0x00c5c2c3, 0x00544749, 0x002e0b04, 0x00904429, 0x00a84419, 0x00b4430e, 0x00bc4a0d, 0x00ae4402, 0x00b4500a, 0x00b75712, 0x00b65717, 0x00b8571e, 0x00ba5b26, 0x00a94e1c, 0x00752800, 0x00440c00, 0x003a0800, 0x00763a06, 0x009c5818, 0x00b46617, 0x00bb650a, 0x00c66907, 0x00ca6803, 0x00c66300, 0x00c86403, 0x00cb6309, 0x00c85c08, 0x00c95809, 0x00c85508, 0x00c75505, 0x00c75807, 0x00c6580c, 0x00bd5710, 0x00b3561a, 0x00a15522, 0x00824720, 0x00491e00, 0x00200100, 0x00110000, 0x00060000, 0x00080304, 0x00110908, 0x00382418, 0x00693a1a, 0x00904b1d, 0x00a44e18, 0x00a9541d, 0x009c5528, 0x0078401c, 0x00260000, 0x003c1000, 0x00984f1c, 0x00b35716, 0x00bc560d, 0x00c0560a, 0x00c0580f, 0x00c05a10, 0x00c4590d, 0x00bc5409, 0x00bc5c17, 0x00ad581d, 0x00904e20, 0x005b2804, 0x00280000, 0x003a0800, 0x00924c21, 0x00ae5b20, 0x00b45811, 0x00b85d12, 0x00af5f18, 0x00ac5c18, 0x00b45c18, 0x00ba5f18, 0x00b85c16, 0x00b26225, 0x007c4418, 0x00331000, 0x000c0000, 0x000f0000, 0x00381000, 0x00a36330, 0x00b96115, 0x00c65d07, 0x00c85808, 0x00c45304, 0x00c55708, 0x00bb5d1e, 0x006c3010, 0x00300f00, 0x000a0000, 0x0015110e, 0x006a6367, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008e8e8e, 0x00020202, 0x00000100, 0x00777878, 0x00bcbdbc, 0x00cbcccc, 0x00c4c6c5, 0x00c2c4c3, 0x00c6c8c7, 0x00c0c2c1, 0x00b0b1b0, 0x00676868, 0x001c1d1c, 0x00000000, 0x00000100, 0x00010302, 0x00000000, 0x00000000, 0x00000000, 0x00000100, 0x00000000, 0x00242625, 0x007a7c7b, 0x00b9bbba, 0x00c6c8c7, 0x00c2c4c3, 0x00c3c4c4, 0x00c3c4c4, 0x00c3c4c4, 0x00c3c4c4, 0x00c3c4c4, 0x00c3c4c4, 0x00c3c4c4, 0x00c4c4c4, 0x00c4c4c2, 0x00c4c4c4, 0x00c2c5c8, 0x00c4c7c9, 0x00c4c6c5, 0x00c3c3c1, 0x00c1c3c2, 0x00c3c6c5, 0x00c8cbcc, 0x00a9acac, 0x00545452, 0x00160100, 0x00501800, 0x00ab581f, 0x00bc5816, 0x00c0540c, 0x00c1550c, 0x00bf560e, 0x00b65514, 0x008c4414, 0x00300f00, 0x00140000, 0x00340b00, 0x0083431a, 0x00b55b1c, 0x00bd5710, 0x00b75615, 0x00954818, 0x00481a03, 0x00270000, 0x007a3810, 0x00af561d, 0x00c05510, 0x00c45309, 0x00bf5610, 0x00b45d24, 0x00602705, 0x002b0300, 0x002d0800, 0x006e3b18, 0x00b05b1c, 0x00c15405, 0x00ca5402, 0x00ca5301, 0x00c35005, 0x00bf5614, 0x00ab501a, 0x007f3e18, 0x00160000, 0x000c0000, 0x001f0000, 0x007b4020, 0x00b0581c, 0x00c1550d, 0x00c8540c, 0x00c85208, 0x00c55405, 0x00bc5a15, 0x008c4419, 0x003e1100, 0x000b0000, 0x00100000, 0x00370a00, 0x00a65d30, 0x00bb581a, 0x00b55315, 0x00985027, 0x00370800, 0x00140000, 0x002e0d00, 0x00843d10, 0x00b1581f, 0x00ab5720, 0x006f3009, 0x003a2219, 0x00898489, 0x00ccc7c8, 0x00ccc8c8, 0x00cccccc, 0x00c3c4c5, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c3c3c3, 0x00c5c5c5, 0x008b8b8b, 0x00111111, 0x00070707, 0x00000000, 0x00000000, 0x00030303, 0x00000000, 0x00040404, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00626262, 0x00b4b4b4, 0x00c3c3c3, 0x00c4c4c4, 0x00c9c9c9, 0x00c0c0c0, 0x00cbcbcb, 0x00cccccc, 0x00c3c3c3, 0x00ccc7c7, 0x00483939, 0x00361006, 0x00904428, 0x00ac481d, 0x00b64711, 0x00ba4809, 0x00bb4f07, 0x00bd560b, 0x00bb5c14, 0x00b45f20, 0x00a3572a, 0x007f3915, 0x00531200, 0x00400500, 0x005c2400, 0x00874d14, 0x00a7641d, 0x00b36414, 0x00c0660c, 0x00c86607, 0x00ca6601, 0x00cc6600, 0x00ca6600, 0x00cb6700, 0x00cc6403, 0x00cc6408, 0x00cc640b, 0x00cc630c, 0x00c96108, 0x00c75d06, 0x00c45806, 0x00c1550c, 0x00bd5815, 0x00b45719, 0x00af561c, 0x009e5320, 0x00743c12, 0x003c1800, 0x001d0c00, 0x00180900, 0x00492e24, 0x0082543f, 0x009c5128, 0x00b0551d, 0x00b6581b, 0x00b35d25, 0x008c4c24, 0x00441100, 0x00250000, 0x00743d19, 0x00a7551c, 0x00b7540d, 0x00c1570b, 0x00c25408, 0x00c0580c, 0x00bb550b, 0x00bf580e, 0x00b95c18, 0x00a45824, 0x0082481f, 0x004d2207, 0x00210000, 0x00390a00, 0x007f4116, 0x00ad5c20, 0x00b35610, 0x00bf6014, 0x00a85109, 0x00914e14, 0x00894c1b, 0x00935020, 0x00a95f2e, 0x00b0602b, 0x00ab5d27, 0x009d5a27, 0x005e3009, 0x000e0000, 0x00080000, 0x001d0500, 0x0072421a, 0x00b3641f, 0x00bd5b08, 0x00c85b0c, 0x00c95809, 0x00c65402, 0x00bc5815, 0x0087421b, 0x003c1400, 0x000c0000, 0x00090502, 0x0050484c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9c9c, 0x00000000, 0x00000000, 0x00616362, 0x00b8bab9, 0x00c9cbca, 0x00c8c9c8, 0x00c4c6c5, 0x00c3c4c4, 0x00c1c3c2, 0x00c0c1c0, 0x00acaead, 0x007e807f, 0x003f4040, 0x000e100f, 0x00000000, 0x00000000, 0x00010302, 0x00000000, 0x001a1c1b, 0x00484948, 0x00848685, 0x00b7b8b8, 0x00c1c3c2, 0x00bcbdbc, 0x00c3c4c4, 0x00c2c4c3, 0x00c2c4c3, 0x00c2c4c3, 0x00c2c4c3, 0x00c2c4c3, 0x00c2c4c3, 0x00c2c4c3, 0x00c2c4c3, 0x00c2c1c0, 0x00c4c4c4, 0x00c0c3c5, 0x00bec1c4, 0x00c1c3c2, 0x00c2c2c0, 0x00c2c4c3, 0x00c4c6c5, 0x00c7cacb, 0x00a1a4a4, 0x00454544, 0x00150000, 0x00501600, 0x00ac5920, 0x00bd5918, 0x00c3570f, 0x00c1530a, 0x00be550f, 0x00b45616, 0x00874214, 0x002c1000, 0x000e0000, 0x002c0700, 0x00783b14, 0x00b65c1f, 0x00bd5710, 0x00ba5613, 0x009f4c18, 0x0056220a, 0x00300000, 0x00873e12, 0x00b3561a, 0x00c1560f, 0x00c3540b, 0x00bd5512, 0x00a95624, 0x004e1f05, 0x00200000, 0x00320b00, 0x00783e15, 0x00b45a18, 0x00c35304, 0x00cc5402, 0x00cc5302, 0x00c15008, 0x00bf5614, 0x00b45318, 0x008d481c, 0x001c0000, 0x000c0000, 0x00190000, 0x00703b1f, 0x00a9541c, 0x00bd540e, 0x00c8540c, 0x00c85007, 0x00c45304, 0x00bb5915, 0x008d4418, 0x00401400, 0x000b0000, 0x000d0000, 0x00300800, 0x00a05a2f, 0x00ba5518, 0x00bb5314, 0x00a75728, 0x004c1500, 0x00180000, 0x00200300, 0x00783810, 0x00ab5924, 0x00ad5b26, 0x0075340f, 0x00381e15, 0x007a7377, 0x00ccc8c9, 0x00ccc8c8, 0x00cacbcc, 0x00bfc4c4, 0x00c2c4c3, 0x00c3c3c3, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c4c4c4, 0x00c3c3c3, 0x00c3c3c3, 0x00c4c4c4, 0x00bcbcbc, 0x00767676, 0x00090909, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00060606, 0x00000000, 0x00474747, 0x009d9d9d, 0x00c4c4c4, 0x00c5c5c5, 0x00c2c2c2, 0x00c4c4c4, 0x00c5c5c5, 0x00cacaca, 0x00cccccc, 0x00c4c0be, 0x0040302b, 0x003d1705, 0x00934722, 0x00b04c1b, 0x00b64c14, 0x00bd5315, 0x00bc5817, 0x00b55917, 0x00ab5618, 0x008e440e, 0x00642400, 0x00490e00, 0x00501400, 0x00723408, 0x0098561c, 0x00ae6620, 0x00b46414, 0x00be640e, 0x00c8630a, 0x00cc6306, 0x00cc6201, 0x00cc6300, 0x00ca6400, 0x00c96500, 0x00cb6402, 0x00ca6503, 0x00cb6605, 0x00ca6606, 0x00c86605, 0x00c86407, 0x00c96008, 0x00c85d0b, 0x00c25a0d, 0x00c35a11, 0x00bc540b, 0x00bc5c1b, 0x00a45a24, 0x0074431c, 0x002e1400, 0x00190400, 0x00341408, 0x00622f18, 0x009e5227, 0x00b25b25, 0x00ad5820, 0x00a05625, 0x005c2508, 0x00270000, 0x00481400, 0x008b491c, 0x00b45a1d, 0x00be5810, 0x00be550c, 0x00b85108, 0x00b95813, 0x00b95c1a, 0x00b15819, 0x00a0521c, 0x00733812, 0x00401400, 0x00250200, 0x003b1400, 0x00743a11, 0x00a35720, 0x00b65c18, 0x00ba5a0e, 0x00b55509, 0x00883400, 0x004c1200, 0x003e1000, 0x00441500, 0x00501d00, 0x007c3e1b, 0x009f5b2f, 0x00aa602c, 0x00804519, 0x00261000, 0x000a0200, 0x000b0000, 0x00462304, 0x00a86324, 0x00bb5d10, 0x00c3590b, 0x00c95809, 0x00ca5503, 0x00c05812, 0x00944819, 0x004a1b01, 0x000e0000, 0x00050100, 0x00473e41, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00aeaeae, 0x000a0a0a, 0x00010302, 0x00444544, 0x00b6b8b7, 0x00c6c8c7, 0x00c9cbca, 0x00c4c6c5, 0x00bec0bf, 0x00c0c2c1, 0x00c0c1c0, 0x00c0c2c1, 0x00b5b7b6, 0x009b9c9c, 0x007c7e7d, 0x00676868, 0x005c5d5c, 0x00565857, 0x00686968, 0x007f8080, 0x009fa0a0, 0x00bbbcbc, 0x00c6c8c7, 0x00c0c2c1, 0x00bdbfbe, 0x00c5c7c6, 0x00c0c2c1, 0x00c0c2c1, 0x00c0c2c1, 0x00c0c2c1, 0x00c0c2c1, 0x00c0c2c1, 0x00c0c2c1, 0x00c0c2c1, 0x00c0c0be, 0x00c4c4c4, 0x00bfc2c4, 0x00bcbfc1, 0x00c1c1c1, 0x00c2c2c0, 0x00c0c2c0, 0x00c5c7c4, 0x00c8cccb, 0x00969897, 0x0030302e, 0x00160000, 0x00511600, 0x00af5921, 0x00bc5716, 0x00c2540c, 0x00c15209, 0x00bd540e, 0x00b45719, 0x007e3d11, 0x00280d00, 0x000c0000, 0x00270300, 0x00703410, 0x00b45a1d, 0x00bb540b, 0x00ba540e, 0x00a75018, 0x00672b11, 0x00390000, 0x00944615, 0x00b45514, 0x00c0550c, 0x00c1530c, 0x00bc5617, 0x009d4e20, 0x003e1403, 0x00180000, 0x00370c00, 0x00804014, 0x00b65917, 0x00c35304, 0x00cc5401, 0x00cc5304, 0x00c15008, 0x00bf5513, 0x00bb5618, 0x009e5322, 0x00260400, 0x000c0000, 0x00160000, 0x00633219, 0x00a14f1a, 0x00bc540f, 0x00c8530e, 0x00c85007, 0x00c35305, 0x00b95814, 0x008f461a, 0x00451800, 0x000c0000, 0x000b0000, 0x00290400, 0x009a552c, 0x00b95317, 0x00c05413, 0x00b15a26, 0x00682b06, 0x00250400, 0x00190000, 0x00672e0b, 0x009d5525, 0x00ac5c2a, 0x007d3c16, 0x00361811, 0x00665c61, 0x00ccc9ca, 0x00ccc8c8, 0x00c8cbcc, 0x00bfc4c4, 0x00c0c2c1, 0x00c1c1c1, 0x00c2c2c2, 0x00c2c2c2, 0x00c2c2c2, 0x00c2c2c2, 0x00c1c1c1, 0x00c1c1c1, 0x00c0c0c0, 0x00b8b8b8, 0x006d6d6d, 0x00020202, 0x00000000, 0x00000000, 0x00030303, 0x00020202, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00030303, 0x00000000, 0x003d3d3d, 0x00979797, 0x00c2c2c2, 0x00c4c4c4, 0x00bebebe, 0x00c6c6c6, 0x00c4c4c4, 0x00cbcbcb, 0x00cccccc, 0x00c2beb9, 0x00251809, 0x00482103, 0x009c4d19, 0x00b95719, 0x00ba551a, 0x00b95c24, 0x00a45828, 0x008d4c22, 0x00682b03, 0x00521700, 0x004c0d00, 0x00642200, 0x008e4312, 0x00ac5a1c, 0x00ba6214, 0x00c0620d, 0x00c3620e, 0x00c6600e, 0x00ca600f, 0x00cc5e0d, 0x00cc5e07, 0x00cc6004, 0x00ca6106, 0x00c96408, 0x00c86506, 0x00c66803, 0x00c76900, 0x00c66b00, 0x00c86906, 0x00c86807, 0x00ca6705, 0x00cc6506, 0x00c45c01, 0x00ca5e08, 0x00c55400, 0x00c0580d, 0x00b36027, 0x00804521, 0x002d0c00, 0x00110000, 0x00110000, 0x00321000, 0x005e2a08, 0x00894c24, 0x00925730, 0x006c381a, 0x002f0600, 0x00260000, 0x007e401c, 0x00a65822, 0x00b45818, 0x00b75510, 0x00ba5917, 0x00b45a1a, 0x00ac5a23, 0x009c5220, 0x00854417, 0x005c2300, 0x00340800, 0x00270100, 0x003c1400, 0x00743e1a, 0x00aa5b24, 0x00b75c17, 0x00b4580e, 0x00b95c10, 0x00b4560e, 0x008c3b01, 0x003d0800, 0x001c0000, 0x00170000, 0x001a0000, 0x00391401, 0x006b3818, 0x00a35c2c, 0x00975527, 0x00543018, 0x00100000, 0x00080000, 0x001f0700, 0x00955923, 0x00b66018, 0x00bd560c, 0x00c95809, 0x00cc5704, 0x00c35810, 0x00a3511c, 0x00582403, 0x00120000, 0x00030000, 0x00393234, 0x004d4b4c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00262626, 0x00020403, 0x00232424, 0x00acaead, 0x00c5c7c6, 0x00c8c9c8, 0x00c2c4c3, 0x00bcbebd, 0x00c0c1c0, 0x00c0c1c0, 0x00babcbb, 0x00bbbcbc, 0x00c0c2c1, 0x00bcbebd, 0x00b0b2b1, 0x00aaacab, 0x00acaead, 0x00b7b8b8, 0x00bec0bf, 0x00c0c2c1, 0x00bcbdbc, 0x00b8bab9, 0x00bdbfbe, 0x00c0c2c1, 0x00bdbfbe, 0x00bfc0c0, 0x00bfc0c0, 0x00bfc0c0, 0x00bfc0c0, 0x00bfc0c0, 0x00bfc0c0, 0x00bfc0c0, 0x00bfc0c0, 0x00bdbdbc, 0x00c2c2c2, 0x00bec1c4, 0x00bcc0c2, 0x00c1c1c1, 0x00c0bfbd, 0x00bfbfbd, 0x00c5c7c4, 0x00c8cac9, 0x00838482, 0x001b1a17, 0x00170100, 0x00571a00, 0x00b15a23, 0x00bc5414, 0x00c05009, 0x00c3520a, 0x00be550f, 0x00b1581c, 0x0074360c, 0x00230c00, 0x000b0000, 0x00280400, 0x00703310, 0x00b3591e, 0x00ba530a, 0x00bc530b, 0x00b05318, 0x00783418, 0x00420200, 0x009f4b17, 0x00b65410, 0x00bd5308, 0x00bd530a, 0x00b95719, 0x0094481f, 0x00340f02, 0x00150000, 0x00370c00, 0x007e3d11, 0x00b65917, 0x00c05204, 0x00c85003, 0x00c95105, 0x00c35008, 0x00c05310, 0x00bd5614, 0x00a85824, 0x00350e00, 0x00120000, 0x00150000, 0x00582b15, 0x009c4d19, 0x00bc5410, 0x00c8530e, 0x00c85109, 0x00c35307, 0x00b85714, 0x0090471c, 0x00481a03, 0x000d0000, 0x000a0000, 0x00260200, 0x00935129, 0x00b85216, 0x00c25310, 0x00b4561c, 0x00884016, 0x00381000, 0x001c0000, 0x00542004, 0x008d4c24, 0x00a85a29, 0x007f3d17, 0x00301208, 0x00504649, 0x00cac3c4, 0x00cac8c9, 0x00c6c9c8, 0x00c0c5c5, 0x00c0c1c0, 0x00c0c0c0, 0x00c0c0c0, 0x00c0c0c0, 0x00c0c0c0, 0x00c0c0c0, 0x00c0c0c0, 0x00c0c0c0, 0x00c0c0c0, 0x00bdbdbd, 0x00787878, 0x00020202, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00474747, 0x00a1a1a1, 0x00c0c0c0, 0x00c1c1c1, 0x00bfbfbf, 0x00c1c1c1, 0x00c6c6c6, 0x00cacaca, 0x00c3c3c3, 0x00b3ada7, 0x00170500, 0x005e3511, 0x00a0551d, 0x00b45a1d, 0x00ab5420, 0x00984f24, 0x00693314, 0x00451800, 0x003c1000, 0x00521f02, 0x00783a17, 0x009f5427, 0x00b86024, 0x00c05f14, 0x00c45f07, 0x00c75f04, 0x00c46008, 0x00c65f0c, 0x00ca5d0d, 0x00cb5c0c, 0x00cb5d08, 0x00ca5e08, 0x00c86109, 0x00c7640a, 0x00c46507, 0x00c46804, 0x00c46900, 0x00c46a00, 0x00c46a02, 0x00c56904, 0x00c86804, 0x00ca6704, 0x00ca6503, 0x00cc6404, 0x00cc5e01, 0x00c05606, 0x00aa5621, 0x0064270a, 0x00240200, 0x00120000, 0x00280d00, 0x0046250d, 0x003a1000, 0x004d2000, 0x0060351c, 0x00361000, 0x001c0000, 0x004a1c0c, 0x009a552c, 0x00ae5c24, 0x00ac561a, 0x00aa5418, 0x00a95820, 0x00a05524, 0x00844419, 0x00612804, 0x00471300, 0x002c0000, 0x00310400, 0x0058280c, 0x00814723, 0x00a05828, 0x00b85b1b, 0x00b8540b, 0x00b85a0e, 0x00b65c10, 0x00bc5c16, 0x00a9561d, 0x00632c0c, 0x00260400, 0x000a0000, 0x00090000, 0x00110000, 0x002f0c00, 0x00783c14, 0x009a592f, 0x007c4e30, 0x00280c00, 0x00100300, 0x00140000, 0x007a4515, 0x00b16020, 0x00bc5810, 0x00c8580a, 0x00ca5506, 0x00c2560c, 0x00ae581d, 0x00642a02, 0x00170100, 0x00030000, 0x002d2a2b, 0x00949094, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000c0c0c, 0x004a4a4a, 0x00000100, 0x00080a09, 0x00939494, 0x00c4c6c5, 0x00c8cac9, 0x00c1c3c2, 0x00bfc0c0, 0x00bdbfbe, 0x00bfc0c0, 0x00bfc0c0, 0x00bec0bf, 0x00bcbebd, 0x00b9bbba, 0x00b8b9b8, 0x00babcbb, 0x00bec0bf, 0x00bbbcbc, 0x00bbbcbc, 0x00bfc0c0, 0x00c0c1c0, 0x00bcbdbc, 0x00bcbdbc, 0x00bcbebd, 0x00babcbb, 0x00bdbfbe, 0x00bdbfbe, 0x00bdbfbe, 0x00bdbfbe, 0x00bdbfbe, 0x00bdbfbe, 0x00bdbfbe, 0x00bdbfbe, 0x00bcbcbb, 0x00bdbfbe, 0x00bcbfc1, 0x00bcc0c2, 0x00bfbfbf, 0x00bcbbb9, 0x00bebfbb, 0x00c8c9c5, 0x00bec0bd, 0x00696968, 0x000c0907, 0x00180100, 0x005e2000, 0x00b45c24, 0x00be5414, 0x00c4510c, 0x00c45208, 0x00be5410, 0x00b05a20, 0x00682f07, 0x00200b00, 0x000a0000, 0x002a0500, 0x00713410, 0x00b45a1f, 0x00bd540c, 0x00c0540a, 0x00b75519, 0x00873c1d, 0x004e0600, 0x00a84e19, 0x00b9540f, 0x00be5409, 0x00bc530b, 0x00b7571a, 0x008a4019, 0x00310b00, 0x00140000, 0x00330a00, 0x00783912, 0x00b35a1b, 0x00bf530b, 0x00c35007, 0x00c75107, 0x00c75008, 0x00c3520c, 0x00be550f, 0x00ab5821, 0x00451a00, 0x00170000, 0x00140000, 0x004f2410, 0x00994b1a, 0x00bb5411, 0x00c6530e, 0x00c7500a, 0x00c3540b, 0x00b65717, 0x0090481d, 0x00491c04, 0x000d0000, 0x000a0000, 0x00250000, 0x008d4d24, 0x00b65114, 0x00c4540f, 0x00b85414, 0x00a25220, 0x00501d01, 0x00250000, 0x003d1000, 0x007c411f, 0x00a55a29, 0x007c3a12, 0x00280a00, 0x003a3030, 0x00b4afaf, 0x00cccacb, 0x00c7c8c8, 0x00c0c4c3, 0x00c0c0c0, 0x00c0c0c0, 0x00c0c0c0, 0x00bfbfbf, 0x00bfbfbf, 0x00bfbfbf, 0x00bfbfbf, 0x00bfbfbf, 0x00c1c1c1, 0x00bebebe, 0x008c8c8c, 0x001e1e1e, 0x00000000, 0x00040404, 0x00000000, 0x00010101, 0x00010101, 0x00000000, 0x00010101, 0x00080808, 0x00000000, 0x00090909, 0x00616161, 0x00b1b1b1, 0x00bfbfbf, 0x00c0c0c0, 0x00bebebe, 0x00bfbfbf, 0x00c7c7c7, 0x00c8c8c8, 0x00c4c4c4, 0x00847c74, 0x001c0300, 0x007a4d28, 0x009e5d2b, 0x00924c19, 0x006d320c, 0x004e1f05, 0x00280700, 0x001b0000, 0x00300a00, 0x006b3819, 0x00a15f35, 0x00b36029, 0x00b85712, 0x00c45b0a, 0x00c96008, 0x00c45f04, 0x00bd6009, 0x00be610a, 0x00c56005, 0x00c85f04, 0x00c86006, 0x00c46106, 0x00c16405, 0x00c16604, 0x00c46505, 0x00c56504, 0x00c46604, 0x00c26801, 0x00c06a00, 0x00c26900, 0x00c46805, 0x00c76705, 0x00ca6b06, 0x00c96601, 0x00cc6300, 0x00c46314, 0x00974c20, 0x00451100, 0x001c0000, 0x00190000, 0x00593115, 0x007d5025, 0x00603004, 0x00370d00, 0x002a0a00, 0x001c0000, 0x002c0400, 0x007c4730, 0x00a25b2e, 0x00aa5c28, 0x00a15825, 0x00914d21, 0x00773c16, 0x00592706, 0x00401400, 0x002e0300, 0x00300000, 0x004b1500, 0x0073350c, 0x0098501e, 0x00ab5920, 0x00b35717, 0x00ba5510, 0x00bc580f, 0x00b85c14, 0x00b45912, 0x00bb5811, 0x00b45b20, 0x008b4b24, 0x003f1703, 0x000d0000, 0x00030000, 0x00060000, 0x00140000, 0x00401500, 0x00844e2c, 0x00935c38, 0x00582d0f, 0x00130000, 0x00150000, 0x005c2b02, 0x00a95f27, 0x00bd5c18, 0x00c7580d, 0x00c85408, 0x00c1550c, 0x00b55c1c, 0x006b2e00, 0x001c0500, 0x00020000, 0x00242223, 0x00838182, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00808080, 0x00040504, 0x00010302, 0x00696b6a, 0x00babcbb, 0x00cacccb, 0x00c4c5c4, 0x00c0c2c1, 0x00babcbb, 0x00b9bbba, 0x00bbbcbc, 0x00bcbdbc, 0x00bdbfbe, 0x00c0c1c0, 0x00c0c1c0, 0x00bdbfbe, 0x00bbbcbc, 0x00bcbebd, 0x00bbbcbc, 0x00bcbebd, 0x00bec0bf, 0x00bcbdbc, 0x00bbbcbc, 0x00bcbebd, 0x00bcbebd, 0x00bcbebd, 0x00bcbebd, 0x00bcbebd, 0x00bcbebd, 0x00bcbebd, 0x00bcbebd, 0x00bcbebd, 0x00bcbebd, 0x00bfbfbd, 0x00bbbcbc, 0x00babdc0, 0x00bcbfc1, 0x00bcbcbc, 0x00bdbcbb, 0x00c3c4c0, 0x00cacbc7, 0x00a7a7a5, 0x004a4948, 0x00060200, 0x001e0500, 0x00692803, 0x00b45a22, 0x00be5211, 0x00c6510c, 0x00c45007, 0x00bd5410, 0x00b05b24, 0x00602803, 0x001c0900, 0x000a0000, 0x002c0800, 0x00743412, 0x00b2581d, 0x00be550d, 0x00c05308, 0x00ba5417, 0x00934220, 0x005c0f00, 0x00ab5018, 0x00bb540d, 0x00c05509, 0x00bc550c, 0x00b4551a, 0x00813813, 0x00300900, 0x00130000, 0x002b0600, 0x00703714, 0x00b05a20, 0x00bc5410, 0x00c0510d, 0x00c5510a, 0x00ca5207, 0x00c85208, 0x00bf540c, 0x00ac581e, 0x00582808, 0x001b0000, 0x00130000, 0x00461c0b, 0x0098491a, 0x00bb5413, 0x00c4500e, 0x00c6500b, 0x00c2540c, 0x00b65618, 0x0091481e, 0x004b1c04, 0x000d0000, 0x000a0000, 0x00240000, 0x0088481f, 0x00b25112, 0x00c5550f, 0x00be5410, 0x00b35a23, 0x006a300f, 0x00310400, 0x002c0100, 0x006b361a, 0x00a55d2d, 0x007c3b10, 0x00230700, 0x00261e1c, 0x008b8887, 0x00c9c9c9, 0x00cbcbcb, 0x00c4c4c4, 0x00bfbfbf, 0x00bebebe, 0x00bebebe, 0x00bdbdbd, 0x00bdbdbd, 0x00bdbdbd, 0x00bdbdbd, 0x00bdbdbd, 0x00bdbdbd, 0x00bcbcbc, 0x00a5a5a5, 0x00585858, 0x00030303, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x002d2d2d, 0x008a8a8a, 0x00bcbcbc, 0x00bdbdbd, 0x00c0c0c0, 0x00bbbbbb, 0x00c3c3c3, 0x00c8c8c8, 0x00c8c8c8, 0x00c6c6c6, 0x00484039, 0x00220600, 0x00683c20, 0x006b340f, 0x00521c00, 0x002e0400, 0x00180000, 0x000d0000, 0x00120200, 0x001b0200, 0x00461f05, 0x007e461f, 0x00a85d26, 0x00c06119, 0x00c45d0c, 0x00c45b04, 0x00c15b03, 0x00be6006, 0x00be6005, 0x00c36003, 0x00c46002, 0x00c46007, 0x00c46007, 0x00c16204, 0x00c16202, 0x00c46404, 0x00c46404, 0x00c46305, 0x00c46404, 0x00c26801, 0x00c46802, 0x00c66805, 0x00c76705, 0x00c46700, 0x00c56702, 0x00c56505, 0x00bf6b21, 0x006f350f, 0x002c0400, 0x00150000, 0x002c0900, 0x00743c13, 0x00a4622c, 0x0094541b, 0x006c3407, 0x00341000, 0x001a0000, 0x003d1705, 0x007a4b33, 0x007f4623, 0x00763b14, 0x00652e0c, 0x00512000, 0x00380b00, 0x00270000, 0x002f0300, 0x00431300, 0x00642e0a, 0x0087461a, 0x00a45720, 0x00b0581a, 0x00b85813, 0x00bc550c, 0x00bc5409, 0x00bf590f, 0x00b75812, 0x00b65811, 0x00be550c, 0x00b75511, 0x00a65928, 0x00663314, 0x00220d03, 0x00040000, 0x00030000, 0x000c0200, 0x001c0400, 0x00542c12, 0x009a6037, 0x00824a23, 0x00280800, 0x00180000, 0x00421300, 0x009d5926, 0x00bd5e1c, 0x00c75810, 0x00c7540b, 0x00c2560e, 0x00ba5f18, 0x00743400, 0x00220a00, 0x00030000, 0x001c1c1c, 0x00727272, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x001f1f1f, 0x00888888, 0x00080a09, 0x00030404, 0x00323433, 0x009d9f9e, 0x00c8c9c8, 0x00c6c8c7, 0x00c0c2c1, 0x00b9bbba, 0x00babcbb, 0x00b9bbba, 0x00b9bbba, 0x00babcbb, 0x00b9bbba, 0x00b7b8b8, 0x00b8b9b8, 0x00bcbdbc, 0x00babcbb, 0x00bbbcbc, 0x00b9bbba, 0x00b8b9b8, 0x00b9bbba, 0x00bcbebd, 0x00bcbebd, 0x00b9bbba, 0x00bbbcbc, 0x00bbbcbc, 0x00bbbcbc, 0x00bbbcbc, 0x00bbbcbc, 0x00bbbcbc, 0x00bbbcbc, 0x00bbbcbc, 0x00bebebc, 0x00b9bbba, 0x00babdc0, 0x00babdc0, 0x00babab8, 0x00c1c0bd, 0x00c7c6c3, 0x00c2c3bf, 0x007f7f7d, 0x00242422, 0x00050000, 0x00250b00, 0x0076340e, 0x00b45820, 0x00bc4f0f, 0x00c7500a, 0x00c65006, 0x00bf5410, 0x00ae5a25, 0x00552000, 0x00180500, 0x000b0000, 0x00330c00, 0x007d3c18, 0x00b0571c, 0x00bf560d, 0x00c05004, 0x00bc5414, 0x009c4824, 0x006b1a00, 0x00ac5015, 0x00ba540b, 0x00be5609, 0x00bd570e, 0x00b3561c, 0x007e3510, 0x00310a00, 0x00130000, 0x00200000, 0x00653215, 0x00aa5824, 0x00ba5614, 0x00bd5412, 0x00c4500c, 0x00cc5004, 0x00cb5004, 0x00bf5309, 0x00ad581d, 0x00693714, 0x00200200, 0x00140000, 0x00411907, 0x00984b1b, 0x00b95413, 0x00c4500e, 0x00c5500c, 0x00c0530c, 0x00b45719, 0x00924820, 0x004b1c04, 0x000c0000, 0x000b0000, 0x00230000, 0x00804218, 0x00b35414, 0x00c25409, 0x00c4550f, 0x00b5571d, 0x00884522, 0x00420f00, 0x00230000, 0x005c2b12, 0x00a0582a, 0x007d3e11, 0x00240a00, 0x00110d08, 0x00525150, 0x00bababa, 0x00ccc8c9, 0x00cbc8c7, 0x00bebcbd, 0x00bdbdbd, 0x00bcbcbc, 0x00bcbcbc, 0x00bcbcbc, 0x00bcbcbc, 0x00bcbcbc, 0x00bcbcbc, 0x00bcbcbc, 0x00bebebe, 0x00b7b7b7, 0x00929292, 0x00393939, 0x000c0c0c, 0x00010101, 0x00000000, 0x00000000, 0x00010101, 0x00020202, 0x00000000, 0x00202020, 0x006c6c6c, 0x00ababab, 0x00bbbbbb, 0x00bbbbbb, 0x00bdbdbd, 0x00bcbcbc, 0x00c4c4c4, 0x00cacaca, 0x00c4c4c4, 0x00a3a3a3, 0x001c1414, 0x00220b08, 0x003c190f, 0x00390e00, 0x003b1000, 0x00280800, 0x00160100, 0x00080000, 0x00040000, 0x000a0400, 0x00110400, 0x00381800, 0x00754318, 0x00aa5c1d, 0x00bc5e11, 0x00c15b0a, 0x00c96009, 0x00c85c00, 0x00c55e00, 0x00c06004, 0x00c06007, 0x00c35f08, 0x00c45e08, 0x00c75d07, 0x00c75d04, 0x00c46004, 0x00c36204, 0x00c36204, 0x00c56205, 0x00c86206, 0x00ca6305, 0x00c96404, 0x00c86502, 0x00c86700, 0x00c46908, 0x00bd6c19, 0x009d6021, 0x00401c00, 0x00180100, 0x00110000, 0x004b220b, 0x00914718, 0x00bb5e20, 0x00b95816, 0x00af5a1d, 0x0074380c, 0x00391000, 0x00311400, 0x00391f10, 0x00311505, 0x00260800, 0x001d0000, 0x001e0000, 0x002c0400, 0x00421200, 0x00642b04, 0x00884418, 0x00a25621, 0x00ac581e, 0x00b05718, 0x00b45512, 0x00bc5812, 0x00c0580d, 0x00bf5406, 0x00bd5307, 0x00ba5511, 0x00bc560f, 0x00c65706, 0x00be5304, 0x00b45b19, 0x008c4c1c, 0x003e1b05, 0x000b0000, 0x00050000, 0x00030000, 0x00090400, 0x00281100, 0x00884d21, 0x00985728, 0x005a2e16, 0x00210000, 0x00310300, 0x00904f22, 0x00b85c1c, 0x00c45810, 0x00c75610, 0x00c1560f, 0x00bb5f16, 0x007b3b02, 0x00280e00, 0x00040000, 0x00141615, 0x00646463, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a4a6, 0x007c7c7c, 0x00444442, 0x000c0503, 0x00070100, 0x00080401, 0x00827f7e, 0x00c1c1c0, 0x00c8c8c6, 0x00c1c1c0, 0x00bebebc, 0x00b9b9bb, 0x00bcbcbd, 0x00bbbcbd, 0x00b8bab9, 0x00b7bbb8, 0x00b9bdba, 0x00b9bebc, 0x00b8bbba, 0x00babcb9, 0x00babcbb, 0x00b9babc, 0x00babbbc, 0x00bcbcbc, 0x00b8b8b8, 0x00b8b8ba, 0x00bcbdbc, 0x00b9bbba, 0x00b9bbb8, 0x00babbb7, 0x00b9bbb7, 0x00b8bbba, 0x00b8bbba, 0x00b9bbba, 0x00babab8, 0x00bcbbb8, 0x00b8b8b6, 0x00b9bcbf, 0x00b8bcbe, 0x00b8b8b6, 0x00c2c1be, 0x00c5c4c1, 0x00b5b4b1, 0x005a5a58, 0x00080402, 0x00050000, 0x002c0f00, 0x00823d14, 0x00b85920, 0x00bf4e0c, 0x00c8500b, 0x00c85109, 0x00be5413, 0x00ac5826, 0x004e1800, 0x00160000, 0x000f0000, 0x003d1200, 0x00884520, 0x00b45719, 0x00c4560d, 0x00c35004, 0x00be5413, 0x00a44e27, 0x00782400, 0x00b25014, 0x00bd540c, 0x00bc5206, 0x00bd5710, 0x00b4561f, 0x007d3410, 0x00340c00, 0x00100000, 0x00160000, 0x005c3015, 0x00a45622, 0x00ba5616, 0x00bf5214, 0x00c34f0c, 0x00c85005, 0x00c85103, 0x00c05207, 0x00b0581b, 0x00784018, 0x00280400, 0x00150000, 0x003e1806, 0x00984c1b, 0x00ba5414, 0x00c2520e, 0x00c7540f, 0x00bf520c, 0x00b45719, 0x00934920, 0x004b1b06, 0x000c0000, 0x000a0000, 0x00220000, 0x007a3d15, 0x00b45718, 0x00bf5106, 0x00c1530a, 0x00b25011, 0x00a2542a, 0x00531700, 0x00240000, 0x00512310, 0x00925026, 0x00783e15, 0x00250f00, 0x00030000, 0x00252423, 0x00a7a7a7, 0x00c6c3c4, 0x00cccacb, 0x00bcbcbe, 0x00bbbcbd, 0x00bcbcbc, 0x00bbbbb9, 0x00bcbbb9, 0x00bcbabb, 0x00bbbbbc, 0x00babbbc, 0x00babbbc, 0x00b9bcbd, 0x00b8b9b8, 0x00b4b6b4, 0x008f8f8d, 0x003b3c3c, 0x001f2024, 0x000c0d10, 0x00080808, 0x00060606, 0x00161616, 0x00303032, 0x0068686a, 0x00a8a9ab, 0x00bcbcbc, 0x00bcbcbc, 0x00bcbcbc, 0x00bbbcbc, 0x00c0c0c2, 0x00c0c0c2, 0x00cccacb, 0x00bcb9b8, 0x00726c6a, 0x000e0000, 0x00280400, 0x00461708, 0x00643018, 0x007c492d, 0x00572c14, 0x002a0900, 0x00120000, 0x00060000, 0x00000000, 0x00020200, 0x00130700, 0x00351700, 0x00713807, 0x00a85a1b, 0x00bd6319, 0x00bc5907, 0x00c65d02, 0x00c45d00, 0x00bf5f05, 0x00bd5f08, 0x00c25d0b, 0x00c65d0a, 0x00ca5c09, 0x00ca5c08, 0x00c55f07, 0x00c46005, 0x00c46005, 0x00c56006, 0x00cb5f08, 0x00cb6005, 0x00ca6202, 0x00c96300, 0x00c86400, 0x00bc6407, 0x00b36c24, 0x00764614, 0x00240e00, 0x000e0100, 0x00110000, 0x00582c0e, 0x00ab5821, 0x00bc540d, 0x00c4550b, 0x00bf5811, 0x00a55518, 0x00763c0d, 0x00300800, 0x00170000, 0x000c0000, 0x00130000, 0x00210400, 0x00370f00, 0x005d2a0c, 0x0085451c, 0x009d511c, 0x00b05b20, 0x00b05515, 0x00b45411, 0x00b85713, 0x00bc5711, 0x00ba540c, 0x00bb5209, 0x00c15405, 0x00c25409, 0x00bc540f, 0x00ba540e, 0x00c25708, 0x00bd5605, 0x00b65810, 0x00a65c24, 0x005a2c0e, 0x00200700, 0x000c0000, 0x00000000, 0x00000000, 0x00201101, 0x00683105, 0x00a45f2e, 0x00865032, 0x00310200, 0x00290000, 0x00854720, 0x00b15718, 0x00c2580f, 0x00c55710, 0x00c0550e, 0x00bc5c14, 0x00823f07, 0x002d1200, 0x00060200, 0x00121110, 0x005d5d5d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00adacb0, 0x007b7f81, 0x00424648, 0x0008080a, 0x00060000, 0x00110000, 0x00190400, 0x00180804, 0x00453a38, 0x00a4a09c, 0x00cccbc7, 0x00cac9c5, 0x00c0c0bc, 0x00bab6bb, 0x00bbb8be, 0x00b8b8bc, 0x00b5b7b6, 0x00b4bab4, 0x00b3bcb4, 0x00b2bcb7, 0x00b5beb9, 0x00b8b9b5, 0x00b8b8b7, 0x00b7b9bd, 0x00b8b9bd, 0x00bbb7ba, 0x00bcb7b8, 0x00b8b7bb, 0x00b7b8b9, 0x00b6b9b8, 0x00b8b9b5, 0x00b9b9b0, 0x00b8bab1, 0x00b5bab7, 0x00b4b9b8, 0x00b8b8b6, 0x00b9b7b3, 0x00bab6b1, 0x00bcb9b5, 0x00b9babc, 0x00b8bbbc, 0x00bbbcbc, 0x00bfbebb, 0x00cac8c4, 0x00868480, 0x00262624, 0x00030000, 0x00080000, 0x00331100, 0x0092491d, 0x00b75215, 0x00c3500a, 0x00c85008, 0x00c5500c, 0x00bb5317, 0x00a85529, 0x004c1100, 0x00180000, 0x00130000, 0x0055220c, 0x0094491e, 0x00bc5414, 0x00c44f03, 0x00c45005, 0x00bc5311, 0x00aa5223, 0x008b3406, 0x00b65011, 0x00c1530c, 0x00c05107, 0x00bf5511, 0x00b65624, 0x00823b19, 0x002d0900, 0x000c0000, 0x000f0000, 0x004c270f, 0x009c4e18, 0x00bb5411, 0x00c45214, 0x00c34d0d, 0x00c4520d, 0x00c2540b, 0x00c05308, 0x00b45717, 0x00904e26, 0x00280000, 0x00150000, 0x003a1605, 0x00944916, 0x00bc5814, 0x00be510c, 0x00c1510c, 0x00bf520c, 0x00b65619, 0x00904721, 0x004c1c0b, 0x000b0000, 0x00070000, 0x00200000, 0x00743912, 0x00b35518, 0x00c05108, 0x00bd5109, 0x00bc5815, 0x00ad5620, 0x00662100, 0x002c0000, 0x004b1d0e, 0x008b4c2c, 0x00743d20, 0x00220d03, 0x00090604, 0x000d0c09, 0x00595a56, 0x00c1c1c1, 0x00c8c8ca, 0x00c0c2c6, 0x00bcc0c2, 0x00b8b9b7, 0x00b9b8b5, 0x00bbb8b4, 0x00b7b4b3, 0x00bfbec2, 0x00b8bac0, 0x00b6bcc0, 0x00b4bcbd, 0x00b3bab6, 0x00b8bcb6, 0x00b8bab6, 0x00a2a5a6, 0x00747682, 0x004c4d58, 0x00414042, 0x00484745, 0x00656668, 0x00929598, 0x00b0b4b7, 0x00b8bbbd, 0x00b8bab9, 0x00babab8, 0x00b8b9b8, 0x00bcbfc0, 0x00b8bcc0, 0x00c7c9cc, 0x00c8c4c8, 0x00a39898, 0x0033201c, 0x00351004, 0x00733418, 0x00a05228, 0x00af5d28, 0x00ab5c25, 0x00a25828, 0x0071340f, 0x00340900, 0x00190000, 0x00060000, 0x00000100, 0x00020200, 0x000b0000, 0x00300d00, 0x006e380c, 0x009f591a, 0x00b36014, 0x00bc600c, 0x00c16109, 0x00bc5e08, 0x00bd5c08, 0x00c45f0b, 0x00c85f0c, 0x00c55b08, 0x00c55b07, 0x00c55c08, 0x00c45e08, 0x00c45e07, 0x00c45e07, 0x00c85e07, 0x00c85f04, 0x00c96002, 0x00ca6202, 0x00ca6200, 0x00c16510, 0x00ab692c, 0x004c2200, 0x00150300, 0x000a0000, 0x00180200, 0x00673b1c, 0x00b56625, 0x00c05b0b, 0x00c85b0c, 0x00bf5406, 0x00bc590e, 0x00ad5918, 0x007c3c0d, 0x00300300, 0x00120000, 0x00240d00, 0x0058280c, 0x008b4820, 0x00a55622, 0x00b3591c, 0x00b2530b, 0x00bb580e, 0x00b6550e, 0x00b5520c, 0x00bd550f, 0x00c25814, 0x00bc5411, 0x00b8520b, 0x00bf5408, 0x00c05408, 0x00bc5610, 0x00b65611, 0x00b35810, 0x00b25a13, 0x00b35b15, 0x00ab5d24, 0x007c4524, 0x00371300, 0x000c0000, 0x00030000, 0x00020100, 0x000f0000, 0x004c1a00, 0x00a05e31, 0x0098582f, 0x00642905, 0x00280000, 0x00743813, 0x00ad5518, 0x00c0580f, 0x00c55911, 0x00c1560f, 0x00ba5814, 0x00883f0b, 0x00341400, 0x00080000, 0x00140c0d, 0x005b575a, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b8b4b0, 0x00918e8f, 0x004c484b, 0x00100d0c, 0x00070000, 0x000f0000, 0x00240700, 0x003e1200, 0x005c2e16, 0x004f2c1d, 0x00281108, 0x007a7068, 0x00bdbbb5, 0x00c7c8c3, 0x00c4c4c2, 0x00b8b7bb, 0x00b8b5bb, 0x00b8b7bb, 0x00b7b8b8, 0x00b3b8b3, 0x00b4bcb5, 0x00b2bcb5, 0x00acb5b0, 0x00b6b8b4, 0x00b6b8b5, 0x00b4b8bc, 0x00b4b7bc, 0x00bab5b8, 0x00bab5b7, 0x00b7b6ba, 0x00b4b8ba, 0x00b2b5b4, 0x00b6b8b3, 0x00bbb9af, 0x00b8b8af, 0x00b1b8b4, 0x00b1b8b8, 0x00b7b8b6, 0x00bcb9b5, 0x00bcb9b2, 0x00b8b6b2, 0x00b7babb, 0x00b3b7b9, 0x00babbbc, 0x00ccccca, 0x00b3aca8, 0x00514a44, 0x000f0b08, 0x00080000, 0x00100000, 0x003f1800, 0x009f5222, 0x00ba5415, 0x00c6530d, 0x00c44d05, 0x00c25110, 0x00b6531b, 0x00a1542b, 0x00450e00, 0x00170000, 0x001a0000, 0x00622a0d, 0x00a05020, 0x00c25713, 0x00c85205, 0x00c75107, 0x00be510e, 0x00ad521a, 0x00943a04, 0x00b54c0b, 0x00c05006, 0x00c45104, 0x00c0520c, 0x00b5521f, 0x008d4320, 0x00361100, 0x00100000, 0x000d0000, 0x003c1c05, 0x00904512, 0x00bc5414, 0x00c45012, 0x00c44e10, 0x00c05310, 0x00bf540c, 0x00c05105, 0x00b75513, 0x00995127, 0x002f0100, 0x00170000, 0x00391504, 0x00944914, 0x00b95811, 0x00bd520c, 0x00c1530c, 0x00be520a, 0x00b65417, 0x00914520, 0x004b1a0b, 0x000a0000, 0x00060000, 0x001e0000, 0x00733814, 0x00b1541a, 0x00bf520c, 0x00bc5209, 0x00bc5713, 0x00b2571c, 0x00702500, 0x00300000, 0x00471a0c, 0x0086492e, 0x00774228, 0x00250f06, 0x00050000, 0x00080000, 0x00201912, 0x0094908d, 0x00c8c8c8, 0x00cbcccc, 0x00b8bbbd, 0x00c0c1bf, 0x00b0b0ac, 0x00bebcb8, 0x00bdbcbb, 0x00b4b4b8, 0x00b3b6bd, 0x00b2b9bf, 0x00b2babc, 0x00b4b8b5, 0x00b5bab2, 0x00b9bab5, 0x00b9bbba, 0x00b7b8c3, 0x00b5b7c1, 0x00c0bebf, 0x00bab9b6, 0x00b4b7b8, 0x00b5b9bc, 0x00b4bbbd, 0x00b4b8ba, 0x00b4b6b5, 0x00b5b7b4, 0x00b8bcb8, 0x00afb4b4, 0x00c6cccc, 0x00c4c5c7, 0x00b0a8a6, 0x006c5853, 0x00240300, 0x007b462c, 0x00a9582c, 0x00b65418, 0x00bc5812, 0x00bd5911, 0x00ba5918, 0x00ac5823, 0x007e3c18, 0x00411500, 0x00160100, 0x00080000, 0x00000000, 0x00080100, 0x00100000, 0x00290700, 0x00663509, 0x009b591e, 0x00b15e17, 0x00ba5c10, 0x00bf5f11, 0x00bf5d0c, 0x00bc5605, 0x00c05908, 0x00c75e0b, 0x00c45c08, 0x00c75e09, 0x00c6600a, 0x00c7600b, 0x00c76009, 0x00c66008, 0x00c56005, 0x00c65e03, 0x00c65f01, 0x00c76002, 0x00bc6415, 0x00915624, 0x00371500, 0x000c0000, 0x000b0000, 0x00200900, 0x0070401d, 0x00b96923, 0x00c35f08, 0x00c85d0b, 0x00c25504, 0x00c45804, 0x00bd5a0d, 0x00a35015, 0x0074340c, 0x00290400, 0x004a2614, 0x008c5031, 0x00a45728, 0x00b25418, 0x00b9530d, 0x00bd5508, 0x00b85001, 0x00ba540a, 0x00c15c17, 0x00b7520f, 0x00aa480b, 0x00af541e, 0x00b25b24, 0x00ae5417, 0x00ab5116, 0x00a14f19, 0x009c501c, 0x00975019, 0x00964c14, 0x009b490d, 0x00a3551e, 0x008e4e27, 0x00582a13, 0x00140000, 0x00080000, 0x00040000, 0x000a0000, 0x00320c00, 0x00824820, 0x00a45d30, 0x00934d22, 0x003c0300, 0x00682903, 0x00aa5214, 0x00bd560c, 0x00c4580f, 0x00c25710, 0x00bc5817, 0x00893e0c, 0x00371400, 0x000a0000, 0x00140b0c, 0x00585458, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a8aca6, 0x005f605c, 0x001c1c1c, 0x00050000, 0x00140000, 0x00280400, 0x00441000, 0x00732f03, 0x00a85722, 0x00aa5c29, 0x008d542d, 0x00442005, 0x00362518, 0x008d8984, 0x00c6c8c5, 0x00c4c8c8, 0x00c5c6c8, 0x00babbbc, 0x00afafb0, 0x00b1b1b3, 0x00b8b9bb, 0x00b4b5b4, 0x00b0b1af, 0x00b8b9b7, 0x00b4b5b1, 0x00b2b5b4, 0x00b0b6b8, 0x00b0b4b8, 0x00b4b3b4, 0x00b7b4b3, 0x00b4b4b6, 0x00b3b6b8, 0x00b1b4b4, 0x00b4b5b1, 0x00b8b5ae, 0x00b6b6b0, 0x00afb6b5, 0x00aeb6b8, 0x00b2b5b6, 0x00b4b4b3, 0x00b3b4af, 0x00afb0ac, 0x00b0b6b8, 0x00b9bfc4, 0x00c7c9cc, 0x00bdbabb, 0x00746760, 0x00312017, 0x001c0f09, 0x001c0a01, 0x001c0000, 0x004e1e00, 0x00a85827, 0x00b65212, 0x00c4550f, 0x00c1500a, 0x00be530f, 0x00b0551c, 0x0095532b, 0x003a0c00, 0x00140000, 0x00250700, 0x00703410, 0x00aa5620, 0x00b85009, 0x00c44e01, 0x00c55003, 0x00c2530a, 0x00ba5518, 0x00ab480b, 0x00b84d08, 0x00c35004, 0x00c44e00, 0x00c35003, 0x00b95017, 0x009b4b23, 0x00380f00, 0x000e0000, 0x000a0000, 0x002e1100, 0x007f3a0b, 0x00b8571b, 0x00c04e11, 0x00c55010, 0x00c0510d, 0x00c1530a, 0x00c35004, 0x00ba5310, 0x00a0572b, 0x00380800, 0x00180000, 0x00391402, 0x00924812, 0x00b85710, 0x00be530d, 0x00c1530c, 0x00bf5009, 0x00b65417, 0x00914520, 0x00491808, 0x000b0000, 0x00050000, 0x001c0000, 0x00703915, 0x00ad541b, 0x00bd540e, 0x00bd500a, 0x00bc5412, 0x00b65820, 0x00762c04, 0x00320400, 0x0043180a, 0x00824627, 0x00784023, 0x00290e04, 0x00110200, 0x00271005, 0x002c1709, 0x0041342c, 0x00b5aeaa, 0x00cac7c8, 0x00c3c1c4, 0x00babab8, 0x00bcbcba, 0x00b0b2b0, 0x00b1b4b4, 0x00b3b7b9, 0x00b2b6bb, 0x00afb3b8, 0x00b0b4b6, 0x00b5b5b4, 0x00b7b7b0, 0x00b6b4ae, 0x00b4b2ae, 0x00b6b4b7, 0x00bababc, 0x00b3b4b0, 0x00b5b7b3, 0x00b1b4b4, 0x00aeb3b3, 0x00b0b5b4, 0x00b3b8b6, 0x00b4b8b4, 0x00b5b9b4, 0x00b3bab6, 0x00bbc2be, 0x00c7ccca, 0x00bebab5, 0x00907e73, 0x002d0d00, 0x00542407, 0x009b582f, 0x00b55b23, 0x00bb5310, 0x00c55a0c, 0x00c55708, 0x00bc4e03, 0x00bf5918, 0x00b15b29, 0x0083411c, 0x004c2108, 0x001d0400, 0x000b0000, 0x00080000, 0x000a0000, 0x000e0000, 0x00200300, 0x005a2b0b, 0x00a2541e, 0x00b05313, 0x00bb5b16, 0x00c05f16, 0x00c05b0f, 0x00c45d0c, 0x00c45f0b, 0x00be5803, 0x00c05c04, 0x00c05c04, 0x00bf5b03, 0x00c05c04, 0x00c15c04, 0x00c45f06, 0x00c66008, 0x00c56109, 0x00c0610b, 0x00b66820, 0x00703f14, 0x00240800, 0x00080000, 0x000c0000, 0x002b0e00, 0x0078441c, 0x00bd6b20, 0x00c86409, 0x00ca6009, 0x00c55903, 0x00c55903, 0x00be5706, 0x00b95816, 0x00ac5826, 0x005f2304, 0x00330000, 0x006b3414, 0x009c572c, 0x00b1541a, 0x00bb5210, 0x00ba520f, 0x00bc540f, 0x00b9510b, 0x00b04e0a, 0x00b0561c, 0x00a95a2c, 0x00955435, 0x008c5037, 0x00844828, 0x006c3518, 0x00572a14, 0x00431a04, 0x004a1800, 0x00551a00, 0x00611900, 0x008a3d0c, 0x009d552b, 0x00703718, 0x002d0a00, 0x000e0000, 0x00000004, 0x00040000, 0x001c0600, 0x00623415, 0x00a85c31, 0x00ac5c2c, 0x00662400, 0x006c2800, 0x00ad5313, 0x00bd540c, 0x00c4580b, 0x00c2580d, 0x00bc5815, 0x008a3f0d, 0x00361400, 0x00080000, 0x00140c0d, 0x00545357, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000c0d0c, 0x00888a84, 0x00343630, 0x00100e08, 0x000d0200, 0x00180000, 0x00390d00, 0x006d2f0a, 0x00a45420, 0x00bb5f1f, 0x00b8500a, 0x00c05f1b, 0x00ac5e25, 0x007e471b, 0x00341300, 0x00514236, 0x009b9794, 0x00c6c7c8, 0x00bfc2c3, 0x00c0c3c2, 0x00bababc, 0x00b2b0b3, 0x00b2b0b4, 0x00b5b1b6, 0x00b5b1b6, 0x00b5b4b4, 0x00b2b2b0, 0x00b0b3b2, 0x00acb4b6, 0x00aeb4b7, 0x00b2b4b3, 0x00b3b3b1, 0x00b2b3b4, 0x00b0b4b4, 0x00b1b4b5, 0x00b1b3b0, 0x00b4b1ad, 0x00b3b2af, 0x00afb5b8, 0x00afb6ba, 0x00afb3b8, 0x00aeb1b4, 0x00b4b8b5, 0x00b3b8b4, 0x00b2b8bb, 0x00bcc2c7, 0x00c2c2c8, 0x00898182, 0x0041281d, 0x003d2011, 0x00442c24, 0x00290e04, 0x00240000, 0x00602806, 0x00af5c27, 0x00b4500e, 0x00c0530c, 0x00c2530a, 0x00be540b, 0x00b15718, 0x008f5029, 0x00350c00, 0x00150000, 0x00361300, 0x007e3e14, 0x00ae581d, 0x00bd5711, 0x00c4540a, 0x00c45104, 0x00be4d04, 0x00ba500e, 0x00b54e0c, 0x00b64b04, 0x00c15208, 0x00c65304, 0x00c25308, 0x00b75118, 0x00a4562d, 0x00441900, 0x00130000, 0x000c0000, 0x001f0500, 0x006d3006, 0x00b35820, 0x00bc4e12, 0x00c65010, 0x00c0500b, 0x00c15208, 0x00c45104, 0x00bc5410, 0x00a5592c, 0x00410d00, 0x00190000, 0x003b1403, 0x00934712, 0x00b85510, 0x00bf5410, 0x00c1530c, 0x00c05108, 0x00b85517, 0x0090441e, 0x00461504, 0x000c0000, 0x00050000, 0x001a0000, 0x006c3815, 0x00aa541c, 0x00be5613, 0x00be510c, 0x00bc5213, 0x00b65821, 0x007a3009, 0x00340800, 0x00411b09, 0x00854928, 0x00793f1e, 0x002e0c00, 0x00200600, 0x004d2815, 0x0064402b, 0x00180100, 0x005c4e46, 0x00c6bebd, 0x00c8c4c8, 0x00c7c5c6, 0x00b1b3b2, 0x00b8bbba, 0x00adb2b2, 0x00acb3b4, 0x00aeb2b4, 0x00b2b5b8, 0x00b3b3b4, 0x00b5b2b1, 0x00b7b3b0, 0x00b7b3b0, 0x00b4b1ad, 0x00b0b0ac, 0x00b0b0ae, 0x00b0b2b0, 0x00b2b7b5, 0x00b2b7b7, 0x00b0b4b4, 0x00b1b4b4, 0x00b0b4b1, 0x00afb3ae, 0x00b0b4b0, 0x00b8bdba, 0x00c6cac7, 0x00c1c0bc, 0x0094897f, 0x00351804, 0x00401200, 0x00945428, 0x00b05d28, 0x00b75615, 0x00bc540b, 0x00c15403, 0x00c45402, 0x00c35304, 0x00c1550d, 0x00bc591c, 0x00b05c28, 0x00905025, 0x00603113, 0x00200300, 0x00120000, 0x00130206, 0x000a0000, 0x000d0000, 0x001a0000, 0x004e1300, 0x0093481c, 0x00b0602e, 0x00aa571c, 0x00b45a18, 0x00bb5d13, 0x00bc5808, 0x00c46009, 0x00c25d04, 0x00c25d03, 0x00c35e04, 0x00c46007, 0x00c56109, 0x00c5610b, 0x00c35f08, 0x00bd5f0a, 0x00bc6210, 0x00b06928, 0x00542a08, 0x00190400, 0x00060000, 0x000c0000, 0x00381400, 0x00844a1c, 0x00bc6718, 0x00c86508, 0x00c86307, 0x00c75f05, 0x00c45c05, 0x00bd5604, 0x00bf540c, 0x00bc5a1c, 0x00a75429, 0x00541000, 0x00430900, 0x007c3e19, 0x00a7501c, 0x00b9581c, 0x00b55419, 0x00b25118, 0x00b4551a, 0x00ac5620, 0x00974f24, 0x00784122, 0x00532a1b, 0x002f0d04, 0x001e0000, 0x00180000, 0x00160000, 0x00160000, 0x00240000, 0x00470b00, 0x007a3202, 0x00a2531d, 0x00a85925, 0x008a4721, 0x004b1f0f, 0x00130000, 0x00030003, 0x00030102, 0x00120400, 0x00452005, 0x00a1582e, 0x00ac5725, 0x00944c1e, 0x008a3e0b, 0x00b65717, 0x00c1570c, 0x00c45808, 0x00c25709, 0x00bc5814, 0x008a3f0d, 0x00321100, 0x00080000, 0x00150e10, 0x0057565b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b5b2b0, 0x0060605c, 0x001c1914, 0x00090200, 0x000d0000, 0x00280300, 0x005e2708, 0x009f5425, 0x00b55d21, 0x00b95914, 0x00c0590e, 0x00ca5d0e, 0x00bc5304, 0x00c06218, 0x00b6682b, 0x006e3409, 0x00310a00, 0x00604a43, 0x00b1a9a8, 0x00cccccc, 0x00c3c6c7, 0x00bfbdbe, 0x00b8b4b7, 0x00b4acb5, 0x00b7aeb9, 0x00b8b1bc, 0x00b0aeb5, 0x00b0b0b2, 0x00afb2b3, 0x00acb4b5, 0x00acb4b6, 0x00b0b3b2, 0x00b0b2b0, 0x00afb2b1, 0x00afb2b3, 0x00aeb1b2, 0x00b0b0b2, 0x00b3b0af, 0x00b2b0b3, 0x00adb3b9, 0x00acb4bb, 0x00acb2ba, 0x00acb2b7, 0x00a7afb0, 0x00b0b8b8, 0x00c1c8c9, 0x00c2c3c6, 0x00949094, 0x003f2e2a, 0x00380f00, 0x00734632, 0x0059382c, 0x00240100, 0x00310200, 0x0075340f, 0x00b25c24, 0x00b75310, 0x00be520a, 0x00c15105, 0x00c45204, 0x00b65611, 0x008c4c20, 0x00340a00, 0x00190000, 0x00492107, 0x008d4818, 0x00b0581b, 0x00b55411, 0x00bc540d, 0x00c2530a, 0x00c05008, 0x00bf520d, 0x00bf5410, 0x00b74d09, 0x00bc540d, 0x00b8510a, 0x00b65513, 0x00b05724, 0x00a15c37, 0x00441f08, 0x00120000, 0x00080000, 0x00140000, 0x005d2703, 0x00a85523, 0x00bb5015, 0x00c65211, 0x00c05009, 0x00c25206, 0x00c55205, 0x00bc5411, 0x00a75a2a, 0x004a1400, 0x001c0000, 0x00401604, 0x00944815, 0x00b85411, 0x00bf5410, 0x00c1510c, 0x00c2530a, 0x00b85616, 0x0090441c, 0x00401200, 0x000c0000, 0x00040000, 0x00190000, 0x006b3818, 0x00a85520, 0x00be5714, 0x00c0510f, 0x00bd5012, 0x00b55621, 0x0078300a, 0x00330b00, 0x00431e0b, 0x00894c25, 0x007e411a, 0x00330c00, 0x00280300, 0x006c3519, 0x008c5435, 0x0058331c, 0x00160000, 0x0058504e, 0x00bebcc0, 0x00c9c8cc, 0x00c1c2c5, 0x00b0b4b7, 0x00acb4b3, 0x00b0b8b7, 0x00b0b4b4, 0x00aeaeae, 0x00b2afb0, 0x00b3aeb1, 0x00b1acae, 0x00b0acad, 0x00b0b0ae, 0x00b2b4b0, 0x00b1b6b3, 0x00aab0b3, 0x00a9b0b4, 0x00aab0b4, 0x00adb1b4, 0x00afb0b3, 0x00afb0b1, 0x00b6b8b7, 0x00c0c1c0, 0x00c9cccc, 0x00c4c3c0, 0x00968e87, 0x003c2416, 0x00401400, 0x00814016, 0x00ac5720, 0x00b85515, 0x00bd570e, 0x00bf580b, 0x00bb5404, 0x00bc5704, 0x00c35b0c, 0x00bd5508, 0x00b85209, 0x00bc5c18, 0x00af5a1c, 0x009f5b25, 0x007b4823, 0x00381200, 0x00130000, 0x000f0000, 0x000a0000, 0x000d0000, 0x00170000, 0x00240000, 0x00592c14, 0x00925936, 0x00a25e2b, 0x00ad5c1c, 0x00bc6016, 0x00be5a05, 0x00c75f05, 0x00c55c00, 0x00c35a00, 0x00c15900, 0x00c05c03, 0x00c05e09, 0x00c0600c, 0x00be6110, 0x00b56214, 0x00a66429, 0x003f1a00, 0x00140200, 0x00050000, 0x000c0000, 0x004a1d00, 0x0097541e, 0x00bb6411, 0x00c46403, 0x00c56205, 0x00c46007, 0x00c05f0b, 0x00c15c0c, 0x00c55508, 0x00c3520c, 0x00be591c, 0x009c481a, 0x003f0200, 0x004f1700, 0x0091481b, 0x00a4531e, 0x00a95824, 0x00a55628, 0x00994d27, 0x00783819, 0x00441700, 0x001e0000, 0x000d0000, 0x00090000, 0x000f0000, 0x00150000, 0x00100000, 0x00240300, 0x005e2502, 0x009a501f, 0x00b05c22, 0x00b1591a, 0x00b25c1e, 0x00a45928, 0x00612f14, 0x001d0000, 0x00080000, 0x00070000, 0x000a0000, 0x002d0d00, 0x00975528, 0x00ad5b25, 0x00ae5d27, 0x00ac551c, 0x00ba5614, 0x00c4580e, 0x00c55706, 0x00c25708, 0x00bc5814, 0x00883c0c, 0x002f1000, 0x00070000, 0x00141011, 0x005c5d61, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a8a3a4, 0x004a4240, 0x00100601, 0x000d0000, 0x00170000, 0x00441c04, 0x00894a28, 0x00af5c2d, 0x00b85718, 0x00bd560b, 0x00c45e08, 0x00bd5800, 0x00ca5f06, 0x00cb6108, 0x00c56109, 0x00c36b1d, 0x00b26930, 0x00693410, 0x002c0e00, 0x00544844, 0x00a9a8a5, 0x00c8cbca, 0x00ccccca, 0x00c1bebf, 0x00bfb9c0, 0x00b4aeb7, 0x00a8a6af, 0x00b1b0b7, 0x00b0afb3, 0x00adb0b1, 0x00abb1b4, 0x00aab2b3, 0x00acb1ae, 0x00adb1ae, 0x00acb0af, 0x00acb0b0, 0x00acadb0, 0x00b0afb3, 0x00b4b0b3, 0x00b0aeb4, 0x00a9acb5, 0x00a6acb5, 0x00a9b0b8, 0x00adb4b8, 0x00b7bfc0, 0x00b9c0c0, 0x00cccccc, 0x009c9694, 0x00382b2b, 0x002a0d04, 0x00753e24, 0x00905539, 0x005a3122, 0x001f0000, 0x00420d00, 0x00844017, 0x00af561d, 0x00b95410, 0x00c2540b, 0x00c35004, 0x00c55204, 0x00b65412, 0x0086461d, 0x00330800, 0x001d0000, 0x005c2f11, 0x009c5220, 0x00b0571a, 0x00b4581a, 0x00b75617, 0x00ba5312, 0x00b85110, 0x00b75215, 0x00b6551b, 0x00ae541d, 0x00ac5823, 0x00ae5f28, 0x00a65c2a, 0x0098542c, 0x00854f33, 0x003c200e, 0x00100500, 0x00080100, 0x000f0000, 0x004d1d00, 0x00994d1f, 0x00ba5118, 0x00c65210, 0x00c05008, 0x00c15208, 0x00c45207, 0x00bc5412, 0x00a95929, 0x00521800, 0x00200000, 0x00461907, 0x00984a18, 0x00b85410, 0x00c05310, 0x00c0500b, 0x00c25308, 0x00b85616, 0x008c431a, 0x003c0f00, 0x000c0000, 0x00040000, 0x001a0100, 0x006b391a, 0x00a85520, 0x00bd5614, 0x00c1500f, 0x00be5113, 0x00b45522, 0x00742d07, 0x00300900, 0x0044210d, 0x00884a20, 0x0084441b, 0x00380d00, 0x00330500, 0x0085401c, 0x009f572f, 0x00936043, 0x00240600, 0x000f0300, 0x00575356, 0x00b4b0b3, 0x00cac7c8, 0x00c8c8c8, 0x00b9bcbd, 0x00a7aead, 0x00a6adac, 0x00acacae, 0x00b0afb1, 0x00b4b0b5, 0x00b3afb4, 0x00b0afb4, 0x00adb0b1, 0x00abb0ac, 0x00a6ada9, 0x00aeb4b7, 0x00abaeb5, 0x00acaeb4, 0x00afb0b4, 0x00b0afb3, 0x00b8b4b8, 0x00c2c0c3, 0x00c8c7c8, 0x00bebcbd, 0x008a8481, 0x0031231b, 0x002c0d00, 0x00764222, 0x00a55c2f, 0x00ae5016, 0x00c05814, 0x00ba530a, 0x00bc5409, 0x00be5909, 0x00be5808, 0x00bb5407, 0x00bc5407, 0x00bf5408, 0x00bc550c, 0x00ba5910, 0x00b65f1c, 0x00a25820, 0x008e5128, 0x005e3115, 0x00260400, 0x00140000, 0x00120000, 0x000c0000, 0x00100000, 0x00160000, 0x00320a00, 0x0064300e, 0x008e4f21, 0x00a55b23, 0x00b4601f, 0x00b45b14, 0x00ba5c10, 0x00bd5f10, 0x00be5e10, 0x00bc5e10, 0x00bc5d10, 0x00bc5d10, 0x00b95f14, 0x00b7631a, 0x009e5e27, 0x00320f00, 0x000f0000, 0x00050000, 0x00100000, 0x005e2b06, 0x00a65c1e, 0x00bd640f, 0x00c36404, 0x00c06205, 0x00b95d08, 0x00ab5408, 0x00ba5c12, 0x00cb5b0d, 0x00c75004, 0x00c0500a, 0x00ba5c22, 0x00702f08, 0x003c0500, 0x006c310a, 0x0094562c, 0x0090512b, 0x007c4222, 0x00481602, 0x00240000, 0x00100000, 0x000c0000, 0x00040000, 0x00050000, 0x00100000, 0x00140000, 0x00320c00, 0x007a4628, 0x00a35b2b, 0x00a95317, 0x00b45714, 0x00b75712, 0x00b45310, 0x00ab551d, 0x00793e1a, 0x00340f00, 0x00100000, 0x00080000, 0x00080000, 0x00200500, 0x0080441a, 0x00ab5a24, 0x00ae581c, 0x00ba5b1b, 0x00ba520f, 0x00c4550c, 0x00c65805, 0x00c15807, 0x00bc5a18, 0x007f3608, 0x002a0c00, 0x00050000, 0x00141414, 0x0064666a, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008c8c88, 0x00342e2c, 0x000f0000, 0x00180000, 0x002e0500, 0x00632c0d, 0x00924d20, 0x00b2571f, 0x00bc5313, 0x00c15209, 0x00c85a07, 0x00c46201, 0x00c46800, 0x00c66500, 0x00cc6e06, 0x00c86804, 0x00bc640b, 0x00b06421, 0x00a1683c, 0x004c2c15, 0x001a0c02, 0x003e3e38, 0x00919791, 0x00c6cac4, 0x00c5c8c2, 0x00c3c3c1, 0x00babcbb, 0x00aab1b0, 0x00acb0b3, 0x00aeafb2, 0x00adaeb1, 0x00aaaeb0, 0x00a8afae, 0x00a9aeab, 0x00a9aeab, 0x00a9aeac, 0x00abaeaf, 0x00acacb0, 0x00adacb1, 0x00b0acb2, 0x00aeacb3, 0x00aaacb4, 0x00abb0b7, 0x00b1b7bc, 0x00b6bcbf, 0x00c7cccc, 0x00c8c8c6, 0x008c837e, 0x00302019, 0x00170000, 0x005a301f, 0x0098542e, 0x009a552e, 0x00582c19, 0x001f0000, 0x004b1600, 0x008e481e, 0x00ae551c, 0x00b9520f, 0x00c55308, 0x00c65004, 0x00c25109, 0x00b2541a, 0x0080421f, 0x00310600, 0x00230000, 0x006c3b1d, 0x00a45824, 0x00ac5217, 0x00b05720, 0x00ae5723, 0x00b35926, 0x00b05b2b, 0x00a4572c, 0x008f4925, 0x00783c1f, 0x00623015, 0x004a1d01, 0x003a1000, 0x002b0100, 0x00260400, 0x00130400, 0x00070300, 0x00020001, 0x000a0000, 0x003e1500, 0x00874018, 0x00b85219, 0x00c3510e, 0x00bf5008, 0x00c05209, 0x00c2520c, 0x00b95416, 0x00ac592a, 0x00591d00, 0x00260000, 0x004c1c08, 0x009c4c1a, 0x00b85412, 0x00c05410, 0x00c0500b, 0x00c05107, 0x00b65514, 0x00874018, 0x00350a00, 0x000b0000, 0x00050000, 0x00190200, 0x006c3b1c, 0x00ac5521, 0x00bc5311, 0x00c04f0c, 0x00bf5214, 0x00b25622, 0x006f2c06, 0x002d0700, 0x0046210c, 0x008c4c21, 0x00844217, 0x003d1000, 0x00410e00, 0x0097461b, 0x00a95424, 0x00915230, 0x003e1600, 0x000e0000, 0x000d0504, 0x003c2e2c, 0x009e908c, 0x00c5bcbb, 0x00ccc9c8, 0x00bdc4c5, 0x00b4bcbe, 0x00aab1b5, 0x00a8acb3, 0x00a8a8b1, 0x00a8a8b1, 0x00a9abb4, 0x00a8aeb3, 0x00a8b0ad, 0x00a8afab, 0x00aaacab, 0x00a8a7a9, 0x00b0acad, 0x00b8b3b4, 0x00c1b9ba, 0x00ccc7c8, 0x00cac3c4, 0x00b3acac, 0x006c6465, 0x00211614, 0x00321f17, 0x00674634, 0x00956143, 0x009e582e, 0x00b25825, 0x00b55217, 0x00bb5413, 0x00bc520e, 0x00c0540a, 0x00c05308, 0x00c05308, 0x00c55910, 0x00c55a13, 0x00bb520a, 0x00bc550c, 0x00b9550d, 0x00bb5b16, 0x00af5719, 0x00a15623, 0x008d5024, 0x005b2908, 0x002c0700, 0x00140000, 0x00170000, 0x00170000, 0x00170000, 0x001e0000, 0x002c0300, 0x00471700, 0x00633014, 0x00834929, 0x0092542d, 0x00a45f34, 0x00af6432, 0x00b36029, 0x00b45c1f, 0x00b95d1b, 0x00bc601c, 0x00b8601b, 0x00995520, 0x002b0900, 0x000c0000, 0x00060000, 0x001c0300, 0x00743a0e, 0x00af5f1a, 0x00bd640d, 0x00c06306, 0x00bd640c, 0x00ac580b, 0x008a4100, 0x00a15010, 0x00c55d12, 0x00c85404, 0x00c55306, 0x00be5915, 0x00a75b24, 0x004d1400, 0x00380a00, 0x005c341a, 0x0049240d, 0x00200200, 0x000c0000, 0x00080000, 0x00050100, 0x00080200, 0x000b0000, 0x00100000, 0x00270500, 0x005b280b, 0x009b542e, 0x00a65120, 0x00ab4e10, 0x00b5540f, 0x00ba540e, 0x00b84e0a, 0x00bf500d, 0x00b75418, 0x00954c20, 0x0054250a, 0x00120000, 0x00070000, 0x00050000, 0x00180200, 0x005e2705, 0x00a65721, 0x00af5312, 0x00bc550e, 0x00be510c, 0x00c4540a, 0x00c65804, 0x00be5705, 0x00bb5c1a, 0x00742f04, 0x00230600, 0x00040000, 0x00191c1d, 0x00707678, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007e8078, 0x002f2c23, 0x00110100, 0x00190000, 0x00441200, 0x007c3a1c, 0x00a45726, 0x00b65c1d, 0x00be550f, 0x00c9570a, 0x00cc5805, 0x00cc6005, 0x00c66700, 0x00c56c00, 0x00c56800, 0x00c56a00, 0x00be690b, 0x00b96c1e, 0x00a96930, 0x006c3b15, 0x00301300, 0x000f0000, 0x00120c03, 0x002c2b21, 0x007a7b70, 0x00bcbeb4, 0x00c5c8bf, 0x00c4c8c3, 0x00c2cbc8, 0x00b3bab9, 0x00afaeb2, 0x00aeacb0, 0x00abacad, 0x00a8abaa, 0x00a7aba8, 0x00a7aca8, 0x00a8acab, 0x00aaadae, 0x00acacb0, 0x00a9a8ad, 0x00a8a6ad, 0x00acaab0, 0x00b4b4b8, 0x00bebec0, 0x00c4c6c5, 0x00c9c8c5, 0x00b8b3ae, 0x00695c55, 0x002d180e, 0x001f0400, 0x00200000, 0x0068351b, 0x009d5020, 0x00a05425, 0x00542711, 0x001e0000, 0x004d1700, 0x00974f24, 0x00b45a22, 0x00b84f0c, 0x00c44e04, 0x00c54e03, 0x00c0500c, 0x00af531d, 0x007d4122, 0x00310900, 0x00240200, 0x006e432e, 0x009c5b34, 0x009a5022, 0x0087421b, 0x0074320c, 0x00612000, 0x004f1300, 0x003f0b00, 0x002c0300, 0x00260700, 0x00160000, 0x00140300, 0x00100000, 0x00100000, 0x000b0000, 0x00050000, 0x00000000, 0x00000001, 0x000d0100, 0x00341000, 0x00783a15, 0x00b4541c, 0x00c1510d, 0x00bd5109, 0x00be5208, 0x00c0510d, 0x00b85115, 0x00ad5b2c, 0x00602000, 0x002b0000, 0x00511e08, 0x009e4c19, 0x00b85312, 0x00c25310, 0x00c0500b, 0x00bf5008, 0x00b25415, 0x0083401a, 0x00300800, 0x00080000, 0x00050000, 0x001c0300, 0x00703c1c, 0x00af5520, 0x00c05010, 0x00bf4d08, 0x00be5413, 0x00b15823, 0x006c2b04, 0x002b0400, 0x0045200c, 0x008d4d23, 0x00813d12, 0x00431200, 0x004a1300, 0x00a54d1b, 0x00b45720, 0x009e5530, 0x00451400, 0x00160000, 0x00372820, 0x002b1107, 0x0034180c, 0x006e564e, 0x00ac9d98, 0x00c8c7c5, 0x00c0c6c8, 0x00bdc4c8, 0x00b7bcc3, 0x00b4b5bf, 0x00b1b3bc, 0x00acb0b8, 0x00a6acb0, 0x00a7afae, 0x00afb4b0, 0x00b5b5b4, 0x00bab7b4, 0x00c6c2c0, 0x00ccc7c5, 0x00cac3c4, 0x00bfb8b8, 0x00878284, 0x003c393a, 0x00131010, 0x000c0402, 0x00261810, 0x00432819, 0x00512811, 0x00652f10, 0x0075330b, 0x00904216, 0x00a45022, 0x00b35825, 0x00b5571d, 0x00b55314, 0x00bb5411, 0x00bc520e, 0x00bc510c, 0x00c1550d, 0x00c05308, 0x00c15206, 0x00c35408, 0x00c0570e, 0x00b55614, 0x00ab581d, 0x00a15928, 0x008e542b, 0x00744525, 0x00562e12, 0x003e1600, 0x00300700, 0x00260000, 0x00250000, 0x002a0000, 0x002d0000, 0x00320100, 0x003f0800, 0x004c0e00, 0x00551000, 0x00621500, 0x007b2800, 0x009e4404, 0x00b65a18, 0x00b45a18, 0x00934c1a, 0x00270700, 0x000b0000, 0x000a0000, 0x00290d00, 0x00884814, 0x00b56118, 0x00bc600a, 0x00bd6008, 0x00bd6614, 0x00a55711, 0x00713400, 0x008a470f, 0x00bd5e16, 0x00c65807, 0x00c85606, 0x00c0580b, 0x00b45d1b, 0x00884713, 0x003b0f00, 0x001d0000, 0x00170000, 0x000d0100, 0x00010206, 0x00000004, 0x00030000, 0x000a0000, 0x00160000, 0x00391400, 0x00703c14, 0x009b5422, 0x00a94d18, 0x00bb5418, 0x00bc5411, 0x00ba530a, 0x00bc500b, 0x00bf500d, 0x00c45010, 0x00b94f13, 0x00a75423, 0x006f3816, 0x00140000, 0x00030000, 0x00000005, 0x000d0000, 0x00441200, 0x00a95e2c, 0x00b65714, 0x00bb5006, 0x00c5550f, 0x00c45408, 0x00c65804, 0x00bb5404, 0x00b75c1e, 0x006c2a02, 0x001a0000, 0x00030000, 0x00202424, 0x007d8486, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00787a73, 0x00282824, 0x000e0000, 0x00200000, 0x00511900, 0x008d4116, 0x00b2581f, 0x00bb5b16, 0x00bd560b, 0x00c35808, 0x00cc5f0a, 0x00cc6407, 0x00cc6401, 0x00c86700, 0x00c76800, 0x00ca6900, 0x00bc6304, 0x00b77028, 0x00945d2c, 0x00532c10, 0x00280c00, 0x00140000, 0x00100000, 0x00180500, 0x001c0d01, 0x00281c0f, 0x004e4739, 0x00908f84, 0x00c1c4be, 0x00c8cccc, 0x00c1c4c8, 0x00c7c4ca, 0x00c3bfc4, 0x00bcbabc, 0x00b8b8b6, 0x00b3b4b2, 0x00aeb2af, 0x00aeb1b0, 0x00b0b4b4, 0x00b4b5b8, 0x00b9b8bd, 0x00bebcc1, 0x00c3bdc3, 0x00ccc5c4, 0x00ccc6c0, 0x00bcb4ac, 0x00897c70, 0x00442c20, 0x002d0f00, 0x004b2716, 0x0048210f, 0x002e0600, 0x006a3414, 0x00a95823, 0x00984a18, 0x004f230b, 0x001f0000, 0x00521b00, 0x00a4592c, 0x00b1541a, 0x00bf5110, 0x00c34c04, 0x00c84f08, 0x00be4d0c, 0x00b45824, 0x006c3115, 0x00260100, 0x001c0701, 0x00301812, 0x00381401, 0x00340c00, 0x002a0800, 0x00250600, 0x00200100, 0x001a0000, 0x00120000, 0x000c0000, 0x00070000, 0x00030000, 0x00010103, 0x00000003, 0x00020004, 0x00040005, 0x00000000, 0x00000000, 0x00000001, 0x00090000, 0x002a0b00, 0x006d3415, 0x00b45721, 0x00c05310, 0x00bc5209, 0x00bd530a, 0x00c0510f, 0x00b85115, 0x00ae5b2a, 0x00662501, 0x002d0000, 0x005c280e, 0x009c4814, 0x00bc5513, 0x00bf500d, 0x00c0500b, 0x00bc5009, 0x00b1581b, 0x007b3d1a, 0x00210000, 0x000a0000, 0x00080000, 0x001f0300, 0x00763f1d, 0x00b0501a, 0x00c4500d, 0x00c4510c, 0x00bc5410, 0x00af5923, 0x00652500, 0x002a0200, 0x0048200c, 0x008d4d26, 0x00823d14, 0x00451300, 0x00581e00, 0x00b25821, 0x00b7551b, 0x00a4542c, 0x00501800, 0x001c0000, 0x004b3221, 0x006f442d, 0x0052210a, 0x00401401, 0x00401f12, 0x005f514c, 0x008f8d8e, 0x00b2b6b8, 0x00c4c8cc, 0x00c4c5c9, 0x00c1c0c5, 0x00c1c2c6, 0x00c5c6c9, 0x00c2c5c4, 0x00c4c6c2, 0x00c6c7c3, 0x00c8c8c4, 0x00c2c3bf, 0x00a7a7a5, 0x00747474, 0x003b3c3f, 0x0014181b, 0x00060a0d, 0x00000305, 0x00030404, 0x00080501, 0x000f0400, 0x00150400, 0x001e0500, 0x00260800, 0x002f0900, 0x003e0e00, 0x00551c03, 0x007c3c1d, 0x009c542c, 0x00ab5827, 0x00b35419, 0x00bd5410, 0x00c25206, 0x00c44f00, 0x00ca5402, 0x00c65304, 0x00c15304, 0x00bf5810, 0x00b65611, 0x00ae5415, 0x00af5d21, 0x00a0571c, 0x009a571d, 0x0097541c, 0x00914f1a, 0x008b4818, 0x00834114, 0x007c3c11, 0x00793810, 0x0076340c, 0x0079350a, 0x007f3809, 0x00873c08, 0x00944309, 0x00a24c0c, 0x00af5510, 0x00b65b16, 0x00b55b1c, 0x00813c0f, 0x00240500, 0x000c0000, 0x000c0000, 0x00432306, 0x00945117, 0x00b76012, 0x00c0600d, 0x00bf600c, 0x00b96216, 0x00a05718, 0x00602b00, 0x00642c00, 0x00bb6623, 0x00c45d0e, 0x00c35703, 0x00c15706, 0x00bb5a10, 0x00a95b20, 0x005d2a07, 0x00200300, 0x000b0000, 0x00010103, 0x00000308, 0x00000000, 0x00100000, 0x00270500, 0x00512104, 0x008c4f25, 0x009e541a, 0x00ac5616, 0x00b75417, 0x00b85014, 0x00b44f0c, 0x00b9530d, 0x00bc520e, 0x00ba4c0c, 0x00be4c10, 0x00bb5118, 0x00ae5420, 0x0081441d, 0x002b1508, 0x00040206, 0x0000000a, 0x00080000, 0x002d0400, 0x009b5729, 0x00b45713, 0x00bd5003, 0x00c4510a, 0x00c45106, 0x00c85b06, 0x00bc580a, 0x00a8551c, 0x005d2300, 0x00140000, 0x00000000, 0x00292d30, 0x00959ba0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007a7e7b, 0x00282924, 0x00080000, 0x00220300, 0x005d250a, 0x0097491f, 0x00b7571a, 0x00bf580e, 0x00c05805, 0x00c45c03, 0x00c85f04, 0x00ca6103, 0x00cc6405, 0x00cc6806, 0x00c96a05, 0x00c36804, 0x00c46c10, 0x00b5681c, 0x00804818, 0x00411b00, 0x00220800, 0x00130000, 0x00150000, 0x00351400, 0x00633b1f, 0x00774d30, 0x005c381b, 0x00321700, 0x002f1f09, 0x004f4538, 0x00807c78, 0x00b0aeb2, 0x00c6c2c8, 0x00cac4cb, 0x00ccc7c8, 0x00c8c4c4, 0x00c2c4c1, 0x00c1c4c4, 0x00c1c4c4, 0x00c0c4c4, 0x00c0c1c4, 0x00c3c2c6, 0x00ccc8cc, 0x00c8c0c0, 0x00a89994, 0x007f6c60, 0x00503b28, 0x00331500, 0x00451901, 0x00632f17, 0x0085543d, 0x005b2d16, 0x002f0400, 0x006c3516, 0x00a85923, 0x00944813, 0x004b2007, 0x00210000, 0x00581f00, 0x00a85b2a, 0x00b45419, 0x00c15211, 0x00c34c08, 0x00c7500c, 0x00bd5010, 0x00aa501d, 0x00521800, 0x001c0000, 0x000a0000, 0x000d0506, 0x00100000, 0x00140000, 0x000a0000, 0x00070000, 0x00060000, 0x00050000, 0x00000000, 0x00000003, 0x00000004, 0x00000105, 0x00000105, 0x00000309, 0x00000009, 0x00000005, 0x00000000, 0x000a0802, 0x00090100, 0x000c0000, 0x00270800, 0x00683117, 0x00b15624, 0x00be5210, 0x00bb520a, 0x00bd530a, 0x00c2520e, 0x00bb5317, 0x00ac5928, 0x00672602, 0x00300000, 0x00682d13, 0x00a24c18, 0x00bc5412, 0x00be4f0c, 0x00c0510d, 0x00bb530c, 0x00ac561c, 0x00703818, 0x001b0000, 0x00080000, 0x00080000, 0x00200200, 0x00844623, 0x00b7511a, 0x00c54f0a, 0x00c24f08, 0x00b9520f, 0x00aa5822, 0x00602400, 0x00290100, 0x004a2210, 0x008d4f2a, 0x007d3b13, 0x00471400, 0x00652a06, 0x00b3581d, 0x00b95418, 0x00a65129, 0x00581b00, 0x001c0000, 0x00452810, 0x008d5738, 0x008d4b28, 0x00773414, 0x00561d04, 0x003c1807, 0x00331e14, 0x0043362c, 0x00595149, 0x00746963, 0x008c8480, 0x00948f8f, 0x00949394, 0x008f8e8c, 0x008e8e8c, 0x00777874, 0x0060615d, 0x00434440, 0x002c2c2a, 0x00191b1a, 0x000a0b0c, 0x00000305, 0x00000104, 0x00010302, 0x00020300, 0x00070100, 0x00070000, 0x00080000, 0x000a0000, 0x000c0000, 0x00100000, 0x00160000, 0x001c0000, 0x002a0500, 0x00461803, 0x006d3312, 0x00964c1e, 0x00b2581b, 0x00bc540e, 0x00c35307, 0x00c35002, 0x00c65406, 0x00c45408, 0x00bc5107, 0x00bc560d, 0x00c05914, 0x00b4530e, 0x00b45912, 0x00b25a13, 0x00b25a14, 0x00b05915, 0x00ad5816, 0x00a85617, 0x00a65418, 0x00a45418, 0x00a15318, 0x00a3541a, 0x00a65619, 0x00a95718, 0x00af5814, 0x00b45b13, 0x00ba5c10, 0x00ba5e17, 0x00b45b21, 0x0079370f, 0x001d0300, 0x00080000, 0x00120000, 0x005b3411, 0x00a35d1d, 0x00b85e0e, 0x00bd5c0b, 0x00be5e10, 0x00b86019, 0x009b5219, 0x00522400, 0x00491800, 0x00b06223, 0x00bd5e0e, 0x00c45a06, 0x00c55804, 0x00c3580c, 0x00b45a1c, 0x00854318, 0x003f1600, 0x000e0000, 0x00000000, 0x00010000, 0x000c0000, 0x003c1500, 0x006d3310, 0x00904b20, 0x00a4541f, 0x00ac5413, 0x00b55510, 0x00b44d0b, 0x00b9500f, 0x00ba5512, 0x00b24e0b, 0x00b65212, 0x00bc581b, 0x00b65019, 0x00b2501a, 0x00ae531b, 0x00955125, 0x00472a17, 0x00070000, 0x00000004, 0x00060000, 0x00240200, 0x007f421b, 0x00b05515, 0x00bc5105, 0x00c7540b, 0x00c65306, 0x00c55905, 0x00b8590e, 0x009b4f1c, 0x00511e01, 0x00120000, 0x00020100, 0x0035383b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008a8988, 0x00262a2c, 0x00040000, 0x00230600, 0x00612b0d, 0x00954218, 0x00b8551d, 0x00c05612, 0x00c25906, 0x00c15f00, 0x00c56600, 0x00cc6a02, 0x00cc6a04, 0x00cc6508, 0x00c8640b, 0x00c3660f, 0x00bc6a1a, 0x00a56120, 0x00703c0c, 0x00381200, 0x00180000, 0x00130000, 0x00230500, 0x004c2200, 0x00824914, 0x009f561c, 0x00ad6023, 0x00a25c20, 0x00844915, 0x0060370c, 0x003c2004, 0x00312015, 0x00403737, 0x00595158, 0x00706a70, 0x008c8485, 0x009b9794, 0x00a3a3a3, 0x00abacac, 0x00a9abaa, 0x00a3a4a5, 0x009b9c9f, 0x00808082, 0x00686465, 0x00544643, 0x00412718, 0x003f1c04, 0x00411900, 0x0062300d, 0x0085421c, 0x009b5430, 0x009c5e40, 0x00542008, 0x002c0000, 0x006b381c, 0x00a05624, 0x0088410f, 0x00411a00, 0x00240000, 0x005d2200, 0x00ad5c28, 0x00b85417, 0x00c15211, 0x00c24e0f, 0x00c15011, 0x00bb5316, 0x00ae5b28, 0x005c2508, 0x00240600, 0x00060000, 0x00010002, 0x00060000, 0x00050000, 0x00000000, 0x00000001, 0x00000000, 0x00000102, 0x00000406, 0x00000506, 0x00000405, 0x00000303, 0x00000001, 0x00040405, 0x00010004, 0x00020001, 0x00060000, 0x00291c10, 0x00200d07, 0x00140000, 0x00250500, 0x00643017, 0x00ae5624, 0x00bc5310, 0x00ba530a, 0x00bd5108, 0x00c4510c, 0x00bc5214, 0x00ab5827, 0x00682701, 0x00310000, 0x00723518, 0x00a84f1a, 0x00bc5311, 0x00bd4e0c, 0x00bf520f, 0x00b85410, 0x00a2531c, 0x00623014, 0x00160000, 0x00080000, 0x000c0000, 0x00250100, 0x00935028, 0x00ba5118, 0x00c54d08, 0x00c14f05, 0x00b7520f, 0x00a75822, 0x005c2000, 0x00260000, 0x004a2112, 0x00884d2e, 0x0072340f, 0x00481400, 0x00783912, 0x00b25519, 0x00ba5518, 0x00a44f25, 0x005e2003, 0x00180000, 0x002e0f00, 0x008e5029, 0x00ac5c2c, 0x00a95223, 0x009b481c, 0x007f3e1a, 0x00622f10, 0x00481d00, 0x00401c01, 0x00371b04, 0x00392414, 0x002f231d, 0x00322c2a, 0x002c292a, 0x00262628, 0x001e2122, 0x00121413, 0x00060504, 0x00030000, 0x00030000, 0x00040000, 0x00050000, 0x00060000, 0x00080000, 0x000b0000, 0x00100000, 0x00140000, 0x00140000, 0x00130000, 0x00100000, 0x000d0000, 0x000c0000, 0x000e0000, 0x000d0000, 0x00110000, 0x00260800, 0x004a1f02, 0x00783b0e, 0x009d4f16, 0x00b85a1b, 0x00b5500c, 0x00ba510b, 0x00be550d, 0x00bb540a, 0x00bd560c, 0x00c25711, 0x00ba510b, 0x00b9540f, 0x00b8550f, 0x00b95610, 0x00b95811, 0x00b85910, 0x00b85b10, 0x00b75b10, 0x00b65c10, 0x00b45c10, 0x00b55d11, 0x00b85d10, 0x00b85d10, 0x00bb5c0c, 0x00bc5a08, 0x00bd5904, 0x00b9580e, 0x00af5b24, 0x00682c0c, 0x00180100, 0x00080000, 0x00210800, 0x0074461c, 0x00ad6421, 0x00b85d0e, 0x00bf5c0d, 0x00bf5c12, 0x00b9601b, 0x00975019, 0x00481a00, 0x00360800, 0x00a75d21, 0x00bc5e11, 0x00c55b07, 0x00c75804, 0x00c5560d, 0x00bc5416, 0x00b05722, 0x006a2c05, 0x00200400, 0x000c0000, 0x001e0700, 0x00441804, 0x007e3813, 0x00a44d1c, 0x00b15720, 0x00ac5015, 0x00b45416, 0x00b2500e, 0x00b8520c, 0x00b64e08, 0x00b85411, 0x00b05010, 0x00ae561a, 0x00ac5823, 0x00954515, 0x00984715, 0x00a94f17, 0x00a45726, 0x00683e1f, 0x00180600, 0x00040000, 0x00080000, 0x001b0000, 0x005f2c0d, 0x00a8551b, 0x00ba5109, 0x00c8550c, 0x00c85408, 0x00c15706, 0x00b45b16, 0x00874318, 0x00401400, 0x000c0000, 0x00060504, 0x00454649, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9894, 0x00302a25, 0x00040000, 0x00180400, 0x005d2b0f, 0x009a4e23, 0x00b9541c, 0x00c45511, 0x00c25708, 0x00c25d03, 0x00c36700, 0x00c76d00, 0x00ca6c00, 0x00c66700, 0x00c7670c, 0x00c46819, 0x00b4631c, 0x009c581f, 0x00602f09, 0x002d0800, 0x00180000, 0x00210000, 0x00381300, 0x00693910, 0x009a5a20, 0x00ad5f18, 0x00c2671a, 0x00be6013, 0x00ba6119, 0x00af6224, 0x00925a2b, 0x006f482a, 0x003d261b, 0x000c0000, 0x000c060c, 0x001c181c, 0x00302828, 0x00383130, 0x00393838, 0x003c3d3f, 0x003b3c3d, 0x00343537, 0x002e2f30, 0x00222021, 0x00181110, 0x00220f05, 0x0049240d, 0x006b3816, 0x0080441c, 0x009e5728, 0x00ab5421, 0x00ad5828, 0x009d5834, 0x00501800, 0x002b0100, 0x00663820, 0x009a5628, 0x00824114, 0x00371300, 0x00250200, 0x00612400, 0x00ad5b26, 0x00b75112, 0x00c0500e, 0x00bf4e0f, 0x00bd4f13, 0x00b74f10, 0x00b15c25, 0x00753c19, 0x002b0a00, 0x000b0000, 0x00000000, 0x00060000, 0x00030000, 0x00000204, 0x00000204, 0x00000101, 0x00000201, 0x00000304, 0x00000301, 0x00000300, 0x00000300, 0x00000000, 0x00040000, 0x00030001, 0x00060000, 0x000f0000, 0x004c3624, 0x00452718, 0x00240000, 0x00280400, 0x00642f15, 0x00ad5622, 0x00bc5410, 0x00ba530a, 0x00bc5108, 0x00c34e09, 0x00bc5013, 0x00aa5827, 0x00662500, 0x00330000, 0x007b3c1e, 0x00ac521c, 0x00bb510f, 0x00bd4e0d, 0x00bf5312, 0x00b35414, 0x00964c1a, 0x0051270e, 0x00130000, 0x00080000, 0x000e0000, 0x002e0400, 0x009d552b, 0x00ba5014, 0x00c54d08, 0x00c15008, 0x00b75513, 0x00a55723, 0x00581d00, 0x00240000, 0x00482014, 0x007c482e, 0x00632808, 0x004a1300, 0x0088461b, 0x00b05315, 0x00b85618, 0x00a44e23, 0x00622407, 0x001c0000, 0x00230500, 0x00874720, 0x00ad5622, 0x00b65319, 0x00b75418, 0x00af5522, 0x009e4e1e, 0x00944c1c, 0x0085481c, 0x006c3c18, 0x00452309, 0x000e0000, 0x00070000, 0x00070000, 0x00040000, 0x00030000, 0x00050000, 0x000b0000, 0x000e0000, 0x00110000, 0x00180000, 0x00240800, 0x00311002, 0x003b1704, 0x00411904, 0x004b1e04, 0x00542508, 0x0056290d, 0x00572b13, 0x00532b18, 0x004e2a18, 0x0044230c, 0x003a1d08, 0x00291002, 0x001a0300, 0x00150000, 0x001d0000, 0x003c1000, 0x00642b04, 0x0090481c, 0x00aa5622, 0x00b7581d, 0x00b85312, 0x00bc540e, 0x00be540b, 0x00bc500b, 0x00c05410, 0x00be5210, 0x00be5210, 0x00be530d, 0x00be530c, 0x00bc5409, 0x00bc5408, 0x00bb5606, 0x00ba5707, 0x00b85706, 0x00b85706, 0x00b95807, 0x00ba5805, 0x00bc5605, 0x00be5705, 0x00c15704, 0x00ba5910, 0x00ac5c2b, 0x00592305, 0x00140200, 0x000e0000, 0x00401d01, 0x00874d1e, 0x00af601b, 0x00bc5f10, 0x00c45e14, 0x00bc5810, 0x00b85e1c, 0x00944c19, 0x003c1100, 0x00300500, 0x009b551c, 0x00b85f15, 0x00c35c08, 0x00c75805, 0x00c5540b, 0x00c0500c, 0x00c25b1a, 0x00903f0d, 0x003f1400, 0x00240600, 0x00502410, 0x00844526, 0x00ab5020, 0x00b44e14, 0x00b65014, 0x00b24d10, 0x00b8571b, 0x00b14f10, 0x00ba540e, 0x00b14c08, 0x00b35518, 0x00ad5723, 0x009b5023, 0x007e3a0f, 0x00702b02, 0x008c3e12, 0x00ae5018, 0x00aa531d, 0x007f4823, 0x00341800, 0x00090000, 0x00070000, 0x00120000, 0x00471a04, 0x00a35625, 0x00b85310, 0x00c55309, 0x00c85508, 0x00c0580b, 0x00b25c1e, 0x00703614, 0x002b0900, 0x000a0000, 0x00100f0d, 0x005d5c60, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b0aba6, 0x00443d39, 0x000c0000, 0x00150000, 0x0054280c, 0x0093481f, 0x00b85620, 0x00c85814, 0x00c65706, 0x00c66109, 0x00c26607, 0x00c26a06, 0x00c46d06, 0x00c46700, 0x00be6200, 0x00c06912, 0x00b86b25, 0x008b4c1c, 0x00542407, 0x00200000, 0x001a0000, 0x00280200, 0x00522003, 0x00854618, 0x00a85d20, 0x00b86118, 0x00bc5d0d, 0x00c35e0e, 0x00be5a10, 0x00bc611c, 0x00ab5c25, 0x00854a23, 0x00623922, 0x00361e18, 0x00080000, 0x00000003, 0x00000001, 0x00040000, 0x00040000, 0x00000000, 0x00000001, 0x00000002, 0x00000002, 0x00000103, 0x00040301, 0x00080000, 0x002a1103, 0x007a4728, 0x009f592e, 0x00b05e29, 0x00b1541a, 0x00b65114, 0x00b3541c, 0x00a0562d, 0x004a1300, 0x00240000, 0x00653a27, 0x00985a34, 0x00753a13, 0x002e0c00, 0x00240200, 0x00602400, 0x00ab5924, 0x00b85010, 0x00bf4f0b, 0x00bd5010, 0x00bd5010, 0x00be510c, 0x00ad5012, 0x00804015, 0x002f0800, 0x000e0000, 0x00090100, 0x00070000, 0x00060000, 0x00000104, 0x00000005, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00020000, 0x00040000, 0x00080100, 0x00060000, 0x00050000, 0x000c0000, 0x00180200, 0x00674429, 0x006e4028, 0x00400f00, 0x002f0300, 0x00682d11, 0x00ad541d, 0x00bc540f, 0x00b9530a, 0x00ba5109, 0x00c44d0a, 0x00bc4e12, 0x00aa5a28, 0x005f2000, 0x00370000, 0x00814020, 0x00b0521b, 0x00bc500e, 0x00c04f0f, 0x00bc5213, 0x00b05619, 0x00884417, 0x00401b08, 0x000e0000, 0x00060000, 0x00110000, 0x003c0d00, 0x00a35728, 0x00b85013, 0x00c34e09, 0x00c0500b, 0x00b65415, 0x00a45524, 0x00551c00, 0x00220000, 0x00462318, 0x006b3d28, 0x00521c00, 0x00501400, 0x00984f23, 0x00b15114, 0x00b85618, 0x00a44e21, 0x0064270a, 0x00140000, 0x00160000, 0x00793c17, 0x00a8521c, 0x00b75110, 0x00bd500a, 0x00bc500e, 0x00ba5110, 0x00b65212, 0x00b05920, 0x009e5a2e, 0x006a3c1c, 0x00180000, 0x000a0000, 0x00080000, 0x00080000, 0x00110000, 0x00200300, 0x00350f00, 0x00491c06, 0x005a240d, 0x00662c11, 0x00703215, 0x00773515, 0x0087421c, 0x008e4319, 0x00964617, 0x009d4a18, 0x00a04d1c, 0x00a14f20, 0x009c4f26, 0x009a4d24, 0x00944918, 0x008b4313, 0x0079370f, 0x00682c0c, 0x00542208, 0x00391000, 0x00280400, 0x002c0600, 0x004e1c0a, 0x00834327, 0x00ac582c, 0x00b7541c, 0x00bd520e, 0x00c0500b, 0x00bf4f10, 0x00c05014, 0x00c25015, 0x00c25014, 0x00c25010, 0x00c2500d, 0x00c2510b, 0x00c2530a, 0x00c1530a, 0x00c05509, 0x00c0550b, 0x00be560b, 0x00bd560c, 0x00bd560c, 0x00be550c, 0x00c0560d, 0x00c2560c, 0x00bb5a19, 0x00a95f31, 0x004c1c00, 0x00130000, 0x00130000, 0x0064310f, 0x009c531d, 0x00b25c15, 0x00bc5c10, 0x00c35c13, 0x00b85410, 0x00b75e1d, 0x008c4815, 0x00300500, 0x002f0700, 0x008a4915, 0x00b4601b, 0x00c35d11, 0x00c8590a, 0x00c75807, 0x00c45406, 0x00c6550c, 0x00b04f14, 0x00632708, 0x003a0a00, 0x006c3214, 0x009f562c, 0x00af4c14, 0x00b84b0e, 0x00bd5016, 0x00b84f17, 0x00b45119, 0x00b45216, 0x00b64f0c, 0x00b45214, 0x00a85425, 0x00904a26, 0x00652e14, 0x004a1500, 0x00652303, 0x0098451b, 0x00b9531a, 0x00b14f17, 0x00934f24, 0x00562c10, 0x000c0000, 0x00050000, 0x000c0000, 0x002e0800, 0x0099532b, 0x00b65619, 0x00c15209, 0x00c85608, 0x00c15b12, 0x00ab5a22, 0x005b2b0e, 0x001b0100, 0x00090000, 0x00221f1c, 0x007c797f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b6b0ac, 0x00645c57, 0x000a0100, 0x00130000, 0x004c1d00, 0x00944d1f, 0x00b75821, 0x00c25414, 0x00c85508, 0x00c45500, 0x00c86506, 0x00c46a06, 0x00c36b07, 0x00c16907, 0x00c46909, 0x00c16c14, 0x00ad641c, 0x0080450e, 0x00451900, 0x001c0000, 0x001c0000, 0x003c1604, 0x0064300f, 0x00945120, 0x00b86727, 0x00bc6118, 0x00bc5d0f, 0x00c46518, 0x00bb6018, 0x00ae591b, 0x00924814, 0x0070340c, 0x004b1d05, 0x00250600, 0x000d0000, 0x00060001, 0x00010407, 0x00000303, 0x00040000, 0x00070000, 0x00010103, 0x00000003, 0x00000003, 0x00000001, 0x00000001, 0x00020000, 0x00080000, 0x002f0f00, 0x00894b24, 0x00ac5521, 0x00c05a1c, 0x00bc4c0a, 0x00c55710, 0x00b35114, 0x009c5126, 0x00440e00, 0x00200000, 0x00613827, 0x00955939, 0x006b3111, 0x00250600, 0x00200000, 0x00592201, 0x00a85826, 0x00b65010, 0x00bf4f08, 0x00bd5110, 0x00bc500f, 0x00c1530c, 0x00b04f11, 0x00874318, 0x00360a00, 0x00130000, 0x002c1d18, 0x00211005, 0x000c0000, 0x00010002, 0x00000004, 0x00020000, 0x00060000, 0x00060000, 0x00040000, 0x00040000, 0x00070100, 0x00080000, 0x00050000, 0x00050000, 0x000d0000, 0x00260a00, 0x00724828, 0x008c5432, 0x005e2203, 0x003b0700, 0x006d2f10, 0x00af541b, 0x00bb530c, 0x00b7540c, 0x00ba520c, 0x00c34e0c, 0x00bc5014, 0x00a85a29, 0x00551800, 0x003e0500, 0x00874423, 0x00b1531b, 0x00bc4f0c, 0x00c05010, 0x00b95012, 0x00b0581e, 0x007a3c11, 0x002d0f00, 0x00080000, 0x00060000, 0x00150000, 0x00511f00, 0x00a65827, 0x00b65011, 0x00c0500a, 0x00bf500c, 0x00b45015, 0x00a05425, 0x00561c00, 0x00210000, 0x0043241a, 0x00552f1d, 0x00441200, 0x005c1c00, 0x00a35424, 0x00b35117, 0x00b85419, 0x00a55123, 0x0064280b, 0x00180000, 0x001b0000, 0x006d3413, 0x00a2511b, 0x00b55410, 0x00bf5008, 0x00c04c03, 0x00c75008, 0x00c9560f, 0x00bc5718, 0x00a45624, 0x006f3917, 0x001c0000, 0x00160400, 0x0024110b, 0x00372017, 0x00502f1f, 0x005f321c, 0x00703a1e, 0x00844421, 0x00964c27, 0x00a4542a, 0x00aa572c, 0x00ac5629, 0x00ac5423, 0x00b0521c, 0x00b45015, 0x00b65013, 0x00b74f10, 0x00b65014, 0x00b45018, 0x00b35117, 0x00b45212, 0x00b85818, 0x00b65821, 0x00ab5424, 0x00984e25, 0x007b3f1d, 0x0058280f, 0x00431804, 0x00380900, 0x00501703, 0x00813714, 0x00a8501e, 0x00b75414, 0x00bd5410, 0x00c05314, 0x00bd4d10, 0x00bf4f11, 0x00bf4f10, 0x00c04f0d, 0x00c0500c, 0x00c1500a, 0x00c1500a, 0x00c1510b, 0x00c0520b, 0x00bd520b, 0x00bc540c, 0x00bd550f, 0x00bd550f, 0x00bd540e, 0x00bd540e, 0x00bf540c, 0x00b65618, 0x00a46032, 0x00421500, 0x00130000, 0x00200400, 0x00814016, 0x00b05a1e, 0x00b85c14, 0x00b9570c, 0x00c05811, 0x00b85411, 0x00b56020, 0x00834210, 0x00240000, 0x002c0600, 0x007f4214, 0x00b26121, 0x00c05d15, 0x00c45a09, 0x00c55803, 0x00c85904, 0x00c65404, 0x00c05a19, 0x0081380f, 0x00480c00, 0x00602301, 0x009a5127, 0x00ac4e16, 0x00b74c0d, 0x00ba4d10, 0x00b84c12, 0x00b04d14, 0x00b3541c, 0x00af541e, 0x00a65424, 0x00803d1a, 0x00521d04, 0x00300700, 0x00401000, 0x007d3717, 0x00aa5223, 0x00bb5014, 0x00b44f11, 0x00a15322, 0x00703c1a, 0x00190200, 0x00080000, 0x00090001, 0x001c0000, 0x00854625, 0x00b15720, 0x00c1530a, 0x00c85708, 0x00c15c18, 0x009a4e1b, 0x00461d08, 0x00100000, 0x00050000, 0x00363330, 0x009a969c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b9b5b2, 0x0079726e, 0x0018100b, 0x000c0100, 0x00361602, 0x008d4515, 0x00b85515, 0x00c0530e, 0x00c55308, 0x00cc5c08, 0x00cc6304, 0x00cc6a06, 0x00c76902, 0x00c86806, 0x00c3650a, 0x00bd6716, 0x00ab611d, 0x0076400c, 0x003a1400, 0x001d0200, 0x00250800, 0x00542201, 0x00844414, 0x00a95f1f, 0x00bb681c, 0x00bd6311, 0x00bf6211, 0x00b96219, 0x00a05414, 0x00844512, 0x006c3c16, 0x00401d06, 0x00180100, 0x000c0000, 0x00080000, 0x00030000, 0x00000100, 0x00000404, 0x00000201, 0x00000000, 0x00030000, 0x00000001, 0x00000004, 0x00000004, 0x00030304, 0x00000002, 0x00030000, 0x000e0000, 0x00371100, 0x0090481e, 0x00b8561a, 0x00c85410, 0x00c84d05, 0x00bc4b01, 0x00ad4c0c, 0x009d5227, 0x00481100, 0x00240000, 0x005c3020, 0x008c5033, 0x00662f14, 0x001c0000, 0x00180000, 0x00511e02, 0x00a25628, 0x00b65212, 0x00be5007, 0x00bc510c, 0x00bb510f, 0x00b94d0c, 0x00b1531b, 0x008c4924, 0x00380a00, 0x00180000, 0x00482d24, 0x004d2f20, 0x002c1105, 0x00100101, 0x00060002, 0x00060000, 0x00080000, 0x00060000, 0x00030001, 0x00000005, 0x00000005, 0x00010002, 0x00040004, 0x00000004, 0x000a0000, 0x003d1e05, 0x007c4c28, 0x009d5b33, 0x00742e09, 0x00490e00, 0x0076330e, 0x00b45318, 0x00bb520a, 0x00b4540c, 0x00b7520c, 0x00c04e0f, 0x00ba5017, 0x00a35626, 0x004c0f00, 0x00481000, 0x008c4926, 0x00b15319, 0x00bb4e09, 0x00c25111, 0x00b74f12, 0x00a9541c, 0x006a3007, 0x001d0300, 0x00060000, 0x00060000, 0x001a0300, 0x00693210, 0x00a85824, 0x00b45111, 0x00bd500c, 0x00bc500e, 0x00b25018, 0x00a15429, 0x00561e03, 0x001d0000, 0x00381e14, 0x00401f10, 0x00380b00, 0x00692802, 0x00ab5626, 0x00b55218, 0x00b55217, 0x00a55324, 0x00632808, 0x00180000, 0x00160000, 0x00592402, 0x0099501c, 0x00ad5414, 0x00ba540e, 0x00bc4c05, 0x00c14d06, 0x00c54d08, 0x00bd5314, 0x00a85526, 0x00713817, 0x00210000, 0x002a1304, 0x00462a1a, 0x0063412d, 0x00784e34, 0x00875333, 0x00985730, 0x00a45728, 0x00ab5423, 0x00af531f, 0x00ae521e, 0x00af511c, 0x00b2541d, 0x00b5541c, 0x00b95414, 0x00bb5210, 0x00bb510f, 0x00ba500e, 0x00ba5113, 0x00bb5212, 0x00bb510d, 0x00ba500c, 0x00b84e12, 0x00b34e13, 0x00b35218, 0x00b1581f, 0x00a1521c, 0x008c4416, 0x006b2805, 0x00541500, 0x005d1c00, 0x00833d12, 0x00a35218, 0x00b25614, 0x00bc540f, 0x00bc5008, 0x00bc540b, 0x00b9550b, 0x00bb550b, 0x00bc5409, 0x00bc5409, 0x00be540b, 0x00be530c, 0x00bc540d, 0x00ba520d, 0x00ba540e, 0x00ba5510, 0x00bb5610, 0x00bc560f, 0x00bc550c, 0x00bc550c, 0x00b45817, 0x009d5c2c, 0x00380c00, 0x00170000, 0x003f1b02, 0x00984918, 0x00be5a18, 0x00bd5910, 0x00bc560c, 0x00bf5710, 0x00b85815, 0x00ac5a1c, 0x00743707, 0x001e0000, 0x00290500, 0x007e451c, 0x00ae6126, 0x00b95d16, 0x00c25b09, 0x00c45802, 0x00c45800, 0x00c25805, 0x00bf5e17, 0x009a4814, 0x005f1a00, 0x00501400, 0x00874828, 0x00ac5828, 0x00b25214, 0x00b64e0b, 0x00b94d0c, 0x00b85014, 0x00a94e1c, 0x008c4926, 0x00683418, 0x00411700, 0x00220000, 0x00280400, 0x00602d17, 0x009b4d24, 0x00b3521b, 0x00b84e0c, 0x00b4500a, 0x00a95418, 0x0084471a, 0x00341400, 0x000c0000, 0x00050005, 0x00100000, 0x00683015, 0x00ab5421, 0x00c1550d, 0x00c85708, 0x00bd5918, 0x0083380b, 0x00310d00, 0x000a0000, 0x00090400, 0x0053504d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9a96, 0x00312a24, 0x000c0000, 0x00240b00, 0x00713e1b, 0x00b1581b, 0x00c45408, 0x00c85708, 0x00c95a06, 0x00cc6006, 0x00c86404, 0x00c86502, 0x00cc6a08, 0x00c66509, 0x00bf6817, 0x00a55e1e, 0x00733b09, 0x003a1000, 0x00200000, 0x00341600, 0x005e340f, 0x009f5920, 0x00b46019, 0x00b86012, 0x00bd6410, 0x00b96314, 0x00ab5b14, 0x00904d14, 0x0069350a, 0x003b1800, 0x001a0400, 0x00080000, 0x00050002, 0x00020005, 0x00000004, 0x00000000, 0x00000100, 0x00000200, 0x00000100, 0x00050000, 0x00070000, 0x00030000, 0x00000001, 0x00020000, 0x00020000, 0x00020100, 0x00030000, 0x000b0000, 0x00320d00, 0x008c4012, 0x00c2591b, 0x00c84e09, 0x00c84a01, 0x00c55108, 0x00b75416, 0x00985026, 0x00390700, 0x001c0000, 0x00543021, 0x007c4832, 0x0050210e, 0x00130000, 0x00100000, 0x00481c04, 0x009c562c, 0x00b45214, 0x00be4e08, 0x00be5009, 0x00bc4f0a, 0x00bc500e, 0x00af5018, 0x00914c27, 0x00380800, 0x001b0000, 0x0046271b, 0x0076472f, 0x0064341d, 0x00290a00, 0x00180200, 0x000c0000, 0x00060001, 0x00040005, 0x00020008, 0x00000008, 0x00000007, 0x00000004, 0x00050408, 0x00000004, 0x000c0000, 0x00583014, 0x008d5026, 0x00a95c31, 0x007f3108, 0x00541500, 0x007e3811, 0x00b65619, 0x00ba5109, 0x00b5520a, 0x00b6510c, 0x00bf4e0f, 0x00b8501a, 0x009c5429, 0x00440a00, 0x00521500, 0x00954c26, 0x00b55217, 0x00bc4d09, 0x00c05211, 0x00b14e13, 0x009c4d1b, 0x005a2604, 0x00110000, 0x00040000, 0x000a0100, 0x00230700, 0x007c3e19, 0x00ac5622, 0x00b55111, 0x00bd520c, 0x00bc5010, 0x00b45119, 0x00a7562b, 0x00591f04, 0x00160000, 0x00291510, 0x002e1408, 0x00320800, 0x00742d05, 0x00b05523, 0x00b85216, 0x00b24f15, 0x00a35323, 0x00602608, 0x001c0000, 0x00140000, 0x004d1d00, 0x00945121, 0x00aa5214, 0x00b85410, 0x00bd500c, 0x00c34e0a, 0x00c84f0a, 0x00c35515, 0x00a55220, 0x006a310e, 0x001e0000, 0x002e190d, 0x003a2113, 0x00422514, 0x004e2b15, 0x005c3014, 0x006e3514, 0x0079370f, 0x0084380d, 0x008d3e10, 0x00944518, 0x00984819, 0x00a04f22, 0x00a55123, 0x00ad5420, 0x00b2541c, 0x00b55418, 0x00b65114, 0x00b65212, 0x00b85211, 0x00b9500e, 0x00ba4e0d, 0x00bd5317, 0x00bd5315, 0x00b84e0c, 0x00b85009, 0x00b8530d, 0x00b05213, 0x00a4511f, 0x00883c13, 0x00652200, 0x00672400, 0x008c410c, 0x00a85314, 0x00b8530f, 0x00bd540c, 0x00b75308, 0x00b45408, 0x00b85409, 0x00ba540a, 0x00bb540b, 0x00bb540b, 0x00bc530c, 0x00bb530e, 0x00bb5310, 0x00ba5310, 0x00b85410, 0x00b8540e, 0x00b8540e, 0x00b9550d, 0x00bc550c, 0x00b35a1b, 0x0094582c, 0x002d0400, 0x001f0000, 0x00633414, 0x00a64f19, 0x00bd5510, 0x00bc550c, 0x00be580e, 0x00be5812, 0x00b55919, 0x009c521a, 0x00602c02, 0x001b0000, 0x00270600, 0x00834820, 0x00ab5c22, 0x00ba5c14, 0x00c35c0c, 0x00c55c05, 0x00c05600, 0x00c15a09, 0x00bf5c14, 0x00af551c, 0x007a2e03, 0x00490f00, 0x006e3419, 0x009d5124, 0x00ac5119, 0x00b45214, 0x00b14f11, 0x00a94e1c, 0x008b401d, 0x00562915, 0x00240500, 0x00180000, 0x00200000, 0x00461c02, 0x00854928, 0x00a95223, 0x00b24d12, 0x00b9500d, 0x00b7500c, 0x00ae5516, 0x00924d1e, 0x004c230c, 0x000f0000, 0x00030000, 0x000d0000, 0x00522007, 0x00a35324, 0x00c05811, 0x00c5570e, 0x00b0571d, 0x00682904, 0x001e0400, 0x00050000, 0x0018130e, 0x00706c69, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a8afae, 0x00515550, 0x00060000, 0x00200600, 0x00602600, 0x00ad5c20, 0x00bd5911, 0x00c55808, 0x00c25600, 0x00c96005, 0x00c96406, 0x00cc6808, 0x00cb6406, 0x00c8640c, 0x00c36617, 0x00a75c1e, 0x0067390d, 0x002e1000, 0x00280800, 0x004b2100, 0x00824810, 0x00b26623, 0x00be6010, 0x00c2600c, 0x00bd6011, 0x00b3621a, 0x009e5b21, 0x00733f14, 0x003e1b00, 0x00190400, 0x00080000, 0x00080300, 0x00050100, 0x00030000, 0x00040000, 0x00040000, 0x00020000, 0x00030000, 0x00060000, 0x000c0000, 0x00140400, 0x00140400, 0x000e0200, 0x00090000, 0x00080000, 0x00070000, 0x00050000, 0x00060200, 0x00030000, 0x00280c00, 0x00873b0c, 0x00bf5616, 0x00c95513, 0x00c54c08, 0x00c44c09, 0x00b75016, 0x00904c27, 0x00381000, 0x00130000, 0x00332014, 0x00583829, 0x00391b12, 0x000a0000, 0x00080000, 0x003b1804, 0x008a4c25, 0x00b4501c, 0x00c24c0e, 0x00c14d0b, 0x00c1500b, 0x00c0500a, 0x00b35013, 0x00985025, 0x00400d00, 0x00170000, 0x003e1c10, 0x00803f1b, 0x009c5429, 0x006e3416, 0x00360d00, 0x00100000, 0x00040004, 0x0000020c, 0x00000009, 0x00020000, 0x00040000, 0x00060000, 0x00030000, 0x00030000, 0x00130000, 0x00713515, 0x00a35225, 0x00ac5326, 0x00853209, 0x005d1d00, 0x007c3914, 0x00b35419, 0x00b85008, 0x00b85308, 0x00bb520c, 0x00bd4b0c, 0x00b4501d, 0x008a4925, 0x00380200, 0x00682101, 0x009c471c, 0x00be5418, 0x00bb4b07, 0x00b9500d, 0x00b0541c, 0x0086441c, 0x003c1400, 0x000f0000, 0x00030001, 0x000c0000, 0x00310c00, 0x009c502a, 0x00b04f18, 0x00b8500e, 0x00bd500a, 0x00be4f0e, 0x00b84f15, 0x00ae5627, 0x005d1f02, 0x00180000, 0x000b0000, 0x00130000, 0x00370e00, 0x00843a0c, 0x00b35218, 0x00ba5113, 0x00b45017, 0x00a45328, 0x005a2308, 0x00140000, 0x00100000, 0x003b1200, 0x00904d24, 0x00b25518, 0x00bc500b, 0x00bc4f0e, 0x00c04e0c, 0x00c64c08, 0x00c55615, 0x00a5511b, 0x00632c05, 0x00140000, 0x00050000, 0x00070000, 0x00060000, 0x000c0000, 0x00110000, 0x00190000, 0x00230000, 0x00300800, 0x003b1000, 0x00451b02, 0x0050240c, 0x0062321c, 0x006c3720, 0x007c3c22, 0x008a4323, 0x00964820, 0x00a24f1c, 0x00aa5419, 0x00b05518, 0x00b4511b, 0x00b6501c, 0x00b6501b, 0x00b85117, 0x00ba5110, 0x00bb5008, 0x00ba4e04, 0x00b74e08, 0x00b85518, 0x00ad531e, 0x009e4a1c, 0x0086350a, 0x007e2a00, 0x009b410c, 0x00b85618, 0x00b7500d, 0x00b8540e, 0x00b6510c, 0x00b8500b, 0x00bc520e, 0x00be5210, 0x00bb510f, 0x00bc5010, 0x00be5211, 0x00bd5110, 0x00bc5210, 0x00bc540f, 0x00b8540e, 0x00b6550e, 0x00b85410, 0x00bb5210, 0x00ae5721, 0x00804d2c, 0x00250100, 0x00350700, 0x0085451c, 0x00b0581e, 0x00bc5411, 0x00bd540c, 0x00bd560d, 0x00bb5610, 0x00b35c20, 0x008a4c20, 0x003f1500, 0x00180000, 0x00280800, 0x008c4c1f, 0x00b25a1b, 0x00c05c12, 0x00c15607, 0x00c45b0a, 0x00c25808, 0x00bd5308, 0x00c45c17, 0x00b8561c, 0x008d3b0c, 0x004c1200, 0x00592106, 0x009a4f25, 0x00ae5728, 0x00a64c1d, 0x009b4922, 0x00783b1e, 0x003c1200, 0x00150000, 0x00100000, 0x001c0000, 0x00380b00, 0x007f4317, 0x00a25621, 0x00a94c14, 0x00b65015, 0x00b84d13, 0x00b44c12, 0x00b0521c, 0x009d5028, 0x006a3720, 0x001a0000, 0x000c0000, 0x000e0000, 0x00380a00, 0x00a4582d, 0x00ba5512, 0x00be5a17, 0x00944f21, 0x00401700, 0x000e0000, 0x00010103, 0x00383230, 0x009a9490, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00757a78, 0x00181811, 0x00100000, 0x00401800, 0x00a0501b, 0x00be5914, 0x00c35909, 0x00c05400, 0x00cc6407, 0x00cb6606, 0x00c56302, 0x00c8680a, 0x00c86710, 0x00c16418, 0x00ab5b1c, 0x00763806, 0x00320c00, 0x00301000, 0x00603709, 0x0090571d, 0x00b4641c, 0x00bf610f, 0x00c76410, 0x00b75808, 0x00b4631f, 0x0092511c, 0x00532501, 0x00260900, 0x000a0000, 0x00030000, 0x00030102, 0x00020000, 0x00060000, 0x000c0000, 0x00120000, 0x00120000, 0x00170200, 0x00280d00, 0x00361400, 0x00401800, 0x00491f05, 0x004a210a, 0x00421d0a, 0x00341200, 0x00240600, 0x00190000, 0x000e0000, 0x000a0000, 0x00040000, 0x00281000, 0x00833a0c, 0x00bc5617, 0x00c1510d, 0x00c44d0a, 0x00c54c0c, 0x00b9521c, 0x0093502a, 0x00351000, 0x000c0000, 0x00180e03, 0x002b1810, 0x001b0806, 0x00050004, 0x00060000, 0x002e1200, 0x0079401f, 0x00b65321, 0x00c04a0f, 0x00bf4b0a, 0x00be4c08, 0x00c05009, 0x00b65212, 0x009f5326, 0x00441000, 0x00160000, 0x00381609, 0x00863d13, 0x00ac541f, 0x009c5024, 0x006c3114, 0x002e0c00, 0x00140403, 0x00000004, 0x00000004, 0x00050100, 0x00050000, 0x00040000, 0x00040000, 0x00080000, 0x00230700, 0x00843f18, 0x00ac5222, 0x00b15528, 0x00833007, 0x005c1d00, 0x007b3815, 0x00b3561c, 0x00b9500a, 0x00b95209, 0x00bc510c, 0x00be4b10, 0x00b34f20, 0x00763a1b, 0x00320000, 0x007b300d, 0x00a84b1c, 0x00bd5014, 0x00bc4c0a, 0x00b8500e, 0x00ac5821, 0x00703615, 0x002a0800, 0x00090000, 0x00030000, 0x00130000, 0x00421400, 0x00a65327, 0x00bc5319, 0x00bc500e, 0x00bf500a, 0x00be4f0c, 0x00b84f13, 0x00b15523, 0x00652303, 0x001c0300, 0x00080002, 0x00100000, 0x003d1500, 0x008e4110, 0x00b55314, 0x00bc4f10, 0x00b65018, 0x00a4542a, 0x00542007, 0x00100000, 0x000b0000, 0x00381000, 0x008e4b25, 0x00b45317, 0x00bf4f09, 0x00bc4f0e, 0x00bf4e0e, 0x00ca520c, 0x00c15413, 0x00a04e17, 0x005c2a01, 0x00120000, 0x00040000, 0x00020004, 0x0003010a, 0x00000003, 0x00020001, 0x00060000, 0x000a0000, 0x00100000, 0x00100000, 0x000e0000, 0x00140300, 0x00110000, 0x001b0000, 0x002c0800, 0x003f1101, 0x00531d06, 0x00682c0c, 0x007b3b12, 0x00884318, 0x0094471c, 0x00a04c22, 0x00a85426, 0x00ab5322, 0x00ae5018, 0x00b44f11, 0x00bc510d, 0x00c0530e, 0x00b64d0d, 0x00b35014, 0x00b15521, 0x00a84e1c, 0x00953c09, 0x00963a04, 0x00ac480d, 0x00b85314, 0x00b55110, 0x00b85410, 0x00be5413, 0x00bf5311, 0x00be5010, 0x00bc4f0e, 0x00bc5010, 0x00bc5210, 0x00bb5110, 0x00bc5210, 0x00bc520e, 0x00bb530c, 0x00ba540e, 0x00b9530d, 0x00ba5310, 0x00ab5722, 0x006b3c20, 0x00230000, 0x00592000, 0x00974c1b, 0x00b35618, 0x00bc5510, 0x00c0570f, 0x00bb540d, 0x00b85814, 0x00aa5c23, 0x00784421, 0x002b0b00, 0x00110000, 0x00290800, 0x00975221, 0x00b75a18, 0x00c05910, 0x00bf5507, 0x00c15a09, 0x00c1590b, 0x00c25409, 0x00c55814, 0x00be5517, 0x009e4614, 0x00571c00, 0x00501c00, 0x00894724, 0x00944c28, 0x008a4425, 0x00632a14, 0x00230000, 0x00110000, 0x000a0000, 0x00100000, 0x002a0400, 0x00743c1a, 0x00984e18, 0x00ab5114, 0x00b45015, 0x00b34a10, 0x00b74b14, 0x00b74e18, 0x00b24f1c, 0x00a55226, 0x007f4227, 0x002d0800, 0x000f0000, 0x000b0000, 0x00240000, 0x00904e28, 0x00b6591d, 0x00b1581f, 0x006d3614, 0x002c1001, 0x00040000, 0x0004060a, 0x00595552, 0x00b8b2ad, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009e9da1, 0x00403c38, 0x000c0000, 0x002e0c00, 0x007f441a, 0x00b55c20, 0x00be550c, 0x00c45905, 0x00c25900, 0x00cc6503, 0x00cc6804, 0x00cb6b08, 0x00bf6408, 0x00bc6618, 0x00ac6224, 0x0073380c, 0x003e0b00, 0x00440c00, 0x007d410c, 0x00a76226, 0x00b56521, 0x00c16115, 0x00c46114, 0x00b7621c, 0x00a35e20, 0x00824d1f, 0x00401c00, 0x00140000, 0x000d0400, 0x00040001, 0x00020000, 0x00060000, 0x000d0000, 0x00180000, 0x00280800, 0x003a1000, 0x00491800, 0x00612b05, 0x007e4015, 0x00964c1b, 0x00a45320, 0x00b05d2b, 0x00b46330, 0x00aa5b2c, 0x00904719, 0x00703007, 0x00552000, 0x003a1400, 0x00240b00, 0x000e0100, 0x00200500, 0x00723002, 0x00b85a1a, 0x00c05209, 0x00c75107, 0x00c24b08, 0x00b8521b, 0x0098532c, 0x00381000, 0x00100000, 0x00060000, 0x000a0000, 0x00070000, 0x00040002, 0x00060000, 0x001e0800, 0x00602e0f, 0x00b45524, 0x00bf4c10, 0x00be4d0d, 0x00be4f0c, 0x00bc500b, 0x00b45214, 0x00a4582c, 0x004c1900, 0x00180000, 0x002d0e02, 0x00833b11, 0x00b0561e, 0x00ac5520, 0x00a05327, 0x00753c1d, 0x002e0800, 0x00120000, 0x00050000, 0x00020003, 0x00000001, 0x00000001, 0x00020000, 0x00080000, 0x00341700, 0x008e481d, 0x00ac5320, 0x00af5728, 0x007a2c04, 0x00531600, 0x00753414, 0x00b2541d, 0x00ba500e, 0x00b8500d, 0x00bb5110, 0x00be4c15, 0x00b24f24, 0x0062270b, 0x00300000, 0x008d411b, 0x00ac501e, 0x00b94f11, 0x00bc4f0e, 0x00b35012, 0x00a15120, 0x005c270b, 0x00190000, 0x00080000, 0x00050000, 0x00200400, 0x0060290c, 0x00ac5424, 0x00bc5317, 0x00bc4f0e, 0x00bf500c, 0x00bd4e0c, 0x00b85011, 0x00b45420, 0x00712c09, 0x00230800, 0x00080000, 0x000f0000, 0x00471c03, 0x009b4c1c, 0x00b85416, 0x00bc4e10, 0x00b65018, 0x00a25428, 0x00501d01, 0x00100000, 0x000c0000, 0x00370e00, 0x008f4a24, 0x00b55217, 0x00bf4f09, 0x00bd500f, 0x00bf500d, 0x00ca540f, 0x00c05414, 0x009a4c1b, 0x00542200, 0x00140000, 0x00100200, 0x00080000, 0x00070005, 0x00000005, 0x00000005, 0x00040004, 0x00060000, 0x00060000, 0x00050000, 0x00020000, 0x00000000, 0x00010200, 0x00020000, 0x00080000, 0x000c0000, 0x00110000, 0x00180000, 0x00200000, 0x002c0600, 0x00461900, 0x005e2c0b, 0x00784021, 0x00894a29, 0x00974b26, 0x00a04b1e, 0x00ae4c18, 0x00b44e14, 0x00ba5215, 0x00b44f11, 0x00b45417, 0x00b5581c, 0x00b05317, 0x00a9490c, 0x00ae4809, 0x00b7500f, 0x00b45012, 0x00b45012, 0x00b64f0c, 0x00b84e0a, 0x00bd4f08, 0x00c0520c, 0x00be530f, 0x00ba5310, 0x00b55410, 0x00b85410, 0x00bc520e, 0x00c0500c, 0x00c04f0a, 0x00bd5109, 0x00b7540a, 0x00a85a1c, 0x005d2c0b, 0x002b0000, 0x007c3c11, 0x00a7531c, 0x00b85616, 0x00bc540d, 0x00be550f, 0x00b85410, 0x00b35818, 0x009c5422, 0x005c3113, 0x00180000, 0x000f0000, 0x002e0c00, 0x00a35b28, 0x00b85916, 0x00bc590f, 0x00bc5608, 0x00bf5907, 0x00c45b08, 0x00c55708, 0x00c5560a, 0x00c2550f, 0x00b0541a, 0x006b2e04, 0x003c0d00, 0x006a3a1d, 0x006c3e26, 0x003c1606, 0x001d0200, 0x000a0000, 0x00080100, 0x000c0000, 0x001e0300, 0x005c2a16, 0x00914c27, 0x00a45118, 0x00ad4e0e, 0x00b75014, 0x00b84f15, 0x00b44812, 0x00b84d16, 0x00b14b10, 0x00ab501d, 0x00924d28, 0x00461a02, 0x000c0000, 0x00060000, 0x001a0000, 0x007c4425, 0x00a55724, 0x009f5422, 0x004c2004, 0x00140000, 0x00020000, 0x001f2125, 0x007e7b78, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x001f1f20, 0x006c6a6e, 0x00160b08, 0x001c0300, 0x00572500, 0x00a55c26, 0x00b55314, 0x00c85a0f, 0x00c55a01, 0x00c96101, 0x00c66200, 0x00ca6804, 0x00c86b08, 0x00bb660f, 0x00ac641e, 0x007e420c, 0x003e1000, 0x00491800, 0x0089440b, 0x00b1601c, 0x00bf661c, 0x00c46619, 0x00bc580a, 0x00b86018, 0x00a4642c, 0x00784b20, 0x002c0c00, 0x00100000, 0x00080000, 0x00040000, 0x000c0400, 0x000e0000, 0x001c0200, 0x00351100, 0x00542604, 0x00753d14, 0x00965627, 0x00ac622c, 0x00af5e24, 0x00af5719, 0x00bc5b1c, 0x00bc5716, 0x00bc5513, 0x00bb5613, 0x00bc5814, 0x00b95a18, 0x00b25c20, 0x00a95d28, 0x008b4d20, 0x006d3e1c, 0x00422410, 0x00300c00, 0x00672500, 0x00b65d1e, 0x00c0540a, 0x00c45104, 0x00c04c09, 0x00b65019, 0x009e562c, 0x003c1200, 0x00140000, 0x00050000, 0x00030000, 0x00030004, 0x00030002, 0x00060000, 0x00130100, 0x00481c01, 0x00a85122, 0x00bc4f14, 0x00bc5011, 0x00be5210, 0x00ba4f0b, 0x00b35114, 0x00a85c2d, 0x005a2408, 0x001e0300, 0x00270500, 0x007d370f, 0x00b0551c, 0x00b35117, 0x00b1541c, 0x00a35324, 0x00793a18, 0x00300800, 0x00170100, 0x00040000, 0x00000004, 0x00000305, 0x00030000, 0x000a0000, 0x00482708, 0x00944c1c, 0x00ad541f, 0x00ac5728, 0x00752903, 0x00460c00, 0x006b2c0d, 0x00ad531c, 0x00ba5110, 0x00b7500d, 0x00b95012, 0x00be4c19, 0x00b05027, 0x00501600, 0x003a0600, 0x00954820, 0x00af511c, 0x00b84e12, 0x00bc5314, 0x00b2541a, 0x008e4318, 0x00491c04, 0x00100000, 0x00060000, 0x000a0000, 0x002f0a00, 0x0081401c, 0x00af531f, 0x00b94c10, 0x00bd5010, 0x00be4f0e, 0x00bc4d0b, 0x00ba5010, 0x00b4541c, 0x007f3610, 0x002e0f03, 0x000c0000, 0x00130000, 0x004e2308, 0x00a25222, 0x00b95317, 0x00bd4d10, 0x00b65018, 0x00a05428, 0x004a1c00, 0x00100000, 0x000c0000, 0x003b0e00, 0x00914823, 0x00b55217, 0x00c0500c, 0x00bc500f, 0x00bd500d, 0x00c7520d, 0x00bf5618, 0x0094481d, 0x004d1a00, 0x002a0800, 0x00382011, 0x001c0100, 0x000d0000, 0x00020004, 0x00000005, 0x00040004, 0x000a0203, 0x00080000, 0x00080000, 0x00090400, 0x00000000, 0x00000000, 0x00000000, 0x00030000, 0x00050000, 0x00080000, 0x00080000, 0x00080003, 0x000f0000, 0x00140000, 0x00160000, 0x00180000, 0x002c0600, 0x004e1c08, 0x0070341c, 0x008b4422, 0x00984a21, 0x00a04e1f, 0x00a5531e, 0x00a7531e, 0x00a8531b, 0x00b0561b, 0x00b45415, 0x00b8500e, 0x00bc5210, 0x00bc5415, 0x00ba5214, 0x00ba520d, 0x00bb520a, 0x00be520a, 0x00be520a, 0x00ba500c, 0x00b6510d, 0x00b55411, 0x00b55410, 0x00bc520e, 0x00bf500c, 0x00c05009, 0x00bd5109, 0x00b55509, 0x00a75918, 0x00582400, 0x00430f00, 0x00944818, 0x00b1571a, 0x00be5714, 0x00bc5009, 0x00ba520c, 0x00b75614, 0x00ad581d, 0x0088491c, 0x003e1b05, 0x000e0000, 0x00110000, 0x003e1a03, 0x00aa5e29, 0x00b85813, 0x00b95810, 0x00bb580c, 0x00be5907, 0x00c25904, 0x00c65805, 0x00c55605, 0x00c45408, 0x00b85c19, 0x007a3b0d, 0x00360c00, 0x002c0c00, 0x00251002, 0x000c0000, 0x00070000, 0x00060504, 0x00040000, 0x00140000, 0x004c2215, 0x00905036, 0x009e4d22, 0x00b05318, 0x00b55110, 0x00b34b0e, 0x00b54c12, 0x00b44a14, 0x00b84e17, 0x00b1490c, 0x00ad4f15, 0x009e4f21, 0x00622f10, 0x000b0000, 0x00040000, 0x00140000, 0x00592d15, 0x00985932, 0x00753a13, 0x002c0b00, 0x000b0000, 0x00030102, 0x00444749, 0x00a4a0a0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00101011, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0096989e, 0x00363237, 0x000b0000, 0x00331000, 0x00844518, 0x00ad571b, 0x00c25918, 0x00c6570b, 0x00c75a00, 0x00cb6404, 0x00ca6705, 0x00c46805, 0x00bc6407, 0x00b86b19, 0x00884f12, 0x00471800, 0x00421600, 0x00804915, 0x00b7661c, 0x00be6009, 0x00c25f05, 0x00c4630c, 0x00b86012, 0x00ab6528, 0x00684019, 0x001e0700, 0x00140200, 0x000e0000, 0x000d0000, 0x001c0700, 0x00240300, 0x00481c00, 0x00794017, 0x00985423, 0x00ac6129, 0x00ae5d1f, 0x00b05918, 0x00b85b15, 0x00c05c14, 0x00c25c13, 0x00bc5713, 0x00bc5713, 0x00be5812, 0x00be580f, 0x00c0580c, 0x00bf580c, 0x00ba570f, 0x00b45814, 0x00b66024, 0x00a85e2c, 0x007e4725, 0x00501b00, 0x005f1900, 0x00b35a21, 0x00c25710, 0x00c55309, 0x00c2500f, 0x00b65018, 0x00a5592b, 0x00491800, 0x00130000, 0x00060000, 0x00020106, 0x00000007, 0x00030002, 0x00060000, 0x000d0000, 0x00351100, 0x00934519, 0x00b45018, 0x00b85013, 0x00ba5110, 0x00b8500e, 0x00b25215, 0x00ab5928, 0x00662c0b, 0x00240400, 0x00210000, 0x0078330c, 0x00ae531b, 0x00ba5214, 0x00bb5110, 0x00b14c10, 0x00a8511e, 0x00824320, 0x002c0400, 0x00100000, 0x00050002, 0x00010103, 0x00040000, 0x00100000, 0x00603815, 0x009a4e1b, 0x00b0561e, 0x00a95527, 0x00722c07, 0x00380400, 0x00612608, 0x00a9521e, 0x00ba5312, 0x00b4500c, 0x00b85014, 0x00ba4e1b, 0x00ac4f28, 0x00420700, 0x004d1800, 0x009b4c1e, 0x00b25118, 0x00b84e12, 0x00b85216, 0x00b05724, 0x00783711, 0x00330f00, 0x000b0000, 0x00040000, 0x00110100, 0x00400f00, 0x009c5024, 0x00b5531b, 0x00bb4d0d, 0x00bf4f11, 0x00bd4d0e, 0x00bc4d0b, 0x00ba500e, 0x00b55315, 0x008e4217, 0x003b1505, 0x00100000, 0x001a0100, 0x0054250a, 0x00a55324, 0x00b95115, 0x00bf4f11, 0x00b55017, 0x009c5325, 0x00451b00, 0x000e0000, 0x000c0000, 0x003c0e00, 0x00934922, 0x00b75118, 0x00bf4f0b, 0x00bc500f, 0x00bd520e, 0x00c7540e, 0x00be581c, 0x0089431e, 0x00471300, 0x0050220a, 0x00774c35, 0x004f2312, 0x00210000, 0x00080000, 0x00030000, 0x000f0400, 0x001c0c03, 0x001a0500, 0x001b0400, 0x001d0700, 0x00170000, 0x00190400, 0x00150000, 0x00120000, 0x00120000, 0x00100000, 0x000a0000, 0x00050004, 0x00060001, 0x000c0000, 0x000c0000, 0x000e0000, 0x000e0000, 0x000d0000, 0x00100000, 0x00200100, 0x00310d00, 0x00522914, 0x00724225, 0x008a5331, 0x0096552b, 0x00a45624, 0x00ae531a, 0x00b54c0c, 0x00bc4c0a, 0x00bc4b09, 0x00bc4c08, 0x00be5008, 0x00be5409, 0x00bb5209, 0x00b74f08, 0x00b7500d, 0x00ba5312, 0x00b85014, 0x00b95113, 0x00ba5110, 0x00b9530d, 0x00b8520b, 0x00b7530b, 0x00b4540b, 0x00ac5718, 0x005b1d00, 0x006a2c04, 0x00a44e18, 0x00b85412, 0x00bc540d, 0x00bc5009, 0x00b9530d, 0x00b45818, 0x00a45824, 0x006f3915, 0x00200800, 0x000b0000, 0x00160300, 0x00552b11, 0x00ab5c24, 0x00b7560f, 0x00b85710, 0x00bc5a10, 0x00bd5807, 0x00c05702, 0x00c55804, 0x00c75805, 0x00c75505, 0x00bc5a15, 0x007f3e0c, 0x003b1400, 0x00130000, 0x00060200, 0x00000005, 0x00000005, 0x00000100, 0x000d0000, 0x00431a0b, 0x008c4d34, 0x00a4512d, 0x00af5020, 0x00b04d10, 0x00b5500d, 0x00b64d0f, 0x00b44c12, 0x00b44c16, 0x00b54f16, 0x00b44c0e, 0x00b35013, 0x00a44d18, 0x0080431e, 0x00140200, 0x00040000, 0x000e0000, 0x00311204, 0x00865b40, 0x00431b00, 0x00140000, 0x00090100, 0x00101113, 0x00707476, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00181818, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0064666c, 0x000c0a0e, 0x000d0000, 0x00300c00, 0x007f3f10, 0x00b35b1c, 0x00c25a17, 0x00c35409, 0x00c95e05, 0x00cb6606, 0x00c8680a, 0x00be6509, 0x00bd6c18, 0x00a15d14, 0x00532000, 0x00481800, 0x007e4711, 0x00a86222, 0x00be6413, 0x00c8650a, 0x00c36004, 0x00ba610d, 0x00a96422, 0x00703f11, 0x001c0400, 0x000c0000, 0x000d0000, 0x00160000, 0x00260300, 0x004a1c00, 0x0082481d, 0x00aa6230, 0x00af5d21, 0x00b75d1a, 0x00b85a12, 0x00b9570c, 0x00bf590d, 0x00c1590b, 0x00c05508, 0x00bf5406, 0x00c0570e, 0x00bf580f, 0x00be580e, 0x00be580a, 0x00c05706, 0x00c05704, 0x00bf5807, 0x00be570c, 0x00b6510c, 0x00b3581d, 0x00924a20, 0x005e1d00, 0x00520d00, 0x00a75524, 0x00c35c1b, 0x00c4540d, 0x00c05010, 0x00b45014, 0x00a95824, 0x00592300, 0x00160000, 0x00040000, 0x00030309, 0x00000007, 0x00020001, 0x00050000, 0x00080000, 0x00270900, 0x0074320c, 0x00ac5320, 0x00b45013, 0x00b8500e, 0x00bc5311, 0x00b45214, 0x00ab5421, 0x0073320e, 0x002a0500, 0x001f0000, 0x00712f0c, 0x00a9521e, 0x00ba5214, 0x00bc4c08, 0x00c0510d, 0x00b55014, 0x00a05020, 0x007f4424, 0x00280400, 0x000e0000, 0x00080000, 0x000a0000, 0x001c0100, 0x0074421c, 0x00a24e1a, 0x00b4551d, 0x00a75324, 0x006d2a05, 0x00300000, 0x00582206, 0x00a4501c, 0x00b85414, 0x00b5500d, 0x00b85213, 0x00b54e19, 0x00a24a23, 0x00370000, 0x00662d14, 0x00a24d1c, 0x00b55315, 0x00b74f12, 0x00b35018, 0x00a65327, 0x00652c0d, 0x001c0100, 0x00060000, 0x00040000, 0x001c0500, 0x00571c00, 0x00a85323, 0x00b85419, 0x00be5113, 0x00be4e12, 0x00bd4d10, 0x00bb4e0b, 0x00ba500c, 0x00b55010, 0x009c4c1c, 0x00481c09, 0x00150000, 0x00220400, 0x0058280c, 0x00a85425, 0x00b84e14, 0x00c04f14, 0x00b44f16, 0x00985324, 0x00411800, 0x000a0000, 0x000b0000, 0x003e0e00, 0x00944822, 0x00b65018, 0x00bd4e0c, 0x00bc510d, 0x00bf540e, 0x00c6550f, 0x00bc581d, 0x00813d1c, 0x003f0900, 0x00672d0f, 0x009a5e3e, 0x00874729, 0x00602a14, 0x00200000, 0x00140000, 0x000d0000, 0x0028160b, 0x00614c3c, 0x00735947, 0x006a4731, 0x006e452c, 0x0062331b, 0x005c2c13, 0x0051240c, 0x00441c04, 0x00381402, 0x002c0e00, 0x00240600, 0x001f0200, 0x001d0100, 0x00160000, 0x00120000, 0x00140000, 0x00140000, 0x00100000, 0x00100000, 0x00100000, 0x00110000, 0x001a0000, 0x002a0900, 0x004c2104, 0x007b401e, 0x009c5328, 0x00ab5424, 0x00b6541e, 0x00bb5116, 0x00ba4e0d, 0x00b84c0a, 0x00b74d09, 0x00b7500c, 0x00b8500d, 0x00b85110, 0x00ba5113, 0x00ba5012, 0x00ba5012, 0x00b8510f, 0x00b6520f, 0x00b4530e, 0x00b4520d, 0x00b6520f, 0x00af5418, 0x00681f00, 0x00904818, 0x00b05418, 0x00ba520d, 0x00ba4f08, 0x00bc530b, 0x00ba5511, 0x00af571b, 0x00955124, 0x0053260a, 0x000f0000, 0x00090000, 0x001d0600, 0x006b3c1c, 0x00ab581d, 0x00ba5510, 0x00b85410, 0x00bc5810, 0x00bc5709, 0x00bc5504, 0x00c45705, 0x00c85808, 0x00c85606, 0x00bc5814, 0x00964f1f, 0x00431900, 0x000b0000, 0x00000001, 0x0000030a, 0x00050507, 0x000c0100, 0x00371703, 0x00894b2e, 0x00a4502c, 0x00ae4d21, 0x00b14c16, 0x00af4a0c, 0x00b14c0c, 0x00b54d10, 0x00b85016, 0x00b04c16, 0x00b04d15, 0x00b44f10, 0x00b45010, 0x00ac4d12, 0x00975023, 0x00301300, 0x00060000, 0x000b0000, 0x00190500, 0x004c3021, 0x00210800, 0x00080000, 0x00000000, 0x00404143, 0x00a0a4a4, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00181818, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9a9b, 0x003b3d41, 0x00000003, 0x000b0101, 0x00180000, 0x004e1600, 0x00a85a20, 0x00b85714, 0x00c85e14, 0x00ca610c, 0x00cb660d, 0x00c2620a, 0x00bb6512, 0x00b06921, 0x00783b00, 0x004a1600, 0x0079410a, 0x00b36620, 0x00bd6414, 0x00be6009, 0x00c0620d, 0x00b76011, 0x00a6611f, 0x00714518, 0x00190100, 0x000c0100, 0x000a0000, 0x00180000, 0x004a1e00, 0x008b4d20, 0x00ad6028, 0x00b45c1b, 0x00b85710, 0x00c05b0f, 0x00c35909, 0x00c15706, 0x00c25807, 0x00c45809, 0x00c05708, 0x00be560b, 0x00c3580e, 0x00c3580c, 0x00c25709, 0x00bf570a, 0x00bc5607, 0x00bf5603, 0x00bf5601, 0x00be5705, 0x00be5609, 0x00c0550c, 0x00b9581a, 0x009b4c20, 0x006a2605, 0x00480800, 0x00934a24, 0x00b9581e, 0x00c05410, 0x00be4f0e, 0x00b64e11, 0x00ac541c, 0x006d3008, 0x00200900, 0x00020000, 0x00050308, 0x000c0a10, 0x000c070a, 0x00050000, 0x00080000, 0x001b0200, 0x004f1b00, 0x00a05428, 0x00b25117, 0x00b9500e, 0x00bc5210, 0x00b65114, 0x00ac521a, 0x00813b13, 0x00310800, 0x001e0000, 0x00692b0c, 0x00a35021, 0x00b14e14, 0x00bc4f0e, 0x00c0500c, 0x00bd5110, 0x00ac4e16, 0x009f5020, 0x00874b2b, 0x002c0100, 0x001a0000, 0x00140000, 0x00330a00, 0x00854720, 0x00ae501b, 0x00b45118, 0x00a75222, 0x006a2803, 0x002a0000, 0x004e1d04, 0x009d4c1a, 0x00b45111, 0x00b5500b, 0x00b85410, 0x00af4e17, 0x00954219, 0x00370000, 0x00804123, 0x00ab501a, 0x00b8510f, 0x00b55012, 0x00af501d, 0x00924621, 0x004e1b04, 0x000f0000, 0x00030000, 0x00070000, 0x00290c01, 0x00793611, 0x00ad5220, 0x00b45318, 0x00b44c0f, 0x00bc4d14, 0x00bc4c12, 0x00bb4e0b, 0x00bc500b, 0x00b54e0c, 0x00a55220, 0x0050220b, 0x001a0000, 0x00260500, 0x00602c10, 0x00ad5627, 0x00b74c13, 0x00c04f14, 0x00b45018, 0x00965224, 0x003c1600, 0x000a0000, 0x000c0000, 0x00401000, 0x00974a22, 0x00b65019, 0x00bc4d0b, 0x00bc510c, 0x00bf540c, 0x00c5550f, 0x00b45318, 0x00783417, 0x00400700, 0x0078320d, 0x00a5562a, 0x00a85428, 0x009b4d29, 0x006c3019, 0x00300600, 0x00130000, 0x00100000, 0x000d0100, 0x00362018, 0x00744b39, 0x008f5438, 0x009f532e, 0x00a65328, 0x00a45328, 0x009e5024, 0x009a5127, 0x009b5228, 0x009c5027, 0x00984f24, 0x008c4c20, 0x0085481f, 0x007d401b, 0x006f3314, 0x005f240a, 0x004a1400, 0x00350700, 0x00250000, 0x001a0000, 0x00140000, 0x00100000, 0x00110000, 0x001b0000, 0x00300800, 0x005a2618, 0x0086452d, 0x009f5024, 0x00ac531e, 0x00b5521f, 0x00b54e19, 0x00b64d14, 0x00ba5014, 0x00b95010, 0x00b74d0c, 0x00bc4e0e, 0x00bc4f0f, 0x00b95010, 0x00b75112, 0x00b45113, 0x00b55013, 0x00b84f13, 0x00b45118, 0x008a3602, 0x00a85420, 0x00b55314, 0x00ba500c, 0x00b85009, 0x00bb530e, 0x00b95514, 0x00a9561d, 0x007b4018, 0x00341000, 0x00080000, 0x00080000, 0x002b0a00, 0x00824924, 0x00ac561c, 0x00ba5510, 0x00bb5410, 0x00bc5510, 0x00bc560c, 0x00bc550a, 0x00c0560a, 0x00c5580b, 0x00c8560b, 0x00bc5716, 0x0094481a, 0x005c2c10, 0x00140000, 0x00050000, 0x000c0000, 0x00180100, 0x00391400, 0x00874b29, 0x00a95427, 0x00a84210, 0x00bc501d, 0x00b44a13, 0x00b55217, 0x00b04f13, 0x00af480c, 0x00b04a10, 0x00ae4c16, 0x00af4e17, 0x00b04e10, 0x00b14d0d, 0x00b55012, 0x00a4511f, 0x00582e13, 0x000e0000, 0x00090000, 0x00080000, 0x000f0000, 0x000c0000, 0x00000000, 0x00101416, 0x007c7c7e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00181818, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00747371, 0x00161618, 0x00000001, 0x00050000, 0x00110000, 0x00380c00, 0x008d4a18, 0x00b55c1a, 0x00c35d10, 0x00ca6611, 0x00c4630c, 0x00bf630e, 0x00bc6c20, 0x00904f12, 0x00571f00, 0x00763a04, 0x00a45c1e, 0x00c06414, 0x00c45d06, 0x00c4600d, 0x00b85d10, 0x00ad6020, 0x00773f0f, 0x00240400, 0x00130000, 0x00100000, 0x002b0f00, 0x0071401d, 0x009c5b2b, 0x00b05b1e, 0x00bc5b14, 0x00bf570c, 0x00c55809, 0x00c45707, 0x00c55807, 0x00c45806, 0x00c45705, 0x00c55808, 0x00c25709, 0x00c0550b, 0x00c1570e, 0x00c35409, 0x00c15408, 0x00bd550a, 0x00bc570b, 0x00bd5808, 0x00bc590b, 0x00ba580d, 0x00b85710, 0x00b85412, 0x00b45820, 0x009e532a, 0x00743517, 0x00400800, 0x00804020, 0x00b1561c, 0x00c45912, 0x00c0500e, 0x00bc5011, 0x00b05116, 0x007c3a0f, 0x002c1102, 0x00040000, 0x00090204, 0x0021181c, 0x001c1314, 0x000a0000, 0x00080000, 0x00120000, 0x00310900, 0x0094542e, 0x00ae5018, 0x00b94d0c, 0x00ba4e0d, 0x00b85011, 0x00b05118, 0x008d4217, 0x00380b00, 0x001f0000, 0x0063280c, 0x009a4e23, 0x00b1521c, 0x00b94f10, 0x00be4d0c, 0x00b94807, 0x00b85011, 0x00b85921, 0x009d4b1c, 0x00884524, 0x00340300, 0x00270000, 0x004e1400, 0x0094481f, 0x00b8521b, 0x00b74d14, 0x00a95321, 0x00692804, 0x00240000, 0x00461905, 0x00944718, 0x00b04e10, 0x00b75009, 0x00b85510, 0x00a84d17, 0x008c3c14, 0x003f0000, 0x00904b28, 0x00b15114, 0x00b84f08, 0x00b45013, 0x00ab5322, 0x007c3a1a, 0x00350c00, 0x000c0000, 0x00020000, 0x000b0000, 0x00341301, 0x00984c26, 0x00b0531d, 0x00ad5018, 0x00a14008, 0x00b84e18, 0x00bb4c13, 0x00bb4d0c, 0x00bc500b, 0x00b44d0a, 0x00aa5621, 0x0056250c, 0x001e0000, 0x00290400, 0x00662f10, 0x00b3582a, 0x00b84a12, 0x00c04e13, 0x00b4501a, 0x00945324, 0x00381200, 0x000b0000, 0x000f0000, 0x00461200, 0x009c4c24, 0x00b7511a, 0x00bc4c0a, 0x00bd500a, 0x00bf540c, 0x00c55710, 0x00a84a10, 0x006e2c0f, 0x00480c00, 0x00904014, 0x00af511c, 0x00b25019, 0x00af501f, 0x00a4512d, 0x007c3c22, 0x003f1302, 0x001b0000, 0x00150100, 0x00140000, 0x002c0400, 0x005a230c, 0x00904726, 0x00a14c23, 0x00aa5221, 0x00ac521c, 0x00ad521a, 0x00b2541c, 0x00b65019, 0x00b04d15, 0x00ac5218, 0x00aa541b, 0x00a7501c, 0x00a24d1d, 0x00a35025, 0x00a0542c, 0x00954e2b, 0x00824626, 0x00673518, 0x00471f04, 0x00280700, 0x001b0000, 0x00180000, 0x00170000, 0x001c0000, 0x002b0400, 0x00542004, 0x007f3d18, 0x00a05430, 0x00aa542c, 0x00ab4c1f, 0x00b14d18, 0x00ba5113, 0x00bd500d, 0x00bd4e0a, 0x00bc4f0a, 0x00ba5010, 0x00b85014, 0x00b65014, 0x00b85014, 0x00bc4d13, 0x00ba4f14, 0x00ae5016, 0x00b25519, 0x00b34f0f, 0x00b95210, 0x00bc5410, 0x00b85310, 0x00b55415, 0x00a55620, 0x00633010, 0x001c0100, 0x00050000, 0x00090000, 0x00371000, 0x00935226, 0x00b0581c, 0x00ba5511, 0x00be5410, 0x00bc520e, 0x00bb540d, 0x00bd570e, 0x00be550c, 0x00c1550c, 0x00c8550c, 0x00c05717, 0x00a75629, 0x00662e13, 0x00180000, 0x00150000, 0x001d0000, 0x00401300, 0x00864726, 0x00a45428, 0x00ab4814, 0x00bc4f17, 0x00b44510, 0x00b54b14, 0x00ad4c15, 0x00ad4f15, 0x00b44f14, 0x00b24c14, 0x00b04f19, 0x00b15019, 0x00b04d10, 0x00b14a09, 0x00bf5110, 0x00ad5018, 0x007c4424, 0x00190000, 0x000a0000, 0x00020000, 0x00040000, 0x00040000, 0x00000206, 0x00484c50, 0x00a8a8a8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00171718, 0x00020202, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00acacac, 0x00514e4d, 0x00070000, 0x00060000, 0x00020000, 0x00080000, 0x00200400, 0x00602b04, 0x00b86624, 0x00c05f0e, 0x00c6660e, 0x00c1640d, 0x00be6716, 0x00af621c, 0x00642800, 0x00713602, 0x009e5417, 0x00bb641b, 0x00c7600e, 0x00c85b08, 0x00c45c0f, 0x00b75b1a, 0x00853c0f, 0x003d0900, 0x00190000, 0x00200000, 0x00532200, 0x008b4b1a, 0x00ac5d23, 0x00b35714, 0x00c05a10, 0x00c75c0e, 0x00c15608, 0x00c2580c, 0x00bd580c, 0x00bc580e, 0x00bf590d, 0x00c1590c, 0x00c3580a, 0x00c45609, 0x00c45408, 0x00c35409, 0x00c55510, 0x00c45412, 0x00be5613, 0x00b95512, 0x00b75712, 0x00b45816, 0x00b05b1e, 0x00af5c25, 0x00ac5a27, 0x009c5126, 0x00844828, 0x005d2b12, 0x00300500, 0x00652c09, 0x00b45a18, 0x00c65809, 0x00c8530e, 0x00ba4b0a, 0x00b25012, 0x00974e22, 0x00331202, 0x000c0000, 0x000c0000, 0x00302222, 0x00342420, 0x00100000, 0x000a0000, 0x000c0000, 0x002a0c00, 0x00743d1e, 0x00a94f1a, 0x00bd5010, 0x00bc4f0f, 0x00b85011, 0x00b15018, 0x0095491e, 0x003e1000, 0x001c0000, 0x0058240a, 0x00944c26, 0x00ad531e, 0x00b85013, 0x00bc4e0e, 0x00be4d0d, 0x00bc4d0c, 0x00b84e0f, 0x00b24f15, 0x00a85021, 0x00833c1e, 0x00500d00, 0x00752b08, 0x00a44c1d, 0x00bc4e14, 0x00ba4c13, 0x00a74f1e, 0x00672805, 0x00220000, 0x003b1404, 0x008b4017, 0x00b35219, 0x00b54f09, 0x00b4500c, 0x00a8521f, 0x00792c06, 0x005b1400, 0x009c4e27, 0x00b44f10, 0x00bc5009, 0x00b25014, 0x00a8572a, 0x0060250c, 0x00230100, 0x00080000, 0x00070300, 0x00180700, 0x004c240c, 0x00a5552c, 0x00ae521e, 0x00a5501f, 0x006e1800, 0x00b5511e, 0x00b74c13, 0x00bc500f, 0x00b84d08, 0x00b7500c, 0x00a95520, 0x005a2a0f, 0x00220000, 0x002d0800, 0x00682f0f, 0x00af5424, 0x00ba4c13, 0x00bc4c12, 0x00b4511b, 0x00975528, 0x00330c00, 0x000a0000, 0x00100000, 0x00572007, 0x009b4720, 0x00b8521b, 0x00be4f0c, 0x00bc4e07, 0x00c3570d, 0x00c15812, 0x009f430d, 0x00571800, 0x004e1100, 0x00a54e1f, 0x00b75014, 0x00bc4f10, 0x00b5480d, 0x00b04d1d, 0x00a85028, 0x00944824, 0x00682c0f, 0x00380b00, 0x001b0000, 0x00170000, 0x001e0000, 0x00350c00, 0x00602c12, 0x008c4a22, 0x00a25421, 0x00ac511b, 0x00b34d18, 0x00b84b19, 0x00bb4c1a, 0x00b95016, 0x00b24c0f, 0x00b14e13, 0x00b25118, 0x00ad5018, 0x00ad511c, 0x00ae521e, 0x00aa4d1c, 0x00a74c1c, 0x00a34a1e, 0x0095451d, 0x00783411, 0x004e1900, 0x00270100, 0x00140000, 0x00140000, 0x001c0000, 0x002a0600, 0x0049200c, 0x007f482f, 0x009d5433, 0x00a84d20, 0x00b95115, 0x00c0500c, 0x00bc4d04, 0x00bc5007, 0x00b74d0c, 0x00b74d11, 0x00bc5117, 0x00ba4c11, 0x00ba4809, 0x00c15211, 0x00b85010, 0x00b55111, 0x00b55314, 0x00b45113, 0x00b85414, 0x00b45214, 0x00b35516, 0x00984c1b, 0x004d2207, 0x00140000, 0x00060000, 0x000c0000, 0x00431400, 0x009f5725, 0x00b3591c, 0x00b85310, 0x00bd520e, 0x00be530d, 0x00bb540f, 0x00b8540e, 0x00bc550c, 0x00c1570e, 0x00c8540d, 0x00c05516, 0x00ad5628, 0x00702f10, 0x00260000, 0x00260000, 0x004f1800, 0x0089431c, 0x00a45026, 0x00ab4c1d, 0x00b14b17, 0x00b44b14, 0x00b24815, 0x00af4b18, 0x00aa501b, 0x00aa5019, 0x00b04c13, 0x00b24c14, 0x00af4c14, 0x00b04c13, 0x00b65010, 0x00b84d08, 0x00c4500b, 0x00c05a1e, 0x00904c28, 0x00290400, 0x000e0000, 0x00000001, 0x00000001, 0x00030407, 0x00191d22, 0x00898c8f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00181819, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00888888, 0x002e2a28, 0x000d0000, 0x001c0e04, 0x0019120b, 0x00060000, 0x00130100, 0x00431b00, 0x00b06322, 0x00c26410, 0x00c2650c, 0x00b9600a, 0x00be6c1e, 0x008a4200, 0x00733500, 0x008f4c14, 0x00b15e17, 0x00c46414, 0x00c55b07, 0x00c95c08, 0x00c55b0f, 0x00ae5011, 0x007d3305, 0x004a1000, 0x003f0f00, 0x005c2809, 0x009a501e, 0x00b45d1c, 0x00bd5d18, 0x00c0580d, 0x00c75a0b, 0x00c45607, 0x00bf5203, 0x00c1590c, 0x00bf5c14, 0x00b95914, 0x00b65812, 0x00b65812, 0x00b85814, 0x00bb5915, 0x00bb5714, 0x00b85517, 0x00b85721, 0x00b45825, 0x00ad5523, 0x00a4501e, 0x00944814, 0x00803806, 0x006c2800, 0x005e1c00, 0x004f0d00, 0x00480a00, 0x003a0600, 0x00310400, 0x00220000, 0x004b1800, 0x00b45c1b, 0x00c35607, 0x00cb540c, 0x00c04e0b, 0x00b65013, 0x009f5224, 0x004b200b, 0x00180000, 0x00100000, 0x002d1a17, 0x00442c24, 0x0029130a, 0x000a0000, 0x000b0000, 0x00180400, 0x00582b10, 0x00a85122, 0x00bc5013, 0x00bc4e0e, 0x00b74e10, 0x00b14f17, 0x00994d22, 0x003f1200, 0x001d0000, 0x00532009, 0x008c4723, 0x00ac511f, 0x00b74f13, 0x00bb4d0f, 0x00bd4c0c, 0x00be4c0b, 0x00bd4c0b, 0x00ba4d0f, 0x00b24f17, 0x00a64e24, 0x0098451c, 0x00a54d1e, 0x00b04e18, 0x00bf4f13, 0x00b84d13, 0x00a14c1e, 0x005c2201, 0x001c0000, 0x00330e02, 0x00823916, 0x00b0511c, 0x00b84f0f, 0x00b44f11, 0x00a44f20, 0x00742703, 0x00712401, 0x00a75023, 0x00b84e0c, 0x00b94c06, 0x00af5119, 0x00944a21, 0x004c1a06, 0x00180000, 0x00060000, 0x00090000, 0x00260c00, 0x006c391d, 0x00a85527, 0x00a84f1c, 0x0091461b, 0x00520600, 0x00ac4e1d, 0x00b64d15, 0x00bc4f10, 0x00ba4e0c, 0x00b7500d, 0x00a95721, 0x0058290e, 0x00210000, 0x00320a00, 0x006d3111, 0x00b05322, 0x00b94c12, 0x00ba4c11, 0x00b2501b, 0x00965428, 0x00330b00, 0x00100000, 0x00140000, 0x006c3014, 0x00a24c23, 0x00b85118, 0x00ba4b08, 0x00c05209, 0x00c2580f, 0x00bd5918, 0x00903c0a, 0x00490f00, 0x005c2107, 0x00a45020, 0x00af490c, 0x00bb4b0c, 0x00be4d0e, 0x00b84c14, 0x00b04a16, 0x00a84c1a, 0x009c4c20, 0x007e3c1c, 0x0054210b, 0x002d0800, 0x001a0000, 0x001a0000, 0x00240300, 0x00441500, 0x006c3009, 0x0096481c, 0x00b15728, 0x00b85226, 0x00b04416, 0x00b84a12, 0x00b74a0d, 0x00b84d10, 0x00b85013, 0x00b44e12, 0x00b34c10, 0x00b64d14, 0x00b84d14, 0x00b94a13, 0x00b94c15, 0x00b14a16, 0x00a54b1c, 0x00974d26, 0x007d4625, 0x00502c11, 0x002b0e00, 0x00180000, 0x00170000, 0x00180000, 0x00300f00, 0x005c2a11, 0x008c4622, 0x00ad5220, 0x00b04b0c, 0x00ba510b, 0x00bb5008, 0x00b64d0c, 0x00b64d0f, 0x00b94e14, 0x00bc4e14, 0x00bd4c0d, 0x00bc4c0a, 0x00bc500b, 0x00b8500c, 0x00b45315, 0x00b25215, 0x00b45214, 0x00b25013, 0x00b05317, 0x008e4616, 0x00411c05, 0x000c0000, 0x00060000, 0x00140000, 0x004d1800, 0x00a55926, 0x00b0561b, 0x00b85412, 0x00bd520e, 0x00bd520c, 0x00b85410, 0x00b6550e, 0x00ba560c, 0x00c0580c, 0x00c8550a, 0x00c25414, 0x00b55828, 0x00803714, 0x00350300, 0x00491700, 0x008a451c, 0x00aa5628, 0x00a84c1e, 0x00aa491c, 0x00ad4f1e, 0x00ac4e1d, 0x00a14013, 0x009c3d0c, 0x00a44a18, 0x00a84e18, 0x00ae4b11, 0x00b44e14, 0x00b04c10, 0x00b75114, 0x00b44b07, 0x00c4540c, 0x00cc550d, 0x00bd5418, 0x009c5530, 0x00401804, 0x000d0000, 0x00000001, 0x00040508, 0x0004070b, 0x0064686c, 0x00b0b4b4, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00141414, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00616163, 0x00150e0a, 0x001e0800, 0x00412814, 0x003f2d1c, 0x000d0000, 0x000c0000, 0x002c0c00, 0x00a96020, 0x00c3680e, 0x00c1660a, 0x00b9640c, 0x00ad6317, 0x00743000, 0x00904807, 0x00ad5f19, 0x00bc6313, 0x00c2610c, 0x00c25e08, 0x00c45e08, 0x00c45c0c, 0x00bb5a11, 0x00a85115, 0x00954811, 0x00934b18, 0x00a55820, 0x00b85f1d, 0x00bc5c13, 0x00bc5810, 0x00c05910, 0x00c45c13, 0x00c2580c, 0x00c05508, 0x00c35b0e, 0x00bc5810, 0x00b85815, 0x00b05b1c, 0x00ac5e25, 0x00a95e2b, 0x00a15929, 0x00954c1f, 0x0088441c, 0x006f3012, 0x0061280f, 0x00531e04, 0x00441400, 0x003a0c00, 0x00340900, 0x00300400, 0x00310200, 0x00320000, 0x003c0800, 0x00401000, 0x00481c08, 0x003d1908, 0x00370700, 0x00a3521a, 0x00be5610, 0x00c8520c, 0x00c4500c, 0x00b44f11, 0x00a65424, 0x006a3215, 0x002a0600, 0x00100000, 0x00240e08, 0x00513024, 0x00492a1e, 0x000e0000, 0x000b0000, 0x000c0000, 0x003a1400, 0x00a45127, 0x00b74c15, 0x00bb4d0f, 0x00b74c0f, 0x00b04f18, 0x009d5228, 0x00411504, 0x001e0000, 0x00491904, 0x0085421f, 0x00af511c, 0x00b94c10, 0x00bc4c0e, 0x00bc4c0c, 0x00be4c0b, 0x00be4c0c, 0x00bb4d0f, 0x00b74f13, 0x00b04c14, 0x00b4531c, 0x00b35115, 0x00b14c0e, 0x00ba4c10, 0x00b14c14, 0x009b4f22, 0x00582408, 0x00150000, 0x002d0b04, 0x007b3418, 0x00ad4e21, 0x00b54c13, 0x00b55017, 0x00a24c23, 0x00701f00, 0x008f3a12, 0x00b05220, 0x00bb4e0b, 0x00b54c08, 0x00ac5520, 0x007c3916, 0x00361000, 0x00100000, 0x00090000, 0x00100000, 0x003c1400, 0x008b502c, 0x00a65224, 0x00a14d1f, 0x007c3b18, 0x003a0000, 0x00a0481b, 0x00b24f17, 0x00b94f11, 0x00bb4e10, 0x00b44f10, 0x00a55622, 0x0053270e, 0x001f0000, 0x00380e00, 0x00743516, 0x00b05221, 0x00b94c12, 0x00b84c10, 0x00af511c, 0x00945228, 0x00340800, 0x00140000, 0x001c0000, 0x00814021, 0x00a74e21, 0x00b65015, 0x00b84c07, 0x00c4570c, 0x00bf580f, 0x00b0551b, 0x00783004, 0x003c0800, 0x006b3820, 0x00a85c2f, 0x00af5119, 0x00b44e14, 0x00b44a0e, 0x00b64c10, 0x00b44e12, 0x00b15016, 0x00ac541c, 0x00a35323, 0x008f4820, 0x006e3314, 0x00502008, 0x002b0600, 0x00180000, 0x00170000, 0x002e0b00, 0x00511f04, 0x00783818, 0x009d4d26, 0x00b05426, 0x00b04c18, 0x00b74d14, 0x00b74c11, 0x00b84c12, 0x00b94e14, 0x00b84d14, 0x00b64c14, 0x00b84d18, 0x00b64c14, 0x00ba5119, 0x00b7511a, 0x00ac4d17, 0x00a8501c, 0x00a35626, 0x00914d22, 0x007a3f1b, 0x005d2a0e, 0x00391100, 0x00160000, 0x00100000, 0x00220a00, 0x00492208, 0x00793b14, 0x00a65423, 0x00ae5014, 0x00b34d0c, 0x00b5500f, 0x00b65011, 0x00b44f11, 0x00b74f12, 0x00b94f10, 0x00b84c0b, 0x00bf500c, 0x00b84e0c, 0x00b45318, 0x00b05318, 0x00b25013, 0x00b25013, 0x00ac5319, 0x00843e13, 0x00381603, 0x000a0000, 0x00070000, 0x00180100, 0x00501a00, 0x00a75b26, 0x00ac5319, 0x00b65514, 0x00ba520d, 0x00bb530c, 0x00b6550e, 0x00b4550c, 0x00b85609, 0x00bf5807, 0x00c85606, 0x00c4540e, 0x00b75520, 0x0084370e, 0x00400900, 0x005d2909, 0x009e5728, 0x00a24f1c, 0x009f471c, 0x00a7502b, 0x00984a26, 0x00823410, 0x0087320c, 0x009b4216, 0x00a24a18, 0x00a84d15, 0x00b34e13, 0x00b2480c, 0x00b04809, 0x00b84c0a, 0x00be4f06, 0x00cb580d, 0x00c8540f, 0x00bc561f, 0x00985534, 0x00381300, 0x000a0000, 0x00020202, 0x00000001, 0x003c3c3e, 0x00a4a7a8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000c0c0c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00acacae, 0x00464648, 0x00100400, 0x00381800, 0x006b4424, 0x00603f25, 0x001e0500, 0x000a0000, 0x00270a00, 0x00a05c1c, 0x00bc640d, 0x00be6508, 0x00bc6910, 0x00924900, 0x00884000, 0x00aa5911, 0x00b96114, 0x00be620c, 0x00bc5f04, 0x00c16108, 0x00c05f06, 0x00c05c07, 0x00be5c0c, 0x00bc6016, 0x00bb621b, 0x00b66019, 0x00b45c14, 0x00bc5b12, 0x00bd5911, 0x00b95914, 0x00b55816, 0x00b55818, 0x00b75919, 0x00ba5b18, 0x00b85918, 0x00b05515, 0x00a34e13, 0x008d430d, 0x007a3608, 0x00692b04, 0x005b2000, 0x004f1400, 0x00450e00, 0x003c0900, 0x00370800, 0x00330500, 0x00340900, 0x003b1300, 0x0048200a, 0x00592a12, 0x00643014, 0x00723817, 0x007f4120, 0x00884a28, 0x00844c2f, 0x00683c26, 0x00360300, 0x00813404, 0x00bb591c, 0x00c5520c, 0x00c6510c, 0x00b44c0e, 0x00ab5420, 0x0088431d, 0x00400f00, 0x00140000, 0x00180100, 0x004e2a1b, 0x00603c2c, 0x00200b05, 0x000d0000, 0x000a0000, 0x00280700, 0x00954924, 0x00b14b18, 0x00b94c11, 0x00b84d10, 0x00b04f18, 0x00a2552c, 0x00441808, 0x001f0000, 0x00411300, 0x00803f1c, 0x00af511c, 0x00ba4d0f, 0x00bc4c0c, 0x00bc4c0c, 0x00bd4b0c, 0x00bc4c0c, 0x00ba4d10, 0x00b84e12, 0x00b85010, 0x00b44b09, 0x00b54d0a, 0x00b64d0d, 0x00b54f14, 0x00ab511f, 0x008c4c26, 0x00451b02, 0x00110000, 0x002c0c04, 0x00793218, 0x00ab4d23, 0x00b44b17, 0x00b8501c, 0x00a84c23, 0x00792300, 0x00a4481b, 0x00b4501a, 0x00bb4d0c, 0x00b44c0c, 0x00a95728, 0x00642b0c, 0x00250800, 0x000c0000, 0x000e0000, 0x001f0200, 0x005b2708, 0x009f572c, 0x00a3501d, 0x009c4e22, 0x00632c11, 0x00300000, 0x00944417, 0x00b04f18, 0x00b64b10, 0x00ba4d12, 0x00b44f14, 0x009f5222, 0x004a230b, 0x001a0000, 0x003c1100, 0x007b391b, 0x00b05020, 0x00b94c11, 0x00b64c10, 0x00ac511b, 0x0093502a, 0x00340500, 0x001a0000, 0x00300800, 0x008f4824, 0x00aa4d1c, 0x00b85013, 0x00bd500c, 0x00c4560b, 0x00ba5712, 0x009c4d19, 0x005d2200, 0x00300800, 0x005c3420, 0x008d5029, 0x009f5222, 0x00ac5424, 0x00ae4e1c, 0x00af4c10, 0x00b55111, 0x00b15012, 0x00ab4d10, 0x00aa5015, 0x00ac5620, 0x009f5020, 0x0089441c, 0x00703718, 0x004e200b, 0x002c0700, 0x001d0000, 0x00210000, 0x00380b00, 0x00622b0c, 0x008c4822, 0x00a55023, 0x00b35322, 0x00b44e18, 0x00b24810, 0x00b64b10, 0x00b84d13, 0x00b64c14, 0x00b54c14, 0x00b54e18, 0x00b44f16, 0x00b44f14, 0x00b24d12, 0x00b04e14, 0x00ae5016, 0x00ac521c, 0x00a85523, 0x00954c22, 0x00783e1c, 0x00542c12, 0x002a0f00, 0x00110000, 0x00180000, 0x003e1400, 0x00763b15, 0x00a05020, 0x00ac5018, 0x00b35014, 0x00b45012, 0x00b45113, 0x00b35012, 0x00b45010, 0x00b7500f, 0x00bc500c, 0x00b64c0b, 0x00b35218, 0x00b05218, 0x00b44f11, 0x00b45214, 0x00ad541c, 0x007f3c13, 0x00341504, 0x00080000, 0x00070000, 0x00160000, 0x004b1700, 0x00a45a28, 0x00a95319, 0x00b55616, 0x00b85310, 0x00b9530d, 0x00b5540d, 0x00b45409, 0x00b85607, 0x00bf5806, 0x00c85604, 0x00c5540b, 0x00bd581d, 0x0089380c, 0x00461000, 0x005c2d0d, 0x00945424, 0x00994e1d, 0x009e4d28, 0x00944526, 0x006d290c, 0x00682204, 0x00853411, 0x00a54d24, 0x00aa4f1c, 0x00ad4c14, 0x00b54d10, 0x00b44708, 0x00ba4e0d, 0x00bb4e0b, 0x00c5570e, 0x00c3570f, 0x00bd5416, 0x00a75020, 0x00662e13, 0x001b0000, 0x000b0000, 0x00000000, 0x00181818, 0x00898989, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00070707, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00949094, 0x00312e2f, 0x00100000, 0x00502405, 0x0090562e, 0x007e4824, 0x003a1000, 0x00100000, 0x00290c00, 0x00945119, 0x00b86211, 0x00bc6208, 0x00bb640c, 0x008d4000, 0x00a65610, 0x00bc6013, 0x00c05f0b, 0x00be610a, 0x00bd6006, 0x00bf6003, 0x00c06104, 0x00c06008, 0x00b95b06, 0x00b65704, 0x00b85b08, 0x00b95f0d, 0x00b85e10, 0x00b85a14, 0x00b85c1b, 0x00b56026, 0x00ac5d28, 0x009e5322, 0x00904818, 0x00833b0b, 0x00742c00, 0x006d2600, 0x00682400, 0x005c1f00, 0x00541a00, 0x00501800, 0x00541a00, 0x005c2001, 0x00622703, 0x006c2c04, 0x00723104, 0x0079380c, 0x00804015, 0x00844722, 0x008e4c26, 0x009b5023, 0x00a5531e, 0x00b0571e, 0x00ae541b, 0x00b15821, 0x00a25223, 0x00854627, 0x00490b00, 0x00621500, 0x00b65a26, 0x00c45412, 0x00c85710, 0x00b64f0c, 0x00b0541c, 0x009e4e1f, 0x00591d00, 0x00200000, 0x00120000, 0x00442011, 0x00684333, 0x003b2014, 0x000f0000, 0x000b0100, 0x001d0400, 0x007d391a, 0x00ad4e21, 0x00b74d14, 0x00b84e12, 0x00b24f17, 0x00a5562a, 0x004c1e0b, 0x00200000, 0x00380c00, 0x007b3c1d, 0x00ac521d, 0x00b84e0f, 0x00ba4c0c, 0x00bc4c0c, 0x00bc4c0c, 0x00bc4c0c, 0x00b74d12, 0x00b74f13, 0x00bc5210, 0x00b84d09, 0x00bd500c, 0x00b64f0e, 0x00ad511d, 0x009c5028, 0x0068381b, 0x00280a00, 0x000f0000, 0x002b0900, 0x00742c11, 0x00ad5025, 0x00b54e1a, 0x00b54e18, 0x00af4f1f, 0x00943808, 0x00b04d1a, 0x00b34c14, 0x00b84c0d, 0x00b04e14, 0x009c5328, 0x004c1d04, 0x00170100, 0x00080000, 0x00130000, 0x00360e00, 0x007f3d15, 0x00a65421, 0x00a4501b, 0x00964e24, 0x00461806, 0x00280000, 0x008c4518, 0x00ac5018, 0x00b44912, 0x00ba4c14, 0x00b25019, 0x0094491e, 0x003f1c08, 0x00150000, 0x003f1302, 0x00803d20, 0x00b0501d, 0x00b84e10, 0x00b44f11, 0x00ac521d, 0x00934d29, 0x00360200, 0x00220000, 0x00502008, 0x009d4d25, 0x00b04e18, 0x00b95010, 0x00c1540e, 0x00c0540a, 0x00b85818, 0x00864118, 0x003e1000, 0x001f0400, 0x002d1404, 0x004a2206, 0x0065300e, 0x00844324, 0x009b4f28, 0x00ab541e, 0x00ae5114, 0x00ad5012, 0x00b05011, 0x00b15011, 0x00b05010, 0x00b04e10, 0x00ac4f17, 0x00a44c1d, 0x00944720, 0x00723013, 0x004e1803, 0x00340800, 0x001f0000, 0x00200400, 0x00431c02, 0x0079391c, 0x009b4a25, 0x00ac5224, 0x00af4d18, 0x00b34b0e, 0x00b44c0c, 0x00b44c0d, 0x00b44f12, 0x00b24f15, 0x00b04c13, 0x00b44d13, 0x00ba5216, 0x00ba5014, 0x00b54c0e, 0x00b44c0f, 0x00b45013, 0x00ac4f11, 0x00a04e17, 0x00944c22, 0x00713819, 0x00431d07, 0x00210400, 0x001b0000, 0x00391300, 0x00793e1a, 0x009c4f23, 0x00b0511e, 0x00b04c13, 0x00b45113, 0x00b45414, 0x00af5112, 0x00b25313, 0x00b85010, 0x00b34b0c, 0x00b35117, 0x00b25014, 0x00b84e0c, 0x00b75110, 0x00ad541c, 0x007d3d14, 0x00341607, 0x00080000, 0x00050000, 0x00100000, 0x00411200, 0x00985428, 0x00aa541c, 0x00b45314, 0x00b65212, 0x00b7520f, 0x00b6530c, 0x00b65409, 0x00b85507, 0x00bf5806, 0x00c75504, 0x00c75409, 0x00c2581c, 0x008f3b0d, 0x00411100, 0x00542c12, 0x008c5930, 0x0092542c, 0x00823e20, 0x00601900, 0x00541100, 0x007e3818, 0x009c4b28, 0x00a44b20, 0x00ae4f1a, 0x00b24c10, 0x00b34608, 0x00bc4d0c, 0x00be4f0e, 0x00c05410, 0x00bc5711, 0x00b45617, 0x00a55422, 0x00743412, 0x002c0600, 0x00120000, 0x00060000, 0x00080808, 0x00666564, 0x00afaeac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00766f71, 0x00231c1c, 0x00160100, 0x00632e08, 0x00a45d2d, 0x00974e22, 0x005b2101, 0x00150000, 0x00260900, 0x007d400f, 0x00b6651c, 0x00bd640e, 0x00b75d05, 0x00a54e02, 0x00b65d14, 0x00c05e11, 0x00c25d0c, 0x00bf5e0a, 0x00c06109, 0x00c15e03, 0x00bf5e04, 0x00be5f0c, 0x00be6112, 0x00bb5f14, 0x00b85f17, 0x00b35e18, 0x00aa5815, 0x00a15014, 0x0090410c, 0x007f3403, 0x00742c00, 0x006b2700, 0x00692700, 0x006e2c02, 0x00702e03, 0x00732f01, 0x00783407, 0x007e3c10, 0x00834114, 0x00884418, 0x008c481c, 0x00944c22, 0x009b5023, 0x00a85822, 0x00ac5a1e, 0x00b0591f, 0x00af581f, 0x00a95722, 0x00aa5420, 0x00b25215, 0x00b7520f, 0x00bb5410, 0x00b7520e, 0x00bc5c1b, 0x00ac5824, 0x0090502d, 0x005c2107, 0x00480700, 0x009e4e24, 0x00bf5718, 0x00c85811, 0x00ba520d, 0x00b45214, 0x00a9501b, 0x00743008, 0x00310c00, 0x00130000, 0x00381608, 0x00654130, 0x00573425, 0x00180100, 0x00070000, 0x00160100, 0x00612409, 0x00ac532b, 0x00b54c16, 0x00bb4e11, 0x00b44d13, 0x00a75426, 0x00592812, 0x00250000, 0x002f0500, 0x0073381a, 0x00aa5220, 0x00b64e11, 0x00b84d10, 0x00ba4c0e, 0x00bc4c0c, 0x00ba4c0e, 0x00b74d14, 0x00b64d14, 0x00b64c0c, 0x00b64a08, 0x00b84c07, 0x00b24d10, 0x00a24f24, 0x00733619, 0x00341200, 0x00170400, 0x000d0000, 0x002a0800, 0x0070280a, 0x00ae5025, 0x00b4501a, 0x00b0490f, 0x00b24c14, 0x00af4c12, 0x00b65015, 0x00b44c10, 0x00b84d13, 0x00ae501b, 0x00884721, 0x003b1300, 0x000d0000, 0x00070000, 0x00170000, 0x004e1d04, 0x009c4c1d, 0x00ab5118, 0x00a7531c, 0x008f4c24, 0x002e0700, 0x00220000, 0x0089471c, 0x00aa5118, 0x00b44a14, 0x00b84c18, 0x00b3511f, 0x00843c14, 0x00301200, 0x00120000, 0x00421605, 0x00854122, 0x00ae4f1a, 0x00b84e0f, 0x00b25010, 0x00aa531d, 0x00924c2c, 0x00380000, 0x00270000, 0x006f3418, 0x00a34e20, 0x00b44f14, 0x00ba500e, 0x00c2560e, 0x00c0540c, 0x00b1571a, 0x006c3110, 0x00200000, 0x000c0000, 0x00080000, 0x00180300, 0x00280800, 0x00431707, 0x005d260f, 0x007c3b14, 0x00904416, 0x00a35120, 0x00ad5420, 0x00b15018, 0x00b34e11, 0x00b54d0f, 0x00b64e10, 0x00ad480d, 0x00b1511f, 0x00a44e24, 0x008c4221, 0x006f341a, 0x00431801, 0x001e0100, 0x001b0000, 0x00380b00, 0x0064290f, 0x00904721, 0x00a75222, 0x00b15018, 0x00b34d10, 0x00b24c0f, 0x00b44f12, 0x00af4c10, 0x00b14e13, 0x00b55012, 0x00b64d0f, 0x00b5480a, 0x00b54808, 0x00b74a0c, 0x00b84d0e, 0x00b85110, 0x00ae4c0f, 0x00ab4f1c, 0x00a35228, 0x0087482a, 0x005c2d15, 0x00331000, 0x00280400, 0x00441100, 0x007b3815, 0x00a75325, 0x00b0521c, 0x00b15014, 0x00b15011, 0x00b05011, 0x00b25214, 0x00b45012, 0x00b24c0f, 0x00b35014, 0x00b44f10, 0x00bb4c06, 0x00b84e0a, 0x00ac531a, 0x007e4019, 0x00351809, 0x00090000, 0x00050000, 0x000c0000, 0x00360e00, 0x00864821, 0x00ac5620, 0x00b25012, 0x00b55014, 0x00b85014, 0x00b8500d, 0x00b85108, 0x00b85406, 0x00be5706, 0x00c75507, 0x00c7540b, 0x00c05519, 0x008c380c, 0x003b0f00, 0x004b2e1b, 0x00764f2f, 0x0064300e, 0x004e0f00, 0x004d0800, 0x00782f0e, 0x00984c25, 0x00a8512c, 0x00a6481d, 0x00ac4911, 0x00b4490c, 0x00b94808, 0x00c04e0c, 0x00be4f0c, 0x00bf5817, 0x00b45a1c, 0x00a25822, 0x006d3310, 0x00350d00, 0x00120000, 0x00060000, 0x00040203, 0x004c4e4d, 0x00aaa9a8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005d5053, 0x00170e0c, 0x00270e00, 0x00773a10, 0x00b05f28, 0x00a9511f, 0x007c330f, 0x001f0000, 0x001f0100, 0x00652d04, 0x00b06628, 0x00bd6615, 0x00ba5c04, 0x00c25d0b, 0x00c05b0f, 0x00be5d16, 0x00bf5c15, 0x00c05c0c, 0x00c25c06, 0x00c55c06, 0x00bc5704, 0x00b85810, 0x00b4591c, 0x00a3501d, 0x008e4318, 0x007b380f, 0x006d2f08, 0x00602400, 0x005c1f00, 0x005e1c00, 0x00682400, 0x00762d01, 0x00823608, 0x008f4211, 0x009c4e18, 0x00aa5820, 0x00ae591e, 0x00b35a1b, 0x00b55818, 0x00b55614, 0x00b65516, 0x00b75518, 0x00b85618, 0x00b55411, 0x00b95410, 0x00c05510, 0x00c25512, 0x00be5517, 0x00bc5415, 0x00c0520c, 0x00c1530c, 0x00b8510c, 0x00b15412, 0x00ac581b, 0x00985322, 0x00744428, 0x004a2210, 0x002d0100, 0x006e3213, 0x00b4571c, 0x00c3570f, 0x00c0540d, 0x00b8510f, 0x00ae5016, 0x008e4318, 0x00481d04, 0x00180000, 0x00270a00, 0x00583728, 0x006c442e, 0x00331500, 0x00050000, 0x00100000, 0x00481100, 0x00a7532f, 0x00b34c18, 0x00ba4d10, 0x00b54c10, 0x00a8501e, 0x00693218, 0x002a0400, 0x00240000, 0x00663116, 0x00a45224, 0x00b04e16, 0x00b44e14, 0x00b84d11, 0x00bc4c0c, 0x00bc4c0c, 0x00b84c12, 0x00b64d14, 0x00b85016, 0x00b84e12, 0x00b74b0a, 0x00b3501a, 0x008c4322, 0x00461504, 0x00100000, 0x000b0000, 0x00100100, 0x003c1804, 0x007c3410, 0x00ae5120, 0x00b15015, 0x00b04a09, 0x00b54d08, 0x00b9500c, 0x00b84e0f, 0x00b64c11, 0x00b84f17, 0x00ab5020, 0x00723616, 0x002c0b00, 0x00050000, 0x00060000, 0x00240500, 0x006b3014, 0x00a8511c, 0x00b04f11, 0x00a45118, 0x0084451f, 0x00210000, 0x001f0000, 0x0086481d, 0x00a75118, 0x00b44c15, 0x00b84b19, 0x00b05020, 0x00712c08, 0x00240800, 0x00100000, 0x00451909, 0x00894526, 0x00ad4e19, 0x00b74e0e, 0x00b0500f, 0x00a8521e, 0x00924a2c, 0x003b0000, 0x00360000, 0x00884525, 0x00a74c19, 0x00b74e10, 0x00bf540e, 0x00c0540c, 0x00c35810, 0x009e480e, 0x004e1e03, 0x00120000, 0x00040000, 0x00000000, 0x00050200, 0x00080000, 0x00130000, 0x001c0000, 0x00300a00, 0x004c1e0b, 0x0071341c, 0x008c4022, 0x009e4820, 0x00ac4d1f, 0x00b04e18, 0x00af4a0f, 0x00b34e11, 0x00b04c11, 0x00ae4c15, 0x00a94e1e, 0x00a15028, 0x008a4424, 0x005f270a, 0x00340b00, 0x00180000, 0x00280c00, 0x00542305, 0x00813c15, 0x00a1481c, 0x00b04c19, 0x00b34d16, 0x00b24c13, 0x00b24d12, 0x00b34e10, 0x00b44d0c, 0x00b44c0a, 0x00b84f0d, 0x00ba5111, 0x00b64e12, 0x00b04910, 0x00b34c15, 0x00b8511b, 0x00b44d17, 0x00ac4a14, 0x00a74c20, 0x009a4c26, 0x0077371c, 0x004c1500, 0x00380400, 0x00551e00, 0x00884119, 0x00a85422, 0x00b04f16, 0x00b24a0c, 0x00b74e10, 0x00b74f12, 0x00b44f14, 0x00b14e13, 0x00b55012, 0x00b84c0b, 0x00c04c02, 0x00bb4c06, 0x00ab5219, 0x00844621, 0x003b1d0f, 0x000b0000, 0x00040000, 0x00080000, 0x00290b00, 0x006e3715, 0x00a95520, 0x00b45013, 0x00b64f18, 0x00b84f15, 0x00bb4f0e, 0x00ba4f08, 0x00b95409, 0x00be560b, 0x00c5540b, 0x00c5540f, 0x00c4561c, 0x008a350d, 0x00350f00, 0x00382318, 0x00482912, 0x003a0f00, 0x00460900, 0x00772c12, 0x00a55026, 0x00a44818, 0x00a9491f, 0x00af4c1d, 0x00b0480e, 0x00ba4a0b, 0x00c5500e, 0x00c34e0c, 0x00c45716, 0x00b85819, 0x009c511c, 0x00703a13, 0x002c0b00, 0x000c0000, 0x00070000, 0x0008090b, 0x00404446, 0x009fa2a3, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00807879, 0x004a3a3c, 0x000f0000, 0x00381804, 0x008c4414, 0x00b85c20, 0x00b5531b, 0x008f3e13, 0x002a0200, 0x001a0000, 0x00502101, 0x00a86530, 0x00b56214, 0x00be5e06, 0x00c65f0c, 0x00c45c0d, 0x00c15e18, 0x00bd5a14, 0x00c45d0e, 0x00c25906, 0x00c55c08, 0x00c0590a, 0x00bb5917, 0x00a74d18, 0x007b2c05, 0x00571300, 0x004f1000, 0x00501500, 0x005b2000, 0x006d2f08, 0x00864114, 0x009c4f1e, 0x00ac5823, 0x00b15820, 0x00b3581d, 0x00b75a1c, 0x00b75818, 0x00b85612, 0x00bc540e, 0x00bf540a, 0x00c2540b, 0x00c2540b, 0x00c1530c, 0x00be510b, 0x00bf520c, 0x00c0520c, 0x00c45008, 0x00c44f0b, 0x00be5010, 0x00bb5214, 0x00bb5212, 0x00b65415, 0x00a85019, 0x00974c1a, 0x007a3a10, 0x005c2c0b, 0x003b1c0a, 0x00230c00, 0x00160000, 0x00441400, 0x00aa5724, 0x00bd5613, 0x00c15810, 0x00bc530c, 0x00b55010, 0x00a5511d, 0x005e2a0a, 0x00260400, 0x00190000, 0x004a2c20, 0x00784c31, 0x004d280d, 0x00080000, 0x000d0000, 0x00370700, 0x009c502e, 0x00b04d1a, 0x00b94c10, 0x00b74a0f, 0x00aa4f1d, 0x0073391b, 0x002d0700, 0x001e0000, 0x005c2b14, 0x00a15226, 0x00af4d18, 0x00b34d14, 0x00b64e12, 0x00bb4d0f, 0x00bc4c0f, 0x00b94c11, 0x00b84c14, 0x00b54b14, 0x00b64d15, 0x00b54d10, 0x00ac501e, 0x00703114, 0x002e0800, 0x00110200, 0x00080000, 0x00200800, 0x005c2c13, 0x0095451e, 0x00b35320, 0x00b04d14, 0x00b65010, 0x00b85009, 0x00b64b05, 0x00b84c0b, 0x00b54d11, 0x00b24e18, 0x00a35024, 0x005c2a0e, 0x001f0600, 0x00060000, 0x000b0000, 0x003b1402, 0x0084431f, 0x00ac5119, 0x00b25014, 0x009d4c17, 0x00783d19, 0x00190000, 0x001b0000, 0x00844820, 0x00a55019, 0x00b54c18, 0x00b54a18, 0x00a85023, 0x005e2200, 0x00190200, 0x000e0000, 0x00481b0b, 0x008d4727, 0x00ae4c18, 0x00b74c0f, 0x00b04e10, 0x00a8501e, 0x0094482a, 0x00400000, 0x00510d00, 0x00a0522e, 0x00ac4d15, 0x00b8500c, 0x00c3580e, 0x00bd560c, 0x00bc5a15, 0x00853600, 0x003f1000, 0x001b0300, 0x000f0400, 0x00050300, 0x00000100, 0x00020000, 0x00090003, 0x00080000, 0x000f0000, 0x00130000, 0x00280200, 0x004c1808, 0x00743119, 0x00904220, 0x00a04c20, 0x00ac511f, 0x00b04f16, 0x00ae4b10, 0x00b44e14, 0x00b24e18, 0x00aa4a1a, 0x00a85026, 0x00984922, 0x006c3112, 0x00351500, 0x00180000, 0x00200000, 0x004c1900, 0x007f3917, 0x00a04b23, 0x00ae4d21, 0x00af4816, 0x00b44b14, 0x00b44c10, 0x00b44e0d, 0x00b34f0c, 0x00b24d0a, 0x00b04b0c, 0x00b44b13, 0x00b54c18, 0x00b24a18, 0x00b44d19, 0x00b4490f, 0x00b84e12, 0x00b64c13, 0x00ae4c1a, 0x00a24e28, 0x00874022, 0x005e2208, 0x00480f00, 0x00652400, 0x00984c1d, 0x00ac501b, 0x00b24d10, 0x00ba500f, 0x00b74c0d, 0x00b44f14, 0x00b24f15, 0x00b85014, 0x00b94d0c, 0x00c14f05, 0x00b94c06, 0x00ad511c, 0x008c4b25, 0x00442213, 0x000f0100, 0x00040000, 0x00060000, 0x001e0700, 0x005a2a0d, 0x00a65423, 0x00b45116, 0x00b64f18, 0x00b84f15, 0x00b84e0f, 0x00b84f0b, 0x00b9510b, 0x00c0550c, 0x00c7540b, 0x00c5540f, 0x00c3591e, 0x0083330b, 0x002a0800, 0x00180600, 0x001f0000, 0x00401200, 0x006f2e17, 0x009c4d2e, 0x00a64a1c, 0x00ac4914, 0x00ad4916, 0x00b34915, 0x00b84b0c, 0x00c0500c, 0x00c55410, 0x00c25615, 0x00b7561c, 0x009d4f1c, 0x0069310a, 0x002c0900, 0x000f0000, 0x00080405, 0x00070707, 0x003f4241, 0x00a0a4a6, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a59ca0, 0x00403232, 0x00100000, 0x004c240b, 0x009f4b14, 0x00c25814, 0x00be5515, 0x009a4514, 0x00431700, 0x00180000, 0x002c0800, 0x00976137, 0x00b06117, 0x00bf620b, 0x00bc5c0b, 0x00c05f10, 0x00c25d0d, 0x00be5908, 0x00c15d08, 0x00bc5904, 0x00bf5c09, 0x00bc5a0d, 0x00b65513, 0x00973e05, 0x006c1e00, 0x005f1a00, 0x0073310b, 0x00874116, 0x00a75826, 0x00ae581f, 0x00b3581c, 0x00b85716, 0x00bc5512, 0x00c0540f, 0x00c0540d, 0x00c1540e, 0x00be530f, 0x00bc510d, 0x00bc510c, 0x00be530c, 0x00c0540d, 0x00c0540c, 0x00c0530c, 0x00c0530c, 0x00c0530e, 0x00be4f0c, 0x00c15010, 0x00c05316, 0x00b35018, 0x00a8511d, 0x00994c1c, 0x0084401b, 0x006a3217, 0x004d200e, 0x002b0c00, 0x00140000, 0x00090000, 0x00080000, 0x00100000, 0x00250000, 0x008d441b, 0x00b4551c, 0x00bd5815, 0x00c0570f, 0x00be510c, 0x00ad4d10, 0x00833f14, 0x00441700, 0x00140000, 0x0040221c, 0x007c482c, 0x006c3d1d, 0x00100300, 0x00080000, 0x00260000, 0x00904d2d, 0x00ab4f1b, 0x00b64b10, 0x00b84a16, 0x00ab4d22, 0x00793f1e, 0x00330d00, 0x001a0000, 0x004d220d, 0x0098481f, 0x00b34f19, 0x00b55015, 0x00b55012, 0x00b84d10, 0x00b84c0f, 0x00bb4c12, 0x00bb4c13, 0x00ba4c16, 0x00b44b14, 0x00b04f14, 0x00a85826, 0x005c270c, 0x00200100, 0x000d0000, 0x00140000, 0x00471a04, 0x008d4727, 0x00ab4d23, 0x00b44a18, 0x00b64f18, 0x00b14b10, 0x00b64c10, 0x00b84e10, 0x00b74c0f, 0x00b24c10, 0x00ac4e16, 0x009b5228, 0x00401d06, 0x00100000, 0x00100000, 0x00190000, 0x005e2a0c, 0x00974e22, 0x00ac511f, 0x00aa4e1a, 0x00994f21, 0x00612d0d, 0x00110000, 0x00190000, 0x00814422, 0x00a8501f, 0x00b34712, 0x00b44c18, 0x009a4f25, 0x00461800, 0x00110000, 0x00100000, 0x004a1c07, 0x00924926, 0x00af4d19, 0x00b4490f, 0x00b64f1a, 0x00aa4e20, 0x00934523, 0x00480000, 0x00843010, 0x00aa4d24, 0x00b14f11, 0x00bd560c, 0x00be5807, 0x00b8580c, 0x00a85516, 0x00682400, 0x00431000, 0x004d2414, 0x0039180a, 0x00190200, 0x000b0100, 0x00040200, 0x00000000, 0x00000001, 0x00000000, 0x00060000, 0x000a0000, 0x00120000, 0x00280600, 0x004b1d08, 0x00763819, 0x00954a21, 0x00a85021, 0x00ae501b, 0x00ae4c15, 0x00af4914, 0x00b14d18, 0x00b24f1c, 0x00ad4d1b, 0x00a24f23, 0x007a3f20, 0x00441c03, 0x00220200, 0x001b0000, 0x003e1300, 0x0073371d, 0x009d4828, 0x00b04b23, 0x00b44718, 0x00ba4e18, 0x00b35013, 0x00ac4f0c, 0x00af5210, 0x00b14f10, 0x00b44710, 0x00b64815, 0x00b34b19, 0x00b24c17, 0x00b54c10, 0x00b64c0b, 0x00b64c0a, 0x00b34d0e, 0x00ab5018, 0x00a45122, 0x00944b25, 0x00702c09, 0x00601a00, 0x007d3209, 0x00a65120, 0x00b1541a, 0x00b04c08, 0x00b6500a, 0x00b44e10, 0x00b34c12, 0x00b54c14, 0x00b74d11, 0x00b85009, 0x00b64f0c, 0x00ad4c19, 0x009b4d2b, 0x00512611, 0x00130000, 0x00060000, 0x00080100, 0x00140100, 0x00461d04, 0x00a4582c, 0x00b05218, 0x00b55014, 0x00b55111, 0x00b35013, 0x00b45010, 0x00bc500b, 0x00c45309, 0x00cb5406, 0x00c7560c, 0x00ba591a, 0x007c360b, 0x001d0000, 0x00180300, 0x00350d00, 0x0070361c, 0x00974a2a, 0x00a44d28, 0x00a34618, 0x00b14f19, 0x00b34910, 0x00bc4c0c, 0x00c7540e, 0x00c5540c, 0x00c05814, 0x00b3591e, 0x008f4a1c, 0x005a2809, 0x002a0c00, 0x00110100, 0x00050000, 0x000c0808, 0x0049443d, 0x00a3a098, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00928d8f, 0x00372827, 0x00130000, 0x0057280c, 0x00ad5218, 0x00c4540c, 0x00c45412, 0x00ac531c, 0x005d2c0c, 0x00160000, 0x00240500, 0x00724422, 0x00ac601e, 0x00b85d0c, 0x00be6011, 0x00be5c0d, 0x00c15c09, 0x00c05a04, 0x00c15f0c, 0x00bc5b07, 0x00bd5c09, 0x00bc5a0d, 0x00b6550e, 0x00a74b0b, 0x00984610, 0x00a0511f, 0x00ac5e28, 0x00af5d22, 0x00b05616, 0x00b75711, 0x00bc5810, 0x00c0570e, 0x00c3550a, 0x00c25307, 0x00c15007, 0x00c05008, 0x00c15410, 0x00c05410, 0x00bf540e, 0x00bd520c, 0x00bc510a, 0x00bb520c, 0x00bb530e, 0x00b85412, 0x00b75718, 0x00b0531b, 0x00ac501d, 0x00a04b1c, 0x008c4419, 0x00763814, 0x00552406, 0x00330b00, 0x00200000, 0x00110000, 0x000a0000, 0x00070004, 0x00030000, 0x000c0300, 0x001a0400, 0x00200000, 0x00551600, 0x00ab5728, 0x00b85618, 0x00c2560e, 0x00bf4f08, 0x00b7500f, 0x009f4c18, 0x00672b0b, 0x00250100, 0x0034120d, 0x00743c21, 0x00764220, 0x00281500, 0x000d0000, 0x00210000, 0x00814628, 0x00a7501c, 0x00b44c10, 0x00b84a18, 0x00ac4c22, 0x00844422, 0x00381100, 0x00160000, 0x00411b08, 0x008d3f19, 0x00b04d1a, 0x00b04d14, 0x00b44e10, 0x00b54d10, 0x00b64c10, 0x00b84c10, 0x00b84a10, 0x00b94a13, 0x00b44b13, 0x00ac5015, 0x00a05524, 0x00502007, 0x001b0000, 0x000d0000, 0x00240800, 0x00682d11, 0x00a04e27, 0x00b44f20, 0x00b84a18, 0x00b84e18, 0x00b44b11, 0x00b64c13, 0x00b54c10, 0x00b84b10, 0x00b14b10, 0x00ac521d, 0x00884820, 0x002d1401, 0x000d0000, 0x00130000, 0x00340e00, 0x00753710, 0x00a15121, 0x00ae501f, 0x00a84e20, 0x00914b23, 0x00512305, 0x00100000, 0x00150000, 0x00783c1c, 0x00a44d20, 0x00b54b17, 0x00b14d1a, 0x008b461f, 0x003a1100, 0x000e0000, 0x000e0000, 0x004c1c05, 0x00934a26, 0x00ae4c18, 0x00b64b10, 0x00b74d19, 0x00ae4c1c, 0x00a04b23, 0x006f1b00, 0x00ac4d25, 0x00b04918, 0x00be5210, 0x00c05509, 0x00c05b0d, 0x00b25912, 0x00853e09, 0x00490c00, 0x00581d00, 0x00884e34, 0x00834a32, 0x004c1d0a, 0x001f0400, 0x00090000, 0x00020000, 0x00000000, 0x00000103, 0x00040406, 0x00000001, 0x00030000, 0x000c0000, 0x00130000, 0x002d0700, 0x005f2a0f, 0x00884420, 0x009e4d20, 0x00ac5220, 0x00b04e18, 0x00b34d18, 0x00b44c16, 0x00b44b14, 0x00ab4b18, 0x009f4f25, 0x008a4c2b, 0x00461a01, 0x00240300, 0x001f0000, 0x00380c00, 0x006c2c14, 0x009c4829, 0x00ad4d24, 0x00ab4714, 0x00ac4b10, 0x00b05314, 0x00ab4d0e, 0x00ac490c, 0x00bc4e16, 0x00be4f1b, 0x00b44b18, 0x00b24c17, 0x00b44c10, 0x00b54c0c, 0x00b54d08, 0x00b44d0a, 0x00b04f10, 0x00ab5018, 0x00a45021, 0x0099481f, 0x00873710, 0x007f2e04, 0x00913a0b, 0x00aa4f17, 0x00b45314, 0x00b24d0a, 0x00b44e10, 0x00b34c12, 0x00b44c15, 0x00b54c13, 0x00b4500c, 0x00b45010, 0x00b04c1b, 0x00a04e2a, 0x005d2a14, 0x001b0000, 0x00080000, 0x00060000, 0x00100000, 0x003f1904, 0x009e552b, 0x00ad5018, 0x00b45012, 0x00b5500f, 0x00b25013, 0x00b45010, 0x00bd500a, 0x00c65407, 0x00cb5404, 0x00c5560a, 0x00ae5114, 0x00803c10, 0x00280200, 0x00351306, 0x00743b21, 0x009d542e, 0x00a44c1f, 0x00a84714, 0x00ad4713, 0x00b34a10, 0x00bc500f, 0x00c35611, 0x00c1540e, 0x00bc5814, 0x00ac561c, 0x00833f11, 0x00562809, 0x001b0000, 0x000a0000, 0x00030000, 0x000e0c0d, 0x00464544, 0x009d9994, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007c7778, 0x002a1c1a, 0x00180000, 0x00623013, 0x00b5581c, 0x00c35208, 0x00c55510, 0x00b75921, 0x0078411d, 0x001d0000, 0x001d0000, 0x00431b00, 0x00a8602c, 0x00b45c14, 0x00c15f12, 0x00c05a09, 0x00c25b09, 0x00bf5a08, 0x00bd5c0c, 0x00bc5b0c, 0x00be5908, 0x00c05b09, 0x00bc590b, 0x00b6560a, 0x00b55710, 0x00bb5c16, 0x00bb5a11, 0x00b65408, 0x00b8590e, 0x00b8590c, 0x00b8580c, 0x00b9550b, 0x00bb5509, 0x00bc560c, 0x00bc5810, 0x00bc5914, 0x00b4520e, 0x00b85411, 0x00bc540e, 0x00bc540c, 0x00bf540c, 0x00bc5410, 0x00b65516, 0x00aa541b, 0x00944d1d, 0x00854b22, 0x00764020, 0x00582a12, 0x00341000, 0x001b0100, 0x00140000, 0x00100000, 0x000c0000, 0x000c0000, 0x00060000, 0x00050000, 0x000c0000, 0x001a0500, 0x00341000, 0x004c1d05, 0x00340000, 0x008c4520, 0x00b65417, 0x00c5560d, 0x00c4540e, 0x00b9500e, 0x00ad4c12, 0x00873a11, 0x00421308, 0x002c0200, 0x00682c12, 0x00844c2d, 0x00462b15, 0x00130000, 0x00210000, 0x00753c24, 0x00a4501c, 0x00b04c0e, 0x00b84b13, 0x00ae4c1c, 0x00904d28, 0x00421700, 0x00140000, 0x00341000, 0x007e3414, 0x00ae4f20, 0x00af4c16, 0x00b44f12, 0x00b34e10, 0x00b44e10, 0x00b64c11, 0x00b64b10, 0x00b84a10, 0x00b44c10, 0x00ad5014, 0x009a5220, 0x00441900, 0x00150000, 0x00100000, 0x00381804, 0x007f411e, 0x00a55124, 0x00b34c1a, 0x00b74913, 0x00b74d12, 0x00b54c10, 0x00b84f10, 0x00b54b0d, 0x00bb4c10, 0x00b24b14, 0x00a95528, 0x006e3514, 0x001f0800, 0x000c0000, 0x00140000, 0x004e2009, 0x008d471f, 0x00aa5221, 0x00b04c1c, 0x00aa4d20, 0x008c4621, 0x003f1400, 0x000d0000, 0x00130000, 0x006c3612, 0x00a04c1c, 0x00b44c18, 0x00b04d1e, 0x00874420, 0x003c1300, 0x00100000, 0x000e0000, 0x004d200a, 0x00944e29, 0x00a94d18, 0x00b54c10, 0x00b54a10, 0x00b24913, 0x00af4f1e, 0x009e400e, 0x00b4501b, 0x00b4470a, 0x00c8500a, 0x00c8540a, 0x00bc5812, 0x00a8571d, 0x00622000, 0x004e0f00, 0x007f371b, 0x00954728, 0x00a25430, 0x00924c2f, 0x005b2a1b, 0x00280a01, 0x00120200, 0x00050000, 0x00060103, 0x00000003, 0x00020003, 0x00060205, 0x00030000, 0x00050000, 0x00110400, 0x001c0300, 0x004b2209, 0x00743a18, 0x00994d1f, 0x00a84f1c, 0x00ae4c16, 0x00b04b15, 0x00b04c19, 0x00b14e1c, 0x00ae4c1a, 0x00a64f20, 0x0098532a, 0x00562202, 0x002a0400, 0x001c0000, 0x00350f00, 0x00633018, 0x00914c27, 0x00a75423, 0x00aa4c15, 0x00af4c12, 0x00b44f16, 0x00b0490f, 0x00b3490e, 0x00b44b10, 0x00b54b14, 0x00b44c15, 0x00b44c14, 0x00b34c12, 0x00b34c10, 0x00b14c10, 0x00b04c13, 0x00af4c16, 0x00b04f1b, 0x00b2501e, 0x00ab4819, 0x009c3909, 0x009a3806, 0x00a94814, 0x00b3511c, 0x00b04d15, 0x00b34c12, 0x00b44c12, 0x00b44c14, 0x00b44c12, 0x00b34d0c, 0x00b34e10, 0x00b04e1c, 0x00a5512c, 0x00683018, 0x00230500, 0x00080000, 0x00040000, 0x000f0000, 0x00391300, 0x009c5328, 0x00ad4f17, 0x00b44d11, 0x00b74e10, 0x00b44f10, 0x00b7500d, 0x00bd5108, 0x00c45507, 0x00c85608, 0x00c1570e, 0x00b25920, 0x00722a02, 0x00340000, 0x00682f17, 0x00a05028, 0x00aa4b14, 0x00ae4408, 0x00b94808, 0x00c14c0a, 0x00c85510, 0x00c0540d, 0x00b95611, 0x00b35b1c, 0x009c511e, 0x00713811, 0x00431800, 0x00140000, 0x000e0000, 0x00060200, 0x00131414, 0x00454a4a, 0x00a7acac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00686566, 0x00221412, 0x001f0500, 0x006d3918, 0x00b85a1b, 0x00c75409, 0x00c8570f, 0x00b8571b, 0x008d4d23, 0x00381000, 0x00190000, 0x00230000, 0x008c4f24, 0x00b15c20, 0x00be5b0e, 0x00c45905, 0x00c35c08, 0x00bf5a08, 0x00ba580c, 0x00bc5a0f, 0x00bc5608, 0x00be5808, 0x00bd5a0c, 0x00be5c0d, 0x00bd5c0c, 0x00bb5606, 0x00be5403, 0x00c35808, 0x00bc5607, 0x00bb5809, 0x00bc580c, 0x00bc590e, 0x00ba5910, 0x00b85810, 0x00b35612, 0x00af5514, 0x00b05818, 0x00b25819, 0x00b25518, 0x00af5216, 0x00aa5118, 0x00a14f1a, 0x0092481a, 0x007e411a, 0x00572b0c, 0x00341500, 0x00190000, 0x000f0000, 0x000a0000, 0x00050000, 0x00030000, 0x00030000, 0x00090300, 0x00060000, 0x000a0000, 0x00140200, 0x00290c00, 0x0060351c, 0x008c5430, 0x008b4f2d, 0x00360200, 0x00551800, 0x00a95019, 0x00be5611, 0x00c65713, 0x00c2530f, 0x00b9500e, 0x00a24a18, 0x00642814, 0x00350300, 0x00591a01, 0x008c5236, 0x005c3b27, 0x00170000, 0x00230000, 0x00703823, 0x00a2501f, 0x00af4c0e, 0x00b84c10, 0x00ae4c16, 0x009c5229, 0x004c1c00, 0x00140000, 0x00250400, 0x006e2c10, 0x00a85028, 0x00ae4c18, 0x00b14e13, 0x00b04e10, 0x00b14f10, 0x00b44e14, 0x00b54c12, 0x00b64c10, 0x00b44e10, 0x00ac5016, 0x00975020, 0x003c1500, 0x00140000, 0x00130000, 0x004d2910, 0x008e4c24, 0x00a8501d, 0x00b04b14, 0x00b4490f, 0x00b54b0d, 0x00b54b0c, 0x00b84f0f, 0x00b54b0c, 0x00ba4c11, 0x00b24e1b, 0x009c522c, 0x00502108, 0x00180400, 0x000c0000, 0x00240300, 0x00683115, 0x009e5026, 0x00ae501e, 0x00b34918, 0x00ae4d23, 0x00874322, 0x00300700, 0x000b0000, 0x00100000, 0x0064300c, 0x009d4f1c, 0x00af4b18, 0x00ad4c1f, 0x00904929, 0x00461803, 0x00140000, 0x00130000, 0x004d1c05, 0x00924c25, 0x00a74c16, 0x00b44e10, 0x00b74c10, 0x00b6480f, 0x00b64d15, 0x00b54f14, 0x00b24909, 0x00c0520c, 0x00cc540b, 0x00c8510b, 0x00b65820, 0x00863b11, 0x00480b00, 0x0060200a, 0x00974424, 0x00ab4c24, 0x00ab4a1e, 0x00a64c26, 0x00954e34, 0x006b3422, 0x00371200, 0x00110000, 0x000a0000, 0x000a0104, 0x00060001, 0x00020001, 0x00010004, 0x00030206, 0x00000000, 0x00060000, 0x00100000, 0x00391400, 0x0067300e, 0x00874018, 0x009c4b1e, 0x00a44d20, 0x00a54e20, 0x00a84e20, 0x00ae4e1c, 0x00aa4c18, 0x009a4515, 0x00944d25, 0x005b290c, 0x002b0800, 0x00180000, 0x00270a00, 0x005a2c0e, 0x0091512a, 0x00a75020, 0x00ab4813, 0x00b54c16, 0x00b54c12, 0x00b44c10, 0x00b24a0d, 0x00b54c12, 0x00b54b14, 0x00b44c15, 0x00b34c15, 0x00b14c14, 0x00b14c14, 0x00b24b14, 0x00b24b14, 0x00b44b13, 0x00b34811, 0x00b54b15, 0x00b44a16, 0x00ad4612, 0x00af4816, 0x00b04d1c, 0x00b04c18, 0x00b34c14, 0x00b44c12, 0x00b44c14, 0x00b44c12, 0x00b34d0c, 0x00b24d10, 0x00b04e1c, 0x00a6522c, 0x0071351c, 0x002e0a00, 0x00090000, 0x00030000, 0x000e0000, 0x00350f00, 0x009d5228, 0x00b2511a, 0x00b54c13, 0x00b74c10, 0x00b74c0d, 0x00b84e0a, 0x00bd5108, 0x00c45507, 0x00c55708, 0x00be5714, 0x009f4b17, 0x006c2300, 0x00511000, 0x00904724, 0x00ab4c17, 0x00b44807, 0x00bf4f09, 0x00c7540e, 0x00c4510c, 0x00c25510, 0x00b55414, 0x00a6541b, 0x008b491b, 0x00562502, 0x00250400, 0x00110000, 0x000f0300, 0x00030000, 0x001c1c1e, 0x005a5e60, 0x00adb4b5, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005c595a, 0x001c0e0b, 0x00270b00, 0x00743e18, 0x00bb5c1a, 0x00ca5709, 0x00cb570c, 0x00bc5615, 0x00a05724, 0x005b2c08, 0x00150000, 0x00140000, 0x00572402, 0x00a25820, 0x00bc5a0b, 0x00c65b00, 0x00c15901, 0x00c15c09, 0x00bc580d, 0x00bd5911, 0x00c15a10, 0x00bd580d, 0x00b6570d, 0x00b7590f, 0x00b9580e, 0x00b8540a, 0x00bd530a, 0x00c7580f, 0x00c25307, 0x00c05205, 0x00bc5208, 0x00b9530c, 0x00b75511, 0x00b45616, 0x00b05619, 0x00ac561c, 0x00a9541c, 0x00a55420, 0x009c5025, 0x008c4b27, 0x00774025, 0x00592c18, 0x00361004, 0x00190000, 0x00130100, 0x00080000, 0x00040000, 0x00020000, 0x00010200, 0x00000000, 0x00000102, 0x00050706, 0x00010000, 0x000a0000, 0x001b0400, 0x00431d05, 0x007c4320, 0x009f562a, 0x00a95520, 0x00a35424, 0x005a2205, 0x00340000, 0x00873e12, 0x00b3591e, 0x00c0540f, 0x00c6540a, 0x00c2540c, 0x00af4e15, 0x00843d1d, 0x004e1300, 0x004c0c00, 0x00854c33, 0x006c442e, 0x00230100, 0x00270000, 0x006c3420, 0x00a05020, 0x00ae4d0e, 0x00b94c0e, 0x00b04a11, 0x00a35428, 0x00582204, 0x00180000, 0x00180000, 0x005b210d, 0x00984b28, 0x00ab4e1d, 0x00b04c13, 0x00ae4d0c, 0x00af4e0d, 0x00b24c14, 0x00b44c14, 0x00b54c10, 0x00b34e11, 0x00aa5019, 0x00924e22, 0x00371300, 0x00150000, 0x001f0300, 0x00603419, 0x009c5328, 0x00ac501b, 0x00b24c14, 0x00b74c10, 0x00b84b0e, 0x00b74a0c, 0x00b64d0d, 0x00b44b0c, 0x00b5480e, 0x00b05022, 0x0085472a, 0x00361000, 0x00100100, 0x000d0000, 0x00401800, 0x00814221, 0x00a85124, 0x00b14b17, 0x00b54715, 0x00b04d24, 0x007f3f21, 0x00240000, 0x00080000, 0x000c0000, 0x00592b04, 0x009e5321, 0x00ac4b18, 0x00ac4c20, 0x00984e2d, 0x00531c04, 0x001c0000, 0x00200000, 0x00571f04, 0x00924820, 0x00a64d16, 0x00b25011, 0x00b94f13, 0x00b94b0f, 0x00b6480c, 0x00b84b0b, 0x00b94c06, 0x00c5560c, 0x00cc580c, 0x00c05212, 0x00a6532a, 0x00581600, 0x004a0f00, 0x0077341b, 0x00a95026, 0x00b24a18, 0x00b84918, 0x00b64a1c, 0x00a74822, 0x009d4c2b, 0x007f4020, 0x00461800, 0x00180000, 0x000b0000, 0x00080000, 0x00080001, 0x00060207, 0x00000005, 0x00000005, 0x00050106, 0x00060000, 0x000d0000, 0x001a0000, 0x003c1400, 0x00683519, 0x00844c2a, 0x008f502a, 0x00965028, 0x009a4a20, 0x00a85225, 0x00ae5323, 0x00a34d20, 0x0098532c, 0x005a2b0b, 0x00280f00, 0x000e0000, 0x00270b00, 0x005a2c15, 0x00924824, 0x00ac5023, 0x00ae4710, 0x00b0460a, 0x00b85014, 0x00b14b0f, 0x00b44c12, 0x00b44c14, 0x00b34c15, 0x00b24b14, 0x00b24b16, 0x00b44a16, 0x00b44a14, 0x00b44a13, 0x00b54a11, 0x00b44910, 0x00b74c13, 0x00b64a14, 0x00b24812, 0x00b44b18, 0x00b74d1c, 0x00b04816, 0x00b44b13, 0x00b44c12, 0x00b44c12, 0x00b44c10, 0x00b44c0e, 0x00b24d10, 0x00af4d19, 0x00a55027, 0x007c3a1c, 0x00391100, 0x000b0000, 0x00020000, 0x000d0000, 0x00340e00, 0x009d5228, 0x00b3521b, 0x00b44c16, 0x00b64b10, 0x00b84b0c, 0x00b94c08, 0x00c05008, 0x00c45408, 0x00c4560d, 0x00bb5818, 0x009c4c1f, 0x00641f00, 0x00540900, 0x009a461a, 0x00b74f13, 0x00c45410, 0x00c2530f, 0x00c05814, 0x00b95a1a, 0x00ac5820, 0x009c5426, 0x00703714, 0x00320b00, 0x00130000, 0x000a0000, 0x00080300, 0x000e0c08, 0x00292827, 0x00707072, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00545054, 0x00180a07, 0x002c0e00, 0x00794018, 0x00bc5c17, 0x00c85404, 0x00ca5407, 0x00c45813, 0x00af5d22, 0x007c441b, 0x00160000, 0x00100000, 0x00240000, 0x0081471b, 0x00b45d15, 0x00c15d07, 0x00bc5600, 0x00c25c0a, 0x00bc580e, 0x00bb5610, 0x00bc5814, 0x00bb5915, 0x00b45c1a, 0x00b15c1a, 0x00b35a18, 0x00b65a19, 0x00b85719, 0x00b65416, 0x00be591c, 0x00ba5819, 0x00b65618, 0x00b0561b, 0x00aa5822, 0x00a45827, 0x009d5628, 0x00975429, 0x008a491f, 0x00713610, 0x004c1a00, 0x002d0500, 0x00170000, 0x000d0000, 0x000b0000, 0x00080000, 0x00060000, 0x00050100, 0x00020300, 0x00000200, 0x00000404, 0x00000203, 0x00000001, 0x00030000, 0x00080000, 0x00210900, 0x00592c0f, 0x00905028, 0x00aa5726, 0x00b4531a, 0x00b95113, 0x00ae5018, 0x0091502a, 0x00400900, 0x00511600, 0x009c5221, 0x00b85714, 0x00c4540a, 0x00c3540b, 0x00b45010, 0x009f4e23, 0x00702c0c, 0x00501000, 0x00743c20, 0x0078482f, 0x003a0f00, 0x002a0000, 0x006c321e, 0x00a05020, 0x00af4d10, 0x00b74d0c, 0x00b04b0d, 0x00a65123, 0x00682c0c, 0x00220500, 0x00120000, 0x00441607, 0x00823f22, 0x00a85024, 0x00ad4b13, 0x00af4e0f, 0x00b04d0d, 0x00b24c14, 0x00b34c15, 0x00b44a0f, 0x00b14c13, 0x00a74d1b, 0x008d4a24, 0x00341100, 0x00150000, 0x002d0c00, 0x006e3b1f, 0x00a15025, 0x00af4d18, 0x00b44d14, 0x00b74c10, 0x00b94b10, 0x00b84a10, 0x00b44c0f, 0x00b24c10, 0x00b24913, 0x00ab532a, 0x00683420, 0x00210600, 0x000c0000, 0x00170000, 0x005f2c10, 0x00974d26, 0x00ad4f1d, 0x00b44814, 0x00b94816, 0x00ac4b24, 0x0074381f, 0x001b0000, 0x00050000, 0x000b0000, 0x004d2200, 0x009c5422, 0x00ac4c1c, 0x00af4b1e, 0x00a04e2a, 0x00682508, 0x003c0700, 0x00491400, 0x007c3916, 0x009f5022, 0x00aa5018, 0x00ae4c0f, 0x00b44b0f, 0x00b8490d, 0x00b94809, 0x00bc4b06, 0x00c05004, 0x00c5560a, 0x00c2540d, 0x00bc5b24, 0x007a3013, 0x00440800, 0x0062250c, 0x00954c29, 0x00a84c19, 0x00b64c13, 0x00b5440f, 0x00b84614, 0x00b84d1b, 0x00af4c1d, 0x00a14c22, 0x00944e2c, 0x005a2b13, 0x00280800, 0x00130000, 0x000d0000, 0x00060000, 0x00020003, 0x0004040a, 0x00000006, 0x00050107, 0x00080003, 0x00080000, 0x000d0000, 0x00130000, 0x001f0000, 0x00381100, 0x0054250a, 0x00773c22, 0x00894727, 0x009b4d29, 0x00994c23, 0x00944a21, 0x00915632, 0x00542c12, 0x002c1000, 0x00150000, 0x00280400, 0x005c230b, 0x00924623, 0x00ac5120, 0x00b04b14, 0x00af4810, 0x00b14b10, 0x00b24c11, 0x00b24c11, 0x00b24c13, 0x00b24b14, 0x00b44a16, 0x00b44a16, 0x00b44a16, 0x00b44a14, 0x00b44c14, 0x00b44b11, 0x00b54c13, 0x00b54c13, 0x00b44a13, 0x00b44a14, 0x00b74b18, 0x00b54b17, 0x00b44a13, 0x00b44b11, 0x00b44c12, 0x00b44c10, 0x00b44c10, 0x00b24d12, 0x00ae4c18, 0x00a44f24, 0x00863f1f, 0x00451802, 0x000a0000, 0x00000000, 0x000d0000, 0x003a1100, 0x009d5126, 0x00b04f18, 0x00b34d18, 0x00b54c12, 0x00b84a0c, 0x00bc4c08, 0x00c24f08, 0x00c5540c, 0x00c45710, 0x00b8581c, 0x008c441c, 0x00511200, 0x00651c00, 0x00b35f30, 0x00b8561c, 0x00bc5719, 0x00b65820, 0x00ab5825, 0x009e5a2c, 0x00683009, 0x00360900, 0x00190000, 0x000e0000, 0x000b0200, 0x00070602, 0x000a0c08, 0x0042433f, 0x009c9c9b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004e4c4f, 0x00140701, 0x00311000, 0x007d4115, 0x00bc5a15, 0x00c85202, 0x00ca5204, 0x00c8580e, 0x00b75b1a, 0x00945425, 0x00260a00, 0x000a0000, 0x000d0000, 0x00472408, 0x0095551e, 0x00b15d14, 0x00b8580b, 0x00bf5a0a, 0x00ba560c, 0x00ba5712, 0x00b95819, 0x00b0571c, 0x00ac5b24, 0x00a95e2b, 0x00a75c2a, 0x00a85d2c, 0x00a95d32, 0x00a3582f, 0x009f5834, 0x00995630, 0x00945027, 0x00884821, 0x00743d1e, 0x00592e13, 0x003d1c06, 0x002e1000, 0x001b0000, 0x00180000, 0x00130000, 0x000f0000, 0x00080100, 0x00050000, 0x00090000, 0x000f0000, 0x00110000, 0x000f0000, 0x00050000, 0x00000000, 0x00010205, 0x00000001, 0x00080000, 0x00180000, 0x00381400, 0x007a441e, 0x00a65928, 0x00b05118, 0x00bb4c10, 0x00c04d0e, 0x00bc4c0c, 0x00b45116, 0x00aa5a2a, 0x00692900, 0x00350300, 0x006a300a, 0x00a85319, 0x00bf5a14, 0x00c1570e, 0x00bf5813, 0x00ae551e, 0x008f4318, 0x00682805, 0x00642b0c, 0x00824c2c, 0x00501d01, 0x002c0000, 0x00743821, 0x00a34f23, 0x00af4c12, 0x00b44c09, 0x00b14c0c, 0x00a9501d, 0x00783616, 0x00300e04, 0x00100000, 0x002a0800, 0x00643018, 0x00a2522a, 0x00aa4b16, 0x00b25012, 0x00b44e10, 0x00b44c14, 0x00b44b14, 0x00b34a12, 0x00b04c17, 0x00a44c21, 0x00894727, 0x00320e00, 0x00160000, 0x003e1506, 0x007c3f25, 0x00a44c21, 0x00b04a16, 0x00b24b14, 0x00b44910, 0x00ba4912, 0x00b94a14, 0x00b34a12, 0x00b14d18, 0x00ad4c19, 0x009d502c, 0x00441b10, 0x00160000, 0x000e0000, 0x00331300, 0x007a3c1c, 0x00a34f23, 0x00b04c16, 0x00b64810, 0x00b84817, 0x00a44820, 0x0064301a, 0x00140000, 0x00040000, 0x000c0000, 0x00461c00, 0x00985022, 0x00ad4d1d, 0x00b24b1c, 0x00a94d21, 0x008b3912, 0x00772e0a, 0x00823915, 0x00a35025, 0x00ac5121, 0x00af511a, 0x00ac4a10, 0x00af480e, 0x00b3480c, 0x00bd4d0e, 0x00c2510b, 0x00ca5506, 0x00c85b10, 0x00b45719, 0x00984a1e, 0x004c0c00, 0x00501400, 0x00803a14, 0x00a4521f, 0x00aa4d11, 0x00b04e10, 0x00b44c18, 0x00b44a16, 0x00b2440c, 0x00b44910, 0x00b75020, 0x00a84a1f, 0x00a2522b, 0x007c3b1b, 0x00451400, 0x001e0000, 0x00100000, 0x000a0000, 0x00020000, 0x00000001, 0x00000000, 0x00000000, 0x00000001, 0x00020000, 0x00080001, 0x00090000, 0x000c0000, 0x00140000, 0x001b0000, 0x001d0000, 0x00370f00, 0x0068381f, 0x008f5031, 0x00975332, 0x00975437, 0x00672e18, 0x002f0800, 0x00170000, 0x00240000, 0x00502009, 0x008c4423, 0x00ac5328, 0x00ad4916, 0x00b74e16, 0x00b14b0f, 0x00b14c0e, 0x00b14b0f, 0x00b44b11, 0x00b44a14, 0x00b44a16, 0x00b24b17, 0x00b04c17, 0x00af4c17, 0x00ac4b14, 0x00ac4c13, 0x00b25018, 0x00b55017, 0x00b24910, 0x00b4460e, 0x00ba4c14, 0x00b44b11, 0x00b34a10, 0x00b34a10, 0x00b34b0f, 0x00b24c11, 0x00b04d15, 0x00ac4d18, 0x00a54e20, 0x00904422, 0x00511e08, 0x000a0000, 0x00040100, 0x00110000, 0x00441808, 0x00a05327, 0x00ad4c15, 0x00ae4d16, 0x00b14c13, 0x00b84b0c, 0x00be4c09, 0x00c7500c, 0x00c95410, 0x00c55612, 0x00b55820, 0x00783913, 0x00400c00, 0x006f310c, 0x00a86439, 0x00a85c2c, 0x00aa5e33, 0x008c4b2b, 0x0058250c, 0x00260400, 0x00140000, 0x00100000, 0x000e0300, 0x00040000, 0x00000000, 0x00282828, 0x00757575, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004c4a4c, 0x00120400, 0x00341000, 0x00814215, 0x00bb5914, 0x00cc5604, 0x00cc5405, 0x00c95609, 0x00b9560e, 0x00a65f28, 0x003b1b06, 0x00090000, 0x00060000, 0x00140000, 0x0073411c, 0x00a05820, 0x00b65c18, 0x00ba560c, 0x00b7530b, 0x00bb5a18, 0x00a0480c, 0x00803000, 0x00692400, 0x00612300, 0x00561c00, 0x004e1700, 0x00491400, 0x00400f00, 0x00340900, 0x002e0400, 0x002b0000, 0x00260000, 0x001d0000, 0x00150000, 0x000c0000, 0x00080000, 0x000a0000, 0x00080000, 0x00050000, 0x00050000, 0x00050000, 0x000b0000, 0x00200800, 0x00321401, 0x00401e11, 0x00280f06, 0x000a0100, 0x00010000, 0x00040003, 0x00080000, 0x00220400, 0x004a1c05, 0x00874821, 0x00a1541d, 0x00b35114, 0x00bc4c0c, 0x00c54e0e, 0x00c44c0c, 0x00bc4b0c, 0x00ba5216, 0x00ac5018, 0x009e5322, 0x004e1700, 0x00400a00, 0x008a4212, 0x00b25a1e, 0x00b9540f, 0x00be570e, 0x00b45414, 0x00a6501a, 0x00873f14, 0x00632200, 0x008c4d27, 0x00602504, 0x002d0000, 0x007c4028, 0x00a54d26, 0x00b04b15, 0x00b34a08, 0x00b24c0c, 0x00ac501d, 0x00863c1d, 0x003a1408, 0x00100000, 0x00140000, 0x0049240f, 0x0098512c, 0x00a44918, 0x00b44e15, 0x00b54c10, 0x00b44814, 0x00b24814, 0x00b44c15, 0x00b04c1b, 0x00a44b24, 0x00884428, 0x00320c00, 0x00180000, 0x004c1b0a, 0x00864125, 0x00ab4d23, 0x00b64c18, 0x00b44c15, 0x00b24810, 0x00ba4815, 0x00b94918, 0x00b04814, 0x00ac4e1b, 0x00a24b1c, 0x008a4828, 0x00250500, 0x000d0000, 0x00140000, 0x00532811, 0x00904723, 0x00ab4e1d, 0x00b14b10, 0x00b54b0f, 0x00b64a17, 0x009b441d, 0x00582a17, 0x00100000, 0x00030000, 0x000e0000, 0x00481c00, 0x00934d23, 0x00ac4c1e, 0x00b4491a, 0x00ae4b19, 0x00a74b18, 0x00a34c1c, 0x00a85021, 0x00ad4d1d, 0x00aa4714, 0x00b14d18, 0x00b14c14, 0x00b44b13, 0x00b4490d, 0x00c05010, 0x00c4530b, 0x00ca5408, 0x00bf5710, 0x00a95b2a, 0x005e2000, 0x00410600, 0x0068280a, 0x00a25222, 0x00a74d12, 0x00aa4e0e, 0x00af5114, 0x00aa4b14, 0x00ad4914, 0x00b64b10, 0x00b6480e, 0x00b64815, 0x00b24818, 0x00ab4a1c, 0x00a34d24, 0x00954e2c, 0x0070381c, 0x003c1200, 0x00200400, 0x00140200, 0x000a0000, 0x00080000, 0x00070100, 0x00040000, 0x00020001, 0x00040004, 0x00030004, 0x00030005, 0x00050004, 0x00090000, 0x000c0000, 0x00100000, 0x00160000, 0x00330800, 0x00692f15, 0x008c462e, 0x0091503b, 0x00633224, 0x00280500, 0x00150000, 0x001e0100, 0x00491904, 0x008c482a, 0x00ac5028, 0x00ac4817, 0x00af4c12, 0x00b04c0f, 0x00b14b10, 0x00b34a12, 0x00b44b14, 0x00b44a16, 0x00b24c19, 0x00b04c19, 0x00ac4d17, 0x00ae5018, 0x00aa4c14, 0x00a94b10, 0x00b04e14, 0x00b34c12, 0x00b3480d, 0x00b54a10, 0x00b54b14, 0x00b34a12, 0x00b1480f, 0x00b24910, 0x00b24c13, 0x00b04c17, 0x00ac4d18, 0x00a64d20, 0x00974826, 0x0057210a, 0x000c0000, 0x00080200, 0x00180000, 0x0050200c, 0x00a65528, 0x00ad4c15, 0x00ac4c16, 0x00af4c14, 0x00b84b0c, 0x00bf4d0a, 0x00c9510c, 0x00cc5510, 0x00c45714, 0x00b15821, 0x00673110, 0x003c1500, 0x006b3c1e, 0x007d4b28, 0x00683210, 0x00431000, 0x00270000, 0x00190000, 0x00090000, 0x00030000, 0x00040100, 0x00000000, 0x00161815, 0x005d6060, 0x00a2a3a6, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0048484a, 0x00100400, 0x00371300, 0x00804013, 0x00bc5b14, 0x00ca5503, 0x00cc5304, 0x00cb5508, 0x00c25a0d, 0x00a45519, 0x00653e24, 0x000c0000, 0x00090000, 0x000d0000, 0x003a1400, 0x008e502c, 0x00b05a20, 0x00b85411, 0x00b8550f, 0x00b45818, 0x0091440d, 0x00642400, 0x003c0400, 0x002a0000, 0x00250000, 0x001c0000, 0x00140000, 0x00140000, 0x00100000, 0x00100000, 0x00100000, 0x000c0000, 0x000a0000, 0x00080000, 0x00050000, 0x00080100, 0x00060000, 0x00050000, 0x00060000, 0x000a0000, 0x001f0600, 0x0050280e, 0x00834921, 0x0090542f, 0x00845844, 0x002b0d06, 0x000a0000, 0x00070204, 0x00080000, 0x00230800, 0x00602c16, 0x00914921, 0x00a95319, 0x00b25110, 0x00b8500e, 0x00bc4e0e, 0x00be4c13, 0x00be4c14, 0x00ba4c13, 0x00b74f13, 0x00b34e11, 0x00b05820, 0x00863e14, 0x004a0b00, 0x00581a00, 0x00974e22, 0x00b85819, 0x00c05810, 0x00bf5811, 0x00b15210, 0x009d4913, 0x008b3e0e, 0x008b4014, 0x006a2803, 0x00300000, 0x00874b31, 0x00a84c28, 0x00b14816, 0x00b44c0d, 0x00b34f0f, 0x00a84817, 0x00994c2a, 0x0046180b, 0x00120000, 0x000a0000, 0x002d1502, 0x00753b1a, 0x00a34f23, 0x00b34f1c, 0x00b54713, 0x00bc4e1c, 0x00b24613, 0x00b64c18, 0x00ac4818, 0x00a94e26, 0x00823a1e, 0x00350800, 0x00200000, 0x00571e08, 0x00914424, 0x00ae4c1e, 0x00b34813, 0x00b54c16, 0x00b44a14, 0x00b84614, 0x00b84918, 0x00b04c18, 0x00a74f1e, 0x009e5529, 0x00521d01, 0x001c0300, 0x000d0000, 0x00240300, 0x00733c21, 0x00a24d25, 0x00af4b18, 0x00b64e12, 0x00b24a0d, 0x00b04c16, 0x0094471e, 0x004a2412, 0x000f0100, 0x00040000, 0x000d0000, 0x00441800, 0x00934e28, 0x00ac4c21, 0x00b64b1a, 0x00b24b14, 0x00b04a11, 0x00b25018, 0x00ac4813, 0x00b44a16, 0x00b54916, 0x00b44914, 0x00b64c14, 0x00b44810, 0x00b84b0c, 0x00c55510, 0x00c7560c, 0x00c5560c, 0x00bd5d20, 0x00713211, 0x003d0c00, 0x005c2408, 0x008a451e, 0x00a84d17, 0x00b04e10, 0x00af4e14, 0x00ab4e14, 0x00a74d12, 0x00a74c13, 0x00af4b15, 0x00b54c18, 0x00b64919, 0x00b14719, 0x00ad491c, 0x00aa4b1e, 0x00a74b1d, 0x00a04c1f, 0x00954a20, 0x007d3f1a, 0x005c2c0e, 0x00401c04, 0x00240800, 0x00180100, 0x00110000, 0x000f0000, 0x000c0000, 0x000a0000, 0x00090000, 0x00050003, 0x00040007, 0x00010004, 0x00020001, 0x00070000, 0x00110000, 0x001f0100, 0x00431506, 0x006b3526, 0x00814d3f, 0x005d3328, 0x002a140b, 0x000b0000, 0x00120000, 0x00441d0c, 0x00863f25, 0x00a84f2a, 0x00a94a15, 0x00ae4c12, 0x00b04d15, 0x00b14c16, 0x00b14a16, 0x00b14918, 0x00b04a18, 0x00ae4a15, 0x00af4c16, 0x00ae4d13, 0x00ac4e13, 0x00ac4f11, 0x00ae4e11, 0x00b04c11, 0x00b14c13, 0x00b24b14, 0x00b14a14, 0x00b34c14, 0x00b44c12, 0x00b24910, 0x00b04913, 0x00b04c16, 0x00ac4d18, 0x00a54c20, 0x00974826, 0x005d260f, 0x00110000, 0x00080000, 0x00230400, 0x0068331c, 0x00a04c1f, 0x00b2511a, 0x00ac4e17, 0x00ae4d14, 0x00b54b0c, 0x00c4520d, 0x00c54e06, 0x00cc5610, 0x00c05714, 0x00a14f1a, 0x00502408, 0x001e0400, 0x00240700, 0x00220500, 0x001f0300, 0x00150000, 0x000a0000, 0x00050001, 0x00020003, 0x00010002, 0x001b191a, 0x00585857, 0x009ea09d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0048484c, 0x00100400, 0x00341100, 0x007f4012, 0x00bc5a15, 0x00cb5605, 0x00cc5505, 0x00ca5506, 0x00c4590a, 0x00ac5818, 0x00784828, 0x00150000, 0x00080000, 0x000a0000, 0x00200300, 0x0064301a, 0x00a45424, 0x00ba591a, 0x00bb5811, 0x00b45713, 0x00a6581f, 0x00985324, 0x00894b24, 0x00784120, 0x00603118, 0x00411c04, 0x002b0b00, 0x001f0400, 0x00170000, 0x00110000, 0x000e0000, 0x000c0000, 0x000c0000, 0x000d0000, 0x00140300, 0x00221008, 0x0030231c, 0x001e0f09, 0x00110000, 0x00250800, 0x005a2d13, 0x00884b26, 0x00a45829, 0x009b552b, 0x005c2e1c, 0x00200600, 0x00100100, 0x000a0000, 0x00290e06, 0x005e301c, 0x00914822, 0x00ad531e, 0x00b5500d, 0x00b85008, 0x00b84f0c, 0x00b94f11, 0x00b94e15, 0x00b84c16, 0x00b84e13, 0x00b84e12, 0x00bb5013, 0x00b24c14, 0x00a44c1f, 0x00732904, 0x00450700, 0x00682704, 0x00a95320, 0x00bb5717, 0x00bc540c, 0x00c05810, 0x00b75414, 0x00a64b12, 0x009b4618, 0x00752c06, 0x003c0400, 0x00905134, 0x00aa4b28, 0x00b44819, 0x00b44c10, 0x00b14f10, 0x00ac4a1a, 0x009f4e2b, 0x00582412, 0x001f0200, 0x00080000, 0x00140600, 0x00502106, 0x00994f2c, 0x00a8481e, 0x00b24618, 0x00b34616, 0x00b54817, 0x00b44a16, 0x00ae4b19, 0x00a84c21, 0x00803311, 0x003c0700, 0x002f0000, 0x00632003, 0x0097431d, 0x00af4a19, 0x00b44812, 0x00b44c14, 0x00b44b13, 0x00b74814, 0x00b44815, 0x00ad4c19, 0x00a35021, 0x008f522a, 0x00360d00, 0x00120000, 0x00120000, 0x00481c0c, 0x00854224, 0x00a84b20, 0x00b34915, 0x00b34b0e, 0x00af4a0c, 0x00ab4d16, 0x008e461e, 0x0042200f, 0x000a0000, 0x00040000, 0x000f0000, 0x00441600, 0x00944c2b, 0x00ac4c24, 0x00b44a18, 0x00b44b11, 0x00b24a0d, 0x00b44f11, 0x00b2480d, 0x00b74810, 0x00b94712, 0x00b54610, 0x00b74810, 0x00b9480f, 0x00c15211, 0x00ca5b12, 0x00bf540c, 0x00b75615, 0x00974a1c, 0x00411300, 0x00280200, 0x006e3c21, 0x009c5832, 0x00a24715, 0x00b04b15, 0x00ac4b15, 0x00ab4d15, 0x00aa5011, 0x00ac4f13, 0x00ac4a14, 0x00ad4716, 0x00b04617, 0x00b24818, 0x00b04b1c, 0x00ae4b1b, 0x00ad4914, 0x00ac4a14, 0x00ab4d18, 0x00a54f1d, 0x00984c23, 0x00894824, 0x0080492a, 0x00704027, 0x005f321c, 0x004b2310, 0x00340f02, 0x00220200, 0x00180000, 0x000f0000, 0x00060000, 0x00050004, 0x00040102, 0x00010000, 0x00020000, 0x00060000, 0x00140000, 0x00290800, 0x00471f16, 0x00603f35, 0x0041312a, 0x00140c05, 0x000b0300, 0x00170000, 0x00411002, 0x007f3921, 0x00a35228, 0x00a84f1c, 0x00aa4c1b, 0x00ac4919, 0x00af4818, 0x00b24817, 0x00b34815, 0x00b34a14, 0x00b24c13, 0x00b04c11, 0x00af4d11, 0x00ae4d13, 0x00ae4d13, 0x00ae4d14, 0x00b04c16, 0x00b04c16, 0x00b14c16, 0x00b24b14, 0x00b34a12, 0x00b14b12, 0x00b14c14, 0x00b04d18, 0x00ae4c18, 0x00a54c20, 0x00964827, 0x005a240d, 0x00120000, 0x000c0000, 0x00300b00, 0x00814429, 0x00a44c1f, 0x00af4e17, 0x00ab4c15, 0x00b04f14, 0x00b64c0b, 0x00c1500a, 0x00c85005, 0x00c8560c, 0x00bc5a18, 0x00863e0e, 0x00381400, 0x00100000, 0x00100000, 0x000a0000, 0x00090000, 0x00040000, 0x00010004, 0x00040509, 0x00302f31, 0x00686768, 0x009e9c9d, 0x001f1f1f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004c4c50, 0x00130703, 0x00310e00, 0x007c3e11, 0x00ba5a15, 0x00c85506, 0x00cc5507, 0x00c95407, 0x00c65909, 0x00b45a17, 0x008f552d, 0x00280600, 0x000d0000, 0x000c0000, 0x000d0000, 0x00381101, 0x008e461e, 0x00b5581c, 0x00bc560d, 0x00bc560c, 0x00b05410, 0x00b0581a, 0x00b0571e, 0x00a9531f, 0x00a04f1d, 0x00984c1b, 0x00904917, 0x00864617, 0x00743a12, 0x0062300f, 0x004e2308, 0x00471c03, 0x00491c02, 0x0054270b, 0x00673921, 0x006d4531, 0x004f3022, 0x002a0b00, 0x002a0000, 0x0059240b, 0x00944f2b, 0x00a85830, 0x00ad5933, 0x008c482b, 0x002c0a00, 0x00100000, 0x00100000, 0x00200200, 0x00623217, 0x00944e28, 0x00ae521c, 0x00bb5413, 0x00b9500a, 0x00b9500a, 0x00b55010, 0x00b35014, 0x00b44f16, 0x00b54f14, 0x00b74f10, 0x00b84e0f, 0x00bb4c10, 0x00b74c13, 0x00b85120, 0x00a0471f, 0x00621a00, 0x00480700, 0x00782d0a, 0x00aa5422, 0x00bb5310, 0x00c8580c, 0x00c35208, 0x00b9500e, 0x00a44818, 0x007a2b09, 0x00460a00, 0x00955234, 0x00ac4926, 0x00b44718, 0x00b44c10, 0x00af4c0f, 0x00ad4b1b, 0x00a34d28, 0x006f331c, 0x002e0900, 0x00090000, 0x00080000, 0x00300d00, 0x00733619, 0x00a44e2c, 0x00ad4923, 0x00b0471a, 0x00b54c1a, 0x00af4914, 0x00ae4c16, 0x00a84b1a, 0x00923f16, 0x00702f0c, 0x006c2e0f, 0x008b3f1a, 0x00a64d20, 0x00af4914, 0x00b44b10, 0x00b44b11, 0x00b34a10, 0x00b54a11, 0x00b24913, 0x00a94c16, 0x009e5224, 0x00703f1c, 0x001e0000, 0x00100000, 0x00200000, 0x006e3621, 0x00994a28, 0x00af4b1e, 0x00b44813, 0x00af480c, 0x00ac4c0f, 0x00a84e19, 0x0087441c, 0x003c1d0c, 0x00080000, 0x00050000, 0x00100000, 0x00451500, 0x00954c2c, 0x00aa4c25, 0x00b0481a, 0x00b24c13, 0x00b04b0d, 0x00b24d10, 0x00b34b0f, 0x00b7460f, 0x00bc4812, 0x00b7440c, 0x00bd4a10, 0x00c75416, 0x00c4520f, 0x00c15408, 0x00bc5c17, 0x00a05528, 0x004c1800, 0x001a0000, 0x001c0100, 0x00411504, 0x00783b20, 0x009f4c2a, 0x00ac4d25, 0x00ab4a1e, 0x00ad4a17, 0x00b24c0f, 0x00b34d0e, 0x00b14c13, 0x00b04a14, 0x00b24817, 0x00b14918, 0x00b04a18, 0x00b04c17, 0x00b14c16, 0x00b04a13, 0x00ad4914, 0x00ad4b15, 0x00ac4c19, 0x00a94c1c, 0x00ab5022, 0x009f491c, 0x0097461b, 0x0090461f, 0x00854422, 0x00743c1f, 0x005c2b14, 0x00431b08, 0x00240300, 0x00190100, 0x000b0000, 0x00030000, 0x00010400, 0x00000300, 0x00020000, 0x00050000, 0x00110605, 0x001f1410, 0x00352d26, 0x00342c25, 0x00150904, 0x000c0000, 0x00190000, 0x00310b00, 0x0073371e, 0x00934826, 0x00a6522c, 0x00a84c20, 0x00ac4517, 0x00b64a17, 0x00bc4b14, 0x00b7460d, 0x00b74910, 0x00b44b11, 0x00b14c14, 0x00af4c16, 0x00ae4c17, 0x00ae4c17, 0x00b04c18, 0x00b04c17, 0x00b04c18, 0x00b04b15, 0x00b24911, 0x00b14b12, 0x00b04d15, 0x00af4c17, 0x00ad4c19, 0x00a74c20, 0x00904728, 0x0057220d, 0x00140000, 0x00140000, 0x00451800, 0x00995333, 0x00a64c1c, 0x00b04c14, 0x00ac4a14, 0x00b24d10, 0x00ba4d0a, 0x00c55308, 0x00cb5605, 0x00c2570b, 0x00b45c1f, 0x006e3108, 0x00210700, 0x00090000, 0x00070000, 0x00030000, 0x000f0d0e, 0x00242424, 0x005a5a58, 0x00878683, 0x00a7a39e, 0x00454443, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00545558, 0x00170b07, 0x002b0a00, 0x00773b0f, 0x00ba5b19, 0x00c55508, 0x00c85408, 0x00c85408, 0x00c45808, 0x00b55813, 0x00a05c2c, 0x003f1400, 0x00100000, 0x00150b06, 0x000a0000, 0x00200400, 0x006c3011, 0x00a1501c, 0x00b45610, 0x00bd580d, 0x00bb5a13, 0x00b95814, 0x00b85211, 0x00b55010, 0x00b85315, 0x00ba581a, 0x00b85818, 0x00ad5516, 0x00a5571c, 0x009a531e, 0x008b491b, 0x0088481c, 0x008a4a20, 0x008c502b, 0x00824e30, 0x00683a23, 0x003a1404, 0x002d0400, 0x00581c00, 0x008f4520, 0x00aa5325, 0x00a85124, 0x009d502f, 0x005f2712, 0x00150000, 0x000c0000, 0x001a0000, 0x005a2b11, 0x008f4a21, 0x00a8521e, 0x00b34e10, 0x00b84c08, 0x00bc500b, 0x00bb500c, 0x00b7500f, 0x00b44f11, 0x00b44f11, 0x00b44f11, 0x00b44f10, 0x00b84f0f, 0x00b84a0e, 0x00bd4f15, 0x00b84c19, 0x00b04f24, 0x008e401f, 0x00561400, 0x004c0f00, 0x00803a18, 0x00b4571c, 0x00c65a12, 0x00c45004, 0x00c45311, 0x00ad4b1d, 0x00832e0c, 0x005b1800, 0x009d5430, 0x00ac4920, 0x00b44718, 0x00b34a10, 0x00ae490e, 0x00ae4c1a, 0x00a54d26, 0x00843f23, 0x00401300, 0x000b0000, 0x00050000, 0x001c0300, 0x00411400, 0x0088422a, 0x00a54f30, 0x00aa4c24, 0x00ad4a1a, 0x00af4c16, 0x00af4c16, 0x00aa4b16, 0x00a34b1a, 0x009c4f26, 0x009b5027, 0x00a04c1f, 0x00a54917, 0x00af4912, 0x00b64c11, 0x00b24910, 0x00b04a10, 0x00b44c10, 0x00af4912, 0x00a74c18, 0x00985227, 0x00482004, 0x00140000, 0x00160000, 0x003b1106, 0x00864428, 0x00a64e27, 0x00b34b1c, 0x00b44511, 0x00b0490f, 0x00ac4d14, 0x00a7501c, 0x0085441d, 0x003c1d0c, 0x00090000, 0x00060000, 0x00130000, 0x004c1802, 0x00984d2c, 0x00ac4c26, 0x00b0481b, 0x00b14c16, 0x00ae4c0e, 0x00b04c0f, 0x00b44c0f, 0x00b6480e, 0x00bb480f, 0x00bc4a0d, 0x00c45113, 0x00c55414, 0x00c05413, 0x00bb5813, 0x00a8571f, 0x00582509, 0x001d0000, 0x000d0000, 0x00100000, 0x001c0000, 0x003c0e00, 0x00682812, 0x00914327, 0x00a44c2a, 0x00ab4c1f, 0x00b04812, 0x00b0470b, 0x00b1490d, 0x00b34c14, 0x00b44b18, 0x00b24817, 0x00ac4711, 0x00af4914, 0x00b24c17, 0x00b24c17, 0x00b14a14, 0x00b04810, 0x00b1460d, 0x00b1460c, 0x00b0450c, 0x00b04710, 0x00af4c17, 0x00ac501f, 0x00a45023, 0x009d5025, 0x00944b24, 0x00874421, 0x00763a21, 0x00582813, 0x00311400, 0x00180800, 0x00090300, 0x00020000, 0x00000000, 0x00060405, 0x00000000, 0x00000000, 0x000c0805, 0x001c140f, 0x00190d09, 0x000b0000, 0x00060000, 0x000f0000, 0x00310a00, 0x00642c18, 0x00904c31, 0x00a2502c, 0x00a94a1d, 0x00b34916, 0x00b94811, 0x00b6440b, 0x00b74810, 0x00b44814, 0x00b04a16, 0x00ae4b19, 0x00ae4b19, 0x00ae4b19, 0x00af4b18, 0x00af4b16, 0x00b04c18, 0x00b04915, 0x00b14812, 0x00b14a14, 0x00ae4c15, 0x00ac4a14, 0x00ac4918, 0x00a54c22, 0x00884428, 0x004e1e0b, 0x00150000, 0x00240700, 0x0061290c, 0x00a0542c, 0x00a74b18, 0x00b14c14, 0x00b14c13, 0x00b44b0c, 0x00be5009, 0x00ca580b, 0x00c85705, 0x00bb570c, 0x009e541c, 0x00572806, 0x00140100, 0x00030001, 0x00131016, 0x00515256, 0x00808387, 0x00989c9c, 0x00b0b1ac, 0x006c6a66, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005f6064, 0x00190e0c, 0x00240400, 0x0070380e, 0x00b85c1c, 0x00c4540a, 0x00c55309, 0x00c7560c, 0x00c3580a, 0x00b6570f, 0x00a95c25, 0x005c2700, 0x00160000, 0x001e1710, 0x001c1815, 0x00140400, 0x003d1600, 0x0084471f, 0x00aa5921, 0x00b45818, 0x00b35211, 0x00b65210, 0x00b85213, 0x00ba5214, 0x00bb5214, 0x00ba5113, 0x00b75112, 0x00b45210, 0x00b05410, 0x00ad5710, 0x00b05917, 0x00b05f20, 0x00a35c27, 0x00884e25, 0x005a3118, 0x002f0e00, 0x00240300, 0x004c1e06, 0x008e4519, 0x00ac521a, 0x00af4e14, 0x00a7531f, 0x00804428, 0x002b0700, 0x00100000, 0x00100000, 0x00401400, 0x0086441e, 0x00a14d18, 0x00b25215, 0x00b65011, 0x00b64d0d, 0x00bb4f0e, 0x00bc4e0d, 0x00bd4d09, 0x00bc4c07, 0x00ba4d08, 0x00b84e0c, 0x00b44f11, 0x00b44f11, 0x00bb4c10, 0x00ba4c11, 0x00b74d1a, 0x00ac4c20, 0x00a15028, 0x007c3a1c, 0x00451608, 0x00451401, 0x00894014, 0x00af5416, 0x00c15610, 0x00c65a19, 0x00ad4a20, 0x0087300c, 0x00742800, 0x00a25223, 0x00ac4a1b, 0x00b44816, 0x00b54a11, 0x00b14810, 0x00b04d1c, 0x00a64d21, 0x00964826, 0x00592209, 0x00140000, 0x000b0300, 0x000b0000, 0x00200400, 0x004d1c0b, 0x008c4830, 0x009e4d28, 0x00a64c1d, 0x00aa4b16, 0x00ae4c14, 0x00ac4a12, 0x00a94a14, 0x00a84d1d, 0x00a44c1c, 0x00a44816, 0x00ab4915, 0x00b04a13, 0x00b54c13, 0x00af4810, 0x00b04910, 0x00b14c11, 0x00ac4b14, 0x00a44c1c, 0x008d4c25, 0x00290800, 0x00130000, 0x00200000, 0x005e2b17, 0x00954926, 0x00aa4c21, 0x00b4481c, 0x00b54514, 0x00b04913, 0x00ac4c16, 0x00a74f1e, 0x00864420, 0x003f1e0e, 0x000d0000, 0x00070000, 0x00120000, 0x00562108, 0x009b4c28, 0x00ac4b24, 0x00b0481b, 0x00af4b16, 0x00ad4c11, 0x00ac4a0c, 0x00b14c0e, 0x00b84a0e, 0x00bc4b0c, 0x00c45311, 0x00c45513, 0x00b94f10, 0x00bc5c1f, 0x00a95720, 0x006b3008, 0x001c0200, 0x00060000, 0x00050000, 0x00050000, 0x000d0000, 0x00180000, 0x00280200, 0x00582213, 0x00823e25, 0x00984824, 0x00ab4b20, 0x00af4814, 0x00af460c, 0x00b1490d, 0x00b44914, 0x00b14814, 0x00b24815, 0x00b04915, 0x00b04a18, 0x00b04a16, 0x00b14a14, 0x00b24910, 0x00b74a0d, 0x00b84b0c, 0x00b64c10, 0x00b24c13, 0x00b04c19, 0x00ab4b1a, 0x00a64817, 0x00a94717, 0x00b04915, 0x00ac4a18, 0x00a85124, 0x00944a24, 0x00783f20, 0x005c3118, 0x00391c04, 0x001e0800, 0x00100000, 0x000a0000, 0x00060000, 0x000b0404, 0x00050000, 0x00030000, 0x000c0601, 0x00090400, 0x00030000, 0x00090000, 0x000e0000, 0x002c0904, 0x00582817, 0x00864628, 0x00a45028, 0x00aa4a19, 0x00af4610, 0x00b54810, 0x00b44813, 0x00b24817, 0x00b0481a, 0x00ad491b, 0x00ad491b, 0x00ae4918, 0x00b04915, 0x00b04a14, 0x00ae4b18, 0x00ae4a17, 0x00b24814, 0x00b04914, 0x00ac4b14, 0x00aa4b14, 0x00ae491a, 0x00a74d27, 0x007e3f26, 0x003e1201, 0x00160000, 0x00381300, 0x00803f1b, 0x00a04c1e, 0x00ab4b18, 0x00b24b14, 0x00b54d11, 0x00b74b0a, 0x00c3520a, 0x00c95809, 0x00c35405, 0x00b85b17, 0x007c4014, 0x00351400, 0x000c0000, 0x00040004, 0x003c3a40, 0x00a1a2a6, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x006d6e72, 0x00201414, 0x001c0000, 0x0069310a, 0x00b4591b, 0x00c2560c, 0x00c4540d, 0x00c75710, 0x00c2580d, 0x00b85710, 0x00ae581c, 0x007a3b0e, 0x001e0000, 0x00281b10, 0x003b322d, 0x00180900, 0x001e0100, 0x006b3918, 0x00a15726, 0x00b05518, 0x00b85616, 0x00ba5310, 0x00b95210, 0x00ba5310, 0x00ba500f, 0x00b84e0c, 0x00b84f0f, 0x00b85310, 0x00b7540d, 0x00b15208, 0x00b65812, 0x00a75215, 0x00823d10, 0x00542002, 0x00280600, 0x001b0000, 0x00431906, 0x007c411d, 0x00ab541b, 0x00b25010, 0x00b05416, 0x009c5020, 0x0054280f, 0x00130000, 0x000e0000, 0x00160000, 0x006f3515, 0x009d4e1f, 0x00b05014, 0x00b7500d, 0x00b55010, 0x00b85014, 0x00b84e14, 0x00bb4c12, 0x00c04c0b, 0x00bf4c06, 0x00bc4c06, 0x00b94e0a, 0x00b44f11, 0x00b44e12, 0x00bb4e10, 0x00b6490c, 0x00b6501b, 0x00ac5022, 0x00a3562d, 0x00824729, 0x003c180d, 0x00230100, 0x00481800, 0x00834010, 0x00b1581b, 0x00c05d22, 0x00ab4920, 0x008c3109, 0x00903c08, 0x00a55018, 0x00ab4c14, 0x00b04913, 0x00b54810, 0x00b24610, 0x00af4c18, 0x00a84c1e, 0x00a04c24, 0x00733315, 0x002b0c00, 0x00080000, 0x00060000, 0x000c0000, 0x001f0000, 0x00592815, 0x008d4928, 0x00a45026, 0x00a74a19, 0x00ad4b15, 0x00ae4b11, 0x00ae4b13, 0x00ae4a17, 0x00ac4817, 0x00ad4a17, 0x00b4501c, 0x00b04a14, 0x00b24c17, 0x00ae4713, 0x00b04a14, 0x00ae4b13, 0x00aa4c17, 0x00a14c1f, 0x007f401f, 0x001c0000, 0x00100000, 0x00300a00, 0x007c4026, 0x00a04d24, 0x00ad4a1a, 0x00b34618, 0x00b64718, 0x00b04915, 0x00ac4b18, 0x00a84d20, 0x00874420, 0x00421e0f, 0x000e0000, 0x00080000, 0x00140000, 0x00662f10, 0x009d4c24, 0x00ac481f, 0x00b14719, 0x00af4814, 0x00ad4a10, 0x00ad4b0d, 0x00b34d0e, 0x00b94c0b, 0x00c55511, 0x00c3540d, 0x00c05710, 0x00bd5d20, 0x00a4521f, 0x006b2c05, 0x002a0400, 0x000f0300, 0x00000004, 0x00000000, 0x00020000, 0x00030001, 0x00070000, 0x00110000, 0x001e0300, 0x00431706, 0x006c3017, 0x00954828, 0x00a84f27, 0x00ad4c18, 0x00b04a13, 0x00b04914, 0x00b04814, 0x00b44c18, 0x00b14b17, 0x00af4816, 0x00ae4814, 0x00ae4813, 0x00ae480f, 0x00b1480e, 0x00b2480f, 0x00b04913, 0x00ab4712, 0x00ab4818, 0x00af4c1d, 0x00b04c1b, 0x00b34c18, 0x00b74911, 0x00b4460e, 0x00aa440f, 0x00a74c1c, 0x00a2522a, 0x00944f2c, 0x007d4223, 0x00643418, 0x00481d07, 0x002a0800, 0x001c0000, 0x000e0000, 0x000c0000, 0x00080100, 0x00030000, 0x00020000, 0x00060504, 0x00020000, 0x00080004, 0x000c0000, 0x00230400, 0x0051240e, 0x00814220, 0x009f5024, 0x00aa4f1d, 0x00af4c18, 0x00af4816, 0x00b04818, 0x00af481a, 0x00af481a, 0x00af4819, 0x00af4818, 0x00b04814, 0x00af4914, 0x00ac4916, 0x00ad4a17, 0x00b14a16, 0x00b04914, 0x00ac4c14, 0x00ac4c16, 0x00b04b1c, 0x00a54c28, 0x0070341f, 0x002e0500, 0x001d0000, 0x0050260d, 0x00974f24, 0x00a44a15, 0x00af4c17, 0x00b04a11, 0x00b3490d, 0x00bb4e0b, 0x00c6540a, 0x00c65407, 0x00c25409, 0x00b15b1f, 0x00602e0f, 0x001a0300, 0x00080000, 0x00100d0e, 0x005c5b5c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00828288, 0x002a1f1e, 0x00180000, 0x005f2803, 0x00ac5215, 0x00c35810, 0x00c45511, 0x00c35610, 0x00bf560d, 0x00bc5911, 0x00b05414, 0x00964c1b, 0x002b0000, 0x002d1406, 0x005e493d, 0x002b1506, 0x001b0000, 0x00502003, 0x00924618, 0x00b15318, 0x00bc520e, 0x00bc5008, 0x00b8520b, 0x00b8540c, 0x00bc550c, 0x00bb540d, 0x00b7520f, 0x00b55111, 0x00b85314, 0x00b35013, 0x00b35824, 0x008d4219, 0x00521e08, 0x00280200, 0x00190000, 0x003b1408, 0x007e3c1c, 0x00a34f1b, 0x00b25010, 0x00b0500f, 0x00a25420, 0x00784018, 0x00270700, 0x00100000, 0x00100000, 0x003a1703, 0x008d4c25, 0x00aa501d, 0x00bc5415, 0x00b74908, 0x00b54d10, 0x00b44d17, 0x00b64c1b, 0x00b84b19, 0x00bc4b14, 0x00bc4b0e, 0x00ba4c0c, 0x00b94d0c, 0x00b84d11, 0x00b74d11, 0x00b94d0c, 0x00b74e0c, 0x00b25016, 0x00a45020, 0x00894b24, 0x00582c11, 0x00230500, 0x00170000, 0x00190400, 0x00442104, 0x00834111, 0x00ac5622, 0x00ac4e24, 0x00943406, 0x00a94f12, 0x00b25815, 0x00ad5111, 0x00af4c0f, 0x00b6480e, 0x00b44510, 0x00ad4916, 0x00a74a19, 0x00a34b1c, 0x00894220, 0x004a2015, 0x000c0000, 0x00040102, 0x00000000, 0x000c0000, 0x00280800, 0x00652d10, 0x00944820, 0x00a84e21, 0x00af4c1a, 0x00b04b14, 0x00b34a12, 0x00b44816, 0x00b44717, 0x00b04715, 0x00ad4714, 0x00ae4918, 0x00b04b1c, 0x00ae4618, 0x00b04a19, 0x00ac4916, 0x00a84c1b, 0x009f4a22, 0x006f3015, 0x00180000, 0x00130000, 0x00512412, 0x008d4b2b, 0x00a54e20, 0x00ad4713, 0x00b44717, 0x00b54618, 0x00b04817, 0x00ac4919, 0x00a84c21, 0x008b4424, 0x00441e0e, 0x00100000, 0x00090000, 0x00180100, 0x00783f1c, 0x00a04c1f, 0x00ac471b, 0x00b44819, 0x00b14814, 0x00b14b10, 0x00b34e10, 0x00b8510f, 0x00bf500a, 0x00c95a10, 0x00c05408, 0x00b95610, 0x00a8541c, 0x00713108, 0x00300b00, 0x00110000, 0x00040000, 0x00000000, 0x00030000, 0x00040100, 0x00000302, 0x00000303, 0x00000000, 0x00030000, 0x000f0000, 0x00301003, 0x005c2a16, 0x00834023, 0x00a04924, 0x00ac4c20, 0x00ac4c19, 0x00ac4b15, 0x00ac4c14, 0x00ac4913, 0x00ad4a12, 0x00b04b15, 0x00b14b17, 0x00af4a19, 0x00ad491c, 0x00ac491e, 0x00a8481f, 0x00a7471d, 0x00ab4a20, 0x00ae4d21, 0x00aa4818, 0x00a84414, 0x00ac4815, 0x00b04c18, 0x00b34c17, 0x00b14a16, 0x00ae4918, 0x00a8481a, 0x00a14821, 0x009c492a, 0x008c4128, 0x0071301e, 0x00572011, 0x00370c00, 0x001e0100, 0x00140200, 0x00090100, 0x00020000, 0x00000000, 0x00000004, 0x00030207, 0x00050000, 0x000b0000, 0x001e0400, 0x00471f04, 0x00743c1b, 0x00924c22, 0x00a04c1f, 0x00aa4c1b, 0x00b04918, 0x00b24817, 0x00b34817, 0x00b24815, 0x00b04915, 0x00ae4a15, 0x00ad4b15, 0x00ac4a16, 0x00ae4b19, 0x00b14918, 0x00b04814, 0x00ab4c14, 0x00ac4f18, 0x00af4819, 0x009d4420, 0x005c2410, 0x00240000, 0x00300e00, 0x006a3b21, 0x00a05323, 0x00aa4c14, 0x00b04c16, 0x00b24911, 0x00b44b0b, 0x00c0530c, 0x00c8540b, 0x00c6540a, 0x00c25711, 0x00984611, 0x00421a06, 0x000d0000, 0x00060000, 0x00302c29, 0x008e8a85, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00919499, 0x0031292a, 0x00140000, 0x00542100, 0x00a04c14, 0x00c05814, 0x00c35610, 0x00c2540c, 0x00be5409, 0x00c15b12, 0x00b2510f, 0x00a45622, 0x00310000, 0x002e0c00, 0x007b5643, 0x0045220c, 0x00210300, 0x00330a00, 0x0079340d, 0x00b05621, 0x00ba5110, 0x00be510b, 0x00ba540c, 0x00b7530b, 0x00b65007, 0x00b65008, 0x00b5520d, 0x00b75313, 0x00b75014, 0x00b25019, 0x00a95426, 0x006d2c0c, 0x002c0400, 0x00170000, 0x002c0700, 0x006f3924, 0x00a04f22, 0x00b45216, 0x00ba520f, 0x00b15416, 0x008a481e, 0x00592f14, 0x00110000, 0x000f0000, 0x001b0000, 0x00713f23, 0x009e5024, 0x00ad4c14, 0x00bb4f0e, 0x00b84908, 0x00c0541a, 0x00b44a17, 0x00b54b1d, 0x00b74b1c, 0x00b84c15, 0x00b84e12, 0x00b84f0f, 0x00b84f0f, 0x00b94c11, 0x00b94c10, 0x00b74d0b, 0x00b45210, 0x00a6521c, 0x008c491e, 0x00592b0c, 0x00280800, 0x00140000, 0x000c0000, 0x00080000, 0x00140200, 0x004b1d00, 0x0087461c, 0x00a04e28, 0x008e3405, 0x00b45515, 0x00bc5c14, 0x00b85614, 0x00b55010, 0x00ba4910, 0x00b6480e, 0x00af4912, 0x00aa4b16, 0x00a64a18, 0x009a4c24, 0x0065301d, 0x00280b04, 0x00050000, 0x00030303, 0x00050000, 0x000e0000, 0x002e0600, 0x00743819, 0x009c4b24, 0x00a94a1d, 0x00af4b18, 0x00b24814, 0x00b34412, 0x00b64815, 0x00b44a16, 0x00ae4814, 0x00ae4a17, 0x00ae491a, 0x00b04518, 0x00b34b1c, 0x00ac4818, 0x00a84c1e, 0x009c4821, 0x0064250b, 0x00190000, 0x001c0000, 0x00763d25, 0x00984a24, 0x00a94918, 0x00ae4410, 0x00b34b1b, 0x00ad4618, 0x00ae491a, 0x00ac491c, 0x00a94c25, 0x008e4427, 0x00441f0f, 0x000f0000, 0x000d0000, 0x00200400, 0x00884822, 0x00a84d1f, 0x00ae4719, 0x00b44917, 0x00b24a0e, 0x00b34d0c, 0x00bb5210, 0x00bf5511, 0x00c55710, 0x00bd520b, 0x00bb5b16, 0x00a95419, 0x00712c00, 0x00451100, 0x00341200, 0x00200c00, 0x000d0000, 0x00070000, 0x00060000, 0x00040100, 0x00000200, 0x00000401, 0x00000605, 0x00000302, 0x00050100, 0x000b0000, 0x00200600, 0x004c2010, 0x007e3c24, 0x009c4b29, 0x00a44e21, 0x00a74c19, 0x00ac4c16, 0x00ac4a12, 0x00ad4914, 0x00b04a16, 0x00b04917, 0x00ae4718, 0x00ab461d, 0x00a84822, 0x00983d1c, 0x008f3817, 0x00933c1b, 0x009f4825, 0x00a74f28, 0x00a74e24, 0x00a54c20, 0x00a74a19, 0x00b04817, 0x00b14512, 0x00b44814, 0x00b44a16, 0x00ae4618, 0x00ab481f, 0x00a84c28, 0x009e492a, 0x0094472b, 0x007b381d, 0x00602c14, 0x00441f0a, 0x002a1000, 0x00180600, 0x000f0000, 0x00080000, 0x00040000, 0x00070000, 0x00080000, 0x000b0000, 0x00180000, 0x003c1800, 0x006b3819, 0x008f4c27, 0x00a24e22, 0x00aa4c1b, 0x00b04915, 0x00b34813, 0x00b24814, 0x00b04914, 0x00ad4b15, 0x00ab4b18, 0x00aa4c1a, 0x00ac4c1c, 0x00ae491a, 0x00ac4814, 0x00ac4c14, 0x00ad4e19, 0x00a5451b, 0x00903e1e, 0x004b1705, 0x00220000, 0x004b200c, 0x0084492c, 0x00a44e1c, 0x00af4c12, 0x00ae4811, 0x00b34b0f, 0x00bb500c, 0x00c7580f, 0x00c8540a, 0x00c65610, 0x00b8571c, 0x006f2800, 0x00250700, 0x00060000, 0x000c0805, 0x004f4c47, 0x00b4b1aa, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a6acb4, 0x0039383d, 0x000e0000, 0x00411700, 0x008c4110, 0x00bb5a18, 0x00c1550d, 0x00c35004, 0x00c55405, 0x00c3580c, 0x00b4520e, 0x00a85a28, 0x00431300, 0x002c0400, 0x00874c30, 0x00743d20, 0x002d1000, 0x00190000, 0x005e2a0c, 0x009c5025, 0x00b2541a, 0x00b85010, 0x00b75310, 0x00b6510d, 0x00b84f0c, 0x00b9500c, 0x00b6500a, 0x00b5510e, 0x00b44f12, 0x00b0531c, 0x00a75828, 0x00531a00, 0x001a0000, 0x00220700, 0x0064301a, 0x00944c24, 0x00aa511a, 0x00b45214, 0x00b44f0e, 0x00a7501a, 0x007a4022, 0x002c0a00, 0x000b0000, 0x00130000, 0x00481700, 0x00904924, 0x00af5520, 0x00b34f0f, 0x00b94d0c, 0x00ba4a0b, 0x00bc4d19, 0x00b94a1b, 0x00b94b19, 0x00b64a15, 0x00b64e11, 0x00b4500f, 0x00b1500e, 0x00b4500e, 0x00b84d11, 0x00b84a0e, 0x00b84b0c, 0x00b0551b, 0x008c4c20, 0x00582e0f, 0x00230700, 0x000e0000, 0x00140300, 0x000a0000, 0x00090000, 0x00100000, 0x00220600, 0x003d1400, 0x00763b1d, 0x008f4219, 0x00b25215, 0x00c45915, 0x00c35314, 0x00c45215, 0x00c04f12, 0x00b5480c, 0x00b34b0e, 0x00b04d12, 0x00a94812, 0x00a54e20, 0x00864424, 0x0052240f, 0x00180200, 0x00060000, 0x00070300, 0x00050000, 0x00100000, 0x00350f00, 0x00803d1d, 0x00a44e27, 0x00a7481b, 0x00ac4517, 0x00b44917, 0x00ae440e, 0x00ae490e, 0x00ad4c0e, 0x00ad4a0f, 0x00b04b14, 0x00b04513, 0x00b34718, 0x00ab4618, 0x00a74b1f, 0x00994920, 0x00642503, 0x00270000, 0x00481906, 0x00893f1e, 0x00a9491f, 0x00b54715, 0x00b44813, 0x00a44816, 0x00a54f1d, 0x00a74a19, 0x00a94c1f, 0x00a54925, 0x008c4428, 0x003b180b, 0x000e0000, 0x000e0000, 0x00391300, 0x009a4c2a, 0x00aa471c, 0x00af4819, 0x00b14c14, 0x00b3520b, 0x00bb580c, 0x00c35810, 0x00c0510d, 0x00c35611, 0x00b85618, 0x009c4f1f, 0x006c2e09, 0x003b0800, 0x00380900, 0x00794827, 0x00623714, 0x003c1c00, 0x001b0500, 0x000d0000, 0x00030000, 0x00000103, 0x00000405, 0x00000000, 0x00050000, 0x00060103, 0x00020001, 0x00030000, 0x00140502, 0x003b1408, 0x006e331d, 0x00944c28, 0x00a14d20, 0x00ae4e1c, 0x00ac4814, 0x00ac4919, 0x00b04c1c, 0x00b34819, 0x00b14517, 0x00b14519, 0x00ae4921, 0x0090391a, 0x00702309, 0x00601b07, 0x006d2c17, 0x00834024, 0x00924828, 0x009c4e25, 0x00a44d20, 0x00ae4719, 0x00b44717, 0x00b24815, 0x00b04915, 0x00ae4a15, 0x00ad4c16, 0x00ab4c17, 0x00a94b19, 0x00a84c1b, 0x00a2491c, 0x009e4d24, 0x00924925, 0x00743818, 0x005a260c, 0x00481c06, 0x00371504, 0x00240c01, 0x00120000, 0x000b0000, 0x000e0000, 0x000c0000, 0x00110000, 0x00361201, 0x00633016, 0x008e4824, 0x009c481b, 0x00aa4814, 0x00b04a11, 0x00b14812, 0x00ae4712, 0x00ac4817, 0x00ab4c1c, 0x00a84b20, 0x00a5491d, 0x00aa4d20, 0x00ac4a1a, 0x00b04b15, 0x00ac4b18, 0x00a14d28, 0x00733017, 0x00330500, 0x00380c00, 0x0074381e, 0x009c4c27, 0x00ac491a, 0x00b64d15, 0x00ae490c, 0x00b44c09, 0x00c4560b, 0x00c65407, 0x00c45104, 0x00c05917, 0x009c4c1f, 0x00451300, 0x00110000, 0x00010004, 0x00201f20, 0x00787874, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00010101, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0066696d, 0x0044474c, 0x00110301, 0x00300c00, 0x007a380c, 0x00b55c1f, 0x00c2580f, 0x00c95607, 0x00c95607, 0x00c05306, 0x00b75310, 0x00a85a28, 0x00582710, 0x00280000, 0x00874525, 0x00905230, 0x00391905, 0x001a0000, 0x00451b01, 0x00834420, 0x00ae5421, 0x00b75215, 0x00b55313, 0x00b65210, 0x00b94f10, 0x00ba500f, 0x00b64f0c, 0x00b6510e, 0x00b55014, 0x00ab4f19, 0x009d5220, 0x00481400, 0x001b0100, 0x002c1105, 0x00763b1c, 0x00a35323, 0x00ad5014, 0x00b35010, 0x00b25215, 0x009b4c1c, 0x00572714, 0x00140000, 0x000e0000, 0x001e0200, 0x00773719, 0x00a75124, 0x00b0521a, 0x00b44e0f, 0x00b9500e, 0x00b94b0f, 0x00bc4c17, 0x00b74715, 0x00ba4b17, 0x00b84d13, 0x00b75110, 0x00af4d09, 0x00b04f0c, 0x00b35010, 0x00b44a0e, 0x00b84e14, 0x00ae4c14, 0x009c5020, 0x005b2e10, 0x00200a00, 0x000e0000, 0x00080000, 0x00080000, 0x000d0000, 0x00140000, 0x00240700, 0x003c1b09, 0x003c1400, 0x00401000, 0x006f2e08, 0x00b35926, 0x00bc5318, 0x00c65617, 0x00c45210, 0x00c55510, 0x00c45610, 0x00b54a06, 0x00b2490b, 0x00af4912, 0x00a84918, 0x00a04d24, 0x007c3a1a, 0x00401500, 0x00140000, 0x000a0000, 0x00080000, 0x000c0000, 0x001e0000, 0x00541500, 0x00903e1a, 0x00a84b24, 0x00ae4a1f, 0x00b14b1a, 0x00ae4813, 0x00af4e14, 0x00ac4c10, 0x00ac4a10, 0x00af4912, 0x00b04311, 0x00b4471b, 0x00af461c, 0x00a8481f, 0x00a04c20, 0x007c350d, 0x00612608, 0x00743516, 0x009c471f, 0x00ac4818, 0x00b34412, 0x00b24814, 0x00a34917, 0x00a34e1c, 0x00a84918, 0x00aa4b1c, 0x00a14824, 0x00844027, 0x00321406, 0x000f0000, 0x001c0100, 0x00592610, 0x00a34b24, 0x00b04514, 0x00b84c17, 0x00bf5415, 0x00bc5806, 0x00bc5704, 0x00c35812, 0x00c45b1c, 0x00b5541c, 0x00994816, 0x00642806, 0x003c0c00, 0x00380a00, 0x00401100, 0x0074411c, 0x00986238, 0x00855126, 0x005a2c08, 0x002d0c00, 0x00130000, 0x00060000, 0x00030000, 0x00050000, 0x00050000, 0x00020000, 0x00020306, 0x00000405, 0x00000000, 0x00100000, 0x002d0700, 0x005c2812, 0x00874424, 0x009c481e, 0x00ab5020, 0x00aa4b1c, 0x00a54113, 0x00b04516, 0x00b84b1b, 0x00b5481a, 0x00ac461c, 0x00a34a26, 0x00853a1d, 0x00541702, 0x00350000, 0x00420d00, 0x00642c15, 0x007c4023, 0x008c4423, 0x00a24924, 0x00aa4820, 0x00aa4b1e, 0x00a84918, 0x00a74813, 0x00a84810, 0x00aa4810, 0x00ad480f, 0x00b04b14, 0x00b14c16, 0x00ad4b1b, 0x00a4481c, 0x00a04c24, 0x00a05430, 0x00914b2b, 0x00723518, 0x005b2810, 0x0049200c, 0x003b1609, 0x002f1006, 0x00200500, 0x00160000, 0x00200000, 0x00340700, 0x00602404, 0x00873d14, 0x00a74f20, 0x00ab4c17, 0x00aa4613, 0x00ae4a17, 0x00ae4b1b, 0x00a74417, 0x00ab4a1e, 0x00a8481c, 0x00ab4c1d, 0x00ac4a18, 0x00b04914, 0x00a8481a, 0x00974d2c, 0x005c240d, 0x00310400, 0x0053200a, 0x008f4424, 0x00a84c21, 0x00ad4818, 0x00b34910, 0x00b04908, 0x00bc510a, 0x00c55306, 0x00c55306, 0x00c75a14, 0x00b1561d, 0x006b2c0b, 0x002c0800, 0x000e0303, 0x00000007, 0x00474747, 0x00a2a39f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x005b5a5e, 0x00180c0c, 0x001d0000, 0x00662c08, 0x00ac5922, 0x00bf5710, 0x00c95809, 0x00ca580a, 0x00bd5206, 0x00b85510, 0x00a85724, 0x00703c22, 0x00280000, 0x00773b1b, 0x00955b3a, 0x00552e16, 0x00260400, 0x002e0700, 0x006f3614, 0x00a95321, 0x00b55217, 0x00b45214, 0x00b55111, 0x00b95113, 0x00b85010, 0x00b5500d, 0x00b65010, 0x00b95114, 0x00ad5018, 0x00a05524, 0x00441100, 0x00170000, 0x00260900, 0x0074391a, 0x00a85526, 0x00b05116, 0x00b25112, 0x00ac5119, 0x0086411a, 0x00321003, 0x000e0000, 0x00180000, 0x00471b03, 0x009b5027, 0x00b05421, 0x00ac4d15, 0x00b04d12, 0x00b85013, 0x00b64c10, 0x00ba4c13, 0x00b74910, 0x00b94c12, 0x00b74c10, 0x00b64d0f, 0x00b34b0c, 0x00b75112, 0x00b85214, 0x00b0480e, 0x00af4d18, 0x00a15223, 0x00683110, 0x00280d01, 0x00080000, 0x00060000, 0x00080100, 0x00080000, 0x00170000, 0x00380c00, 0x00652e15, 0x00874924, 0x00773c14, 0x00481600, 0x00400800, 0x00752c06, 0x00a74f1e, 0x00b55614, 0x00c15b0d, 0x00c25100, 0x00ca5503, 0x00c45408, 0x00bf5110, 0x00b44a13, 0x00b34c1c, 0x00ae4a1c, 0x00a14920, 0x00743010, 0x00400c00, 0x00260400, 0x00260c00, 0x002e1000, 0x003b0e00, 0x005a1500, 0x00903a18, 0x00a34523, 0x00a5441e, 0x00ab471c, 0x00ab4819, 0x00ab4c1b, 0x00a54714, 0x00a94917, 0x00ad4819, 0x00af4317, 0x00b4471d, 0x00b1461d, 0x00aa451c, 0x00a84d22, 0x009a461a, 0x009c4c22, 0x009e4d22, 0x00a7501f, 0x00a74b17, 0x00ac4813, 0x00af4b18, 0x00a84a19, 0x00aa4a1a, 0x00ac4210, 0x00b04b1c, 0x00a45029, 0x007c4125, 0x00230c00, 0x000c0000, 0x00230000, 0x00793821, 0x00ac4c1c, 0x00be4c0c, 0x00c74e0c, 0x00c85005, 0x00c85300, 0x00c65805, 0x00be5716, 0x00ac5220, 0x008a451e, 0x00541f00, 0x003b0f00, 0x00542909, 0x00693817, 0x00481400, 0x003a0d00, 0x007d4928, 0x00a85d2e, 0x00a75828, 0x00823f1c, 0x00501c04, 0x00200400, 0x000c0000, 0x000a0100, 0x00040000, 0x00000000, 0x00000200, 0x00000200, 0x00030400, 0x000c0000, 0x000e0000, 0x001c0400, 0x00431f10, 0x007b4425, 0x008f491f, 0x00a75224, 0x00ae4e1d, 0x00a94110, 0x00af4411, 0x00b34b1b, 0x00aa4618, 0x00a8491b, 0x00a04c22, 0x00803a18, 0x00501800, 0x002b0000, 0x001d0000, 0x002f0c01, 0x00542719, 0x00753820, 0x008c4324, 0x009c4e2c, 0x00a04e27, 0x00a44c20, 0x00ab4c1d, 0x00af4c1a, 0x00af4814, 0x00af4814, 0x00ab4410, 0x00ad4818, 0x00b04d1e, 0x00a8481c, 0x00a3451a, 0x00a84c23, 0x00ad542c, 0x00a8512c, 0x009d4c28, 0x008b4424, 0x0078381c, 0x00642c12, 0x00501f06, 0x00421300, 0x003c0900, 0x00400900, 0x00612200, 0x00883c16, 0x009d481f, 0x00a4481d, 0x00ab481b, 0x00b14a1e, 0x00b54d1f, 0x00b24818, 0x00b04714, 0x00b34a14, 0x00af4811, 0x00ad4914, 0x00a14a1d, 0x0089472c, 0x004c1702, 0x00440d00, 0x00783820, 0x00a05029, 0x00a84d1c, 0x00ac4a14, 0x00b04a0e, 0x00b84c08, 0x00c6550c, 0x00cc5609, 0x00c2530a, 0x00bf5f22, 0x00904419, 0x003e0d00, 0x00170000, 0x00060000, 0x001c1c1d, 0x00787877, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00797878, 0x00241c1c, 0x00150000, 0x00522205, 0x009a5220, 0x00bc5814, 0x00c35305, 0x00c65608, 0x00c05509, 0x00ba5511, 0x00a8541d, 0x0084482b, 0x00310000, 0x005e2708, 0x00854f30, 0x00774a30, 0x00371000, 0x00220000, 0x005c280a, 0x009d4d1e, 0x00b25118, 0x00b25014, 0x00b25011, 0x00b85014, 0x00b74f10, 0x00b5500f, 0x00b65011, 0x00bb5115, 0x00ae4f18, 0x00a15929, 0x00441300, 0x00140000, 0x001c0000, 0x00703213, 0x00a65224, 0x00b05116, 0x00af5114, 0x009c4c1a, 0x00682e0e, 0x001d0300, 0x00120000, 0x00270200, 0x007b401e, 0x00a75220, 0x00b14f17, 0x00ae4c15, 0x00b35018, 0x00b44e14, 0x00b34b0e, 0x00b84f10, 0x00b74e0e, 0x00b74e10, 0x00b54c0e, 0x00b44a0c, 0x00b84d11, 0x00b84c12, 0x00b24c13, 0x00ae4c17, 0x00a14f20, 0x00743918, 0x002d0900, 0x000a0000, 0x00070308, 0x00020004, 0x00050000, 0x00140000, 0x00381101, 0x00703117, 0x009c4e27, 0x00a75423, 0x00a25524, 0x007f421a, 0x00501700, 0x00440200, 0x00651c00, 0x009b4d17, 0x00ac5410, 0x00be5608, 0x00cc5f0c, 0x00c55306, 0x00c75710, 0x00c25517, 0x00b54a10, 0x00b2470e, 0x00b14c16, 0x009b4215, 0x007c330d, 0x00692e12, 0x0068341c, 0x00743c22, 0x00834426, 0x00924321, 0x00a74d28, 0x00a74824, 0x00a94820, 0x00b04c21, 0x00ac4b1d, 0x00aa4d1e, 0x00a94c1c, 0x00a8491b, 0x00ad4b1d, 0x00ad4419, 0x00b1461c, 0x00b1461c, 0x00ac4418, 0x00ab4b1b, 0x00a84c1b, 0x00ab4c1d, 0x00a94b1a, 0x00a44b16, 0x00a44911, 0x00a84911, 0x00ac4a14, 0x00aa4717, 0x00ac4414, 0x00b74716, 0x00b2481a, 0x0099441c, 0x006c3011, 0x001d0200, 0x00140000, 0x003b0700, 0x009c4d30, 0x00b85218, 0x00ca540c, 0x00cc560c, 0x00cc5508, 0x00c95809, 0x00c05a13, 0x00a24c18, 0x007a3714, 0x00411200, 0x00280400, 0x00502802, 0x00916136, 0x00a26638, 0x007c431c, 0x00380d00, 0x00390c00, 0x00813c15, 0x00ab5b2c, 0x00ae5a2c, 0x00954a21, 0x00683310, 0x00351100, 0x00150000, 0x00080000, 0x00050200, 0x00030300, 0x00000100, 0x00020000, 0x00080000, 0x00080000, 0x00050001, 0x000f0000, 0x00301201, 0x00663619, 0x008f4c24, 0x009e4c1d, 0x00ab4c1b, 0x00af4c18, 0x00ac4817, 0x00ae4c1c, 0x00ac4c19, 0x00a24818, 0x009d5025, 0x0081401e, 0x00461500, 0x00270100, 0x001f0100, 0x00150000, 0x00270100, 0x00481c09, 0x006c3821, 0x00804428, 0x00904827, 0x009f4d27, 0x00a74c22, 0x00a64519, 0x00ae4a1c, 0x00ac4718, 0x00ad4618, 0x00b0481a, 0x00b0491b, 0x00af4818, 0x00ad4716, 0x00ab4414, 0x00ae4817, 0x00ad491b, 0x00a84a20, 0x00a04b23, 0x009b4f2a, 0x0096502e, 0x008c4b2b, 0x00834424, 0x00723010, 0x006c2704, 0x00772905, 0x00933e16, 0x00aa4e23, 0x00af4b20, 0x00ac4316, 0x00ac4012, 0x00b24514, 0x00b44612, 0x00b54810, 0x00b14710, 0x00ac4b17, 0x00a14e24, 0x0078381c, 0x00501501, 0x00692610, 0x0094482a, 0x00a74e21, 0x00a74811, 0x00aa4c10, 0x00b45010, 0x00c4540e, 0x00ca540a, 0x00c65306, 0x00c15916, 0x00a85828, 0x005c2405, 0x00250400, 0x000d0000, 0x00050000, 0x004d4c49, 0x00a4a5a1, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a29d9d, 0x00383434, 0x000f0000, 0x003a1500, 0x0082441b, 0x00b95d1d, 0x00bf5408, 0x00c35408, 0x00c6580d, 0x00ba540c, 0x00ac5319, 0x0093502d, 0x003a0500, 0x003f0f00, 0x0078482a, 0x008e593d, 0x004f1e05, 0x00230000, 0x00431800, 0x008e4319, 0x00ac501c, 0x00b15016, 0x00b25012, 0x00b65013, 0x00b44e10, 0x00b45010, 0x00b55012, 0x00b95014, 0x00aa4b14, 0x009e5626, 0x00441400, 0x00190000, 0x00200300, 0x00743212, 0x00a85122, 0x00ad4f15, 0x00a95018, 0x0086441c, 0x00401500, 0x000f0000, 0x00160000, 0x00501d01, 0x009c5224, 0x00af5017, 0x00b54d10, 0x00b44e17, 0x00b5511c, 0x00b44d14, 0x00b24c0f, 0x00b5500d, 0x00b34e0a, 0x00b24c0c, 0x00b85010, 0x00b7480c, 0x00bc4c12, 0x00b44710, 0x00ad4916, 0x00a85225, 0x007f401f, 0x00330f00, 0x000e0000, 0x00040000, 0x00020105, 0x00030001, 0x00100000, 0x003a1305, 0x0075381d, 0x009f4c21, 0x00b3541f, 0x00ac4b10, 0x00a94e15, 0x009f4f1f, 0x008f4822, 0x00642408, 0x00400400, 0x00440900, 0x0084401b, 0x00ab541e, 0x00b5500d, 0x00c05207, 0x00c85809, 0x00c25506, 0x00c55a0c, 0x00c2560c, 0x00bc530c, 0x00b24d10, 0x00ab4c15, 0x00a44c1d, 0x00a04b21, 0x00a14b24, 0x00a64e24, 0x00a84c1e, 0x00ac4c1c, 0x00a94718, 0x00ab4818, 0x00ac4a18, 0x00a44412, 0x00a34714, 0x00a74c19, 0x00a64918, 0x00ac4d1c, 0x00ab4818, 0x00ac4615, 0x00ae4616, 0x00ac4511, 0x00ac4812, 0x00ac4814, 0x00ac4417, 0x00ab4618, 0x00a74813, 0x00a74a10, 0x00aa4a0d, 0x00ac4910, 0x00ae4814, 0x00af4514, 0x00b44111, 0x00b24418, 0x009c431c, 0x006d2b09, 0x00260000, 0x00240000, 0x00500e00, 0x00b0572a, 0x00c15514, 0x00ca570a, 0x00ca560c, 0x00bf540e, 0x00af5216, 0x00964a1c, 0x00642d0e, 0x00330900, 0x001e0000, 0x00240400, 0x00693908, 0x00b07135, 0x00b5682b, 0x00a96434, 0x005b3018, 0x001a0000, 0x002c0500, 0x00754121, 0x00a45625, 0x00b35a21, 0x00ac5d23, 0x007e3e0d, 0x00411900, 0x001f0800, 0x00080000, 0x00060300, 0x00080400, 0x00040000, 0x00080000, 0x00080000, 0x00080009, 0x00030005, 0x00070000, 0x001e0800, 0x00532810, 0x00834824, 0x009a4d1f, 0x00a54d1b, 0x00a94e1c, 0x00a44815, 0x00a64918, 0x00a84c1f, 0x00a0471a, 0x009d4c24, 0x00904a2a, 0x00582008, 0x00240000, 0x001c0000, 0x000c0000, 0x000b0000, 0x001a0300, 0x00361709, 0x005b2e18, 0x007b4026, 0x0091492c, 0x009f4a28, 0x00a74825, 0x00ae4923, 0x00b04720, 0x00af4419, 0x00ae4618, 0x00b04917, 0x00ae4c15, 0x00ae4c15, 0x00af4816, 0x00ae491a, 0x00ac4a1c, 0x00a84a20, 0x00a54c24, 0x00a44e28, 0x00a34c27, 0x00a04924, 0x00a44b23, 0x00a84b22, 0x00aa4b1e, 0x00ac491a, 0x00ac4718, 0x00ad4716, 0x00b04818, 0x00b44c1a, 0x00b04614, 0x00b34814, 0x00b44710, 0x00b04811, 0x00a84a17, 0x00a24f23, 0x006e2809, 0x00652006, 0x00903d21, 0x00a44b24, 0x00a94814, 0x00ab480a, 0x00ad4e0c, 0x00b85410, 0x00cc5a13, 0x00c85109, 0x00bf4f08, 0x00b95c22, 0x007a3e1c, 0x002c0800, 0x00100000, 0x00050000, 0x0028231e, 0x0084817a, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00454443, 0x00504c4d, 0x000b0000, 0x00220600, 0x00653110, 0x00b25c23, 0x00c05910, 0x00c45509, 0x00c65809, 0x00bc530a, 0x00b15417, 0x00a0582d, 0x00440c00, 0x00270000, 0x006c4429, 0x008e5639, 0x006b3418, 0x002e0b00, 0x002c0500, 0x00773411, 0x00a34f21, 0x00b0531b, 0x00b25012, 0x00b55012, 0x00b34d10, 0x00b45012, 0x00b34e11, 0x00b84e14, 0x00ac4d18, 0x009d5829, 0x00451800, 0x00180000, 0x00240600, 0x00783210, 0x00aa5020, 0x00ab5018, 0x00a0501e, 0x006c381a, 0x00220400, 0x000e0000, 0x00240600, 0x00844621, 0x00a54f1b, 0x00b34e10, 0x00b54c0c, 0x00b54c14, 0x00b44c16, 0x00b44c12, 0x00b44f11, 0x00b4500c, 0x00af4d08, 0x00ae4c0a, 0x00b74f10, 0x00b7470b, 0x00bb4a13, 0x00b84c1c, 0x00ad5126, 0x00884522, 0x00401500, 0x00100000, 0x00030001, 0x00040102, 0x00060000, 0x00120000, 0x00431e11, 0x007c4028, 0x009f502b, 0x00ac4e1b, 0x00b85014, 0x00b64c0e, 0x00b74f13, 0x00ab4c17, 0x00aa5628, 0x00944d2c, 0x006f341a, 0x00390c00, 0x00300000, 0x005f1c00, 0x009b4819, 0x00ba5c1f, 0x00be5812, 0x00bd5508, 0x00c55b0a, 0x00c75a0b, 0x00c5580b, 0x00c2560e, 0x00c05412, 0x00bb5013, 0x00b54c10, 0x00b0470d, 0x00ac4309, 0x00af4610, 0x00b04811, 0x00ae4712, 0x00ad4611, 0x00ae4813, 0x00ac4914, 0x00a84914, 0x00a94b18, 0x00a74817, 0x00aa4a19, 0x00aa4818, 0x00a94414, 0x00ad4714, 0x00ae4712, 0x00ac450f, 0x00ac4510, 0x00af4418, 0x00b0471a, 0x00aa4812, 0x00ab490d, 0x00ad480a, 0x00ad4508, 0x00b24913, 0x00b44814, 0x00b84410, 0x00b74715, 0x00a74414, 0x00802f02, 0x004a0f00, 0x004c1200, 0x00762600, 0x00bb5c25, 0x00c05c18, 0x00b7520e, 0x00b45818, 0x00ab5821, 0x0080390c, 0x004b1000, 0x00380700, 0x003c1500, 0x00331405, 0x00290700, 0x00632f00, 0x00b06b27, 0x00b5601a, 0x00a85c23, 0x005a3016, 0x00130000, 0x000d0000, 0x00240500, 0x0072340d, 0x00ab5924, 0x00ac5718, 0x00b06024, 0x0099592a, 0x00572806, 0x002a0c00, 0x000d0000, 0x00060000, 0x000a0300, 0x000c0000, 0x00080000, 0x00040007, 0x00000008, 0x00010005, 0x00050000, 0x00170000, 0x00431b07, 0x00793f1e, 0x00944b22, 0x009c4a1c, 0x00a85020, 0x00a64c1d, 0x00a74c1c, 0x00a84b1c, 0x00a4491c, 0x00a04c24, 0x00984e2c, 0x0071341c, 0x003a0c00, 0x001e0600, 0x000b0000, 0x000c0000, 0x00100000, 0x001b0000, 0x002e0a00, 0x00522410, 0x007c4029, 0x0090482d, 0x009e492a, 0x00a44724, 0x00a9461d, 0x00ac481c, 0x00ad4a18, 0x00ab4a13, 0x00ad4b14, 0x00af4914, 0x00b04816, 0x00ad4819, 0x00ac481c, 0x00aa471d, 0x00a9461d, 0x00aa471e, 0x00ac481f, 0x00ad451c, 0x00af4619, 0x00af4415, 0x00ac4311, 0x00ae4413, 0x00b04915, 0x00af4816, 0x00a94512, 0x00ae4817, 0x00b04818, 0x00af4715, 0x00ad4916, 0x00a64a18, 0x00a04a1d, 0x00742703, 0x00803110, 0x00a44824, 0x00ab471c, 0x00af460c, 0x00b74f0c, 0x00b55109, 0x00bc550c, 0x00cc5b11, 0x00c2510b, 0x00c15d1d, 0x00984b1b, 0x00421702, 0x00100000, 0x00030003, 0x00030206, 0x00645e59, 0x00b5b0a8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00706e70, 0x001c1514, 0x00100000, 0x00491f05, 0x00994e1b, 0x00bc5b17, 0x00c8590b, 0x00c55404, 0x00c25408, 0x00b65412, 0x00a85828, 0x00571c00, 0x00200000, 0x00482814, 0x0081492e, 0x00874c30, 0x00411a00, 0x00230000, 0x005c2206, 0x00944a24, 0x00ad531e, 0x00b44f11, 0x00b74f10, 0x00b44c0e, 0x00b65014, 0x00b24d12, 0x00b44c16, 0x00af5320, 0x009c582c, 0x00411500, 0x00150000, 0x002e0c00, 0x00823611, 0x00ab4e1d, 0x00a8501d, 0x008d4820, 0x0048230e, 0x00150000, 0x00200300, 0x0054260f, 0x00a1562b, 0x00ab4d15, 0x00b34e10, 0x00b44c0d, 0x00b54a10, 0x00b44810, 0x00b74a0f, 0x00b74e10, 0x00b34f0d, 0x00b04f0c, 0x00af4c0c, 0x00b44c0f, 0x00b8480f, 0x00b74816, 0x00b05025, 0x00934826, 0x004d2109, 0x00100000, 0x00060000, 0x00030001, 0x00080000, 0x001d0400, 0x00481900, 0x00803e1c, 0x00a7552f, 0x00a84c1e, 0x00b04d18, 0x00b44b11, 0x00b44608, 0x00bc4d11, 0x00b64d17, 0x00ad4c19, 0x00a64e1f, 0x009a552e, 0x007c553d, 0x00331402, 0x00250000, 0x00370000, 0x006c2602, 0x009c4a1c, 0x00b5571d, 0x00bc5512, 0x00bf500a, 0x00c4530b, 0x00c95610, 0x00c95610, 0x00c6530c, 0x00c45309, 0x00c45406, 0x00c35307, 0x00ba490a, 0x00b7460d, 0x00b4440d, 0x00b0430b, 0x00b0440e, 0x00b14812, 0x00ad4612, 0x00ab4412, 0x00ac4818, 0x00a94616, 0x00aa4717, 0x00aa4516, 0x00ad4716, 0x00af4715, 0x00af4512, 0x00ad4514, 0x00ac4418, 0x00ad481a, 0x00ac4511, 0x00b1480e, 0x00b44509, 0x00b44408, 0x00b84a12, 0x00b84912, 0x00c34e12, 0x00c45010, 0x00c55815, 0x00bf5d1b, 0x00b06024, 0x00ae6027, 0x00b3561c, 0x00b95b21, 0x00b25b24, 0x00a75c2c, 0x00814922, 0x004c1d00, 0x00320000, 0x004b1100, 0x007f3c0a, 0x0098592c, 0x00512207, 0x002f0500, 0x005c2800, 0x00a96826, 0x00b96219, 0x00aa5c1f, 0x00542b0d, 0x000d0000, 0x000c0402, 0x00080000, 0x00210000, 0x005b2708, 0x009b5323, 0x00b66026, 0x00b45618, 0x00ac5620, 0x00773812, 0x003d1500, 0x000c0000, 0x00040000, 0x00080000, 0x00040000, 0x00000000, 0x00020200, 0x00020000, 0x00030000, 0x00060000, 0x000f0000, 0x00330c00, 0x006b311d, 0x00944927, 0x009d481e, 0x00a04819, 0x00a44a1a, 0x00a84e1e, 0x00a64c1d, 0x00a2461a, 0x00a44820, 0x00a24b2a, 0x0096482c, 0x0061250c, 0x003f1100, 0x00210000, 0x00140000, 0x00100000, 0x000b0000, 0x000d0000, 0x00180100, 0x00401c09, 0x006c3c20, 0x008f4d2d, 0x00984c25, 0x00a1491f, 0x00aa4b1c, 0x00ac481a, 0x00ac4614, 0x00b04812, 0x00af4811, 0x00b04814, 0x00b04918, 0x00af481a, 0x00ad451c, 0x00ae451c, 0x00b1461d, 0x00af4419, 0x00b2461a, 0x00b4481c, 0x00b44b19, 0x00b04817, 0x00ad4714, 0x00ac4815, 0x00ad4c19, 0x00ac491a, 0x00aa491d, 0x00a8481c, 0x00aa4b1c, 0x00a6491a, 0x009f4416, 0x0090380e, 0x009c4118, 0x00aa4820, 0x00ad4716, 0x00b5480c, 0x00c0510a, 0x00c25408, 0x00c35607, 0x00c7580c, 0x00bc5512, 0x00a85620, 0x005a2100, 0x00170000, 0x00030001, 0x0000010b, 0x0034363d, 0x009f9896, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00909092, 0x00383534, 0x000b0000, 0x00341300, 0x007e3d11, 0x00b4591b, 0x00ca5c10, 0x00c55000, 0x00c75708, 0x00b8520b, 0x00ac541f, 0x006c2d07, 0x00230600, 0x00200700, 0x00784028, 0x00985c40, 0x0050250a, 0x00280000, 0x00451500, 0x00844427, 0x00a85120, 0x00b24d10, 0x00b64f0e, 0x00b54c0c, 0x00b75014, 0x00b14c13, 0x00b34c18, 0x00ab5022, 0x00905028, 0x00380d00, 0x001a0000, 0x00451c08, 0x00934218, 0x00ad511f, 0x00a05125, 0x00783e1d, 0x002b0c00, 0x00130000, 0x00380d00, 0x008a4b28, 0x00a04c1a, 0x00b45218, 0x00b44f12, 0x00b64e11, 0x00ba4c13, 0x00b94b10, 0x00b84a10, 0x00b54b0f, 0x00b04b0d, 0x00b35012, 0x00b24c0f, 0x00b34a10, 0x00bb501b, 0x00ac481c, 0x00974623, 0x00642d14, 0x001a0000, 0x00060000, 0x00050000, 0x00100200, 0x00180000, 0x00471800, 0x008d471f, 0x00a85122, 0x00ac4c1c, 0x00b14d1a, 0x00b04a16, 0x00b54b14, 0x00b7480e, 0x00b9490d, 0x00b4470f, 0x00b34a14, 0x00b3501a, 0x009e5123, 0x007a5238, 0x00240900, 0x00381000, 0x00420e00, 0x003b0000, 0x004a0400, 0x007c3106, 0x00a3511e, 0x00b75c24, 0x00b85618, 0x00bf5415, 0x00c55413, 0x00c5540e, 0x00c75408, 0x00c85502, 0x00c45303, 0x00c95513, 0x00c45114, 0x00c45214, 0x00c35213, 0x00bd4d0e, 0x00b8480b, 0x00b4460c, 0x00b84b11, 0x00b44812, 0x00ac440d, 0x00ac450f, 0x00af4811, 0x00ae4710, 0x00b0470f, 0x00b0450c, 0x00b34710, 0x00b24714, 0x00b64c18, 0x00b64b10, 0x00be5211, 0x00c3530f, 0x00c2500d, 0x00c65618, 0x00c55417, 0x00cc5413, 0x00cb540e, 0x00c9570c, 0x00bd560d, 0x00b05a1a, 0x00ae5e22, 0x00b25f24, 0x00ac5b26, 0x008f471c, 0x00581e00, 0x002a0000, 0x00340a00, 0x0068330c, 0x00995828, 0x00b56424, 0x00ac6126, 0x00693411, 0x00270000, 0x00522000, 0x00a8692a, 0x00bc651c, 0x00a6591c, 0x004c2508, 0x000b0000, 0x00020000, 0x00080200, 0x00180100, 0x00260000, 0x00571c00, 0x00984918, 0x00b8571c, 0x00bc5b1f, 0x00ae5928, 0x008c4c26, 0x004b2611, 0x00170200, 0x000a0000, 0x00080100, 0x00040100, 0x00000000, 0x00020100, 0x00000000, 0x00020005, 0x00080004, 0x00100000, 0x00220000, 0x00521a06, 0x00844021, 0x009e5028, 0x00a04c20, 0x00a04819, 0x00a74a1b, 0x00ad4c1f, 0x00ab481c, 0x00a8441d, 0x00a54924, 0x009e502a, 0x008c4926, 0x006a3217, 0x00401300, 0x001e0000, 0x00130000, 0x000f0000, 0x000d0000, 0x00120000, 0x001d0100, 0x00370e00, 0x00632c10, 0x008c4a28, 0x009c4f2b, 0x009f4823, 0x00a84c20, 0x00a94918, 0x00ab4915, 0x00ac4815, 0x00ac4817, 0x00af4818, 0x00b0481a, 0x00b1471a, 0x00b0441a, 0x00b0471c, 0x00b0471c, 0x00ae471b, 0x00ab4618, 0x00ac4718, 0x00ad4a1a, 0x00ad4a18, 0x00aa4818, 0x00ab4a1c, 0x00a8481d, 0x00a5491e, 0x00a84c20, 0x00a84c1e, 0x009f4010, 0x00ab4c1c, 0x00ad4b1c, 0x00ad4a1a, 0x00b14812, 0x00b9490a, 0x00c15008, 0x00c9570a, 0x00c6580c, 0x00bd5710, 0x00b15b1f, 0x0073350a, 0x00230000, 0x00090000, 0x00000005, 0x000c131c, 0x007c7f86, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00585554, 0x000d0200, 0x00140000, 0x00612b07, 0x00ac5b23, 0x00c0580c, 0x00c85300, 0x00c95705, 0x00be5409, 0x00b05317, 0x00864418, 0x00240900, 0x00140000, 0x005c2a16, 0x00864c32, 0x00734124, 0x00390f00, 0x00300900, 0x00602c15, 0x00a9562a, 0x00b04d12, 0x00ba5111, 0x00b74d0c, 0x00b44c10, 0x00b44c16, 0x00b34f1c, 0x00a44d20, 0x00814724, 0x00360c00, 0x00200000, 0x00683319, 0x00a14a1d, 0x00a84c1c, 0x0094512e, 0x005c2d15, 0x00160000, 0x002a0800, 0x006a2c0b, 0x00a15122, 0x00b0521b, 0x00b04d14, 0x00b04e14, 0x00b34e13, 0x00ba4c13, 0x00bb4a10, 0x00b6480d, 0x00b74910, 0x00b74d14, 0x00b34a10, 0x00b34910, 0x00b34c15, 0x00ac4c1c, 0x00a04e28, 0x006d341b, 0x00240300, 0x00090000, 0x00000000, 0x00080000, 0x001a0000, 0x00511d04, 0x008e4520, 0x00a84e1b, 0x00af4c12, 0x00b34d14, 0x00b24b14, 0x00b44a17, 0x00b54916, 0x00b64711, 0x00b6480f, 0x00b44b10, 0x00b74f13, 0x00af460c, 0x00a85424, 0x005b2c10, 0x00250000, 0x007e411a, 0x00a2592d, 0x00833b10, 0x00521400, 0x00310300, 0x003b1000, 0x005c2a07, 0x00905025, 0x00ad5a29, 0x00b95822, 0x00c0581e, 0x00c25414, 0x00c55710, 0x00c4540c, 0x00c4540e, 0x00c55510, 0x00c5550f, 0x00c5540b, 0x00c75409, 0x00c8540a, 0x00c85308, 0x00c45008, 0x00c6530c, 0x00c4540d, 0x00c1540e, 0x00c15610, 0x00c15610, 0x00c25510, 0x00c3540e, 0x00c45310, 0x00c95415, 0x00c85413, 0x00c5560d, 0x00c25708, 0x00c45705, 0x00c45705, 0x00c4550c, 0x00c6530e, 0x00ca520e, 0x00cc5511, 0x00c04e09, 0x00b85515, 0x00ad612c, 0x009a5d2f, 0x007a4317, 0x004c1900, 0x00320000, 0x00350200, 0x00652c00, 0x00925019, 0x00ab5c22, 0x00ba6321, 0x00bb6017, 0x00b36423, 0x006f3814, 0x002e0400, 0x004c1c00, 0x00a06326, 0x00b5641c, 0x00a45c21, 0x00391a01, 0x00080000, 0x00050100, 0x00090000, 0x0058381e, 0x005f3010, 0x00360400, 0x004c1300, 0x00833c14, 0x00a95826, 0x00b3541b, 0x00b45a22, 0x009d5629, 0x006b3818, 0x00280a00, 0x000c0000, 0x000d0500, 0x00000000, 0x00000004, 0x00000108, 0x00040004, 0x00060001, 0x00070000, 0x000a0000, 0x00190000, 0x00360f03, 0x0070341d, 0x00924524, 0x00a84f24, 0x00ac491c, 0x00aa481a, 0x00ac481d, 0x00a94920, 0x00a1481e, 0x00a04d1f, 0x009a4d1f, 0x009a4d24, 0x00934c28, 0x007f4020, 0x005c250c, 0x00360a00, 0x001c0000, 0x00110000, 0x000f0000, 0x00110000, 0x00190000, 0x00300a00, 0x0053220c, 0x00793f23, 0x00955130, 0x009c4e28, 0x00a34d24, 0x00a74c20, 0x00a94919, 0x00ac4815, 0x00af4814, 0x00ae4814, 0x00ab4615, 0x00a9481c, 0x00a7491f, 0x00a74a23, 0x00a74a23, 0x00a94920, 0x00ac481f, 0x00ac4819, 0x00ac4818, 0x00aa4618, 0x00a9481b, 0x00a84c20, 0x00a84c20, 0x00a8481c, 0x00a74717, 0x00ab4814, 0x00ae4a14, 0x00b24c15, 0x00b85013, 0x00c1500f, 0x00c85510, 0x00c95812, 0x00bd5510, 0x00b45e20, 0x0080400f, 0x002c0800, 0x000d0000, 0x00070401, 0x00000005, 0x0060666c, 0x009b9ba0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007c7c7a, 0x0028201e, 0x00140000, 0x003c1000, 0x008d4819, 0x00bb5915, 0x00c85707, 0x00c85606, 0x00c25409, 0x00b45310, 0x00974f1f, 0x002d1000, 0x00140000, 0x003f1303, 0x007b452e, 0x00824e2e, 0x00481900, 0x00210000, 0x004b1f0e, 0x00984c26, 0x00b0531c, 0x00b24c0f, 0x00b54c0c, 0x00b44c10, 0x00b54e18, 0x00b04c18, 0x00a8542a, 0x006a3215, 0x002e0200, 0x00481500, 0x00803f20, 0x00aa5023, 0x00a75023, 0x007d4327, 0x003e1602, 0x00210000, 0x00481901, 0x008e4217, 0x00ac4e18, 0x00b35018, 0x00b04c13, 0x00b04e16, 0x00b04c14, 0x00b64c11, 0x00b84b11, 0x00b74911, 0x00b84b13, 0x00b84c15, 0x00b44812, 0x00b74b14, 0x00ae4b19, 0x00a35027, 0x007e4021, 0x003b1505, 0x000c0000, 0x00030000, 0x00040000, 0x00140000, 0x00502409, 0x008c4621, 0x00a54d1e, 0x00ac4913, 0x00b24c10, 0x00b44d13, 0x00b1480f, 0x00b44814, 0x00b74816, 0x00b74814, 0x00b74b14, 0x00b34a10, 0x00b34d14, 0x00ad4b15, 0x00984418, 0x00380400, 0x00532001, 0x00a0511f, 0x00b3591e, 0x00aa541c, 0x00a15a2a, 0x00724724, 0x003a1c00, 0x002b0c00, 0x002b0400, 0x004e1700, 0x007c3713, 0x009d4d25, 0x00b25a2b, 0x00ba5c24, 0x00b85618, 0x00b95815, 0x00bb5813, 0x00be5610, 0x00c1550c, 0x00c5560a, 0x00c95809, 0x00cc5708, 0x00ca5506, 0x00c95608, 0x00c65608, 0x00c55708, 0x00c45609, 0x00c45609, 0x00c4570a, 0x00c5580c, 0x00c8580c, 0x00ca540a, 0x00c85409, 0x00c15608, 0x00bf5808, 0x00c05a09, 0x00c05a0c, 0x00bc5814, 0x00bb5518, 0x00bd541a, 0x00bf5821, 0x00b85622, 0x009c4718, 0x00682502, 0x003f0800, 0x00320600, 0x00340800, 0x0068320c, 0x008d4e1f, 0x00a55d1f, 0x00b2611b, 0x00bc601a, 0x00bc5911, 0x00bd5b0e, 0x00b86421, 0x00733c15, 0x00310800, 0x00471b00, 0x00975f25, 0x00b3641d, 0x00a15b20, 0x00341701, 0x00080000, 0x00040000, 0x000e0000, 0x006c401b, 0x00945c2f, 0x0078441d, 0x00441100, 0x003c0500, 0x00743208, 0x00ab551f, 0x00b3561a, 0x00ab541e, 0x00a5592b, 0x00804a26, 0x00401800, 0x00180000, 0x000e0000, 0x00040000, 0x00020105, 0x00030002, 0x00020001, 0x00000004, 0x00020005, 0x00050004, 0x000d0000, 0x00270100, 0x00541d06, 0x00823c1d, 0x00994b25, 0x00a34e28, 0x00a44c23, 0x00a54a1f, 0x00a84d20, 0x00a44b1e, 0x00a14a1c, 0x00a1481c, 0x00a34c1f, 0x009f4c23, 0x00954824, 0x00854225, 0x00773f2a, 0x00502315, 0x00300d03, 0x001a0000, 0x00160000, 0x00180000, 0x001c0000, 0x002e0400, 0x00481700, 0x0074381e, 0x00884123, 0x00994c28, 0x00a14c23, 0x00a54818, 0x00a84612, 0x00ac4914, 0x00af4c18, 0x00a94919, 0x00a7491e, 0x00a64b21, 0x00a64b21, 0x00a84921, 0x00aa491f, 0x00ad481c, 0x00ae4719, 0x00af4c1c, 0x00aa4818, 0x00a64616, 0x00a84918, 0x00ac491a, 0x00ad4818, 0x00ae4710, 0x00b0460a, 0x00b44c0a, 0x00bd520e, 0x00c75713, 0x00c45414, 0x00bc5114, 0x00b35820, 0x00894818, 0x00360d00, 0x000e0000, 0x00020000, 0x00000000, 0x00484c4e, 0x00a1a4a8, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a9a8a7, 0x004c4845, 0x000c0000, 0x00220200, 0x005d2400, 0x00b15b20, 0x00bf560d, 0x00c45408, 0x00c4570c, 0x00ba540e, 0x00a55723, 0x00441c04, 0x001c0200, 0x00210000, 0x00643522, 0x008b5434, 0x00602c10, 0x00240200, 0x00340f00, 0x007b3817, 0x00a95424, 0x00ae4d13, 0x00b65013, 0x00b64d14, 0x00b34c15, 0x00ae4c16, 0x00a85329, 0x004d1600, 0x00380600, 0x00773518, 0x009b4a25, 0x00ab5024, 0x00a15129, 0x0063321b, 0x00280400, 0x00380800, 0x00723312, 0x00ac5121, 0x00b24c13, 0x00b24d12, 0x00b04c13, 0x00b04e16, 0x00ae4b13, 0x00b24c13, 0x00b64c14, 0x00b54b15, 0x00b64a15, 0x00b84915, 0x00b64814, 0x00b44a17, 0x00a94f22, 0x00884524, 0x00491e09, 0x00100000, 0x00060000, 0x00070000, 0x00140100, 0x004e240a, 0x00844620, 0x00a95426, 0x00ad4d1b, 0x00ac4c1a, 0x00af4c18, 0x00af4912, 0x00b54c12, 0x00b6480f, 0x00b74911, 0x00b54916, 0x00b74c18, 0x00b04811, 0x00ac4c1a, 0x00a05026, 0x00702d0a, 0x00300000, 0x007d3c15, 0x00b0561c, 0x00c35b16, 0x00bd550f, 0x00b85c1b, 0x00a4602d, 0x0071401b, 0x00331200, 0x00140000, 0x00190000, 0x00250700, 0x00300900, 0x00501c02, 0x0074330c, 0x00914615, 0x00a95c25, 0x00af5d22, 0x00b65c21, 0x00ba5b1b, 0x00bb5612, 0x00bc540c, 0x00c1550c, 0x00c6580d, 0x00c25709, 0x00c25709, 0x00c1570b, 0x00c1570b, 0x00c1570b, 0x00c2580c, 0x00c2580d, 0x00c2580a, 0x00c45908, 0x00c05908, 0x00bd5a12, 0x00bc5c19, 0x00b95d1c, 0x00b35a21, 0x00a75425, 0x009c5028, 0x00813a1a, 0x00672407, 0x004e0c00, 0x00420200, 0x00390000, 0x00320000, 0x004c1c05, 0x008d542d, 0x00a35317, 0x00bd621b, 0x00b86013, 0x00b65b0e, 0x00c06018, 0x00c45d16, 0x00c35b0c, 0x00bb631f, 0x007a441a, 0x00361000, 0x003f1900, 0x008c5822, 0x00b1631c, 0x00a0581c, 0x00321000, 0x00080000, 0x00040000, 0x00140000, 0x00844d19, 0x00aa6323, 0x00a75e24, 0x00884814, 0x00562100, 0x003c0a00, 0x00591c00, 0x008e471a, 0x00b05c2a, 0x00b45a25, 0x00b25922, 0x00a35424, 0x00703113, 0x002b0100, 0x00120000, 0x00050000, 0x00020000, 0x00040307, 0x0000020c, 0x00000009, 0x00000005, 0x00080001, 0x00100000, 0x00180200, 0x002b0d00, 0x004e2814, 0x00794429, 0x0094502d, 0x00a04c20, 0x00a4481a, 0x00a94b23, 0x00a84b24, 0x00a74a21, 0x00a54a20, 0x00a44c21, 0x00a24c21, 0x009f4a20, 0x00994922, 0x00944824, 0x00894324, 0x007a3b22, 0x00642c18, 0x00481808, 0x002e0400, 0x00200000, 0x00200000, 0x002c0200, 0x00451401, 0x00672c13, 0x00844020, 0x009b4b23, 0x00a44c1d, 0x00a84817, 0x00a8440f, 0x00ae4815, 0x00ae4815, 0x00ac4818, 0x00ac481a, 0x00ac481a, 0x00ac481c, 0x00ad481a, 0x00ac481a, 0x00ac481a, 0x00ab4816, 0x00ad4812, 0x00b04a14, 0x00af4816, 0x00af4813, 0x00b6490c, 0x00be4f0b, 0x00c65608, 0x00c55508, 0x00c1510c, 0x00c45a1e, 0x00b45929, 0x00853f18, 0x00401600, 0x00100000, 0x00020000, 0x00020707, 0x002e302f, 0x00969696, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00757473, 0x0018100b, 0x00180100, 0x00380d00, 0x00904818, 0x00b55919, 0x00bc540d, 0x00c3580c, 0x00bd540c, 0x00ac561c, 0x00633014, 0x00290800, 0x00170000, 0x00441e0c, 0x0081472c, 0x00784125, 0x00361404, 0x00240200, 0x005b2308, 0x009b4f28, 0x00aa501d, 0x00b04e14, 0x00b34c14, 0x00b04b14, 0x00b04e18, 0x00974317, 0x00470b00, 0x005d220c, 0x00974624, 0x00a84f24, 0x00a44c22, 0x00924925, 0x004f220c, 0x002d0500, 0x00581d00, 0x00964820, 0x00b04d1c, 0x00b44a10, 0x00b0490f, 0x00b04d14, 0x00b14e16, 0x00ae4b13, 0x00b04b14, 0x00b44c16, 0x00b44a16, 0x00b44816, 0x00b74816, 0x00b44818, 0x00aa491c, 0x00994c26, 0x005d2b10, 0x00220600, 0x000b0000, 0x000c0000, 0x001b0300, 0x00451d09, 0x00894c2a, 0x00a05023, 0x00a74b18, 0x00ab4814, 0x00b05020, 0x00ae4c1c, 0x00ad4713, 0x00b74e16, 0x00b54b0f, 0x00b74910, 0x00b44813, 0x00b44b18, 0x00ad4716, 0x00a74e22, 0x008d4b2b, 0x004a0f00, 0x00500c00, 0x00a45122, 0x00bb5717, 0x00c7580d, 0x00c75709, 0x00bd5910, 0x00ae6028, 0x00723c13, 0x00280900, 0x000c0000, 0x00040000, 0x00040000, 0x00100000, 0x001d0300, 0x002e0400, 0x00410f00, 0x004a1400, 0x005b1c00, 0x00742c02, 0x008c3c10, 0x009e4718, 0x00a84e19, 0x00b0541c, 0x00b75a1e, 0x00b6591c, 0x00b75a1c, 0x00b95b20, 0x00bb5c21, 0x00bc5b20, 0x00bb5b1e, 0x00b85a1c, 0x00b55919, 0x00b35714, 0x00ab5213, 0x009e4814, 0x00903c10, 0x00813007, 0x00702200, 0x00601500, 0x00540e00, 0x00480600, 0x004a0800, 0x004f0800, 0x00580f0c, 0x005e1519, 0x00430000, 0x00400800, 0x00884a27, 0x00b45f20, 0x00bc5a0b, 0x00c05f0b, 0x00c05d0b, 0x00c05b10, 0x00c35a11, 0x00c45809, 0x00c0631d, 0x0085491b, 0x00431900, 0x003b1400, 0x0081501e, 0x00af641e, 0x009c561b, 0x002c0b00, 0x000a0000, 0x00080000, 0x00180000, 0x0094551c, 0x00b46118, 0x00b15b13, 0x00b46523, 0x00975822, 0x00642d00, 0x00451000, 0x004e1100, 0x00782d04, 0x00a85323, 0x00b95c22, 0x00b3551d, 0x00a45022, 0x008b4822, 0x004f2400, 0x00280c00, 0x000d0000, 0x00060000, 0x00030002, 0x00020005, 0x00040005, 0x00030000, 0x00000000, 0x00020000, 0x00080200, 0x00150700, 0x002f1000, 0x004c1d05, 0x00743310, 0x00944823, 0x00984824, 0x009c4a28, 0x00a04b28, 0x009f4824, 0x00a04720, 0x00a44920, 0x00a8481e, 0x00a8481c, 0x00a54619, 0x00a64b20, 0x009d4822, 0x008c3f1d, 0x00803e23, 0x007a422d, 0x006b3c2c, 0x005c2f21, 0x004b1d0d, 0x00481602, 0x00471000, 0x00521200, 0x006b2000, 0x0087330c, 0x009e4216, 0x00ac4919, 0x00ae4614, 0x00b04613, 0x00b04714, 0x00af4814, 0x00ae4815, 0x00ac4817, 0x00ab4818, 0x00aa4818, 0x00a94718, 0x00ab4714, 0x00b1480e, 0x00b44a0e, 0x00b2480f, 0x00b3480d, 0x00bd4e0c, 0x00c7560c, 0x00c85504, 0x00c55708, 0x00bb5310, 0x00b45620, 0x008f4019, 0x004b1000, 0x001a0000, 0x000d0000, 0x00010302, 0x00040a0c, 0x007c7c7a, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a3a3a4, 0x00484444, 0x000d0100, 0x00210400, 0x00582300, 0x00a45827, 0x00b85919, 0x00c0580f, 0x00c1560a, 0x00b15414, 0x00884723, 0x00340800, 0x00170000, 0x00280900, 0x006c341d, 0x00894f35, 0x004c2611, 0x00210000, 0x003e1000, 0x007e4124, 0x00a15226, 0x00a74b17, 0x00af4b15, 0x00b14c16, 0x00af4d18, 0x00842e01, 0x00642004, 0x00874026, 0x00a84b25, 0x00ad4c22, 0x00a45029, 0x007c3a1a, 0x003f1100, 0x00431400, 0x007f3812, 0x00aa5023, 0x00ae4817, 0x00b34814, 0x00b14c13, 0x00b04c13, 0x00b04c13, 0x00ae4b13, 0x00b14c14, 0x00b34d18, 0x00b34915, 0x00b44816, 0x00b44b19, 0x00ac4c1e, 0x009e4e26, 0x00753c1c, 0x00300e00, 0x00140000, 0x00120000, 0x001e0100, 0x00461804, 0x0089482a, 0x00a05024, 0x00a94e1c, 0x00ab4c19, 0x00ab4b18, 0x00ad4b1c, 0x00af4c1c, 0x00b04a18, 0x00b04913, 0x00b04a0e, 0x00b44b0f, 0x00b44810, 0x00b44a17, 0x00aa491f, 0x009e4d2c, 0x006f381f, 0x00320000, 0x00823001, 0x00bb581c, 0x00c35611, 0x00c45408, 0x00ca5c10, 0x00c05f1a, 0x00a45924, 0x00582502, 0x00130000, 0x00070000, 0x00000000, 0x00020403, 0x00040000, 0x000a0000, 0x002f190a, 0x00533727, 0x002c0b00, 0x00300700, 0x00370200, 0x00400300, 0x004c0800, 0x00540c00, 0x00581400, 0x005b1800, 0x00642101, 0x00652102, 0x00692104, 0x006b2104, 0x006c2004, 0x006a1f00, 0x00661f00, 0x00651e00, 0x00601900, 0x005c1500, 0x00551002, 0x00500a02, 0x004d0500, 0x004f0500, 0x00530600, 0x00580600, 0x006c1207, 0x0075140b, 0x00841712, 0x008d1d1e, 0x0090252e, 0x0070151c, 0x00430400, 0x004b1200, 0x009c5426, 0x00b45e1c, 0x00c3620f, 0x00c96109, 0x00c65c0c, 0x00c45a0c, 0x00c85c0c, 0x00bb5c14, 0x00944e17, 0x00552000, 0x003c0f00, 0x0078461b, 0x00aa6425, 0x00945520, 0x00270600, 0x000d0000, 0x00110000, 0x002b0400, 0x009a541f, 0x00b85f17, 0x00c05f14, 0x00bd5c12, 0x00b45b13, 0x00ac5c1a, 0x00843e05, 0x005c1e00, 0x00420b00, 0x00571c00, 0x00884315, 0x00ae5c24, 0x00bc5e20, 0x00b95c1e, 0x009b4a10, 0x00743404, 0x00481900, 0x00210400, 0x000e0000, 0x00090000, 0x00080000, 0x00020000, 0x00010204, 0x00020304, 0x00010000, 0x00050000, 0x000f0000, 0x001b0100, 0x002b0d00, 0x003e1906, 0x005a2a0d, 0x00713818, 0x00894628, 0x00994e30, 0x00a34e2f, 0x00a84b2a, 0x00a94520, 0x00a64118, 0x00ac481c, 0x00aa4818, 0x00a64918, 0x00a44c1d, 0x00a45024, 0x00a04f28, 0x00994825, 0x008f4220, 0x008c4524, 0x00854120, 0x00803a1a, 0x007f3516, 0x00823515, 0x008c3918, 0x0099401c, 0x00a3441c, 0x00ac461a, 0x00b04516, 0x00b04513, 0x00b04612, 0x00ad4612, 0x00ab4714, 0x00a84815, 0x00a74818, 0x00ab4b1b, 0x00aa4613, 0x00b04206, 0x00b74606, 0x00ba4c0c, 0x00bd500f, 0x00c2520c, 0x00c55509, 0x00c35406, 0x00c35c13, 0x00b1581e, 0x0087390d, 0x00541300, 0x00441200, 0x0044220e, 0x00180500, 0x00060000, 0x00000002, 0x00716e6d, 0x00a09d9b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007c7b7f, 0x00191414, 0x000d0000, 0x00300a00, 0x007b3e17, 0x00b55f25, 0x00bf5811, 0x00c45708, 0x00b95611, 0x00a3552c, 0x00440f00, 0x00170000, 0x00180000, 0x0057200e, 0x00894d36, 0x00683c23, 0x002e0a00, 0x00250000, 0x00592914, 0x00944f29, 0x00a85323, 0x00b04f1b, 0x00ae4a14, 0x00ac4c18, 0x00832b00, 0x008e3f1d, 0x00a14c2c, 0x00b04b22, 0x00ae4b21, 0x00a15230, 0x00642808, 0x003b0b00, 0x005d2805, 0x009d4c21, 0x00af4c1d, 0x00b24a1c, 0x00b24817, 0x00b4501b, 0x00ad4c11, 0x00af4c12, 0x00b04a11, 0x00b24c15, 0x00b34c15, 0x00b44914, 0x00b44b17, 0x00b14c1c, 0x00a34d22, 0x00844624, 0x004a210a, 0x00110000, 0x000d0000, 0x001f0300, 0x00451804, 0x00803b20, 0x00a8532e, 0x00aa4d1c, 0x00ac4914, 0x00b04c18, 0x00b34f1c, 0x00ae491a, 0x00ad4819, 0x00b24c18, 0x00af4912, 0x00b0490d, 0x00b24c10, 0x00b34a14, 0x00b14c1d, 0x00a94c25, 0x00904527, 0x00511d07, 0x00390100, 0x00a54c19, 0x00c05413, 0x00c55509, 0x00c45405, 0x00c35c0f, 0x00b35c19, 0x0088481b, 0x00471d00, 0x00140100, 0x00040000, 0x00000000, 0x00000504, 0x00000000, 0x00110a04, 0x003c2e28, 0x004c342d, 0x00280100, 0x003e090b, 0x00541316, 0x00611518, 0x00631011, 0x005d0c08, 0x00540901, 0x00500900, 0x004e0800, 0x004e0700, 0x00510400, 0x00530200, 0x00540100, 0x00540200, 0x00510400, 0x00500500, 0x00520400, 0x00540702, 0x0058080f, 0x005d0d15, 0x00651115, 0x00701618, 0x007d1b1c, 0x00851d1d, 0x00932120, 0x00991f1b, 0x00ac2523, 0x00ab2022, 0x009c1922, 0x00902029, 0x00681818, 0x003d0000, 0x00632405, 0x00a25b26, 0x00b85c0f, 0x00c05b02, 0x00c45d0a, 0x00c25b09, 0x00cc6112, 0x00b7560f, 0x009d5218, 0x00622600, 0x003a0800, 0x00703c19, 0x00a56429, 0x008c5420, 0x001f0200, 0x000c0000, 0x00120000, 0x00401500, 0x009f5520, 0x00b45811, 0x00c35f14, 0x00c45e0f, 0x00bf5808, 0x00be5e10, 0x00b05915, 0x00924812, 0x006c3110, 0x004b1600, 0x00491100, 0x006f2c00, 0x009c4910, 0x00b55b1c, 0x00b85e20, 0x00ac5920, 0x00904c1e, 0x0068320c, 0x00401600, 0x00260600, 0x00160000, 0x000c0000, 0x00040000, 0x00030000, 0x00040000, 0x00050000, 0x00090000, 0x00080000, 0x00060000, 0x000c0000, 0x001b0400, 0x002c0b00, 0x00411603, 0x00541f0a, 0x00682814, 0x007f361f, 0x00944429, 0x00a34e2f, 0x009f4924, 0x009e481f, 0x00a04a1d, 0x00a24b1c, 0x00a3481a, 0x00a14417, 0x00a8471c, 0x00ad4d24, 0x00a1461c, 0x00a04a20, 0x00a14c27, 0x00a04c2a, 0x009d4828, 0x009b4524, 0x009d4420, 0x00a24520, 0x00aa471d, 0x00ad4618, 0x00af4514, 0x00af4512, 0x00ad4612, 0x00ab4714, 0x00a94815, 0x00a84817, 0x00ab4818, 0x00b04713, 0x00b84808, 0x00be4b06, 0x00c0520c, 0x00c45710, 0x00c75810, 0x00c45910, 0x00c05c18, 0x00a95017, 0x007c3408, 0x004f1100, 0x00440c00, 0x00744020, 0x00825235, 0x0046210e, 0x00100000, 0x00050000, 0x0026201e, 0x00908c8a, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a8ac, 0x004f4e53, 0x000c0402, 0x001c0300, 0x00471700, 0x009a4b17, 0x00bc5814, 0x00c45808, 0x00c0580f, 0x00b25829, 0x0065260c, 0x001e0500, 0x00110000, 0x00400d00, 0x00783c27, 0x00804e2f, 0x004f280d, 0x001f0000, 0x00350f04, 0x0075391a, 0x00a45428, 0x00ae501e, 0x00ac4a14, 0x00aa4e1a, 0x00963c0c, 0x00a74c22, 0x00ad4d25, 0x00b3481d, 0x00af4b24, 0x008c4324, 0x00531800, 0x004c1700, 0x007d4016, 0x00a85021, 0x00ae491a, 0x00b44b20, 0x00b14a1c, 0x00b04e18, 0x00ab4c13, 0x00ad4c11, 0x00ae4b11, 0x00b24c13, 0x00b44912, 0x00b7480f, 0x00b64c14, 0x00a84c1b, 0x00904820, 0x00582c14, 0x00230a00, 0x000b0000, 0x00150000, 0x00421904, 0x007c3c20, 0x00a74e2c, 0x00ad4820, 0x00b0501d, 0x00ac4812, 0x00b4450e, 0x00bb4914, 0x00b44a18, 0x00af4816, 0x00b24c13, 0x00b34c10, 0x00b1490c, 0x00b04b12, 0x00ad4b1c, 0x00aa4e23, 0x00a44c24, 0x00833816, 0x003f0800, 0x00602404, 0x00ad5620, 0x00c45b14, 0x00c85804, 0x00c45802, 0x00be6112, 0x00b06628, 0x006a3c15, 0x00200600, 0x00080000, 0x00020000, 0x00000100, 0x00000100, 0x00000000, 0x00100707, 0x00291414, 0x00370e0c, 0x00520809, 0x00751418, 0x008f2128, 0x00982028, 0x00941820, 0x008c1419, 0x00851618, 0x00801818, 0x007b1715, 0x007c1516, 0x007e1114, 0x00800f14, 0x00820e14, 0x00821013, 0x00801313, 0x00801514, 0x00851717, 0x0088181b, 0x008d1c24, 0x00941f27, 0x00992123, 0x009e1f22, 0x00a21c23, 0x00a41b24, 0x00a41b22, 0x00a4171d, 0x00af181b, 0x00ae1519, 0x00a41018, 0x00a21f26, 0x008b2427, 0x00580902, 0x003d0100, 0x007c401b, 0x00b0601b, 0x00bc600c, 0x00b85b06, 0x00b85804, 0x00c25c0b, 0x00bc5d15, 0x00a2571f, 0x00692c04, 0x00360300, 0x00673319, 0x00a0602c, 0x00855020, 0x00150000, 0x00080000, 0x00110000, 0x00461e04, 0x00a05a20, 0x00b96017, 0x00b95a10, 0x00bc580e, 0x00c15b0a, 0x00c55c0b, 0x00c95f0e, 0x00b6530e, 0x00a24e20, 0x007e3b18, 0x00551e00, 0x00451400, 0x00542100, 0x00733814, 0x00a05426, 0x00ac5824, 0x00b05925, 0x00a85422, 0x00914719, 0x006e3009, 0x00481a00, 0x00300f00, 0x001b0400, 0x000f0000, 0x000a0000, 0x00080000, 0x00080000, 0x00080304, 0x00040006, 0x00040005, 0x00040000, 0x00060000, 0x000f0000, 0x00180400, 0x00250a03, 0x00341207, 0x00441c0f, 0x00502414, 0x00673620, 0x00733c21, 0x00814324, 0x00904827, 0x009d4b28, 0x00a44b26, 0x00a84721, 0x00a8411a, 0x00b04820, 0x00ad451c, 0x00a8441b, 0x00a8451c, 0x00a8461f, 0x00a7471d, 0x00a7491f, 0x00a84b20, 0x00a8471b, 0x00a94718, 0x00aa4717, 0x00aa4715, 0x00ab4615, 0x00ac4716, 0x00ac4818, 0x00ae4817, 0x00b04612, 0x00bb4c13, 0x00c5500e, 0x00c6520b, 0x00c4550c, 0x00c25910, 0x00bf5810, 0x00b35515, 0x00984817, 0x006f2e08, 0x00411100, 0x00360900, 0x00501a00, 0x00a05f32, 0x00a4592c, 0x00884723, 0x00300b00, 0x00100000, 0x00060000, 0x00585454, 0x00acb0b0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0087888c, 0x00241f1f, 0x000e0000, 0x00230200, 0x00642904, 0x00ad5c22, 0x00c05910, 0x00c4580e, 0x00b6551e, 0x0086401b, 0x002b0c00, 0x00100000, 0x002b0000, 0x00612b18, 0x00885130, 0x00704023, 0x002c0b00, 0x00240200, 0x00501d07, 0x008c4824, 0x00a44b1e, 0x00af501b, 0x00ac521c, 0x00aa4e1a, 0x00a94518, 0x00b34b21, 0x00ae461c, 0x00a94d28, 0x00712e11, 0x00481000, 0x00642804, 0x00985026, 0x00a54a1a, 0x00b04918, 0x00af4619, 0x00b34c1e, 0x00a94711, 0x00af4e15, 0x00af4c12, 0x00b14b12, 0x00b34a14, 0x00b24812, 0x00b5460f, 0x00b24b17, 0x009d481b, 0x007e401f, 0x00341400, 0x000e0000, 0x00190400, 0x00381400, 0x0074391a, 0x00a05028, 0x00ad4820, 0x00b4481c, 0x00ae4815, 0x00b44c15, 0x00bb4810, 0x00b8440f, 0x00b34916, 0x00b24c18, 0x00b24c11, 0x00b34b0e, 0x00b14b10, 0x00b04a13, 0x00ac4b18, 0x00a84d20, 0x00994922, 0x0075300d, 0x00390000, 0x0089441d, 0x00b5571c, 0x00c55a0e, 0x00c25401, 0x00c25c08, 0x00b35d12, 0x009a5c22, 0x004b290b, 0x00130400, 0x00060000, 0x00000000, 0x00000200, 0x00000000, 0x00070202, 0x000d0000, 0x001e0000, 0x004c0c10, 0x00821920, 0x009a1a22, 0x00a51c27, 0x00a61823, 0x00a51820, 0x00a71c23, 0x00a21e24, 0x009b1a1e, 0x009e1d21, 0x009e1d22, 0x009e1c28, 0x009e1c29, 0x00a01c27, 0x00a01d26, 0x009f1f25, 0x00a02024, 0x00a01b20, 0x00a21b20, 0x00a11920, 0x00a41920, 0x00a8191e, 0x00ab181e, 0x00ad1421, 0x00ad1322, 0x00ab1420, 0x00ae1821, 0x00ab1216, 0x00ae1618, 0x00b1181f, 0x00a51820, 0x00991e24, 0x00822021, 0x00420000, 0x004d1400, 0x00985219, 0x00b36316, 0x00b45e07, 0x00c0640b, 0x00b85503, 0x00ba5e17, 0x00a75a1f, 0x006e3007, 0x00330100, 0x005f2e18, 0x009d5d2e, 0x00824d1f, 0x00110000, 0x00070000, 0x00120000, 0x00522809, 0x00a2581b, 0x00b85d10, 0x00bb5a10, 0x00c15e11, 0x00c35c0c, 0x00c05604, 0x00c45400, 0x00c95c10, 0x00bb5a20, 0x00a45425, 0x008d5026, 0x00542606, 0x001d0000, 0x002d0c00, 0x005a2408, 0x00833e18, 0x00a35225, 0x00af5827, 0x00b45d2c, 0x00a95929, 0x008e481d, 0x00743912, 0x005a2905, 0x00461c00, 0x002e0b00, 0x001e0200, 0x00140000, 0x000b0000, 0x00080000, 0x00070000, 0x00080000, 0x00050000, 0x00050000, 0x00080000, 0x000a0000, 0x000e0000, 0x00140000, 0x001c0000, 0x00280700, 0x00370e00, 0x004b1907, 0x005c2009, 0x006c2207, 0x007f2908, 0x00983711, 0x00ac441b, 0x00b24219, 0x00b14118, 0x00b0441c, 0x00b0471d, 0x00ad461a, 0x00a94418, 0x00a84416, 0x00a94718, 0x00a94719, 0x00a94719, 0x00aa4618, 0x00ab4615, 0x00ae4614, 0x00b04714, 0x00b14814, 0x00b44811, 0x00bf4f13, 0x00c45213, 0x00c8530f, 0x00c5520c, 0x00c25711, 0x00bc5a16, 0x00aa5014, 0x00944511, 0x00642300, 0x00471400, 0x00421c06, 0x004f270c, 0x00581e00, 0x00b26630, 0x00b6591d, 0x00ad5925, 0x005e280c, 0x001c0000, 0x000c0000, 0x00121013, 0x00808585, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00aeadac, 0x006d6966, 0x00110804, 0x000c0000, 0x00270d00, 0x006f3c1a, 0x00b65b20, 0x00c35810, 0x00bf5815, 0x00a2531f, 0x003f1600, 0x00140000, 0x00160000, 0x004b1e10, 0x00804424, 0x008a4e2c, 0x00592e19, 0x00210000, 0x002b0500, 0x00602c14, 0x009e5028, 0x00a84c1a, 0x00ac5018, 0x00a74811, 0x00b24b1f, 0x00b04821, 0x00a94920, 0x00974621, 0x00541c01, 0x00481400, 0x00803e1e, 0x00994922, 0x00aa4e20, 0x00af4b18, 0x00b24815, 0x00b34915, 0x00b04a14, 0x00af4912, 0x00b14710, 0x00b64a15, 0x00ae4713, 0x00af4715, 0x00b44b19, 0x00a9481c, 0x00964826, 0x00552007, 0x001c0100, 0x00130000, 0x003a0f00, 0x00733718, 0x009b4c1e, 0x00a74b18, 0x00ac471b, 0x00b4481e, 0x00b84818, 0x00b84715, 0x00b64713, 0x00b34813, 0x00b04a16, 0x00af4b15, 0x00b34a10, 0x00b24910, 0x00b04c17, 0x00b04a13, 0x00b24808, 0x00b35219, 0x008f4a24, 0x004d1200, 0x00541000, 0x00ac5826, 0x00c35610, 0x00cb5808, 0x00c15608, 0x00b8580f, 0x00b36220, 0x00824916, 0x00301700, 0x00070000, 0x00000000, 0x00000100, 0x00000400, 0x00000100, 0x000c0100, 0x00190000, 0x004b0b12, 0x007a1c27, 0x00a01b2b, 0x00ad1828, 0x00ad1828, 0x00aa1623, 0x00a4181d, 0x00a4191c, 0x00a51b20, 0x00ab1b1d, 0x00b01716, 0x00ac1418, 0x00a71a2c, 0x009e182c, 0x00a01c28, 0x00a72328, 0x009d191f, 0x00a61d24, 0x00a9161c, 0x00ac161c, 0x00aa181c, 0x00aa171d, 0x00ac1721, 0x00ae1825, 0x00b01425, 0x00af1224, 0x00ac1621, 0x00a8181c, 0x00a61919, 0x00a61a18, 0x00a8181c, 0x00a8181f, 0x00a51823, 0x00981e28, 0x00651014, 0x00390000, 0x007c4014, 0x00a4601c, 0x00b05d04, 0x00bb5f01, 0x00be5f0d, 0x00b45912, 0x00ab5d1e, 0x00763708, 0x002d0100, 0x0053250e, 0x00a15c31, 0x0082451e, 0x00100000, 0x00060000, 0x00110000, 0x00673915, 0x00aa5c1d, 0x00b95a0a, 0x00be5806, 0x00bf5907, 0x00c05a09, 0x00c05908, 0x00c05908, 0x00bf580c, 0x00c05c18, 0x00b35818, 0x00ac5c20, 0x0082491e, 0x00120000, 0x00090000, 0x00170000, 0x00351001, 0x005c2c13, 0x007c3f1c, 0x009b4e26, 0x00b05928, 0x00b75d20, 0x00b35a19, 0x00a95418, 0x00944710, 0x007c360c, 0x00652908, 0x00532000, 0x00441900, 0x00331100, 0x00270800, 0x00240600, 0x001f0200, 0x00180100, 0x00180000, 0x001a0000, 0x001c0000, 0x00210000, 0x00270100, 0x002b0400, 0x002e0500, 0x00360900, 0x00471200, 0x005d1d01, 0x00782b04, 0x00933808, 0x00a64110, 0x00b24218, 0x00b3411b, 0x00ac421e, 0x00ab441f, 0x00ac461c, 0x00ad4618, 0x00ad4515, 0x00ac4414, 0x00aa4317, 0x00b0491d, 0x00b04819, 0x00af4411, 0x00b5480e, 0x00ba4c10, 0x00bb4e11, 0x00c05312, 0x00c8540b, 0x00cb540c, 0x00c55410, 0x00c05313, 0x00ba5418, 0x00a64c18, 0x007b3309, 0x00531900, 0x00451100, 0x00673810, 0x0073492c, 0x00643417, 0x00601e00, 0x00b86428, 0x00bf5b11, 0x00ba5814, 0x00984f1c, 0x003b0c00, 0x000d0000, 0x0005040b, 0x00424546, 0x00a4a9a6, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a7a3a0, 0x00403b36, 0x000d0600, 0x00070000, 0x00341704, 0x008c441a, 0x00b6581c, 0x00bc5914, 0x00b05a20, 0x005a2606, 0x00210200, 0x00150000, 0x00200200, 0x006d3518, 0x00915230, 0x00764125, 0x00431803, 0x00230000, 0x00340b00, 0x007d3c1c, 0x00a25124, 0x00a54c14, 0x00ab4a13, 0x00b34a1d, 0x00ac4720, 0x00a24e28, 0x0074310c, 0x00420d00, 0x005b2409, 0x00924525, 0x00a44b23, 0x00ac4c1e, 0x00af4816, 0x00b14814, 0x00b24913, 0x00b04a13, 0x00b04a13, 0x00b04610, 0x00b34814, 0x00b24c18, 0x00ac4a18, 0x00aa4a1a, 0x00a04c22, 0x00763618, 0x003b0e00, 0x00170000, 0x00301001, 0x00692d14, 0x00984820, 0x00ac5018, 0x00af4c12, 0x00ac4919, 0x00af481c, 0x00b44818, 0x00b54715, 0x00b24815, 0x00ae4a17, 0x00ac4b18, 0x00ad4a17, 0x00b34a14, 0x00b44a13, 0x00b04913, 0x00b44c12, 0x00be4f0b, 0x00b05116, 0x007c401f, 0x003e0900, 0x00742800, 0x00ba5a1d, 0x00c45104, 0x00cb5503, 0x00c2580d, 0x00b75b1a, 0x00a85d26, 0x0065340c, 0x001f0800, 0x00050000, 0x00030000, 0x00020400, 0x00000600, 0x00000000, 0x000e0000, 0x002f0000, 0x007f232d, 0x00941928, 0x00a61426, 0x00ac1223, 0x00ab1220, 0x00aa1520, 0x00a81a1f, 0x00a81b20, 0x00a8171e, 0x00a61016, 0x00b41718, 0x00aa1519, 0x009d1e2e, 0x00962434, 0x008b1c21, 0x00780a0a, 0x00750508, 0x008f161c, 0x00a52025, 0x00a81820, 0x00aa181c, 0x00ac171e, 0x00ad1421, 0x00ab1021, 0x00ad1022, 0x00b01524, 0x00a9141d, 0x00a7161c, 0x00a3181a, 0x00a21a1b, 0x00a4191b, 0x00a7171e, 0x00a81721, 0x00a01a28, 0x00821c25, 0x004a0000, 0x005b1f00, 0x0097581f, 0x00b2600d, 0x00b95c02, 0x00ba5c0c, 0x00b85c15, 0x00af5e1c, 0x00793907, 0x002c0400, 0x004b2008, 0x009c5833, 0x007c401e, 0x000e0000, 0x00060000, 0x00170000, 0x0074431d, 0x00ab5a1a, 0x00bb5809, 0x00c05906, 0x00c25904, 0x00bf5808, 0x00bd580a, 0x00bd5a0d, 0x00bc580c, 0x00c15c10, 0x00b8580f, 0x00b15a18, 0x00834618, 0x00110000, 0x00010000, 0x00050001, 0x000d0000, 0x00170000, 0x00381100, 0x00672c10, 0x007f370f, 0x009e4c14, 0x00b05818, 0x00b85c1c, 0x00b45a1d, 0x00b35c28, 0x00b05e2c, 0x009f5523, 0x00884416, 0x00783812, 0x00733715, 0x00682c0c, 0x005f2808, 0x0055230a, 0x0051210b, 0x0051210c, 0x0053220c, 0x0057210a, 0x005a230a, 0x005f2810, 0x00632c14, 0x006c331c, 0x007a3b22, 0x008a4020, 0x0097461c, 0x00a54a18, 0x00b04c19, 0x00b04415, 0x00b04418, 0x00ac461c, 0x00aa471c, 0x00ac4818, 0x00af4715, 0x00af4814, 0x00af4814, 0x00ae4817, 0x00b04714, 0x00b4470f, 0x00bc4b0e, 0x00c1500e, 0x00c2500c, 0x00c15410, 0x00c75b13, 0x00c55708, 0x00be540b, 0x00b7551b, 0x00ae5422, 0x00944011, 0x006c2300, 0x00531500, 0x00501800, 0x007a420b, 0x00935d27, 0x00855732, 0x005a2804, 0x00591800, 0x00b96728, 0x00c45f0f, 0x00bc5504, 0x00b86021, 0x006d3008, 0x00180000, 0x00030001, 0x00131112, 0x007f807c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00333231, 0x009a9490, 0x00221b15, 0x00050000, 0x00100000, 0x004d2207, 0x00914f24, 0x00b4581e, 0x00b45b21, 0x00783812, 0x00300800, 0x000e0000, 0x00140100, 0x004f240c, 0x00874e2c, 0x00935433, 0x0073381e, 0x002b0000, 0x00220000, 0x00451500, 0x00884828, 0x00a24f1c, 0x00ac4b15, 0x00b0481b, 0x00a74822, 0x00904b27, 0x00501800, 0x003f0b00, 0x00733411, 0x00a24c24, 0x00af4b1e, 0x00b04818, 0x00b04614, 0x00b04818, 0x00b04917, 0x00ac4a12, 0x00ad4b13, 0x00ad4914, 0x00ab4714, 0x00b05018, 0x00a74c16, 0x00a34e1e, 0x008f4820, 0x004d1e03, 0x00200000, 0x002c0800, 0x005c2c15, 0x00914a27, 0x00a8501f, 0x00ae4b11, 0x00af4a0f, 0x00aa4c18, 0x00a84b1a, 0x00ac4a18, 0x00ad4a17, 0x00ae4b19, 0x00ac4a1b, 0x00a9491f, 0x00aa491d, 0x00b04817, 0x00b64810, 0x00b9490c, 0x00bd4c0c, 0x00c15514, 0x00a64c18, 0x00652f13, 0x00390600, 0x00984610, 0x00c05a13, 0x00c45504, 0x00c45503, 0x00c2580d, 0x00b85d20, 0x00935129, 0x00451a04, 0x00130000, 0x00090000, 0x00070000, 0x00030000, 0x00000000, 0x00060000, 0x00220108, 0x00540f16, 0x009e242e, 0x00a3111b, 0x00aa1823, 0x00a91922, 0x00a8171c, 0x00a41418, 0x00a61319, 0x00a8141e, 0x00aa1424, 0x00a81524, 0x00a51821, 0x00961d23, 0x00761d24, 0x005d1418, 0x004b0800, 0x00400000, 0x00470603, 0x0054090a, 0x007c1c20, 0x00931f24, 0x00a51d24, 0x00ab1620, 0x00ac121e, 0x00b01420, 0x00ac1621, 0x00a9141f, 0x00a8141e, 0x00a8141e, 0x00a61620, 0x00a4171f, 0x00a41820, 0x00a4191e, 0x00a4181e, 0x00a01a20, 0x0099242c, 0x00680704, 0x00440000, 0x0089481b, 0x00b15c16, 0x00b95c09, 0x00b9580e, 0x00b95c17, 0x00b2601f, 0x007d3d0b, 0x002f0800, 0x003e1a03, 0x00905632, 0x006f3c1c, 0x000b0000, 0x00070000, 0x001a0000, 0x00834c27, 0x00aa581c, 0x00ba580c, 0x00c15a09, 0x00c25906, 0x00bf5807, 0x00c15b0d, 0x00be580e, 0x00bd580c, 0x00c3590b, 0x00bc580e, 0x00af5a1c, 0x007c4318, 0x00110000, 0x00010000, 0x00020005, 0x000a0305, 0x00100400, 0x00100000, 0x001c0000, 0x002f0a00, 0x0058280c, 0x00743915, 0x0090481e, 0x00a45321, 0x00b05924, 0x00b4591f, 0x00b85b1c, 0x00bc5b1c, 0x00bb581c, 0x00ba571d, 0x00b5531b, 0x00b0521a, 0x00a8501b, 0x00a3501d, 0x00a15121, 0x00a25324, 0x00a15223, 0x009e4f20, 0x009f4e21, 0x00a14d21, 0x00a44c20, 0x00a84c20, 0x00aa491f, 0x00a9461b, 0x00a8441b, 0x00a84416, 0x00a94710, 0x00a9480e, 0x00a84911, 0x00a84a10, 0x00ac490c, 0x00ad480c, 0x00ac4a10, 0x00ac4b10, 0x00b24f14, 0x00b84f0d, 0x00c45208, 0x00cc5608, 0x00cb5607, 0x00c75408, 0x00c4550c, 0x00be570d, 0x00bd5d11, 0x00ac5818, 0x008c4823, 0x00642e12, 0x00441200, 0x00400d00, 0x00642a00, 0x008f4c10, 0x00b26418, 0x00b86f28, 0x008b5626, 0x00471700, 0x00521900, 0x00b56c2c, 0x00c26414, 0x00bd5807, 0x00b45914, 0x009c5424, 0x00350f00, 0x000e0000, 0x00070000, 0x004f504c, 0x00a3a7a2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00333231, 0x0075706b, 0x00140e09, 0x00100400, 0x00100000, 0x0051270d, 0x009c5021, 0x00ac5924, 0x008b4822, 0x00441800, 0x000a0000, 0x000a0000, 0x00341200, 0x00733f20, 0x009b5630, 0x008d4928, 0x00522010, 0x00250000, 0x00200000, 0x00532510, 0x00964e26, 0x00a64e1f, 0x00a8481e, 0x00a14c26, 0x00713819, 0x00380a00, 0x00511c00, 0x00843e16, 0x00a84b1d, 0x00b34817, 0x00b24514, 0x00b14615, 0x00b0491b, 0x00ac4919, 0x00aa4912, 0x00ab4c13, 0x00ae4c1a, 0x00a84714, 0x00ac4d15, 0x00a34c16, 0x00a05226, 0x00733715, 0x00300b00, 0x00260400, 0x00582814, 0x00834328, 0x00a45026, 0x00ab4915, 0x00ae450d, 0x00b04812, 0x00a94b19, 0x00a64c1a, 0x00a74c14, 0x00ab4c15, 0x00ac4c1b, 0x00ac4b1d, 0x00aa491f, 0x00ac481b, 0x00b34814, 0x00b7480c, 0x00c1500c, 0x00c0500e, 0x00bc571a, 0x00994718, 0x004d1800, 0x004a1300, 0x00b25a1c, 0x00c05707, 0x00c85c08, 0x00c05501, 0x00bd560b, 0x00b35c23, 0x00723c1e, 0x002c0b00, 0x000e0000, 0x00090000, 0x00080000, 0x00040000, 0x00070306, 0x00080000, 0x00260008, 0x00681a24, 0x009b1820, 0x00b0161f, 0x00a4121c, 0x00a4161c, 0x00a61818, 0x00a7181a, 0x00a71720, 0x00a41826, 0x009c1a29, 0x00951c2a, 0x00871b20, 0x006d1212, 0x004c0600, 0x003f0600, 0x004e1400, 0x00602c17, 0x00542a1d, 0x00210000, 0x00440403, 0x006d161b, 0x0095222a, 0x00a41d28, 0x00a8141e, 0x00ab131c, 0x00a8151d, 0x00a5141c, 0x00a5151f, 0x00a61521, 0x00a41623, 0x00a41623, 0x00a31820, 0x00a3181f, 0x00a3171c, 0x00a0181c, 0x009c1f22, 0x00801715, 0x00410000, 0x00743212, 0x00a75418, 0x00b95a12, 0x00bc5610, 0x00bc5816, 0x00b65d1e, 0x00833e0d, 0x00340c00, 0x00351400, 0x00855133, 0x0063381b, 0x00080000, 0x00080000, 0x001f0000, 0x0090542d, 0x00ad5c20, 0x00b95a12, 0x00c0590e, 0x00bf5807, 0x00bf5507, 0x00c35b0e, 0x00be580e, 0x00bd560c, 0x00c45708, 0x00bd570e, 0x00aa5920, 0x00723d17, 0x00120000, 0x00040000, 0x00020000, 0x00040000, 0x002c1f13, 0x002a1809, 0x00140000, 0x00140000, 0x001c0000, 0x00260100, 0x00471600, 0x00692f0e, 0x00884119, 0x009a4a1a, 0x00ac541c, 0x00bc5a1e, 0x00c05618, 0x00be5010, 0x00c25713, 0x00c35915, 0x00c05916, 0x00bb5613, 0x00b65414, 0x00b45414, 0x00b25214, 0x00af4f10, 0x00b04d10, 0x00b04b0e, 0x00b1480c, 0x00b4470c, 0x00b4470f, 0x00b54713, 0x00b44818, 0x00b24b17, 0x00ad4c0d, 0x00ac4f09, 0x00b0500d, 0x00b3510d, 0x00b9510b, 0x00bc530c, 0x00bc5513, 0x00bc5814, 0x00be5812, 0x00c0560c, 0x00c85606, 0x00c45504, 0x00c0550b, 0x00c05b15, 0x00ba591a, 0x00a85010, 0x00944808, 0x00703100, 0x004a1400, 0x003c0b00, 0x00502100, 0x007a4517, 0x00a25d20, 0x00b8671d, 0x00bf6814, 0x00b4651a, 0x007c4818, 0x00380b00, 0x00542000, 0x00b06d28, 0x00c06413, 0x00c45f0b, 0x00b8560c, 0x00b16026, 0x00622c0c, 0x001c0000, 0x000c0000, 0x0020201c, 0x0080827c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a19e9b, 0x005e5a57, 0x00070000, 0x000b0402, 0x00160000, 0x005e2a0c, 0x0096542e, 0x00975b39, 0x004d220c, 0x000a0000, 0x00050000, 0x00200400, 0x00602d11, 0x00994e24, 0x00974a22, 0x00824931, 0x00360c01, 0x00170000, 0x001f0000, 0x006a3318, 0x0098512c, 0x00a24e28, 0x00944a28, 0x004c1f07, 0x002b0400, 0x00642c0b, 0x0094481d, 0x00aa4818, 0x00b44511, 0x00b44410, 0x00b24514, 0x00af4a1c, 0x00ab4819, 0x00a84913, 0x00ac4d15, 0x00ad4b1b, 0x00ab4818, 0x00ab4915, 0x00a44c1b, 0x00954c28, 0x00531a00, 0x002f0600, 0x00491f12, 0x0081402b, 0x009c492a, 0x00ac4c20, 0x00af4715, 0x00b44717, 0x00b34819, 0x00a9481b, 0x00a64a18, 0x00ac4b10, 0x00ac4c0f, 0x00ab4b18, 0x00ac481a, 0x00b04715, 0x00b64711, 0x00bc4b0c, 0x00bf4f0b, 0x00c35611, 0x00bc5718, 0x00b25824, 0x00894017, 0x00410700, 0x006b2a04, 0x00ba5d1b, 0x00c05604, 0x00c45c04, 0x00bc5701, 0x00bc590c, 0x00a4571e, 0x004a2108, 0x00160200, 0x00080000, 0x00050000, 0x00040003, 0x00040004, 0x00050104, 0x000c0001, 0x00240007, 0x006f252e, 0x00981c26, 0x00a6141e, 0x00a71720, 0x00a5141c, 0x00a51214, 0x00a41518, 0x00a01b24, 0x00901e29, 0x00721c21, 0x005c1716, 0x003c0000, 0x003b0000, 0x00521200, 0x00742e0e, 0x00984724, 0x00a55e3c, 0x00805538, 0x00200000, 0x001c0000, 0x00390204, 0x0068151b, 0x008f222a, 0x00a21d25, 0x00a31219, 0x00a31218, 0x00a71920, 0x00a0171e, 0x00a01822, 0x00a01724, 0x00a21624, 0x00a41522, 0x00a5151f, 0x00a4141d, 0x00a1171c, 0x009b1b1c, 0x008a231f, 0x00450500, 0x00581f07, 0x009b4c1a, 0x00b95a1a, 0x00be5211, 0x00c15415, 0x00bb581c, 0x008c3d10, 0x003e0f00, 0x00341000, 0x007a4932, 0x0059311c, 0x00090000, 0x000b0000, 0x002c0400, 0x00995930, 0x00b05c24, 0x00b75814, 0x00bc5913, 0x00bf590f, 0x00be5408, 0x00be5609, 0x00be580f, 0x00be550c, 0x00c65406, 0x00be570e, 0x00a35722, 0x00673514, 0x00130000, 0x00060000, 0x000b0300, 0x00100000, 0x00432510, 0x00664028, 0x00542c13, 0x002e0b00, 0x00130000, 0x00100000, 0x00130000, 0x00190000, 0x00290700, 0x00471805, 0x006c2f15, 0x008b401d, 0x00a14c1c, 0x00ae541b, 0x00ac5314, 0x00b45818, 0x00bb5c17, 0x00ba5814, 0x00ba560e, 0x00bc560f, 0x00bf5710, 0x00bf5710, 0x00c45811, 0x00c45811, 0x00c65610, 0x00c6550d, 0x00c5540e, 0x00c5540f, 0x00c4520f, 0x00c1530c, 0x00bd560b, 0x00bc580c, 0x00be580f, 0x00c0570e, 0x00c75409, 0x00ca5407, 0x00ca5408, 0x00c85508, 0x00c65608, 0x00c25708, 0x00c05a0c, 0x00b75a14, 0x00a7561e, 0x00995023, 0x0088431c, 0x006f320b, 0x00441300, 0x00390900, 0x00501500, 0x00823e13, 0x00a85c23, 0x00b4601b, 0x00bc5f10, 0x00c46614, 0x00bb6413, 0x00a55e1c, 0x00673c16, 0x002e0800, 0x005d2900, 0x00b16924, 0x00c06310, 0x00c96009, 0x00c75d0d, 0x00b35614, 0x00934c1f, 0x003a0d00, 0x000d0000, 0x00050300, 0x005c5d58, 0x00b5b6b1, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b1af, 0x0040403e, 0x0006070a, 0x00060000, 0x00200200, 0x00572c10, 0x0085563b, 0x0055301d, 0x00150905, 0x00090100, 0x00150000, 0x00471901, 0x00954a1f, 0x00a05021, 0x00904e2c, 0x0064321e, 0x001c0000, 0x00110000, 0x00300b00, 0x0077432b, 0x00945134, 0x007d3d21, 0x00370d00, 0x00310800, 0x006e3411, 0x00a05226, 0x00ac4919, 0x00b44813, 0x00b44511, 0x00b04612, 0x00ac4819, 0x00aa481a, 0x00aa4814, 0x00ae4c17, 0x00aa4816, 0x00ac4a18, 0x00ad4a18, 0x00a64c1f, 0x00803919, 0x00440b00, 0x00471608, 0x00743c2c, 0x009a4a2f, 0x00a74822, 0x00ac4818, 0x00b04714, 0x00b2481a, 0x00b0471c, 0x00ac4819, 0x00ac4916, 0x00b04b10, 0x00ad4a0f, 0x00a94917, 0x00ac4815, 0x00b5480e, 0x00bd4c0a, 0x00c45208, 0x00c8560b, 0x00c5570e, 0x00bd5b1c, 0x00a85527, 0x0077310d, 0x00440500, 0x008b4319, 0x00ba5814, 0x00c55904, 0x00bf5801, 0x00b95a07, 0x00b65f16, 0x00884814, 0x00280d00, 0x00080000, 0x00040000, 0x00030000, 0x00030000, 0x00040000, 0x00080000, 0x002b1713, 0x002c0502, 0x005a1516, 0x0090272c, 0x009b1f25, 0x009e1e24, 0x009e1f22, 0x009c201f, 0x0091201f, 0x007c1a23, 0x005b1019, 0x00330304, 0x001a0000, 0x00200000, 0x004a1a00, 0x008e4c24, 0x00af5f2f, 0x00b45826, 0x00a65728, 0x00774d27, 0x00140000, 0x00100000, 0x00160000, 0x00300001, 0x005b1314, 0x00882124, 0x00a02426, 0x00a51e22, 0x00a4181d, 0x00a01620, 0x009e1522, 0x009f1522, 0x00a11422, 0x00a41320, 0x00a4131f, 0x00a4141e, 0x00a2151d, 0x00a11c1e, 0x00902323, 0x004e0b09, 0x00460d00, 0x0095481c, 0x00b8581d, 0x00be5012, 0x00c25414, 0x00b9561b, 0x008c3f0f, 0x00401200, 0x002f0e00, 0x0069402c, 0x00502c1c, 0x000c0000, 0x000f0000, 0x003f1000, 0x009d582d, 0x00ae5820, 0x00ac4e0e, 0x00b15414, 0x00bc5c18, 0x00c0580f, 0x00bc5409, 0x00bd5710, 0x00be550c, 0x00c55405, 0x00be5610, 0x009c5423, 0x005a2d10, 0x00120000, 0x00080000, 0x00100200, 0x00301a09, 0x00321000, 0x006f442c, 0x00855738, 0x005c3014, 0x00301000, 0x00170000, 0x00080000, 0x00050000, 0x000b0000, 0x00180100, 0x00270000, 0x003c0800, 0x00561800, 0x00662100, 0x008a4313, 0x00954b15, 0x00a45319, 0x00af571b, 0x00b45719, 0x00b55818, 0x00b8581a, 0x00ba591a, 0x00ba5616, 0x00bd5614, 0x00bf5712, 0x00bf560e, 0x00bf560e, 0x00c0570e, 0x00c0570e, 0x00bf570c, 0x00bf580c, 0x00be580f, 0x00bc5815, 0x00be5818, 0x00c45817, 0x00c55614, 0x00c25510, 0x00be5410, 0x00b95512, 0x00ac5212, 0x00a15115, 0x008f4714, 0x006e3005, 0x004f1400, 0x00400400, 0x003b0200, 0x00481800, 0x00743e12, 0x00a45c29, 0x00b45d21, 0x00ba5b11, 0x00c5600d, 0x00cc600a, 0x00c15c08, 0x00b96417, 0x009a581c, 0x00542d0b, 0x002a0600, 0x00683000, 0x00b36821, 0x00c36513, 0x00c96009, 0x00c55803, 0x00bc550c, 0x00b15b21, 0x005c2100, 0x00180100, 0x00050100, 0x0030302c, 0x00949490, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b0aeaf, 0x0029282c, 0x00110c0e, 0x00090000, 0x00100000, 0x00462a18, 0x00503728, 0x00251714, 0x00080000, 0x00100000, 0x00330b00, 0x00823e13, 0x00a85722, 0x00994b1a, 0x00904e2b, 0x00401608, 0x00190000, 0x00100000, 0x003d2015, 0x00784936, 0x00622d18, 0x00310400, 0x004b1905, 0x007f3d1f, 0x00a2522a, 0x00a74c1c, 0x00af4b18, 0x00b04814, 0x00ad4611, 0x00ac4818, 0x00ac4819, 0x00ab4718, 0x00ac4918, 0x00ab4a13, 0x00a94811, 0x00af4b18, 0x00a64a1f, 0x00662203, 0x00531700, 0x0074321f, 0x00964a32, 0x00a54c24, 0x00a84818, 0x00ab4813, 0x00ab4813, 0x00a84617, 0x00aa4618, 0x00b04816, 0x00b34813, 0x00b24610, 0x00b14814, 0x00ad4c19, 0x00b05018, 0x00b9510c, 0x00c15404, 0x00c85700, 0x00ca5802, 0x00c75505, 0x00bf5815, 0x009c4920, 0x005f1800, 0x00541000, 0x00a45529, 0x00bc560d, 0x00c85804, 0x00be5705, 0x00b65a10, 0x00a55b1d, 0x005c2a00, 0x00130300, 0x00010200, 0x00000100, 0x00010000, 0x00040000, 0x00100200, 0x00331d0c, 0x0060402b, 0x00451804, 0x00390000, 0x00661814, 0x007f2524, 0x00842522, 0x007a211c, 0x00601810, 0x00410a04, 0x00250003, 0x00130002, 0x000c0000, 0x00110000, 0x00290000, 0x00652c0d, 0x00a55a28, 0x00b15b1f, 0x00b45817, 0x00a4591c, 0x006e491a, 0x00100000, 0x000f0000, 0x000c0000, 0x000a0000, 0x001d0100, 0x004d130c, 0x007d241f, 0x009b2324, 0x00a2171f, 0x00a71624, 0x00a81424, 0x00a61422, 0x00a4131f, 0x00a11420, 0x00a01420, 0x00a01420, 0x00a0141f, 0x00a81b23, 0x009a2128, 0x00590d12, 0x00440400, 0x0095441b, 0x00b6581c, 0x00bc5311, 0x00be5714, 0x00b35a19, 0x00874410, 0x003b1700, 0x00280f00, 0x00573626, 0x0045281b, 0x000e0000, 0x00140000, 0x00511c01, 0x00a05429, 0x00b0571e, 0x009e4104, 0x009c460c, 0x00ae5618, 0x00be5b14, 0x00bc550c, 0x00bd5711, 0x00be550d, 0x00c45406, 0x00bb5612, 0x00975224, 0x0051270d, 0x00110000, 0x000c0000, 0x00180300, 0x00513a2f, 0x001f0700, 0x00452819, 0x007f5538, 0x00895835, 0x00723f20, 0x00451a05, 0x001d0601, 0x00060000, 0x00020003, 0x0017100f, 0x002f1914, 0x00401f10, 0x00411700, 0x00300100, 0x00310000, 0x00390300, 0x004d0c00, 0x00621d00, 0x00782f09, 0x0089401c, 0x00944d2a, 0x009e5531, 0x00a4552e, 0x00a85829, 0x00ac5824, 0x00ad571d, 0x00ad571b, 0x00af591b, 0x00b05a18, 0x00b25918, 0x00b65516, 0x00b5531b, 0x00af5523, 0x00ab552a, 0x00a9552f, 0x00a5542d, 0x009f4f27, 0x00974d26, 0x00773817, 0x00592507, 0x003c0f00, 0x00300400, 0x00370300, 0x004b0d00, 0x006e2a00, 0x00924817, 0x00b0652e, 0x00b06022, 0x00b85c15, 0x00c25c0f, 0x00c55c09, 0x00c75904, 0x00cb5a06, 0x00c86010, 0x00b7641a, 0x00894c10, 0x00401700, 0x00300600, 0x007a3801, 0x00b86720, 0x00c16618, 0x00c5610c, 0x00c85904, 0x00c95b0a, 0x00b95815, 0x007b3405, 0x00270a00, 0x00080300, 0x000f0e0b, 0x00747473, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b0b4, 0x002a2629, 0x000b0807, 0x00050000, 0x000d0000, 0x0024150c, 0x00170c0b, 0x000c0002, 0x000a0000, 0x00280900, 0x00682c04, 0x00a75821, 0x00b0581c, 0x009a4815, 0x007d4226, 0x00220000, 0x00120000, 0x000e0000, 0x005d3e32, 0x00502414, 0x00340000, 0x00682b14, 0x00934828, 0x009e4b22, 0x00a4481a, 0x00aa4a18, 0x00ac4914, 0x00ab4712, 0x00ac4918, 0x00ae491b, 0x00ab4519, 0x00a84515, 0x00ac4e16, 0x00a4460e, 0x00ac481a, 0x00a34820, 0x00591300, 0x006f2c11, 0x00984930, 0x00a64c2c, 0x00a84818, 0x00ab4810, 0x00ae4d14, 0x00ab4c15, 0x00a74716, 0x00ac4918, 0x00b44912, 0x00b24409, 0x00b44308, 0x00b6480e, 0x00b35018, 0x00b85618, 0x00c4590f, 0x00c75906, 0x00c45801, 0x00c05604, 0x00bc580e, 0x00b0571d, 0x0084411c, 0x00450700, 0x00671e00, 0x00b65e2c, 0x00c0550e, 0x00c45407, 0x00be570e, 0x00ad5819, 0x008f5023, 0x00330e00, 0x00080000, 0x00000400, 0x00000100, 0x00030000, 0x000c0000, 0x00260b00, 0x00643d1d, 0x00916038, 0x00814821, 0x004c0c00, 0x003c0000, 0x003f0000, 0x00440000, 0x003e0000, 0x002d0000, 0x001b0000, 0x00090003, 0x00010008, 0x00000005, 0x000a0000, 0x003d1200, 0x007a3813, 0x00b15a24, 0x00b45411, 0x00bc5b14, 0x00a75718, 0x00684014, 0x00140100, 0x000c0000, 0x00080004, 0x00030102, 0x00080000, 0x00200000, 0x00440500, 0x00761712, 0x00982428, 0x00a1202c, 0x00a51b2a, 0x00a81723, 0x00a7151f, 0x00a2141d, 0x00a0141e, 0x00a01420, 0x00a01420, 0x00a41721, 0x009e242e, 0x00611017, 0x00470200, 0x00944014, 0x00b55818, 0x00bc5711, 0x00b85810, 0x00af5d1c, 0x00834713, 0x00361900, 0x00211000, 0x00483021, 0x003e241c, 0x000e0000, 0x00160000, 0x00602509, 0x00a65729, 0x00b55a21, 0x00943900, 0x00863804, 0x00994a14, 0x00b45815, 0x00b9540f, 0x00bb5612, 0x00bd550f, 0x00c25409, 0x00b85714, 0x00935124, 0x004a2309, 0x000f0000, 0x000c0000, 0x00280c00, 0x00715042, 0x00280e08, 0x00160000, 0x00300c00, 0x006a3f20, 0x008c593c, 0x00845138, 0x00522d20, 0x00210b02, 0x00080000, 0x00050000, 0x000c0000, 0x002a1810, 0x005c4433, 0x007d5d49, 0x006a4132, 0x005e2a18, 0x00501100, 0x00460000, 0x00400000, 0x003c0000, 0x00380000, 0x00380000, 0x00440c00, 0x004c1400, 0x00591f00, 0x00622701, 0x006b2e04, 0x00743508, 0x007a3905, 0x00803806, 0x00883506, 0x00842f05, 0x00782904, 0x006b2100, 0x005c1800, 0x004c0c00, 0x003e0000, 0x002f0000, 0x00200000, 0x00170000, 0x001c0300, 0x00432210, 0x007e4826, 0x00a15c2d, 0x00af5e26, 0x00b65e1f, 0x00b65b14, 0x00bc5c10, 0x00c35d0b, 0x00c55c05, 0x00c55c04, 0x00c85c05, 0x00cc5a07, 0x00c35c0f, 0x00b16620, 0x0077410b, 0x00290500, 0x00370c00, 0x008a440a, 0x00bc651b, 0x00c16412, 0x00c6620a, 0x00cc5e05, 0x00c65500, 0x00c1570e, 0x00a04f1a, 0x00381300, 0x00090000, 0x00040100, 0x00535353, 0x00797878, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00686667, 0x00292827, 0x00080804, 0x00080200, 0x00050000, 0x000c0506, 0x00070107, 0x00030004, 0x00100000, 0x004a1800, 0x00a45825, 0x00bb5a18, 0x00b55411, 0x009e4c1d, 0x00581e02, 0x00180000, 0x000c0000, 0x002c140e, 0x006c483b, 0x00652a13, 0x00863c1b, 0x009f4a24, 0x00a64b20, 0x00a74a1b, 0x00a94b19, 0x00aa4a18, 0x00ac4a18, 0x00ac4817, 0x00ac4818, 0x00ae471b, 0x00ac471b, 0x00aa4c18, 0x00ab4e1d, 0x00a4441c, 0x008e3412, 0x00803416, 0x008b4021, 0x00a24729, 0x00ac4821, 0x00ae4918, 0x00ac4810, 0x00a94810, 0x00ac4b14, 0x00ac4a14, 0x00ac4711, 0x00b04509, 0x00b64504, 0x00c34c04, 0x00c65209, 0x00c05715, 0x00c05614, 0x00c8540a, 0x00cb580b, 0x00c45811, 0x00b35818, 0x009a5420, 0x00602c04, 0x002a0500, 0x00340800, 0x007d3302, 0x00b8571b, 0x00cb5819, 0x00c45011, 0x00ba5418, 0x00af5f30, 0x005c2910, 0x001e0400, 0x00040000, 0x00000001, 0x00000000, 0x00090000, 0x001d0000, 0x005b2804, 0x00985626, 0x00a75c24, 0x00a55a20, 0x00a25623, 0x00873b14, 0x00722805, 0x006a2400, 0x006f310e, 0x00774837, 0x003e201c, 0x000e0208, 0x00000007, 0x00000206, 0x000c0000, 0x00502204, 0x009b5021, 0x00b8541c, 0x00c05313, 0x00c15411, 0x00ad541c, 0x00683617, 0x00180000, 0x000e0004, 0x00070008, 0x00080004, 0x001c0605, 0x00472010, 0x003f0c00, 0x003a0000, 0x00530b02, 0x007b2024, 0x0093252d, 0x00a01c24, 0x00ad1c22, 0x00b21f25, 0x00ac181f, 0x00ab1a21, 0x00a51a22, 0x00a4212a, 0x0095282d, 0x00540504, 0x00510b00, 0x0098420f, 0x00b85813, 0x00ba560c, 0x00b95a12, 0x00ac5c1a, 0x00844b18, 0x00341800, 0x001a0c00, 0x003a281b, 0x0037231d, 0x000c0000, 0x001c0000, 0x00723617, 0x00a85624, 0x00b45719, 0x00ac5217, 0x005d1800, 0x007d390c, 0x00aa551a, 0x00b55613, 0x00ba5814, 0x00bb540f, 0x00bf560d, 0x00b55818, 0x00945327, 0x00431c02, 0x000d0000, 0x000c0000, 0x00381000, 0x008c5d45, 0x00381104, 0x001d0000, 0x00140000, 0x00160000, 0x003e1c0c, 0x00714430, 0x00905b40, 0x006f3d1e, 0x00371400, 0x00140000, 0x00080000, 0x00040000, 0x00140800, 0x003c2415, 0x00805446, 0x009c5f48, 0x00a45630, 0x00ae5729, 0x00a14a1c, 0x0085380d, 0x006d3112, 0x00401200, 0x00200000, 0x00180000, 0x00110000, 0x00140000, 0x001a0000, 0x001e0000, 0x002b0000, 0x00340000, 0x00340000, 0x00390000, 0x003b0000, 0x003c0000, 0x00450900, 0x00531800, 0x00581d00, 0x004d1b00, 0x00240300, 0x00100000, 0x001b0500, 0x004a2711, 0x00a76535, 0x00af5918, 0x00bd6015, 0x00be5b0b, 0x00c25b08, 0x00c25c06, 0x00c05b03, 0x00c46008, 0x00bf5b03, 0x00c45e07, 0x00c75906, 0x00bd5c12, 0x009c5e22, 0x00583004, 0x001a0000, 0x00371300, 0x00a05a1b, 0x00bc6210, 0x00c46005, 0x00cc6304, 0x00cc6005, 0x00c85702, 0x00c45507, 0x00b25c22, 0x0051270d, 0x00120400, 0x00030000, 0x00343436, 0x00909092, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b0afac, 0x0041403d, 0x00080402, 0x00050200, 0x00000001, 0x00000004, 0x00010109, 0x000c0000, 0x00381300, 0x0088481d, 0x00b05313, 0x00bd550f, 0x00bb5b1e, 0x00974c20, 0x002a0000, 0x00120000, 0x00150300, 0x004e2f23, 0x00814326, 0x009c4920, 0x00a94c1f, 0x00aa4818, 0x00ad4a17, 0x00ac4a16, 0x00aa4a19, 0x00aa4a19, 0x00ac4918, 0x00ad4818, 0x00af4718, 0x00ac4718, 0x00a54515, 0x00a74a1c, 0x00a74620, 0x009c401d, 0x0096421e, 0x009d4823, 0x00ac4821, 0x00af4418, 0x00ae4410, 0x00b04810, 0x00b0490f, 0x00ae480d, 0x00b0470c, 0x00b84c0f, 0x00c05212, 0x00c6550f, 0x00ca5204, 0x00cc580a, 0x00c65a12, 0x00bd5410, 0x00c0530e, 0x00be5515, 0x00a74c18, 0x008a3f14, 0x00440d00, 0x00300900, 0x001c0000, 0x00381100, 0x00944812, 0x00b85413, 0x00c55314, 0x00c65618, 0x00b85620, 0x00984f29, 0x00380f04, 0x00110002, 0x00050005, 0x00010005, 0x00040100, 0x00100000, 0x004b1800, 0x00894111, 0x00ac5a1c, 0x00b25a16, 0x00b35b17, 0x00b05819, 0x00aa531d, 0x00a4501e, 0x009f561e, 0x009c6032, 0x0070402c, 0x002f100c, 0x000a0002, 0x00000003, 0x00000000, 0x00190800, 0x00683208, 0x00a8571d, 0x00bd5518, 0x00c25111, 0x00c05310, 0x00a95019, 0x00612f14, 0x00110000, 0x00050000, 0x00030001, 0x000c0000, 0x0032140b, 0x00794830, 0x0080492a, 0x0057260d, 0x00340300, 0x00320000, 0x0053070c, 0x00760f12, 0x00911a1c, 0x009c2020, 0x009e2122, 0x00a22728, 0x009e2728, 0x00942829, 0x00721410, 0x00430000, 0x00672002, 0x00a44f17, 0x00b85812, 0x00bb570f, 0x00b4520d, 0x00af5a1c, 0x00844818, 0x00341700, 0x00160800, 0x00302015, 0x002d1e18, 0x000a0000, 0x001b0000, 0x0080401e, 0x00aa5621, 0x00b65717, 0x00b2581d, 0x00622200, 0x005a1f00, 0x00924611, 0x00b55c1f, 0x00b75814, 0x00b8550f, 0x00bd5710, 0x00b25819, 0x00915024, 0x00401800, 0x000c0000, 0x000e0000, 0x00461800, 0x00985f3c, 0x00582b15, 0x00240300, 0x000d0000, 0x000a0000, 0x001b0500, 0x00250300, 0x00532004, 0x00804a28, 0x007c5030, 0x0045260d, 0x00140400, 0x00050000, 0x00080000, 0x000f0000, 0x002f0c00, 0x0078432d, 0x00a0542d, 0x00ac5421, 0x00b2571f, 0x00ab551f, 0x009b5628, 0x007c4725, 0x003d1804, 0x00120000, 0x000b0200, 0x00050000, 0x000c0000, 0x00391d0e, 0x007c4c2f, 0x00844925, 0x00844828, 0x008c4c2a, 0x00945024, 0x00975223, 0x009b5729, 0x009d5c2d, 0x009a582a, 0x008d5430, 0x0045200d, 0x00180000, 0x00100000, 0x003e1904, 0x009b5320, 0x00b3570e, 0x00c05b08, 0x00c55c03, 0x00c65900, 0x00c55a01, 0x00c05c06, 0x00be5d08, 0x00bc5e08, 0x00c0600a, 0x00c05808, 0x00bb631d, 0x00834e1e, 0x003c1d00, 0x00180000, 0x00441e00, 0x00aa601c, 0x00c0610b, 0x00c66205, 0x00ca6001, 0x00cc5f04, 0x00c95804, 0x00c65608, 0x00b85b1f, 0x00673415, 0x00200a00, 0x00050000, 0x001f1f20, 0x007c7c80, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b8b1af, 0x0053504f, 0x00141414, 0x00050608, 0x00000003, 0x00000005, 0x00020000, 0x00240e04, 0x00734328, 0x00ac5c2b, 0x00bf5c1c, 0x00bd5711, 0x00b0571c, 0x00642402, 0x00260000, 0x000e0000, 0x002c1102, 0x00804321, 0x00a14a1c, 0x00ab4712, 0x00af440b, 0x00b1460c, 0x00af460e, 0x00a94614, 0x00a94718, 0x00ab4816, 0x00ac4814, 0x00ac4511, 0x00ac4414, 0x00ac461a, 0x00ac481f, 0x00aa471e, 0x00a7441b, 0x00a74418, 0x00ab4718, 0x00af4715, 0x00b14310, 0x00b5430e, 0x00b8450d, 0x00bb490c, 0x00c14d0c, 0x00c84f0c, 0x00c9510d, 0x00c2530f, 0x00c0520b, 0x00cb5508, 0x00c55003, 0x00bc5208, 0x00bc5c17, 0x00b05c20, 0x008e4414, 0x005c1d00, 0x00380000, 0x00471100, 0x00572511, 0x003e1805, 0x00471700, 0x00a25621, 0x00b95a17, 0x00c45811, 0x00bc5411, 0x00ae5822, 0x00723310, 0x00200000, 0x000a0004, 0x00040006, 0x00030004, 0x000a0000, 0x00250700, 0x00743108, 0x00aa5419, 0x00b65714, 0x00b4550d, 0x00b65a13, 0x00b4540f, 0x00bc5514, 0x00bc5a1c, 0x00ac5c1c, 0x00a16330, 0x004c1e07, 0x00180000, 0x00080000, 0x000a0401, 0x00080000, 0x00361700, 0x0081420c, 0x00b15a16, 0x00b95611, 0x00ba540c, 0x00b7580e, 0x009f541a, 0x00582c14, 0x000d0000, 0x00000200, 0x00030700, 0x000d0000, 0x00401c00, 0x008c4c1f, 0x00a45c2e, 0x00854b2a, 0x004d1f0d, 0x00180000, 0x001d0000, 0x002e0000, 0x003f0000, 0x00480200, 0x00520800, 0x005c100a, 0x005a0c05, 0x00500400, 0x00480000, 0x004e0c00, 0x008a461a, 0x00ac581b, 0x00b55510, 0x00c15916, 0x00bd5517, 0x00b55820, 0x00894117, 0x00371300, 0x00140200, 0x0024160e, 0x00221811, 0x00080000, 0x001a0000, 0x008e4e27, 0x00ae581e, 0x00b75513, 0x00b35b1f, 0x00692e07, 0x003d0900, 0x00743304, 0x00ac5b23, 0x00b45818, 0x00b75510, 0x00bb5811, 0x00b1581b, 0x008f4e22, 0x003c1400, 0x000b0000, 0x00100000, 0x005a2800, 0x009c5e31, 0x00704128, 0x00260400, 0x00100000, 0x00090000, 0x000d0000, 0x000d0000, 0x00230600, 0x002c0b00, 0x004b2510, 0x00684432, 0x00573a30, 0x00230f09, 0x00080000, 0x000c0300, 0x000d0000, 0x00280c00, 0x00632f0d, 0x009b5422, 0x00ae581c, 0x00b05412, 0x00b45c1b, 0x00a65821, 0x00783e15, 0x00310c00, 0x00110200, 0x00050000, 0x000e0000, 0x00381500, 0x009f5a2b, 0x00ac561c, 0x00ac561c, 0x00b0591d, 0x00b75c17, 0x00b85c14, 0x00b45c15, 0x00b45d17, 0x00b15a18, 0x00a65b23, 0x00784220, 0x00320c00, 0x00150000, 0x00300800, 0x00823d0e, 0x00b45a17, 0x00bd5706, 0x00c65b02, 0x00c55800, 0x00c35903, 0x00c45d0e, 0x00bb590a, 0x00bc5f0b, 0x00bc5f0c, 0x00b9580e, 0x00b16027, 0x00683a1a, 0x00240800, 0x00200300, 0x005f320c, 0x00b4661b, 0x00c06006, 0x00c6620a, 0x00c45d06, 0x00c85f06, 0x00c95c06, 0x00c75708, 0x00b85919, 0x00824721, 0x00341301, 0x00080000, 0x00080809, 0x00616064, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b0b3, 0x006b6c6d, 0x00202120, 0x00040807, 0x00020608, 0x00000000, 0x000e0200, 0x003c1c0d, 0x00804320, 0x00b05f2a, 0x00bb5e1c, 0x00b1571a, 0x00965029, 0x00380800, 0x000e0000, 0x00160000, 0x00612a09, 0x009e4c1d, 0x00b24c17, 0x00b7480c, 0x00b64607, 0x00b24508, 0x00ac4510, 0x00aa4613, 0x00ab4711, 0x00ad4810, 0x00b0470d, 0x00b0450e, 0x00b14615, 0x00b04516, 0x00ac4413, 0x00ae4410, 0x00b4460e, 0x00b84a10, 0x00bb4e11, 0x00bc4f10, 0x00c65117, 0x00c44c10, 0x00c44d0a, 0x00c9520a, 0x00cc5108, 0x00ca5108, 0x00c15610, 0x00c05a14, 0x00c05813, 0x00c05b18, 0x00b75d1c, 0x00994b10, 0x00672500, 0x00430800, 0x00480d00, 0x0060240d, 0x00884830, 0x007b3d27, 0x00471501, 0x00582102, 0x00b05f28, 0x00b75711, 0x00bf570a, 0x00bc5b14, 0x00a15721, 0x00471400, 0x001b0000, 0x00060003, 0x00040004, 0x00070000, 0x00150000, 0x004f240b, 0x00964918, 0x00b85718, 0x00b95610, 0x00b8540c, 0x00b85813, 0x00b85510, 0x00bd500a, 0x00b8510f, 0x00a8571b, 0x0084481c, 0x00300800, 0x00110000, 0x00080000, 0x000a0200, 0x00100000, 0x00502606, 0x00964d14, 0x00b55a13, 0x00b5540d, 0x00b5540c, 0x00b35a10, 0x009c551c, 0x00502813, 0x000c0000, 0x00000300, 0x00000400, 0x000d0000, 0x00532903, 0x00994d17, 0x00ac5824, 0x00904f29, 0x00522410, 0x00100000, 0x001c0808, 0x00432015, 0x00582a17, 0x00501801, 0x00440900, 0x00440700, 0x00400200, 0x004f0b00, 0x00692304, 0x00864016, 0x00a85e28, 0x00ac5a1b, 0x00b15514, 0x00b35012, 0x00b55017, 0x00b55822, 0x00873f17, 0x00361100, 0x000e0000, 0x00150d05, 0x0018100b, 0x00070000, 0x00200300, 0x0099552a, 0x00b3581c, 0x00b85411, 0x00ad5519, 0x00703811, 0x00390b00, 0x005c2200, 0x00964f1f, 0x00b0581c, 0x00b75712, 0x00ba5712, 0x00b1581b, 0x008e4c20, 0x00390f00, 0x000b0000, 0x00130000, 0x00682e02, 0x00a05c28, 0x00875331, 0x00320c00, 0x0030150c, 0x0024100b, 0x00130000, 0x000c0000, 0x000d0000, 0x00100000, 0x001b0100, 0x002a1008, 0x003f241d, 0x0044302b, 0x002a1e1a, 0x00040000, 0x00050100, 0x000c0000, 0x002b0a00, 0x005f2a02, 0x00964f1a, 0x00b35d1f, 0x00b65513, 0x00b35414, 0x00a65420, 0x006e330f, 0x00240600, 0x000b0000, 0x00100000, 0x00260100, 0x008d4515, 0x00b15514, 0x00b75510, 0x00bb550b, 0x00bc5504, 0x00be5502, 0x00bb5503, 0x00ba5505, 0x00bb580b, 0x00b55c1a, 0x00995427, 0x005d280c, 0x00280200, 0x00240000, 0x00642601, 0x00b05d26, 0x00ba580d, 0x00c35703, 0x00c45704, 0x00c45806, 0x00c35b0e, 0x00bb580b, 0x00bc5c0c, 0x00b85d10, 0x00ba5e1c, 0x009c5221, 0x00512610, 0x00190000, 0x00300c00, 0x007d481f, 0x00b7641a, 0x00c05f04, 0x00c5610c, 0x00c45c09, 0x00c85f08, 0x00c85e07, 0x00c55507, 0x00b85614, 0x00995427, 0x00441a00, 0x000f0000, 0x00000000, 0x004a494d, 0x00b1b1b3, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00afb0b1, 0x00898b88, 0x00393b37, 0x000b0b09, 0x00000000, 0x00080104, 0x001e0b08, 0x003b1604, 0x005e2807, 0x008b4412, 0x00ad6230, 0x00a15f3c, 0x00542710, 0x00130200, 0x000f0000, 0x003c1200, 0x008c4622, 0x00b45623, 0x00b94c10, 0x00bf500d, 0x00bd4e0c, 0x00b84d10, 0x00b54d11, 0x00b64e11, 0x00b74f10, 0x00ba4d0f, 0x00bc4c0c, 0x00bc4c0c, 0x00bd4c0d, 0x00bc500c, 0x00be510b, 0x00c45008, 0x00c45006, 0x00c25308, 0x00c3540c, 0x00c4520d, 0x00c8530f, 0x00cb550b, 0x00cb5509, 0x00c95407, 0x00c35409, 0x00b85712, 0x00b25a1b, 0x00b1602a, 0x00904818, 0x00652800, 0x00481100, 0x00440d00, 0x005d2000, 0x00883a11, 0x00a44e23, 0x00a7522a, 0x007f3210, 0x00430700, 0x006f2e0c, 0x00b75d22, 0x00be570c, 0x00c15706, 0x00b55910, 0x00864918, 0x00270200, 0x00120000, 0x00060000, 0x00070000, 0x000c0000, 0x00301100, 0x00743e17, 0x00ac5822, 0x00b45210, 0x00b95512, 0x00b5540f, 0x00b15410, 0x00b95914, 0x00bc540d, 0x00b45214, 0x00a85b30, 0x005a230a, 0x001b0000, 0x000c0000, 0x00020000, 0x00060000, 0x00220500, 0x006a3614, 0x00a55620, 0x00b85918, 0x00b5540f, 0x00b4540f, 0x00b45a15, 0x00995320, 0x00482210, 0x000b0000, 0x00030200, 0x00020000, 0x00100000, 0x00653918, 0x00a5541f, 0x00af5420, 0x00894220, 0x00441403, 0x00100000, 0x00220907, 0x0064321e, 0x00924e2d, 0x0096461e, 0x00913e12, 0x00904518, 0x0093481e, 0x0097431f, 0x00a85028, 0x00af5522, 0x00ab541a, 0x00ac581e, 0x00a65318, 0x00903800, 0x009b410c, 0x00b05a27, 0x00814018, 0x002f1400, 0x00050000, 0x00070700, 0x000c0a04, 0x00090000, 0x002c0a00, 0x00a05828, 0x00b45617, 0x00ba5613, 0x00aa5418, 0x00783e18, 0x00401300, 0x00431100, 0x0080411a, 0x00ad5a21, 0x00b85716, 0x00b95410, 0x00b2581b, 0x00904c20, 0x00370c00, 0x000b0000, 0x00150000, 0x0079380c, 0x00ab5d26, 0x009c5e31, 0x00411000, 0x00492107, 0x005c3724, 0x00472314, 0x00230400, 0x00110000, 0x000f0000, 0x000b0205, 0x00040004, 0x000c0504, 0x001e1614, 0x00201513, 0x000b0200, 0x00030000, 0x00070000, 0x00120000, 0x00280700, 0x005f2c0f, 0x0098522a, 0x00b35721, 0x00ba5216, 0x00b64d14, 0x00a64f21, 0x005a240f, 0x00200000, 0x00140000, 0x00200100, 0x006c3212, 0x00ad5e2a, 0x00b85712, 0x00c05407, 0x00c25505, 0x00c45707, 0x00c25807, 0x00c05405, 0x00bf5408, 0x00b95813, 0x00ab5720, 0x008a4820, 0x004c1c06, 0x00210000, 0x00431200, 0x00975730, 0x00b45a1d, 0x00be550c, 0x00c45609, 0x00c45608, 0x00c5580c, 0x00c1590e, 0x00bb590a, 0x00b85c14, 0x00b86026, 0x00813910, 0x00390d00, 0x001c0000, 0x00481c04, 0x0097592e, 0x00b46118, 0x00bf5e08, 0x00c45e0c, 0x00c75e0b, 0x00c85f08, 0x00c65e06, 0x00c45506, 0x00bb5610, 0x00ac5b24, 0x00572000, 0x00180100, 0x00030000, 0x0039383c, 0x009e9fa2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00444443, 0x00a0a19d, 0x005e5d5a, 0x0024211f, 0x00030000, 0x00060000, 0x00140100, 0x00200200, 0x003e1300, 0x005b2809, 0x00754328, 0x00684330, 0x00180e00, 0x000c0300, 0x001e0000, 0x00632a12, 0x00a85328, 0x00bd571e, 0x00c25816, 0x00c35810, 0x00c35611, 0x00c15610, 0x00c05510, 0x00c05510, 0x00c45410, 0x00c6530e, 0x00c8540d, 0x00c8550c, 0x00c5580b, 0x00c7580a, 0x00cc5608, 0x00cb5406, 0x00c55708, 0x00c2580c, 0x00c1560f, 0x00c35812, 0x00c2550f, 0x00bc530c, 0x00b95611, 0x00b65a19, 0x00a8551c, 0x00974d1b, 0x00682700, 0x00511800, 0x00440d00, 0x00531900, 0x00733514, 0x00964b22, 0x00b0521c, 0x00b4521c, 0x00a74e21, 0x00782c08, 0x004a0c00, 0x00843d18, 0x00b75416, 0x00c55708, 0x00c35909, 0x00ab5613, 0x005a2a02, 0x00180000, 0x000a0000, 0x00070000, 0x00080000, 0x00140000, 0x005b2d09, 0x0094501d, 0x00b3591e, 0x00b24c0d, 0x00be5514, 0x00bb5410, 0x00b04f0a, 0x00b65610, 0x00b8540e, 0x00ae551c, 0x00914f2d, 0x002e0400, 0x000c0000, 0x00040000, 0x00020000, 0x000b0000, 0x003f1901, 0x0083441e, 0x00ad5723, 0x00b65516, 0x00b7540f, 0x00b5540f, 0x00b65917, 0x009b5020, 0x00441d0b, 0x000b0000, 0x00040002, 0x00050000, 0x00180100, 0x006f4020, 0x00a3501c, 0x00ac521d, 0x0083401f, 0x00401303, 0x00160000, 0x00270c04, 0x00703417, 0x00a8582b, 0x00b95a24, 0x00b6551b, 0x00ab541a, 0x00a8521c, 0x00b45625, 0x00b65422, 0x00b55315, 0x00ae5212, 0x00a95b22, 0x00883d0c, 0x006f2000, 0x00924011, 0x00ac5a2b, 0x007e4019, 0x002c1403, 0x00020000, 0x00000200, 0x00050300, 0x000c0000, 0x003b1300, 0x00a65928, 0x00b45312, 0x00bb5714, 0x00ad571c, 0x007f441e, 0x00401400, 0x002c0200, 0x006f3917, 0x00aa5825, 0x00b75617, 0x00b8510e, 0x00b45719, 0x00904a20, 0x00350900, 0x000c0000, 0x00190000, 0x008e461c, 0x00ad561f, 0x00a8602e, 0x00591c00, 0x004c1500, 0x007d482c, 0x00885338, 0x0063321b, 0x00330c00, 0x00180000, 0x00060000, 0x00020105, 0x00000302, 0x00010200, 0x00090100, 0x000a0200, 0x00070401, 0x00020000, 0x00080000, 0x00110000, 0x00260500, 0x005d2910, 0x00994c21, 0x00b75520, 0x00b94c10, 0x00b5521a, 0x00904824, 0x004e1c0a, 0x001a0000, 0x00140000, 0x003d1200, 0x0096562d, 0x00b25818, 0x00be5409, 0x00bf5408, 0x00c25307, 0x00c45406, 0x00c25307, 0x00be540b, 0x00bb540f, 0x00b55616, 0x00aa5824, 0x00763813, 0x00390700, 0x00330800, 0x0075401e, 0x00af5c23, 0x00bc5812, 0x00c1560f, 0x00c3550a, 0x00c45608, 0x00c45b0b, 0x00b9590c, 0x00b45d19, 0x00a45524, 0x005f2000, 0x00240000, 0x00280100, 0x00662f0e, 0x00a8602e, 0x00b55e14, 0x00c05e09, 0x00c45c09, 0x00c75e09, 0x00c65e06, 0x00c65e06, 0x00c45806, 0x00c05910, 0x00b75c20, 0x006a2900, 0x00210400, 0x00050000, 0x002c2a2c, 0x0088888c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b2b3, 0x00888583, 0x004d4642, 0x0019100c, 0x00070000, 0x00050000, 0x00100401, 0x00130000, 0x002c1208, 0x003f2a1e, 0x000d0b00, 0x00040100, 0x000d0000, 0x00380d04, 0x00883c1c, 0x00b65826, 0x00b85718, 0x00be580f, 0x00c4590c, 0x00c75809, 0x00c65808, 0x00c65608, 0x00c8540d, 0x00cb540e, 0x00c75308, 0x00c45406, 0x00c25408, 0x00c3550a, 0x00c8550c, 0x00c8570f, 0x00c45710, 0x00bf5813, 0x00b85b18, 0x00b55c1d, 0x00b75c23, 0x00af5824, 0x0098501f, 0x007c3c10, 0x00622100, 0x004d0f00, 0x00491000, 0x005a1d00, 0x007c3106, 0x009c4818, 0x00ad511d, 0x00b24f15, 0x00b85010, 0x00b6551b, 0x009b5228, 0x005f2303, 0x00460c00, 0x00944b24, 0x00c05413, 0x00c45003, 0x00b9530c, 0x00a25724, 0x002e0b00, 0x000c0000, 0x00050000, 0x00080001, 0x000a0000, 0x002c1100, 0x00814517, 0x00aa581c, 0x00b6541a, 0x00bb5014, 0x00c45414, 0x00c55410, 0x00bd5108, 0x00b95409, 0x00b25510, 0x00a25820, 0x00643618, 0x00180000, 0x00010100, 0x00000500, 0x00050000, 0x00180200, 0x00602e0d, 0x00954c20, 0x00af541e, 0x00b65212, 0x00b8530d, 0x00b8540c, 0x00b85515, 0x009b4e1d, 0x00401b06, 0x000c0000, 0x00060000, 0x000a0000, 0x00200300, 0x00784624, 0x00a85822, 0x00ac5e25, 0x00743f1b, 0x002c0b00, 0x000d0000, 0x002b0e01, 0x00793c14, 0x00ac571d, 0x00b55412, 0x00b7520e, 0x00b55315, 0x00ba581e, 0x00b45118, 0x00b55013, 0x00be5810, 0x00b85c18, 0x009b541f, 0x00601f00, 0x00641c00, 0x00954820, 0x00ab582c, 0x00803e1b, 0x002c1405, 0x00020000, 0x00000000, 0x00040000, 0x00140000, 0x004d1e06, 0x00ac5924, 0x00b5510e, 0x00b85614, 0x00ad581e, 0x00874a23, 0x003d1000, 0x00210000, 0x005f2f12, 0x00a45526, 0x00b55416, 0x00b9500d, 0x00b75519, 0x008e481e, 0x00320500, 0x000d0000, 0x001e0000, 0x00984a20, 0x00b1531b, 0x00b15e2c, 0x00782c01, 0x00500a00, 0x00803a1a, 0x00a0582e, 0x00944c20, 0x007d3d13, 0x00501e00, 0x00200200, 0x000a0000, 0x00000000, 0x00000400, 0x00020200, 0x00000000, 0x00000004, 0x0007060b, 0x00080000, 0x000b0000, 0x00170100, 0x00321100, 0x00653111, 0x009f5425, 0x00b7591a, 0x00b35211, 0x00a7531c, 0x007c3c13, 0x003a1100, 0x00170000, 0x00240300, 0x00704023, 0x00a75923, 0x00b65513, 0x00bc540f, 0x00c0510a, 0x00c45006, 0x00c4530b, 0x00bf5714, 0x00bc5814, 0x00bc550c, 0x00b85812, 0x009e4e12, 0x006d2d00, 0x003f1000, 0x00582500, 0x00ab591d, 0x00bc5812, 0x00bc5914, 0x00bd560c, 0x00c45802, 0x00c15b03, 0x00b55c0d, 0x00a85d1f, 0x00783a15, 0x003c0b00, 0x001c0000, 0x00401600, 0x008b4818, 0x00b45f1d, 0x00bc5e0c, 0x00c25f05, 0x00c45f04, 0x00c65e04, 0x00c55d02, 0x00c75d04, 0x00c55807, 0x00c45a10, 0x00ba5814, 0x007f3404, 0x002c0800, 0x00080000, 0x001f1b1e, 0x00737477, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a7a09a, 0x00757069, 0x00434343, 0x000c0e12, 0x00000008, 0x00010006, 0x00060000, 0x00080000, 0x00000100, 0x00000100, 0x00080000, 0x001d0000, 0x00541b07, 0x0088401a, 0x00a05421, 0x00a9581c, 0x00b45a17, 0x00ba5c15, 0x00bb5c14, 0x00bc5914, 0x00bf5718, 0x00c05819, 0x00bd5b1b, 0x00bc5c1b, 0x00b85b1c, 0x00b7581d, 0x00b75820, 0x00b15520, 0x00a7501a, 0x009a4b17, 0x00884410, 0x0078390c, 0x006f2d07, 0x00612505, 0x00461800, 0x00380800, 0x004a1000, 0x00642405, 0x007b3810, 0x00924818, 0x00a9521c, 0x00b45017, 0x00ba4d0f, 0x00c0500e, 0x00c0510f, 0x00b0521a, 0x00864825, 0x0057240c, 0x00501600, 0x00994d20, 0x00c35812, 0x00cc590e, 0x00b45312, 0x00874318, 0x001b0000, 0x00040002, 0x00020003, 0x00060000, 0x00150000, 0x00582e0e, 0x009c511a, 0x00b35515, 0x00b65014, 0x00c05418, 0x00bc4a0d, 0x00c04e0c, 0x00c2530a, 0x00b75008, 0x00af5615, 0x009a5828, 0x00391600, 0x000b0000, 0x00000400, 0x00000300, 0x00080000, 0x00250600, 0x00783c14, 0x00a85520, 0x00b3561c, 0x00b65212, 0x00bc5410, 0x00b9530d, 0x00b85316, 0x00984b1f, 0x003c1801, 0x000a0000, 0x00070000, 0x000d0000, 0x002f0c00, 0x00885028, 0x00ab5a20, 0x00a65821, 0x00673514, 0x00240700, 0x000f0000, 0x00321502, 0x00824012, 0x00af5617, 0x00b95410, 0x00bc520e, 0x00b7500d, 0x00b75110, 0x00b95515, 0x00b5500d, 0x00b85209, 0x00ad5412, 0x00803f12, 0x00470d00, 0x006e2800, 0x009c4f26, 0x00a8572d, 0x007d3e1f, 0x002d1307, 0x00040000, 0x00010000, 0x00050000, 0x001b0000, 0x005c2710, 0x00ae5824, 0x00b85310, 0x00b45310, 0x00aa541b, 0x008c4d26, 0x003d0e00, 0x00230000, 0x0055250f, 0x009f5125, 0x00b35218, 0x00b8500d, 0x00b7571a, 0x008c481f, 0x002f0400, 0x00100000, 0x00230100, 0x009f5024, 0x00bc5a22, 0x00b35824, 0x00802d00, 0x00500600, 0x00803512, 0x00a85523, 0x00b15b20, 0x00a9561c, 0x00904514, 0x00632c0b, 0x00340f00, 0x00110000, 0x00040000, 0x00060000, 0x00040100, 0x00000108, 0x00000007, 0x00100504, 0x0027140e, 0x00180500, 0x00140000, 0x003c1600, 0x00743c17, 0x00a5541a, 0x00b45814, 0x00b05414, 0x00a2531c, 0x006e3410, 0x002e0500, 0x001c0000, 0x003a1400, 0x0097542b, 0x00ad541c, 0x00ba5415, 0x00c1520e, 0x00c45108, 0x00c3520a, 0x00bc5414, 0x00b85412, 0x00c05509, 0x00b85004, 0x00b95b13, 0x009d4f13, 0x00581f00, 0x004d1300, 0x00ab561b, 0x00b85813, 0x00bb5a18, 0x00b9550c, 0x00c45a04, 0x00bd5701, 0x00b25b12, 0x00a05a23, 0x00532306, 0x00240000, 0x00260100, 0x00582804, 0x00a55b1d, 0x00b85c0f, 0x00c05e09, 0x00c15c04, 0x00c56005, 0x00c45c01, 0x00c55d02, 0x00c65e04, 0x00c55807, 0x00c4580c, 0x00bb540f, 0x008c3d0b, 0x00320d00, 0x000b0000, 0x00151012, 0x00666768, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9c9c, 0x006e6f70, 0x00404044, 0x001a191d, 0x00010002, 0x00000000, 0x00000000, 0x00000100, 0x00040000, 0x000b0000, 0x00210400, 0x003b1601, 0x0050250a, 0x005c2d0c, 0x006c3510, 0x00763911, 0x007d3c10, 0x00844014, 0x00894117, 0x00874117, 0x0084431d, 0x0082441f, 0x00803f1b, 0x00773817, 0x006c3216, 0x00612c13, 0x0054250d, 0x00472008, 0x00361601, 0x00280c00, 0x00200200, 0x001a0000, 0x00160000, 0x00210000, 0x00682c0c, 0x009f4f20, 0x00b75a20, 0x00b75617, 0x00b25214, 0x00b35010, 0x00bc4d09, 0x00c04f0c, 0x00c04f12, 0x00a6491a, 0x006c341f, 0x00390c00, 0x00531700, 0x00a75826, 0x00bc5b16, 0x00bd570e, 0x00af5418, 0x006c2a02, 0x00160000, 0x00030000, 0x00030004, 0x000c0000, 0x00381300, 0x007c3c12, 0x00ae541b, 0x00bb5413, 0x00b95210, 0x00b95010, 0x00bc5214, 0x00ba5012, 0x00b8500c, 0x00b75614, 0x00a95319, 0x008d4d26, 0x00200100, 0x00070000, 0x00000100, 0x00000100, 0x000c0000, 0x00441f02, 0x008f4717, 0x00b0551b, 0x00b25415, 0x00b65210, 0x00bc500f, 0x00bb5013, 0x00b24f1c, 0x00984f29, 0x00311000, 0x000a0000, 0x00050002, 0x000c0000, 0x00482004, 0x008c4c1c, 0x00ac561c, 0x00ab5824, 0x00602d11, 0x001d0000, 0x000f0000, 0x00381800, 0x00904817, 0x00b35316, 0x00b64c11, 0x00bd5315, 0x00b54f09, 0x00b8550f, 0x00b65516, 0x00b15012, 0x00b4500f, 0x00ad561f, 0x005a2100, 0x003f0900, 0x007f3202, 0x00a55220, 0x00a3582e, 0x007b4326, 0x002c1204, 0x00060000, 0x00000000, 0x00060000, 0x001b0000, 0x006e371e, 0x00ac5422, 0x00b95211, 0x00b85412, 0x00a95318, 0x008c4c22, 0x00401000, 0x00200000, 0x0050200c, 0x00984a20, 0x00b3541b, 0x00b65210, 0x00b0561b, 0x00884922, 0x002c0300, 0x00160000, 0x002e0900, 0x00a45526, 0x00bb591d, 0x00b4561c, 0x00933e0c, 0x004a0600, 0x0074310e, 0x00ac5420, 0x00b45214, 0x00b85517, 0x00b25418, 0x00a34c19, 0x007d3a14, 0x00481c06, 0x001c0200, 0x00100000, 0x000d0000, 0x00020108, 0x00000003, 0x00190400, 0x00593c2c, 0x004c2e1d, 0x002c0b00, 0x001c0000, 0x00481a02, 0x008c4416, 0x00ac5217, 0x00b85817, 0x00b05214, 0x009f4f1d, 0x00662b07, 0x00200000, 0x00210000, 0x00682e10, 0x00a5562a, 0x00b6541a, 0x00c05410, 0x00c4550c, 0x00ba4e04, 0x00ba5512, 0x00b95512, 0x00be5409, 0x00c4590d, 0x00b85209, 0x00b15514, 0x00974715, 0x006e2000, 0x00913800, 0x00b85919, 0x00b65714, 0x00bc5911, 0x00c05306, 0x00bd530a, 0x00b95e24, 0x00803c10, 0x00351100, 0x00140000, 0x003c1400, 0x007f441c, 0x00ab5c17, 0x00b75b06, 0x00c2600b, 0x00c05a04, 0x00c75c08, 0x00c45b04, 0x00c55d05, 0x00c35b03, 0x00c55905, 0x00c4590d, 0x00b95410, 0x008f4211, 0x00381300, 0x00080000, 0x000b0808, 0x005a5c5b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009e9e9e, 0x00727473, 0x0048494b, 0x002a2d2e, 0x000f1010, 0x00030301, 0x00030000, 0x00050000, 0x00080000, 0x000c0000, 0x00130000, 0x00180100, 0x001f0300, 0x00250400, 0x002c0800, 0x00350e00, 0x003d1300, 0x003e1500, 0x00391400, 0x00371200, 0x00340c00, 0x002a0400, 0x00200100, 0x001a0000, 0x00140000, 0x00100000, 0x00090000, 0x00080100, 0x00080000, 0x00080000, 0x000b0000, 0x00290c00, 0x0084441b, 0x00b0571d, 0x00be5410, 0x00c1530c, 0x00b54d07, 0x00bc5512, 0x00bd520e, 0x00b54b0d, 0x00b14b17, 0x008b3713, 0x00441206, 0x00320500, 0x005e1c00, 0x00ae5c23, 0x00bb5b15, 0x00ba5a14, 0x00a7541f, 0x004b1200, 0x00110000, 0x00030000, 0x00040000, 0x00130000, 0x00592807, 0x00964b19, 0x00b35115, 0x00bb4f0d, 0x00bb5310, 0x00b7500d, 0x00b85014, 0x00b65014, 0x00b4500f, 0x00b25415, 0x00a4501c, 0x00753718, 0x00180000, 0x00070006, 0x00030300, 0x00040000, 0x00180400, 0x005f3010, 0x00a1501c, 0x00b45414, 0x00b35412, 0x00b45310, 0x00bc4f0f, 0x00bc5014, 0x00b24f1f, 0x00974e2a, 0x00301000, 0x00090000, 0x00050004, 0x000e0000, 0x00592b0b, 0x0096501d, 0x00b0541a, 0x00a85323, 0x005a2710, 0x001b0000, 0x00100000, 0x003e1c00, 0x00974c1a, 0x00b45116, 0x00b74c15, 0x00bc5117, 0x00b65008, 0x00b7540c, 0x00b35414, 0x00af5015, 0x00b1541c, 0x00984819, 0x00461300, 0x00410e00, 0x008c3a05, 0x00b0581f, 0x00a4582c, 0x00794223, 0x00301203, 0x00080000, 0x00020000, 0x00080000, 0x001f0000, 0x007a4025, 0x00ac5220, 0x00b85010, 0x00b85412, 0x00ac551b, 0x008c4c23, 0x003e0f00, 0x001e0000, 0x004e1e0b, 0x00964820, 0x00b2541c, 0x00b45212, 0x00ad571c, 0x00844a21, 0x002c0400, 0x00180000, 0x00381000, 0x00a85623, 0x00bc5817, 0x00b85618, 0x0098410e, 0x00480900, 0x006d2f10, 0x00a8501c, 0x00b75112, 0x00bb4f0d, 0x00bd520e, 0x00bc5313, 0x00ac511b, 0x00884724, 0x00602f18, 0x00380f00, 0x00180000, 0x00070000, 0x00070000, 0x001a0300, 0x00573320, 0x00764d36, 0x005f341d, 0x00310c00, 0x002d0200, 0x00612400, 0x009f5020, 0x00af5114, 0x00b85618, 0x00a84e16, 0x0092491f, 0x004f1e08, 0x001f0000, 0x00370700, 0x00854722, 0x00a34c16, 0x00b85410, 0x00bd520b, 0x00c0540c, 0x00bf5814, 0x00b8510e, 0x00be510b, 0x00bc5008, 0x00c25711, 0x00bb5514, 0x00ac4d14, 0x009c3e06, 0x00973600, 0x00b45414, 0x00b85814, 0x00b9550d, 0x00c0540b, 0x00bc5412, 0x00b05926, 0x00642601, 0x00200000, 0x00210600, 0x005a2808, 0x009b5824, 0x00af5b12, 0x00bf610c, 0x00bc5906, 0x00be5806, 0x00c55e0d, 0x00c45a0a, 0x00c45d08, 0x00c45b04, 0x00c65a06, 0x00c45a0c, 0x00bb5612, 0x00934615, 0x003b1604, 0x00090000, 0x00070404, 0x00525453, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b4b2, 0x008c8c8b, 0x0060605f, 0x0041403f, 0x002b2a28, 0x001c1c1a, 0x00100c0c, 0x00020000, 0x00040000, 0x00050000, 0x00060000, 0x000a0000, 0x000c0000, 0x000c0000, 0x000b0000, 0x000c0000, 0x000c0000, 0x000d0000, 0x00120000, 0x00120000, 0x000c0000, 0x00080000, 0x00080000, 0x00050000, 0x00020000, 0x00040400, 0x000e0c08, 0x000f0806, 0x000a0000, 0x00290900, 0x00924d1c, 0x00b75919, 0x00c05510, 0x00c04f05, 0x00c65407, 0x00bd4d07, 0x00b85216, 0x00ac501f, 0x0082310c, 0x0064240c, 0x00401308, 0x003a0c00, 0x006a2100, 0x00b65c1f, 0x00bb570f, 0x00b65917, 0x00985328, 0x002c0000, 0x000d0000, 0x00040000, 0x00080000, 0x00200600, 0x0078411d, 0x00a55723, 0x00b35014, 0x00ba4e0c, 0x00bc5410, 0x00b64f0c, 0x00b85014, 0x00b85014, 0x00b65212, 0x00b05418, 0x00a15121, 0x00581d01, 0x00120000, 0x00040003, 0x00030000, 0x00090000, 0x002d1100, 0x00794420, 0x00ab5420, 0x00b55013, 0x00b35211, 0x00b6520f, 0x00bb4f0d, 0x00bc4f12, 0x00b34f1c, 0x00984c27, 0x002d0d00, 0x00080000, 0x00080000, 0x00120000, 0x006d3b18, 0x009f5523, 0x00af541b, 0x00a14f20, 0x0050200b, 0x00160000, 0x00120000, 0x00442005, 0x009d5221, 0x00b45218, 0x00b84f18, 0x00b95014, 0x00b8510c, 0x00b5520a, 0x00b25313, 0x00ad531b, 0x00ac5828, 0x0078340e, 0x00330400, 0x004d1a00, 0x0096440f, 0x00b4551a, 0x00ac5725, 0x00803f1b, 0x00341300, 0x000b0000, 0x00050000, 0x000a0000, 0x00250100, 0x008a4c2f, 0x00ac501e, 0x00b84f0f, 0x00b85211, 0x00ac561c, 0x00854821, 0x003a1000, 0x001b0000, 0x004b1c0b, 0x0095481d, 0x00b25118, 0x00b45111, 0x00ac561c, 0x00844821, 0x002c0400, 0x001b0000, 0x00481c03, 0x00ae551c, 0x00c25710, 0x00bc5817, 0x009b4814, 0x00450d00, 0x00632c10, 0x009f4c1d, 0x00b45214, 0x00bd500c, 0x00c35008, 0x00c45108, 0x00bd5413, 0x00ae5b28, 0x0098542c, 0x00753816, 0x004c1d05, 0x00180000, 0x00100000, 0x00100000, 0x003c1c0c, 0x007b482e, 0x008e5434, 0x00652f11, 0x00370400, 0x00380500, 0x00743818, 0x00a6521e, 0x00b4551c, 0x00af541e, 0x00ab5b2b, 0x00874420, 0x00400c00, 0x00250000, 0x00401400, 0x00955220, 0x00a85010, 0x00bf5714, 0x00bd4e0a, 0x00b84b06, 0x00c0540f, 0x00c05310, 0x00bc4e0d, 0x00c25414, 0x00bf5214, 0x00b8500d, 0x00bb5613, 0x00a64404, 0x00b75414, 0x00bb5811, 0x00b9530a, 0x00c1560f, 0x00b75818, 0x00975020, 0x00441200, 0x001c0000, 0x003f1701, 0x00814817, 0x00ac6121, 0x00b85d17, 0x00bd5b10, 0x00bc5909, 0x00bc5808, 0x00bb580e, 0x00be5a10, 0x00c15c0b, 0x00c45c07, 0x00c65a06, 0x00c4580b, 0x00bd5711, 0x00994918, 0x00411907, 0x000c0000, 0x00040000, 0x004a4c4b, 0x0020201f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9c9b, 0x008c8c8c, 0x0068686a, 0x004f5053, 0x003c3c40, 0x00303034, 0x00242428, 0x0017181c, 0x000f1014, 0x00090a0e, 0x00040509, 0x00030207, 0x00040304, 0x00050300, 0x00060300, 0x000b0400, 0x000f0901, 0x00110f0b, 0x00171612, 0x0024221c, 0x002e2e28, 0x00393b37, 0x00444845, 0x00474745, 0x002c2825, 0x000d0100, 0x002a0500, 0x00a45521, 0x00c05b15, 0x00c2550f, 0x00be4d04, 0x00c45104, 0x00b84c08, 0x00ae5320, 0x008d401a, 0x005c1a00, 0x00602814, 0x005e3124, 0x00471400, 0x00702400, 0x00b95c1c, 0x00bc560f, 0x00b45719, 0x00884b28, 0x00210000, 0x000b0000, 0x00080000, 0x000d0000, 0x003b1908, 0x008b4e26, 0x00a8561f, 0x00b45013, 0x00bc5010, 0x00bb5310, 0x00b54e0c, 0x00b85011, 0x00b95114, 0x00b65212, 0x00ae541b, 0x009e5328, 0x003d0b00, 0x00100000, 0x00030001, 0x00040000, 0x00100000, 0x004d270a, 0x008e4e27, 0x00ac521d, 0x00b85214, 0x00b45111, 0x00b6520f, 0x00b84f0c, 0x00ba5010, 0x00b5501a, 0x00984b23, 0x00290c00, 0x00080000, 0x000b0000, 0x001c0000, 0x00804824, 0x00a55724, 0x00ad531b, 0x009b4c1e, 0x00461b08, 0x00130000, 0x00140000, 0x004c250b, 0x00a35827, 0x00b25016, 0x00b65017, 0x00b74f13, 0x00b8520c, 0x00b5500b, 0x00b45111, 0x00ad541d, 0x00a0552c, 0x005a1f01, 0x002a0000, 0x00602c10, 0x00a04c17, 0x00b05012, 0x00b05621, 0x00833c14, 0x00391400, 0x000b0000, 0x00060000, 0x000b0000, 0x002b0200, 0x00965434, 0x00b15320, 0x00b84f10, 0x00b5500f, 0x00ab551d, 0x007b421f, 0x00340f00, 0x00190000, 0x004a1d0b, 0x0096471b, 0x00b15016, 0x00b45210, 0x00ac561c, 0x00844821, 0x002e0500, 0x001c0000, 0x0058280f, 0x00b05518, 0x00c3550a, 0x00be5915, 0x009f4c18, 0x00441000, 0x005d2a0e, 0x0098491a, 0x00b45214, 0x00bf500a, 0x00c45004, 0x00c34d01, 0x00bb4b04, 0x00b35115, 0x00ae5824, 0x00a35323, 0x008e4c24, 0x00522108, 0x00220000, 0x00140000, 0x001c0000, 0x00612f14, 0x00884b28, 0x00975530, 0x00602404, 0x00330600, 0x00441400, 0x008f441b, 0x00ac5320, 0x00b2541d, 0x00b25620, 0x00a34f20, 0x007c3916, 0x002a0100, 0x00240000, 0x00622c06, 0x009a5220, 0x00ae5018, 0x00bb5212, 0x00c3540e, 0x00bf4f09, 0x00bd500d, 0x00c05715, 0x00ba5012, 0x00bc5112, 0x00bb530c, 0x00ba540c, 0x00b85410, 0x00bb5714, 0x00bc550e, 0x00bc560d, 0x00bd5711, 0x00b0591d, 0x00743c10, 0x00330800, 0x00320500, 0x00642f13, 0x00a15b20, 0x00b05c13, 0x00bb5a13, 0x00bb5610, 0x00bb5a11, 0x00ba5c14, 0x00a04400, 0x00bb5c16, 0x00bd5a0c, 0x00c25b08, 0x00c65805, 0x00c45708, 0x00bf5610, 0x009d4c18, 0x00441a07, 0x000c0000, 0x00040000, 0x00454746, 0x00434443, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00aeb0b4, 0x0097999f, 0x0085888d, 0x006d7075, 0x005a5c62, 0x004b4d53, 0x00404248, 0x00383b40, 0x0037393d, 0x00343736, 0x00383935, 0x003f403c, 0x004c4d4b, 0x00595c5d, 0x006d7071, 0x00878785, 0x00989897, 0x00adb0b1, 0x001f2020, 0x009fa0a3, 0x004b4646, 0x000f0000, 0x00340800, 0x00b35a23, 0x00c05009, 0x00c2540c, 0x00bc5009, 0x00b54805, 0x00b7541c, 0x00904420, 0x00581900, 0x005d2206, 0x007e452c, 0x00703d27, 0x00480e00, 0x00742700, 0x00b95e24, 0x00bf5815, 0x00b45a20, 0x00784021, 0x001a0000, 0x000b0000, 0x00090000, 0x00140000, 0x005d331a, 0x00975325, 0x00a95017, 0x00b85315, 0x00bb4f0e, 0x00b7500d, 0x00b44d0b, 0x00b84e10, 0x00b95012, 0x00b45012, 0x00a9521b, 0x0094502b, 0x002a0000, 0x000c0000, 0x00040000, 0x00060000, 0x001a0200, 0x006e3a18, 0x009f5326, 0x00b14f19, 0x00bb5214, 0x00b55110, 0x00b75310, 0x00b8500c, 0x00b95010, 0x00b75018, 0x0097491f, 0x00270800, 0x00090000, 0x000e0000, 0x00300c00, 0x008e4d28, 0x00a75522, 0x00ac521c, 0x0094481d, 0x003d1705, 0x00120000, 0x00180100, 0x00562c10, 0x00a55828, 0x00b05015, 0x00b55017, 0x00b44f11, 0x00b9520f, 0x00b6500a, 0x00b54e0c, 0x00af541c, 0x008f4c28, 0x00420f00, 0x002d0400, 0x006f3b1c, 0x00a7531f, 0x00b25013, 0x00b3541d, 0x00873c12, 0x003b1601, 0x000b0000, 0x00060000, 0x000b0000, 0x00340800, 0x009c5532, 0x00b45421, 0x00b94f11, 0x00b44f0e, 0x00aa5620, 0x006f3c1c, 0x002f0e00, 0x00160000, 0x00491e0b, 0x0097481a, 0x00b15012, 0x00b5510e, 0x00ac561c, 0x00844924, 0x00320700, 0x00200000, 0x00683418, 0x00af5418, 0x00c05509, 0x00c05914, 0x00a14d17, 0x00481000, 0x005f280b, 0x009a4817, 0x00b75313, 0x00bc4d06, 0x00c25004, 0x00c45006, 0x00c05008, 0x00b9500c, 0x00b85213, 0x00b65416, 0x00ae551e, 0x009a4f24, 0x005e2708, 0x00260000, 0x001c0000, 0x00380b00, 0x0073391b, 0x009f572d, 0x008e4922, 0x0054240f, 0x00340800, 0x005c1e00, 0x009f5024, 0x00b55218, 0x00bb5214, 0x00ae4d16, 0x00a8582c, 0x0060290f, 0x002d0100, 0x002c0000, 0x006c341a, 0x00964b20, 0x00b0551b, 0x00bd520e, 0x00c04f07, 0x00ba4f09, 0x00be5714, 0x00b4520e, 0x00b75614, 0x00bb5917, 0x00b1500c, 0x00bb5915, 0x00b8540e, 0x00bc530b, 0x00c05811, 0x00b55711, 0x00a65b23, 0x00512200, 0x00290200, 0x00541f04, 0x008a4820, 0x00b05c19, 0x00b95b0e, 0x00ba530a, 0x00c25b18, 0x00b35618, 0x00a64d14, 0x008c3700, 0x00b85e1b, 0x00ba5a0e, 0x00c15a09, 0x00c55804, 0x00c45506, 0x00c0550e, 0x009f4c18, 0x00461b04, 0x000d0000, 0x00060000, 0x00444547, 0x00787a79, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a2a4aa, 0x003f3b3e, 0x000b0000, 0x00380b00, 0x00bc5b24, 0x00c65209, 0x00c1530c, 0x00b85010, 0x00b5541d, 0x009c481c, 0x00611f04, 0x004f1400, 0x007b3919, 0x009b5a36, 0x00733a18, 0x00480b00, 0x00772b00, 0x00b75e27, 0x00bc5615, 0x00b25820, 0x006f381b, 0x00180000, 0x000a0000, 0x000a0000, 0x00220100, 0x007a4628, 0x00a15624, 0x00ad5014, 0x00bc5417, 0x00b84b0c, 0x00b85010, 0x00b85010, 0x00b94f10, 0x00ba5113, 0x00b44f11, 0x00a5511c, 0x00864a2a, 0x001f0000, 0x00080000, 0x00060300, 0x000c0000, 0x002c0c00, 0x0085451e, 0x00ac5423, 0x00b64f18, 0x00bb4e13, 0x00b5500f, 0x00b75310, 0x00b4500c, 0x00b85110, 0x00b85115, 0x0096481c, 0x00240600, 0x000a0000, 0x00120000, 0x004a1f08, 0x00985028, 0x00a95320, 0x00ac521d, 0x008c441b, 0x00371405, 0x00100000, 0x00240800, 0x00613116, 0x00a85828, 0x00b25016, 0x00b35013, 0x00b55010, 0x00ba520f, 0x00b74f0a, 0x00b8500c, 0x00b05620, 0x00793b1c, 0x00330400, 0x003d1000, 0x007a4020, 0x00a85420, 0x00b45318, 0x00b2531c, 0x00893e14, 0x003b1704, 0x00090000, 0x00040000, 0x000d0000, 0x00401100, 0x00a15530, 0x00b4521e, 0x00b94f13, 0x00b5500f, 0x00ab5a24, 0x00623519, 0x00260c00, 0x00160000, 0x004c210c, 0x009c4c1c, 0x00b35012, 0x00b5500d, 0x00ad541b, 0x00864b25, 0x00370b00, 0x00250000, 0x00784025, 0x00ae5417, 0x00c0550c, 0x00be5915, 0x00a04c16, 0x00491000, 0x0063290b, 0x009f4815, 0x00b95211, 0x00be5008, 0x00bf4e04, 0x00bf4f08, 0x00c1510c, 0x00c0520c, 0x00bd500c, 0x00ba4f0b, 0x00b44f0e, 0x00b3551d, 0x009d5124, 0x0059250d, 0x002a0400, 0x001e0000, 0x0054210b, 0x008c4620, 0x00a35b31, 0x007c452b, 0x004a1903, 0x00400800, 0x007b3410, 0x00b6541c, 0x00bc5010, 0x00bc5417, 0x00af531f, 0x009f552e, 0x005b2007, 0x00290000, 0x002c0000, 0x006a3416, 0x00995023, 0x00ac4f10, 0x00c05811, 0x00bd540e, 0x00b8520b, 0x00b8550f, 0x00b4530c, 0x00bc5714, 0x00b7520f, 0x00b95611, 0x00b9530d, 0x00be510c, 0x00bd5613, 0x00ac5717, 0x0094521d, 0x003d1100, 0x00330800, 0x0074360f, 0x00a75822, 0x00b45814, 0x00c05a10, 0x00bf580f, 0x00b95717, 0x00a5501f, 0x007a2a00, 0x00944207, 0x00b45c1a, 0x00ba5b11, 0x00c05a0b, 0x00c75807, 0x00c65608, 0x00c1560f, 0x00a04c17, 0x00461a02, 0x000f0000, 0x00050000, 0x00444547, 0x009b9fa0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00989ba4, 0x0037343a, 0x00100101, 0x003d1000, 0x00b95720, 0x00cc5610, 0x00be5412, 0x00ad5018, 0x00a2522b, 0x00672206, 0x004a0c00, 0x00753519, 0x009b4b1c, 0x00aa5825, 0x007b380d, 0x00501000, 0x00742c02, 0x00b05b29, 0x00bc5415, 0x00b1541c, 0x006d3617, 0x00180000, 0x000c0000, 0x000d0000, 0x003b1300, 0x008c4e29, 0x00a8561f, 0x00b25112, 0x00bb5214, 0x00b84c0d, 0x00b85010, 0x00ba5312, 0x00bb4e10, 0x00bb5013, 0x00b25011, 0x00a45320, 0x00784127, 0x00180000, 0x00050000, 0x00040100, 0x00100000, 0x004b2307, 0x0094491e, 0x00b3511d, 0x00b94d17, 0x00b84b11, 0x00b55010, 0x00b55411, 0x00b34f0d, 0x00b55110, 0x00b85214, 0x0094471b, 0x00200400, 0x00090000, 0x00180000, 0x00673418, 0x00a05228, 0x00ac5120, 0x00ac5320, 0x00844018, 0x00301304, 0x00100000, 0x002f0e00, 0x006e381a, 0x00aa5525, 0x00b45114, 0x00b45010, 0x00b8510f, 0x00ba500e, 0x00b84f0b, 0x00b8510f, 0x00ac5520, 0x005e2307, 0x002b0000, 0x00582408, 0x00894823, 0x00a85420, 0x00b0521a, 0x00af531f, 0x0088411b, 0x0038190a, 0x00080000, 0x00030000, 0x00110000, 0x00501c03, 0x00a4562d, 0x00b3501c, 0x00b94e14, 0x00b65011, 0x00a85824, 0x00542b12, 0x001c0600, 0x00180000, 0x00552911, 0x00a2501f, 0x00b65212, 0x00b4500c, 0x00ac541a, 0x008b4c28, 0x003f0e00, 0x002e0000, 0x00884a2d, 0x00ae531a, 0x00be5812, 0x00bb5818, 0x009c4a15, 0x00480e00, 0x00672b0b, 0x00a44a15, 0x00ba500f, 0x00c0500b, 0x00be4e08, 0x00b84c0c, 0x00b84e0c, 0x00bc4f0c, 0x00bf500d, 0x00bd500d, 0x00bc500e, 0x00b54c0b, 0x00b2571e, 0x0098512b, 0x004c1700, 0x002b0500, 0x00270000, 0x006c3314, 0x00924f29, 0x00985530, 0x00783918, 0x004c1800, 0x00501400, 0x009c4411, 0x00b44f11, 0x00c05819, 0x00b34b0e, 0x00b04d12, 0x00a15121, 0x004f1c04, 0x00240100, 0x002a0800, 0x0067381c, 0x009c5221, 0x00ae5414, 0x00bc5810, 0x00ba5005, 0x00bf5309, 0x00bd4f06, 0x00bf4e06, 0x00c1510c, 0x00bc5010, 0x00be5113, 0x00c0500e, 0x00b95414, 0x00a7581e, 0x00783b0c, 0x003f0d00, 0x00582300, 0x00964c17, 0x00b35a19, 0x00ba5512, 0x00be5613, 0x00be5b16, 0x00a84f12, 0x00843910, 0x005d1500, 0x00a6551c, 0x00b35b15, 0x00ba5b13, 0x00c0580d, 0x00c65706, 0x00c85606, 0x00c0550e, 0x009c4814, 0x00441700, 0x000f0000, 0x00060000, 0x0048494c, 0x00787b7c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00999fa5, 0x002f3034, 0x000c0000, 0x00401400, 0x00b5571f, 0x00c8540f, 0x00bc5414, 0x00a8501c, 0x00783013, 0x00460600, 0x005e1c04, 0x009a4e2b, 0x00b2541c, 0x00ae5417, 0x0080390b, 0x00501300, 0x006c2600, 0x00b05c2c, 0x00c05818, 0x00b25117, 0x00703516, 0x00180000, 0x000c0000, 0x00110000, 0x0053240a, 0x00944e23, 0x00ad5418, 0x00b44f0e, 0x00b94f11, 0x00bc5013, 0x00b54e0d, 0x00b95211, 0x00b84b0c, 0x00b84e10, 0x00b04e10, 0x00a25222, 0x006c3b24, 0x00130000, 0x00060200, 0x00030000, 0x00140000, 0x006b391a, 0x00a14d1f, 0x00b84f18, 0x00bc4c17, 0x00ba4c14, 0x00b44f11, 0x00b55314, 0x00b0500f, 0x00b35010, 0x00b55315, 0x0092461b, 0x001f0200, 0x000a0000, 0x001c0000, 0x007b4220, 0x00a75327, 0x00b05120, 0x00ac5423, 0x007e3c17, 0x002c1102, 0x000f0000, 0x00381200, 0x00783a18, 0x00ad5421, 0x00b75114, 0x00b44f0e, 0x00b9520f, 0x00b8500d, 0x00b7500f, 0x00b05015, 0x009e4f20, 0x00450e00, 0x00270000, 0x00713515, 0x009b5226, 0x00ae5723, 0x00b0521b, 0x00ae5321, 0x0088431f, 0x0036180a, 0x00070000, 0x00030000, 0x00140200, 0x005c2508, 0x00a7562b, 0x00b3501c, 0x00b95016, 0x00b45012, 0x00a25524, 0x0048230e, 0x00140100, 0x001a0000, 0x00613018, 0x00a65320, 0x00b85211, 0x00b54e0b, 0x00ac5318, 0x008e4c26, 0x00451000, 0x00360000, 0x0094502f, 0x00b05217, 0x00bf5813, 0x00b9591b, 0x00984816, 0x00470c00, 0x006a2c0c, 0x00a54c18, 0x00b94f10, 0x00bd4c08, 0x00c0500c, 0x00bc5214, 0x00b95012, 0x00bb4d0d, 0x00bd4e0d, 0x00be5010, 0x00be5210, 0x00c05310, 0x00b55010, 0x00ab5421, 0x00904d28, 0x00431500, 0x001c0000, 0x00411100, 0x00753c1c, 0x009f552c, 0x009d552c, 0x00682e12, 0x003e0400, 0x00702400, 0x00ab511e, 0x00b55015, 0x00bc5210, 0x00c05511, 0x00aa4d11, 0x0092542f, 0x004d220c, 0x00210000, 0x002a0200, 0x00642b08, 0x00944c1c, 0x00a65318, 0x00b45414, 0x00bb5310, 0x00c4550f, 0x00bd4c03, 0x00c05108, 0x00bb5110, 0x00b95012, 0x00c05010, 0x00b85318, 0x00a45928, 0x00602400, 0x004b1000, 0x00814013, 0x00b05e1c, 0x00b5560e, 0x00bc5414, 0x00b85416, 0x00ad5418, 0x009c501c, 0x00591700, 0x005f1d00, 0x00ac5c20, 0x00b55c15, 0x00b95a12, 0x00bf580c, 0x00c75505, 0x00c75507, 0x00bd540e, 0x00984712, 0x00411500, 0x000e0000, 0x00080000, 0x004c4d50, 0x00545758, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00969ea0, 0x00303535, 0x00080300, 0x00371300, 0x00b15820, 0x00c65913, 0x00ba5616, 0x0099410f, 0x00470000, 0x00581300, 0x0092411e, 0x00ae5323, 0x00b34d0e, 0x00b35414, 0x00813c0f, 0x004f1400, 0x00662000, 0x00b05928, 0x00c55614, 0x00b65114, 0x00743818, 0x001a0000, 0x000c0000, 0x00100000, 0x00713b1d, 0x00994c1c, 0x00b05213, 0x00b74f0c, 0x00b74c0f, 0x00b94f13, 0x00b74f10, 0x00b85010, 0x00bc4f12, 0x00b84d10, 0x00b14f11, 0x00a05122, 0x00603420, 0x00100000, 0x00030000, 0x00060000, 0x001c0000, 0x007c4422, 0x00b05423, 0x00b94c14, 0x00bb4c16, 0x00b94e15, 0x00b45014, 0x00b25013, 0x00b05012, 0x00b05012, 0x00b15016, 0x008f461c, 0x001d0000, 0x000e0000, 0x002b0400, 0x008d4c27, 0x00ab5225, 0x00b04e1e, 0x00aa5324, 0x00783914, 0x00281001, 0x00100000, 0x00431500, 0x008c4520, 0x00ae501b, 0x00b54c0c, 0x00bc5410, 0x00b8510e, 0x00ad4605, 0x00b6551c, 0x00a45424, 0x00793816, 0x00300000, 0x003a0700, 0x008b441c, 0x00a4521d, 0x00ae531b, 0x00ae5019, 0x00ac501f, 0x0089421f, 0x003b1c0e, 0x00090000, 0x00040000, 0x001c0600, 0x00692e0f, 0x00a55124, 0x00b3501c, 0x00b44c12, 0x00b45216, 0x00994d1f, 0x00371502, 0x000e0000, 0x00280800, 0x006a3519, 0x00a95320, 0x00b85010, 0x00b54e0c, 0x00ac5016, 0x00904a22, 0x00501300, 0x00440500, 0x00a0532c, 0x00b75313, 0x00c05710, 0x00b75a20, 0x008d4116, 0x00430c00, 0x00682d11, 0x00a64f20, 0x00b84f13, 0x00bf4d0a, 0x00c14e09, 0x00be5012, 0x00b84e10, 0x00bb4b0c, 0x00bf4f10, 0x00be5114, 0x00b74c0f, 0x00bc500f, 0x00b74e0c, 0x00b35114, 0x00a7531f, 0x0080411f, 0x003e0e00, 0x001e0000, 0x004b1e08, 0x008c471e, 0x00a4582a, 0x00904c27, 0x00632504, 0x00430700, 0x0086401b, 0x00ab501c, 0x00b85214, 0x00b95113, 0x00b04f14, 0x00a95826, 0x0095502b, 0x005e240a, 0x00320000, 0x00280000, 0x00491802, 0x007d4528, 0x0095532b, 0x00ab5723, 0x00b35414, 0x00b85209, 0x00bc560c, 0x00b35610, 0x00b15412, 0x00bc5314, 0x00b3501a, 0x00a0552c, 0x004b0900, 0x007a3202, 0x00a45418, 0x00ae520b, 0x00b9570c, 0x00ba5614, 0x00b0551d, 0x009f562c, 0x00642702, 0x00440a00, 0x007d3e11, 0x00a85819, 0x00b85c15, 0x00bc5b14, 0x00bf560d, 0x00c75404, 0x00c55507, 0x00bc5713, 0x008e4110, 0x003b1200, 0x000d0000, 0x00070000, 0x00505154, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00969d9b, 0x00343834, 0x00070200, 0x00331000, 0x00b05d26, 0x00be5611, 0x00b75313, 0x00903500, 0x005c0e00, 0x00803310, 0x00ac5024, 0x00b55018, 0x00b44a08, 0x00b35314, 0x00823e13, 0x00501400, 0x00631e00, 0x00b05a28, 0x00c45511, 0x00b95414, 0x007c3e1c, 0x001b0000, 0x000d0000, 0x00140000, 0x00793f1e, 0x00a14e1c, 0x00b35213, 0x00b8500c, 0x00b84d11, 0x00ba4f14, 0x00b74f10, 0x00b7500f, 0x00b94f11, 0x00b84e12, 0x00b04f13, 0x009d5022, 0x005c3020, 0x000e0000, 0x00020000, 0x00080000, 0x00310e00, 0x0085441f, 0x00b0511e, 0x00bb4c13, 0x00bc4c15, 0x00b84c16, 0x00b45014, 0x00b25014, 0x00b05014, 0x00ae5014, 0x00ac4f17, 0x008c441c, 0x001d0000, 0x00100000, 0x00441400, 0x00965026, 0x00ae5122, 0x00b14e1e, 0x00a85124, 0x00743614, 0x00270e00, 0x00110000, 0x00501c03, 0x0091441c, 0x00b3511c, 0x00b74e0e, 0x00b14906, 0x00b85310, 0x00b65318, 0x00a6501e, 0x00985734, 0x00441100, 0x002a0000, 0x00562009, 0x00924517, 0x00af541b, 0x00ac4c11, 0x00b35018, 0x00af501d, 0x008c421c, 0x00401c0c, 0x000e0000, 0x00080000, 0x00200500, 0x00743613, 0x00a85023, 0x00b24f1c, 0x00b34d14, 0x00b15016, 0x008e4518, 0x00311000, 0x00100000, 0x00381202, 0x00783c1c, 0x00aa501d, 0x00b74f10, 0x00b7500d, 0x00ae5117, 0x00964b21, 0x00601c00, 0x00581000, 0x00a85427, 0x00bd5411, 0x00c0550e, 0x00b55b24, 0x00833b13, 0x00430c00, 0x006e3317, 0x00a85023, 0x00b74f13, 0x00bf4e0c, 0x00ba4807, 0x00b84c0f, 0x00bd5317, 0x00bf4f11, 0x00ba4a0b, 0x00ba4c0e, 0x00bd5110, 0x00bb4f0d, 0x00b84f0c, 0x00ba5110, 0x00b35419, 0x009a4e20, 0x00632909, 0x00290400, 0x00280300, 0x00642807, 0x009c542a, 0x00a2582a, 0x008c451d, 0x00521800, 0x00470b00, 0x00a25327, 0x00ae541d, 0x00b35115, 0x00b85518, 0x00b8571c, 0x00ac5320, 0x009b4d23, 0x00723010, 0x00400a00, 0x002a0000, 0x002e0000, 0x00511e08, 0x007d3e1c, 0x009a5124, 0x00a8571d, 0x00a95415, 0x00aa5414, 0x00b45919, 0x00b75214, 0x00b4521e, 0x008b3c17, 0x006a2000, 0x0094410a, 0x00b25614, 0x00b8560c, 0x00bc5810, 0x00b25415, 0x00aa5a2a, 0x00793e20, 0x003e0c00, 0x00440d00, 0x00975420, 0x00b45f1f, 0x00b4540c, 0x00bb5610, 0x00c0560d, 0x00c85506, 0x00c55708, 0x00bb5a19, 0x00823b0c, 0x00310c00, 0x000b0000, 0x000d0607, 0x005c5b5f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009d9e98, 0x003e3c33, 0x00060000, 0x002e0c00, 0x00aa5b27, 0x00b95210, 0x00bc5411, 0x00a13c00, 0x008c3000, 0x00a74b1d, 0x00b44f19, 0x00b95014, 0x00b64e10, 0x00ac5018, 0x0088431a, 0x00551800, 0x005c1800, 0x00ab5827, 0x00be5412, 0x00bb5618, 0x00894824, 0x00200000, 0x000e0000, 0x00190000, 0x00834421, 0x00a7501c, 0x00b35010, 0x00b74e0c, 0x00b74d12, 0x00b95014, 0x00b85011, 0x00b54d0f, 0x00b84e12, 0x00b74f13, 0x00b15014, 0x009b4e20, 0x00562c1b, 0x000d0000, 0x00040000, 0x000b0000, 0x0050250a, 0x00914920, 0x00af4d19, 0x00bb4d14, 0x00bb4d15, 0x00b64c14, 0x00b44f16, 0x00b15015, 0x00b05015, 0x00ad5016, 0x00a74d18, 0x0088431d, 0x001f0000, 0x00140000, 0x00642d0e, 0x00a05327, 0x00af4f1e, 0x00b14e1c, 0x00a85024, 0x00703311, 0x00260c00, 0x00140000, 0x00592104, 0x009e4d22, 0x00b2511a, 0x00b85011, 0x00b44f0e, 0x00b04f11, 0x00ab501c, 0x009b512a, 0x00643721, 0x00260100, 0x00260000, 0x0070361c, 0x00a44f1d, 0x00b55315, 0x00b44e10, 0x00b44e12, 0x00b4501a, 0x00914118, 0x00471e08, 0x00130000, 0x000d0000, 0x00240700, 0x0083411c, 0x00aa5020, 0x00b14e1b, 0x00b24e18, 0x00ac4f17, 0x0081390f, 0x002c0b00, 0x00130000, 0x004e200b, 0x00894621, 0x00ac501b, 0x00b74f10, 0x00b65011, 0x00af5017, 0x009a4a1b, 0x00742800, 0x00701e00, 0x00ac501e, 0x00c45410, 0x00c15410, 0x00b45c28, 0x0077300a, 0x00460b00, 0x007a381a, 0x00a95223, 0x00b44e14, 0x00bd5011, 0x00bd5011, 0x00b85016, 0x00b74e14, 0x00bb4c10, 0x00bf4e0e, 0x00c14d0b, 0x00c04d08, 0x00c0500c, 0x00bc500c, 0x00ba5110, 0x00b35114, 0x00ac5521, 0x008c481f, 0x004b1d06, 0x001e0000, 0x00390c00, 0x00783c1a, 0x00a55524, 0x00a75522, 0x007c3b15, 0x00420700, 0x00642404, 0x009d542a, 0x00ad5316, 0x00b8530f, 0x00b64f0c, 0x00b14c0b, 0x00b95a1a, 0x00a64f18, 0x00873c12, 0x00632305, 0x00360100, 0x00270000, 0x00200000, 0x00340800, 0x00531d06, 0x0072300e, 0x00954210, 0x00b1541a, 0x00b45116, 0x00b3541f, 0x007b2400, 0x00903c12, 0x00ac5014, 0x00b85710, 0x00bc560d, 0x00b85612, 0x00ad5820, 0x00904d25, 0x00471a08, 0x00280000, 0x005d2500, 0x00a85e20, 0x00b55c18, 0x00b8550f, 0x00bb540d, 0x00c1550c, 0x00c95607, 0x00c4560b, 0x00b85d1f, 0x00723107, 0x00240500, 0x000b0000, 0x00140f10, 0x0068686c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00aba59d, 0x00494439, 0x00080000, 0x002b0c00, 0x00995225, 0x00bc5b20, 0x00bd5615, 0x00b34a0a, 0x00ae4b13, 0x00b4501b, 0x00b0460b, 0x00b84e12, 0x00b85014, 0x00ab4f1b, 0x00944a23, 0x005f1e00, 0x00531200, 0x009c5021, 0x00b85312, 0x00bb581a, 0x00965128, 0x002b0000, 0x00100000, 0x001d0000, 0x00894724, 0x00ab511c, 0x00b25011, 0x00b54e0d, 0x00b74d14, 0x00b84f15, 0x00b85011, 0x00b44c0d, 0x00b74d12, 0x00b74e14, 0x00b15015, 0x00984c1d, 0x00522615, 0x000e0000, 0x00060000, 0x00100000, 0x006b3718, 0x009c4c1f, 0x00ae4d16, 0x00b94e14, 0x00b84d14, 0x00b64c13, 0x00b44e15, 0x00b14e14, 0x00b04f14, 0x00ad5018, 0x00a44e1b, 0x0084401d, 0x00200000, 0x001c0000, 0x00804320, 0x00a85424, 0x00af4c18, 0x00b24e1b, 0x00a85124, 0x006e3010, 0x00280b00, 0x001a0000, 0x00602404, 0x00a65425, 0x00b1501a, 0x00b34c10, 0x00b45114, 0x00ac5119, 0x009e4f21, 0x00844829, 0x00300a00, 0x001c0000, 0x003d0f00, 0x00864424, 0x00ac531e, 0x00b85011, 0x00b85010, 0x00b44b0f, 0x00b54f16, 0x00964216, 0x004e2008, 0x00140000, 0x000d0000, 0x00270700, 0x00904a22, 0x00ac501e, 0x00b14e1b, 0x00b04f19, 0x00a94f18, 0x00773308, 0x00280700, 0x00180000, 0x00622c10, 0x009a4d24, 0x00af501b, 0x00b74f12, 0x00b65013, 0x00b04f14, 0x00a04c1a, 0x008b3709, 0x008b3002, 0x00b04c17, 0x00c55510, 0x00c15612, 0x00b15e2d, 0x006a2500, 0x004b0c00, 0x00833c18, 0x00ac5220, 0x00b45014, 0x00b2480c, 0x00b84f14, 0x00b4511c, 0x00af4d18, 0x00b44f16, 0x00bd5315, 0x00c1500f, 0x00c04c08, 0x00bf4d08, 0x00bd4e0c, 0x00b85010, 0x00b14f11, 0x00b0531b, 0x00a55627, 0x00723818, 0x00380c00, 0x00230000, 0x004c1c03, 0x008f4314, 0x00a6521d, 0x009b5024, 0x00763513, 0x00340000, 0x00713515, 0x00a95624, 0x00b35213, 0x00b84f0d, 0x00bc4f0a, 0x00bb5008, 0x00b44f0b, 0x00b2571e, 0x009b4c1e, 0x0083401f, 0x00693219, 0x004a1d09, 0x003a0d00, 0x003b0600, 0x00500c00, 0x00812a00, 0x00ad4c14, 0x00b45116, 0x00b3521b, 0x00842800, 0x00a74c1c, 0x00b55415, 0x00b6510c, 0x00b8540e, 0x00b05618, 0x009e5424, 0x00683010, 0x00250100, 0x00300a00, 0x00824412, 0x00ab5a18, 0x00b3540f, 0x00c05912, 0x00be550d, 0x00c4560b, 0x00c85407, 0x00c0550b, 0x00b45e24, 0x00622802, 0x00190000, 0x00080001, 0x001c181c, 0x0078777c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b7afa7, 0x00585047, 0x00080100, 0x00240c00, 0x007a3c1c, 0x00b35e30, 0x00b95820, 0x00b34d10, 0x00b34c10, 0x00b85115, 0x00b44c10, 0x00b44c12, 0x00b34910, 0x00b3511d, 0x00a04f25, 0x006a2400, 0x004c1000, 0x008b451b, 0x00b75617, 0x00bc5b18, 0x00a15527, 0x003d0a00, 0x00120000, 0x00200100, 0x008c4824, 0x00ac511c, 0x00b04f11, 0x00b34d10, 0x00b54c14, 0x00b74e16, 0x00b84e12, 0x00b44b0c, 0x00b74d14, 0x00b44d14, 0x00b25016, 0x00984b1c, 0x00502310, 0x00100000, 0x000c0000, 0x00180000, 0x007e401d, 0x00a34e1c, 0x00af4e17, 0x00b74f13, 0x00b64c11, 0x00b74d12, 0x00b64d14, 0x00b44d13, 0x00b24d12, 0x00af5019, 0x00a34f20, 0x007d3c1a, 0x00230000, 0x00300400, 0x00945028, 0x00ac5320, 0x00b04a14, 0x00b44e1a, 0x00aa5326, 0x006b2c0c, 0x00280800, 0x00210300, 0x00682a07, 0x00a45022, 0x00af511c, 0x00ad4c15, 0x00aa4c15, 0x00aa5828, 0x008c4c29, 0x004f1c05, 0x00200000, 0x00220000, 0x0070351b, 0x009c5028, 0x00a94c14, 0x00b54e0d, 0x00b54c0e, 0x00b64c10, 0x00b64d15, 0x00994417, 0x0055240c, 0x00140000, 0x000d0000, 0x002a0800, 0x00985025, 0x00ae501b, 0x00b14f19, 0x00ad4e19, 0x00a8511c, 0x00712f05, 0x00270500, 0x00230200, 0x00743212, 0x00a65123, 0x00b14f19, 0x00b54c13, 0x00b44d13, 0x00b04f14, 0x00aa5019, 0x00a24813, 0x00a5440e, 0x00b85014, 0x00c4540f, 0x00bf5817, 0x00ac5d30, 0x005d1a00, 0x00571000, 0x008e3e14, 0x00af5019, 0x00b75014, 0x00b75014, 0x009e3c05, 0x008b3000, 0x00944011, 0x00a85021, 0x00ac501c, 0x00b24c10, 0x00be5010, 0x00bc4b08, 0x00bb4c09, 0x00b74f12, 0x00b25016, 0x00b05218, 0x00ae5723, 0x0090481d, 0x005e2708, 0x00210000, 0x002c0500, 0x00692804, 0x009d4e1f, 0x00a55221, 0x00994c24, 0x00541c04, 0x003d0800, 0x00874020, 0x00a85023, 0x00b65116, 0x00c05310, 0x00bc4c08, 0x00ba4d0a, 0x00b75311, 0x00ac5010, 0x00ae581e, 0x00a04f1a, 0x00944417, 0x00904114, 0x00964413, 0x009a4410, 0x00a64710, 0x00b24f15, 0x00b55014, 0x00b04f13, 0x00a0400a, 0x00ad4e18, 0x00b55315, 0x00b55111, 0x00b45515, 0x00a95721, 0x00793e1a, 0x003f1300, 0x00200000, 0x00471c00, 0x009c5520, 0x00af5514, 0x00b85410, 0x00be550f, 0x00c2560e, 0x00c4550b, 0x00c75507, 0x00be570e, 0x00aa5c26, 0x00542200, 0x00100000, 0x00030002, 0x0029282c, 0x008a898d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00bdb6af, 0x00646158, 0x00000000, 0x00110300, 0x00471805, 0x00843e1e, 0x00af5b2c, 0x00b2541c, 0x00b24f14, 0x00b44f11, 0x00b65014, 0x00b64d14, 0x00b54810, 0x00b64f1b, 0x00a74e22, 0x00752c08, 0x004a1000, 0x00783810, 0x00ba5b19, 0x00bf5a14, 0x00a95722, 0x00561c00, 0x00170000, 0x00200100, 0x008c4622, 0x00ab501c, 0x00b05015, 0x00b34e11, 0x00b44c16, 0x00b64d17, 0x00b74d11, 0x00b44a0e, 0x00b74e16, 0x00b24c15, 0x00b05015, 0x009a4b1d, 0x004f200d, 0x00130000, 0x00100000, 0x00270400, 0x008c4720, 0x00a84e19, 0x00b05017, 0x00b34e13, 0x00b44c10, 0x00b64c10, 0x00b54c10, 0x00b64d14, 0x00b44b11, 0x00b04f19, 0x00a04f22, 0x00773515, 0x00280000, 0x004d1c06, 0x009f5428, 0x00af511a, 0x00b34a12, 0x00b44e1a, 0x00aa5326, 0x00672507, 0x00250400, 0x00280700, 0x0070320d, 0x00a55221, 0x00aa4f1c, 0x00ac501e, 0x00ac5424, 0x00964b22, 0x005a250c, 0x00220000, 0x00300300, 0x005b2409, 0x00984f29, 0x00a7501f, 0x00ae4d13, 0x00b24c0d, 0x00b55012, 0x00b34c12, 0x00b34c15, 0x009b471b, 0x00592a12, 0x00130000, 0x000c0000, 0x00301000, 0x009e5227, 0x00b05018, 0x00b04e18, 0x00ac4e18, 0x00a85420, 0x006c2b03, 0x00290500, 0x00340f00, 0x00823915, 0x00ac501f, 0x00b24e19, 0x00b44d14, 0x00b14c13, 0x00b04e14, 0x00ae5018, 0x00ae4d14, 0x00b34c12, 0x00bc500f, 0x00c4540d, 0x00bd5818, 0x00a0552a, 0x00511000, 0x00641c00, 0x00964414, 0x00b04f16, 0x00b85214, 0x00b14c10, 0x00ac4e17, 0x00883406, 0x00621500, 0x00671e00, 0x00893e15, 0x00a14e1d, 0x00ac4c16, 0x00b94f13, 0x00bc4f10, 0x00b64e12, 0x00b45014, 0x00b45013, 0x00b35219, 0x00a34e1c, 0x00803f19, 0x003b1203, 0x001a0000, 0x003e0b00, 0x007a3814, 0x00a95527, 0x00a04c20, 0x0086482b, 0x00410a00, 0x00460800, 0x00873d1c, 0x00a9511f, 0x00b45214, 0x00b94c0e, 0x00bd500f, 0x00b74d09, 0x00bc5510, 0x00b34f0c, 0x00b45212, 0x00b45318, 0x00b45318, 0x00b65417, 0x00b55314, 0x00b65014, 0x00b85315, 0x00b7500f, 0x00b24e0c, 0x00b75518, 0x00b04f13, 0x00b65116, 0x00b8561c, 0x00b0551d, 0x00974e20, 0x00522308, 0x00200000, 0x002a0400, 0x0064310c, 0x00ab5c26, 0x00b15212, 0x00bc5411, 0x00bf520c, 0x00c3540b, 0x00c45408, 0x00c85608, 0x00bd5813, 0x009b511f, 0x00461900, 0x000b0000, 0x00000004, 0x003a393e, 0x009d9ea1, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00585854, 0x00747b72, 0x00000404, 0x00000000, 0x001c0100, 0x00451400, 0x007f3d1d, 0x009c4d20, 0x00ad521a, 0x00b04d10, 0x00b34c12, 0x00b84e13, 0x00bd4c10, 0x00b74913, 0x00ad4e21, 0x0080340f, 0x00491300, 0x00662800, 0x00bd5a14, 0x00c2570b, 0x00b0581f, 0x00753814, 0x001a0000, 0x001e0000, 0x0088421e, 0x00a84d1b, 0x00af5017, 0x00b14e14, 0x00b24c17, 0x00b54c16, 0x00b64c10, 0x00b34b0e, 0x00b64f18, 0x00af4b15, 0x00b05017, 0x009c4c1d, 0x0050200c, 0x00170000, 0x00130000, 0x003c1304, 0x00964b21, 0x00ab4d15, 0x00af5017, 0x00af4d11, 0x00b54d10, 0x00b54c0e, 0x00b44b10, 0x00b94e14, 0x00b4490f, 0x00b04d18, 0x009c4c23, 0x006c2d0e, 0x002f0000, 0x006f381f, 0x00a35324, 0x00b04f16, 0x00b44b11, 0x00b44e18, 0x00a95024, 0x00612001, 0x00230000, 0x002f0c00, 0x00783812, 0x00a65424, 0x00a74f1e, 0x00a64e1f, 0x009b481d, 0x00682403, 0x002e0200, 0x002c0600, 0x00602608, 0x009a5127, 0x00aa4f1c, 0x00af4c12, 0x00b45116, 0x00b04c11, 0x00b45318, 0x00af4c16, 0x00af4c18, 0x00994921, 0x005a2d19, 0x00100000, 0x000d0000, 0x003a1c08, 0x00a05324, 0x00b15015, 0x00b04f18, 0x00a94d19, 0x00a85422, 0x00662600, 0x002a0500, 0x004b2110, 0x0090421b, 0x00b14e1b, 0x00b44d18, 0x00b44d17, 0x00b14c14, 0x00b04c13, 0x00b04d14, 0x00b04c0f, 0x00b74c0d, 0x00bd4d09, 0x00c6540a, 0x00bb5715, 0x00904921, 0x00440800, 0x006f2802, 0x009d4b1c, 0x00b05017, 0x00b65011, 0x00b45012, 0x00b0531b, 0x00984818, 0x00742f09, 0x004e1400, 0x003d0800, 0x005f2404, 0x0098502a, 0x00a84c1a, 0x00ba5119, 0x00b74d12, 0x00b64c0e, 0x00bb4d0c, 0x00b74e0e, 0x00b0521b, 0x009b5027, 0x0064301b, 0x00240000, 0x001d0000, 0x00441504, 0x00914824, 0x00a45024, 0x009f5029, 0x00773312, 0x00300000, 0x00531e04, 0x0087441f, 0x00a65424, 0x00b35219, 0x00b74f10, 0x00b44b09, 0x00bb4f0e, 0x00b64c0e, 0x00b95114, 0x00b75217, 0x00b24f15, 0x00b44f14, 0x00b44e12, 0x00b84f0f, 0x00bb510d, 0x00ba4f08, 0x00b75009, 0x00b65611, 0x00b25313, 0x00b45015, 0x00b55621, 0x00a04c1d, 0x0070310c, 0x00300d00, 0x00180000, 0x00441800, 0x0086481c, 0x00af5b26, 0x00b45114, 0x00bb510f, 0x00c1530c, 0x00c35208, 0x00c55508, 0x00c85708, 0x00ba5814, 0x00853e0e, 0x00360e00, 0x00090000, 0x00000209, 0x004e4e54, 0x00b0b1b5, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00889088, 0x00000b0b, 0x00010405, 0x00120000, 0x00220000, 0x00400c00, 0x0071300e, 0x00984c20, 0x00aa531f, 0x00b04d15, 0x00b4490f, 0x00bf4d12, 0x00b74911, 0x00b05020, 0x00883912, 0x004b1300, 0x00591c00, 0x00b85918, 0x00bc5409, 0x00b8581c, 0x00924a22, 0x001f0000, 0x001e0000, 0x00823f1a, 0x00a44c18, 0x00ad5018, 0x00b04d15, 0x00b14a15, 0x00b44b14, 0x00b54c10, 0x00b34b0e, 0x00b45119, 0x00ad4b14, 0x00b05017, 0x009d4c20, 0x0051200c, 0x00190000, 0x00170000, 0x004c1f0b, 0x009d4e22, 0x00ac4c13, 0x00b04f16, 0x00ae4c10, 0x00b74f10, 0x00b44c0c, 0x00b34b0e, 0x00b85014, 0x00b44a10, 0x00ac4c1a, 0x00974a22, 0x00672808, 0x00350000, 0x008b4929, 0x00a54f1d, 0x00b04c11, 0x00b44b0f, 0x00b14d18, 0x00a55028, 0x005c1c02, 0x00230000, 0x00341001, 0x00783c18, 0x009d5227, 0x00a2552c, 0x00924823, 0x00672302, 0x003c0200, 0x00330600, 0x005c2c15, 0x0098502c, 0x00a54d1c, 0x00af4910, 0x00b85013, 0x00b04c10, 0x00b04e14, 0x00ad4b13, 0x00b04e18, 0x00ac4c1a, 0x00984b22, 0x005c2f19, 0x00130000, 0x00120200, 0x0046230f, 0x00a25325, 0x00b34d14, 0x00b04e18, 0x00a94e1c, 0x00a45526, 0x00602200, 0x002e0300, 0x00602e15, 0x009d491d, 0x00b34d18, 0x00b44a14, 0x00b64d17, 0x00b34c15, 0x00b24c14, 0x00b34c12, 0x00b44c0d, 0x00bd4e0d, 0x00c2500c, 0x00c7540c, 0x00b75617, 0x0083411b, 0x003c0200, 0x00793108, 0x00a54f1c, 0x00b44f14, 0x00b84d0e, 0x00b34d0e, 0x00b15016, 0x00aa5220, 0x009b4e26, 0x006f3215, 0x003c0800, 0x00350400, 0x005b2407, 0x0087401c, 0x00a55124, 0x00ae501b, 0x00b44d11, 0x00bb4f0e, 0x00b74c0d, 0x00b25018, 0x00a55124, 0x00804122, 0x00441805, 0x00180000, 0x00250300, 0x0062280e, 0x00a1552f, 0x00a85425, 0x009e4f21, 0x005a2304, 0x00300000, 0x00551e04, 0x00894725, 0x00a45123, 0x00af5019, 0x00bc5217, 0x00b84a0e, 0x00b94c10, 0x00bb5014, 0x00b95014, 0x00b54f13, 0x00b65015, 0x00b85013, 0x00ba4e0c, 0x00bc4f08, 0x00bc5009, 0x00bb530c, 0x00ad4c07, 0x00b55614, 0x00b05116, 0x00ab5423, 0x0088421e, 0x00471400, 0x00190000, 0x00250500, 0x00662e07, 0x00a15623, 0x00ae551c, 0x00b85616, 0x00ba520f, 0x00bd500a, 0x00c35409, 0x00c6560a, 0x00c8580a, 0x00b55614, 0x00703005, 0x00270500, 0x00080100, 0x00020910, 0x005c5f63, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009a9c97, 0x001c1b17, 0x00070000, 0x00180400, 0x004c2d24, 0x00250000, 0x00380800, 0x005e2b0f, 0x008a4823, 0x00ad511d, 0x00b2480c, 0x00ba5014, 0x00b24c10, 0x00ac4e16, 0x00954516, 0x005e2305, 0x004d1300, 0x009c4a15, 0x00b55616, 0x00c25a1c, 0x00a85424, 0x00340700, 0x00240000, 0x00783410, 0x00a34e1c, 0x00a84e19, 0x00b04e18, 0x00b54c18, 0x00b54913, 0x00b54c10, 0x00b04c0e, 0x00ac4c13, 0x00ad5018, 0x00b05018, 0x009c481c, 0x005a2512, 0x001b0000, 0x00180000, 0x0069391e, 0x009f4c20, 0x00ad4b15, 0x00b3501b, 0x00b04b12, 0x00b74c0f, 0x00b64c0c, 0x00b14f10, 0x00af4f10, 0x00b04d15, 0x00a94f1f, 0x008f4824, 0x00591b00, 0x00541100, 0x009c5025, 0x00a84c17, 0x00b44f11, 0x00b34a08, 0x00b04f18, 0x009e5130, 0x00561d0c, 0x001e0000, 0x003d190a, 0x00794324, 0x00945935, 0x007b4024, 0x00521e08, 0x00350800, 0x00350500, 0x00682c12, 0x00994f2e, 0x00a74d25, 0x00af4c1c, 0x00b24b14, 0x00b24c11, 0x00b04c14, 0x00b04d15, 0x00b34c14, 0x00b24c14, 0x00ad4c15, 0x009f5020, 0x00613114, 0x001a0000, 0x001f0400, 0x00532610, 0x00a75228, 0x00b44c18, 0x00b04915, 0x00ab4e1d, 0x009d552c, 0x005f2400, 0x003e0800, 0x00773814, 0x00aa5020, 0x00b24913, 0x00b84b13, 0x00b84a12, 0x00b44c14, 0x00b34c14, 0x00b44c10, 0x00b74a0d, 0x00c04c0d, 0x00c75210, 0x00c3530f, 0x00bc6025, 0x005c2000, 0x00430d00, 0x00873a0c, 0x00b04f18, 0x00c05014, 0x00bc4a0c, 0x00b84e12, 0x00b24d10, 0x00b84f15, 0x00b04f1b, 0x009d4923, 0x00733010, 0x003d0a00, 0x002c0100, 0x00431908, 0x005f2c12, 0x00944c21, 0x00a7511b, 0x00ad5018, 0x00b5531b, 0x00af4c16, 0x00ad511f, 0x00a05324, 0x00692f0e, 0x00280500, 0x00180000, 0x00340c00, 0x00793e22, 0x00a85420, 0x00aa5118, 0x0090481c, 0x00541900, 0x00330300, 0x0057240e, 0x008c4626, 0x00a75128, 0x00b45120, 0x00b54a11, 0x00ba4d12, 0x00bb4e10, 0x00bb4f0e, 0x00b94f10, 0x00b55014, 0x00b55012, 0x00bb500a, 0x00bc500b, 0x00bc4f10, 0x00b74e10, 0x00b5510e, 0x00b25513, 0x00ac5218, 0x009a4f25, 0x0055250f, 0x00220000, 0x00180000, 0x003f1400, 0x008c4317, 0x00af551a, 0x00af5210, 0x00b65610, 0x00b85411, 0x00ba520d, 0x00c2560e, 0x00c6580f, 0x00c4570c, 0x00b05618, 0x00551e00, 0x001b0200, 0x00000003, 0x00171f27, 0x00797c7f, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a8a7a3, 0x003d3630, 0x000b0000, 0x001c0804, 0x00614338, 0x00582b15, 0x00370600, 0x00300400, 0x005a250c, 0x0091441c, 0x00a14814, 0x00ac4e16, 0x00b25117, 0x00b2541a, 0x009f4c19, 0x00692c0a, 0x00470c00, 0x0083380c, 0x00b55b23, 0x00c05714, 0x00b65720, 0x00541e08, 0x00260000, 0x006d2e0c, 0x009b4c1c, 0x00a94e1c, 0x00b14d18, 0x00b44914, 0x00b64b12, 0x00b44c10, 0x00b04e10, 0x00ac4e13, 0x00ae5016, 0x00b04d17, 0x009c481e, 0x005c2817, 0x001c0000, 0x00200000, 0x00744020, 0x00a24c21, 0x00b04c18, 0x00b14f19, 0x00b04b14, 0x00b84c10, 0x00b64c0c, 0x00af4e0f, 0x00ae5114, 0x00ac4c16, 0x00a44d20, 0x008a4625, 0x00501100, 0x006e2400, 0x00a75222, 0x00b04e16, 0x00b64e10, 0x00b24b0a, 0x00a84e18, 0x00944d30, 0x004d1909, 0x00210000, 0x00422012, 0x0070442c, 0x0066371d, 0x00471a08, 0x00320600, 0x00350c00, 0x005f2b11, 0x00964c29, 0x00a74c22, 0x00af4b1c, 0x00b24b17, 0x00b44b13, 0x00b24c11, 0x00b14c14, 0x00b14c13, 0x00b54c12, 0x00b44c12, 0x00ae4c14, 0x00a05020, 0x00673415, 0x00200000, 0x00260400, 0x00602c16, 0x00a65027, 0x00b44a18, 0x00b44a17, 0x00ac4c1e, 0x009d5730, 0x005f2400, 0x00501500, 0x00843c13, 0x00ab4f1c, 0x00b44c14, 0x00b74910, 0x00b54a10, 0x00b24c13, 0x00b14c13, 0x00b44b0f, 0x00b84b0b, 0x00c24f09, 0x00c7540e, 0x00c25614, 0x00aa531d, 0x00481400, 0x004d1b00, 0x0092451c, 0x00b04d18, 0x00ba480d, 0x00c04c0e, 0x00b64c11, 0x00b34c10, 0x00b94c0e, 0x00b64c11, 0x00a94c1d, 0x009d4f28, 0x00753816, 0x00380b00, 0x001a0000, 0x002e0a00, 0x00562000, 0x00874318, 0x00a25021, 0x00a84d1b, 0x00b4521c, 0x00b04e18, 0x00a54c15, 0x008f471c, 0x004d200c, 0x001c0000, 0x001d0000, 0x004a1c08, 0x009b4f20, 0x00a95018, 0x00a95423, 0x00883e15, 0x004c1500, 0x003d0a00, 0x0064270c, 0x00914520, 0x00b05022, 0x00b84f17, 0x00b84e0f, 0x00ba4e0c, 0x00bb4f0e, 0x00b94f10, 0x00b74f13, 0x00b55012, 0x00b8500d, 0x00b9500d, 0x00b84d13, 0x00b95014, 0x00b7520f, 0x00ae5211, 0x00a25621, 0x006e3512, 0x00311003, 0x00170000, 0x00290400, 0x0061280f, 0x009f4b1c, 0x00b55416, 0x00b5540f, 0x00b8550f, 0x00b8530f, 0x00bc5410, 0x00c4560f, 0x00c1550d, 0x00bd5711, 0x009a4913, 0x00401400, 0x000d0000, 0x00000004, 0x0030373e, 0x00919294, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b2b1ad, 0x00615c57, 0x00080000, 0x00180401, 0x00603f30, 0x00915734, 0x006a2904, 0x003b0500, 0x002f0000, 0x00521f08, 0x00804122, 0x00a05024, 0x00ab4f1b, 0x00ac4c14, 0x00a8511d, 0x007d3c17, 0x00480e00, 0x00671e00, 0x00b55d2b, 0x00c05410, 0x00ba5819, 0x007b3f1f, 0x002a0000, 0x00592000, 0x00924820, 0x00ac4e1c, 0x00b54c16, 0x00b14812, 0x00b44d14, 0x00af4c0e, 0x00b04f10, 0x00b14f11, 0x00b04c13, 0x00b14a14, 0x009d481f, 0x005f301d, 0x001a0000, 0x002a0200, 0x00844a2a, 0x00a54e21, 0x00b04c19, 0x00b04c19, 0x00b14c16, 0x00b84b11, 0x00b74a0f, 0x00ae4c0e, 0x00b05116, 0x00ab4c17, 0x00a44d20, 0x0087411f, 0x004b0900, 0x008a3d15, 0x00a95120, 0x00b24c11, 0x00b44c0d, 0x00b04e12, 0x00a45020, 0x008e4c2f, 0x00441302, 0x001c0000, 0x0033160b, 0x0045271c, 0x00331104, 0x00210000, 0x00340400, 0x00672c0c, 0x00964d28, 0x00aa5429, 0x00ac4e1c, 0x00b04c14, 0x00b24c10, 0x00b44c0d, 0x00b44c0d, 0x00b24c11, 0x00b44b11, 0x00b74911, 0x00b54913, 0x00b14a15, 0x00a55023, 0x0070381b, 0x00250000, 0x002c0700, 0x006c3820, 0x00a44f24, 0x00b14a16, 0x00b64b1a, 0x00ab4a1c, 0x00a05731, 0x00602200, 0x00662803, 0x008e441c, 0x00ab4c1c, 0x00b44d14, 0x00b34b0e, 0x00b14c0f, 0x00ae4e11, 0x00af4d11, 0x00b24c0d, 0x00b84d06, 0x00c15201, 0x00c45806, 0x00bd5c14, 0x008f430e, 0x00340600, 0x00471c0e, 0x00884626, 0x00aa5124, 0x00b44b11, 0x00bb4d0f, 0x00b54f14, 0x00b44f16, 0x00b44c0e, 0x00b55014, 0x00ab4f19, 0x00aa5527, 0x00a15129, 0x00723010, 0x00370a00, 0x001c0000, 0x00280000, 0x00542006, 0x00843f1b, 0x00a55022, 0x00b04e18, 0x00b65014, 0x00b35218, 0x00a04d1e, 0x00763c1e, 0x00330c00, 0x00150000, 0x002a0500, 0x006c300e, 0x00a55428, 0x00ae501f, 0x00b25526, 0x00873e14, 0x00581a00, 0x00501400, 0x00702c06, 0x00a04614, 0x00b65014, 0x00b94e0a, 0x00ba4f0b, 0x00b74f12, 0x00b74e14, 0x00b84d14, 0x00b84d13, 0x00b45012, 0x00b45113, 0x00b55014, 0x00b44e0f, 0x00b6520a, 0x00aa5414, 0x00854b20, 0x003f1901, 0x00150000, 0x00160000, 0x00471503, 0x0086401e, 0x00ac5421, 0x00b45214, 0x00ba5310, 0x00b9500c, 0x00bc4f0c, 0x00c4540e, 0x00c9570d, 0x00c0540d, 0x00b75c21, 0x00743207, 0x00290600, 0x00080000, 0x00030304, 0x00505457, 0x00b0b0b0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00323231, 0x00837c7a, 0x000b0000, 0x00100000, 0x00401e0f, 0x00a06037, 0x00a05426, 0x00793715, 0x00400800, 0x002c0100, 0x004c1e0c, 0x007c391c, 0x009e4b22, 0x00aa4e1c, 0x00aa5220, 0x008c461c, 0x005a1c00, 0x00501000, 0x00a35428, 0x00bc5410, 0x00bb5613, 0x009c582c, 0x003c0800, 0x00410c00, 0x00894623, 0x00ac4c1c, 0x00b64b12, 0x00b04812, 0x00b04d14, 0x00ac4c0e, 0x00ae4d0e, 0x00b34d10, 0x00b34b0f, 0x00b34a12, 0x00a04c20, 0x00653824, 0x00190000, 0x00380a00, 0x00915030, 0x00a84d20, 0x00b14d1a, 0x00af4c18, 0x00b14c16, 0x00b94a14, 0x00b74910, 0x00b04b10, 0x00af5017, 0x00ab4b18, 0x00a54e21, 0x007f3814, 0x00530f00, 0x009d4c24, 0x00a94c1d, 0x00b14810, 0x00b3490e, 0x00af4e17, 0x00a15122, 0x00854a2c, 0x003c1200, 0x00160000, 0x001d0500, 0x001c0400, 0x001c0000, 0x00310800, 0x00642b13, 0x00994d27, 0x00ab5322, 0x00a84816, 0x00b24f17, 0x00b14b0f, 0x00b34b0c, 0x00b44c0c, 0x00b44c0d, 0x00b24c11, 0x00b44b13, 0x00b74913, 0x00b54914, 0x00b24b17, 0x00a85124, 0x00783c1c, 0x002e0200, 0x00320800, 0x007c4529, 0x00a44f20, 0x00b34c15, 0x00b84917, 0x00ad4819, 0x00a2542c, 0x00621f00, 0x007b3410, 0x009c4a23, 0x00ac491a, 0x00b44c15, 0x00b14c10, 0x00b04e10, 0x00ac4e14, 0x00ad4c14, 0x00b44c0f, 0x00ba4f09, 0x00c25403, 0x00c05908, 0x00b55e1c, 0x006c2d00, 0x00210000, 0x00290b04, 0x00602c16, 0x00954c28, 0x00ac501e, 0x00b04d14, 0x00b04e16, 0x00b35014, 0x00b44c0d, 0x00b55010, 0x00b04f16, 0x00a74815, 0x00a94c1d, 0x00a4522b, 0x00773c1c, 0x00360a00, 0x001c0000, 0x00240000, 0x00531c04, 0x0089421f, 0x00a04816, 0x00b04d14, 0x00b85115, 0x00a94c16, 0x00914921, 0x005c290d, 0x00230200, 0x001c0000, 0x003c0d00, 0x008d4c2d, 0x00a84c20, 0x00b24f1d, 0x00ac5522, 0x00944818, 0x00702c03, 0x00732900, 0x009c4310, 0x00b04e10, 0x00b74f0a, 0x00b74f0a, 0x00b45013, 0x00b44f16, 0x00b84c15, 0x00b84c14, 0x00b45014, 0x00b35013, 0x00b65414, 0x00ad4c09, 0x00b2520d, 0x00a1561c, 0x00562f0e, 0x00200a00, 0x00100000, 0x00280400, 0x006a2b10, 0x00a04d23, 0x00b0551f, 0x00b35013, 0x00b95010, 0x00bc4c0c, 0x00c3500b, 0x00c7530c, 0x00c85409, 0x00be5714, 0x00a75a2a, 0x004c1b00, 0x00180000, 0x000a0200, 0x000f0d0e, 0x00717274, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009d9a98, 0x001e1614, 0x000d0000, 0x00260700, 0x00905028, 0x00ad5c27, 0x00ab5825, 0x00813813, 0x00461404, 0x002c0200, 0x00461000, 0x00783518, 0x009f4e24, 0x00a65123, 0x00984a20, 0x00722f0a, 0x00410b00, 0x00803d1a, 0x00b95718, 0x00c05815, 0x00ae5f29, 0x005b1c00, 0x00300000, 0x007c4124, 0x00a84918, 0x00b64b10, 0x00b24b16, 0x00ad4b14, 0x00ae4d13, 0x00ad4c0d, 0x00b54c0e, 0x00b4490c, 0x00b44912, 0x00a34d22, 0x006d402a, 0x001d0000, 0x004a1400, 0x0099502d, 0x00a84c1e, 0x00b04c18, 0x00ae4b18, 0x00b14b17, 0x00b84814, 0x00b74812, 0x00b34c15, 0x00ae4c17, 0x00aa4a19, 0x00a24b1e, 0x00752c08, 0x006c2300, 0x00a65028, 0x00ab4a1c, 0x00b24b17, 0x00b14a14, 0x00ad4b14, 0x009e4d20, 0x00784428, 0x00351406, 0x00100000, 0x00120000, 0x00180000, 0x002c0700, 0x0064301b, 0x00945031, 0x00a74e22, 0x00ac4814, 0x00b24910, 0x00b54b0f, 0x00b4490f, 0x00b4490f, 0x00b44a0e, 0x00b44a0f, 0x00b24b14, 0x00b24b17, 0x00b54916, 0x00b44917, 0x00b14b18, 0x00a55023, 0x007c3f1d, 0x00390900, 0x00380b00, 0x00864d2a, 0x00a44e1a, 0x00b44c10, 0x00b9480e, 0x00b44815, 0x00a85124, 0x006d1f00, 0x008e3a16, 0x00a84c27, 0x00b0481b, 0x00b54817, 0x00b14c16, 0x00af4d18, 0x00ac4c1c, 0x00ad4a1a, 0x00b54a18, 0x00be5015, 0x00c2560e, 0x00bc5a15, 0x00a55926, 0x00441100, 0x00130000, 0x000b0000, 0x002e0d00, 0x00653118, 0x00904820, 0x00a65120, 0x00ab5018, 0x00b04d10, 0x00b94d0c, 0x00b84a0a, 0x00b74c15, 0x00b44d18, 0x00b04812, 0x00ae521e, 0x009b5224, 0x00703715, 0x00360a00, 0x001c0000, 0x00240000, 0x004f1f0c, 0x008b441e, 0x00a84f1a, 0x00b1480c, 0x00bb5317, 0x00a74f1c, 0x0089441d, 0x00481c01, 0x00180000, 0x001d0000, 0x00542719, 0x00a0532c, 0x00a74b17, 0x00ac4f18, 0x00b15520, 0x00a44a1a, 0x009f4414, 0x00ab4c19, 0x00af4d13, 0x00b34f0d, 0x00b4500c, 0x00b25010, 0x00b24f14, 0x00b44d17, 0x00b64d17, 0x00b84c14, 0x00b84e12, 0x00b8510f, 0x00b0500f, 0x00ab561b, 0x007e4015, 0x00291400, 0x000a0000, 0x00170000, 0x00471b0b, 0x0090421e, 0x00ad511d, 0x00b15318, 0x00b45214, 0x00b85011, 0x00bf4e0e, 0x00cc540e, 0x00c95207, 0x00c55205, 0x00bd5d1f, 0x007f4420, 0x002c0c00, 0x000c0000, 0x00040102, 0x00302d2c, 0x00989494, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00060606, 0x00030303, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00afaeac, 0x00443d3c, 0x000a0000, 0x001a0000, 0x00733816, 0x00a85621, 0x00ba5c1f, 0x00b0551f, 0x00844024, 0x00581f0f, 0x00430a00, 0x00480c00, 0x00712a08, 0x0094461f, 0x00a3532b, 0x00843d18, 0x003e0a00, 0x005e2404, 0x00b15821, 0x00bd5919, 0x00b65c21, 0x00803808, 0x00340200, 0x006d371b, 0x00a04515, 0x00b44b13, 0x00b34c18, 0x00ac4916, 0x00b04f18, 0x00ae4b10, 0x00b54c0c, 0x00b44a0c, 0x00b34a10, 0x00a34d20, 0x0079452d, 0x00270000, 0x00642508, 0x009e4d28, 0x00aa4c1b, 0x00b04c17, 0x00af4c17, 0x00b14b17, 0x00b74715, 0x00b84816, 0x00b64c18, 0x00ad4a17, 0x00a84818, 0x009c4317, 0x00702400, 0x00873b14, 0x00a94e24, 0x00b04c1e, 0x00b14b1a, 0x00b24c18, 0x00af4b16, 0x00a05023, 0x00693c20, 0x002b1204, 0x000c0000, 0x00100000, 0x00310a00, 0x00642e18, 0x00904d30, 0x00a4522b, 0x00ac491a, 0x00b44914, 0x00b84d11, 0x00b4480b, 0x00b6480f, 0x00b44910, 0x00b44910, 0x00b34a12, 0x00b04a16, 0x00b04a18, 0x00b24b17, 0x00b24b17, 0x00ae4b18, 0x00a54e20, 0x0082401c, 0x004c1500, 0x00420d00, 0x00904f2b, 0x00a74c18, 0x00b44b0f, 0x00b9480b, 0x00b64b12, 0x00a94f1f, 0x00802b01, 0x009c401a, 0x00b04d24, 0x00b44819, 0x00b54916, 0x00b04b15, 0x00af4c17, 0x00af4a19, 0x00b24817, 0x00bc4b18, 0x00c55219, 0x00c35812, 0x00b4591b, 0x00854722, 0x00220000, 0x000b0000, 0x00030000, 0x00100000, 0x00300f00, 0x00602d11, 0x00914f27, 0x00aa5823, 0x00ab4b0e, 0x00bc4f0e, 0x00bd4b0c, 0x00b64810, 0x00bb4f18, 0x00b64c10, 0x00b04b10, 0x00a9541c, 0x00985025, 0x00703720, 0x00370c02, 0x00160000, 0x00240000, 0x005f280d, 0x00974a21, 0x00b24e18, 0x00b64c10, 0x00b45318, 0x00a24f1c, 0x007a3c18, 0x00340b00, 0x00130000, 0x00230200, 0x007a3f21, 0x00a15224, 0x00af5019, 0x00b14b12, 0x00b65019, 0x00b24e18, 0x00af4d18, 0x00b25118, 0x00b34e11, 0x00b44e0f, 0x00b44f11, 0x00b44f12, 0x00b34e13, 0x00b54c13, 0x00ba4c12, 0x00b94c10, 0x00b44d0c, 0x00b1581b, 0x00954e21, 0x004b1c00, 0x00140500, 0x00080000, 0x002a0b00, 0x006c341c, 0x00a65025, 0x00b24f17, 0x00b05111, 0x00b45210, 0x00b85010, 0x00c1500f, 0x00cc550a, 0x00c85205, 0x00c45810, 0x00b05c24, 0x004f2208, 0x001a0801, 0x00050000, 0x00000003, 0x005d5957, 0x00b5b1ae, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x001b1b1c, 0x000c0c0c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000c0c0c, 0x007b7676, 0x00070000, 0x00130000, 0x00481800, 0x009b5323, 0x00bc5815, 0x00c0540f, 0x00b15120, 0x009e4825, 0x00783014, 0x00531200, 0x00501300, 0x00702d12, 0x00934724, 0x008d4421, 0x00541f04, 0x00440e00, 0x0093481c, 0x00b45923, 0x00ba581b, 0x00a44f17, 0x00481300, 0x005b2707, 0x00944115, 0x00b04c1b, 0x00b24b1c, 0x00b0481a, 0x00b04d1a, 0x00ac4911, 0x00b54c0e, 0x00b44c0c, 0x00b04b12, 0x00a44f20, 0x00884b2e, 0x003a0100, 0x00803514, 0x00a24a21, 0x00ae4c1a, 0x00af4b15, 0x00ae4d16, 0x00b04c17, 0x00b54715, 0x00b94918, 0x00b44b18, 0x00b04c18, 0x00a94919, 0x00983e11, 0x00732300, 0x009e4d24, 0x00aa4b1e, 0x00b14c1d, 0x00ae491a, 0x00b04c1b, 0x00b04a16, 0x00a55428, 0x005c3419, 0x001e0c00, 0x000d0000, 0x00240500, 0x005f240b, 0x00984b27, 0x00a75126, 0x00a8491b, 0x00b34c1d, 0x00b64b18, 0x00b44b11, 0x00b2480d, 0x00b44a10, 0x00b44912, 0x00b34a12, 0x00b04b14, 0x00ae4c16, 0x00ad4c16, 0x00ae4c15, 0x00ae4c15, 0x00ac4c18, 0x00a64f20, 0x008c431f, 0x00642406, 0x00541100, 0x009b4e2c, 0x00ad491b, 0x00b64810, 0x00b6490c, 0x00b34e13, 0x00a64e1c, 0x00933d10, 0x00a4461b, 0x00b14d1f, 0x00b34814, 0x00b54a11, 0x00b04a11, 0x00b04c10, 0x00b6480f, 0x00bb480c, 0x00c64c0d, 0x00cc5310, 0x00c1560f, 0x00a8561c, 0x0051240c, 0x000f0000, 0x00060101, 0x00020202, 0x00060000, 0x000d0000, 0x002c1000, 0x005f3013, 0x00934c1f, 0x00a74c13, 0x00bc4e0e, 0x00bf4b0c, 0x00b64810, 0x00b44912, 0x00b74a0f, 0x00b64d0f, 0x00b05011, 0x00a6501a, 0x009b512c, 0x00682c17, 0x00300b04, 0x001d0000, 0x002c0300, 0x00682d13, 0x00a24e22, 0x00a8450f, 0x00b54f13, 0x00ac4e14, 0x009f5020, 0x006d3213, 0x002c0902, 0x00140000, 0x003c1805, 0x00844928, 0x00ae5424, 0x00b2480f, 0x00b34b0e, 0x00af4a0d, 0x00ac4b10, 0x00b35018, 0x00b64a14, 0x00b94a14, 0x00b94c14, 0x00b74c10, 0x00b64d0c, 0x00b64e0b, 0x00b84c0d, 0x00b84d11, 0x00b14b0f, 0x00a75423, 0x00642f15, 0x00210400, 0x00100000, 0x001a0300, 0x0055240e, 0x00904824, 0x00ad5220, 0x00b14e13, 0x00b2500e, 0x00b3500b, 0x00b8500d, 0x00c4550e, 0x00c95304, 0x00c65407, 0x00be5c1a, 0x008c4517, 0x002c0b00, 0x000c0303, 0x00000003, 0x001d1c20, 0x008b8784, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00181818, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00aca9aa, 0x000c0708, 0x00100000, 0x001c0000, 0x00844821, 0x00b85612, 0x00c75407, 0x00be4d0d, 0x00b34c18, 0x00a44e28, 0x00904627, 0x0067240b, 0x00571400, 0x00702402, 0x008f4826, 0x00743d23, 0x00340100, 0x0070300c, 0x00ad5b2c, 0x00bc581a, 0x00ba5c1f, 0x005e2000, 0x00531a00, 0x008c4015, 0x00aa4e20, 0x00b04a1e, 0x00b1481c, 0x00af4c1c, 0x00aa4611, 0x00b54c10, 0x00b44c0d, 0x00ae4b11, 0x00a64e1f, 0x00964f2d, 0x004d0700, 0x0094401a, 0x00a6491c, 0x00b04d1a, 0x00ae4b13, 0x00af4e15, 0x00b04c16, 0x00b34616, 0x00b94a1b, 0x00b24714, 0x00b34c1a, 0x00ac4a1b, 0x00983c0f, 0x00792600, 0x00ab5528, 0x00ab4818, 0x00b04818, 0x00b0481a, 0x00b04b1c, 0x00ad4818, 0x00a4542a, 0x00522a10, 0x001c0500, 0x001f0400, 0x00471c07, 0x008c411e, 0x00a94e1e, 0x00ac4b17, 0x00b44d19, 0x00b44918, 0x00af4411, 0x00b44e17, 0x00b04b12, 0x00b34915, 0x00b44915, 0x00b14a15, 0x00b04b15, 0x00ae4c16, 0x00ad4c16, 0x00ae4c14, 0x00ae4c12, 0x00af4e15, 0x00ab501d, 0x0094471e, 0x0078300c, 0x00611600, 0x00a44f2c, 0x00b14a1c, 0x00b54810, 0x00b34a0c, 0x00b04c11, 0x00a64b1b, 0x00a4481d, 0x00aa491c, 0x00b14b1a, 0x00b0470f, 0x00b34b0f, 0x00ae4b11, 0x00b24c10, 0x00b94809, 0x00c04805, 0x00ca4e06, 0x00ca560d, 0x00b75712, 0x00995320, 0x00260200, 0x000c0000, 0x00010004, 0x00000104, 0x00010101, 0x00040000, 0x000b0000, 0x00290b00, 0x0066300e, 0x009d5221, 0x00b04d15, 0x00b1470b, 0x00ba5018, 0x00b74c17, 0x00b7480f, 0x00b84b0e, 0x00b24b0a, 0x00b05014, 0x00a8501f, 0x009a512e, 0x00703c28, 0x00360c00, 0x00250000, 0x00400e00, 0x007c3818, 0x00a75325, 0x00ac4a12, 0x00b14e13, 0x00ab501a, 0x00954c23, 0x00602c1b, 0x00200000, 0x001e0000, 0x005d3119, 0x009c4a23, 0x00b14d18, 0x00b34c10, 0x00b34f0f, 0x00b25013, 0x00b04b12, 0x00b84817, 0x00bc4818, 0x00bb4914, 0x00b94b10, 0x00b74d09, 0x00b64e08, 0x00b64d0f, 0x00b44e15, 0x00ab4f1c, 0x00904825, 0x00351003, 0x00120000, 0x00160000, 0x003a1200, 0x00803e1c, 0x00a75325, 0x00ac4f19, 0x00b25012, 0x00b7520e, 0x00b44d04, 0x00bc530a, 0x00c7590e, 0x00c55204, 0x00c45811, 0x00ae5a24, 0x00602a06, 0x001b0400, 0x00020001, 0x00000003, 0x00474748, 0x00a9a6a5, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x001c1c1c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009c9b9d, 0x00504c50, 0x00050000, 0x00100200, 0x00481d00, 0x00b05317, 0x00cc560a, 0x00c75008, 0x00b84a0a, 0x00b04d1e, 0x00a64e27, 0x00a5502b, 0x0093421d, 0x00732600, 0x00692603, 0x007a432a, 0x004a1600, 0x00430800, 0x00a2572d, 0x00b45214, 0x00bb581a, 0x008f4412, 0x00510f00, 0x00853913, 0x00a65028, 0x00ac461c, 0x00b2491c, 0x00ac481c, 0x00ae4b19, 0x00b44a0f, 0x00b44b0f, 0x00ae4813, 0x00ac4f20, 0x0099451f, 0x006c1b00, 0x00a5491e, 0x00ac4919, 0x00af4b15, 0x00ae4b11, 0x00aa4c10, 0x00ad4b14, 0x00b44818, 0x00b54818, 0x00b34916, 0x00b04a16, 0x00a44111, 0x0096390a, 0x00984112, 0x00a74d1b, 0x00b24c19, 0x00b24814, 0x00b54a18, 0x00af4717, 0x00ab4a1c, 0x00a1542e, 0x00481c00, 0x00200000, 0x00431600, 0x007a3c1b, 0x00a34c1f, 0x00b04c18, 0x00b24c17, 0x00b44914, 0x00b64713, 0x00b74816, 0x00b04d18, 0x00ad4c18, 0x00b3481b, 0x00b34519, 0x00b24618, 0x00b24818, 0x00b04a18, 0x00b14c16, 0x00b14b10, 0x00b04b0d, 0x00b0490d, 0x00af4e17, 0x00a34c1c, 0x008e3d12, 0x00752400, 0x00a85026, 0x00ac4813, 0x00b44a0f, 0x00b54d10, 0x00b24c14, 0x00ad4a1f, 0x00ad4a21, 0x00b0491c, 0x00b14a16, 0x00b14b12, 0x00af4c10, 0x00ae4d16, 0x00ae4810, 0x00be4f0c, 0x00c34f06, 0x00c85407, 0x00bc550c, 0x00a8581c, 0x00622a00, 0x001d0000, 0x00080000, 0x00000003, 0x00000308, 0x00000004, 0x00040001, 0x00080000, 0x00100000, 0x002b0b00, 0x00653411, 0x00985022, 0x00aa501c, 0x00b04c17, 0x00b54914, 0x00b54811, 0x00b7480f, 0x00b64c0c, 0x00b34d10, 0x00ab4c14, 0x00a85020, 0x00a3532c, 0x007e391d, 0x00471102, 0x00280000, 0x00501d09, 0x00844627, 0x00a85323, 0x00ae4d16, 0x00b04e18, 0x00a34818, 0x009d542e, 0x005b2409, 0x001e0000, 0x00280300, 0x00864326, 0x00a54d24, 0x00a84710, 0x00bc5818, 0x00ab480a, 0x00b54f14, 0x00bc4c1a, 0x00b74413, 0x00bc4913, 0x00bb4c10, 0x00b8510f, 0x00ad4906, 0x00b34e13, 0x00ac501f, 0x00a05532, 0x00511c08, 0x001c0100, 0x00100000, 0x002f0700, 0x00703415, 0x00a24e22, 0x00ac4f19, 0x00af5019, 0x00b35014, 0x00b44c08, 0x00bd5206, 0x00c45808, 0x00c45506, 0x00c4550b, 0x00b65618, 0x00925127, 0x002c0600, 0x000c0000, 0x00050203, 0x000b090a, 0x00838182, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00908f91, 0x00030000, 0x00030000, 0x00240700, 0x00934817, 0x00ba5312, 0x00cc5c15, 0x00bb4c08, 0x00b7501b, 0x00a94718, 0x00a84719, 0x00a84d20, 0x00a04c20, 0x00964c25, 0x00814022, 0x006f331a, 0x00370000, 0x00722f0a, 0x00bb6028, 0x00b65416, 0x00ac5822, 0x00601400, 0x0082350f, 0x009f4b25, 0x00b14c21, 0x00ac4416, 0x00ac491e, 0x00ac4a1a, 0x00b2480f, 0x00b54a10, 0x00b04814, 0x00af4c1d, 0x00a44a1d, 0x00882e01, 0x00aa4818, 0x00ae4a17, 0x00b24c17, 0x00b04d15, 0x00ac4d12, 0x00ac4b12, 0x00af4715, 0x00b04617, 0x00b14a16, 0x00b04c17, 0x00a84515, 0x009f4010, 0x00a24714, 0x00ac4e18, 0x00b34c17, 0x00b44813, 0x00b54811, 0x00b14814, 0x00ad4e21, 0x008e411b, 0x00420c00, 0x00411000, 0x00783914, 0x009b4d23, 0x00ab4c1c, 0x00b04a16, 0x00b04915, 0x00b14814, 0x00b74510, 0x00b64713, 0x00ad4a17, 0x00aa4a18, 0x00b34c1d, 0x00b44a1d, 0x00b34a1d, 0x00b1491b, 0x00b04918, 0x00b04914, 0x00b1490d, 0x00b2480c, 0x00b44b0f, 0x00ac460d, 0x00ac4d1c, 0x00a44c1f, 0x00984015, 0x00ae5427, 0x00ab4915, 0x00ae4b11, 0x00aa480e, 0x00a94814, 0x00aa4620, 0x00ac4824, 0x00ae481e, 0x00af4a19, 0x00ab4c15, 0x00a84c16, 0x00a74c1c, 0x00ac4d1c, 0x00b34b0e, 0x00c05511, 0x00c05910, 0x00b45b19, 0x00925020, 0x00330400, 0x00200000, 0x00180000, 0x00050000, 0x00000003, 0x00040006, 0x00090108, 0x00060001, 0x00080000, 0x000e0000, 0x00280c00, 0x0063320f, 0x00985228, 0x00ac5124, 0x00b24c1b, 0x00b84e1a, 0x00b84c12, 0x00b84b0e, 0x00b64d0d, 0x00b45116, 0x00ae4d14, 0x00ab4915, 0x00a64e24, 0x00843c23, 0x004e1504, 0x002c0000, 0x005d2a14, 0x00964c24, 0x00a74c1a, 0x00b34f19, 0x00b14d18, 0x00a44b18, 0x009a522a, 0x0054240c, 0x002c0200, 0x004b1000, 0x008e4423, 0x00af5422, 0x00ac480d, 0x00ac470a, 0x00b75016, 0x00b44a16, 0x00b84a16, 0x00bc4c13, 0x00b4490d, 0x00b04d10, 0x00b5571d, 0x00a84713, 0x00a8532b, 0x00753c26, 0x00280200, 0x00110000, 0x00230500, 0x005b2308, 0x00984b22, 0x00ae501c, 0x00b14e14, 0x00b25118, 0x00b04e10, 0x00bb4e08, 0x00be4e00, 0x00c45503, 0x00c55809, 0x00ba5310, 0x00b3602f, 0x00502002, 0x00150000, 0x000c0200, 0x00030000, 0x00484442, 0x00a6a5a2, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00343334, 0x00040000, 0x000d0000, 0x00542408, 0x009f5428, 0x00b4561b, 0x00b85010, 0x00b85018, 0x00b04a14, 0x00b34f1c, 0x00ab4917, 0x00b05422, 0x00a34c1b, 0x009d481f, 0x00954c29, 0x004d1400, 0x003d0200, 0x00a35323, 0x00af541b, 0x00bb6027, 0x00862c00, 0x0087330c, 0x009a441f, 0x00b04c1d, 0x00ae4614, 0x00aa4c1b, 0x00ab4b1a, 0x00b24810, 0x00b74913, 0x00b34918, 0x00ae491a, 0x00ac4c1c, 0x00a44411, 0x00ae4a17, 0x00b04a16, 0x00b04a16, 0x00ae4c15, 0x00ac4c13, 0x00ac4b14, 0x00ae4918, 0x00b14b1a, 0x00b04915, 0x00b04c17, 0x00ac4818, 0x00a94717, 0x00ab4c17, 0x00af4e17, 0x00b14a14, 0x00b34811, 0x00b5460f, 0x00b24812, 0x00aa4b1c, 0x0086330a, 0x00601c00, 0x00783610, 0x00a05124, 0x00a94f1f, 0x00ac4c1b, 0x00ac4919, 0x00a94919, 0x00ae4918, 0x00b64814, 0x00b74812, 0x00b04b15, 0x00ad4c16, 0x00a94a15, 0x00aa4a18, 0x00aa4a19, 0x00ac4919, 0x00ac4918, 0x00b04a14, 0x00b44b11, 0x00b64c11, 0x00b84d14, 0x00ac430f, 0x00ac481a, 0x00ab4b21, 0x00a54a22, 0x00a64b21, 0x00a74c1c, 0x00a84d18, 0x00a9501b, 0x00a94f20, 0x00a84c29, 0x00a94b2c, 0x00aa4c25, 0x00a84d20, 0x00a34e20, 0x009f4e21, 0x00a04f2a, 0x00a4532c, 0x00b15728, 0x00b55b24, 0x00b66025, 0x00a15825, 0x00582102, 0x002d0000, 0x0077412a, 0x004b1e0a, 0x001d0800, 0x00080000, 0x00050000, 0x00040004, 0x00080008, 0x00050005, 0x00020000, 0x00080000, 0x002d1000, 0x00663419, 0x00984e2d, 0x00ab5028, 0x00ac4a16, 0x00b0490d, 0x00b84b0e, 0x00b14708, 0x00b04c11, 0x00af4d11, 0x00b0470c, 0x00b6501c, 0x00a94e26, 0x0082381b, 0x00471400, 0x00421200, 0x00773817, 0x00a45328, 0x00b04c17, 0x00b44b11, 0x00aa470f, 0x00ad5524, 0x00924c28, 0x005b2006, 0x00350000, 0x0062230a, 0x009b461e, 0x00ac4b17, 0x00b55018, 0x00ae4810, 0x00af4c14, 0x00b14e13, 0x00b64d0d, 0x00b24c0f, 0x00a64a18, 0x00ab5225, 0x00a54a20, 0x009a4f30, 0x003c1308, 0x00140000, 0x00180000, 0x0058290c, 0x00914921, 0x00a84f1c, 0x00b14f17, 0x00b44d11, 0x00ae4b10, 0x00bc5415, 0x00bd4c06, 0x00c85306, 0x00c75602, 0x00be560b, 0x00b35723, 0x00823e1d, 0x00200000, 0x000c0000, 0x00070000, 0x00150f0c, 0x00888280, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008a8a8c, 0x00080809, 0x00070000, 0x001f0300, 0x00734021, 0x009e4f20, 0x00ac4f18, 0x00a84610, 0x00b5541e, 0x00ae4c18, 0x00ab4914, 0x00b04e18, 0x00a74813, 0x00b05421, 0x009c4c22, 0x0074341c, 0x00360000, 0x006a2400, 0x00aa5825, 0x00b55a21, 0x00a84812, 0x00872e04, 0x009e4319, 0x00b14a16, 0x00b44c14, 0x00a94c16, 0x00ab4d18, 0x00b24913, 0x00b64814, 0x00b34718, 0x00b04819, 0x00af4b18, 0x00b04e18, 0x00b04a16, 0x00af4814, 0x00ac4815, 0x00ac4a14, 0x00ac4c13, 0x00ac4c14, 0x00ac4a1a, 0x00ae4b1b, 0x00ac4916, 0x00ae4a17, 0x00ad4819, 0x00ae491a, 0x00b04c18, 0x00af4c14, 0x00ae4811, 0x00b24911, 0x00b44810, 0x00b44b14, 0x00ab4917, 0x008f3609, 0x00924218, 0x00a15025, 0x00a84e1c, 0x00a94917, 0x00ad4c19, 0x00ac491a, 0x00a84b1d, 0x00ac4c1c, 0x00b44a16, 0x00b44811, 0x00b04814, 0x00ad4b14, 0x00ad4c14, 0x00ac4e16, 0x00ac4d1a, 0x00ac4d1c, 0x00ac4c1b, 0x00ab4b18, 0x00ab4915, 0x00a94814, 0x00ae4c1c, 0x00a94a1d, 0x00a84c27, 0x00a34c29, 0x009e4d2c, 0x009a4c2a, 0x009f532c, 0x00985328, 0x008c4b23, 0x00884724, 0x00833d25, 0x007d3520, 0x00783015, 0x00702e0e, 0x00692c0a, 0x00652a0b, 0x00622711, 0x00672b14, 0x00743417, 0x00763813, 0x007a3d15, 0x006c3714, 0x002f0100, 0x004b1a0b, 0x00965437, 0x008b4c2c, 0x00582a12, 0x00240800, 0x00100000, 0x00080000, 0x00030003, 0x00010004, 0x00000001, 0x00080100, 0x000e0000, 0x002c0900, 0x006a321d, 0x0098502f, 0x00a65224, 0x00ab4c14, 0x00b64c10, 0x00b44a0e, 0x00ae4b11, 0x00b24f15, 0x00b84c12, 0x00b44810, 0x00af4715, 0x00a85025, 0x007b3c1e, 0x00471200, 0x00511600, 0x00914822, 0x00ad4d1c, 0x00b34811, 0x00b54f16, 0x00a94814, 0x00a85024, 0x009a502d, 0x0062260d, 0x00450900, 0x00782a06, 0x00a44c20, 0x00ac4c1b, 0x00b14f18, 0x00ac4e13, 0x00ad4d0f, 0x00b14c0c, 0x00b44f14, 0x00a94c1f, 0x00a14b25, 0x00a5502f, 0x006a280e, 0x001e0000, 0x001d0000, 0x00572a0c, 0x0084471d, 0x00a65322, 0x00b3511c, 0x00a94308, 0x00b85014, 0x00b1490c, 0x00be5413, 0x00c35008, 0x00ca580b, 0x00c05407, 0x00b85817, 0x009a4d27, 0x003f0c00, 0x000f0000, 0x00060200, 0x00040000, 0x00514c47, 0x00aeaaa7, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0034373b, 0x00080404, 0x000d0000, 0x003a1701, 0x008c4b28, 0x0096461c, 0x0088380c, 0x00903e10, 0x00a24c1a, 0x00b15523, 0x00ac4815, 0x00b04d18, 0x00a94c16, 0x00a14c1e, 0x00924829, 0x005f1c01, 0x003d0000, 0x0089441c, 0x00b05a26, 0x00b65820, 0x008d2f00, 0x00a74412, 0x00bc4f14, 0x00b64c0e, 0x00ab4a10, 0x00ac4d15, 0x00b14a14, 0x00b14713, 0x00b2481a, 0x00b04819, 0x00ac4815, 0x00b04c17, 0x00ae4814, 0x00ac4614, 0x00ab4617, 0x00ad4a18, 0x00ae4c17, 0x00ab4c15, 0x00a84918, 0x00a64718, 0x00ac4a16, 0x00ad4a17, 0x00af481a, 0x00b0481a, 0x00b14a16, 0x00af4811, 0x00ad4812, 0x00af4b15, 0x00b04b15, 0x00b04b15, 0x00b04c17, 0x00a3410f, 0x00aa4e20, 0x00a94d21, 0x00a64615, 0x00ad4c19, 0x00af4c1a, 0x00ad4b1b, 0x00aa4b1e, 0x00aa4b1c, 0x00ad4916, 0x00ae4813, 0x00ae4814, 0x00af4912, 0x00b44e12, 0x00b04c10, 0x00ac4914, 0x00aa4a1a, 0x00a84c1f, 0x00a85024, 0x00a45125, 0x00a15129, 0x00984c28, 0x00944b2c, 0x00854028, 0x00793924, 0x00652c18, 0x0054210b, 0x00481b00, 0x00371200, 0x002b1000, 0x00270e00, 0x00260900, 0x00240600, 0x00220400, 0x00200400, 0x001d0400, 0x001d0400, 0x001c0100, 0x001c0200, 0x001c0200, 0x00240b00, 0x00200600, 0x00220500, 0x00200000, 0x004f1e0f, 0x00964d29, 0x009f4e23, 0x00994d2a, 0x00703418, 0x00320f00, 0x000f0000, 0x00040200, 0x00000000, 0x000a0004, 0x000b0000, 0x000c0000, 0x00100000, 0x002b0d00, 0x0064381d, 0x0097542c, 0x00a7501f, 0x00ae4b13, 0x00b54c13, 0x00b04d17, 0x00ad4b15, 0x00b04b15, 0x00b14812, 0x00b4470f, 0x00b04d1a, 0x00994921, 0x00733010, 0x004a0d00, 0x00682403, 0x00a54c20, 0x00b04d1a, 0x00b04c19, 0x00af4b18, 0x00b34c1d, 0x00a4471c, 0x00994d27, 0x0072300c, 0x00571400, 0x0079300a, 0x00a24c20, 0x00ae501c, 0x00ac4b12, 0x00b04d12, 0x00b04910, 0x00b14b17, 0x00b14d22, 0x00a54c27, 0x00874020, 0x00370000, 0x002c0000, 0x005e2f17, 0x00894820, 0x00a1521e, 0x00ab4f19, 0x00ae4b13, 0x00b84f15, 0x00b5480c, 0x00c05010, 0x00ba4a04, 0x00c8590f, 0x00c2580f, 0x00b55613, 0x00a25623, 0x005f280f, 0x001a0000, 0x000b0000, 0x00000000, 0x0024201d, 0x0095918e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008c8f91, 0x00131313, 0x00080100, 0x00180000, 0x00602c12, 0x008c4928, 0x0089441f, 0x006c2400, 0x0080340b, 0x0096451a, 0x00a34a1d, 0x00ac4f20, 0x00a74815, 0x00aa4f1f, 0x00a44f28, 0x00883f20, 0x003e0400, 0x00501400, 0x009e5121, 0x00b85d25, 0x00a9470f, 0x00af450a, 0x00c2500f, 0x00bc4d09, 0x00af4b0b, 0x00ac4c0f, 0x00ae4b13, 0x00ad4713, 0x00af4819, 0x00b0491c, 0x00ab4714, 0x00ac4814, 0x00af4b18, 0x00ac4718, 0x00a84418, 0x00aa4618, 0x00ab4915, 0x00a94917, 0x00a84c1f, 0x00ab4f21, 0x00aa4c18, 0x00ad4a18, 0x00ae471b, 0x00b1471a, 0x00b44915, 0x00b04811, 0x00ac4814, 0x00af4d19, 0x00ac4b17, 0x00a84610, 0x00b14e16, 0x00af4914, 0x00ad4819, 0x00aa4619, 0x00af4a1b, 0x00ad4818, 0x00ae4918, 0x00ad4a18, 0x00ac491a, 0x00ab4819, 0x00ab4915, 0x00ad4c16, 0x00ae4c1a, 0x00ae4c1a, 0x00a84814, 0x00a74b17, 0x00a64d21, 0x00a25029, 0x00984e2b, 0x00874423, 0x00723616, 0x00632b0e, 0x00531f05, 0x004b1802, 0x003b0700, 0x00380600, 0x002f0000, 0x00290000, 0x00200000, 0x001a0000, 0x00120000, 0x00100000, 0x00130000, 0x00130000, 0x00100000, 0x000f0000, 0x000d0000, 0x000c0000, 0x000c0000, 0x00080000, 0x00040000, 0x00050100, 0x00090000, 0x00110000, 0x002b0400, 0x00723923, 0x00a45428, 0x00ac501e, 0x00ab4a1e, 0x009f4924, 0x00783e1e, 0x003a1900, 0x000d0100, 0x00090300, 0x000b0000, 0x000b0003, 0x000a0004, 0x000a0000, 0x000d0000, 0x002d1100, 0x00683317, 0x0099502a, 0x00a94e1c, 0x00ac4a14, 0x00af4c18, 0x00ae4b18, 0x00ac4612, 0x00b34a14, 0x00b84c10, 0x00ae450d, 0x00a84d1f, 0x00974925, 0x0066260a, 0x00501000, 0x00853812, 0x00a85024, 0x00ab4818, 0x00b24a18, 0x00b14614, 0x00b04a18, 0x00a84d1d, 0x0097491d, 0x007b3511, 0x006b2503, 0x0083320d, 0x00a2491d, 0x00ab4c17, 0x00b04d15, 0x00b04812, 0x00b14a16, 0x00ae491b, 0x0099411a, 0x00601d00, 0x00460c00, 0x00723415, 0x008b4420, 0x00a75425, 0x00a64c15, 0x00ac4c14, 0x00b75016, 0x00b4470d, 0x00bd4c0d, 0x00c8530f, 0x00c35007, 0x00c3580a, 0x00bd5e16, 0x00a85a21, 0x006d340d, 0x00260400, 0x000e0000, 0x00030000, 0x00080808, 0x006c6866, 0x00565554, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x004f4e4c, 0x00100a08, 0x00100000, 0x00300800, 0x00743e1f, 0x0095542e, 0x007d3814, 0x00591800, 0x00602102, 0x00844121, 0x00984c27, 0x00ab4f23, 0x00a84617, 0x00ab4a1c, 0x009c4a24, 0x00612914, 0x00340300, 0x00702e03, 0x00a5541a, 0x00bb5818, 0x00bc4c08, 0x00c75008, 0x00c8510b, 0x00ba4e0c, 0x00ac4a0a, 0x00ac4c11, 0x00a84913, 0x00ac4919, 0x00ae4a1c, 0x00ab4617, 0x00ad4818, 0x00b04b1a, 0x00ac481a, 0x00aa451c, 0x00a74418, 0x00a44210, 0x00a04210, 0x00a1471a, 0x00a84d20, 0x00a84c19, 0x00ac4b18, 0x00af461c, 0x00b1441b, 0x00b64816, 0x00b24812, 0x00ac4914, 0x00ac4d1a, 0x00a84c19, 0x00a64813, 0x00ab4a13, 0x00b04a14, 0x00b2481a, 0x00b04619, 0x00b44c1d, 0x00ac4514, 0x00ae4815, 0x00b04917, 0x00b04816, 0x00ad4713, 0x00ac4a14, 0x00ac4f19, 0x00a64c1f, 0x009b461e, 0x00a0542d, 0x008f4927, 0x0077381d, 0x005f2712, 0x00481c09, 0x00381300, 0x002b0c00, 0x00230900, 0x001c0000, 0x001c0000, 0x001e0000, 0x00280000, 0x00300000, 0x003a0c00, 0x003e1300, 0x00481e05, 0x0054240c, 0x00532209, 0x004f1e05, 0x00471901, 0x003c1300, 0x00300b00, 0x00270300, 0x00200000, 0x001a0000, 0x000f0000, 0x000b0500, 0x00020000, 0x00070000, 0x001c0200, 0x004f1800, 0x00a15832, 0x00a4501c, 0x00a84810, 0x00b04514, 0x00af491d, 0x009d4c21, 0x007f451d, 0x004c2b0c, 0x001e0a00, 0x000d0000, 0x00070006, 0x00030004, 0x00040000, 0x000c0400, 0x00130000, 0x00361000, 0x00703821, 0x009c4c24, 0x00a84c1b, 0x00ae4e1e, 0x00b24d1c, 0x00b44c15, 0x00b54c12, 0x00b54c10, 0x00b04b12, 0x00ab4c1c, 0x009d4923, 0x00833f21, 0x005b1e04, 0x005c1d00, 0x00924824, 0x00af4e20, 0x00b24814, 0x00b04c17, 0x00ae4c15, 0x00aa4810, 0x00ac4e1b, 0x009e4a24, 0x00853816, 0x00823215, 0x008b3614, 0x00a4481c, 0x00ac4916, 0x00b34a12, 0x00b14a14, 0x00a94815, 0x008e380d, 0x00662201, 0x007f3c18, 0x00a64f21, 0x00b04f1b, 0x00a84614, 0x00ae4c18, 0x00b3501a, 0x00af480e, 0x00bb4b0f, 0x00c54e0e, 0x00ca4f07, 0x00cc580c, 0x00b95304, 0x00ad5a14, 0x007e4113, 0x00300b00, 0x000c0000, 0x00030000, 0x00010000, 0x00444442, 0x00a4a3a1, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a5a5a4, 0x002c2829, 0x000d0000, 0x00180000, 0x003e1500, 0x007c4224, 0x00945536, 0x006a2f11, 0x00491300, 0x004b1700, 0x00703519, 0x00994c2a, 0x00a44921, 0x00ae4d20, 0x00a04b21, 0x00884b33, 0x004d1901, 0x00470c00, 0x00843c0c, 0x00ab5116, 0x00c15916, 0x00c7530a, 0x00ca540a, 0x00c3540d, 0x00b14a07, 0x00ac4c0e, 0x00a94c12, 0x00aa4b16, 0x00ac4a1a, 0x00ab4617, 0x00b04b1c, 0x00ac4817, 0x00ad4819, 0x00ae4a1f, 0x00aa471c, 0x009f3e10, 0x00933709, 0x008d3710, 0x00903c15, 0x00a04c20, 0x00a44c22, 0x00a74825, 0x00ab4722, 0x00b0491d, 0x00ae4918, 0x00a94918, 0x00a84c1b, 0x00a64b1b, 0x00ad5220, 0x00a74813, 0x00ab4714, 0x00b54b1e, 0x00ae4417, 0x00ad4618, 0x00af4b1c, 0x00aa4818, 0x00ab4b1b, 0x00aa491c, 0x00a5491c, 0x00a24d1f, 0x009c4e24, 0x008c4423, 0x0077381c, 0x00582108, 0x00491904, 0x00380c00, 0x00270100, 0x001c0000, 0x001a0000, 0x001b0000, 0x00200400, 0x00341203, 0x00471e0d, 0x00602c1c, 0x0069301e, 0x00743621, 0x007c3c24, 0x007c4024, 0x00834728, 0x00894526, 0x008b4422, 0x0089441f, 0x0086441c, 0x0082421b, 0x007d3f1a, 0x00793c1a, 0x00743a1c, 0x0064351d, 0x00523120, 0x002f241b, 0x000a0800, 0x00080000, 0x00280c00, 0x00824627, 0x00ac5b2e, 0x00ac5119, 0x00b45017, 0x00b74814, 0x00b34614, 0x00ac4c1c, 0x009e4e1f, 0x007d431a, 0x00603518, 0x00331309, 0x00170000, 0x00080000, 0x000a0300, 0x00060000, 0x00080000, 0x00150200, 0x002e0c00, 0x00753a1c, 0x009d5028, 0x00a84d22, 0x00a74414, 0x00b54c18, 0x00b44a13, 0x00ac450c, 0x00b25019, 0x00ac4b18, 0x00a64d21, 0x00994c2c, 0x0076341a, 0x00490d00, 0x00773417, 0x00a44c21, 0x00ac4817, 0x00ad4c16, 0x00ac4a12, 0x00b24c11, 0x00ae4813, 0x00a84b20, 0x00a14b26, 0x00903c1c, 0x00893412, 0x00993c11, 0x00aa4516, 0x00b54c18, 0x00b04814, 0x00ad4b1b, 0x00984014, 0x0092451f, 0x00a05026, 0x00ab4712, 0x00b54a11, 0x00b04a16, 0x00ad4916, 0x00b04c13, 0x00b74e10, 0x00c04e0f, 0x00ca520e, 0x00ca5309, 0x00c3540c, 0x00b25814, 0x008b4810, 0x00421800, 0x00110000, 0x00080100, 0x00000305, 0x001f1f1f, 0x00969594, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00777777, 0x00241d1c, 0x000a0000, 0x001a0000, 0x004c200d, 0x00844d31, 0x008d5332, 0x0065300e, 0x00330800, 0x003d1200, 0x005e2815, 0x0086422b, 0x00a04e28, 0x00a14c23, 0x009c4f2b, 0x00833f20, 0x00440900, 0x00501400, 0x0090481f, 0x00b05b24, 0x00b85009, 0x00c8580a, 0x00c35607, 0x00bb5308, 0x00b3500b, 0x00ae4d0e, 0x00ad4a10, 0x00ac4a14, 0x00ac4819, 0x00ac481a, 0x00b04816, 0x00ad4514, 0x00ac4718, 0x00ac4a1c, 0x00a74b20, 0x0098421b, 0x00823311, 0x00702709, 0x006c280a, 0x00773216, 0x008a4025, 0x00994b2f, 0x00a34d2c, 0x00a84c24, 0x00a84a1f, 0x00a8491c, 0x00a64a1f, 0x00a74b20, 0x00a94a1d, 0x00aa481a, 0x00ac481c, 0x00ad491e, 0x00ad4a1f, 0x00a84a20, 0x00a54c24, 0x00a04e28, 0x00984d2b, 0x00894829, 0x00743d21, 0x00592c14, 0x00401a08, 0x00301001, 0x001e0000, 0x001b0000, 0x00190000, 0x00200100, 0x00300d00, 0x00451c0c, 0x005c2c15, 0x006d3318, 0x00833c20, 0x008e3f1e, 0x009b4421, 0x00a44824, 0x00a44b24, 0x00a44c25, 0x00a14d27, 0x00a24e28, 0x00a44b27, 0x00a44a24, 0x00a44c1d, 0x00a64f19, 0x00aa5118, 0x00b2571c, 0x00b75820, 0x00ad5524, 0x009d542f, 0x00825035, 0x00352012, 0x00100900, 0x00080000, 0x00200500, 0x00743c20, 0x00a7592f, 0x00b3551e, 0x00b85014, 0x00b84c17, 0x00b74c19, 0x00ac4414, 0x00a84818, 0x00a85122, 0x0093461d, 0x007a3b1c, 0x00511e08, 0x00260400, 0x00110000, 0x00080000, 0x00000000, 0x00000100, 0x00050000, 0x00321404, 0x0070391f, 0x009c4d28, 0x00a94a1c, 0x00b24c19, 0x00b34c18, 0x00ab4814, 0x00ac4d17, 0x00a94811, 0x00ad511f, 0x00a04924, 0x00904228, 0x006a2513, 0x00510c00, 0x00914724, 0x00a04c20, 0x00a94b1a, 0x00ae4a15, 0x00b14c16, 0x00b04c17, 0x00ae4c1a, 0x00aa4c1b, 0x00a54619, 0x00a34218, 0x009f3b10, 0x00a94216, 0x00b2491e, 0x00b34a1f, 0x00ad481c, 0x00a94719, 0x00a84b1d, 0x00ad4f1e, 0x00ac4916, 0x00b14d18, 0x00ac4b17, 0x00ac4913, 0x00b55010, 0x00bf540e, 0x00c65208, 0x00c85508, 0x00c35610, 0x00b4581a, 0x008c4818, 0x004c1d00, 0x00180000, 0x00080000, 0x00060304, 0x000b0c0f, 0x007b7b7b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b2b2b2, 0x00545050, 0x001c1518, 0x000c0000, 0x00210400, 0x00512610, 0x00834c2a, 0x00915834, 0x0059290c, 0x002c0000, 0x002f0500, 0x0050200f, 0x0078381c, 0x009f5432, 0x00a0512c, 0x00914724, 0x00723216, 0x00420600, 0x005a1c00, 0x008e481e, 0x00b45e28, 0x00b95a1a, 0x00bf5c15, 0x00bd5710, 0x00b5500c, 0x00b04a09, 0x00ad480c, 0x00ac4813, 0x00ad4a18, 0x00ae491a, 0x00b04818, 0x00b34b1b, 0x00b14a1c, 0x00ab471a, 0x00a7491e, 0x00a24a23, 0x00904120, 0x007d3518, 0x00591900, 0x00541800, 0x00551804, 0x005f210b, 0x006c2b13, 0x00783317, 0x00853c1c, 0x00904321, 0x00934826, 0x00984b29, 0x009b4d2b, 0x009b4d2b, 0x009a4b29, 0x00984828, 0x00924423, 0x008c4022, 0x007f381c, 0x00733318, 0x00622913, 0x004e1c08, 0x003a1000, 0x00290500, 0x001c0000, 0x00180000, 0x00270500, 0x00351006, 0x00482114, 0x005d301e, 0x006f3b23, 0x007f4426, 0x00904b28, 0x009f4e29, 0x00a14820, 0x00a8471c, 0x00ac461a, 0x00ae4719, 0x00af4819, 0x00ac4919, 0x00ac4919, 0x00ac491c, 0x00af4a21, 0x00ac471b, 0x00ac4911, 0x00b04b0a, 0x00b84f06, 0x00c2560c, 0x00c55817, 0x00b85620, 0x00a0552c, 0x005d2b10, 0x00200b00, 0x00050000, 0x00070000, 0x00180300, 0x003b0e00, 0x007b3817, 0x00b45c28, 0x00bc581d, 0x00af4912, 0x00b04812, 0x00b84d19, 0x00b04713, 0x00ae4814, 0x00ac4e1c, 0x00a04c20, 0x008b4420, 0x00673017, 0x003c1505, 0x00180100, 0x00080000, 0x00020300, 0x00080501, 0x000e0000, 0x003b1505, 0x0078381e, 0x009b4824, 0x00a4471c, 0x00ab4818, 0x00ae4c18, 0x00ab4a13, 0x00b04d15, 0x00ab4915, 0x00a94920, 0x00a44a2a, 0x0087381f, 0x005e1700, 0x00642104, 0x00984f29, 0x00a64b20, 0x00ac481a, 0x00ab4816, 0x00a94613, 0x00ac4815, 0x00ae4b18, 0x00af4a19, 0x00ad4819, 0x00ac4718, 0x00ac471b, 0x00ad481c, 0x00b0481b, 0x00b04a19, 0x00b04915, 0x00b04913, 0x00b04a13, 0x00ae4a14, 0x00ac4911, 0x00b04b10, 0x00ba5312, 0x00c2550f, 0x00c15208, 0x00c25307, 0x00c45d14, 0x00b2581c, 0x00853e10, 0x00512104, 0x001b0000, 0x000b0000, 0x00030000, 0x000e0e10, 0x00606163, 0x009b9b9c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a69fa0, 0x00443d40, 0x00100707, 0x000a0000, 0x00240800, 0x00612e10, 0x0094532d, 0x00904f29, 0x005f2404, 0x00260000, 0x001e0000, 0x00411504, 0x00693420, 0x008f4d2f, 0x0099502c, 0x00944a27, 0x00692200, 0x00460800, 0x00581d03, 0x00703519, 0x0084421f, 0x00a1501e, 0x00b1541a, 0x00be5819, 0x00bf5616, 0x00b75014, 0x00b04b12, 0x00af4811, 0x00ad4612, 0x00ab4415, 0x00ac471b, 0x00ae4719, 0x00aa4517, 0x00ac4819, 0x00ad4e20, 0x00a64d21, 0x00984820, 0x0087401e, 0x00632609, 0x003f0b00, 0x00300100, 0x00300700, 0x00351004, 0x003d1b0e, 0x00482414, 0x004c2410, 0x00522710, 0x00552a15, 0x00562c19, 0x00552c1a, 0x00532918, 0x004e2415, 0x004a2013, 0x00401508, 0x00380c00, 0x002c0000, 0x00240000, 0x00250000, 0x00320400, 0x00441502, 0x0055200b, 0x006d2a15, 0x007e341b, 0x00904323, 0x009c4c24, 0x00a14d20, 0x00a44c1b, 0x00a64c1a, 0x00a84d1c, 0x00a94e1e, 0x00a94c1f, 0x00a74a1c, 0x00a8491c, 0x00ab4818, 0x00ac4916, 0x00ae4813, 0x00af4813, 0x00af4717, 0x00b04613, 0x00b64c0e, 0x00be520a, 0x00c75404, 0x00c85608, 0x00be5613, 0x00aa5420, 0x006c3418, 0x002c0d00, 0x000b0000, 0x00040100, 0x00050000, 0x000c0000, 0x00190000, 0x003b0e00, 0x0082390d, 0x00b0571e, 0x00ba5d20, 0x00b35213, 0x00b44c0e, 0x00b34b0e, 0x00b14812, 0x00ac4716, 0x00a94c1f, 0x00a24c23, 0x00944926, 0x007b3c1d, 0x0059270e, 0x00350f00, 0x001c0000, 0x00110000, 0x00120000, 0x00140000, 0x003f1108, 0x00773827, 0x009b4a28, 0x00aa4d1e, 0x00b04f14, 0x00ae490c, 0x00b04b12, 0x00ad4714, 0x00b0481b, 0x00af4c22, 0x00a1461e, 0x00843612, 0x00571500, 0x00722f11, 0x009f4824, 0x00ab4b21, 0x00af4e22, 0x00ad4b1d, 0x00ac4919, 0x00ae491a, 0x00ae4b19, 0x00ac4918, 0x00ae4c1a, 0x00aa4a18, 0x00a84913, 0x00aa4910, 0x00ae4b10, 0x00b04c0c, 0x00b24b08, 0x00b04907, 0x00b24c10, 0x00b2490b, 0x00bc4b04, 0x00c65004, 0x00cb5404, 0x00c85708, 0x00bc5713, 0x00ab551d, 0x0088481f, 0x004c1f04, 0x001f0100, 0x000e0000, 0x00090100, 0x000e0c0f, 0x004c4c50, 0x00acadaf, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008b8888, 0x00322e2c, 0x00100b04, 0x000d0000, 0x002c0700, 0x005f280c, 0x00955130, 0x0093522e, 0x00512202, 0x00240000, 0x00200100, 0x002d0800, 0x0065301c, 0x00904f31, 0x009b4d29, 0x00924621, 0x00602004, 0x00380300, 0x002c0300, 0x003e1504, 0x005c2509, 0x0075330b, 0x00944213, 0x00a64c18, 0x00ac511c, 0x00ae501c, 0x00ae4c16, 0x00ac4814, 0x00af4a1c, 0x00ac471b, 0x00ae4719, 0x00b0481a, 0x00b04917, 0x00ad4818, 0x00a94918, 0x00a44c1d, 0x00a05026, 0x008b4521, 0x00703417, 0x00502109, 0x00300c00, 0x00190000, 0x00110000, 0x00140000, 0x001a0000, 0x001c0000, 0x001b0000, 0x001b0000, 0x00190000, 0x001a0000, 0x001a0000, 0x001c0000, 0x00250000, 0x002d0400, 0x003a0c00, 0x004a1701, 0x005c240d, 0x0070341a, 0x00844126, 0x00944a2c, 0x00a24b2c, 0x00a84927, 0x00ab4b21, 0x00ad4b1b, 0x00ae4a14, 0x00ac4910, 0x00ab4810, 0x00a94811, 0x00a84916, 0x00a54a18, 0x00a5491c, 0x00a74a1b, 0x00ab4818, 0x00ac4814, 0x00b04810, 0x00b1480e, 0x00b0440d, 0x00b74a0d, 0x00c0500a, 0x00c35305, 0x00ca5708, 0x00c65c11, 0x00a64c13, 0x0078360e, 0x00300900, 0x00110100, 0x00020000, 0x00080a09, 0x0017140f, 0x00130c06, 0x00080000, 0x00140000, 0x003c0800, 0x00763206, 0x00a85a24, 0x00b75f21, 0x00b45210, 0x00b8500e, 0x00b95014, 0x00af4610, 0x00af4a19, 0x00a74819, 0x00a0491c, 0x009d4d24, 0x00904a25, 0x0075371a, 0x00551c0b, 0x003a0c00, 0x001c0000, 0x00140000, 0x001b0000, 0x00461810, 0x007c3c24, 0x009b4b23, 0x00a84a14, 0x00ad480f, 0x00ac4814, 0x00af4a1b, 0x00ad4716, 0x00ae4918, 0x00a44412, 0x00a44c20, 0x007c3414, 0x00631c00, 0x007c2905, 0x00923810, 0x00a4481d, 0x00ab4a1e, 0x00ac4819, 0x00ac4818, 0x00ad4818, 0x00ac4916, 0x00aa4814, 0x00a94a14, 0x00aa4c14, 0x00ac4b10, 0x00ac4a0c, 0x00b04908, 0x00b44807, 0x00b74a07, 0x00b74b0a, 0x00c3530f, 0x00cc580b, 0x00cc5201, 0x00c85304, 0x00c45c14, 0x00a9561d, 0x0080411a, 0x00421902, 0x001c0300, 0x000b0000, 0x00080000, 0x00100c0d, 0x00464648, 0x009c9fa1, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00808078, 0x0028251e, 0x000a0200, 0x00120100, 0x00280800, 0x005a2610, 0x008c4c2f, 0x00904f2f, 0x00521b00, 0x00170000, 0x00170000, 0x002f0800, 0x00673321, 0x00904c2c, 0x00944926, 0x00854321, 0x004f1a00, 0x00260700, 0x00100000, 0x00100000, 0x00200600, 0x00401800, 0x00632c0c, 0x00833d19, 0x00994921, 0x00a44c21, 0x00a94a1d, 0x00ac4819, 0x00ac4517, 0x00ad4515, 0x00af4715, 0x00ae4614, 0x00ac4410, 0x00ac4511, 0x00ac4916, 0x00a24614, 0x00a24d1f, 0x009c5025, 0x00894620, 0x006e3514, 0x00522204, 0x003f1400, 0x00340c00, 0x00340700, 0x00320400, 0x00300300, 0x00310400, 0x00350800, 0x003c0e00, 0x00441500, 0x004b1900, 0x005b2504, 0x00682c0b, 0x007b3a16, 0x008c4421, 0x00984a26, 0x009c4c27, 0x00a04a27, 0x00a24824, 0x00aa4924, 0x00a9481e, 0x00a84618, 0x00a94717, 0x00ac4a14, 0x00ac4c14, 0x00ac4c14, 0x00aa4b14, 0x00a84816, 0x00a94b19, 0x00ab4b1b, 0x00ac4919, 0x00ac4817, 0x00ae4713, 0x00b04713, 0x00b3480f, 0x00bb4d0d, 0x00c1510b, 0x00c65305, 0x00c45204, 0x00c0570e, 0x00af551a, 0x0078340f, 0x00380c00, 0x00170000, 0x00030001, 0x00000307, 0x00212829, 0x005c605f, 0x00505250, 0x000c0d0b, 0x00050000, 0x00160000, 0x00300800, 0x00672e09, 0x009c5220, 0x00b45a1d, 0x00bc5412, 0x00bc5011, 0x00ba4d12, 0x00b04510, 0x00af4b16, 0x00ab4c17, 0x00a44a18, 0x00a14d20, 0x00a05028, 0x008f4425, 0x0078341e, 0x004f190c, 0x00381007, 0x00190000, 0x00170000, 0x00411804, 0x00783c1f, 0x009f4924, 0x00aa4821, 0x00ac4821, 0x00a8481d, 0x00a84918, 0x00aa4c15, 0x00a4450c, 0x00a84c18, 0x00a34c28, 0x00893817, 0x00742700, 0x00863709, 0x009a4517, 0x00a6491a, 0x00ab4818, 0x00ae4817, 0x00b04816, 0x00ad4714, 0x00ac4815, 0x00ad4a17, 0x00ae4c16, 0x00ae4a14, 0x00b04811, 0x00b44710, 0x00bb4812, 0x00c04c10, 0x00c6510d, 0x00c85208, 0x00ca5405, 0x00c85508, 0x00bd5813, 0x00a8561c, 0x00743a14, 0x00391400, 0x00150200, 0x00070000, 0x00080102, 0x000a0507, 0x00423f40, 0x009a9a9c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b7ac, 0x0074716a, 0x00282422, 0x00050107, 0x00080000, 0x00260300, 0x0057230c, 0x008f4c2f, 0x0082452c, 0x00401d10, 0x00170000, 0x00140000, 0x002b0400, 0x00653017, 0x008a4b2a, 0x00965430, 0x007e4426, 0x00441d0c, 0x00190200, 0x000a0002, 0x00040000, 0x000b0000, 0x00180000, 0x00320700, 0x00531b00, 0x00743416, 0x008f4524, 0x00984620, 0x00a24a21, 0x00a84c21, 0x00a8491c, 0x00aa4818, 0x00ae4918, 0x00b04a16, 0x00ae4814, 0x00ae4b18, 0x00a94b19, 0x00a24a19, 0x009e4c1d, 0x009b5024, 0x00955028, 0x00884620, 0x0078391a, 0x0070331e, 0x006f3121, 0x006e311f, 0x0072341e, 0x0078391f, 0x00804021, 0x00884822, 0x00904d25, 0x00985026, 0x009b5024, 0x009f5024, 0x00a24d24, 0x00a34b20, 0x00a54a20, 0x00a74820, 0x00a94920, 0x00a8481d, 0x00a9481b, 0x00aa4a1a, 0x00ab4917, 0x00aa4814, 0x00a94812, 0x00a94812, 0x00a94814, 0x00ab4917, 0x00ac4919, 0x00ac4919, 0x00ac4817, 0x00b04613, 0x00b14711, 0x00b74911, 0x00bb4d0f, 0x00c45610, 0x00c15408, 0x00c7590e, 0x00c6601a, 0x00a85118, 0x00733007, 0x003b1000, 0x00140000, 0x00050000, 0x0008080e, 0x00181c20, 0x0062686b, 0x00313333, 0x00a6adab, 0x00494e4c, 0x000e100d, 0x00050000, 0x000e0000, 0x002a0600, 0x00572304, 0x008e471a, 0x00b05924, 0x00b8551a, 0x00bd5416, 0x00b54b0d, 0x00b54c10, 0x00b04a11, 0x00a94811, 0x00a74815, 0x00a84c1c, 0x00a54a1f, 0x009c4722, 0x00954b30, 0x00723723, 0x004d2513, 0x00341200, 0x00310800, 0x00561c01, 0x008b391b, 0x00a44524, 0x00ac4824, 0x00a84419, 0x00ac4f19, 0x00a84a12, 0x00aa4c12, 0x00a94a15, 0x00a6481e, 0x00a74d27, 0x009a471b, 0x009c491b, 0x00a2491c, 0x00a8481a, 0x00ad4819, 0x00b04818, 0x00b04715, 0x00ae4411, 0x00ae4814, 0x00ac4813, 0x00ac4711, 0x00af4811, 0x00b44812, 0x00bd4c15, 0x00c44e17, 0x00c75114, 0x00cc5712, 0x00c4530b, 0x00c1560f, 0x00b95a1a, 0x00984c18, 0x00662e07, 0x002f0d00, 0x000c0000, 0x00050000, 0x00000003, 0x00100c10, 0x00494446, 0x00999695, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x000d0c0c, 0x00727073, 0x001b1e28, 0x0006060e, 0x00130302, 0x00200000, 0x004d1706, 0x00824a36, 0x0076503e, 0x00381e10, 0x001a0800, 0x00100000, 0x002a0900, 0x0063361c, 0x00834522, 0x0093512c, 0x006f3416, 0x004b1e0c, 0x00150100, 0x00050006, 0x00000005, 0x00030002, 0x000b0000, 0x00130000, 0x00220600, 0x00341000, 0x0062341f, 0x00743c22, 0x00874528, 0x00944926, 0x00a04b21, 0x00a84c1e, 0x00ac491a, 0x00aa4516, 0x00a84515, 0x00a94718, 0x00a8491c, 0x00a84b1d, 0x00a84c1c, 0x00a84c1b, 0x00a74a19, 0x00a34818, 0x00a04c22, 0x009c4b24, 0x009c4a23, 0x009e4a24, 0x009e4b22, 0x009f4a20, 0x00a04b21, 0x00a44c21, 0x00a44c21, 0x00a44b20, 0x00a44920, 0x00a44920, 0x00a44820, 0x00a54821, 0x00a64922, 0x00a64920, 0x00a2481b, 0x00a54a1a, 0x00aa4c1b, 0x00ab4b18, 0x00ac4916, 0x00ac4814, 0x00ae4a17, 0x00b04b1a, 0x00aa4618, 0x00aa4618, 0x00ab4617, 0x00ae4713, 0x00b44810, 0x00bb4b0d, 0x00c34f0c, 0x00c6530d, 0x00c55710, 0x00bb540f, 0x00b85819, 0x00a2531f, 0x006b3210, 0x002e0a00, 0x000c0000, 0x00070204, 0x00040406, 0x00191a1d, 0x00656668, 0x00313232, 0x00000000, 0x00000000, 0x00b2b4b0, 0x004c4c48, 0x001a1517, 0x000a0104, 0x00080000, 0x00180000, 0x00411b0b, 0x00783e1e, 0x009d4f1e, 0x00b35518, 0x00c45c18, 0x00be530f, 0x00b64c10, 0x00b34c14, 0x00ae4a15, 0x00aa4611, 0x00ae4811, 0x00b24e19, 0x00a84a1f, 0x009c4822, 0x00944e24, 0x0083451c, 0x00652702, 0x005d1600, 0x007c2506, 0x009b3c19, 0x00ac461a, 0x00ac4612, 0x00b04d15, 0x00a8470e, 0x00ac4d18, 0x00ac4c1c, 0x00a44317, 0x00a9481e, 0x00ac4c22, 0x00a8471e, 0x00a9441b, 0x00ac4418, 0x00b04418, 0x00b14518, 0x00b14615, 0x00b14814, 0x00ae4712, 0x00ae4810, 0x00b04a0e, 0x00b44d0c, 0x00bb5110, 0x00c25310, 0x00c85410, 0x00c75510, 0x00c0530e, 0x00bc5a1a, 0x00ac5822, 0x00864519, 0x004e2304, 0x001d0400, 0x00080000, 0x00090605, 0x00000001, 0x00171518, 0x00494444, 0x00a09a98, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00757b83, 0x00191c24, 0x00060103, 0x00100000, 0x00180000, 0x00381101, 0x00664535, 0x00705645, 0x00362010, 0x001e0a00, 0x00100000, 0x00230200, 0x005a2a0f, 0x00854929, 0x00965531, 0x00713819, 0x003e1808, 0x001e0a04, 0x00050002, 0x00010004, 0x00040100, 0x00050000, 0x00080000, 0x000e0000, 0x00130000, 0x00270800, 0x00471f0c, 0x006a3720, 0x00844528, 0x00904726, 0x00984824, 0x009f4924, 0x00a54c28, 0x00a34923, 0x00a34721, 0x00a4471e, 0x00a5451b, 0x00a54417, 0x00a94616, 0x00aa4a1a, 0x00a54b1e, 0x00a24b1e, 0x00a34b20, 0x00a34d24, 0x00a24d25, 0x009e4a24, 0x009c4823, 0x009c4824, 0x009b4624, 0x009b4624, 0x009a4622, 0x009a4622, 0x00994520, 0x0098441f, 0x0097421c, 0x00954018, 0x00984014, 0x009c4114, 0x00a04416, 0x00a64616, 0x00ac4818, 0x00ac4817, 0x00ad4716, 0x00ac4615, 0x00ad4716, 0x00ad4714, 0x00af4813, 0x00b44a10, 0x00ba4c0c, 0x00c1510c, 0x00c85409, 0x00c7560c, 0x00bc5512, 0x00b65c23, 0x009a5022, 0x005f2809, 0x00240500, 0x000b0000, 0x00040405, 0x00000407, 0x00141818, 0x00646867, 0x009c9c9b, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00606062, 0x0018191d, 0x00000007, 0x00080007, 0x000d0000, 0x00290700, 0x00612c09, 0x00904a18, 0x00ac551b, 0x00b85818, 0x00be591c, 0x00be551c, 0x00b95016, 0x00b84a10, 0x00b44707, 0x00b14406, 0x00ad440e, 0x00b14f19, 0x00a74c14, 0x009f4814, 0x00a04f22, 0x0098461f, 0x00903a15, 0x009c3d15, 0x00ad4716, 0x00b04713, 0x00ae4710, 0x00ac4812, 0x00a84817, 0x00a84818, 0x00ae4b1b, 0x00ae491b, 0x00aa4418, 0x00a94418, 0x00ad4418, 0x00b24818, 0x00b34614, 0x00b1430f, 0x00b1440c, 0x00b4480c, 0x00b6490c, 0x00ba4e0d, 0x00be5412, 0x00c05811, 0x00c25711, 0x00c0550e, 0x00c1550d, 0x00bd5613, 0x00b1571a, 0x009e5120, 0x006d330f, 0x00340c00, 0x00130000, 0x00080100, 0x00020202, 0x00000104, 0x00171718, 0x00585758, 0x00aaa5a5, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007f7d7e, 0x00272320, 0x00080300, 0x00070200, 0x00080000, 0x00150600, 0x00462f20, 0x00785740, 0x004f2d19, 0x00200800, 0x00100000, 0x001c0100, 0x0047210c, 0x007c4521, 0x0095582e, 0x008b5028, 0x005c2d0c, 0x002a0d00, 0x00140400, 0x00100806, 0x00100808, 0x00110301, 0x000f0000, 0x000c0000, 0x000a0000, 0x000e0000, 0x00180000, 0x00280800, 0x00492013, 0x006c3a2c, 0x007f4532, 0x008c4b34, 0x00914a30, 0x0094482c, 0x00944627, 0x00984727, 0x009b4828, 0x009a4825, 0x00964524, 0x00984727, 0x00954729, 0x0092472a, 0x0090482d, 0x008c4a32, 0x00874933, 0x00814630, 0x007c442f, 0x00743c28, 0x006f3820, 0x00682d14, 0x00612408, 0x005d1e00, 0x005b1800, 0x00581400, 0x005a0e00, 0x00742000, 0x008b3008, 0x00a04119, 0x00a94920, 0x00aa471d, 0x00a84418, 0x00ac4416, 0x00af4715, 0x00b44a14, 0x00b0450b, 0x00b94c0e, 0x00c45813, 0x00c4560d, 0x00c05105, 0x00c45405, 0x00c05910, 0x00b35a23, 0x0088421d, 0x004c1c05, 0x00190000, 0x00060000, 0x00000103, 0x00010604, 0x00131a16, 0x00696f69, 0x00b4b8b3, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0078807f, 0x00232324, 0x000b0403, 0x000c0100, 0x000f0000, 0x00150000, 0x00331000, 0x006c3814, 0x00975224, 0x00b15722, 0x00be551c, 0x00c65418, 0x00c75111, 0x00c65211, 0x00bc4c0c, 0x00b44c0d, 0x00b0480c, 0x00b24a0e, 0x00b04b14, 0x00a44815, 0x00a1491a, 0x00a34c1f, 0x00a4481b, 0x00ac4718, 0x00ae4614, 0x00ac4612, 0x00ab4714, 0x00a84817, 0x00a84817, 0x00ad4714, 0x00ad4714, 0x00ac4817, 0x00aa4814, 0x00ab4810, 0x00ac480b, 0x00b14808, 0x00b74a05, 0x00bd4c04, 0x00c24e04, 0x00c85206, 0x00c85206, 0x00ca580e, 0x00c85a13, 0x00c05710, 0x00bc5714, 0x00b85716, 0x00a55219, 0x0084431b, 0x00461800, 0x001e0000, 0x00100000, 0x00030000, 0x00000001, 0x00040708, 0x001c1d1f, 0x00717070, 0x00444343, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0095938f, 0x002f3029, 0x00000800, 0x00000200, 0x00090400, 0x000d0000, 0x00290c00, 0x005e402f, 0x00553f36, 0x00281512, 0x00140000, 0x00140000, 0x00360a00, 0x00743b18, 0x009e5d33, 0x009c5e34, 0x00734120, 0x00320e00, 0x00190200, 0x00392722, 0x00412d29, 0x001e0a04, 0x000c0000, 0x00140800, 0x000a0000, 0x000b0000, 0x000f0000, 0x00130000, 0x00140000, 0x00280400, 0x003c1004, 0x00501c0e, 0x00642c18, 0x006c331f, 0x006c311d, 0x00662c18, 0x00642c18, 0x00642c18, 0x005c210c, 0x00581d08, 0x00501703, 0x00451000, 0x003c0800, 0x00340000, 0x002e0000, 0x002c0000, 0x002e0000, 0x00340000, 0x00400700, 0x00501400, 0x00642506, 0x007b3815, 0x008e4924, 0x009c502a, 0x00a34b24, 0x00a64820, 0x00a6461e, 0x00a6461e, 0x00ab481e, 0x00af4a1c, 0x00b04814, 0x00b0450c, 0x00b34505, 0x00c45410, 0x00c2540c, 0x00ba4e04, 0x00c05910, 0x00c05d17, 0x00b85814, 0x00b05a20, 0x007b3810, 0x003c0c00, 0x00140000, 0x00080000, 0x00040408, 0x00000005, 0x00181d1d, 0x0070746f, 0x00787b78, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009e9f9b, 0x003c3834, 0x00130c06, 0x00050000, 0x00080000, 0x00120400, 0x001a0000, 0x003d1200, 0x00783710, 0x00a85426, 0x00b85720, 0x00bf551a, 0x00c55b1d, 0x00c05413, 0x00c35715, 0x00c05310, 0x00c04f0d, 0x00bd4d0e, 0x00b54d11, 0x00b04f14, 0x00ac4d17, 0x00ab4914, 0x00ae4712, 0x00b04610, 0x00b04710, 0x00ad4810, 0x00ac4813, 0x00ae4811, 0x00b2470e, 0x00b4460c, 0x00b0480e, 0x00b14c10, 0x00b65010, 0x00bb540f, 0x00be550c, 0x00c15608, 0x00c45406, 0x00c85405, 0x00cc5a0c, 0x00c14f04, 0x00c0540f, 0x00bb5717, 0x00ac531a, 0x00a85824, 0x008c4718, 0x00541c00, 0x00200000, 0x00130000, 0x00080000, 0x00020000, 0x00010407, 0x00010508, 0x00323536, 0x008d8f8e, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00acaea7, 0x004a4f45, 0x00020400, 0x00000000, 0x00030000, 0x00060000, 0x00100400, 0x00331f19, 0x004d3630, 0x00402825, 0x00230806, 0x00180000, 0x00230000, 0x00511c04, 0x00814324, 0x00a1603b, 0x00935532, 0x005a280c, 0x00280000, 0x00301304, 0x0065493a, 0x006b4a32, 0x00381700, 0x001d0100, 0x001c0600, 0x000d0000, 0x000c0000, 0x00100000, 0x000e0000, 0x00140000, 0x00160000, 0x00160000, 0x00160000, 0x00150000, 0x00140000, 0x00110000, 0x00110000, 0x00140000, 0x00170000, 0x00190000, 0x001d0000, 0x00280000, 0x003b0600, 0x00501300, 0x00601c08, 0x007e351e, 0x00893c21, 0x00944428, 0x009d4b2a, 0x00a04d29, 0x009f4d26, 0x009e4c25, 0x00a04b21, 0x00a6461c, 0x00aa471c, 0x00aa471c, 0x00a84518, 0x00a84515, 0x00b04a13, 0x00ba5010, 0x00c4540e, 0x00cc580c, 0x00ca5708, 0x00c95b0c, 0x00c05910, 0x00b55b1c, 0x00b0612d, 0x008c481d, 0x00501b00, 0x00230000, 0x00130000, 0x000a0000, 0x00080303, 0x00000003, 0x0028292d, 0x00878588, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x008e8e89, 0x00716e67, 0x001e1812, 0x00040000, 0x00050000, 0x00080000, 0x00100000, 0x001d0100, 0x00340c00, 0x00662d08, 0x00985024, 0x00af5b27, 0x00ba581c, 0x00c0540f, 0x00cb570c, 0x00cc570c, 0x00c8540a, 0x00c7540c, 0x00c4540d, 0x00c35411, 0x00c45514, 0x00c25213, 0x00c15114, 0x00bf5214, 0x00bc5213, 0x00be5211, 0x00c15211, 0x00c6510f, 0x00c8500d, 0x00c8530f, 0x00c65410, 0x00c4540e, 0x00c3550a, 0x00c05508, 0x00c05707, 0x00c35808, 0x00c25a0f, 0x00b8520c, 0x00c05e20, 0x00b6602c, 0x009d542a, 0x00773e1c, 0x00411700, 0x00180000, 0x00100000, 0x000d0100, 0x00040000, 0x00040203, 0x00000001, 0x000e1112, 0x005e605f, 0x00acacaa, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b4b4b0, 0x00787874, 0x00181513, 0x00020001, 0x00000107, 0x00000003, 0x000b0000, 0x001b0703, 0x002d1716, 0x003a2326, 0x002f1b20, 0x001e0405, 0x001f0000, 0x003c0c00, 0x00612809, 0x008a4e2c, 0x00986041, 0x006c3c21, 0x00360d00, 0x00250000, 0x00482004, 0x00754d31, 0x007b5740, 0x00573723, 0x00391c0c, 0x00240900, 0x00180000, 0x00180000, 0x00180000, 0x00180000, 0x00180000, 0x001c0000, 0x001c0000, 0x00180000, 0x00170000, 0x00180000, 0x00301400, 0x00401d01, 0x00572d10, 0x006b3b1d, 0x007d4425, 0x00894727, 0x00944828, 0x009c4826, 0x009f4421, 0x00a44620, 0x00aa4820, 0x00ac481f, 0x00a8451a, 0x00a44416, 0x00a44315, 0x00a64414, 0x00ab4410, 0x00b04812, 0x00b64d17, 0x00b95018, 0x00bd5418, 0x00c15514, 0x00c3540d, 0x00c15206, 0x00c35304, 0x00bf5507, 0x00bb5810, 0x00b25c20, 0x00985024, 0x00642b0b, 0x00330800, 0x001b0000, 0x00100000, 0x00060000, 0x00050100, 0x00080503, 0x00424043, 0x009d9ca0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00323231, 0x00a4a29e, 0x004c4848, 0x00121013, 0x00030206, 0x00000001, 0x00030000, 0x000a0000, 0x001b0100, 0x00300800, 0x004c1500, 0x007c360b, 0x00a5511c, 0x00b5581c, 0x00bb5a1b, 0x00bc5816, 0x00c15817, 0x00c15815, 0x00bf5513, 0x00c25816, 0x00c15815, 0x00c05715, 0x00c05614, 0x00c05414, 0x00c15413, 0x00c45412, 0x00c65410, 0x00c85510, 0x00cb5813, 0x00c75713, 0x00c35814, 0x00be5915, 0x00bb5a18, 0x00b65c1b, 0x00b25c1e, 0x00af5d24, 0x00a55724, 0x00833d13, 0x00581c00, 0x00350600, 0x001f0000, 0x00110000, 0x00060000, 0x00000001, 0x00000004, 0x00000004, 0x00040709, 0x003b3e3f, 0x00949594, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00201f20, 0x00a49a95, 0x00534c48, 0x00010108, 0x0000020c, 0x00000005, 0x00040001, 0x000b0104, 0x0014080b, 0x001b0f11, 0x00201414, 0x001b0c0b, 0x00160400, 0x00200600, 0x00341404, 0x005a301d, 0x00865640, 0x0088543b, 0x00602e15, 0x00300800, 0x00320d00, 0x00502810, 0x0076492f, 0x008c593b, 0x008c5735, 0x00814825, 0x00733a15, 0x00683009, 0x00652c04, 0x00622900, 0x00662a00, 0x00703001, 0x007d3c0a, 0x008c4814, 0x0099501a, 0x009c4c18, 0x00a04c18, 0x00a24c18, 0x00a34c18, 0x00a54b16, 0x00a84b15, 0x00ac4a14, 0x00ae4a14, 0x00b04812, 0x00b04810, 0x00b1460d, 0x00b3450d, 0x00b4470f, 0x00b94a13, 0x00bf5018, 0x00c25418, 0x00c25312, 0x00c2540d, 0x00c45009, 0x00c45007, 0x00c75004, 0x00c95405, 0x00c95809, 0x00c4590d, 0x00b95811, 0x00b56120, 0x0098501e, 0x00652d06, 0x003c1000, 0x00210300, 0x00130000, 0x00080000, 0x00040001, 0x00000000, 0x0014110a, 0x006a6860, 0x00b5b2b0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x0087878d, 0x003e4046, 0x00111418, 0x00000402, 0x00000300, 0x00040100, 0x000c0200, 0x00100000, 0x001b0200, 0x00270900, 0x003f1800, 0x005a2809, 0x00783b16, 0x00974d24, 0x00a65627, 0x00aa5822, 0x00ae5b20, 0x00b05b1b, 0x00b45a1a, 0x00bb581b, 0x00c0581c, 0x00c2571c, 0x00c1581c, 0x00bc5a18, 0x00ba5918, 0x00bb5619, 0x00b9571f, 0x00b55a28, 0x00aa5a2a, 0x00985228, 0x007c411c, 0x00602c0c, 0x004c1f04, 0x00330b00, 0x00260400, 0x001c0000, 0x00170000, 0x00100000, 0x00060000, 0x00020000, 0x00050408, 0x00030408, 0x0035383b, 0x007e7e80, 0x00b1b1b0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b2aca8, 0x00878788, 0x00313439, 0x0003050b, 0x00040408, 0x00020003, 0x00030000, 0x000b0606, 0x00080404, 0x000b090a, 0x00030102, 0x000a0200, 0x00130400, 0x00190000, 0x00351000, 0x0061341e, 0x00784a34, 0x00714c3d, 0x004d291a, 0x00330b00, 0x00390c00, 0x00582408, 0x007b4422, 0x00935832, 0x009d5d34, 0x009a582c, 0x009d5626, 0x00a05520, 0x00a4551b, 0x00ac5718, 0x00b65a18, 0x00bb5c14, 0x00be5a12, 0x00c35814, 0x00c45513, 0x00c25310, 0x00c05310, 0x00be530f, 0x00be530d, 0x00bf540e, 0x00c0530e, 0x00bd500c, 0x00c0500c, 0x00c2520c, 0x00c4520d, 0x00c65210, 0x00c75210, 0x00c7500e, 0x00c44f0b, 0x00c4540a, 0x00c5560a, 0x00c8580c, 0x00c7560c, 0x00c6550d, 0x00c15610, 0x00b95514, 0x00ae561a, 0x00914814, 0x00602600, 0x003c1100, 0x00260800, 0x00120000, 0x00080000, 0x00070006, 0x00000007, 0x00000004, 0x003a3d3c, 0x008c8e87, 0x00b5b7ae, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00adb0b5, 0x007c8083, 0x00424648, 0x00141818, 0x00000100, 0x00000000, 0x00000000, 0x00040301, 0x00020000, 0x000b0200, 0x00180500, 0x00250700, 0x00360900, 0x00431000, 0x00501b00, 0x00602800, 0x006a3002, 0x00713203, 0x007c3307, 0x00823408, 0x0085340b, 0x00813408, 0x00793404, 0x00763303, 0x00722c01, 0x00692400, 0x00571900, 0x00451000, 0x00360b00, 0x00280700, 0x001c0300, 0x00140000, 0x000c0000, 0x000a0000, 0x00050000, 0x00040000, 0x00060302, 0x00000000, 0x000c0b0d, 0x00353438, 0x00808084, 0x00a4a4a6, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a49d, 0x006e6f6b, 0x00323431, 0x00090909, 0x00000000, 0x00000201, 0x00000000, 0x00000001, 0x00040504, 0x00010000, 0x00040000, 0x000c0000, 0x00140300, 0x001d0800, 0x002d1208, 0x004c291f, 0x005c372c, 0x00553229, 0x003b1b13, 0x002a0a02, 0x002d0c00, 0x00441d0b, 0x005f3016, 0x00864c29, 0x009c572c, 0x00b1602b, 0x00b85e23, 0x00b85817, 0x00bc5411, 0x00be550f, 0x00c0540c, 0x00c4540c, 0x00c6540a, 0x00c7540b, 0x00c6560a, 0x00c6570b, 0x00c5580b, 0x00c55809, 0x00c55809, 0x00c6590a, 0x00c6590a, 0x00c65809, 0x00c65608, 0x00c85508, 0x00c85508, 0x00cb5509, 0x00c8560b, 0x00c6580d, 0x00c0570f, 0x00bb5514, 0x00b8581d, 0x00b05826, 0x009b4d24, 0x00773515, 0x00562208, 0x00320c00, 0x00230800, 0x000c0000, 0x00060000, 0x00070300, 0x00010000, 0x00040404, 0x00181618, 0x006c666c, 0x00a7a5a9, 0x00434546, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00abaaae, 0x008c8b8f, 0x00646064, 0x002a2629, 0x00080405, 0x00040301, 0x00030200, 0x00020000, 0x00040000, 0x000b0200, 0x000c0000, 0x000e0000, 0x00120000, 0x00180200, 0x001b0400, 0x001f0600, 0x00240800, 0x00280a00, 0x00290b00, 0x00280a00, 0x00250800, 0x00230700, 0x001f0500, 0x001b0200, 0x00150000, 0x00100000, 0x000c0000, 0x00070000, 0x00040000, 0x00020000, 0x00010200, 0x00000000, 0x00000200, 0x00080905, 0x001c1e1c, 0x00515151, 0x008a8a8c, 0x00a6a4a7, 0x000c0c0c, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x007c7c78, 0x009e9f9b, 0x00777876, 0x00404443, 0x00121516, 0x00000304, 0x00000203, 0x00000201, 0x00000100, 0x00010000, 0x00040000, 0x00040000, 0x00040000, 0x000a0000, 0x001b0300, 0x00270b06, 0x002b1311, 0x00210e0e, 0x000f0000, 0x000b0000, 0x00180200, 0x00260800, 0x003c1100, 0x00541e00, 0x00702e06, 0x00883c0e, 0x00a04d18, 0x00b35c26, 0x00b85f28, 0x00b75a20, 0x00bc5818, 0x00bf5815, 0x00c05814, 0x00bf5814, 0x00bc5812, 0x00bc5810, 0x00bc580f, 0x00bd5910, 0x00bc580f, 0x00bd5911, 0x00bd5911, 0x00bc5812, 0x00bc5812, 0x00bc5814, 0x00bd5815, 0x00ba5918, 0x00b15b20, 0x00a3541e, 0x008f4415, 0x0076340c, 0x005d2405, 0x00441400, 0x002c0700, 0x00180000, 0x000d0000, 0x00050000, 0x00040203, 0x00030404, 0x00000000, 0x00151916, 0x00585a58, 0x00959493, 0x00585457, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b5b0b5, 0x009e989e, 0x00807c7f, 0x00555454, 0x002b2b29, 0x00101010, 0x00000003, 0x00000001, 0x00000000, 0x00030200, 0x00050300, 0x00040000, 0x00030000, 0x00030000, 0x00030000, 0x00030000, 0x00040000, 0x00040000, 0x00050000, 0x00050000, 0x00020000, 0x00000000, 0x00010000, 0x00000000, 0x00000003, 0x00000003, 0x00000104, 0x00000305, 0x00090e0e, 0x00242b28, 0x00494e4b, 0x006f7470, 0x00949895, 0x00afb0b0, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00a4a5a4, 0x00808180, 0x00606261, 0x00343635, 0x00161817, 0x00000000, 0x00000000, 0x00040301, 0x00010000, 0x00000000, 0x00040000, 0x00070000, 0x00080000, 0x00080001, 0x00050002, 0x00030000, 0x00020000, 0x00040000, 0x00090000, 0x000c0000, 0x00170100, 0x00270a00, 0x00341000, 0x00411800, 0x0051240a, 0x00603116, 0x00703819, 0x00864018, 0x00924418, 0x009c4c1f, 0x00a15121, 0x00a75524, 0x00aa5825, 0x00ac5924, 0x00ab5823, 0x00ac5924, 0x00a95824, 0x00a55525, 0x009f5222, 0x00984c1f, 0x008b4218, 0x007f370f, 0x006f310e, 0x00512609, 0x0041200a, 0x00341702, 0x00280c00, 0x00190200, 0x00100000, 0x000c0000, 0x00060000, 0x00030000, 0x00000000, 0x00070708, 0x00222423, 0x00535454, 0x00868885, 0x00afafad, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b0b0b0, 0x00949494, 0x00838383, 0x00686869, 0x004c4c4c, 0x00343434, 0x0020201e, 0x00100f0d, 0x00050403, 0x00000000, 0x00000000, 0x00010000, 0x00010000, 0x00010000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00040404, 0x000d0d0d, 0x001a1a1c, 0x002f2f30, 0x004b4c4d, 0x00616264, 0x007f8080, 0x00909190, 0x00a8aaa9, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b0b0b0, 0x00949494, 0x007e7e7e, 0x00616161, 0x00444444, 0x00292929, 0x00101010, 0x00020202, 0x00000000, 0x00000002, 0x00000001, 0x00000003, 0x00000001, 0x00000001, 0x00000102, 0x00000201, 0x00020200, 0x00000000, 0x00040000, 0x00060000, 0x000b0000, 0x000f0000, 0x00130000, 0x001c0400, 0x00280a00, 0x00391000, 0x00441500, 0x004d1b00, 0x00521f02, 0x00572003, 0x005b2403, 0x005e2504, 0x005e2504, 0x005e2504, 0x00582203, 0x00532003, 0x004e1e03, 0x00481a02, 0x003f1400, 0x00340c00, 0x00280700, 0x00170500, 0x000a0000, 0x00060000, 0x00050000, 0x00060200, 0x00040100, 0x00000000, 0x00000000, 0x00101113, 0x00303133, 0x005c5c5e, 0x00878889, 0x00aeaeae, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00787878, 0x00a7a7a7, 0x00989898, 0x00888888, 0x00787878, 0x006d6d6d, 0x00606060, 0x005a5a5a, 0x00525252, 0x004b4b4b, 0x00484848, 0x00494949, 0x004d4d4d, 0x00505050, 0x00585858, 0x005e5e5e, 0x006b6b6b, 0x00797979, 0x00858585, 0x00939393, 0x00a5a5a5, 0x00acacac, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009b9b9b, 0x00a0a0a0, 0x008a8a8a, 0x00757575, 0x00636363, 0x00585858, 0x00454444, 0x003b3b3b, 0x002f2f30, 0x00262728, 0x00212224, 0x00202022, 0x001f2020, 0x0020211f, 0x00242422, 0x0014110f, 0x00060000, 0x00060000, 0x00090000, 0x000c0000, 0x000c0000, 0x000c0000, 0x000c0000, 0x000c0000, 0x000e0000, 0x000e0000, 0x00100000, 0x00120000, 0x00140000, 0x00160000, 0x00140000, 0x00100000, 0x000d0000, 0x000c0000, 0x000a0000, 0x00090000, 0x00080000, 0x00070000, 0x00060000, 0x00080000, 0x00080000, 0x00050000, 0x00050100, 0x000f0c09, 0x00292827, 0x004a4a4a, 0x006a6b6c, 0x008f9091, 0x009b9c9d, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00313131, 0x00898989, 0x00afafaf, 0x00a8a8a8, 0x00a6a6a6, 0x00a6a6a6, 0x00a9a9a9, 0x00acacac, 0x00b0b0b0, 0x00898989, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00b3b3b3, 0x00a6a5a4, 0x009c9b99, 0x008f8f8d, 0x00868686, 0x00818382, 0x00808082, 0x00808082, 0x00818382, 0x00797979, 0x006a6a68, 0x00555251, 0x003e3a38, 0x0028231e, 0x00150e08, 0x000b0200, 0x00060000, 0x00000000, 0x00000000, 0x00000000, 0x00020100, 0x00040200, 0x00050100, 0x00040000, 0x00030000, 0x00040000, 0x00040100, 0x00030200, 0x00020200, 0x00000203, 0x00000003, 0x00000104, 0x00000001, 0x00030000, 0x00130c08, 0x00241e19, 0x00373330, 0x00524f4c, 0x006a6968, 0x00888888, 0x00a9a9a9, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x009b9b9c, 0x009b9b9b, 0x007f7d7e, 0x00646462, 0x004e4d4c, 0x00403f3d, 0x00373538, 0x002d2c30, 0x00222023, 0x0019181a, 0x00161314, 0x00131010, 0x00100d0e, 0x000e0b0a, 0x00100c0d, 0x00120f10, 0x00141315, 0x0018181c, 0x001f1e23, 0x0028282f, 0x0033353b, 0x003d3e41, 0x00504d4c, 0x0066625f, 0x007c7875, 0x00969390, 0x00b5b2b1, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00acadaf, 0x009c9ca0, 0x00908e92, 0x007d7c7e, 0x00706e70, 0x00686668, 0x00646264, 0x00616062, 0x00616062, 0x00605e62, 0x00626064, 0x00666569, 0x006c6c70, 0x0078777c, 0x0089888d, 0x009c9da1, 0x00abaaae, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000, 0x00000000}; -======= -#include -int intense_milk_width = 426; -int intense_milk_height = 244 -;uint32_t intense_milk[103944] = {0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00221e1f, 0x001e1a1b, 0x00191617, 0x00151313, 0x0011ff, 0x00cbb, 0x00877, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001e1b1c, 0x001a1718, 0x00161314, 0x0011f10, 0x00dbc, 0x00988, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001b1818, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001f1b1c, 0x001b1818, 0x00161414, 0x00121011, 0x00ecd, 0x00989, 0x00545, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x001b1819, 0x00171415, 0x00131111, 0x00edd, 0x00a99, 0x00655, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1e, 0x001c191a, 0x00181516, 0x00131112, 0x00fde, 0x00baa, 0x00666, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a89, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x001d191a, 0x00191616, 0x00141212, 0x0010ee, 0x00baa, 0x00767, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001e1a1b, 0x00191617, 0x00151213, 0x0011ff, 0x00cbb, 0x00877, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001e1b1b, 0x001a1718, 0x00161314, 0x0011f10, 0x00dbc, 0x00988, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151313, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001f1b1c, 0x001b1718, 0x00161414, 0x00121010, 0x00ecc, 0x00988, 0x00545, 0x00101, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x009e2822, 0x00d12c23, 0x00b72a23, 0x009e2822, 0x00862622, 0x006c2421, 0x00532321, 0x003a2120, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x001b1819, 0x00171415, 0x00131011, 0x00ecd, 0x00a99, 0x00655, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00323, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2020, 0x00b42a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00d42c23, 0x00bb2a23, 0x00a22823, 0x00892722, 0x00702522, 0x00582321, 0x003e2121, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x001c1919, 0x00171515, 0x00131112, 0x00fde, 0x00b9a, 0x00656, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00545, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00352020, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00d92c24, 0x00bf2b23, 0x00a62923, 0x008e2722, 0x00742522, 0x005b2321, 0x00432121, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x001d191a, 0x00181516, 0x00141212, 0x0010ee, 0x00baa, 0x00766, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00412121, 0x00d42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00d12920, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2d24, 0x00c22b23, 0x00aa2923, 0x00912722, 0x00772522, 0x00602321, 0x00462221, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001d1a1b, 0x00181516, 0x00121011, 0x00cab, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00512221, 0x00de2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x004e1411, 0x00477, 0x00788, 0x001ffe, 0x003c12f, 0x00591512, 0x00761a15, 0x00921f19, 0x00b0241c, 0x00cc2820, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02d24, 0x00c72b23, 0x00ae2923, 0x00952722, 0x007c2622, 0x00632421, 0x004a2221, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d191a, 0x0011ff, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00632421, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x003912f, 0x00477, 0x006a6c6c, 0x00767878, 0x00585a5a, 0x00383b3b, 0x00191a1a, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x001bed, 0x003811f, 0x00541411, 0x00711915, 0x008f1e18, 0x00ab231c, 0x00c7281f, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00cb2b23, 0x00b22a23, 0x00992822, 0x007f2622, 0x00672421, 0x004e2221, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00782522, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2920, 0x0027fe, 0x00799, 0x009fa0a0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00d8d8d8, 0x00b8b9b9, 0x009a9b9b, 0x007b7d7d, 0x005c5e5e, 0x003d3f3f, 0x001e1f1f, 0x00588, 0x00477, 0x00477, 0x00477, 0x00477, 0x0017dc, 0x003311f, 0x00501410, 0x006e1914, 0x00891d17, 0x00a6221b, 0x00c4271f, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00cf2c23, 0x00b52a23, 0x009d2822, 0x00842622, 0x006b2421, 0x00512221, 0x00392120, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00656, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171415, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x0018dc, 0x00f1010, 0x00b8b9b9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00dcdcdc, 0x00bebfbf, 0x009fa0a0, 0x007f8181, 0x00626363, 0x00424444, 0x00222424, 0x00799, 0x00477, 0x00477, 0x00477, 0x00477, 0x0012cb, 0x002f11f, 0x004b1310, 0x00681813, 0x00851d17, 0x00a2211b, 0x00be261e, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00d22c23, 0x00ba2a23, 0x00a12822, 0x00872622, 0x006f2522, 0x00562321, 0x003c2121, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00121011, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00a62923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ab231c, 0x00daa, 0x001b1c1c, 0x00cdcdcd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00e1e2e2, 0x00c2c3c3, 0x00a3a5a5, 0x00858686, 0x00656767, 0x00474949, 0x00282a2a, 0x00acc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00daa, 0x002a10f, 0x004712f, 0x00631713, 0x00801c16, 0x009d211a, 0x00bb251e, 0x00d72a21, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00d72c24, 0x00bd2a23, 0x00a52923, 0x008c2722, 0x00732522, 0x005a2321, 0x00412121, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00788, 0x00292b2b, 0x00dfdfdf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00e5e6e6, 0x00c8c9c9, 0x00a8a9a9, 0x00898a8a, 0x006a6c6c, 0x004c4e4e, 0x002c2e2e, 0x00e10f, 0x00477, 0x00477, 0x00477, 0x00477, 0x00a99, 0x002610f, 0x00421210, 0x005f1612, 0x007c1b16, 0x00992019, 0x00b5251d, 0x00d22921, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2d24, 0x00c22b23, 0x00a92923, 0x008f2722, 0x00772522, 0x005e2321, 0x00442121, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00c92b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00791a15, 0x00477, 0x003d3f3f, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x00cccccc, 0x00acadad, 0x008f9090, 0x006f7171, 0x00505252, 0x00323434, 0x00131414, 0x00477, 0x00477, 0x00477, 0x00477, 0x00888, 0x0021fe, 0x003e12f, 0x005b1612, 0x00771a15, 0x00941f19, 0x00b1241c, 0x00cd2820, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00c52b23, 0x00ac2923, 0x00942722, 0x007b2522, 0x00612421, 0x00492221, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00452221, 0x00d82c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x005d1612, 0x00477, 0x00555757, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00d1d1d1, 0x00b2b3b3, 0x00939494, 0x00747676, 0x00565858, 0x00363838, 0x00181919, 0x00477, 0x00477, 0x00477, 0x00477, 0x00577, 0x001dfe, 0x003911f, 0x00561511, 0x00731a15, 0x008f1e18, 0x00ac231c, 0x00c9281f, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00c92b23, 0x00b12923, 0x00972822, 0x007f2622, 0x00662421, 0x004c2221, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00451310, 0x00477, 0x006e7070, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00d6d6d6, 0x00b6b7b7, 0x00999a9a, 0x00797b7b, 0x005a5c5c, 0x003b3d3d, 0x001c1d1d, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x0018dd, 0x003511f, 0x00521411, 0x006e1914, 0x008b1d18, 0x00a8221b, 0x00c5271f, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00ab2923, 0x00722522, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00692421, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82a21, 0x003211f, 0x00477, 0x008c8d8d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00dbdbdb, 0x00bcbdbd, 0x009d9e9e, 0x007d7f7f, 0x00606161, 0x00404242, 0x00202221, 0x00799, 0x00477, 0x00477, 0x00477, 0x00477, 0x0014cc, 0x003111f, 0x004c1310, 0x006a1814, 0x00871d17, 0x00a3211b, 0x00c0261e, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00a32823, 0x00412121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007f2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2820, 0x0022fd, 0x009bb, 0x00a7a8a8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00e0e0e0, 0x00c0c1c1, 0x00a1a3a3, 0x00838484, 0x00636565, 0x00454747, 0x00262828, 0x009bb, 0x00477, 0x00477, 0x00477, 0x00477, 0x00eba, 0x002c11f, 0x00491210, 0x00651713, 0x00821c17, 0x009f211a, 0x00bc261e, 0x00d82a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x008e2722, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00962822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b8251d, 0x0015cc, 0x00121313, 0x00bfc0c0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00e4e5e5, 0x00c6c7c7, 0x00a6a7a7, 0x00878888, 0x00696b6b, 0x004a4c4c, 0x002a2c2c, 0x00cee, 0x00477, 0x00477, 0x00477, 0x00477, 0x00b99, 0x002810f, 0x004312f, 0x00611612, 0x00851d17, 0x00b4241d, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf2b23, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131011, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00ad2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a2211b, 0x00caa, 0x001e2020, 0x00d4d4d4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e9eaea, 0x00cacaca, 0x00abacac, 0x008d8e8e, 0x006d6f6f, 0x004e5050, 0x00303232, 0x00101111, 0x00477, 0x00477, 0x00eba, 0x005a1612, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322020, 0x00bf2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00688, 0x00303232, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00d8d8d8, 0x00a5a6a6, 0x005e6060, 0x00cee, 0x00477, 0x00611713, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a22822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x006e1914, 0x00477, 0x00434545, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x00686a6a, 0x00477, 0x003611f, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00502221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00767, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004b2221, 0x00dc2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00551512, 0x00477, 0x005c5e5e, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a2a4a4, 0x00477, 0x005d1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ab2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005b2321, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02c22, 0x003f1310, 0x00477, 0x00777979, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x00577, 0x00c8281f, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00682421, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x002c10e, 0x00699, 0x00949595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00477, 0x007e1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00612421, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c4271f, 0x001ded, 0x00dff, 0x00aeafaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00171818, 0x00581511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00602421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00542321, 0x00e92e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b5251d, 0x0011bb, 0x00171818, 0x00c5c6c6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00202222, 0x00521411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00caa, 0x00212323, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00bdd, 0x00661713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00572321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00c32b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ba251e, 0x00caa, 0x00262828, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c6c7c7, 0x00477, 0x00961f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00777, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00832622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22920, 0x0018dc, 0x001e2020, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007a7c7c, 0x00477, 0x00d52a21, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x003712f, 0x00cee, 0x00cdcdcd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00252727, 0x003911f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009d2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009c2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00811c16, 0x00477, 0x009a9b9b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c8c9c9, 0x00477, 0x008a1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005b2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbb, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00656, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00d72a21, 0x00daa, 0x00444646, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00727474, 0x00688, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00772522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006e1914, 0x00477, 0x00cfcfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x001d1e1e, 0x00411310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00992822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b22a23, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x0017dc, 0x00484a4a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c0c1c1, 0x00477, 0x00931f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00e22d24, 0x00ee2e24, 0x00ee2e24, 0x00be261e, 0x00477, 0x009d9e9e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00696b6b, 0x00999, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00d72c24, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00362020, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00171818, 0x004a1311, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791a15, 0x00477, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00477, 0x009b201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00412121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007e1b16, 0x00477, 0x00e6e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x00baa, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00a5221b, 0x00477, 0x00b2b3b3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00121313, 0x00531411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008b2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x0010bb, 0x00464848, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00adaeae, 0x00477, 0x00a3211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00432121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008e2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f1b16, 0x00477, 0x00878888, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00585a5a, 0x0011bb, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003b2120, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00471411, 0x00477, 0x006d6f6f, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00cee, 0x005a1512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008d2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x005f1713, 0x00477, 0x00171818, 0x007b7d7d, 0x00c6c7c7, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a4a6a6, 0x00477, 0x00ac231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003d2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00be2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x003f12f, 0x00477, 0x00477, 0x00acc, 0x002c2e2e, 0x004c4e4e, 0x00696b6b, 0x00898a8a, 0x00a8a9a9, 0x00c6c7c7, 0x00e5e6e6, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004f5151, 0x0018dc, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00c22b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302020, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00931f19, 0x00671813, 0x004612f, 0x002a10f, 0x00daa, 0x00477, 0x00477, 0x00477, 0x00477, 0x009bb, 0x00262828, 0x00444646, 0x00636565, 0x00818383, 0x00a1a2a2, 0x00bebfbf, 0x00dedede, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x008aa, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007b2522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171415, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2020, 0x009e2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x00bf261e, 0x00a3211b, 0x00851d17, 0x006a1814, 0x004c1310, 0x003111f, 0x0014cc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00588, 0x001e1f1f, 0x003d3f3f, 0x005c5e5e, 0x007a7c7c, 0x00999a9a, 0x00b8b9b9, 0x00d6d6d6, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009d9e9e, 0x00477, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00582321, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00c6271f, 0x00aa231c, 0x008d1e18, 0x00711915, 0x00541411, 0x003711f, 0x001bed, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00181919, 0x00363838, 0x00555757, 0x00737575, 0x00929393, 0x00b0b1b1, 0x00cfcfcf, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00454747, 0x001ced, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00b92a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00542321, 0x009e2822, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00cd2820, 0x00b0241c, 0x00941f19, 0x00771a15, 0x005b1612, 0x003e12f, 0x002310f, 0x00888, 0x00477, 0x00477, 0x00477, 0x00477, 0x00101111, 0x002e3030, 0x004e5050, 0x006b6d6d, 0x008b8c8c, 0x00a8a9a9, 0x00c8c9c9, 0x00e6e7e7, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00699, 0x006d1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00742522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x005a2321, 0x00732522, 0x008c2722, 0x00a42923, 0x00bd2a23, 0x00d52c24, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00d32a21, 0x00b7251d, 0x009a201a, 0x007e1b16, 0x00621713, 0x004512f, 0x002810f, 0x00caa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00acc, 0x00272929, 0x00464848, 0x00656767, 0x00838484, 0x00a2a4a4, 0x00c0c1c1, 0x00e0e0e0, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00929393, 0x00477, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00434, 0x001f1c1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x003b2120, 0x00542321, 0x006c2421, 0x00862622, 0x009e2822, 0x00b72a23, 0x00d02c23, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2b21, 0x00be261e, 0x00a1211a, 0x00851d17, 0x00681813, 0x004c1310, 0x002f11f, 0x0013cc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00699, 0x00202121, 0x003e4040, 0x005e6060, 0x007b7d7d, 0x009b9c9c, 0x00b9baba, 0x00d8d8d8, 0x00f7f7f7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x002b2d2d, 0x002a10e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b22a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00362020, 0x004e2221, 0x00672421, 0x007f2622, 0x00992822, 0x00b12a23, 0x00ca2b23, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00c5271f, 0x00a8221b, 0x008c1e18, 0x006f1914, 0x00531411, 0x003712f, 0x0019ed, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00191a1a, 0x00383a3a, 0x00565858, 0x00757777, 0x00939494, 0x00b2b3b3, 0x00d1d1d1, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a1a2a2, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302020, 0x00482221, 0x00612421, 0x007a2522, 0x00922722, 0x00ab2923, 0x00c42b23, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00cb2820, 0x00af231c, 0x00921f19, 0x00761a15, 0x00591512, 0x003d12f, 0x0021fe, 0x00788, 0x00477, 0x00477, 0x00477, 0x00477, 0x00121313, 0x00303232, 0x004f5151, 0x006d6f6f, 0x008c8d8d, 0x00aaabab, 0x00c9caca, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x00151616, 0x002d10f, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00de2d24, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00532321, 0x008a2722, 0x00bd2a23, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00d22921, 0x00b5251d, 0x009a201a, 0x007c1b16, 0x00611612, 0x004312f, 0x002810f, 0x00b99, 0x00477, 0x00477, 0x00477, 0x00477, 0x00bdd, 0x00292b2b, 0x00484a4a, 0x00666868, 0x00858686, 0x00a3a5a5, 0x00e4e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x002c2e2e, 0x00daa, 0x00c5271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00502221, 0x00a62923, 0x00e22d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x00d62a21, 0x00c7271f, 0x00b6251d, 0x00a6221b, 0x00941f19, 0x00841c17, 0x00741a15, 0x004e1310, 0x0021cb, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00aeafaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c2c3c3, 0x00202222, 0x00caa, 0x00ac231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131011, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x00ae2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x00d22920, 0x00c0261e, 0x00b0241c, 0x00a0211a, 0x008f1e18, 0x007f1b16, 0x006f1914, 0x005f1612, 0x004e1310, 0x003e12f, 0x002d11f, 0x001ced, 0x00caa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00101111, 0x00222323, 0x00343636, 0x00464848, 0x00585a5a, 0x00686a6a, 0x007a7c7c, 0x008c8d8d, 0x009d9e9e, 0x00aeafaf, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00959696, 0x00b3b4b4, 0x00d2d2d2, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00bebfbf, 0x00525454, 0x00477, 0x0020fe, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00522221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00191516, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00542321, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00dc2b22, 0x00cc2820, 0x00bc261e, 0x00ab231c, 0x009b201a, 0x008b1d18, 0x007a1b16, 0x006a1814, 0x00581511, 0x00491210, 0x003911f, 0x002810f, 0x0018dd, 0x00888, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00588, 0x00171818, 0x00272929, 0x00393c3c, 0x004b4d4d, 0x005d5f5f, 0x006d6f6f, 0x007f8181, 0x00929393, 0x00a3a5a5, 0x00b5b6b6, 0x00c6c7c7, 0x00d8d8d8, 0x00e9eaea, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b5b6b6, 0x00477, 0x00477, 0x00477, 0x00477, 0x00131414, 0x00313333, 0x00505252, 0x006c6e6e, 0x00808282, 0x00909191, 0x008a8b8b, 0x00787a7a, 0x00505252, 0x00171818, 0x00477, 0x00eba, 0x00721915, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00732522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00b9a, 0x00131112, 0x001a1717, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00492221, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00ac231c, 0x005a1512, 0x0023fe, 0x00888, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00acc, 0x001b1c1c, 0x002c2e2e, 0x003e4040, 0x00505252, 0x00626363, 0x00747676, 0x00858686, 0x00979898, 0x00a8a9a9, 0x00babbbb, 0x00cbcbcb, 0x00dddddd, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e8e8, 0x00477, 0x005f1612, 0x00982019, 0x007b1b16, 0x005f1612, 0x00421210, 0x002610f, 0x00caa, 0x00477, 0x00477, 0x00477, 0x00999, 0x0020fe, 0x00511411, 0x00951f19, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x007b2522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00544, 0x00988, 0x00dcc, 0x00111010, 0x00161314, 0x001b1718, 0x001f1b1c, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x003611f, 0x00477, 0x00111212, 0x004d4f4f, 0x00737575, 0x008a8b8b, 0x009c9d9d, 0x00adaeae, 0x00bebfbf, 0x00d2d2d2, 0x00e3e4e4, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e6e6, 0x00477, 0x00831c17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00da2b21, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00602321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00877, 0x00cbb, 0x0011ef, 0x00151313, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007a2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x0016dc, 0x00141515, 0x00979898, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cbcbcb, 0x00477, 0x009e211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00a12822, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x002a10e, 0x00161717, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a5a6a6, 0x00477, 0x00bf261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00db2d24, 0x00942722, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201d1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a6221b, 0x00477, 0x00a1a2a2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00828383, 0x00477, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00c02b23, 0x00772522, 0x008f2722, 0x00a62923, 0x00b72a23, 0x00bc2a23, 0x00bb2a23, 0x00ad2923, 0x00972822, 0x00762522, 0x00492221, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151313, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00592321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00691814, 0x008aa, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x0017dc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00662421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00561511, 0x00212222, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003b3d3d, 0x003811f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00732522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191717, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00622421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00e10f, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00181919, 0x00581511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00582321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171415, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004b2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00941f19, 0x00477, 0x00c5c6c6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00477, 0x00791b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003c2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00fee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00271f20, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00caa, 0x00555757, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cdcdcd, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191616, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aa2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a1814, 0x00477, 0x00cfcfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00522221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92a21, 0x00eba, 0x004d4f4f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00858686, 0x00477, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00b02923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00191616, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bc2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00721915, 0x00477, 0x00c7c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x0013cb, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00952722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1b, 0x00151314, 0x00dbc, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00101, 0x00767, 0x00dcc, 0x00121010, 0x00161314, 0x00181516, 0x00171515, 0x00141212, 0x0010ee, 0x00988, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00522221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x0012cb, 0x00424444, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003e4040, 0x003411f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00782522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fde, 0x00656, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00dbb, 0x00141212, 0x001b1819, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00161414, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b42a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c1b16, 0x00477, 0x00bcbdbd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00101111, 0x005f1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00592321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00b9a, 0x00121010, 0x00191617, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004a2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0016cc, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00babbbb, 0x00477, 0x00982019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00878, 0x0010ee, 0x00171515, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00878, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ab2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00871d17, 0x00477, 0x00b0b1b1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003c3e3e, 0x0012bb, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00656, 0x00ecd, 0x00151313, 0x001d191a, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00992822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2920, 0x00477, 0x004c4e4e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00727474, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008b2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00cab, 0x00131111, 0x001b1818, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00656, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006d2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00381210, 0x00bdd, 0x00cbcbcb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d5d5d5, 0x004c4e4e, 0x00477, 0x005a1612, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00372020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00a89, 0x0011ff, 0x00191616, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00101, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004a2221, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00477, 0x009e9f9f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00e7e8e8, 0x00d6d6d6, 0x00c5c6c6, 0x00b3b4b4, 0x00a2a4a4, 0x00909191, 0x007e8080, 0x00626464, 0x002f3131, 0x00477, 0x00baa, 0x007d1b16, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00892722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00767, 0x00fde, 0x00161414, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00d32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00477, 0x00686a6a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00e0e0e0, 0x00cecece, 0x00bcbdbd, 0x00aaabab, 0x009a9b9b, 0x00888989, 0x00777979, 0x00656767, 0x00555757, 0x00434545, 0x00303232, 0x001f2020, 0x00eff, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x0015dc, 0x003b1210, 0x007d1b16, 0x00d72a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bd2a23, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00dbc, 0x00141213, 0x001c1819, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ae2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bd261e, 0x00ba9, 0x00393b3b, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00e8e9e9, 0x00d8d8d8, 0x00c6c7c7, 0x00b5b6b6, 0x00a3a5a5, 0x00929393, 0x007f8181, 0x006e7070, 0x005d5f5f, 0x004c4e4e, 0x003a3c3c, 0x00292b2b, 0x00181919, 0x00799, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00577, 0x0016dc, 0x002510f, 0x003612f, 0x004512f, 0x00561511, 0x00651713, 0x00761a15, 0x00851d17, 0x00971f19, 0x00a7221b, 0x00b7251d, 0x00c7281f, 0x00d72a21, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c32b23, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00b9a, 0x00121010, 0x001a1717, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00712522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x001eed, 0x001b1c1c, 0x00e4e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x00565858, 0x00444646, 0x00323434, 0x00202121, 0x00f1010, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00caa, 0x001cee, 0x002d11f, 0x003c12f, 0x004d1310, 0x005e1612, 0x006e1914, 0x007e1b16, 0x008e1e18, 0x009e211a, 0x00ae231c, 0x00be261e, 0x00cf2920, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00888, 0x0010ef, 0x00171516, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00423f3f, 0x006b6869, 0x00828080, 0x00807e7e, 0x00555253, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00471310, 0x00699, 0x00c2c3c3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x001e2020, 0x0011bb, 0x00351110, 0x004412f, 0x00551411, 0x00641713, 0x00751a15, 0x00841c17, 0x00961f19, 0x00a6221b, 0x00b7251d, 0x00c7271f, 0x00d72a21, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00b52a23, 0x00532321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00766, 0x00ecc, 0x00151314, 0x001d191a, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00646162, 0x00929091, 0x00c2c1c1, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c4c4, 0x002f2b2c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a62923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c1e18, 0x00477, 0x007d7f7f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00525454, 0x00688, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x00d32c23, 0x00c52b23, 0x00b32a23, 0x00952722, 0x006f2521, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00565354, 0x00858384, 0x00b4b3b3, 0x00e3e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a09e9f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004e2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00eba, 0x00383a3a, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00969797, 0x00477, 0x00771a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00db2d24, 0x00cd2c23, 0x00bf2b23, 0x00b12a23, 0x00a32823, 0x00942722, 0x00872622, 0x00782522, 0x006b2421, 0x005c2321, 0x004e2221, 0x00402121, 0x00322020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00484546, 0x00787677, 0x00a6a5a5, 0x00d6d5d5, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00877, 0x00cbb, 0x00fdd, 0x00211e1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b32a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00531411, 0x008aa, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d2d2d2, 0x00bdd, 0x003a1210, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00d42c23, 0x00c62b23, 0x00b82a23, 0x00aa2923, 0x009c2822, 0x008e2722, 0x00802622, 0x00732522, 0x00642421, 0x00562321, 0x00482221, 0x00392120, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003b3838, 0x006b6869, 0x00999798, 0x00c8c7c7, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00dbc, 0x00161414, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003e2121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x00707272, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x002c2e2e, 0x0013cb, 0x00d22921, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12923, 0x00792522, 0x006b2421, 0x005d2321, 0x00502221, 0x00412121, 0x00342020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302c2d, 0x005e5b5b, 0x008c8a8b, 0x00bbbaba, 0x00e9e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00181616, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00852622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005d1612, 0x00bdd, 0x00e6e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00676969, 0x00477, 0x00a3211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2b23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x003b2120, 0x003b2120, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00272324, 0x00514e4e, 0x007e7c7d, 0x00aeacad, 0x00dcdcdc, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bf2b23, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x0010bb, 0x00585a5a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00452221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00342020, 0x00412121, 0x00502221, 0x005d2321, 0x006b2421, 0x007a2522, 0x00872622, 0x00962822, 0x00a52923, 0x00b32a23, 0x00c12b23, 0x00cf2c23, 0x00dc2d24, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00ca2b23, 0x00842622, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00726f70, 0x00a09e9f, 0x00d0cfcf, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x001c1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00b9251d, 0x00477, 0x00a6a7a7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00131414, 0x002c10e, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00742522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2020, 0x00382120, 0x00472221, 0x00542321, 0x00642421, 0x00722522, 0x00802622, 0x008e2722, 0x009c2822, 0x00aa2923, 0x00b82a23, 0x00c62b23, 0x00d42c23, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2d24, 0x005d2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00646162, 0x00939192, 0x00c2c1c1, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0012f10, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00362020, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003c3e3e, 0x00baa, 0x00c6271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00be2a23, 0x004d2221, 0x005c2321, 0x00692421, 0x00772522, 0x00852622, 0x00932722, 0x00a12822, 0x00b12923, 0x00be2a23, 0x00cd2c23, 0x00da2d24, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00642421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2829, 0x00575454, 0x00868485, 0x00b4b3b3, 0x00e3e3e3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00442121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007e1b16, 0x00477, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007e8080, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92d23, 0x00d92a21, 0x00c8281f, 0x00b9251d, 0x00a8221b, 0x00992019, 0x00871d17, 0x00771a15, 0x00661713, 0x005b1612, 0x005c1612, 0x00801c16, 0x00d22921, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52d24, 0x003e2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00494646, 0x00797777, 0x00a7a5a6, 0x00d6d6d6, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00e2e3e3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00799, 0x004d1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00d32a21, 0x00c2271f, 0x00b1241c, 0x00a1211a, 0x00911f19, 0x00811c16, 0x00701914, 0x00611612, 0x00501410, 0x004112f, 0x002f11f, 0x001ffe, 0x00eba, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00dff, 0x001d1e1e, 0x001b1c1c, 0x00477, 0x00a99, 0x00982019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a82923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c3839, 0x00c9c8c8, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2020, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00477, 0x00a4a6a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003a3c3c, 0x0019ed, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00dc2b22, 0x00cb2820, 0x00bc261e, 0x00ab231c, 0x009b201a, 0x008b1d18, 0x007a1b16, 0x006a1814, 0x00591512, 0x00491210, 0x003911f, 0x002911f, 0x0018dd, 0x00999, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00151616, 0x00262727, 0x00373a3a, 0x00494b4b, 0x005a5c5c, 0x006b6d6d, 0x007d7f7f, 0x008e8f8f, 0x00a0a1a1, 0x00b2b3b3, 0x00c3c4c4, 0x00d5d5d5, 0x00e6e7e7, 0x00f7f7f7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dadada, 0x003b3d3d, 0x00788, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00502221, 0x00812622, 0x00a42923, 0x00bc2a23, 0x00c92b23, 0x00c92b23, 0x00ba2a23, 0x00a22822, 0x00732522, 0x003a2120, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x001ced, 0x00393b3b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00477, 0x004c1310, 0x00a5221b, 0x00a4221b, 0x00941f19, 0x00841c17, 0x00731a15, 0x00631713, 0x00531411, 0x004312f, 0x00331210, 0x002310f, 0x0012cb, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00acc, 0x001a1c1b, 0x002c2e2e, 0x003e4040, 0x004f5151, 0x00616262, 0x00737575, 0x00858686, 0x00969797, 0x00a7a8a8, 0x00b8b9b9, 0x00cacaca, 0x00dcdcdc, 0x00eceded, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x00151616, 0x004d1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00982822, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00b72a23, 0x00562321, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00821c17, 0x00477, 0x00bebfbf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x003e4040, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00101111, 0x00222323, 0x00343636, 0x00464848, 0x00575959, 0x00686a6a, 0x007a7c7c, 0x008b8c8c, 0x009d9e9e, 0x00adaeae, 0x00c0c1c1, 0x00d2d2d2, 0x00e3e4e4, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00616262, 0x0012cb, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008e2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c6c5c5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003a2120, 0x00a82923, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c42b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0012bb, 0x00464848, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dadada, 0x00c2c3c3, 0x00cdcdcd, 0x00d9d9d9, 0x00e9eaea, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007f8181, 0x00477, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bab9b9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00722522, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x00c6271f, 0x00b1241c, 0x00ab231c, 0x00bd261e, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00761a15, 0x00477, 0x00cacaca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00eba, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00932722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bdbbbc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x009a2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82a21, 0x007f1b16, 0x003712f, 0x00788, 0x00477, 0x00477, 0x00477, 0x00477, 0x00688, 0x00391210, 0x00971f19, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x00daa, 0x00535555, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x001c1d1d, 0x00451310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00772522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cfcece, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00383435, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00631713, 0x00898, 0x00477, 0x00373939, 0x00787a7a, 0x00a7a8a8, 0x00bbbcbc, 0x00bbbcbc, 0x00a5a6a6, 0x00707272, 0x00212323, 0x00477, 0x002d10f, 0x00c5271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a1814, 0x00588, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a0a1a1, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00492221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00e8e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00862622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a5221b, 0x0015cc, 0x00699, 0x00676969, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00a2a4a4, 0x00151616, 0x0011cb, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00999, 0x00616262, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eceded, 0x001a1b1b, 0x002d10f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332f30, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccbcb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c2221, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008b1d18, 0x00477, 0x00323434, 0x00d1d1d1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dbdbdb, 0x001d1f1f, 0x0019dc, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005d1612, 0x00799, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00565858, 0x00688, 0x00b9251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00782522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00676465, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00747272, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c12b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c201a, 0x00477, 0x004b4d4d, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c6c7c7, 0x00588, 0x00671813, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2820, 0x00577, 0x006d6f6f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a0a1a1, 0x00477, 0x00731a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a7a5a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9c8c8, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1717, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00582321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00fbb, 0x00353737, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00565858, 0x00eba, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00511511, 0x00cee, 0x00e9eaea, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x00f1010, 0x003311f, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005c2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cbcacb, 0x00302c2d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ae2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005d1612, 0x00799, 0x00d7d7d7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a7a8a8, 0x00477, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c0261e, 0x00477, 0x007a7c7c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00393b3b, 0x00eba, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00727070, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x007f7d7e, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2b21, 0x00a99, 0x005f6060, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cdcdcd, 0x00477, 0x00992019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00451310, 0x00131414, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007d7f7f, 0x00477, 0x00901e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00dbdada, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00d1d0d1, 0x00a4a2a2, 0x00737171, 0x00413e3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151313, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00912722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c1b16, 0x00477, 0x00cdcdcd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cacaca, 0x00477, 0x00982019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b3241d, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x00699, 0x004d1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x004b2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00757273, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dedede, 0x00b0afaf, 0x00817f7f, 0x00524f50, 0x00292526, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x001ded, 0x003b3d3d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a9aaaa, 0x00477, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00bf2b23, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003811f, 0x001a1b1b, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00222424, 0x001bed, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00822622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2a2b, 0x00e7e6e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ececec, 0x00bdbcbd, 0x008e8c8c, 0x005f5c5d, 0x00322e2f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00722522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009f211a, 0x00477, 0x00a6a7a7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005d5f5f, 0x00baa, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x007e2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a7221b, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005d5f5f, 0x00477, 0x00af231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bb2a23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a4a2a2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cac9ca, 0x009b999a, 0x006c6a6a, 0x003e3a3b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131011, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c92b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003b1210, 0x001c1d1d, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00dff, 0x00561511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006e2521, 0x002d2020, 0x00df2d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x002d10e, 0x00212323, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a7a7, 0x00477, 0x006c1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00464344, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00d7d7d7, 0x00a9a7a8, 0x007a7878, 0x004b4748, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c3271f, 0x00477, 0x00828383, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008e8f8f, 0x00477, 0x00b8251d, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00302020, 0x00231f20, 0x00892722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c201a, 0x00477, 0x00a2a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00121313, 0x002e10f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00e5e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e4e4e4, 0x00b6b4b5, 0x00878585, 0x00585555, 0x002c292a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aa2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e1612, 0x009bb, 0x00e6e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00232525, 0x003010f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a32823, 0x00231f20, 0x00231f20, 0x00322020, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x0024fe, 0x002c2e2e, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x003f4141, 0x00b99, 0x00c7281f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a22822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00807e7f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c3c2c2, 0x00949293, 0x00656262, 0x00373334, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00baa, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b1b2b2, 0x00477, 0x00951f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00932722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00b0b1b1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00858686, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32c23, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2c2c, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0cfcf, 0x00a2a0a1, 0x00726f70, 0x00444041, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008e2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00811c16, 0x00477, 0x00c8c9c9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00474949, 0x0017dc, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00c12b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x001adc, 0x00393b3b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cacaca, 0x008aa, 0x00471310, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00502221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a7a6a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dddddd, 0x00aeacad, 0x007f7d7e, 0x00514e4e, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x0021fd, 0x00363838, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x00477, 0x00711915, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009e2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00831c17, 0x00477, 0x00b7b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00262828, 0x0018dc, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00882622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c3839, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00423f3f, 0x00423f3f, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2521, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a4221b, 0x00477, 0x00a1a3a3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x00788, 0x00d22921, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2d24, 0x00c62b23, 0x00a92923, 0x00832622, 0x005c2321, 0x00342020, 0x00402121, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x001eed, 0x00232525, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00e8e9e9, 0x00d8d8d8, 0x00c6c7c7, 0x00b5b6b6, 0x00a3a5a5, 0x00939494, 0x00808282, 0x006f7171, 0x005e6060, 0x00343737, 0x00477, 0x00a9231b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c02b23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aeacad, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x003b3838, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x006c6a6a, 0x009a9899, 0x00c9c8c8, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00dedede, 0x00555253, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00989, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c62b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003f1210, 0x00191a1a, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00f1111, 0x004f1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b2241d, 0x00999, 0x002a2c2c, 0x00d2d2d2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00dedede, 0x00cdcdcd, 0x00bcbdbd, 0x00aaabab, 0x009a9b9b, 0x00888989, 0x00777979, 0x00656767, 0x00555757, 0x00444646, 0x00313333, 0x001f2020, 0x00f1010, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00baa, 0x001bed, 0x002c11f, 0x00741a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x003e2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00474445, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322e2f, 0x005f5c5d, 0x008d8b8c, 0x00bdbcbd, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00502221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c7271f, 0x00477, 0x007d7f7f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00929393, 0x00477, 0x00b3241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ad231c, 0x0014cc, 0x00799, 0x005c5e5e, 0x00b2b3b3, 0x00e2e3e3, 0x00efefef, 0x00e6e7e7, 0x00d5d5d5, 0x00c4c5c5, 0x00b2b3b3, 0x00a1a3a3, 0x008f9090, 0x007e8080, 0x006c6e6e, 0x005c5e5e, 0x004a4c4c, 0x00393c3c, 0x00282a2a, 0x00171818, 0x00699, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00577, 0x0015dc, 0x002510f, 0x00351110, 0x004512f, 0x00551411, 0x00641713, 0x00751a15, 0x00841c17, 0x00951f19, 0x00a6221b, 0x00b6251d, 0x00c6271f, 0x00d62a21, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b0aeaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00535051, 0x00828080, 0x00b1b0b0, 0x00dfdedf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009d9b9b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a72923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00799, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00272929, 0x002d10f, 0x00ee2e24, 0x00df2c22, 0x00bd261e, 0x00a2211b, 0x00961f19, 0x009b201a, 0x00b7251d, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92a21, 0x00651713, 0x00daa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00daa, 0x001dfe, 0x002d11f, 0x003e11f, 0x004e1310, 0x005f1612, 0x006e1914, 0x007e1b16, 0x008f1e18, 0x009e211a, 0x00af231c, 0x00be261e, 0x00cf2920, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a92923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302c2d, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00484546, 0x00777475, 0x00a5a4a4, 0x00d3d2d2, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcece, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x00daa, 0x00585a5a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b6b7b7, 0x00477, 0x002eec, 0x002e11f, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x001bed, 0x00481310, 0x00761a15, 0x00a3211b, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00af231c, 0x008c1e18, 0x00871d17, 0x00881d17, 0x00982019, 0x00a8221b, 0x00b8251d, 0x00c8281f, 0x00d82a21, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72c24, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00636061, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c3839, 0x006b6969, 0x00999798, 0x00c8c7c7, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008a2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00861d17, 0x00477, 0x00c3c4c4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004b4d4d, 0x00477, 0x00588, 0x003d3f3f, 0x00787a7a, 0x00adaeae, 0x00c6c7c7, 0x00d6d6d6, 0x00d2d2d2, 0x00b3b4b4, 0x00888989, 0x00575959, 0x00262828, 0x00477, 0x00477, 0x00477, 0x0014cc, 0x00411210, 0x006e1914, 0x009a201a, 0x00c9281f, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00d62c24, 0x00c72b23, 0x00b92a23, 0x00ab2923, 0x009e2822, 0x00902722, 0x00822622, 0x004a2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00848182, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322e2f, 0x005f5c5d, 0x008d8b8c, 0x00bdbbbc, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c1c0c0, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00db2d24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x0023fe, 0x00313333, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dbdbdb, 0x001e2020, 0x00828383, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c1c2c2, 0x008f9090, 0x00606161, 0x002d2f2f, 0x00799, 0x00477, 0x00477, 0x00daa, 0x00391210, 0x00651713, 0x00941f19, 0x00c0261e, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00dc2d24, 0x00cd2c23, 0x00c02b23, 0x00b22a23, 0x00a42923, 0x00962722, 0x00872622, 0x00792522, 0x006b2421, 0x005e2321, 0x00502221, 0x00422121, 0x00342020, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00918f90, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00535051, 0x00828080, 0x00b1b0b0, 0x00dfdedf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008e8c8c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006b2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a7221b, 0x00477, 0x009e9f9f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e1e2e2, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00c9caca, 0x00999a9a, 0x00676969, 0x00373939, 0x00acc, 0x00477, 0x00477, 0x00999, 0x003111f, 0x005f1612, 0x008c1e18, 0x00b9251d, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2d24, 0x00b32a23, 0x008b2722, 0x00642421, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a3a1a1, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00474445, 0x00777475, 0x00a5a4a4, 0x00d3d2d2, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00441310, 0x00161717, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00d2d2d2, 0x00a1a2a2, 0x006f7171, 0x003f4141, 0x00101111, 0x00477, 0x00477, 0x00688, 0x002910f, 0x00571511, 0x00841c17, 0x00b1241c, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02d24, 0x00b92a23, 0x00922722, 0x006b2421, 0x00432121, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00636061, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00494646, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003b3838, 0x006b6869, 0x00989697, 0x00c7c6c6, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bab9b9, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ff, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004d2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2820, 0x00477, 0x00787a7a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00dadada, 0x00a8a9a9, 0x00787a7a, 0x00474949, 0x00171818, 0x00477, 0x00477, 0x00477, 0x0023fe, 0x004e1310, 0x007d1b16, 0x00a9231b, 0x00d72a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d24, 0x00c02b23, 0x009a2822, 0x00712522, 0x004b2221, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00625f60, 0x00413e3f, 0x00615e5f, 0x008d8b8c, 0x00bcbabb, 0x00eaeaea, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004d4a4b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00434, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a32823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00671813, 0x00699, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e1e2e2, 0x00b1b2b2, 0x00808282, 0x00505252, 0x001e2020, 0x00477, 0x00477, 0x00477, 0x0019dd, 0x00471310, 0x00741a15, 0x00a2211b, 0x00cf2920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00c72b23, 0x009c2822, 0x00682421, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bbbaba, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00352020, 0x00e92e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00fba, 0x00535555, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00b9baba, 0x00898a8a, 0x00585a5a, 0x00272929, 0x00477, 0x00477, 0x00477, 0x0012cb, 0x004012f, 0x006d1814, 0x009a201a, 0x00c7281f, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52d24, 0x00982822, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00272324, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00484546, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00bfc0c0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00c2c3c3, 0x00919292, 0x00606161, 0x002f3131, 0x00799, 0x00477, 0x00477, 0x00daa, 0x003812f, 0x00651713, 0x00911f19, 0x00c0261e, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00662421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00494646, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b4b3b3, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x0027fe, 0x002d2f2f, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cacaca, 0x00999a9a, 0x00686a6a, 0x00373939, 0x00cee, 0x00477, 0x00477, 0x00888, 0x003011f, 0x005d1612, 0x008b1d18, 0x00bb251e, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00752522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008d8b8c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00474445, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00672421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x00477, 0x00999a9a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00d2d2d2, 0x00a2a4a4, 0x00707272, 0x00404242, 0x00101111, 0x00477, 0x00477, 0x0010bb, 0x00551511, 0x00c2271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00562321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00d3d2d2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0aeaf, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00be2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00491310, 0x00141515, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dbdbdb, 0x00a4a6a6, 0x005e6060, 0x00bdd, 0x00688, 0x007d1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00494646, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171415, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00492221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ce2920, 0x00577, 0x00727474, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x004f5151, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00642421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00adacac, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a02822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b1814, 0x00588, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003d3f3f, 0x0011bb, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00a62923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00d0cfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322020, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x0011bb, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b3b4b4, 0x00477, 0x00a6221b, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00151313, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00464243, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00832622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00b8b9b9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e4e5e5, 0x00477, 0x00871d17, 0x00ee2e24, 0x00ee2e24, 0x00e02d24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00211, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00858384, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d52c24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x002b10e, 0x00292b2b, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dedede, 0x00477, 0x008a1d18, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00cbcacb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00632421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00477, 0x00949595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x00ae231c, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00838181, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00767, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004d1411, 0x00101111, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00595b5b, 0x0011bb, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00a32823, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00dbc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00e1e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00452221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12920, 0x00688, 0x006e7070, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e9e9, 0x009bb, 0x005d1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006c2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x001e1b1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00726f70, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009c2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f1914, 0x00477, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00828383, 0x00477, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00e52d24, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00dcdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00c8c7c7, 0x00787576, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x0014cb, 0x004a4c4c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x001d1f1f, 0x003a1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00686566, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfbfc, 0x00d3d2d2, 0x00a5a4a4, 0x00777475, 0x00484546, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007e2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00452221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d3d2d2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x00b1b0b0, 0x00838181, 0x00545152, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00656, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002e10f, 0x00252727, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003d3f3f, 0x001ced, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00bb2a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00655, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00615e5f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00bebdbd, 0x008f8d8d, 0x00615e5f, 0x00332f30, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00602421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b4241d, 0x00477, 0x00909191, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcfcf, 0x00477, 0x007a1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cac9c9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cac9ca, 0x009b999a, 0x006d6b6b, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b72a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00521511, 0x00e1010, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00999, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00d52c24, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbb, 0x00000, 0x001a1717, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00585555, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00d6d6d6, 0x00a8a6a7, 0x007a7878, 0x004b4748, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00788, 0x00696b6b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d5d5d5, 0x00d2d2d2, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00bdd, 0x00581512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00100, 0x00767, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e3e3, 0x00b4b3b3, 0x00868485, 0x00575454, 0x002c292a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00982822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00731a15, 0x00477, 0x00d5d5d5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00383a3a, 0x00477, 0x00acc, 0x00373939, 0x00676969, 0x00999a9a, 0x00c9caca, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00898a8a, 0x00477, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00322020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00111010, 0x00000, 0x00191516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004e4b4c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efeeee, 0x00c1c0c0, 0x00929091, 0x00646162, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2020, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x0018dc, 0x00444646, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9caca, 0x00477, 0x00571511, 0x00661713, 0x003911f, 0x00daa, 0x00477, 0x00477, 0x00799, 0x002f3131, 0x00606161, 0x00919292, 0x00c2c3c3, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00202222, 0x003511f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a02822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00545, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfbfc, 0x00cdcccc, 0x009e9d9d, 0x00706d6e, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007b2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00971f19, 0x00477, 0x00afb0b0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x00b99, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00c9281f, 0x009a201a, 0x006e1914, 0x004012f, 0x0013cb, 0x00477, 0x00477, 0x00477, 0x00272929, 0x00595b5b, 0x00898a8a, 0x00bbbcbc, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00adaeae, 0x00477, 0x00992019, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00492221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00474445, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00d02c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003211f, 0x00222424, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e9e9, 0x009bb, 0x005c1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2920, 0x00a3211b, 0x00741a15, 0x00481310, 0x0019dd, 0x00477, 0x00477, 0x00477, 0x00202221, 0x00505252, 0x00828383, 0x00b2b3b3, 0x00e4e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00424444, 0x0018dc, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00be2a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b0aeaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2829, 0x00575454, 0x00868485, 0x00b0aeaf, 0x00c7c6c6, 0x00c2c1c1, 0x00918f90, 0x00332f30, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ba251e, 0x00477, 0x008b8c8c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00838484, 0x00477, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72a21, 0x00a9231b, 0x007c1b16, 0x004e1310, 0x0021fe, 0x00477, 0x00477, 0x00477, 0x00181919, 0x004a4c4c, 0x00797b7b, 0x00abacac, 0x00dcdcdc, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d3d3d3, 0x00477, 0x00761a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00545, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00413e3f, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x004a4747, 0x00797777, 0x00a8a6a7, 0x00d6d6d6, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e7e7, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b02923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00561511, 0x00cee, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x001d1f1f, 0x003a1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c42b23, 0x00bd2a23, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00b1241c, 0x00831c17, 0x00551411, 0x002810f, 0x00577, 0x00477, 0x00477, 0x00121313, 0x00414343, 0x00737575, 0x00a3a5a5, 0x00d5d5d5, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00676969, 0x00898, 0x00d52a21, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00dbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a19fa0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x006c6a6a, 0x009b999a, 0x00cac9c9, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0afaf, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00101, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82a21, 0x00999, 0x00646666, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00452221, 0x00231f20, 0x00241f20, 0x00402121, 0x00672421, 0x008f2722, 0x00b72a23, 0x00de2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00b8251d, 0x00891d17, 0x005d1612, 0x002e11f, 0x00888, 0x00477, 0x00477, 0x00cee, 0x003a3c3c, 0x006b6d6d, 0x009c9d9d, 0x00cdcdcd, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00cee, 0x00541512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00872622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00111, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312d2e, 0x005f5c5c, 0x008d8b8c, 0x00bdbbbc, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00652421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00871d17, 0x00477, 0x00c9caca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003e4040, 0x001ced, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00b92a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00522221, 0x00892722, 0x00c12b23, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x00bd261e, 0x00911f19, 0x00631713, 0x003712f, 0x00baa, 0x00477, 0x00477, 0x008aa, 0x00323434, 0x00636565, 0x00959696, 0x00c5c6c6, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00636565, 0x00577, 0x00c7281f, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00474445, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00524e4f, 0x00807e7e, 0x00b0aeaf, 0x00dedede, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00363233, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008a2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1310, 0x001d1e1e, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcfcf, 0x00477, 0x007a1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x006c2421, 0x00b52a23, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x00c6271f, 0x00982019, 0x006b1814, 0x003c12f, 0x0010bb, 0x00477, 0x00477, 0x00588, 0x002a2c2c, 0x005d5f5f, 0x008c8d8d, 0x00bebfbf, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a7a7, 0x00477, 0x005e1613, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00434, 0x00000, 0x00000, 0x00171516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00625f60, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00454142, 0x00737171, 0x00a3a1a1, 0x00d1d0d1, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a02822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a11f, 0x00474949, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00999, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00d52c24, 0x00251f20, 0x00231f20, 0x00251f20, 0x00752522, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00cc2820, 0x009f211a, 0x00711915, 0x00431210, 0x0017dc, 0x00477, 0x00477, 0x00477, 0x00242626, 0x00545656, 0x00868787, 0x00b5b6b6, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009e9f9f, 0x00799, 0x002e11f, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00686566, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00383435, 0x00666464, 0x00969494, 0x00c4c3c4, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002510f, 0x004e5050, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00bdd, 0x00581512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00812622, 0x00231f20, 0x00422121, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00df2c22, 0x00df2c22, 0x00de2b22, 0x00d12920, 0x00d12920, 0x00d12920, 0x00c9281f, 0x00c2271f, 0x00c2271f, 0x00c2271f, 0x00b3241d, 0x00b3241d, 0x00b3241d, 0x00ac231c, 0x00a5221b, 0x00a5221b, 0x00a5221b, 0x009a201a, 0x00a6221b, 0x00c9281f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00a6221b, 0x00781a15, 0x004b1310, 0x001ded, 0x00477, 0x00477, 0x00477, 0x001c1d1d, 0x004d4f4f, 0x007d7f7f, 0x00aeafaf, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x004d4f4f, 0x00477, 0x002f10f, 0x00d62a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00686566, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a4a2a2, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2a2a, 0x00595657, 0x00898787, 0x00b7b5b6, 0x00e6e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00972822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003d1210, 0x002f3131, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00666868, 0x00477, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00312020, 0x00642421, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00b6251d, 0x006f1914, 0x00401210, 0x002710f, 0x002110f, 0x0018ed, 0x0012cb, 0x0012cb, 0x0011cc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x001bed, 0x00731a15, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00db2b22, 0x00ac231c, 0x00801c16, 0x00511411, 0x002510e, 0x00477, 0x00477, 0x00477, 0x00151616, 0x00414343, 0x005b5d5d, 0x00626363, 0x004e5050, 0x001c1d1d, 0x00477, 0x00a99, 0x00731a15, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004a4747, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x004c494a, 0x007c797a, 0x00aaa8a8, 0x00d9d8d9, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00777, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00772522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00731a15, 0x00588, 0x00e0e1e1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aaabab, 0x00477, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009e2822, 0x00712522, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00941f19, 0x0026fe, 0x00477, 0x00699, 0x00303232, 0x00535555, 0x00626363, 0x00626363, 0x00626464, 0x00717373, 0x00717373, 0x00717373, 0x00797b7b, 0x00818383, 0x00818383, 0x00818383, 0x00919292, 0x00919292, 0x00919292, 0x00999a9a, 0x00a1a2a2, 0x00a1a2a2, 0x00a1a2a2, 0x00b0b1b1, 0x00b0b1b1, 0x00b0b1b1, 0x00b7b8b8, 0x00c0c1c1, 0x00c0c1c1, 0x00c0c1c1, 0x00cfcfcf, 0x00d0d0d0, 0x00d0d0d0, 0x00c4c5c5, 0x00979898, 0x00484a4a, 0x00477, 0x0018dc, 0x00ae231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02c22, 0x00b5251d, 0x00851d17, 0x00591512, 0x003711f, 0x001dfe, 0x001aed, 0x002410e, 0x004d1310, 0x00871d17, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22c23, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbb, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00676465, 0x004e4b4c, 0x006f6c6d, 0x009d9b9b, 0x00cccbcb, 0x00f7f7f7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00462221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00577, 0x00656767, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aeafaf, 0x009bb, 0x003111f, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x007f2622, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2820, 0x00351110, 0x00477, 0x002b2d2d, 0x009a9b9b, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9caca, 0x00282a2a, 0x00999, 0x00ab231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008c8a8b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00477, 0x00a2a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00787a7a, 0x00588, 0x003111f, 0x00db2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ae2923, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ad231c, 0x0010bb, 0x00f1110, 0x00989999, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x002a2c2c, 0x0013cb, 0x00db2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x008e2722, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x003611f, 0x00588, 0x007b7d7d, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00a0a1a1, 0x00232524, 0x00477, 0x005a1612, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ce2c23, 0x00d52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00999, 0x00272929, 0x00dadada, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cdcdcd, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00312020, 0x00582321, 0x00802622, 0x00a72923, 0x00cf2c23, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00972822, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00585555, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c42b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x004f1411, 0x00477, 0x001b1c1c, 0x006e7070, 0x00b3b4b4, 0x00cdcdcd, 0x00dadada, 0x00c4c5c5, 0x009fa0a0, 0x005e6060, 0x00161717, 0x00477, 0x002d10f, 0x00b1241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00c12b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2820, 0x0012cb, 0x00252727, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c4e4e, 0x0014cb, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00d52c23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00522221, 0x00762522, 0x00912722, 0x009e2822, 0x00a22823, 0x00912722, 0x00782522, 0x004f2221, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a5a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003f2121, 0x00e12d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x00411310, 0x00577, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x0017dc, 0x00531411, 0x00b1241c, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x009a2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x002c10e, 0x00101111, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b2b3b3, 0x00477, 0x00961f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2b2c, 0x00e9e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00af231c, 0x00971f19, 0x00982019, 0x00ab231c, 0x00c7271f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a32823, 0x00672421, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00531512, 0x00477, 0x00aeafaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00212323, 0x003711f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00676465, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00cc2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00602421, 0x00402121, 0x00e22d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00831c17, 0x00477, 0x007b7d7d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00858686, 0x00477, 0x00c1271e, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003c2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b6b4b5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00812622, 0x00df2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c72b23, 0x006f2521, 0x00281f20, 0x002d2020, 0x00cc2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00688, 0x00484a4a, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e8e8, 0x008aa, 0x00611612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008d2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00383435, 0x00f1f1f1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00373334, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x006a2421, 0x00a72923, 0x00d62c24, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00d82c24, 0x00b32a23, 0x00832622, 0x00452221, 0x00231f20, 0x00231f20, 0x00241f20, 0x00aa2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22920, 0x0016cc, 0x00232525, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00585a5a, 0x00daa, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00dc2d24, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00787576, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00272324, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00666, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00302020, 0x00302020, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007f2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x003211f, 0x00dff, 0x00d0d0d0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bfc0c0, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00888, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00c6c5c5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c7c6c6, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00582321, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005b1612, 0x00477, 0x00a4a6a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x002b2d2d, 0x002c10e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc2a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00191616, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00423f3f, 0x00f7f7f7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006d6b6b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2120, 0x00de2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008b1d18, 0x00477, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00919292, 0x00477, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00442121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001d191a, 0x00161314, 0x00dbc, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00898787, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bfbebe, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00c62b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b7251d, 0x00999, 0x00414343, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00dff, 0x00561511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00545, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00d4d3d3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bfbebe, 0x002c2829, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00777, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72a21, 0x001adc, 0x001d1f1f, 0x00e8e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00636565, 0x00999, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004e4b4c, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00d2d1d2, 0x00726f70, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00141213, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00782522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x003912f, 0x00acc, 0x00c9caca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00477, 0x00801c16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00722522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00999798, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00c4c3c4, 0x00969494, 0x00666464, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00171415, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00522221, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00641713, 0x00477, 0x009c9d9d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00363838, 0x0022fd, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00e1e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfbfc, 0x00d3d2d2, 0x00a5a4a4, 0x00767374, 0x00464344, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x00db2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00951f19, 0x00477, 0x00666868, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009e9f9f, 0x00477, 0x00aa231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c595a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e2e2, 0x00b4b3b3, 0x00848283, 0x00555253, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00c02b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bd261e, 0x00ba9, 0x00393b3b, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00131414, 0x004a1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aaa9a9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00c3c2c2, 0x00949293, 0x00646162, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009a2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00db2b22, 0x0020ed, 0x001a1b1b, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00707272, 0x00688, 0x00d22920, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00989, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312d2e, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00d1d0d1, 0x00a3a1a1, 0x00727070, 0x00454142, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x003f1210, 0x008aa, 0x00c1c2c2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x00477, 0x00751a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00696667, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x00b1b0b0, 0x00838181, 0x00535051, 0x00292526, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c2221, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d1814, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00dcdcdc, 0x00d0d0d0, 0x00d0d0d0, 0x00d0d0d0, 0x00d0d0d0, 0x00dedede, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00424444, 0x0019dc, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ce2c23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b8889, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efeeee, 0x00c1c0c0, 0x00918f90, 0x00625f60, 0x00333031, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332020, 0x00d62c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009e211a, 0x00477, 0x005e6060, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d2d2d2, 0x00646666, 0x00626363, 0x00626363, 0x00525454, 0x00525454, 0x00505252, 0x00424444, 0x00424444, 0x003d3f3f, 0x00323535, 0x00323434, 0x002a2b2b, 0x00222424, 0x00222323, 0x00181919, 0x00171919, 0x00cbcbcb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00444646, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aaabab, 0x00477, 0x009f211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00562321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dcc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00605d5e, 0x00d9d8d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0cfcf, 0x00a09e9f, 0x00716e6f, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00b12a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00daa, 0x00323434, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00252727, 0x00898, 0x0018ed, 0x0021fe, 0x0021fe, 0x002a1110, 0x002f11f, 0x002f11f, 0x003b1311, 0x003e11e, 0x003e11e, 0x004c1310, 0x004c1310, 0x004f1410, 0x0015a9, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989999, 0x00477, 0x00591512, 0x00961f19, 0x00961f19, 0x00a5221b, 0x009f211a, 0x00531411, 0x00477, 0x00dadada, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x001b1c1c, 0x003e1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a22822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x004f4c4d, 0x00838181, 0x009e9c9c, 0x00999798, 0x007e7b7c, 0x00514e4e, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00464344, 0x00767374, 0x00a19fa0, 0x00bfbebe, 0x00c0bfbf, 0x009f9d9e, 0x004c4849, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x0024fe, 0x00151616, 0x00dedede, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004d4f4f, 0x00688, 0x00ad231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009f211a, 0x00477, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cbcbcb, 0x00acc, 0x00391210, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003811f, 0x00181919, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007b7d7d, 0x00477, 0x00ce2920, 0x00ee2e24, 0x00ee2e24, 0x00d82c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003a3738, 0x00696667, 0x00979696, 0x00c6c5c5, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00666464, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004d1411, 0x00699, 0x00babbbb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00838484, 0x00477, 0x007c1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c6271f, 0x00eba, 0x00303232, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00222424, 0x0017dc, 0x00d52a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c1e18, 0x00477, 0x00939494, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cecece, 0x00477, 0x00931f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2a2b, 0x005c595a, 0x008b8889, 0x00b9b8b8, 0x00e9e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e5e5, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009d211a, 0x00477, 0x007f8181, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00588, 0x004b1411, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x0026fe, 0x00141515, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004c4e4e, 0x00688, 0x00b1241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c2271f, 0x00b99, 0x00404242, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00477, 0x00791b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00272324, 0x00504d4d, 0x007e7b7c, 0x00acabab, 0x00dcdbdb, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00413e3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x002610e, 0x00282a2a, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dfdfdf, 0x00151616, 0x0024fe, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00892722, 0x007c2622, 0x00b52a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x004b1411, 0x00588, 0x00b7b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00848585, 0x00477, 0x007d1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x0025fe, 0x00151616, 0x00e3e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x00477, 0x007b1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00716e6f, 0x00a09e9f, 0x00cfcece, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2020, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00b2241d, 0x00477, 0x009b9c9c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00343636, 0x00daa, 0x00c4271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b72a23, 0x00251f20, 0x00231f20, 0x00442121, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007a1b16, 0x00477, 0x00848585, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bcbdbd, 0x00699, 0x00481311, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00541512, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcfcf, 0x00477, 0x00961f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1818, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00363233, 0x00646162, 0x00939192, 0x00c2c1c1, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00588, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d62c24, 0x00322020, 0x00231f20, 0x002e2020, 0x00d02c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a9231b, 0x00577, 0x00505252, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00191a1a, 0x0022fd, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00757777, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008d8e8e, 0x00477, 0x00c9281f, 0x00ee2e24, 0x00ee2e24, 0x00d62c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c292a, 0x00575454, 0x00878585, 0x00b5b3b4, 0x00e3e3e3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00692421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1310, 0x00262828, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009b9c9c, 0x00477, 0x00681813, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x004c2221, 0x00231f20, 0x00241f20, 0x00af2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2820, 0x0013cb, 0x00282a2a, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x003c3e3e, 0x00a99, 0x00be261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00baa, 0x003b3d3d, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x002e3030, 0x002910e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a42923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00101, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x004b4748, 0x007a7878, 0x00a8a6a7, 0x00d7d7d7, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00434, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003e11e, 0x003d3f3f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cacaca, 0x00acc, 0x003912f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00652421, 0x006f2522, 0x009a2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x002d10f, 0x00f1010, 0x00d5d5d5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00727474, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0028fe, 0x00151616, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ef, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003e3a3b, 0x006d6b6b, 0x009b999a, 0x00cac9ca, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006c2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004712f, 0x00292b2b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00222424, 0x0019dc, 0x00d62a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00551512, 0x00477, 0x00abacac, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x00591612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00581512, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x001d1f1f, 0x0025fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332f30, 0x00605d5e, 0x008e8c8c, 0x00bebdbd, 0x00ececec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00532321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006e1914, 0x00799, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00616262, 0x00477, 0x00ae231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00861d17, 0x00477, 0x00767878, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dadada, 0x00101111, 0x002d10f, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00921f19, 0x00477, 0x00757777, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00565858, 0x00577, 0x00b3241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00802622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00535051, 0x00828080, 0x00b1b0b0, 0x00dfdedf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00b3241d, 0x00477, 0x009c9d9d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x00477, 0x00651713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b2241d, 0x00788, 0x00454747, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x002f3131, 0x00fba, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00baa, 0x00383a3a, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9b9b, 0x00477, 0x00731a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c595a, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x0022fd, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bebfbf, 0x00477, 0x002f10e, 0x00531411, 0x005b1612, 0x005b1612, 0x00591512, 0x004c1310, 0x004c1310, 0x004c1310, 0x004111f, 0x003e11e, 0x003e12f, 0x00391311, 0x0011bb, 0x00212323, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00606161, 0x00477, 0x00a1211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0028fe, 0x00141515, 0x00dfdfdf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d4d4d4, 0x00cee, 0x003912f, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00592321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00712522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007b1b16, 0x00477, 0x00d4d4d4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00868787, 0x00373939, 0x00222323, 0x00161717, 0x00212121, 0x00222424, 0x00222424, 0x002a2b2b, 0x00323434, 0x00323535, 0x00343737, 0x00424444, 0x00424444, 0x00424444, 0x00cbcbcb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9b9b, 0x00477, 0x006b1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005b1612, 0x00477, 0x00afb0b0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x002e3030, 0x0012cb, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00787677, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00577, 0x00727474, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00acc, 0x00391210, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00961f19, 0x00477, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00686a6a, 0x00477, 0x00a0211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00656, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2a2a, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009f2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00461310, 0x00171818, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00232525, 0x0018dc, 0x00d52a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c7271f, 0x00daa, 0x00383a3a, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x00611713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171414, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00969494, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00502221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a2211b, 0x00477, 0x00abacac, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004d4f4f, 0x00688, 0x00b1241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x002b10e, 0x00141515, 0x00dfdfdf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x00141515, 0x002b10e, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201d1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00474445, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00545, 0x00ecc, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cc2b23, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x0017dc, 0x00494b4b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00868787, 0x00477, 0x007d1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005b1612, 0x00477, 0x00aeafaf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003d3f3f, 0x00baa, 0x00c5271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a32823, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b3b2b2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x002c292a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00baa, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x0010ff, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007e2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d1814, 0x00588, 0x00e0e1e1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbebe, 0x00699, 0x00481311, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00961f19, 0x00477, 0x006d6f6f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x008e1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b9b8b8, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00171415, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332020, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00c7281f, 0x00477, 0x00818383, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e4e5e5, 0x00191a1a, 0x0022fe, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00daa, 0x00353737, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bebfbf, 0x00699, 0x004f1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x004a2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00cfcece, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00464243, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00101, 0x00121011, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ab2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003812f, 0x00212323, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x003d3f3f, 0x00a99, 0x00be261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x002d10f, 0x00121313, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x001d1e1e, 0x001fed, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00706d6e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x005d5a5b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00477, 0x00babbbb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00727474, 0x00477, 0x008f1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005f1713, 0x00477, 0x00acadad, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004d4f4f, 0x00788, 0x00b8251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b22a23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00e4e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00aaa8a8, 0x003a3738, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x00fbb, 0x00585a5a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x00581512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a201a, 0x00477, 0x006d6f6f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00909191, 0x00477, 0x007c1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2d24, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008c8a8b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c2c1c1, 0x00939192, 0x00615e5f, 0x002c2829, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00211e1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008a2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e1612, 0x00acc, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dadada, 0x00101111, 0x002c10e, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00eba, 0x00353737, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cecece, 0x00acc, 0x003f1310, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00572321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00383435, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0cfcf, 0x00a2a0a1, 0x00726f70, 0x00434040, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2120, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ba251e, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x002f3131, 0x00fba, 0x00ca2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x002e10f, 0x00101111, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00272929, 0x0016cc, 0x00d62a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00aaa8a8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dedede, 0x00b0aeaf, 0x007f7d7e, 0x00524e4f, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00271f20, 0x00432121, 0x00602421, 0x006f2522, 0x006f2522, 0x006f2522, 0x00632421, 0x005a2321, 0x00502221, 0x00452221, 0x003b2120, 0x00302020, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a10e, 0x002f3131, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00606161, 0x00477, 0x00a0211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00781a15, 0x00477, 0x00a5a6a6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00606161, 0x00477, 0x00a8221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c02b23, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00423f3f, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ececec, 0x00bdbcbd, 0x008e8c8c, 0x005f5c5d, 0x00312d2e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x006e2521, 0x00af2923, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00477, 0x00c9caca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9b9b, 0x00477, 0x006a1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2b22, 0x00daa, 0x004c4e4e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a3a5a5, 0x00477, 0x00691814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x003b2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a3a1a1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cccbcb, 0x009c9a9a, 0x006d6b6b, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00712522, 0x00db2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00db2b22, 0x00999, 0x00666868, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00acc, 0x003912f, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00c6c7c7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x00101111, 0x003011f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00652421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00dad9d9, 0x00aaa8a8, 0x007c797a, 0x004c494a, 0x00262323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00b12923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004f1411, 0x00111212, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00232525, 0x0018dc, 0x00d42a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1411, 0x001e2020, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00353737, 0x00eba, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00555, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171415, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004b4748, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e7e7, 0x00b8b7b7, 0x008a8888, 0x005a5758, 0x002e2a2b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2020, 0x00c32b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x009e211a, 0x005c1612, 0x00341110, 0x0017dc, 0x0012cb, 0x0018ed, 0x002410f, 0x003011f, 0x003e12f, 0x004a1310, 0x00561511, 0x00621713, 0x006e1914, 0x00791b16, 0x00871d17, 0x00931f19, 0x009f211a, 0x00701914, 0x00477, 0x00a0a1a1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x004d4f4f, 0x00688, 0x00b0241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a11f, 0x004e5050, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00747676, 0x00477, 0x00971f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00d82c24, 0x00cd2c23, 0x00c32b23, 0x00b92a23, 0x00ae2923, 0x00a22823, 0x00962822, 0x00812622, 0x005e2321, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1919, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00656363, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00c6c5c5, 0x00979696, 0x00696667, 0x00393637, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00af2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x008f1e18, 0x001add, 0x00477, 0x00e1010, 0x00424444, 0x005e6060, 0x00626363, 0x00626363, 0x00545656, 0x00474949, 0x003b3d3d, 0x002e3030, 0x00212222, 0x00131414, 0x00588, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x003e4040, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00868787, 0x00477, 0x00631713, 0x00da2b21, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002710f, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b6b7b7, 0x00477, 0x00571512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00b32a23, 0x005c2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00625f60, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00d4d3d3, 0x00a6a5a5, 0x00777475, 0x00474445, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322e2f, 0x005f5c5d, 0x008b8889, 0x00a7a5a6, 0x00a5a4a4, 0x007c797a, 0x002d2a2a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006a2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x004f1411, 0x00477, 0x00363838, 0x00b0b1b1, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00e8e9e9, 0x00dcdcdc, 0x00d0d0d0, 0x00c0c1c1, 0x00b3b4b4, 0x00a6a7a7, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbebe, 0x00699, 0x00477, 0x00477, 0x00477, 0x00477, 0x00688, 0x0012cb, 0x0021fe, 0x002d1110, 0x00391210, 0x004312f, 0x0013a9, 0x00202222, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x00191a1a, 0x0024fe, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b52a23, 0x00362020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00363233, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e2e2, 0x00b4b3b3, 0x00848283, 0x00565354, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00535051, 0x00817f7f, 0x00b0afaf, 0x00dfdedf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e6e7, 0x00403d3e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e1613, 0x00477, 0x00757777, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d3d3d3, 0x00b6b7b7, 0x00a9aaaa, 0x009d9e9e, 0x00919292, 0x00818383, 0x00747676, 0x00676969, 0x005b5d5d, 0x004e5050, 0x00424444, 0x00323535, 0x00252626, 0x00191b1b, 0x00c1c2c2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x002e3131, 0x00477, 0x0019dc, 0x00341210, 0x004011e, 0x004c1310, 0x005a1512, 0x00661713, 0x00721915, 0x007e1b16, 0x008a1d18, 0x00961f19, 0x00a5221b, 0x00b1241c, 0x00bc261e, 0x00c8281f, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00baa, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009b999a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c2c1c1, 0x00939192, 0x00646162, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00464243, 0x00747272, 0x00a4a2a2, 0x00d2d1d2, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c3c2c2, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b4241d, 0x00477, 0x00676969, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x006b6d6d, 0x005f6060, 0x00525454, 0x00424444, 0x00353838, 0x00282a2a, 0x001c1d1d, 0x00101111, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00eba, 0x003d1210, 0x008a1d18, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00242021, 0x00828080, 0x00d9d8d9, 0x00f8f8f8, 0x00f1f1f1, 0x00d0cfcf, 0x00a2a0a1, 0x00726f70, 0x00434040, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00393536, 0x00686566, 0x00979595, 0x00c4c3c4, 0x00f3f3f3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00312d2e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008e2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00511511, 0x00111212, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00e2e3e3, 0x00d6d6d6, 0x00c9caca, 0x00bcbdbd, 0x00afb0b0, 0x00a1a2a2, 0x008b8c8c, 0x006a6c6c, 0x00272929, 0x00477, 0x0019dc, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00992822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2a2b, 0x005b5859, 0x008a8888, 0x00b8b7b7, 0x00e8e7e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00494646, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b42a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0012cb, 0x005e6060, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00222424, 0x00daa, 0x00c8281f, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x004e4b4c, 0x007d7a7b, 0x00abaaaa, 0x00dbdada, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00d62a21, 0x00477, 0x008b8c8c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dfdfdf, 0x00cee, 0x004b1311, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00423f3f, 0x00706d6e, 0x009e9d9d, 0x00cecdcd, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d52c24, 0x00ee2e24, 0x00ee2e24, 0x00d12920, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00656767, 0x00999, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00942722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00636061, 0x00929091, 0x00c1c0c0, 0x00efeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cc2b23, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00577, 0x007b7d7d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00909191, 0x00477, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00a22823, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00565354, 0x00858384, 0x00b4b3b3, 0x00e3e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ae2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002810f, 0x003f4141, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008d8e8e, 0x00477, 0x00d72a21, 0x00ee2e24, 0x00ee2e24, 0x00a22823, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x00494646, 0x00787677, 0x00a7a5a6, 0x00d6d5d5, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00882622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00701914, 0x00588, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626464, 0x00fba, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00211e1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c3839, 0x006c6a6a, 0x009a9899, 0x00c9c8c8, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00492221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c2271f, 0x00477, 0x008b8c8c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00252727, 0x00411310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f2521, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00504d4d, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d22c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002e10f, 0x002c2e2e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dfdfdf, 0x00477, 0x00801c16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cbcacb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00851d17, 0x00477, 0x00cacaca, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009b9c9c, 0x00477, 0x00bf261e, 0x00ee2e24, 0x00ee2e24, 0x00d62c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006b6969, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92a21, 0x00898, 0x006b6d6d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x0015cc, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x009f2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00e3e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004b1311, 0x00151616, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00151616, 0x00521411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbb, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a3211b, 0x00477, 0x00acadad, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cbcbcb, 0x00477, 0x00911f19, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x0015cc, 0x004e5050, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00878888, 0x00477, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00c62b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a4a3a3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00661713, 0x00799, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00434545, 0x0024fe, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00484546, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00562321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00be261e, 0x00477, 0x008d8e8e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00acc, 0x00641713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00582321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c1c0c0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0025fd, 0x002e3030, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00477, 0x00a3211b, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00656, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00605d5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008e1e18, 0x00477, 0x00444646, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00747676, 0x00688, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00b72a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171415, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00dad9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00962822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008e1e18, 0x00477, 0x00444646, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00303232, 0x003711f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00802622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ff, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007e7b7c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00972822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00851d17, 0x00477, 0x00444646, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e9e9, 0x00477, 0x00761a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00492221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302c2d, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00801c16, 0x00477, 0x00444646, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a4a6a6, 0x00477, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00999798, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00bfbebe, 0x00908e8e, 0x00838181, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00801c16, 0x00477, 0x004f5151, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626363, 0x00eba, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00a72923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00777, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00cccbcb, 0x009d9b9b, 0x006e6b6c, 0x003f3c3d, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dbc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007b2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00801c16, 0x00477, 0x00505252, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00151616, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00702522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a5a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fdfdfd, 0x00d9d8d9, 0x00a9a7a8, 0x007b7979, 0x004c494a, 0x00262323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00632421, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00831c17, 0x00477, 0x00505252, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x009e211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c292a, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e5e5, 0x00b7b5b6, 0x00888686, 0x00595657, 0x002c292a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00931f19, 0x00477, 0x004b4d4d, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00292b2b, 0x0022fd, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00c32b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00615e5f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00c3c2c3, 0x00959393, 0x00656363, 0x00383435, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c2020, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ad231c, 0x00788, 0x003d3f3f, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x007c7e7e, 0x00898a8a, 0x00969797, 0x00a2a4a4, 0x00b0b1b1, 0x00bfc0c0, 0x00cccccc, 0x00d9d9d9, 0x00e5e6e6, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00646666, 0x00477, 0x00a0211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00742522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151313, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1919, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c797a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0d0d0, 0x00a2a0a1, 0x00727070, 0x00444041, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004c494a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009b2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2820, 0x0011bb, 0x00282a2a, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00262827, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00131414, 0x00202121, 0x002d2f2f, 0x003a3c3c, 0x00474949, 0x00545656, 0x00626363, 0x00707272, 0x007d7f7f, 0x008a8b8b, 0x00979898, 0x00a3a5a5, 0x00b0b1b1, 0x00c0c1c1, 0x00cdcdcd, 0x00dadada, 0x00e7e8e8, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00616262, 0x00477, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72c24, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00676465, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dddddd, 0x00afadae, 0x007f7d7e, 0x00514e4e, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00512221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x002e10e, 0x00f1010, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x002f3131, 0x00ba9, 0x00b0241c, 0x00df2c22, 0x00d22920, 0x00c6271f, 0x00ba251e, 0x00ae231c, 0x00a2211b, 0x00961f19, 0x00871d17, 0x007b1b16, 0x006f1914, 0x00631713, 0x00571511, 0x004b1310, 0x003e11f, 0x003011f, 0x002410f, 0x0018ed, 0x00caa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00588, 0x00131414, 0x00212222, 0x002e3030, 0x003b3d3d, 0x00484a4a, 0x00555757, 0x00626363, 0x00717373, 0x007e8080, 0x008b8c8c, 0x00989999, 0x00a4a6a6, 0x00b2b3b3, 0x00c0c1c1, 0x00cfcfcf, 0x00dcdcdc, 0x00e8e9e9, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00989999, 0x00202222, 0x00477, 0x00681813, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00682421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00ebebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaeaea, 0x00bbbaba, 0x008c8a8b, 0x005f5c5c, 0x00302c2d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00721915, 0x00477, 0x00a7a8a8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f1f1f1, 0x00393b3b, 0x00688, 0x00a6221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00df2c22, 0x00d12920, 0x00c5271f, 0x00b9251d, 0x00ad231c, 0x00a1211a, 0x00951f19, 0x00871d17, 0x00791b16, 0x006e1914, 0x00621713, 0x00561511, 0x004a1310, 0x003e12f, 0x002f11f, 0x002310e, 0x0018dd, 0x00baa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00699, 0x00131414, 0x00222323, 0x002f3131, 0x003c3e3e, 0x00494b4b, 0x00525454, 0x004b4d4d, 0x00292b2b, 0x00699, 0x00477, 0x002c10f, 0x00ad231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a52923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00524e4f, 0x00e5e5e5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00c8c7c7, 0x00999798, 0x006b6969, 0x003b3838, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c494a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abaaaa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005e2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c7271f, 0x00788, 0x00545656, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00444646, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x00de2b22, 0x00d12920, 0x00c4271f, 0x00b8251d, 0x00ab231c, 0x009f211a, 0x00931f19, 0x00871d17, 0x00791a15, 0x006d1814, 0x00611612, 0x00551411, 0x00491210, 0x003d12f, 0x002f11f, 0x002f1311, 0x002f11f, 0x00471310, 0x00721915, 0x00b9251d, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ba2a23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x006b6969, 0x00999798, 0x009f9d9e, 0x00989697, 0x00777475, 0x00484546, 0x00262223, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b52a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1411, 0x00cee, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00505252, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a92923, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171414, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201d1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00959393, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00352020, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2820, 0x00477, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x005e6060, 0x00477, 0x007c1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00812622, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2020, 0x00392120, 0x00442121, 0x004e2221, 0x00582321, 0x00632421, 0x006f2522, 0x007a2522, 0x00842622, 0x008e2722, 0x00992822, 0x00a32823, 0x00af2923, 0x00ba2a23, 0x00c52b23, 0x00cf2c23, 0x00d92c24, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00712522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131111, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a9a7a8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbbbc, 0x00262323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a89, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f2521, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791b16, 0x00477, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006c6e6e, 0x00477, 0x006d1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008e2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00392120, 0x00442121, 0x004f2221, 0x00592321, 0x00632421, 0x006f2522, 0x007b2522, 0x00852622, 0x008f2722, 0x009a2822, 0x00a42923, 0x00af2923, 0x00bb2a23, 0x00c52b23, 0x00d02c23, 0x00da2d24, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x007f2622, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00353132, 0x00ececec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b2b1b1, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009b2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003511f, 0x00343636, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007d7f7f, 0x00477, 0x005e1613, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009b2822, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302020, 0x003a2120, 0x00442121, 0x004f2221, 0x005a2321, 0x00642421, 0x006f2522, 0x007b2622, 0x00862622, 0x00902722, 0x009a2822, 0x00a22823, 0x009a2822, 0x00892722, 0x006b2421, 0x003d2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00464344, 0x00d7d7d7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e6e6, 0x00767374, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bd2a23, 0x00ee2e24, 0x00ee2e24, 0x00e92d23, 0x00a99, 0x006d6f6f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008d8e8e, 0x00477, 0x00511512, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a72923, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x006b6869, 0x00acabab, 0x00c5c4c4, 0x00c3c2c2, 0x00a4a3a3, 0x00676465, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00d82a21, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009d9e9e, 0x00477, 0x00441310, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001a1717, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00555, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d52c24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aaabab, 0x00699, 0x00391210, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc2a23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00577, 0x00757777, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00babbbb, 0x009bb, 0x002e10f, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312d2e, 0x003a3738, 0x00272324, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b02923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003411f, 0x00323434, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d3d3d3, 0x00f1111, 0x0023fd, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac2923, 0x00912722, 0x00872622, 0x007c2622, 0x006f2522, 0x00652421, 0x005b2321, 0x00502221, 0x00462221, 0x003c2120, 0x00302020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00fde, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00333031, 0x00625f60, 0x00918f8f, 0x00c0bfbf, 0x00eeedee, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00acabab, 0x00302c2d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00812622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007b1b16, 0x00477, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x002a2c2c, 0x0014cb, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d24, 0x00dc2d24, 0x00d12c23, 0x00c72b23, 0x00bc2a23, 0x00b02923, 0x00a62923, 0x009b2822, 0x00912722, 0x00872622, 0x007c2622, 0x006f2522, 0x00652421, 0x005b2321, 0x00512221, 0x00472221, 0x003c2121, 0x00302020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00edd, 0x00151313, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2728, 0x00555253, 0x00848182, 0x00b2b1b1, 0x00e1e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c6c5c5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a7a7, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00dc2d24, 0x00d22c23, 0x00c82b23, 0x00bc2a23, 0x00b12923, 0x00a62923, 0x009c2822, 0x00922722, 0x00872622, 0x007c2622, 0x00702522, 0x00662421, 0x005c2321, 0x00512221, 0x00472221, 0x003c2121, 0x00302020, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00191616, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00252122, 0x00484546, 0x00777475, 0x00a5a4a4, 0x00d4d3d3, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00535051, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cb2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002d10f, 0x00353737, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a3a5a5, 0x00477, 0x003b12f, 0x00711915, 0x008c1e18, 0x009e211a, 0x00ab231c, 0x00b7251d, 0x00c3271f, 0x00d12920, 0x00dd2b22, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00dc2d24, 0x00d22c23, 0x00c92b23, 0x00bc2a23, 0x00b12a23, 0x00a72923, 0x009d2822, 0x008e2722, 0x00752522, 0x004b2221, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00111010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003a3738, 0x006a6768, 0x00989697, 0x00c7c6c6, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00858384, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171414, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007b1b16, 0x00477, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00878888, 0x002b2d2d, 0x00699, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00b99, 0x0017dc, 0x0023fe, 0x002f11f, 0x003c12f, 0x004812f, 0x00541411, 0x00601612, 0x006c1814, 0x00791a15, 0x00861d17, 0x00921f19, 0x009e211a, 0x00aa231c, 0x00b6251d, 0x00c2271f, 0x00d12920, 0x00dd2b22, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22c23, 0x00762522, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2b2c, 0x005d5a5b, 0x008b898a, 0x00bab9b9, 0x00e9e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00e1e2e2, 0x00cecece, 0x00c0c1c1, 0x00b2b3b3, 0x00a5a6a6, 0x00999a9a, 0x008c8d8d, 0x007f8181, 0x00717373, 0x00626464, 0x00565858, 0x00494b4b, 0x003c3e3e, 0x002f3131, 0x00222323, 0x00131414, 0x00699, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00a99, 0x0016dc, 0x0022fe, 0x002f11f, 0x003c12f, 0x004812f, 0x00541411, 0x00601612, 0x006c1814, 0x00791a15, 0x00861d17, 0x00921f19, 0x009e211a, 0x00a9231b, 0x00b5251d, 0x00c2271f, 0x00d02920, 0x00dc2b22, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c42b23, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00272324, 0x00504d4d, 0x007e7c7d, 0x00adacac, 0x00dcdcdc, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cb2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002d10f, 0x00353737, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00e8e9e9, 0x00dcdcdc, 0x00cfcfcf, 0x00c0c1c1, 0x00b2b3b3, 0x00a5a6a6, 0x009a9b9b, 0x008d8e8e, 0x00808282, 0x00717373, 0x00636565, 0x00575959, 0x004a4c4c, 0x003d3f3f, 0x00303232, 0x00222323, 0x00141515, 0x00799, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00999, 0x0015dc, 0x0021fe, 0x002f1110, 0x003b12f, 0x004712f, 0x00531411, 0x005f1612, 0x006b1814, 0x00791a15, 0x00851d17, 0x00911f19, 0x009d211a, 0x00a9231b, 0x00b5251d, 0x00c2271f, 0x00d02920, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d52c23, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00726f70, 0x00a09e9f, 0x00d0cfcf, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791b16, 0x00477, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00e9eaea, 0x00dddddd, 0x00d0d0d0, 0x00c0c1c1, 0x00b3b4b4, 0x00a6a7a7, 0x009a9b9b, 0x008d8e8e, 0x00818383, 0x00717373, 0x00646666, 0x00585a5a, 0x004b4d4d, 0x003e4040, 0x00313333, 0x00222323, 0x00151616, 0x008aa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x0023fe, 0x00741a15, 0x00df2c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bd2a23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00363233, 0x00646162, 0x00949293, 0x00c2c1c1, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00eaebeb, 0x00dedede, 0x00d0d0d0, 0x00c1c2c2, 0x00b4b5b5, 0x00a7a8a8, 0x009b9c9c, 0x00818383, 0x00454747, 0x00477, 0x001ced, 0x00c5271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002c292a, 0x00575454, 0x00878585, 0x00b5b3b4, 0x00e3e3e3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cb2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0028fe, 0x00353737, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c3c4c4, 0x00181919, 0x001ded, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00c42b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1818, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262223, 0x004a4747, 0x00797777, 0x00a8a6a7, 0x00d6d6d6, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00872622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00761a15, 0x00477, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b7b8b8, 0x00477, 0x007f1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x006c6a6a, 0x009b999a, 0x00cac9c9, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00303232, 0x00391210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00545152, 0x00acabab, 0x00e9e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cd2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002810e, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00636565, 0x0014cc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007a2522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00302c2d, 0x00b4b3b3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00761a15, 0x00477, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x0013cc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007c2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00292526, 0x00d0cfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00424444, 0x002f11f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00732522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00918f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002810e, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eceded, 0x00acc, 0x00631713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9899, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00761a15, 0x00477, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00808282, 0x00477, 0x00ba251e, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181616, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00555253, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008a8888, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d8d8d8, 0x00bdd, 0x00471411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a82923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006f6c6d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00615e5f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151313, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002810e, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00303232, 0x00fba, 0x00d02920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00512221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeedee, 0x002a2627, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008b2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00477, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x004d4f4f, 0x00477, 0x00a2211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b22a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007e7c7d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00626363, 0x00477, 0x007f1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x003c2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a5a4a4, 0x00242021, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0023fe, 0x003a3c3c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00757777, 0x00477, 0x006a1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e6e7, 0x00777475, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008e2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00588, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008e8f8f, 0x00477, 0x00561511, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00902722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00c7c6c6, 0x00979696, 0x005f5c5c, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00888, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x00477, 0x00949595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a1a3a3, 0x00477, 0x00451310, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a72923, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00d5d4d4, 0x00a6a5a5, 0x00777475, 0x00484546, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0023fe, 0x003f4141, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b5b6b6, 0x00799, 0x003611f, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b52a23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e2e1e1, 0x00b4b3b3, 0x00848283, 0x00565354, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00588, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x00dff, 0x002910e, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c32b23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efefef, 0x00c2c1c1, 0x00929091, 0x00646162, 0x00353132, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004c2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x00477, 0x00949595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d3d3d3, 0x00141515, 0x001ded, 0x00d42a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ce2c23, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00d0cfcf, 0x00a09e9f, 0x00716e6f, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0023fe, 0x003f4141, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x001e2020, 0x0015cc, 0x00c7281f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x003a2120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00dcdcdc, 0x00aeacad, 0x007e7c7d, 0x00514e4e, 0x00272324, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1a1b, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008f2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00741a15, 0x00477, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00292b2b, 0x00caa, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02d24, 0x00442121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009e9c9c, 0x00302c2d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004b2221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00a99, 0x004d4f4f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00373939, 0x00999, 0x00ab231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d24, 0x00502221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00706d6e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d9d8d9, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c82b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007d1b16, 0x00477, 0x00838484, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00474949, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x005d2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00565354, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00aaa8a8, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00672421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00501411, 0x00477, 0x00717373, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00595b5b, 0x00477, 0x00861d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006d2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211d1e, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00e9e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006f6c6d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dbc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00ba2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x005f1713, 0x00477, 0x002b2d2d, 0x00acadad, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006e7070, 0x00477, 0x00721915, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007d2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fdd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00636061, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeedee, 0x00c0bfbf, 0x00939192, 0x00646162, 0x00383435, 0x00bbbaba, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00382120, 0x00dc2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a0211a, 0x0020fe, 0x00477, 0x001a1b1b, 0x005c5e5e, 0x00858686, 0x009fa0a0, 0x00abacac, 0x00b8b9b9, 0x00c6c7c7, 0x00d3d3d3, 0x00e0e0e0, 0x00efefef, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00838484, 0x00477, 0x005e1613, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00baa, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00656, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004a4747, 0x00a19fa0, 0x00bebdbd, 0x00bab9b9, 0x00989697, 0x006c6a6a, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004d4a4b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x002a2627, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e92d23, 0x009e211a, 0x004f1411, 0x0016dc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00eff, 0x001a1b1b, 0x00272828, 0x00343737, 0x00424444, 0x00525454, 0x005f6060, 0x006b6d6d, 0x00787a7a, 0x00858686, 0x00939494, 0x00a1a2a2, 0x00afb0b0, 0x00bcbdbd, 0x00c9caca, 0x00d7d7d7, 0x00e3e4e4, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009a9b9b, 0x00477, 0x004c1411, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x004f4c4d, 0x00787677, 0x00848182, 0x00585555, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00cc2820, 0x00c0261e, 0x00b3241d, 0x00a6221b, 0x00992019, 0x008d1e18, 0x00811c16, 0x00751a15, 0x00681813, 0x005b1612, 0x004d1310, 0x004111f, 0x00361210, 0x002911f, 0x001dfe, 0x0011cb, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00111212, 0x001e1f1f, 0x002b2d2c, 0x00383b3b, 0x00454747, 0x00535555, 0x00626363, 0x006f7171, 0x007c7e7e, 0x00898a8a, 0x00979898, 0x00a3a5a5, 0x00b0b1b1, 0x00c0c1c1, 0x00cdcdcd, 0x00dbdbdb, 0x00e7e8e8, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00699, 0x003c1210, 0x00e62d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00af2923, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006f6c6d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00413e3f, 0x006f6c6d, 0x009e9d9d, 0x00cdcccc, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0aeaf, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00992822, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00d42a21, 0x00c8281f, 0x00bc261e, 0x00b1241c, 0x00a5221b, 0x00961f19, 0x00891d17, 0x007d1b16, 0x00711915, 0x00651713, 0x00581511, 0x004c1310, 0x003e11f, 0x003211f, 0x002610f, 0x0019ed, 0x00daa, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00588, 0x00131414, 0x00222323, 0x002f3131, 0x003c3e3e, 0x009bb, 0x002d10e, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00be2a23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f4f5, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00333031, 0x00615e5f, 0x00918f8f, 0x00bfbebe, 0x00eeedee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00737171, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00442121, 0x00a42923, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00df2c22, 0x00d22920, 0x00c5271f, 0x00b9251d, 0x00ad231c, 0x00a1211a, 0x00951f19, 0x00871d17, 0x00791b16, 0x006e1914, 0x00621713, 0x00561511, 0x00491210, 0x003d12f, 0x003d12f, 0x00d72a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2b23, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x002a2627, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00535051, 0x00838181, 0x00b2b1b1, 0x00e0dfe0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bbbaba, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x006c2421, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00d92a21, 0x00c1271e, 0x00b3241d, 0x00a9231b, 0x00c7271f, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00252122, 0x00464243, 0x00757273, 0x00a4a3a3, 0x00d2d1d2, 0x00fcfbfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d5d5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d2121, 0x00c02b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x00cb2820, 0x00b4241d, 0x009c201a, 0x00821c17, 0x006a1814, 0x00521411, 0x003811f, 0x0020fe, 0x00999, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x001eed, 0x008e1e18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2d24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccbcb, 0x00f3f3f3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d1d0d1, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00622421, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00b6251d, 0x00731a15, 0x00491310, 0x002b11f, 0x0013cc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x009bb, 0x00222423, 0x003c3e3e, 0x00595b5b, 0x00727474, 0x008c8d8d, 0x00a7a8a8, 0x00bebfbf, 0x00bebfbf, 0x009b9c9c, 0x00353737, 0x00477, 0x00841c17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a82923, 0x00562321, 0x00622421, 0x006c2421, 0x00772522, 0x00822622, 0x008c2722, 0x00962822, 0x00a22823, 0x00ae2923, 0x00b92a23, 0x00c32b23, 0x00ce2c23, 0x00d92c24, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32d24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1a1b, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00323, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b5b3b4, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00762522, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00941f19, 0x0026fe, 0x00477, 0x00699, 0x00282a2a, 0x004b4d4d, 0x00666868, 0x00808282, 0x009a9b9b, 0x00b6b7b7, 0x00d0d0d0, 0x00e8e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00474949, 0x00caa, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00cc2b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002e2020, 0x00392120, 0x00442121, 0x004e2221, 0x00582321, 0x00632421, 0x006f2522, 0x007b2522, 0x00852622, 0x00902722, 0x009a2822, 0x00a52923, 0x00582321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00434, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x0011f10, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00838181, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00662421, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ca2820, 0x003511f, 0x00477, 0x002c2e2e, 0x00999a9a, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbebe, 0x00477, 0x00a3211b, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x0010bb, 0x00f1110, 0x00979898, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e9eaea, 0x00477, 0x00871d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00332020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c1c0c0, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa231c, 0x00999, 0x00292b2b, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00477, 0x00891d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00595657, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00852622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2820, 0x0011bb, 0x00272929, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cacaca, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00352020, 0x00592321, 0x00672421, 0x006d2421, 0x00562321, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00a3a1a1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9c8c8, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x003712f, 0x00f1110, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0b1b1, 0x00477, 0x00b7251d, 0x00ee2e24, 0x00ee2e24, 0x00d82c24, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x008a2722, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00c12b23, 0x006f2522, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00252122, 0x00c7c6c6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00585556, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00831c17, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00979898, 0x00477, 0x00cf2920, 0x00ee2e24, 0x00ee2e24, 0x00c22b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00922722, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2b23, 0x00492221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x003a3738, 0x00231f20, 0x00393637, 0x00efeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c2c1c1, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00802622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00b99, 0x00434545, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007a7c7c, 0x00477, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ac2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004e2221, 0x00d62c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00612421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c2c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009f9d9e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00666464, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00535051, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003711f, 0x00f1010, 0x00dfdfdf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00616262, 0x0017dc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00972822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00692421, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x00941f19, 0x005f1612, 0x004111f, 0x004112f, 0x00611612, 0x00a8221b, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00592321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00535051, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00393536, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a3a1a1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bcbabb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00555, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c22b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00871d17, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00474949, 0x002e11f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00822622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006b2421, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x00721915, 0x00eba, 0x00477, 0x00111212, 0x00333636, 0x00373939, 0x00e10f, 0x00477, 0x002d10f, 0x00c3271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2d24, 0x00322020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c3c2c3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009c9a9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2627, 0x00d8d7d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004d4a4b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00802622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2820, 0x00caa, 0x00434545, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x002b2d2d, 0x004712f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00be261e, 0x0023fe, 0x00477, 0x00515353, 0x00bfc0c0, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x009c9d9d, 0x00171818, 0x00caa, 0x00b6251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f5f5, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00474445, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b7b6b6, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00544, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00432121, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003b1210, 0x00dff, 0x00dcdcdc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00111212, 0x00621713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00572321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322020, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00af231c, 0x00caa, 0x00181919, 0x00b6b7b7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e1e1, 0x00202222, 0x0019dc, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00df2d24, 0x00271f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c9c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00989697, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c797a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00474445, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c12b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00871d17, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00477, 0x00791b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00412121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a62923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x00caa, 0x00262828, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bebfbf, 0x00477, 0x00811c16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b3b2b2, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2820, 0x00caa, 0x003f4141, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d8d8d8, 0x00477, 0x00911f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002a2020, 0x00231f20, 0x00231f20, 0x005f2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x001fed, 0x001c1d1d, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x002d2f2f, 0x003b12f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007d2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c9c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00918f90, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00332f30, 0x00e7e6e7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00423f3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003b12f, 0x00dff, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bdbebe, 0x00477, 0x00ab231c, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x00231f20, 0x00231f20, 0x00302020, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005c1612, 0x00477, 0x00bebfbf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005e6060, 0x0018dd, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00988, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x00312d2e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00585556, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00adacac, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00be2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00881d17, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a3a5a5, 0x00477, 0x00c4271f, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00231f20, 0x00231f20, 0x00a22823, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ae231c, 0x00477, 0x006c6e6e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00626363, 0x0015dc, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00932722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00989, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c9c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008f8d8d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00939192, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x003f3b3c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d02920, 0x00eba, 0x003f4141, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00898a8a, 0x00477, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00b62a23, 0x00231f20, 0x005b2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x001fed, 0x00202222, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00434545, 0x002e11f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00852622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191616, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00efeeee, 0x002d2a2a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00262323, 0x00cdcccc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a6a5a5, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00323, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003f1310, 0x00dff, 0x00dbdbdb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006d6f6f, 0x00b99, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a12822, 0x002e2020, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00641713, 0x00477, 0x00babbbb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00e1010, 0x005c1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00632421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c9c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00888686, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003e3a3b, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x003d393a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00be2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c1e18, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00545656, 0x002310e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c2722, 0x009e2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b2241d, 0x00477, 0x00636565, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x00a2211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00392120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00100, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cab, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005a5758, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaeaea, 0x002b2728, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00696667, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00c2c1c1, 0x00929091, 0x00636061, 0x00343131, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001e1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007c2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d02920, 0x00eba, 0x003a3c3c, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00393c3c, 0x003b11f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x0023fe, 0x001d1f1f, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003a3c3c, 0x001adc, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00c62b23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141112, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00c3c2c3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00828080, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767374, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00d0d0d0, 0x00a2a0a1, 0x00726f70, 0x00434040, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011f10, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d2121, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003f1210, 0x00bdd, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x001d1e1e, 0x00541411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a1814, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a7a8a8, 0x00477, 0x00841c17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007e2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00151314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d393a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e6e6, 0x00282425, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00434040, 0x00aeacad, 0x00f5f4f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0dfe0, 0x00b1b0b0, 0x00817f7f, 0x00524f50, 0x00292526, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008c1e18, 0x00477, 0x008c8d8d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00799, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b8251d, 0x00577, 0x005d5f5f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eceded, 0x001b1c1c, 0x002a10e, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x002d2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00787677, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c797a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x004b4748, 0x005a5758, 0x00524e4f, 0x00322e2f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0011ff, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00782522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00eba, 0x003a3c3c, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x00c1c2c2, 0x00a6a7a7, 0x008a8b8b, 0x006f7171, 0x00555757, 0x003a3c3c, 0x00323535, 0x00646666, 0x00f2f2f2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e6e6, 0x00477, 0x00861d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x002810e, 0x001a1b1b, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005d5f5f, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00852622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009c9a9a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e1e0e0, 0x00262323, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d2121, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00431310, 0x00bdd, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x00477, 0x00477, 0x00a99, 0x002310f, 0x003b12f, 0x004612f, 0x00477, 0x00868787, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9caca, 0x00477, 0x009e211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006e1914, 0x00477, 0x00abacac, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b0b1b1, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a6a5a5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00767374, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00911f19, 0x00477, 0x008c8d8d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00799, 0x00491310, 0x00c1271e, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dba, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c6c7c7, 0x00477, 0x008b1d18, 0x00c6271f, 0x00ad231c, 0x00961f19, 0x007f1b16, 0x00641713, 0x00788, 0x00575959, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eceded, 0x001b1c1c, 0x002810e, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00979595, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x00252122, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x001a1717, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00652421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x0010bb, 0x00383a3a, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x002e3030, 0x0015cb, 0x00d82a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x00477, 0x00838484, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x00191a1a, 0x00477, 0x00477, 0x00477, 0x00477, 0x00477, 0x00bdd, 0x002b2d2d, 0x00e7e8e8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005b5d5d, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001a1717, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00686566, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x004d4a4b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00222, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00461311, 0x00acc, 0x00d4d4d4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00477, 0x009d9e9e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e7e8e8, 0x00a3a5a5, 0x00a4a6a6, 0x00babbbb, 0x00d6d6d6, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00282425, 0x00e4e4e4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x005c595a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00989, 0x00000, 0x00000, 0x00544, 0x001e1b1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001b1819, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121010, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00632421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a8221b, 0x00477, 0x00818383, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00799, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e32d24, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00b0241c, 0x00477, 0x00b8b9b9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x002810e, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00121011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00555253, 0x00f3f3f3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c0bfbf, 0x00413e3f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00171516, 0x0010ef, 0x00988, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b12a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003311f, 0x00202222, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x002e3030, 0x0015cb, 0x00d82a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00742522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00982019, 0x00477, 0x00d3d3d3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003f3b3c, 0x00a09e9f, 0x00d7d7d7, 0x00ececec, 0x00e8e7e7, 0x00d1d0d1, 0x009e9d9d, 0x004f4c4d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001a1717, 0x00131111, 0x00baa, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00e92e24, 0x00ee2e24, 0x00ee2e24, 0x00bb251e, 0x00477, 0x008e8f8f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b32a23, 0x003c2121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f1b16, 0x00477, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00444, 0x00171414, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001c191a, 0x00151313, 0x00ecc, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00562321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f1914, 0x00699, 0x00e9eaea, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00799, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00382120, 0x00512221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00641713, 0x00bdd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x002810e, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x0011ff, 0x001b1819, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00171515, 0x0010ef, 0x00888, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007b2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003d12f, 0x00313333, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x002e3030, 0x0015cb, 0x00d82a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f2522, 0x00231f20, 0x00682421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c1310, 0x00272929, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211, 0x00877, 0x00dbc, 0x0010ee, 0x0011f10, 0x0011ef, 0x00ecd, 0x00988, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00892722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x0021fe, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x009a201a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b32a23, 0x00231f20, 0x00231f20, 0x007d2622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003511f, 0x00414343, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x008c2722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x001cee, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c7c8c8, 0x00799, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00382120, 0x00231f20, 0x00231f20, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x001aed, 0x005b5d5d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x0028fe, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007a2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003b1210, 0x00313333, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e6e6, 0x00202222, 0x001bed, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006f2522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a82923, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x00688, 0x00777979, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00688, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00572321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f1b16, 0x00477, 0x00c3c4c4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e2e3e3, 0x002d2f2f, 0x00a99, 0x00b5251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b32a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bd2a23, 0x00ee2e24, 0x00ee2e24, 0x00d52a21, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x006e1914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00191617, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00e42d24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x001add, 0x00202222, 0x00dadada, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00babbbb, 0x001b1c1c, 0x00baa, 0x00a6221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dd2d24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d22c23, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x00477, 0x00aaabab, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x0028fe, 0x00e72d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00151314, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x0011bb, 0x00f1010, 0x007f8181, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00b3b4b4, 0x004a4c4c, 0x00477, 0x001fed, 0x00ba251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x005b2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00a2211b, 0x00477, 0x00c7c8c8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00788, 0x00bc261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00161414, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00151313, 0x00555, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00342020, 0x00dd2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cc2820, 0x00461311, 0x00477, 0x00477, 0x00101111, 0x00181818, 0x00477, 0x00477, 0x0010bb, 0x00721915, 0x00e12c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00722522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00322020, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00e0e1e1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x00741a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00edd, 0x00171515, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x001d1a1b, 0x00151313, 0x00b9a, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c6271f, 0x00831c17, 0x00611612, 0x005d1612, 0x00751a15, 0x00a4221b, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x006e2521, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00711915, 0x00477, 0x00f9f9f9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00181919, 0x002c10f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00322, 0x00545, 0x00544, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00662421, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82c24, 0x00532321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00581511, 0x00191b1b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00575959, 0x00788, 0x00be261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00bb2a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x00932722, 0x002e2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00732522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004012f, 0x00353737, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x00741a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d12c23, 0x002b2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00dbc, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00552321, 0x00a52923, 0x00e12d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00eb2e24, 0x00c52b23, 0x00832622, 0x00372020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00342020, 0x00732522, 0x00a42923, 0x00cb2b23, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x002710f, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e8e9e9, 0x00181919, 0x002c10f, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003d2121, 0x00502221, 0x00532321, 0x00442121, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004a2221, 0x00aa2923, 0x00eb2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00daa, 0x00696b6b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00494b4b, 0x00477, 0x00b9251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b62a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x00333, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x009e2822, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12c22, 0x00477, 0x00858686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x005b5d5d, 0x00477, 0x004a1411, 0x00e92d23, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00482221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151213, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00d72c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00c9281f, 0x00a4221b, 0x00831c17, 0x00601612, 0x003a11f, 0x00477, 0x00919292, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008c8d8d, 0x00477, 0x00711915, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b92a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00622421, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x00641713, 0x0018dc, 0x00477, 0x00477, 0x00477, 0x00101111, 0x00333535, 0x00575959, 0x00c1c2c2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005a5c5c, 0x00788, 0x00c8281f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00602321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a89, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011f10, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005f2321, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x00611612, 0x00577, 0x009bb, 0x004f5151, 0x00979898, 0x00c5c6c6, 0x00e9eaea, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00cee, 0x00481310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2c23, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x001e1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00e62d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x0022fe, 0x00477, 0x00626464, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007d7f7f, 0x00477, 0x00b0241c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00792522, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x0011ff, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00cb2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b4241d, 0x0010bb, 0x001a1b1b, 0x00bdbebe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x001b1c1c, 0x002d10f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2d24, 0x00302020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00fde, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00892722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c9281f, 0x0011bb, 0x00212323, 0x00dcdcdc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009d9e9e, 0x00477, 0x00921f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00922722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00baa, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00402121, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x002e10f, 0x00121313, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00303232, 0x001adc, 0x00e32c23, 0x00ee2e24, 0x00ee2e24, 0x00e92e24, 0x003e2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b52a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007e1b16, 0x00477, 0x00a3a5a5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bbbcbc, 0x00477, 0x00761a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171415, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00672421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22920, 0x00caa, 0x00464848, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004d4f4f, 0x00baa, 0x00d42a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00522221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00d92c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004b1411, 0x00acc, 0x00d9d9d9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x00799, 0x00581512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c32b23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a6221b, 0x00477, 0x007c7e7e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x00577, 0x00be261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006a2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x0021ed, 0x00232525, 0x00f6f6f6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00121313, 0x003c1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d52c24, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00bf2b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00731a15, 0x00477, 0x00b5b6b6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008b8c8c, 0x00477, 0x00a4221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00702522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c8281f, 0x00999, 0x00525454, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f7f7f7, 0x00232525, 0x0025fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00352020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00322, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00766, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00de2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00401210, 0x00e1010, 0x00e0e1e1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a9aaaa, 0x00477, 0x00861d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009c2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009d2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a201a, 0x00477, 0x00898a8a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003b3d3d, 0x0013cb, 0x00dd2b22, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00462221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00edd, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00e02c22, 0x0019dc, 0x002c2e2e, 0x00fafafa, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c7c8c8, 0x00477, 0x006a1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b52a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00322, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x00c82b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00671813, 0x00477, 0x00c0c1c1, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005a5c5c, 0x00999, 0x00cb2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005c2321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00161414, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x007b2522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c0261e, 0x00688, 0x005e6060, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00bdd, 0x004c1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2b23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00767, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00878, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003611f, 0x00131414, 0x00e8e9e9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fafafa, 0x00e4e5e5, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00787a7a, 0x00477, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a72923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00696b6b, 0x00474949, 0x00242626, 0x00799, 0x00477, 0x00477, 0x007d7f7f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00191a1a, 0x003611f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ef, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00582321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2b21, 0x0014cb, 0x00363838, 0x00fcfcfc, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dcdcdc, 0x00acc, 0x00daa, 0x002e11f, 0x004d1310, 0x006e1914, 0x00861d17, 0x002fec, 0x001b1c1c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008e8f8f, 0x00477, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00e42d24, 0x00261f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00281f20, 0x00cf2c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005c1612, 0x00588, 0x00cbcbcb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00c5c6c6, 0x00a1a3a3, 0x007e8080, 0x005f6060, 0x00efefef, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004e5050, 0x00b99, 0x00cf2920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x001fed, 0x00414343, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e5e6e6, 0x00477, 0x007f1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x003f2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00171515, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00852622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b7251d, 0x00477, 0x006a6c6c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00cbcbcb, 0x00a3a5a5, 0x00808282, 0x005d5f5f, 0x00373939, 0x00131414, 0x00477, 0x00477, 0x00477, 0x00477, 0x007c7e7e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b5b6b6, 0x00477, 0x00761a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00982019, 0x00477, 0x00a8a9a9, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00131414, 0x00611612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00532321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00988, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003c2121, 0x00e72d24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x002c10e, 0x00191a1a, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e0e0e0, 0x00848585, 0x00616262, 0x003a3c3c, 0x00161717, 0x00477, 0x00477, 0x00477, 0x00477, 0x0019ed, 0x003b12f, 0x005e1612, 0x00801c16, 0x009a201a, 0x00fa9, 0x00232525, 0x00f5f5f5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00272929, 0x0020ed, 0x00e52c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x001ded, 0x002c2e2e, 0x00fdfdfd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00191a1a, 0x005b1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00562321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b12a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00477, 0x00a2a4a4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00474949, 0x00477, 0x0017dc, 0x003911f, 0x005a1512, 0x007b1b16, 0x009f211a, 0x00c1271e, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00741a15, 0x00477, 0x00b3b4b4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00888989, 0x00477, 0x00a0211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791a15, 0x00477, 0x00b5b6b6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00799, 0x006c1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x004c2221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00666, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00612421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d32a21, 0x00fbb, 0x00404242, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00abacac, 0x00477, 0x007d1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2820, 0x00a99, 0x00505252, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e4e5e5, 0x00e1010, 0x00411310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00caa, 0x00494b4b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00477, 0x00931f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00141212, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002b2020, 0x00d62c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00511512, 0x008aa, 0x00d5d5d5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x001f2121, 0x0025fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00421310, 0x00dff, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005a5c5c, 0x00788, 0x00c7271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00571512, 0x00799, 0x00d5d5d5, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007c7e7e, 0x00477, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00862622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x00477, 0x00777979, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00797b7b, 0x00477, 0x00ac231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009f211a, 0x00477, 0x00868787, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c1c2c2, 0x00477, 0x006b1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bb251e, 0x00477, 0x006c6e6e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x001c1d1d, 0x003c1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009e2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00767, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002f2020, 0x00e32d24, 0x00ee2e24, 0x00ee2e24, 0x00e72d23, 0x0023fe, 0x001f2121, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x009bb, 0x004e1411, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d52c23, 0x005c2321, 0x003f2121, 0x004f2221, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x001ced, 0x002a2c2c, 0x00f8f8f8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fbfbfb, 0x00303232, 0x0018dc, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003711f, 0x00141515, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00909191, 0x00477, 0x00a6221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00562321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00cab, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ef, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00762522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00477, 0x00adaeae, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00444646, 0x00daa, 0x00d32a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00612421, 0x00231f20, 0x00251f20, 0x00c52b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006c1814, 0x00477, 0x00bcbdbd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00959696, 0x00477, 0x00951f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a201a, 0x00477, 0x00929393, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eeeeee, 0x00151616, 0x003812f, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00cd2c23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00bc2a23, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x001bed, 0x00393b3b, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x00801c16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00231f20, 0x00231f20, 0x00772522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c5271f, 0x00788, 0x005a5c5c, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00eaebeb, 0x00141515, 0x003611f, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52c23, 0x001ded, 0x002b2d2d, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00737575, 0x00477, 0x00b8251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00291f20, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x00477, 0x00a1a3a3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f2f2f2, 0x001d1f1f, 0x002810e, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00e82e24, 0x003d2121, 0x00231f20, 0x00352020, 0x00e12d24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003a1210, 0x00111212, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00666868, 0x00577, 0x00bd261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791a15, 0x00477, 0x00b7b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dddddd, 0x009bb, 0x00511511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c82b23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00edd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00442121, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791b16, 0x00477, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00767878, 0x00477, 0x00af231c, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a02822, 0x005c2321, 0x00792522, 0x00b92a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00961f19, 0x00477, 0x00909191, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cccccc, 0x00588, 0x00601713, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00caa, 0x004b4d4d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00565858, 0x00999, 0x00cf2920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00572321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00562321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x005e1612, 0x00191a1a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x008aa, 0x00511511, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x0018dc, 0x00313333, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003a3c3c, 0x0013cb, 0x00da2b21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00571512, 0x00799, 0x00d7d7d7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c5c6c6, 0x00477, 0x006d1814, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12a23, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00141212, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00592321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00521411, 0x00222424, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00484a4a, 0x00daa, 0x00d32a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00477, 0x00c5c6c6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a1a2a2, 0x00477, 0x00891d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b9251d, 0x00477, 0x006f7171, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003a3c3c, 0x0014cb, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00432121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00542321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00651713, 0x00dff, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bfc0c0, 0x00477, 0x00771a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e22c23, 0x00aa231c, 0x00577, 0x00636565, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x001a1b1b, 0x002d10f, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003511f, 0x00151616, 0x00ededed, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a8a9a9, 0x00477, 0x00881d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a2822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00392120, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f1e18, 0x00477, 0x00cdcdcd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005f6060, 0x0013cc, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00e02c22, 0x00bf261e, 0x009d211a, 0x007c1b16, 0x005c1612, 0x003b12f, 0x0019ed, 0x00477, 0x00477, 0x00151616, 0x00eaebeb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00737575, 0x00477, 0x00b4241d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00982019, 0x00477, 0x00939494, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f8f8f8, 0x00232525, 0x0025fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00e32d24, 0x00342020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00d82c24, 0x00ee2e24, 0x00ee2e24, 0x00d42a21, 0x00788, 0x00686a6a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x003d3f3f, 0x0011ba, 0x003e11e, 0x003011f, 0x0017dc, 0x00477, 0x00477, 0x00477, 0x00477, 0x00161717, 0x00393b3b, 0x005d5f5f, 0x00808282, 0x00a3a5a5, 0x00d8d8d8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d6d6d6, 0x00799, 0x00541512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x001ced, 0x002b2d2d, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008d8e8e, 0x00477, 0x00a2211b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00832622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x0010ee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151314, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x009d2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00581612, 0x009bb, 0x00dddddd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c9caca, 0x004b4d4d, 0x00323535, 0x00474949, 0x00616262, 0x00848585, 0x00a5a6a6, 0x00cbcbcb, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00464848, 0x00daa, 0x00d32a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00771a15, 0x00477, 0x00b7b8b8, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ebecec, 0x00131414, 0x003a1210, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d62c24, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cf2920, 0x00999, 0x005c5e5e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00acadad, 0x00477, 0x007e1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d22921, 0x00baa, 0x004b4d4d, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006e7070, 0x00477, 0x00bd261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x006b2421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00baa, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00434, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00af2923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00671813, 0x00477, 0x00cfcfcf, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f5f5f5, 0x00212323, 0x0024fe, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00551512, 0x008aa, 0x00d7d7d7, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dadada, 0x008aa, 0x00561512, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c52b23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00452221, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00da2b21, 0x00eba, 0x00484a4a, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x007f8181, 0x00477, 0x00a9231b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b9251d, 0x00477, 0x00717373, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00535555, 0x00ba9, 0x00d12920, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00542321, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00ecc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a12822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00791a15, 0x00477, 0x00bdbebe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00dfdfdf, 0x00cee, 0x00481310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x003511f, 0x00161717, 0x00eeeeee, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c1c2c2, 0x00477, 0x00701914, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ae2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171515, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003b2120, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00e32c23, 0x0018dc, 0x00373939, 0x00fefefe, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00525454, 0x00a99, 0x00cc2820, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00982019, 0x00477, 0x00969797, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x00363838, 0x0017dc, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x00402121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00444, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00922722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008a1d18, 0x00477, 0x00abacac, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b8b9b9, 0x00477, 0x00721915, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00e42c23, 0x001ced, 0x002d2f2f, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00a4a6a6, 0x00477, 0x008b1d18, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00962822, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00312020, 0x00e22d24, 0x00ee2e24, 0x00ee2e24, 0x00e82d23, 0x0023fd, 0x00272929, 0x00fbfbfb, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f9f9f9, 0x002a2c2c, 0x001ded, 0x00e42c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00771a15, 0x00477, 0x00b9baba, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f6f6f6, 0x00212323, 0x0027fe, 0x00ea2d24, 0x00ee2e24, 0x00ee2e24, 0x00e22d24, 0x00322020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00cbb, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00842622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009a201a, 0x00477, 0x00989999, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x008c8d8d, 0x00477, 0x009d211a, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d62a21, 0x00baa, 0x004d4f4f, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00878888, 0x00477, 0x00a7221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fdd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001c191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002a2020, 0x00da2d24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x003011f, 0x001c1d1d, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e6e7e7, 0x00101111, 0x003d1210, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00681813, 0x00588, 0x00d6d6d6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e9eaea, 0x00111212, 0x003f1310, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d42c23, 0x00281f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00a99, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00742522, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ac231c, 0x00477, 0x00858686, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x005e6060, 0x00788, 0x00c4271f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ea2d24, 0x0015cc, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x006b6d6d, 0x00577, 0x00bf261e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00672421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b9a, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00d02c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00401310, 0x00131414, 0x00ebecec, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00c4c5c5, 0x00477, 0x00671813, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x00477, 0x00a1a2a2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00d7d7d7, 0x00799, 0x00591612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c12b23, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1718, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00767, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00652421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bc261e, 0x00477, 0x00737575, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00333535, 0x0017dc, 0x00de2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00971f19, 0x00477, 0x00d2d2d2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x004e5050, 0x00baa, 0x00d42a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00512221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00c42b23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00501411, 0x00acc, 0x00e1e2e2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00999a9a, 0x00477, 0x00911f19, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00961f19, 0x00477, 0x00e0e0e0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00bcbdbd, 0x00477, 0x00751a15, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00aa2923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00161314, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00555, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00572321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00cb2820, 0x00788, 0x00616262, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x00151616, 0x003311f, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00e12d24, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00a6221b, 0x00477, 0x00bcbdbd, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f3f3f3, 0x00272929, 0x001ced, 0x00e22c23, 0x00ee2e24, 0x00ee2e24, 0x00ea2e24, 0x003e2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00151313, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b52a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00611612, 0x00588, 0x00d3d3d3, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00696b6b, 0x00477, 0x00bb251e, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00782522, 0x00d12c23, 0x00ee2e24, 0x00ee2e24, 0x00dd2b22, 0x00999, 0x00626363, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fcfcfc, 0x00545656, 0x00477, 0x00a7221b, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00932722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00121010, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00492221, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00d72a21, 0x00caa, 0x004f5151, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00cfcfcf, 0x00699, 0x005b1612, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x00261f20, 0x009e2822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00631713, 0x00588, 0x00acadad, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ededed, 0x004e5050, 0x00477, 0x00791b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00dc2d24, 0x002f2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00211, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00131011, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a62923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00731a15, 0x00477, 0x00c3c4c4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00fefefe, 0x003e4040, 0x0011bb, 0x00d92a21, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00552321, 0x00231f20, 0x00532321, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x002d11f, 0x00699, 0x00777979, 0x00e5e6e6, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f0f0f0, 0x00969797, 0x001b1c1c, 0x00688, 0x007f1b16, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00622421, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00ecd, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00211d1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x003e2121, 0x00ea2e24, 0x00ee2e24, 0x00ee2e24, 0x00df2c22, 0x0015cc, 0x003c3e3e, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00939494, 0x00477, 0x00881d17, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a82923, 0x00231f20, 0x00231f20, 0x00231f20, 0x00b32a23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00de2b22, 0x00501411, 0x00477, 0x00699, 0x00343636, 0x005c5e5e, 0x00585a5a, 0x003e4040, 0x00bdd, 0x00477, 0x003011f, 0x00b6251d, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x008f2722, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001d1a1b, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0010ee, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00972822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00477, 0x00b1b2b2, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00b2b3b3, 0x00799, 0x003e1210, 0x00ec2e24, 0x00ee2e24, 0x00ee2e24, 0x00e52d24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00372020, 0x00dc2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00bf261e, 0x006b1814, 0x003711f, 0x002110f, 0x001add, 0x003211f, 0x00651713, 0x00b1241c, 0x00ed2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x009b2822, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00342020, 0x00e52d24, 0x00ee2e24, 0x00ee2e24, 0x00e62d23, 0x0020ed, 0x00262828, 0x00f4f4f4, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x009fa0a0, 0x009bb, 0x002910e, 0x00dc2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x007f2622, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00472221, 0x00d62c24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00862622, 0x00241f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191617, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00dcc, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00882622, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00a6221b, 0x00477, 0x00494b4b, 0x00f0f0f0, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00e3e4e4, 0x00565858, 0x00477, 0x003511f, 0x00db2b22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c12b23, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00342020, 0x00a92923, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x00512221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x002d2020, 0x00dc2d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00841c17, 0x00577, 0x001e2020, 0x00959696, 0x00eceded, 0x00ffffff, 0x00ffffff, 0x00ffffff, 0x00f4f4f4, 0x00bbbcbc, 0x00636565, 0x009bb, 0x00898, 0x00711915, 0x00e82d23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d82c24, 0x00382120, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x004f2221, 0x00a42923, 0x00e02d24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00b92a23, 0x00652421, 0x00251f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00fee, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00b9a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x006a2421, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b1241c, 0x002c10e, 0x00477, 0x00477, 0x00232424, 0x00323535, 0x00232424, 0x00699, 0x00477, 0x00a99, 0x00581512, 0x00c8281f, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00d92c24, 0x00442121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00251f20, 0x004c2221, 0x006b2421, 0x00822622, 0x00832622, 0x007b2522, 0x005c2321, 0x00312020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00171516, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001b1819, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00972822, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ed2e24, 0x00b7251d, 0x00751a15, 0x00501410, 0x004312f, 0x00521411, 0x00701914, 0x00a1211a, 0x00e02c22, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00c92b23, 0x003c2121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c1819, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00877, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00241f20, 0x00902722, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00962722, 0x00291f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001c191a, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x005c2321, 0x00d02c23, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00b12923, 0x00482221, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1818, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00544, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x006a2421, 0x00b22a23, 0x00e82e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ee2e24, 0x00ec2e24, 0x00c72b23, 0x008b2722, 0x00422121, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00131112, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x0011ff, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00261f20, 0x00482221, 0x005c2321, 0x00642421, 0x005c2321, 0x004b2221, 0x002a2020, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00a99, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x001a1718, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x0011f10, 0x001e1b1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00211e1e, 0x0011f10, 0x00111, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x001d1a1b, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201c1d, 0x00877, 0x00000, 0x00000, 0x00b9a, 0x00191616, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001e1b1c, 0x0010ef, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00323, 0x001d191a, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001b1819, 0x00433, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00222, 0x00baa, 0x00141112, 0x001b1819, 0x00201d1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x00191617, 0x0011f10, 0x00766, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00212, 0x00181516, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00221e1f, 0x0011ef, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00111, 0x00433, 0x00544, 0x00434, 0x00222, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00fde, 0x00211e1e, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00181516, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00333, 0x00151314, 0x00221e1f, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00191616, 0x00877, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00433, 0x00111010, 0x001f1b1c, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x00231f20, 0x001f1b1c, 0x00131011, 0x00545, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00655, 0x00fdd, 0x00161314, 0x001c1919, 0x00201c1d, 0x00231f20, 0x00231f20, 0x00231f20, 0x00201d1d, 0x001c191a, 0x00161314, 0x00fee, 0x00655, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000, 0x00000}; ->>>>>>> refs/subrepo/core/fetch diff --git a/include/utils/graph_drawer.h b/include/utils/graph_drawer.h index f4f3f97..2df4f8b 100644 --- a/include/utils/graph_drawer.h +++ b/include/utils/graph_drawer.h @@ -18,7 +18,7 @@ class GraphDrawer * @param y_label the name of the y axis (currently unused) * @param draw_border whether to draw the border around the graph. can be turned off if there are multiple graphs in the same space ie. a graph of error and output * @param lower_bound the bottom of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints - * @param upper_bound the top of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints + * @param upper_bound the top of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints */ GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound) : Screen(screen), sample_index(0), xlabel(x_label), ylabel(y_label), col(col), border(draw_border), upper(upper_bound), lower(lower_bound) { diff --git a/src/subsystems/screen.cpp b/src/subsystems/screen.cpp index 4a4f5f4..13af0c8 100644 --- a/src/subsystems/screen.cpp +++ b/src/subsystems/screen.cpp @@ -113,10 +113,10 @@ void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char // PORT screen.drawLine(x + name_width + 50, y, x + name_width + 50, y + 20); - char *warning = "!"; + char *warning = (char *)"!"; if (pluggedin) { - warning = ""; + warning = (char *)""; } screen.printAt(x + name_width + 60, y + 15, "%d%s", port, warning); } @@ -157,10 +157,10 @@ void draw_dev_stats(vex::brain::lcd &screen, int x, int y, int width, const char // PORT screen.drawLine(x + name_width + 50, y, x + name_width + 50, y + 20); - char *warning = "!"; + char *warning = (char *)"!"; if (pluggedin) { - warning = ""; + warning = (char *)""; } screen.printAt(x + name_width + 60, y + 15, "%d%s", port, warning); } From c5bda37890c2a3668610d500d695683f88d043d3 Mon Sep 17 00:00:00 2001 From: cowsed Date: Mon, 17 Apr 2023 18:49:05 -0400 Subject: [PATCH 205/243] grpah drawer to a source file --- include/utils/graph_drawer.h | 113 ++++++----------------------------- src/utils/graph_drawer.cpp | 108 +++++++++++++++++++++++++++++++++ 2 files changed, 125 insertions(+), 96 deletions(-) create mode 100644 src/utils/graph_drawer.cpp diff --git a/include/utils/graph_drawer.h b/include/utils/graph_drawer.h index 2df4f8b..3087d3e 100644 --- a/include/utils/graph_drawer.h +++ b/include/utils/graph_drawer.h @@ -3,117 +3,38 @@ #include #include #include +#include #include "vex.h" #include "../core/include/utils/vector2d.h" class GraphDrawer { public: -/** - * Construct a GraphDrawer - * @brief a helper class to graph values on the brain screen - * @param screen a reference to Brain.screen we can save for later - * @param num_samples the graph works on a fixed window and will plot the last `num_samples` before the history is forgotten. Larger values give more context but may slow down if you have many graphs or an exceptionally high - * @param x_label the name of the x axis (currently unused) - * @param y_label the name of the y axis (currently unused) - * @param draw_border whether to draw the border around the graph. can be turned off if there are multiple graphs in the same space ie. a graph of error and output - * @param lower_bound the bottom of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints - * @param upper_bound the top of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints -*/ - GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound) : Screen(screen), sample_index(0), xlabel(x_label), ylabel(y_label), col(col), border(draw_border), upper(upper_bound), lower(lower_bound) - { - std::vector temp(num_samples, Vector2D::point_t{.x = 0.0, .y = 0.0}); - samples = temp; - } - + /** + * Construct a GraphDrawer + * @brief a helper class to graph values on the brain screen + * @param screen a reference to Brain.screen we can save for later + * @param num_samples the graph works on a fixed window and will plot the last `num_samples` before the history is forgotten. Larger values give more context but may slow down if you have many graphs or an exceptionally high + * @param x_label the name of the x axis (currently unused) + * @param y_label the name of the y axis (currently unused) + * @param draw_border whether to draw the border around the graph. can be turned off if there are multiple graphs in the same space ie. a graph of error and output + * @param lower_bound the bottom of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints + * @param upper_bound the top of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints + */ + GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound); /** * add_sample adds a point to the graph, removing one from the back * @param sample an x, y coordinate of the next point to graph - */ - void add_sample(Vector2D::point_t sample) - { - samples[sample_index] = sample; - sample_index++; - sample_index %= samples.size(); - } + */ + void add_sample(Vector2D::point_t sample); /** * draws the graph to the screen in the constructor * @param x x position of the top left of the graphed region * @param y y position of the top left of the graphed region * @param width the width of the graphed region * @param height the height of the graphed region - */ - void draw(int x, int y, int width, int height) - { - if (samples.size() < 1) - { - return; - } - - double current_min = samples[0].y; - double current_max = samples[0].y; - double earliest_time = samples[0].x; - double latest_time = samples[0].x; - // collect data - for (int i = 0; i < samples.size(); i++) - { - Vector2D::point_t p = samples[i]; - if (p.x < earliest_time) - { - earliest_time = p.x; - } - else if (p.x > latest_time) - { - latest_time = p.x; - } - - if (p.y < current_min) - { - current_min = p.y; - } - else if (p.y > current_max) - { - current_max = p.y; - } - } - if (fabs(latest_time - earliest_time) < 0.001) - { - Screen.printAt(width / 2, height / 2, "Not enough Data"); - return; - } - if (upper != lower) - { - current_min = lower; - current_max = upper; - } - - if (border) - { - Screen.setPenWidth(1); - Screen.setPenColor(vex::white); - Screen.setFillColor(bgcol); - Screen.drawRectangle(x, y, width, height); - } - - double time_range = latest_time - earliest_time; - double sample_range = current_max - current_min; - double x_s = (double)x; - double y_s = (double)y + (double)height; - Screen.setPenWidth(4); - Screen.setPenColor(col); - for (int i = sample_index; i < samples.size() + sample_index - 1; i++) - { - Vector2D::point_t p = samples[i % samples.size()]; - double x_pos = x_s + ((p.x - earliest_time) / time_range) * (double)width; - double y_pos = y_s + ((p.y - current_min) / sample_range) * (double)(-height); - - Vector2D::point_t p2 = samples[(i + 1) % samples.size()]; - double x_pos2 = x_s + ((p2.x - earliest_time) / time_range) * (double)width; - double y_pos2 = y_s + ((p2.y - current_min) / sample_range) * (double)(-height); - - Screen.drawLine((int)x_pos, (int)y_pos, (int)x_pos2, (int)y_pos2); - } - } + */ + void draw(int x, int y, int width, int height); private: vex::brain::lcd &Screen; diff --git a/src/utils/graph_drawer.cpp b/src/utils/graph_drawer.cpp new file mode 100644 index 0000000..4b99563 --- /dev/null +++ b/src/utils/graph_drawer.cpp @@ -0,0 +1,108 @@ +#include "../core/include/utils/graph_drawer.h" + +/** + * Construct a GraphDrawer + * @brief a helper class to graph values on the brain screen + * @param screen a reference to Brain.screen we can save for later + * @param num_samples the graph works on a fixed window and will plot the last `num_samples` before the history is forgotten. Larger values give more context but may slow down if you have many graphs or an exceptionally high + * @param x_label the name of the x axis (currently unused) + * @param y_label the name of the y axis (currently unused) + * @param draw_border whether to draw the border around the graph. can be turned off if there are multiple graphs in the same space ie. a graph of error and output + * @param lower_bound the bottom of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints + * @param upper_bound the top of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints + */ +GraphDrawer::GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound) : Screen(screen), sample_index(0), xlabel(x_label), ylabel(y_label), col(col), border(draw_border), upper(upper_bound), lower(lower_bound) +{ + std::vector temp(num_samples, Vector2D::point_t{.x = 0.0, .y = 0.0}); + samples = temp; +} + +/** + * add_sample adds a point to the graph, removing one from the back + * @param sample an x, y coordinate of the next point to graph + */ +void GraphDrawer::add_sample(Vector2D::point_t sample) +{ + samples[sample_index] = sample; + sample_index++; + sample_index %= samples.size(); +} + +/** + * draws the graph to the screen in the constructor + * @param x x position of the top left of the graphed region + * @param y y position of the top left of the graphed region + * @param width the width of the graphed region + * @param height the height of the graphed region + */ +void GraphDrawer::draw(int x, int y, int width, int height) +{ + if (samples.size() < 1) + { + return; + } + + double current_min = samples[0].y; + double current_max = samples[0].y; + double earliest_time = samples[0].x; + double latest_time = samples[0].x; + // collect data + for (int i = 0; i < samples.size(); i++) + { + Vector2D::point_t p = samples[i]; + if (p.x < earliest_time) + { + earliest_time = p.x; + } + else if (p.x > latest_time) + { + latest_time = p.x; + } + + if (p.y < current_min) + { + current_min = p.y; + } + else if (p.y > current_max) + { + current_max = p.y; + } + } + if (std::abs(latest_time - earliest_time) < 0.001) + { + Screen.printAt(width / 2, height / 2, "Not enough Data"); + return; + } + if (upper != lower) + { + current_min = lower; + current_max = upper; + } + + if (border) + { + Screen.setPenWidth(1); + Screen.setPenColor(vex::white); + Screen.setFillColor(bgcol); + Screen.drawRectangle(x, y, width, height); + } + + double time_range = latest_time - earliest_time; + double sample_range = current_max - current_min; + double x_s = (double)x; + double y_s = (double)y + (double)height; + Screen.setPenWidth(4); + Screen.setPenColor(col); + for (int i = sample_index; i < samples.size() + sample_index - 1; i++) + { + Vector2D::point_t p = samples[i % samples.size()]; + double x_pos = x_s + ((p.x - earliest_time) / time_range) * (double)width; + double y_pos = y_s + ((p.y - current_min) / sample_range) * (double)(-height); + + Vector2D::point_t p2 = samples[(i + 1) % samples.size()]; + double x_pos2 = x_s + ((p2.x - earliest_time) / time_range) * (double)width; + double y_pos2 = y_s + ((p2.y - current_min) / sample_range) * (double)(-height); + + Screen.drawLine((int)x_pos, (int)y_pos, (int)x_pos2, (int)y_pos2); + } +} From 841e3a1cfd24eb73a98055bc5ed2d80e50b2e759 Mon Sep 17 00:00:00 2001 From: cowsed Date: Tue, 18 Apr 2023 18:28:08 -0400 Subject: [PATCH 206/243] Command control applying timeoutsacross vector add initial tunings for flynn skills and auto worlds paths --- .../utils/command_structure/auto_command.h | 3 +- .../command_structure/command_controller.h | 22 ++++--- .../command_structure/command_controller.cpp | 58 ++++++++++++++----- 3 files changed, 58 insertions(+), 25 deletions(-) diff --git a/include/utils/command_structure/auto_command.h b/include/utils/command_structure/auto_command.h index fd44850..e19a356 100644 --- a/include/utils/command_structure/auto_command.h +++ b/include/utils/command_structure/auto_command.h @@ -10,6 +10,7 @@ class AutoCommand { public: + static constexpr double default_timeout = 10.0; /** * Executes the command * Overridden by child classes @@ -33,6 +34,6 @@ class AutoCommand { * - a command that waits until something is up to speed that never gets up to speed because of battery voltage * - something else... */ - double timeout_seconds = 10.0; + double timeout_seconds = default_timeout; }; \ No newline at end of file diff --git a/include/utils/command_structure/command_controller.h b/include/utils/command_structure/command_controller.h index 75766be..2757f1a 100644 --- a/include/utils/command_structure/command_controller.h +++ b/include/utils/command_structure/command_controller.h @@ -12,22 +12,28 @@ #include #include "../core/include/utils/command_structure/auto_command.h" -class CommandController { - public: - +class CommandController +{ +public: /** * Adds a command to the queue * @param cmd the AutoCommand we want to add to our list * @param timeout_seconds the number of seconds we will let the command run for. If it exceeds this, we cancel it and run on_timeout. if it is <= 0 no time out will be applied */ void add(AutoCommand *cmd, double timeout_seconds = 10.0); - + /** - * Add multiple commands to the queue. No timeout here. + * Add multiple commands to the queue. No timeout here. * @param cmds the AutoCommands we want to add to our list */ void add(std::vector cmds); + /** + * Add multiple commands to the queue. No timeout here. + * @param cmds the AutoCommands we want to add to our list + * @param timeout_sec timeout in seconds to apply to all commands if they are still the default + */ + void add(std::vector cmds, double timeout_sec); /** * Adds a command that will delay progression * of the queue @@ -48,7 +54,7 @@ class CommandController { */ bool last_command_timed_out(); - private: - std::queue command_queue; - bool command_timed_out = false; +private: + std::queue command_queue; + bool command_timed_out = false; }; \ No newline at end of file diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index 0a83bff..782ca0a 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -6,7 +6,7 @@ * a queue and get executed and removed from the queue * in FIFO order. */ - +#include #include "../core/include/utils/command_structure/command_controller.h" #include "../core/include/utils/command_structure/delay_command.h" @@ -15,19 +15,39 @@ * @param cmd the AutoCommand we want to add to our list * @param timeout_seconds the number of seconds we will let the command run for. If it exceeds this, we cancel it and run on_timeout */ -void CommandController::add(AutoCommand *cmd, double timeout_seconds) { +void CommandController::add(AutoCommand *cmd, double timeout_seconds) +{ cmd->timeout_seconds = timeout_seconds; command_queue.push(cmd); } /** - * Add multiple commands to the queue. No timeout here. + * Add multiple commands to the queue. No timeout here. * @param cmds the AutoCommands we want to add to our list */ -void CommandController::add(std::vector cmds) { - for(AutoCommand * cmd : cmds){ +void CommandController::add(std::vector cmds) +{ + for (AutoCommand *cmd : cmds) + { command_queue.push(cmd); - } + } +} + +/** + * Add multiple commands to the queue. No timeout here. + * @param cmds the AutoCommands we want to add to our list + * @param timeout timeout in seconds to apply to all commands if they are still the default + */ +void CommandController::add(std::vector cmds, double timeout_sec) +{ + for (AutoCommand *cmd : cmds) + { + if (cmd->timeout_seconds == AutoCommand::default_timeout) + { + cmd->timeout_seconds = timeout_sec; + } + command_queue.push(cmd); + } } /** @@ -36,7 +56,8 @@ void CommandController::add(std::vector cmds) { * @param ms - number of milliseconds to wait * before continuing execution of autonomous */ -void CommandController::add_delay(int ms) { +void CommandController::add_delay(int ms) +{ AutoCommand *delay = new DelayCommand(ms); command_queue.push(delay); } @@ -45,7 +66,8 @@ void CommandController::add_delay(int ms) { * Begin execution of the queue * Execute and remove commands in FIFO order */ -void CommandController::run() { +void CommandController::run() +{ AutoCommand *next_cmd; printf("Running Auto. Commands 1 to %d\n", command_queue.size()); fflush(stdout); @@ -53,7 +75,8 @@ void CommandController::run() { vex::timer tmr; tmr.reset(); - while(!command_queue.empty()) { + while (!command_queue.empty()) + { // retrieve and remove command at the front of the queue next_cmd = command_queue.front(); command_queue.pop(); @@ -62,35 +85,38 @@ void CommandController::run() { printf("Beginning Command %d : timeout = %.2f : at time = %.1f seconds\n", command_count, next_cmd->timeout_seconds, tmr.time(vex::seconds)); fflush(stdout); - vex::timer timeout_timer; timeout_timer.reset(); bool doTimeout = next_cmd->timeout_seconds > 0.0; // run the current command until it returns true or we timeout - while(!next_cmd -> run()) { + while (!next_cmd->run()) + { vexDelay(20); - if (!doTimeout){ + if (!doTimeout) + { continue; } // If we do want to check for timeout, check and end the command if we should - double cmd_elapsed_sec = ((double)timeout_timer.time())/1000.0; - if (cmd_elapsed_sec > next_cmd->timeout_seconds){ + double cmd_elapsed_sec = ((double)timeout_timer.time()) / 1000.0; + if (cmd_elapsed_sec > next_cmd->timeout_seconds) + { next_cmd->on_timeout(); command_timed_out = true; break; } } - printf("Finished Command %d. Timed out: %s\n", command_count, command_timed_out ? "true" : "false" ); + printf("Finished Command %d. Timed out: %s\n", command_count, command_timed_out ? "true" : "false"); fflush(stdout); command_count++; } printf("Finished commands in %f seconds\n", tmr.time(vex::sec)); } -bool CommandController::last_command_timed_out(){ +bool CommandController::last_command_timed_out() +{ return command_timed_out; } \ No newline at end of file From d637387dff3eb96f7c0b29e7e03794bf21c2b20d Mon Sep 17 00:00:00 2001 From: cowsed Date: Tue, 16 May 2023 12:22:23 -0400 Subject: [PATCH 207/243] geometry.h created holds point_t (2d point) and pose_t (2d pose) --- include/subsystems/odometry/odometry_3wheel.h | 4 +- include/subsystems/odometry/odometry_base.h | 25 +++----- include/subsystems/odometry/odometry_tank.h | 7 ++- .../utils/command_structure/drive_commands.h | 7 ++- include/utils/geometry.h | 58 +++++++++++++++++++ include/utils/graph_drawer.h | 5 +- include/utils/pure_pursuit.h | 15 ++--- include/utils/vector2d.h | 55 +----------------- src/subsystems/odometry/odometry_3wheel.cpp | 10 ++-- src/subsystems/odometry/odometry_base.cpp | 10 ++-- src/subsystems/odometry/odometry_tank.cpp | 12 ++-- src/subsystems/tank_drive.cpp | 15 ++--- .../command_structure/drive_commands.cpp | 4 +- src/utils/graph_drawer.cpp | 10 ++-- src/utils/motion_controller.cpp | 2 +- src/utils/pure_pursuit.cpp | 56 +++++++++--------- src/utils/vector2d.cpp | 2 +- 17 files changed, 152 insertions(+), 145 deletions(-) create mode 100644 include/utils/geometry.h diff --git a/include/subsystems/odometry/odometry_3wheel.h b/include/subsystems/odometry/odometry_3wheel.h index f66da93..15ce85d 100644 --- a/include/subsystems/odometry/odometry_3wheel.h +++ b/include/subsystems/odometry/odometry_3wheel.h @@ -62,7 +62,7 @@ class Odometry3Wheel : public OdometryBase * * @return the robot's updated position */ - position_t update() override; + pose_t update() override; /** * A guided tuning process to automatically find tuning parameters. @@ -88,7 +88,7 @@ class Odometry3Wheel : public OdometryBase * @param cfg Data on robot's configuration (wheel diameter, wheelbase, off-axis distance from center) * @return The robot's new position (x, y, rot) */ - static position_t calculate_new_pos(double lside_delta_deg, double rside_delta_deg, double offax_delta_deg, position_t old_pos, odometry3wheel_cfg_t cfg); + static pose_t calculate_new_pos(double lside_delta_deg, double rside_delta_deg, double offax_delta_deg, pose_t old_pos, odometry3wheel_cfg_t cfg); CustomEncoder &lside_fwd, &rside_fwd, &off_axis; odometry3wheel_cfg_t &cfg; diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index 25128d8..304a2c4 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -1,21 +1,14 @@ #pragma once #include "vex.h" +#include "../core/include/utils/geometry.h" #include "../core/include/robot_specs.h" #ifndef PI #define PI 3.141592654 #endif -/** - * Describes a single position and rotation - */ -typedef struct -{ - double x; ///< x position in the world - double y; ///< y position in the world - double rot; ///< rotation in the world -} position_t; + /** * OdometryBase @@ -44,19 +37,19 @@ class OdometryBase * Gets the current position and rotation * @return the position that the odometry believes the robot is at */ - position_t get_position(void); + pose_t get_position(void); /** * Sets the current position of the robot * @param newpos the new position that the odometry will believe it is at */ - virtual void set_position(const position_t& newpos=zero_pos); + virtual void set_position(const pose_t& newpos=zero_pos); /** * Update the current position on the field based on the sensors * @return the location that the robot is at after the odometry does its calculations */ - virtual position_t update() = 0; + virtual pose_t update() = 0; /** * Function that runs in the background task. This function pointer is passed @@ -80,7 +73,7 @@ class OdometryBase * @param end_pos to this point * @return the euclidean distance between start_pos and end_pos */ - static double pos_diff(position_t start_pos, position_t end_pos); + static double pos_diff(pose_t start_pos, pose_t end_pos); /** * Get the change in rotation between two points @@ -88,7 +81,7 @@ class OdometryBase * @param pos2 position with final rotation * @return change in rotation between pos1 and pos2 */ - static double rot_diff(position_t pos1, position_t pos2); + static double rot_diff(pose_t pos1, pose_t pos2); /** * Get the smallest difference in angle between a start heading and end heading. @@ -130,7 +123,7 @@ class OdometryBase /** * Zeroed position. X=0, Y=0, Rotation= 90 degrees */ - inline static constexpr position_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}; + inline static constexpr pose_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}; protected: /** @@ -146,7 +139,7 @@ class OdometryBase /** * Current position of the robot in terms of x,y,rotation */ - position_t current_pos; + pose_t current_pos; double speed; /**< the speed at which we are travelling (inch/s)*/ double accel; /**< the rate at which we are accelerating (inch/s^2)*/ diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index 2a2a92f..6c35e10 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -2,6 +2,7 @@ #include "../core/include/subsystems/odometry/odometry_base.h" #include "../core/include/subsystems/custom_encoder.h" +#include "../core/include/utils/geometry.h" #include "../core/include/utils/vector2d.h" #include "../core/include/robot_specs.h" @@ -42,13 +43,13 @@ class OdometryTank : public OdometryBase * Update the current position on the field based on the sensors * @return the position that odometry has calculated itself to be at */ - position_t update() override; + pose_t update() override; /** * set_position tells the odometry to place itself at a position * @param newpos the position the odometry will take */ - void set_position(const position_t &newpos=zero_pos) override; + void set_position(const pose_t &newpos=zero_pos) override; @@ -56,7 +57,7 @@ class OdometryTank : public OdometryBase /** * Get information from the input hardware and an existing position, and calculate a new current position */ - static position_t calculate_new_pos(robot_specs_t &config, position_t &stored_info, double lside_diff, double rside_diff, double angle_deg); + static pose_t calculate_new_pos(robot_specs_t &config, pose_t &stored_info, double lside_diff, double rside_diff, double angle_deg); vex::motor_group *left_side, *right_side; CustomEncoder *left_enc, *right_enc; diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index fba33f2..97a08d7 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -19,6 +19,7 @@ #pragma once #include "vex.h" +#include "../core/include/utils/geometry.h" #include "../core/include/utils/command_structure/auto_command.h" #include "../core/include/subsystems/tank_drive.h" @@ -99,7 +100,7 @@ class TurnDegreesCommand: public AutoCommand { class DriveToPointCommand: public AutoCommand { public: DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed = 1); - DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, Vector2D::point_t point, directionType dir, double max_speed=1); + DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, point_t point, directionType dir, double max_speed=1); /** * Run drive_to_point @@ -197,7 +198,7 @@ class OdomSetPosition: public AutoCommand { * @param odom the odometry system we are setting * @param newpos the position we are telling the odometry to take. defaults to (0, 0), angle = 90 */ - OdomSetPosition(OdometryBase &odom, const position_t &newpos=OdometryBase::zero_pos); + OdomSetPosition(OdometryBase &odom, const pose_t &newpos=OdometryBase::zero_pos); /** * Run set_position @@ -209,5 +210,5 @@ class OdomSetPosition: public AutoCommand { private: // drive system with an odometry config OdometryBase &odom; - position_t newpos; + pose_t newpos; }; diff --git a/include/utils/geometry.h b/include/utils/geometry.h new file mode 100644 index 0000000..5730e6d --- /dev/null +++ b/include/utils/geometry.h @@ -0,0 +1,58 @@ +#pragma once +#include + +/** + * Data structure representing an X,Y coordinate + */ +struct point_t +{ + double x; ///< the x position in space + double y; ///< the y position in space + + /** + * dist calculates the euclidian distance between this point and another point using the pythagorean theorem + * @param other the point to measure the distance from + * @return the euclidian distance between this and other + */ + double dist(const point_t other) + { + return std::sqrt(std::pow(this->x - other.x, 2) + pow(this->y - other.y, 2)); + } + + /** + * Vector2D addition operation on points + * @param other the point to add on to this + * @return this + other (this.x + other.x, this.y + other.y) + */ + point_t operator+(const point_t &other) + { + point_t p{ + .x = this->x + other.x, + .y = this->y + other.y}; + return p; + } + + /** + * Vector2D subtraction operation on points + * @param other the point_t to subtract from this + * @return this - other (this.x - other.x, this.y - other.y) + */ + point_t operator-(const point_t &other) + { + point_t p{ + .x = this->x - other.x, + .y = this->y - other.y}; + return p; + } +}; + + +/** + * Describes a single position and rotation + */ +typedef struct +{ + double x; ///< x position in the world + double y; ///< y position in the world + double rot; ///< rotation in the world +} pose_t; \ No newline at end of file diff --git a/include/utils/graph_drawer.h b/include/utils/graph_drawer.h index 3087d3e..09cce09 100644 --- a/include/utils/graph_drawer.h +++ b/include/utils/graph_drawer.h @@ -5,6 +5,7 @@ #include #include #include "vex.h" +#include "../core/include/utils/geometry.h" #include "../core/include/utils/vector2d.h" class GraphDrawer @@ -26,7 +27,7 @@ class GraphDrawer * add_sample adds a point to the graph, removing one from the back * @param sample an x, y coordinate of the next point to graph */ - void add_sample(Vector2D::point_t sample); + void add_sample(point_t sample); /** * draws the graph to the screen in the constructor * @param x x position of the top left of the graphed region @@ -38,7 +39,7 @@ class GraphDrawer private: vex::brain::lcd &Screen; - std::vector samples; + std::vector samples; int sample_index = 0; std::string xlabel; std::string ylabel; diff --git a/include/utils/pure_pursuit.h b/include/utils/pure_pursuit.h index e14f8f6..f3f427c 100644 --- a/include/utils/pure_pursuit.h +++ b/include/utils/pure_pursuit.h @@ -1,6 +1,7 @@ #pragma once #include +#include "../core/include/utils/geometry.h" #include "../core/include/utils/vector2d.h" #include "vex.h" @@ -30,7 +31,7 @@ namespace PurePursuit { double dir; double mag; - Vector2D::point_t getPoint() { + point_t getPoint() { return {x, y}; } @@ -43,16 +44,16 @@ namespace PurePursuit { * Returns points of the intersections of a line segment and a circle. The line * segment is defined by two points, and the circle is defined by a center and radius. */ - static std::vector line_circle_intersections(Vector2D::point_t center, double r, Vector2D::point_t point1, Vector2D::point_t point2); + static std::vector line_circle_intersections(point_t center, double r, point_t point1, point_t point2); /** * Selects a look ahead from all the intersections in the path. */ - static Vector2D::point_t get_lookahead(std::vector path, Vector2D::point_t robot_loc, double radius); + static point_t get_lookahead(std::vector path, point_t robot_loc, double radius); /** * Injects points in a path without changing the curvature with a certain spacing. */ - static std::vector inject_path(std::vector path, double spacing); + static std::vector inject_path(std::vector path, double spacing); /** * Returns a smoothed path maintaining the start and end of the path. @@ -65,9 +66,9 @@ namespace PurePursuit { * https://medium.com/@jaems33/understanding-robot-motion-path-smoothing-5970c8363bc4 */ - static std::vector smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance); + static std::vector smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance); - static std::vector smooth_path_cubic(std::vector path, double res); + static std::vector smooth_path_cubic(std::vector path, double res); /** * Interpolates a smooth path given a list of waypoints using hermite splines. @@ -77,5 +78,5 @@ namespace PurePursuit { * @param steps The number of points interpolated between points. * @return The smoothed path. */ - static std::vector smooth_path_hermite(std::vector path, double step); + static std::vector smooth_path_hermite(std::vector path, double step); } \ No newline at end of file diff --git a/include/utils/vector2d.h b/include/utils/vector2d.h index 221cb84..c39f50f 100644 --- a/include/utils/vector2d.h +++ b/include/utils/vector2d.h @@ -1,6 +1,8 @@ #pragma once + #include +#include "../core/include/utils/geometry.h" #ifndef PI #define PI 3.141592654 @@ -13,57 +15,6 @@ class Vector2D { public: - - /** - * Data structure representing an X,Y coordinate - */ - struct point_t - { - double x; ///< the x position in space - double y; ///< the y position in space - - - /** - * dist calculates the euclidian distance between this point and another point using the pythagorean theorem - * @param other the point to measure the distance from - * @return the euclidian distance between this and other - */ - double dist(const point_t other) - { - return sqrt(pow(this->x - other.x, 2) + pow(this->y - other.y, 2)); - } - - /** - * Vector2D addition operation on points - * @param other the point to add on to this - * @return this + other (this.x + other.x, this.y + other.y) - */ - point_t operator+(const point_t &other) - { - point_t p - { - .x = this->x + other.x, - .y = this->y + other.y - }; - return p; - } - - /** - * Vector2D subtraction operation on points - * @param other the point_t to subtract from this - * @return this - other (this.x - other.x, this.y - other.y) - */ - point_t operator-(const point_t &other) - { - point_t p - { - .x = this->x - other.x, - .y = this->y - other.y - }; - return p; - } - }; - /** * Construct a vector object. * @@ -113,7 +64,7 @@ class Vector2D * Returns a point from the vector * @return the point represented by the vector */ - Vector2D::point_t point(); + point_t point(); /** * Scales a Vector2D by a scalar with the * operator diff --git a/src/subsystems/odometry/odometry_3wheel.cpp b/src/subsystems/odometry/odometry_3wheel.cpp index a032512..4715559 100644 --- a/src/subsystems/odometry/odometry_3wheel.cpp +++ b/src/subsystems/odometry/odometry_3wheel.cpp @@ -12,7 +12,7 @@ Odometry3Wheel::Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fw * * @return the robot's updated position */ -position_t Odometry3Wheel::update() +pose_t Odometry3Wheel::update() { static double lside_old=0, rside_old=0, offax_old=0; @@ -28,9 +28,9 @@ position_t Odometry3Wheel::update() rside_old = rside; offax_old = offax; - position_t updated_pos = calculate_new_pos(lside_delta, rside_delta, offax_delta, current_pos, cfg); + pose_t updated_pos = calculate_new_pos(lside_delta, rside_delta, offax_delta, current_pos, cfg); - static position_t last_pos = updated_pos; + static pose_t last_pos = updated_pos; static double last_speed = 0; static double last_ang_speed = 0; static timer tmr; @@ -86,9 +86,9 @@ position_t Odometry3Wheel::update() * @param cfg Data on robot's configuration (wheel diameter, wheelbase, off-axis distance from center) * @return The robot's new position (x, y, rot) */ -position_t Odometry3Wheel::calculate_new_pos(double lside_delta_deg, double rside_delta_deg, double offax_delta_deg, position_t old_pos, odometry3wheel_cfg_t cfg) +pose_t Odometry3Wheel::calculate_new_pos(double lside_delta_deg, double rside_delta_deg, double offax_delta_deg, pose_t old_pos, odometry3wheel_cfg_t cfg) { - position_t retval = {}; + pose_t retval = {}; // Arclength formula for encoder degrees -> single wheel distance driven double lside_dist = (cfg.wheel_diam / 2.0) * deg2rad(lside_delta_deg); diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index ecbfae0..fad0728 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -45,12 +45,12 @@ void OdometryBase::end_async() /** * Gets the current position and rotation */ -position_t OdometryBase::get_position(void) +pose_t OdometryBase::get_position(void) { mut.lock(); // Create a new struct to pass-by-value - position_t out = current_pos; + pose_t out = current_pos; mut.unlock(); @@ -60,7 +60,7 @@ position_t OdometryBase::get_position(void) /** * Sets the current position of the robot */ -void OdometryBase::set_position(const position_t& newpos) +void OdometryBase::set_position(const pose_t& newpos) { mut.lock(); @@ -75,7 +75,7 @@ void OdometryBase::set_position(const position_t& newpos) * @param end_pos to this point * @return the euclidean distance between start_pos and end_pos */ -double OdometryBase::pos_diff(position_t start_pos, position_t end_pos) +double OdometryBase::pos_diff(pose_t start_pos, pose_t end_pos) { // Use the pythagorean theorem double retval = sqrt(pow(end_pos.x - start_pos.x, 2) + pow(end_pos.y - start_pos.y, 2)); @@ -86,7 +86,7 @@ double OdometryBase::pos_diff(position_t start_pos, position_t end_pos) /** * Get the change in rotation between two points */ -double OdometryBase::rot_diff(position_t pos1, position_t pos2) +double OdometryBase::rot_diff(pose_t pos1, pose_t pos2) { return pos1.rot - pos2.rot; } diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 404f865..e594ef4 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -30,7 +30,7 @@ OdometryTank::OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, ro * Resets the position and rotational data to the input. * */ -void OdometryTank::set_position(const position_t &newpos) +void OdometryTank::set_position(const pose_t &newpos) { mut.lock(); rotation_offset = newpos.rot - (current_pos.rot - rotation_offset); @@ -43,7 +43,7 @@ void OdometryTank::set_position(const position_t &newpos) * Update, store and return the current position of the robot. Only use if not initializing * with a separate thread. */ -position_t OdometryTank::update() +pose_t OdometryTank::update() { double lside_revs = 0, rside_revs = 0; @@ -92,7 +92,7 @@ position_t OdometryTank::update() current_pos = calculate_new_pos(config, current_pos, lside_revs, rside_revs, angle); - static position_t last_pos = current_pos; + static pose_t last_pos = current_pos; static double last_speed = 0; static double last_ang_speed = 0; static timer tmr; @@ -126,9 +126,9 @@ position_t OdometryTank::update() * Using information about the robot's mechanical structure and sensors, calculate a new position * of the robot, relative to when this method was previously ran. */ -position_t OdometryTank::calculate_new_pos(robot_specs_t &config, position_t &curr_pos, double lside_revs, double rside_revs, double angle_deg) +pose_t OdometryTank::calculate_new_pos(robot_specs_t &config, pose_t &curr_pos, double lside_revs, double rside_revs, double angle_deg) { - position_t new_pos; + pose_t new_pos; static double stored_lside_revs = lside_revs; static double stored_rside_revs = rside_revs; @@ -145,7 +145,7 @@ position_t OdometryTank::calculate_new_pos(robot_specs_t &config, position_t &cu Vector2D chg_vec(angle, dist_driven); // Create a vector from the current position in reference to X,Y=0,0 - Vector2D::point_t curr_point = {.x = curr_pos.x, .y = curr_pos.y}; + point_t curr_point = {.x = curr_pos.x, .y = curr_pos.y}; Vector2D curr_vec(curr_point); // Tack on the "difference" vector to the current vector diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 812f6bd..6c0353e 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -1,3 +1,4 @@ +#include "../core/include/utils/geometry.h" #include "../core/include/subsystems/tank_drive.h" #include "../core/include/utils/math_util.h" @@ -76,7 +77,7 @@ void TankDrive::drive_arcade(double forward_back, double left_right, int power) */ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed) { - static position_t pos_setpt; + static pose_t pos_setpt; // We can't run the auto drive function without odometry if(odometry == NULL) @@ -89,7 +90,7 @@ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedba // Generate a point X inches forward of the current position, on first startup if (!func_initialized) { - position_t cur_pos = odometry->get_position(); + pose_t cur_pos = odometry->get_position(); // forwards is positive Y axis, backwards is negative if (dir == directionType::rev) @@ -221,11 +222,11 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb } // Store the initial position of the robot - position_t current_pos = odometry->get_position(); - position_t end_pos = {.x=x, .y=y}; + pose_t current_pos = odometry->get_position(); + pose_t end_pos = {.x=x, .y=y}; // Create a point (and vector) to get the direction - Vector2D::point_t pos_diff_pt = + point_t pos_diff_pt = { .x = x - current_pos.x, .y = y - current_pos.y @@ -411,9 +412,9 @@ double TankDrive::modify_inputs(double input, int power) bool TankDrive::pure_pursuit(std::vector path, directionType dir, double radius, double res, Feedback &feedback, double max_speed) { is_pure_pursuit = true; - std::vector smoothed_path = PurePursuit::smooth_path_hermite(path, res); + std::vector smoothed_path = PurePursuit::smooth_path_hermite(path, res); - Vector2D::point_t lookahead = PurePursuit::get_lookahead(smoothed_path, {odometry->get_position().x, odometry->get_position().y}, radius); + point_t lookahead = PurePursuit::get_lookahead(smoothed_path, {odometry->get_position().x, odometry->get_position().y}, radius); //printf("%f\t%f\n", odometry->get_position().x, odometry->get_position().y); //printf("%f\t%f\n", lookahead.x, lookahead.y); bool is_last_point = (path.back().x == lookahead.x) && (path.back().y == lookahead.y); diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index 6e8ea45..dbb5d3d 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -97,7 +97,7 @@ DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedbac * @param dir the direction to drive * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at */ -DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, Vector2D::point_t point, directionType dir, double max_speed): +DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, point_t point, directionType dir, double max_speed): drive_sys(drive_sys), feedback(feedback), x(point.x), y(point.y), dir(dir), max_speed(max_speed) {} /** @@ -173,7 +173,7 @@ bool DriveStopCommand::run() { * @param odom the odometry system we are setting * @param newpos the now position to set the odometry to */ -OdomSetPosition::OdomSetPosition(OdometryBase &odom, const position_t &newpos): odom(odom), newpos(newpos){} +OdomSetPosition::OdomSetPosition(OdometryBase &odom, const pose_t &newpos): odom(odom), newpos(newpos){} bool OdomSetPosition::run() { odom.set_position(newpos); diff --git a/src/utils/graph_drawer.cpp b/src/utils/graph_drawer.cpp index 4b99563..3386620 100644 --- a/src/utils/graph_drawer.cpp +++ b/src/utils/graph_drawer.cpp @@ -13,7 +13,7 @@ */ GraphDrawer::GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound) : Screen(screen), sample_index(0), xlabel(x_label), ylabel(y_label), col(col), border(draw_border), upper(upper_bound), lower(lower_bound) { - std::vector temp(num_samples, Vector2D::point_t{.x = 0.0, .y = 0.0}); + std::vector temp(num_samples, point_t{.x = 0.0, .y = 0.0}); samples = temp; } @@ -21,7 +21,7 @@ GraphDrawer::GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x * add_sample adds a point to the graph, removing one from the back * @param sample an x, y coordinate of the next point to graph */ -void GraphDrawer::add_sample(Vector2D::point_t sample) +void GraphDrawer::add_sample(point_t sample) { samples[sample_index] = sample; sample_index++; @@ -49,7 +49,7 @@ void GraphDrawer::draw(int x, int y, int width, int height) // collect data for (int i = 0; i < samples.size(); i++) { - Vector2D::point_t p = samples[i]; + point_t p = samples[i]; if (p.x < earliest_time) { earliest_time = p.x; @@ -95,11 +95,11 @@ void GraphDrawer::draw(int x, int y, int width, int height) Screen.setPenColor(col); for (int i = sample_index; i < samples.size() + sample_index - 1; i++) { - Vector2D::point_t p = samples[i % samples.size()]; + point_t p = samples[i % samples.size()]; double x_pos = x_s + ((p.x - earliest_time) / time_range) * (double)width; double y_pos = y_s + ((p.y - current_min) / sample_range) * (double)(-height); - Vector2D::point_t p2 = samples[(i + 1) % samples.size()]; + point_t p2 = samples[(i + 1) % samples.size()]; double x_pos2 = x_s + ((p2.x - earliest_time) / time_range) * (double)width; double y_pos2 = y_s + ((p2.y - current_min) / sample_range) * (double)(-height); diff --git a/src/utils/motion_controller.cpp b/src/utils/motion_controller.cpp index 9d915ca..a68770a 100644 --- a/src/utils/motion_controller.cpp +++ b/src/utils/motion_controller.cpp @@ -107,7 +107,7 @@ FeedForward::ff_config_t MotionController::tune_feedforward(TankDrive &drive, Od { FeedForward::ff_config_t out = {}; - position_t start_pos = odometry.get_position(); + pose_t start_pos = odometry.get_position(); // ========== kS Tuning ========= // Start at 0 and slowly increase the power until the robot starts moving diff --git a/src/utils/pure_pursuit.cpp b/src/utils/pure_pursuit.cpp index 4b28a3c..6c70ad1 100644 --- a/src/utils/pure_pursuit.cpp +++ b/src/utils/pure_pursuit.cpp @@ -4,9 +4,9 @@ * Returns points of the intersections of a line segment and a circle. The line * segment is defined by two points, and the circle is defined by a center and radius. */ -std::vector PurePursuit::line_circle_intersections(Vector2D::point_t center, double r, Vector2D::point_t point1, Vector2D::point_t point2) +std::vector PurePursuit::line_circle_intersections(point_t center, double r, point_t point1, point_t point2) { - std::vector intersections = {}; + std::vector intersections = {}; //Do future calculations relative to the circle's center point1.y -= center.y; @@ -38,12 +38,12 @@ std::vector PurePursuit::line_circle_intersections(Vector2D:: //The equations used define an infinitely long line, so we check if the detected intersection falls on the line segment. if(x1 >= fmin(point1.x, point2.x) && x1 <= fmax(point1.x, point2.x) && y1 >= fmin(point1.y, point2.y) && y1 <= fmax(point1.y, point2.y)) { - intersections.push_back(Vector2D::point_t{.x = x1 + center.x, .y = y1 + center.y}); + intersections.push_back(point_t{.x = x1 + center.x, .y = y1 + center.y}); } if(x2 >= fmin(point1.x, point2.x) && x2 <= fmax(point1.x, point2.x) && y2 >= fmin(point1.y, point2.y) && y2 <= fmax(point1.y, point2.y)) { - intersections.push_back(Vector2D::point_t{.x = x2 + center.x, .y = y2 + center.y}); + intersections.push_back(point_t{.x = x2 + center.x, .y = y2 + center.y}); } return intersections; @@ -52,10 +52,10 @@ std::vector PurePursuit::line_circle_intersections(Vector2D:: /** * Selects a look ahead from all the intersections in the path. */ -Vector2D::point_t PurePursuit::get_lookahead(std::vector path, Vector2D::point_t robot_loc, double radius) +point_t PurePursuit::get_lookahead(std::vector path, point_t robot_loc, double radius) { //Default: the end of the path - Vector2D::point_t target = path.back(); + point_t target = path.back(); if(target.dist(robot_loc) <= radius) @@ -66,13 +66,13 @@ Vector2D::point_t PurePursuit::get_lookahead(std::vector path //Check each line segment of the path for potential targets for(int i = 0; i < path.size() - 1; i++) { - Vector2D::point_t start = path[i]; - Vector2D::point_t end = path[i+1]; + point_t start = path[i]; + point_t end = path[i+1]; - std::vector intersections = line_circle_intersections(robot_loc, radius, start, end); + std::vector intersections = line_circle_intersections(robot_loc, radius, start, end); //Choose the intersection that is closest to the end of the line segment //This prioritizes the closest intersection to the end of the path - for(Vector2D::point_t intersection: intersections) + for(point_t intersection: intersections) { if(intersection.dist(end) < target.dist(end)) target = intersection; @@ -85,17 +85,17 @@ Vector2D::point_t PurePursuit::get_lookahead(std::vector path /** Injects points in a path without changing the curvature with a certain spacing. */ -std::vector PurePursuit::inject_path(std::vector path, double spacing) +std::vector PurePursuit::inject_path(std::vector path, double spacing) { - std::vector new_path; + std::vector new_path; //Injecting points for each line segment for(int i = 0; i < path.size() - 1; i++) { - Vector2D::point_t start = path[i]; - Vector2D::point_t end = path[i+1]; + point_t start = path[i]; + point_t end = path[i+1]; - Vector2D::point_t diff = end - start; + point_t diff = end - start; Vector2D vector = Vector2D(diff); int num_points = ceil(vector.get_mag() / spacing); @@ -106,7 +106,7 @@ std::vector PurePursuit::inject_path(std::vector PurePursuit::inject_path(std::vector PurePursuit::smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance) +std::vector PurePursuit::smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance) { - std::vector new_path = path; + std::vector new_path = path; double change = tolerance; while(change >= tolerance) { change = 0; for(int i = 1; i < path.size() - 1; i++) { - Vector2D::point_t x_i = path[i]; - Vector2D::point_t y_i = new_path[i]; - Vector2D::point_t y_prev = new_path[i-1]; - Vector2D::point_t y_next = new_path[i+1]; + point_t x_i = path[i]; + point_t y_i = new_path[i]; + point_t y_prev = new_path[i-1]; + point_t y_next = new_path[i+1]; - Vector2D::point_t y_i_saved = y_i; + point_t y_i_saved = y_i; y_i.x += weight_data * (x_i.x - y_i.x) + weight_smooth * (y_next.x + y_prev.x - (2 * y_i.x)); y_i.y += weight_data * (x_i.y - y_i.y) + weight_smooth * (y_next.y + y_prev.y - (2 * y_i.y)); @@ -159,12 +159,12 @@ std::vector PurePursuit::smooth_path(std::vector PurePursuit::smooth_path_hermite(std::vector path, double steps) { - std::vector new_path; +std::vector PurePursuit::smooth_path_hermite(std::vector path, double steps) { + std::vector new_path; for(int i = 0; i < path.size() - 1; i++) { for(int t = 0; t < steps; t++) { // Storing the start and end points and slopes at those points as Vector2Ds. - Vector2D::point_t tmp = path[i].getPoint(); + point_t tmp = path[i].getPoint(); Vector2D p1 = Vector2D(tmp); tmp = path[i+1].getPoint(); Vector2D p2 = Vector2D(tmp); @@ -191,8 +191,8 @@ std::vector PurePursuit::smooth_path_hermite(std::vector PurePursuit::smooth_path_cubic(std::vector path, double res) { - std::vector new_path; +std::vector PurePursuit::smooth_path_cubic(std::vector path, double res) { + std::vector new_path; std::vector splines; double delta_x[path.size() - 1]; diff --git a/src/utils/vector2d.cpp b/src/utils/vector2d.cpp index 322dd6f..8399b5f 100644 --- a/src/utils/vector2d.cpp +++ b/src/utils/vector2d.cpp @@ -64,7 +64,7 @@ Vector2D Vector2D::normalize() * Convert a direction and magnitude representation to an x, y representation * @return the x, y representation of the vector */ -Vector2D::point_t Vector2D::point() +point_t Vector2D::point() { point_t p = { From 21a91b9f3696891e3ef6eb0b7e382678e9d3e368 Mon Sep 17 00:00:00 2001 From: cowsed Date: Wed, 21 Jun 2023 19:53:32 -0400 Subject: [PATCH 208/243] fixed ternary in modify inputs --- src/subsystems/tank_drive.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 6c0353e..92c613b 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -406,7 +406,7 @@ bool TankDrive::turn_to_heading(double heading_deg, double max_speed) */ double TankDrive::modify_inputs(double input, int power) { - return (power % 2 == 0 ? (input < 0 ? -1 : 1) : 1) * pow(input, power); + return sign(input)* pow(std::abs(input), power); } bool TankDrive::pure_pursuit(std::vector path, directionType dir, double radius, double res, Feedback &feedback, double max_speed) From 9cc5b1d9ac6b64c6866af4955b257cd3868973f4 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 10 Sep 2023 15:55:24 -0400 Subject: [PATCH 209/243] Serializer (brought from other branch) --- include/utils/serializer.h | 52 ++++++++ src/utils/serializer.cpp | 249 +++++++++++++++++++++++++++++++++++++ 2 files changed, 301 insertions(+) create mode 100644 include/utils/serializer.h create mode 100644 src/utils/serializer.cpp diff --git a/include/utils/serializer.h b/include/utils/serializer.h new file mode 100644 index 0000000..2a762d1 --- /dev/null +++ b/include/utils/serializer.h @@ -0,0 +1,52 @@ +#pragma once +#include +#include +#include +#include +#include + +const char serialization_separator = '$'; +const std::size_t MAX_FILE_SIZE = 2048; + +class Serializer +{ +private: + bool flush_always; + std::string filename; + std::map ints; + std::map bools; + std::map doubles; + std::map strings; + +public: + /// @brief create an empty Serializer + ~Serializer() + { + save_to_disk(); + printf("Saving %s\n", filename.c_str()); + fflush(stdout); + } + + /// @brief create a Serializer filled with values from file + explicit Serializer(const std::string &filename, bool flush_always = true) : flush_always(flush_always), filename(filename), ints({}), bools({}), doubles({}), strings({}) { read_from_disk(); } + + /// @brief saves current Serializer state to disk + void save_to_disk() const; + /// @brief loads Serializer state from disk + bool read_from_disk(); + + /// Setters - not saved until save_to_disk is called + + void set_int(const std::string &name, int i); + void set_bool(const std::string &name, bool b); + void set_double(const std::string &name, double d); + void set_string(const std::string &name, std::string str); + + /// Getters + /// Return value if it exists in the serializer + + int int_or(const std::string &name, int otherwise); + bool bool_or(const std::string &name, bool otherwise); + double double_or(const std::string &name, double otherwise); + std::string string_or(const std::string &name, std::string otherwise); +}; diff --git a/src/utils/serializer.cpp b/src/utils/serializer.cpp new file mode 100644 index 0000000..50b4161 --- /dev/null +++ b/src/utils/serializer.cpp @@ -0,0 +1,249 @@ +#include "../core/include/utils/serializer.h" +#include "stdlib.h" +#include "vex.h" + +// ===================== Helper Functions for converting to and from bytes ===================== +// Specialize these if you have non trivial types you need to save I suppose + +// Convert a type to bytes to serialize + +template +std::vector to_bytes(T value) +{ + // copy bytes of data into vector + std::vector value_bytes(sizeof(T)); + std::copy(static_cast(static_cast(&value)), + static_cast(static_cast(&value)) + sizeof(value), + value_bytes.begin()); + return value_bytes; +} + +template <> +std::vector to_bytes(std::string str) +{ + std::vector value_bytes(str.size() + 1); + std::copy(str.begin(), str.end(), value_bytes.begin()); + value_bytes[str.size()] = 0x0; + return value_bytes; +} + +// Convert bytes to a type + +template +T from_bytes(const std::vector &data, std::vector::const_iterator &position) +{ + T value; + std::copy(position, position + sizeof(T), static_cast(static_cast(&value))); + position = position + sizeof(T); + return value; +} + +template <> +std::string from_bytes(const std::vector &data, std::vector::const_iterator &position) +{ + auto pos = position; + while (*pos != 0x0) + { + ++pos; + } + std::string s(position, pos); + position = pos + 1; + return s; +} + +// Replaces funny characters in names so they don't mess with serialization specifiers + +std::string sanitize_name(std::string s) +{ + std::replace(s.begin(), s.end(), serialization_separator, '-'); + return s; +} + +// Protocol +/* + * Null terminated name immediatly followed by the bytes of the value + * +----Ints-----+ + * |name\0 bytes | + * | [sep] | + * +---Bools-----+ + * |name\0 byte | + * | [sep] | + * +---Doubles --+ + * |name\0 bytes | + * | [sep] | + * +---Strings --+ + * |name\0 str\0 | + * | [sep] | + * +-------------+ + */ + +// Adds data to a file (represented by array of bytes) as specified by the format above +template +static void add_data(std::vector &data, const std::map &map) +{ + for (const auto &pair : map) + { + const std::string &name = pair.first; + const value_type value = pair.second; + + data.insert(data.end(), name.cbegin(), name.cend()); + data.insert(data.end(), 0x0); + + auto bytes = to_bytes(value); + data.insert(data.end(), bytes.cbegin(), bytes.cend()); + } + data.push_back(serialization_separator); +} + +// reads data of a certain type from a file +template +static std::vector::const_iterator read_data(const std::vector &data, + std::vector::const_iterator begin, + std::map &map) +{ + std::vector::const_iterator pos = begin; + + while (*pos != serialization_separator) + { + auto name_start = pos; + // read name + std::string name = from_bytes(data, name_start); + pos += name.size() + 1; + // read value + value_type value = from_bytes(data, pos); + printf("Read Name: %s\n", name.c_str()); + map.insert({name, value}); + } + + return pos + 1; +} + +void Serializer::set_int(const std::string &name, int i) +{ + ints[sanitize_name(name)] = i; + if (flush_always) + { + save_to_disk(); + } +} +void Serializer::set_bool(const std::string &name, bool b) +{ + bools[sanitize_name(name)] = b; + if (flush_always) + { + save_to_disk(); + } +} +void Serializer::set_double(const std::string &name, double d) +{ + doubles[sanitize_name(name)] = d; + if (flush_always) + { + save_to_disk(); + } +} +void Serializer::set_string(const std::string &name, std::string str) +{ + strings[sanitize_name(name)] = str; + if (flush_always) + { + save_to_disk(); + } +} + +int Serializer::int_or(const std::string &name, int otherwise) +{ + if (ints.count(name)) + { + return ints.at(name); + } + return otherwise; +} +bool Serializer::bool_or(const std::string &name, bool otherwise) +{ + if (bools.count(name)) + { + return bools.at(name); + } + return otherwise; +} +double Serializer::double_or(const std::string &name, double otherwise) +{ + if (doubles.count(name)) + { + printf("Double Read"); + fflush(stdout); + return doubles.at(name); + } + set_double(name, otherwise); + return otherwise; +} +std::string Serializer::string_or(const std::string &name, std::string otherwise) +{ + if (strings.count(name)) + { + return strings.at(name); + } + return otherwise; +} + +// forms data bytes then saves to a filename +void Serializer::save_to_disk() const +{ + std::vector data = {}; + add_data(data, ints); + add_data(data, bools); + add_data(data, doubles); + add_data(data, strings); + + fflush(stdout); + + vex::brain::sdcard sd; + int32_t written = sd.savefile(filename.c_str(), (unsigned char *)&data[0], data.size()); + if (written != data.size()) + { + printf("!! Error writing to `%s`!!", filename.c_str()); + return; + } +} + +// reads types from file data +bool Serializer::read_from_disk() +{ + vex::brain::sdcard sd; + if (!sd.isInserted()) + { + printf("!! Trying to Serialize to No SD Card !!\n"); + return false; + } + int size = sd.size(filename.c_str()); + + if (filename == ""){ + printf("!! Can't write to empty filename!!\n"); + return false; + } + + if (!sd.exists(filename.c_str())) + { + printf("!!f Trying to Serialize to a file that doesnt exist: Creating %s !!\n", filename.c_str()); + save_to_disk(); + return false; + } + + std::vector data(size); + + int readsize = sd.loadfile(filename.c_str(), (unsigned char *)&data[0], size); + if (size != readsize) + { + printf("!! Error reading from file !!");; + return false; + } + + auto bool_start = read_data(data, data.cbegin(), ints); + auto doubles_start = read_data(data, bool_start, bools); + auto strings_start = read_data(data, doubles_start, doubles); + auto file_end = read_data(data, strings_start, strings); + + + return true; +} From 8396a1f3b6a2356bc55d5c96c1a4a89b99a86589 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 10 Sep 2023 16:10:56 -0400 Subject: [PATCH 210/243] bLOcK CoMmeNts MakE YoUR CoDe MoRE REadaBLE --- include/utils/serializer.h | 50 ++++++++++++++++++++++++++++++++++---- src/utils/serializer.cpp | 22 ++++++++++------- 2 files changed, 58 insertions(+), 14 deletions(-) diff --git a/include/utils/serializer.h b/include/utils/serializer.h index 2a762d1..bf29138 100644 --- a/include/utils/serializer.h +++ b/include/utils/serializer.h @@ -5,9 +5,12 @@ #include #include +/// @brief character that will be used to seperate values const char serialization_separator = '$'; -const std::size_t MAX_FILE_SIZE = 2048; +/// @brief max file size that the system can deal with +const std::size_t MAX_FILE_SIZE = 4096; +/// @brief Serializes Arbitrary data to a file on the SD Card class Serializer { private: @@ -18,8 +21,11 @@ class Serializer std::map doubles; std::map strings; + /// @brief loads Serializer state from disk + bool read_from_disk(); + public: - /// @brief create an empty Serializer + /// @brief Save and close upon destruction (bc of vex, this doesnt always get called when the program ends. To be sure, call save_to_disk) ~Serializer() { save_to_disk(); @@ -27,26 +33,60 @@ class Serializer fflush(stdout); } - /// @brief create a Serializer filled with values from file + /// @brief create a Serializer + /// @param filename the file to read from. If filename does not exist we will create that file + /// @param flush_always If true, after every write flush to a file. If false, you are responsible for calling save_to_disk explicit Serializer(const std::string &filename, bool flush_always = true) : flush_always(flush_always), filename(filename), ints({}), bools({}), doubles({}), strings({}) { read_from_disk(); } /// @brief saves current Serializer state to disk void save_to_disk() const; - /// @brief loads Serializer state from disk - bool read_from_disk(); /// Setters - not saved until save_to_disk is called + /// @brief sets an integer by the name of name to i. If flush_always == true, this will save to the sd card + /// @param name name of integer + /// @param i value of integer void set_int(const std::string &name, int i); + + /// @brief sets a bool by the name of name to b. If flush_always == true, this will save to the sd card + /// @param name name of bool + /// @param b value of bool void set_bool(const std::string &name, bool b); + + /// @brief sets a double by the name of name to d. If flush_always == true, this will save to the sd card + /// @param name name of double + /// @param d value of double void set_double(const std::string &name, double d); + + /// @brief sets a string by the name of name to s. If flush_always == true, this will save to the sd card + /// @param name name of string + /// @param i value of string void set_string(const std::string &name, std::string str); /// Getters /// Return value if it exists in the serializer + /// @brief gets a value stored in the serializer. If not found, sets the value to otherwise + /// @param name name of value + /// @param otherwise value if the name is not specified + /// @return the value if found or otherwise int int_or(const std::string &name, int otherwise); + + /// @brief gets a value stored in the serializer. If not, sets the value to otherwise + /// @param name name of value + /// @param otherwise value if the name is not specified + /// @return the value if found or otherwise bool bool_or(const std::string &name, bool otherwise); + + /// @brief gets a value stored in the serializer. If not, sets the value to otherwise + /// @param name name of value + /// @param otherwise value if the name is not specified + /// @return the value if found or otherwise double double_or(const std::string &name, double otherwise); + + /// @brief gets a value stored in the serializer. If not, sets the value to otherwise + /// @param name name of value + /// @param otherwise value if the name is not specified + /// @return the value if found or otherwise std::string string_or(const std::string &name, std::string otherwise); }; diff --git a/src/utils/serializer.cpp b/src/utils/serializer.cpp index 50b4161..c93d1ad 100644 --- a/src/utils/serializer.cpp +++ b/src/utils/serializer.cpp @@ -7,6 +7,8 @@ // Convert a type to bytes to serialize +/// @brief Convert type to bytes. Overload this for non integer types +/// @param value value to convert template std::vector to_bytes(T value) { @@ -27,8 +29,8 @@ std::vector to_bytes(std::string str) return value_bytes; } -// Convert bytes to a type - +/// @brief Convert bytes to a type +/// @param gets data from arbitrary bytes. Overload this for non integer types template T from_bytes(const std::vector &data, std::vector::const_iterator &position) { @@ -51,8 +53,7 @@ std::string from_bytes(const std::vector &data, std::vector::const_i return s; } -// Replaces funny characters in names so they don't mess with serialization specifiers - +/// @brief Replaces funny characters in names so they don't mess with serialization specifiers std::string sanitize_name(std::string s) { std::replace(s.begin(), s.end(), serialization_separator, '-'); @@ -77,7 +78,9 @@ std::string sanitize_name(std::string s) * +-------------+ */ -// Adds data to a file (represented by array of bytes) as specified by the format above +/// @brief Adds data to a file (represented by array of bytes) as specified by the format above +/// @param data the bytes to add to +/// @param map the values and names we are talking about template static void add_data(std::vector &data, const std::map &map) { @@ -157,6 +160,7 @@ int Serializer::int_or(const std::string &name, int otherwise) { return ints.at(name); } + set_int(name, otherwise); return otherwise; } bool Serializer::bool_or(const std::string &name, bool otherwise) @@ -165,14 +169,13 @@ bool Serializer::bool_or(const std::string &name, bool otherwise) { return bools.at(name); } + set_bool(name, otherwise); return otherwise; } double Serializer::double_or(const std::string &name, double otherwise) { if (doubles.count(name)) { - printf("Double Read"); - fflush(stdout); return doubles.at(name); } set_double(name, otherwise); @@ -184,10 +187,11 @@ std::string Serializer::string_or(const std::string &name, std::string otherwise { return strings.at(name); } + set_string(name, otherwise); return otherwise; } -// forms data bytes then saves to a filename +/// @brief forms data bytes then saves to filename this was openned with void Serializer::save_to_disk() const { std::vector data = {}; @@ -207,7 +211,7 @@ void Serializer::save_to_disk() const } } -// reads types from file data +/// @brief reads types from file data bool Serializer::read_from_disk() { vex::brain::sdcard sd; From b3b0916c9296689e5ef135a3115715ae928e2cab Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 10 Sep 2023 15:55:24 -0400 Subject: [PATCH 211/243] Serializer (brought from other branch) --- include/utils/serializer.h | 52 ++++++++ src/utils/serializer.cpp | 249 +++++++++++++++++++++++++++++++++++++ 2 files changed, 301 insertions(+) create mode 100644 include/utils/serializer.h create mode 100644 src/utils/serializer.cpp diff --git a/include/utils/serializer.h b/include/utils/serializer.h new file mode 100644 index 0000000..2a762d1 --- /dev/null +++ b/include/utils/serializer.h @@ -0,0 +1,52 @@ +#pragma once +#include +#include +#include +#include +#include + +const char serialization_separator = '$'; +const std::size_t MAX_FILE_SIZE = 2048; + +class Serializer +{ +private: + bool flush_always; + std::string filename; + std::map ints; + std::map bools; + std::map doubles; + std::map strings; + +public: + /// @brief create an empty Serializer + ~Serializer() + { + save_to_disk(); + printf("Saving %s\n", filename.c_str()); + fflush(stdout); + } + + /// @brief create a Serializer filled with values from file + explicit Serializer(const std::string &filename, bool flush_always = true) : flush_always(flush_always), filename(filename), ints({}), bools({}), doubles({}), strings({}) { read_from_disk(); } + + /// @brief saves current Serializer state to disk + void save_to_disk() const; + /// @brief loads Serializer state from disk + bool read_from_disk(); + + /// Setters - not saved until save_to_disk is called + + void set_int(const std::string &name, int i); + void set_bool(const std::string &name, bool b); + void set_double(const std::string &name, double d); + void set_string(const std::string &name, std::string str); + + /// Getters + /// Return value if it exists in the serializer + + int int_or(const std::string &name, int otherwise); + bool bool_or(const std::string &name, bool otherwise); + double double_or(const std::string &name, double otherwise); + std::string string_or(const std::string &name, std::string otherwise); +}; diff --git a/src/utils/serializer.cpp b/src/utils/serializer.cpp new file mode 100644 index 0000000..50b4161 --- /dev/null +++ b/src/utils/serializer.cpp @@ -0,0 +1,249 @@ +#include "../core/include/utils/serializer.h" +#include "stdlib.h" +#include "vex.h" + +// ===================== Helper Functions for converting to and from bytes ===================== +// Specialize these if you have non trivial types you need to save I suppose + +// Convert a type to bytes to serialize + +template +std::vector to_bytes(T value) +{ + // copy bytes of data into vector + std::vector value_bytes(sizeof(T)); + std::copy(static_cast(static_cast(&value)), + static_cast(static_cast(&value)) + sizeof(value), + value_bytes.begin()); + return value_bytes; +} + +template <> +std::vector to_bytes(std::string str) +{ + std::vector value_bytes(str.size() + 1); + std::copy(str.begin(), str.end(), value_bytes.begin()); + value_bytes[str.size()] = 0x0; + return value_bytes; +} + +// Convert bytes to a type + +template +T from_bytes(const std::vector &data, std::vector::const_iterator &position) +{ + T value; + std::copy(position, position + sizeof(T), static_cast(static_cast(&value))); + position = position + sizeof(T); + return value; +} + +template <> +std::string from_bytes(const std::vector &data, std::vector::const_iterator &position) +{ + auto pos = position; + while (*pos != 0x0) + { + ++pos; + } + std::string s(position, pos); + position = pos + 1; + return s; +} + +// Replaces funny characters in names so they don't mess with serialization specifiers + +std::string sanitize_name(std::string s) +{ + std::replace(s.begin(), s.end(), serialization_separator, '-'); + return s; +} + +// Protocol +/* + * Null terminated name immediatly followed by the bytes of the value + * +----Ints-----+ + * |name\0 bytes | + * | [sep] | + * +---Bools-----+ + * |name\0 byte | + * | [sep] | + * +---Doubles --+ + * |name\0 bytes | + * | [sep] | + * +---Strings --+ + * |name\0 str\0 | + * | [sep] | + * +-------------+ + */ + +// Adds data to a file (represented by array of bytes) as specified by the format above +template +static void add_data(std::vector &data, const std::map &map) +{ + for (const auto &pair : map) + { + const std::string &name = pair.first; + const value_type value = pair.second; + + data.insert(data.end(), name.cbegin(), name.cend()); + data.insert(data.end(), 0x0); + + auto bytes = to_bytes(value); + data.insert(data.end(), bytes.cbegin(), bytes.cend()); + } + data.push_back(serialization_separator); +} + +// reads data of a certain type from a file +template +static std::vector::const_iterator read_data(const std::vector &data, + std::vector::const_iterator begin, + std::map &map) +{ + std::vector::const_iterator pos = begin; + + while (*pos != serialization_separator) + { + auto name_start = pos; + // read name + std::string name = from_bytes(data, name_start); + pos += name.size() + 1; + // read value + value_type value = from_bytes(data, pos); + printf("Read Name: %s\n", name.c_str()); + map.insert({name, value}); + } + + return pos + 1; +} + +void Serializer::set_int(const std::string &name, int i) +{ + ints[sanitize_name(name)] = i; + if (flush_always) + { + save_to_disk(); + } +} +void Serializer::set_bool(const std::string &name, bool b) +{ + bools[sanitize_name(name)] = b; + if (flush_always) + { + save_to_disk(); + } +} +void Serializer::set_double(const std::string &name, double d) +{ + doubles[sanitize_name(name)] = d; + if (flush_always) + { + save_to_disk(); + } +} +void Serializer::set_string(const std::string &name, std::string str) +{ + strings[sanitize_name(name)] = str; + if (flush_always) + { + save_to_disk(); + } +} + +int Serializer::int_or(const std::string &name, int otherwise) +{ + if (ints.count(name)) + { + return ints.at(name); + } + return otherwise; +} +bool Serializer::bool_or(const std::string &name, bool otherwise) +{ + if (bools.count(name)) + { + return bools.at(name); + } + return otherwise; +} +double Serializer::double_or(const std::string &name, double otherwise) +{ + if (doubles.count(name)) + { + printf("Double Read"); + fflush(stdout); + return doubles.at(name); + } + set_double(name, otherwise); + return otherwise; +} +std::string Serializer::string_or(const std::string &name, std::string otherwise) +{ + if (strings.count(name)) + { + return strings.at(name); + } + return otherwise; +} + +// forms data bytes then saves to a filename +void Serializer::save_to_disk() const +{ + std::vector data = {}; + add_data(data, ints); + add_data(data, bools); + add_data(data, doubles); + add_data(data, strings); + + fflush(stdout); + + vex::brain::sdcard sd; + int32_t written = sd.savefile(filename.c_str(), (unsigned char *)&data[0], data.size()); + if (written != data.size()) + { + printf("!! Error writing to `%s`!!", filename.c_str()); + return; + } +} + +// reads types from file data +bool Serializer::read_from_disk() +{ + vex::brain::sdcard sd; + if (!sd.isInserted()) + { + printf("!! Trying to Serialize to No SD Card !!\n"); + return false; + } + int size = sd.size(filename.c_str()); + + if (filename == ""){ + printf("!! Can't write to empty filename!!\n"); + return false; + } + + if (!sd.exists(filename.c_str())) + { + printf("!!f Trying to Serialize to a file that doesnt exist: Creating %s !!\n", filename.c_str()); + save_to_disk(); + return false; + } + + std::vector data(size); + + int readsize = sd.loadfile(filename.c_str(), (unsigned char *)&data[0], size); + if (size != readsize) + { + printf("!! Error reading from file !!");; + return false; + } + + auto bool_start = read_data(data, data.cbegin(), ints); + auto doubles_start = read_data(data, bool_start, bools); + auto strings_start = read_data(data, doubles_start, doubles); + auto file_end = read_data(data, strings_start, strings); + + + return true; +} From b20a35d8ca30ba4bb0d950b255666f97b16c163e Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 10 Sep 2023 16:10:56 -0400 Subject: [PATCH 212/243] bLOcK CoMmeNts MakE YoUR CoDe MoRE REadaBLE --- include/utils/serializer.h | 50 ++++++++++++++++++++++++++++++++++---- src/utils/serializer.cpp | 22 ++++++++++------- 2 files changed, 58 insertions(+), 14 deletions(-) diff --git a/include/utils/serializer.h b/include/utils/serializer.h index 2a762d1..bf29138 100644 --- a/include/utils/serializer.h +++ b/include/utils/serializer.h @@ -5,9 +5,12 @@ #include #include +/// @brief character that will be used to seperate values const char serialization_separator = '$'; -const std::size_t MAX_FILE_SIZE = 2048; +/// @brief max file size that the system can deal with +const std::size_t MAX_FILE_SIZE = 4096; +/// @brief Serializes Arbitrary data to a file on the SD Card class Serializer { private: @@ -18,8 +21,11 @@ class Serializer std::map doubles; std::map strings; + /// @brief loads Serializer state from disk + bool read_from_disk(); + public: - /// @brief create an empty Serializer + /// @brief Save and close upon destruction (bc of vex, this doesnt always get called when the program ends. To be sure, call save_to_disk) ~Serializer() { save_to_disk(); @@ -27,26 +33,60 @@ class Serializer fflush(stdout); } - /// @brief create a Serializer filled with values from file + /// @brief create a Serializer + /// @param filename the file to read from. If filename does not exist we will create that file + /// @param flush_always If true, after every write flush to a file. If false, you are responsible for calling save_to_disk explicit Serializer(const std::string &filename, bool flush_always = true) : flush_always(flush_always), filename(filename), ints({}), bools({}), doubles({}), strings({}) { read_from_disk(); } /// @brief saves current Serializer state to disk void save_to_disk() const; - /// @brief loads Serializer state from disk - bool read_from_disk(); /// Setters - not saved until save_to_disk is called + /// @brief sets an integer by the name of name to i. If flush_always == true, this will save to the sd card + /// @param name name of integer + /// @param i value of integer void set_int(const std::string &name, int i); + + /// @brief sets a bool by the name of name to b. If flush_always == true, this will save to the sd card + /// @param name name of bool + /// @param b value of bool void set_bool(const std::string &name, bool b); + + /// @brief sets a double by the name of name to d. If flush_always == true, this will save to the sd card + /// @param name name of double + /// @param d value of double void set_double(const std::string &name, double d); + + /// @brief sets a string by the name of name to s. If flush_always == true, this will save to the sd card + /// @param name name of string + /// @param i value of string void set_string(const std::string &name, std::string str); /// Getters /// Return value if it exists in the serializer + /// @brief gets a value stored in the serializer. If not found, sets the value to otherwise + /// @param name name of value + /// @param otherwise value if the name is not specified + /// @return the value if found or otherwise int int_or(const std::string &name, int otherwise); + + /// @brief gets a value stored in the serializer. If not, sets the value to otherwise + /// @param name name of value + /// @param otherwise value if the name is not specified + /// @return the value if found or otherwise bool bool_or(const std::string &name, bool otherwise); + + /// @brief gets a value stored in the serializer. If not, sets the value to otherwise + /// @param name name of value + /// @param otherwise value if the name is not specified + /// @return the value if found or otherwise double double_or(const std::string &name, double otherwise); + + /// @brief gets a value stored in the serializer. If not, sets the value to otherwise + /// @param name name of value + /// @param otherwise value if the name is not specified + /// @return the value if found or otherwise std::string string_or(const std::string &name, std::string otherwise); }; diff --git a/src/utils/serializer.cpp b/src/utils/serializer.cpp index 50b4161..c93d1ad 100644 --- a/src/utils/serializer.cpp +++ b/src/utils/serializer.cpp @@ -7,6 +7,8 @@ // Convert a type to bytes to serialize +/// @brief Convert type to bytes. Overload this for non integer types +/// @param value value to convert template std::vector to_bytes(T value) { @@ -27,8 +29,8 @@ std::vector to_bytes(std::string str) return value_bytes; } -// Convert bytes to a type - +/// @brief Convert bytes to a type +/// @param gets data from arbitrary bytes. Overload this for non integer types template T from_bytes(const std::vector &data, std::vector::const_iterator &position) { @@ -51,8 +53,7 @@ std::string from_bytes(const std::vector &data, std::vector::const_i return s; } -// Replaces funny characters in names so they don't mess with serialization specifiers - +/// @brief Replaces funny characters in names so they don't mess with serialization specifiers std::string sanitize_name(std::string s) { std::replace(s.begin(), s.end(), serialization_separator, '-'); @@ -77,7 +78,9 @@ std::string sanitize_name(std::string s) * +-------------+ */ -// Adds data to a file (represented by array of bytes) as specified by the format above +/// @brief Adds data to a file (represented by array of bytes) as specified by the format above +/// @param data the bytes to add to +/// @param map the values and names we are talking about template static void add_data(std::vector &data, const std::map &map) { @@ -157,6 +160,7 @@ int Serializer::int_or(const std::string &name, int otherwise) { return ints.at(name); } + set_int(name, otherwise); return otherwise; } bool Serializer::bool_or(const std::string &name, bool otherwise) @@ -165,14 +169,13 @@ bool Serializer::bool_or(const std::string &name, bool otherwise) { return bools.at(name); } + set_bool(name, otherwise); return otherwise; } double Serializer::double_or(const std::string &name, double otherwise) { if (doubles.count(name)) { - printf("Double Read"); - fflush(stdout); return doubles.at(name); } set_double(name, otherwise); @@ -184,10 +187,11 @@ std::string Serializer::string_or(const std::string &name, std::string otherwise { return strings.at(name); } + set_string(name, otherwise); return otherwise; } -// forms data bytes then saves to a filename +/// @brief forms data bytes then saves to filename this was openned with void Serializer::save_to_disk() const { std::vector data = {}; @@ -207,7 +211,7 @@ void Serializer::save_to_disk() const } } -// reads types from file data +/// @brief reads types from file data bool Serializer::read_from_disk() { vex::brain::sdcard sd; From d7ac2c1391aba2059e7acc91b2c5769a8b650437 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 10 Sep 2023 16:53:20 -0400 Subject: [PATCH 213/243] Logging From other branch --- include/utils/logger.h | 68 ++++++++++++++++++++++++++++++++++ src/utils/logger.cpp | 84 ++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 152 insertions(+) create mode 100644 include/utils/logger.h create mode 100644 src/utils/logger.cpp diff --git a/include/utils/logger.h b/include/utils/logger.h new file mode 100644 index 0000000..3194841 --- /dev/null +++ b/include/utils/logger.h @@ -0,0 +1,68 @@ +#pragma once + +#include +#include +#include +#include "vex.h" + +/// @brief possible values for log filtering +enum LogLevel +{ + DEBUG, + NOTICE, + WARNING, + ERROR, + CRITICAL, + TIME +}; + +/// @brief Class to simplify writing to files +class Logger +{ +private: + const std::string filename; + vex::brain::sdcard sd; + void write_level(LogLevel l); + +public: + /// @brief maximum size for a string to be before it's written + const int MAX_FORMAT_LEN = 512; + /// @brief Create a logger that will save to a file + /// @param filename the file to save to + explicit Logger(const std::string &filename); + + /// @brief copying not allowed + Logger(const Logger &l) = delete; + /// @brief copying not allowed + Logger &operator=(const Logger &l) = delete; + + + /// @brief Write a string to the log + /// @param s the string to write + void Log(const std::string &s); + + /// @brief Write a string to the log with a loglevel + /// @param level the level to write. DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME + /// @param s the string to write + void Log(LogLevel level, const std::string &s); + + /// @brief Write a string and newline to the log + /// @param s the string to write + void Logln(const std::string &s); + + /// @brief Write a string and a newline to the log with a loglevel + /// @param level the level to write. DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME + /// @param s the string to write + void Logln(LogLevel level, const std::string &s); + + /// @brief Write a formatted string to the log + /// @param fmt the format string (like printf) + /// @param ... the args + void Logf(const char *fmt, ...); + + /// @brief Write a formatted string to the log with a loglevel + /// @param level the level to write. DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME + /// @param fmt the format string (like printf) + /// @param ... the args + void Logf(LogLevel level, const char *fmt, ...); +}; diff --git a/src/utils/logger.cpp b/src/utils/logger.cpp new file mode 100644 index 0000000..65ff58d --- /dev/null +++ b/src/utils/logger.cpp @@ -0,0 +1,84 @@ +#include "../core/include/utils/logger.h" +#include + +void Logger::write_level(LogLevel l) +{ + unsigned char *debug = (unsigned char *)"DEBUG: "; + unsigned char *notice = (unsigned char *)"NOTICE: "; + unsigned char *warning = (unsigned char *)"WARNING: "; + unsigned char *error = (unsigned char *)"ERROR: "; + unsigned char *critical = (unsigned char *)"CRITICAL: "; + switch (l) + { + case DEBUG: + sd.appendfile(filename.c_str(), debug, 7); + break; + case NOTICE: + sd.appendfile(filename.c_str(), notice, 8); + break; + case WARNING: + sd.appendfile(filename.c_str(), warning, 9); + break; + case ERROR: + sd.appendfile(filename.c_str(), error, 7); + break; + case CRITICAL: + sd.appendfile(filename.c_str(), critical, 10); + break; + case TIME: + int32_t msec = vexSystemTimeGet(); + Logf("%d: ", msec); + break; + }; +} + +Logger::Logger(const std::string &filename) : filename(filename) { + sd.savefile(filename.c_str(), NULL, 0); +} + +void Logger::Log(const std::string &s) +{ + sd.appendfile(filename.c_str(), (unsigned char *)s.c_str(), s.size()); +} +void Logger::Log(LogLevel level, const std::string &s) +{ + write_level(level); + sd.appendfile(filename.c_str(), (unsigned char *)s.c_str(), s.size()); +} + +void Logger::Logln(const std::string &s) +{ + sd.appendfile(filename.c_str(), (unsigned char *)s.c_str(), s.size()); + unsigned char newline = '\n'; + sd.appendfile(filename.c_str(), &newline, 1); +} +void Logger::Logln(LogLevel level, const std::string &s) +{ + write_level(level); + Logln(s); +} + +void Logger::Logf(const char *fmt, ...) +{ + char buf[MAX_FORMAT_LEN]; + va_list args; + va_start(args, fmt); + + int32_t written = vex_vsnprintf(buf, MAX_FORMAT_LEN, fmt, args); + + va_end(args); + sd.appendfile(filename.c_str(), (unsigned char *)buf, written); + +} +void Logger::Logf(LogLevel level, const char *fmt, ...) +{ + char buf[MAX_FORMAT_LEN]; + + write_level(level); + va_list args; + va_start(args, fmt); + int32_t written = vex_vsnprintf(buf, MAX_FORMAT_LEN, fmt, args); + va_end(args); + + sd.appendfile(filename.c_str(), (unsigned char *)buf, written); +} From f6e30a2ba3bf619dfe07697fa7ad6c0d80f76124 Mon Sep 17 00:00:00 2001 From: Richie Sommers <44383226+cowsed@users.noreply.github.com> Date: Sun, 17 Sep 2023 13:41:52 -0400 Subject: [PATCH 214/243] Updated action to make pdf --- .github/workflows/main.yml | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index c033af1..5f89bed 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -29,6 +29,26 @@ jobs: doxyfile-path: "./Doxyfile" # default is ./Doxyfile # Working directory working-directory: "." # default is . + + - name: Install pdflatex dependencies + run: sudo apt-get install -y texlive-latex-base texlive-fonts-extra texlive-latex-extra texlive-font-utils + + - run: sudo make --directory=documentation/latex + + + - name: Copy file + uses: canastro/copy-action@0.0.2 + with: + source: "documentation/latex/refman.pdf" + target: "documentation/html/refman.pdf" + + - name: Copy log + uses: canastro/copy-action@0.0.2 + with: + source: "documentation/latex/refman.log" + target: "documentation/html/refman.log" + + - name: Deploy uses: peaceiris/actions-gh-pages@v3 From 4d2eadcc6e7f7b78acaa4bb608711944707109ad Mon Sep 17 00:00:00 2001 From: Richie Sommers <44383226+cowsed@users.noreply.github.com> Date: Sun, 17 Sep 2023 13:46:51 -0400 Subject: [PATCH 215/243] Update README.md --- README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/README.md b/README.md index c44aaaf..6e1e6b0 100644 --- a/README.md +++ b/README.md @@ -2,6 +2,8 @@ This is the host repository for the custom VEX libraries used by the RIT VEXU team Automatically updated documentation is available at [here](https://rit-vex-u.github.io/Core/). +There is also a downloadable [reference manual](https://rit-vex-u.github.io/Core/refman.pdf). + ## Getting Started In order to simply use this repo, you can either clone it into your VEXcode project folder, or download the .zip and place it into a core/ subfolder. Then follow the instructions for setting up compilation at [Wiki/BuildSystem](https://github.com/RIT-VEX-U/Core/wiki/1-%7C-Project-Setup#build-system) From 52888361b7fb77b8860a598ccba1ec292970cd96 Mon Sep 17 00:00:00 2001 From: Richie Sommers <44383226+cowsed@users.noreply.github.com> Date: Sun, 17 Sep 2023 14:50:50 -0400 Subject: [PATCH 216/243] Generate Notebook --- .github/workflows/main.yml | 29 ++++++++++++++++++++++++++--- 1 file changed, 26 insertions(+), 3 deletions(-) diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index 5f89bed..40da577 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -21,6 +21,15 @@ jobs: steps: # Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it - uses: actions/checkout@v2 + + + - name: Install Dependencies + uses: awalsh128/cache-apt-pkgs-action@latest + with: + packages: doxygen-latex poppler-utils + version: 1.1 + + - name: Doxygen Action uses: mattnotmitt/doxygen-action@v1.1.0 @@ -30,10 +39,9 @@ jobs: # Working directory working-directory: "." # default is . - - name: Install pdflatex dependencies - run: sudo apt-get install -y texlive-latex-base texlive-fonts-extra texlive-latex-extra texlive-font-utils - - run: sudo make --directory=documentation/latex + - name: Generate Reference Manual + run: sudo make --directory=documentation/latex - name: Copy file @@ -49,6 +57,21 @@ jobs: target: "documentation/html/refman.log" + - name: Get Notebook Link + shell: bash + run: | + echo "NOTEBOOK_URL=$(curl -s https://docs.google.com/document/d/1Qi4-ZraS1KN8aG-58iJjD0aQQz0nNSEPkc6Hfz7vbTE/export\?format\=pdf |grep HREF |sed -E "s|.*HREF=\"([^\"]*).*|\1|g")" >> "$GITHUB_ENV" + + - name: Download Notebook + uses: wei/curl@master + with: + args: ${{ env.NOTEBOOK_URL }} --output documentation/html/notebook_top.pdf + + + + - name: Concatenate Manual and Notebook + run: sudo pdfunite documentation/html/notebook_top.pdf documentation/html/refman.pdf documentation/html/notebook.pdf + - name: Deploy uses: peaceiris/actions-gh-pages@v3 From 65f1f26b07f8cfa5c7517a8de3cf5223c451c899 Mon Sep 17 00:00:00 2001 From: Richie Sommers <44383226+cowsed@users.noreply.github.com> Date: Sun, 17 Sep 2023 14:59:14 -0400 Subject: [PATCH 217/243] Updated to new notebook link --- .github/workflows/main.yml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index 40da577..e7cb32f 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -60,7 +60,8 @@ jobs: - name: Get Notebook Link shell: bash run: | - echo "NOTEBOOK_URL=$(curl -s https://docs.google.com/document/d/1Qi4-ZraS1KN8aG-58iJjD0aQQz0nNSEPkc6Hfz7vbTE/export\?format\=pdf |grep HREF |sed -E "s|.*HREF=\"([^\"]*).*|\1|g")" >> "$GITHUB_ENV" + echo "NOTEBOOK_URL=$(curl -s https://docs.google.com/document/d/1MXCeYx3YnUjLv4AaNY4qdkM84N3KkZn0HwgL6a-Di8U/export\?format\=pdf |grep HREF |sed -E "s|.*HREF=\"([^\"]*).*|\1|g")" >> "$GITHUB_ENV" + - name: Download Notebook uses: wei/curl@master From 7bca3d54eb97db1eaddefae907c79246280a198e Mon Sep 17 00:00:00 2001 From: Richie Sommers <44383226+cowsed@users.noreply.github.com> Date: Sun, 17 Sep 2023 15:00:44 -0400 Subject: [PATCH 218/243] fixed dependencies --- .github/workflows/main.yml | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index e7cb32f..e93b7f8 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -24,10 +24,7 @@ jobs: - name: Install Dependencies - uses: awalsh128/cache-apt-pkgs-action@latest - with: - packages: doxygen-latex poppler-utils - version: 1.1 + run: sudo apt-get install -y doxygen-latex poppler-utils From 4d8fd9175fbbc7b61feac12d2b7a5f61ba58debb Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 10 Sep 2023 13:48:16 -0400 Subject: [PATCH 219/243] fixed initial warnings --- src/utils/pidff.cpp | 2 +- src/utils/pure_pursuit.cpp | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/utils/pidff.cpp b/src/utils/pidff.cpp index 01286de..7d1df2a 100644 --- a/src/utils/pidff.cpp +++ b/src/utils/pidff.cpp @@ -1,7 +1,7 @@ #include "../core/include/utils/pidff.h" #include "../core/include/utils/math_util.h" -PIDFF::PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg): ff_cfg(ff_cfg), pid(pid_cfg), ff(ff_cfg) +PIDFF::PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg): pid(pid_cfg), ff_cfg(ff_cfg),ff(ff_cfg) { out = 0; lower_lim = 0; diff --git a/src/utils/pure_pursuit.cpp b/src/utils/pure_pursuit.cpp index 6c70ad1..78e1740 100644 --- a/src/utils/pure_pursuit.cpp +++ b/src/utils/pure_pursuit.cpp @@ -52,7 +52,7 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub /** * Selects a look ahead from all the intersections in the path. */ -point_t PurePursuit::get_lookahead(std::vector path, point_t robot_loc, double radius) +[[maybe_unused]] point_t PurePursuit::get_lookahead(std::vector path, point_t robot_loc, double radius) { //Default: the end of the path point_t target = path.back(); @@ -85,7 +85,7 @@ point_t PurePursuit::get_lookahead(std::vector path, point_t robot_loc, /** Injects points in a path without changing the curvature with a certain spacing. */ -std::vector PurePursuit::inject_path(std::vector path, double spacing) +[[maybe_unused]] std::vector PurePursuit::inject_path(std::vector path, double spacing) { std::vector new_path; @@ -125,7 +125,7 @@ std::vector PurePursuit::inject_path(std::vector path, double * Honestly have no idea if/how this works. * https://medium.com/@jaems33/understanding-robot-motion-path-smoothing-5970c8363bc4 */ -std::vector PurePursuit::smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance) +[[maybe_unused]] std::vector PurePursuit::smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance) { std::vector new_path = path; double change = tolerance; @@ -159,7 +159,7 @@ std::vector PurePursuit::smooth_path(std::vector path, double * @param steps The number of points interpolated between points. * @return The smoothed path. */ -std::vector PurePursuit::smooth_path_hermite(std::vector path, double steps) { +[[maybe_unused]] std::vector PurePursuit::smooth_path_hermite(std::vector path, double steps) { std::vector new_path; for(int i = 0; i < path.size() - 1; i++) { for(int t = 0; t < steps; t++) { @@ -191,7 +191,7 @@ std::vector PurePursuit::smooth_path_hermite(std::vector return new_path; } -std::vector PurePursuit::smooth_path_cubic(std::vector path, double res) { +[[maybe_unused]] std::vector PurePursuit::smooth_path_cubic(std::vector path, double res) { std::vector new_path; std::vector splines; From 888585ea874b3bd48881a53373de20169e078558 Mon Sep 17 00:00:00 2001 From: max-49 Date: Tue, 12 Sep 2023 20:01:35 -0400 Subject: [PATCH 220/243] Odometry now can use VEX encoders --- include/subsystems/odometry/odometry_tank.h | 20 ++++++++++--- src/subsystems/odometry/odometry_tank.cpp | 33 ++++++++++++++++----- 2 files changed, 41 insertions(+), 12 deletions(-) diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index 6c35e10..c2e4e1c 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -30,14 +30,25 @@ class OdometryTank : public OdometryBase /** * Initialize the Odometry module, calculating position from the drive motors. - * @param left_enc The left motors - * @param right_enc The right motors + * @param left_custom_enc The left custom encoder + * @param right_custom_enc The right custom encoder * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). */ - OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true); + OdometryTank(CustomEncoder &left_custom_enc, CustomEncoder &right_custom_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true); + + /** + * Initialize the Odometry module, calculating position from the drive motors. + * @param left_vex_enc The left vex encoder + * @param right_vex_enc The right vex encoder + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained + * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). + */ + + OdometryTank(vex::encoder &left_vex_enc, vex::encoder &right_vex_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true); /** * Update the current position on the field based on the sensors @@ -60,7 +71,8 @@ class OdometryTank : public OdometryBase static pose_t calculate_new_pos(robot_specs_t &config, pose_t &stored_info, double lside_diff, double rside_diff, double angle_deg); vex::motor_group *left_side, *right_side; - CustomEncoder *left_enc, *right_enc; + CustomEncoder *left_custom_enc, *right_custom_enc; + vex::encoder *left_vex_enc, *right_vex_enc; vex::inertial *imu; robot_specs_t &config; diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index e594ef4..171c880 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -9,20 +9,33 @@ * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). */ OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu, bool is_async) -: OdometryBase(is_async), left_side(&left_side), right_side(&right_side), left_enc(NULL), right_enc(NULL), imu(imu), config(config) +: OdometryBase(is_async), left_side(&left_side), right_side(&right_side), left_custom_enc(NULL), right_custom_enc(NULL), left_vex_enc(NULL), right_vex_enc(NULL), imu(imu), config(config) { } /** * Initialize the Odometry module, calculating position from the drive motors. -* @param left_enc The left motors -* @param right_enc The right motors +* @param left_custom_enc The left custom encoder +* @param right_custom_enc The right custom encoder * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). */ -OdometryTank::OdometryTank(CustomEncoder &left_enc, CustomEncoder &right_enc, robot_specs_t &config, vex::inertial *imu, bool is_async) -: OdometryBase(is_async), left_side(NULL), right_side(NULL), left_enc(&left_enc), right_enc(&right_enc), imu(imu), config(config) +OdometryTank::OdometryTank(CustomEncoder &left_custom_enc, CustomEncoder &right_custom_enc, robot_specs_t &config, vex::inertial *imu, bool is_async) +: OdometryBase(is_async), left_side(NULL), right_side(NULL), left_custom_enc(&left_custom_enc), right_custom_enc(&right_custom_enc), left_vex_enc(NULL), right_vex_enc(NULL), imu(imu), config(config) +{ +} + +/** +* Initialize the Odometry module, calculating position from the drive motors. +* @param left_vex_enc The left vex encoder +* @param right_vex_enc The right vex encoder +* @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained +* @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. +* @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). +*/ +OdometryTank::OdometryTank(vex::encoder &left_vex_enc, vex::encoder &right_vex_enc, robot_specs_t &config, vex::inertial *imu, bool is_async) +: OdometryBase(is_async), left_side(NULL), right_side(NULL), left_custom_enc(NULL), right_custom_enc(NULL), left_vex_enc(&left_vex_enc), right_vex_enc(&right_vex_enc), imu(imu), config(config) { } @@ -51,10 +64,14 @@ pose_t OdometryTank::update() { lside_revs = left_side->position(vex::rotationUnits::rev) / config.odom_gear_ratio; rside_revs = right_side->position(vex::rotationUnits::rev) / config.odom_gear_ratio; - }else if(left_enc != NULL && right_enc != NULL) + }else if(left_custom_enc != NULL && right_custom_enc != NULL) + { + lside_revs = left_custom_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; + rside_revs = right_custom_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; + }else if(left_vex_enc != NULL && right_vex_enc != NULL) { - lside_revs = left_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; - rside_revs = right_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; + lside_revs = left_vex_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; + rside_revs = right_vex_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; } double angle = 0; From 4da2becb438ae6f283b13ac846dc785416d2c0b8 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 24 Sep 2023 15:20:58 -0400 Subject: [PATCH 221/243] First working version of pure pursuit; no reverse drive --- include/splash.h | 6 -- include/subsystems/tank_drive.h | 18 ++--- include/utils/geometry.h | 10 +++ include/utils/math_util.h | 5 +- include/utils/moving_average.h | 1 + include/utils/pure_pursuit.h | 25 +++++-- src/subsystems/odometry/odometry_base.cpp | 1 + src/subsystems/tank_drive.cpp | 84 +++++++++++++++++------ src/utils/math_util.cpp | 20 ++++++ src/utils/pidff.cpp | 8 ++- src/utils/pure_pursuit.cpp | 50 ++++++++++++-- 11 files changed, 173 insertions(+), 55 deletions(-) delete mode 100644 include/splash.h diff --git a/include/splash.h b/include/splash.h deleted file mode 100644 index d45932d..0000000 --- a/include/splash.h +++ /dev/null @@ -1,6 +0,0 @@ -#include -// file: clu.png -int intense_milk_width = 420; -int intense_milk_height = 246; -uint32_t intense_milk[103320]; -// = {0x00152021, 0x00141f21, 0x00141d20, 0x00131d1f, 0x00131e1e, 0x00131e1e, 0x00141f1f, 0x00141f1f, 0x00141e20, 0x00131d1f, 0x00131d1f, 0x00131d1e, 0x00121c1c, 0x00111c1c, 0x00111c1a, 0x00111c1a, 0x00111c1a, 0x00111b19, 0x00111b19, 0x00111b19, 0x00111b19, 0x00101918, 0x00101918, 0x00101918, 0x00101918, 0x00101916, 0x00101916, 0x00101818, 0x00101817, 0x00101817, 0x00101817, 0x00101817, 0x00101817, 0x000f1817, 0x000f1816, 0x000e1816, 0x000d1714, 0x000d1714, 0x000d1714, 0x000c1613, 0x000c1512, 0x000c1512, 0x000e1611, 0x000e1611, 0x000e1611, 0x000e1511, 0x000d1410, 0x000c1410, 0x000c1410, 0x000c1410, 0x000c1410, 0x000c1410, 0x000c1410, 0x000c140f, 0x000c140e, 0x000c140d, 0x000c140d, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000f1310, 0x000d140e, 0x000d140e, 0x000c140c, 0x000c140c, 0x000c140c, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140f, 0x000b1410, 0x000b1510, 0x000c1510, 0x000c1511, 0x000c1512, 0x000c1610, 0x000c1611, 0x000c1710, 0x000f1610, 0x00101811, 0x000f1814, 0x00101914, 0x00101a17, 0x00101a17, 0x00101916, 0x00101915, 0x00101918, 0x00101918, 0x00101918, 0x000f1a18, 0x000f1b18, 0x000e1c19, 0x000c1d19, 0x000c1c19, 0x000d1c19, 0x000d1c19, 0x000d1c19, 0x000f1c19, 0x000e1b18, 0x000e1918, 0x000f1a18, 0x000f1a18, 0x00111c1a, 0x00121b18, 0x00111c18, 0x00101b17, 0x00141c19, 0x002d3030, 0x00454545, 0x00403e3e, 0x00444040, 0x00484446, 0x004a4649, 0x004a484b, 0x00494448, 0x004a4244, 0x004b4040, 0x004a3d3b, 0x004c3e3a, 0x0050403c, 0x004c3b35, 0x00493833, 0x00473530, 0x00473630, 0x0045322e, 0x00473430, 0x00413831, 0x0039322c, 0x00342c26, 0x00322b25, 0x0038332c, 0x00372e26, 0x003a2a22, 0x00412c23, 0x003e1e15, 0x00401b10, 0x003d1c0d, 0x003a1e09, 0x00462812, 0x0050301a, 0x004c2c16, 0x004e2c1a, 0x004f2c1c, 0x00492515, 0x00442210, 0x004c2e18, 0x00573a1f, 0x005e3419, 0x0064391c, 0x00673b1a, 0x00633914, 0x00643a18, 0x00532b0a, 0x004e2508, 0x00532a10, 0x005c3418, 0x005e3818, 0x00603a1a, 0x005c3515, 0x00573113, 0x00593417, 0x00583416, 0x005a3414, 0x005d3716, 0x00613819, 0x00643c1c, 0x006c4220, 0x00673d18, 0x00653c16, 0x00633a16, 0x00603414, 0x00633815, 0x00683c18, 0x006e441c, 0x006e421b, 0x00643910, 0x006a3f18, 0x005b320b, 0x00643c15, 0x00633b16, 0x00613b16, 0x00603a16, 0x005d3818, 0x00583414, 0x005b3518, 0x004c280b, 0x004a2508, 0x00502b0c, 0x005c3416, 0x00613719, 0x0061371a, 0x005e3716, 0x00502c0b, 0x003c220c, 0x00311c0c, 0x00261810, 0x00201414, 0x0017140d, 0x00141509, 0x0015160c, 0x001a1a10, 0x0018170f, 0x00191910, 0x0018180f, 0x0016160d, 0x0016160d, 0x0016160d, 0x0016160d, 0x0015170c, 0x0018160c, 0x001a160c, 0x00201810, 0x00281d16, 0x00342720, 0x00302a24, 0x00312924, 0x00302b24, 0x00282a20, 0x001b2420, 0x00182623, 0x00182824, 0x00152824, 0x00152824, 0x00152724, 0x00172625, 0x00182627, 0x00182627, 0x00182627, 0x00172526, 0x00162424, 0x00162425, 0x00172526, 0x00182526, 0x00172524, 0x00162423, 0x00152420, 0x00142320, 0x00152220, 0x0013201d, 0x00131f1e, 0x0013201f, 0x00121f1e, 0x00101d1d, 0x00101c1c, 0x000f1c1b, 0x00101b1b, 0x00101a1a, 0x000f1819, 0x000f1818, 0x000e1814, 0x000e1611, 0x000e170f, 0x000e170e, 0x000e1610, 0x00101610, 0x00101610, 0x00101610, 0x00101510, 0x0010140f, 0x000e140e, 0x000d140e, 0x000c140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000e140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1417, 0x000b1517, 0x00091416, 0x000a1417, 0x000b1616, 0x000c1716, 0x000c1716, 0x000c1717, 0x000c1718, 0x000c1819, 0x000d1819, 0x000d1818, 0x000c1818, 0x000c1716, 0x000c1715, 0x000c1715, 0x000c1715, 0x000c1514, 0x000c1514, 0x000c1514, 0x000c1514, 0x000b1413, 0x000b1413, 0x000b1413, 0x000b1413, 0x000a1410, 0x000a1410, 0x00091211, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081010, 0x0008100f, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00040e0b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d07, 0x00050d07, 0x00050d06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c08, 0x00060c07, 0x00060c07, 0x00050d05, 0x00050d05, 0x00050d05, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040f09, 0x00040f0a, 0x00040f0b, 0x00050f0a, 0x0005100a, 0x00061008, 0x00070f08, 0x00070f08, 0x0005100a, 0x0006100b, 0x0006100c, 0x0007110d, 0x0008120f, 0x0008120f, 0x00091311, 0x00091311, 0x00091311, 0x00081311, 0x00081412, 0x00071512, 0x00051612, 0x00061612, 0x00061512, 0x00061512, 0x00071512, 0x00081412, 0x00081411, 0x00081311, 0x00081311, 0x00081311, 0x000a1613, 0x000b1411, 0x000c1613, 0x000c1310, 0x001c2220, 0x00343734, 0x00343433, 0x00302c2c, 0x003a3436, 0x00464042, 0x00403c3d, 0x00393436, 0x003b3537, 0x003e3536, 0x003c3130, 0x003a2d2a, 0x003e2f29, 0x0044352f, 0x00483831, 0x003e2d26, 0x0032211a, 0x002d1c14, 0x00301d16, 0x0033241c, 0x0034271f, 0x00332820, 0x00342920, 0x002e241c, 0x00281e15, 0x00302219, 0x00342118, 0x00341e13, 0x00402216, 0x00472515, 0x00452513, 0x00371802, 0x00381802, 0x003a1a06, 0x00452410, 0x004c2c14, 0x004d2b14, 0x00502d15, 0x004c2a10, 0x00432304, 0x004c2d0e, 0x005d3315, 0x00603415, 0x00603514, 0x00623814, 0x005f3612, 0x005a320f, 0x004f2708, 0x00482001, 0x004c2406, 0x005b3414, 0x005a3413, 0x00552f10, 0x004f280b, 0x00441f04, 0x004d280b, 0x00583113, 0x005b3414, 0x005f3715, 0x00613a16, 0x00694019, 0x00643c14, 0x00653c14, 0x00633915, 0x00582e0d, 0x00582e0d, 0x00613612, 0x00683d18, 0x00633811, 0x00643813, 0x00603610, 0x005b320c, 0x00603711, 0x005d3510, 0x005d3611, 0x005d3814, 0x005c3616, 0x00583314, 0x00542f11, 0x00462104, 0x00421d00, 0x00553013, 0x005b3416, 0x00633a1c, 0x005c3416, 0x00542f10, 0x00472407, 0x00341904, 0x002c1709, 0x0021120a, 0x001b100d, 0x0016110b, 0x00151409, 0x00141309, 0x0018170e, 0x00131108, 0x00121007, 0x00121007, 0x00111108, 0x00111108, 0x00111108, 0x00111108, 0x00101206, 0x00101105, 0x00100e04, 0x00161007, 0x00191008, 0x001e140c, 0x00241c15, 0x00251c16, 0x0028211a, 0x0026271e, 0x0018201c, 0x0014201d, 0x0010201d, 0x000f211c, 0x000f201d, 0x0010201f, 0x0010201f, 0x00101f20, 0x00112020, 0x00112020, 0x00122021, 0x00112020, 0x00101f20, 0x00101e1f, 0x000f1d1e, 0x000f1d1c, 0x000d1c1b, 0x000c1c18, 0x000c1b18, 0x000d1a18, 0x000a1814, 0x000a1716, 0x000a1716, 0x00091615, 0x00081514, 0x00081414, 0x00071413, 0x00071313, 0x00071212, 0x00061111, 0x00061010, 0x00050f0c, 0x00060e09, 0x00060e06, 0x00060e06, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c07, 0x00050c06, 0x00050c06, 0x00040c06, 0x00040c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060b06, 0x00060b06, 0x00060b06, 0x00060b06, 0x00060b06, 0x00060b06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000b1517, 0x000b1517, 0x00091416, 0x00081415, 0x000a1414, 0x000a1414, 0x000a1414, 0x000a1414, 0x000b1516, 0x000b1517, 0x000b1517, 0x000b1516, 0x000b1515, 0x000a1414, 0x000a1513, 0x000b1413, 0x000b1413, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x00091211, 0x00091211, 0x0008120f, 0x0008120f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0006100e, 0x0006100d, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x00050c0a, 0x00060d0b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c09, 0x00070d08, 0x00070d08, 0x00060e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d09, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00060e09, 0x00060e09, 0x0005100a, 0x0005100a, 0x0006100c, 0x0007110d, 0x0007110d, 0x0008120f, 0x00091211, 0x00091211, 0x000a1412, 0x00081412, 0x00081413, 0x00081613, 0x00061512, 0x00061512, 0x00061512, 0x00061512, 0x00061512, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x000a1410, 0x000c1310, 0x00171b19, 0x00292c2b, 0x002e2d2c, 0x002c2828, 0x00393433, 0x00484041, 0x004e4545, 0x00474040, 0x003f3838, 0x00372e2d, 0x00312524, 0x00322420, 0x0034241e, 0x0034241c, 0x00312319, 0x003b2b22, 0x0044332a, 0x00402f25, 0x002e1e14, 0x002c190e, 0x0028170c, 0x0029180d, 0x002a190d, 0x002c1b10, 0x00312015, 0x00342219, 0x002c1910, 0x002c180c, 0x00341f10, 0x00381e0e, 0x00482816, 0x0052311c, 0x00502f17, 0x0041200b, 0x003d1c08, 0x003e1c08, 0x0045250e, 0x00503017, 0x004e2c11, 0x00502d10, 0x00563114, 0x004a2404, 0x00522808, 0x005e3214, 0x00592d0c, 0x00603611, 0x00643b14, 0x00633a14, 0x005c3411, 0x00502808, 0x00502808, 0x00542c0c, 0x005c3414, 0x00532c0c, 0x00451f04, 0x0048210c, 0x00462007, 0x00552f12, 0x005c3516, 0x005e3713, 0x00623b13, 0x00653c13, 0x00643c11, 0x00613810, 0x00623814, 0x00552c0a, 0x00522807, 0x00613817, 0x00653c18, 0x00582f0c, 0x005e3411, 0x005c330e, 0x005c340e, 0x005c340f, 0x005a330d, 0x0058310d, 0x005c3513, 0x00583112, 0x00583315, 0x00502b0f, 0x00462003, 0x00512c0f, 0x00563013, 0x005e3819, 0x0060391b, 0x005b3518, 0x0049260d, 0x003c1a03, 0x00301707, 0x00281307, 0x0023140b, 0x001d130c, 0x0019140c, 0x0019160c, 0x0018140c, 0x0016120a, 0x0014110a, 0x00141109, 0x00121008, 0x00131209, 0x0013130a, 0x00131209, 0x00131209, 0x00111308, 0x00101207, 0x000f1004, 0x00131006, 0x00161008, 0x00181108, 0x001c130c, 0x00271a15, 0x00251b15, 0x00242119, 0x001d231e, 0x00141d1c, 0x00121f1c, 0x0010201c, 0x0010201d, 0x0010201f, 0x00112020, 0x00122021, 0x00122021, 0x00112020, 0x00101f20, 0x00101e1f, 0x00101e1f, 0x00101e1f, 0x00101e1f, 0x000f1d1c, 0x000e1c1b, 0x000c1b18, 0x000b1a17, 0x000b1816, 0x000a1814, 0x00091615, 0x00091615, 0x000a1514, 0x000a1414, 0x00081414, 0x00081313, 0x00081212, 0x00071010, 0x00061010, 0x0006100f, 0x00050f0c, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000b1517, 0x000b1517, 0x00091416, 0x00081414, 0x000a1414, 0x000a1513, 0x000a1414, 0x000a1414, 0x000b1515, 0x000b1515, 0x000b1515, 0x000b1515, 0x000b1515, 0x000a1414, 0x000a1513, 0x000b1413, 0x000b1413, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091310, 0x00091310, 0x00091310, 0x0008120f, 0x0008120f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007100f, 0x0006100e, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00040e09, 0x00050d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d08, 0x00070d08, 0x00060e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d09, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100c, 0x0007110d, 0x0007110d, 0x0008120f, 0x00091310, 0x00091310, 0x000a1412, 0x00081412, 0x00081413, 0x00081613, 0x00061512, 0x00061512, 0x00061512, 0x00061512, 0x00061512, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081410, 0x000a1410, 0x000c1210, 0x00101512, 0x001e201d, 0x00323030, 0x00464340, 0x00554d4c, 0x004f4645, 0x00443c3b, 0x00423838, 0x00403837, 0x003d3331, 0x003b2e2c, 0x00382924, 0x0034241c, 0x0034271c, 0x00392c22, 0x002f2217, 0x0034261a, 0x00433428, 0x00443428, 0x00312014, 0x00281608, 0x002b170a, 0x002a1808, 0x002b1708, 0x002c1609, 0x00331a10, 0x00371f14, 0x00321b0e, 0x002e1607, 0x00311905, 0x00442810, 0x004a2810, 0x00553218, 0x0058351a, 0x0046240c, 0x00391802, 0x003d1c07, 0x0043220e, 0x004f2c16, 0x00522e14, 0x004c260a, 0x005b3013, 0x0054280c, 0x00532909, 0x005d3210, 0x005c330d, 0x00623912, 0x00643b14, 0x00603813, 0x0059310d, 0x00532b09, 0x00532a09, 0x00583110, 0x00563010, 0x00452005, 0x00401905, 0x00442008, 0x0049240a, 0x00583114, 0x00643c15, 0x00633a11, 0x00653d11, 0x00643c10, 0x005e350c, 0x005e3510, 0x00512908, 0x004d2505, 0x00593210, 0x0055300e, 0x00542c0b, 0x005c3410, 0x00552e0a, 0x005f3713, 0x00562f0a, 0x0056300a, 0x0056300c, 0x00583210, 0x00542f10, 0x00553013, 0x004c280c, 0x00482306, 0x004e2b0d, 0x004f2c0e, 0x005b3718, 0x00573311, 0x00502c0e, 0x003c1a03, 0x00331604, 0x002d1408, 0x00251207, 0x0024140b, 0x001d140a, 0x00191309, 0x00181108, 0x001b150d, 0x001a150e, 0x00141009, 0x00100e06, 0x000f0e05, 0x000e0e05, 0x000e0e05, 0x000e0f06, 0x00101007, 0x00121107, 0x00131308, 0x00111308, 0x00141308, 0x00151308, 0x00181108, 0x001c120b, 0x0022150f, 0x00251b13, 0x00211d15, 0x0020241f, 0x00141e1b, 0x00101d1a, 0x0010201c, 0x0010201d, 0x0011201f, 0x00112020, 0x00122021, 0x00122021, 0x00112020, 0x00101f20, 0x00101e1f, 0x00101e1f, 0x00101e1d, 0x00101e1d, 0x000f1d1c, 0x000e1c1b, 0x000c1b18, 0x000b1a17, 0x000b1816, 0x000a1814, 0x00091615, 0x00091615, 0x000a1514, 0x000a1414, 0x00081414, 0x00081313, 0x00081212, 0x00071011, 0x00061010, 0x0006100e, 0x00050f0c, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1414, 0x00091414, 0x00081414, 0x00081313, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00091413, 0x000a1513, 0x000a1414, 0x000b1414, 0x000b1413, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x00091211, 0x00091310, 0x00091310, 0x00091310, 0x0008120f, 0x0008120f, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100d, 0x0006100e, 0x0006100d, 0x0006100c, 0x0006100c, 0x0008100c, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d05, 0x00040d07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008120d, 0x0008120d, 0x0007130f, 0x0007130f, 0x00081311, 0x00081311, 0x00081412, 0x00071512, 0x00061512, 0x00071512, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081510, 0x00081510, 0x00091410, 0x000f1514, 0x00101514, 0x00171c18, 0x00323633, 0x00424340, 0x004a4b48, 0x00424040, 0x00312e2c, 0x00302a28, 0x00342c2c, 0x00383132, 0x00413837, 0x003c3330, 0x003d342f, 0x00383128, 0x002f291e, 0x002f271d, 0x003c3128, 0x0033271e, 0x0035261d, 0x00403227, 0x00403126, 0x002c1c10, 0x00271708, 0x00291807, 0x002a1604, 0x002e1806, 0x00301709, 0x00351a0d, 0x00412718, 0x003e2411, 0x003e200c, 0x00401d08, 0x004c2910, 0x00512c10, 0x00543011, 0x00563315, 0x00462409, 0x00411f08, 0x003b1905, 0x003f1c0c, 0x004b2814, 0x004d2a10, 0x004c2807, 0x00553010, 0x00583212, 0x00562e0b, 0x005c320d, 0x0060350d, 0x00643b12, 0x00633a13, 0x00582f0b, 0x00552c0a, 0x00522b09, 0x00502a0b, 0x004e290c, 0x0045240a, 0x00351700, 0x003f1e09, 0x004b2813, 0x004c260c, 0x0068401b, 0x00623911, 0x00643b10, 0x00643c10, 0x005c350c, 0x005b3410, 0x004c2607, 0x00442105, 0x004c2a0e, 0x00462406, 0x004d280a, 0x00583212, 0x0055300f, 0x005a3412, 0x004d2804, 0x00542d0b, 0x004f2704, 0x00532c0c, 0x00522c0e, 0x00502c10, 0x00452409, 0x00482810, 0x00412008, 0x00492810, 0x004c2c11, 0x004a2c0f, 0x003e2106, 0x002e1300, 0x002c1404, 0x00291409, 0x0024120a, 0x0022150b, 0x001c140a, 0x00191408, 0x0018140b, 0x001e1a10, 0x00130f06, 0x00120f07, 0x00100f06, 0x000e0c04, 0x00121008, 0x0016140c, 0x0016140c, 0x00141309, 0x00141208, 0x00141208, 0x00141208, 0x00161409, 0x00161208, 0x0018140b, 0x001b130b, 0x001e130c, 0x00241b13, 0x00201f14, 0x0020251d, 0x0017211d, 0x00101e1b, 0x00111f1d, 0x00121f1e, 0x0013201f, 0x0013201f, 0x0013201f, 0x0011201f, 0x0011201f, 0x000f201e, 0x000f1d1d, 0x000f1d1d, 0x000f1d1c, 0x000f1d1c, 0x00101c1c, 0x000f1c1b, 0x000c1918, 0x000c1918, 0x000c1716, 0x000b1515, 0x000b1515, 0x000a1414, 0x00091414, 0x00081414, 0x00081313, 0x00081313, 0x00081211, 0x0007100f, 0x0006100e, 0x0006100e, 0x00050f0c, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1414, 0x00091414, 0x00081414, 0x00081311, 0x00081412, 0x00081410, 0x00081410, 0x00081410, 0x00081411, 0x00081412, 0x00091412, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x00081110, 0x0008120f, 0x00091310, 0x0009130e, 0x0008120d, 0x0007110c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0008100c, 0x00070f0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040d08, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008120d, 0x0008120d, 0x0007130f, 0x0007130f, 0x00081410, 0x00081410, 0x00081411, 0x00071512, 0x00061512, 0x00071512, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081412, 0x00081513, 0x00061510, 0x00071510, 0x000c1410, 0x000c130f, 0x00121714, 0x002d312e, 0x00454845, 0x004c4d4b, 0x003d3e3c, 0x00333130, 0x00353231, 0x00373333, 0x00353130, 0x00332d2d, 0x00322d2c, 0x003d3635, 0x003e3935, 0x003c3833, 0x0037342d, 0x00342e28, 0x00312821, 0x00382c24, 0x00362822, 0x0031241c, 0x0041342a, 0x00403228, 0x00302015, 0x002b1a0b, 0x002c1807, 0x00301b08, 0x00341b0a, 0x00371c0c, 0x00371b09, 0x003c1f0c, 0x004b2914, 0x0048230d, 0x004c250c, 0x004f280c, 0x00502a09, 0x00583410, 0x005a3718, 0x004d2810, 0x00421e0c, 0x003e1a0c, 0x003f1d0b, 0x00482710, 0x004e2f12, 0x00442406, 0x004e2b0a, 0x005c3512, 0x0058300d, 0x005b300b, 0x00643a15, 0x00643b15, 0x005e3411, 0x00532a08, 0x004e2807, 0x00492507, 0x00442207, 0x0040230c, 0x00371d07, 0x00351a06, 0x00482915, 0x0044200a, 0x00673e1f, 0x00623b17, 0x005b340d, 0x005c350e, 0x0058330d, 0x00502a0a, 0x00462208, 0x00402008, 0x0041220d, 0x00402008, 0x004c280f, 0x004d280e, 0x00583315, 0x00512e0e, 0x004c2909, 0x004e290a, 0x004f2809, 0x00522c0c, 0x00502c0f, 0x00472509, 0x003f2008, 0x003d200a, 0x00391c08, 0x003c1f0a, 0x0040240c, 0x003e240c, 0x00311804, 0x002a1403, 0x00291408, 0x0028170c, 0x00231208, 0x0021140a, 0x001e1408, 0x001c1509, 0x001e180b, 0x00191208, 0x00171107, 0x00140e04, 0x00120e04, 0x00141007, 0x00151108, 0x00141006, 0x00140f06, 0x00151006, 0x00151005, 0x00181207, 0x00191408, 0x001a1409, 0x00181308, 0x00191408, 0x001a140a, 0x001f140b, 0x0021180f, 0x00211f14, 0x0023251d, 0x0018211c, 0x00101e1a, 0x00101f1d, 0x00111f1e, 0x00121f1e, 0x0013201f, 0x0013201f, 0x0011201f, 0x0011201f, 0x000f201e, 0x000f1d1c, 0x000f1d1c, 0x000f1d1c, 0x000f1d1c, 0x00101c1c, 0x000d1a19, 0x000c1918, 0x000b1818, 0x000c1716, 0x000b1515, 0x000b1614, 0x000a1513, 0x00081412, 0x00081311, 0x00081311, 0x00081311, 0x00081210, 0x0007100d, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081414, 0x00081414, 0x00081313, 0x00081311, 0x00081311, 0x00081410, 0x00081410, 0x00081410, 0x00081311, 0x00081311, 0x00081311, 0x00091211, 0x00091211, 0x00091211, 0x00091211, 0x000a1211, 0x000a1211, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0008120f, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x00060f0c, 0x00070e0c, 0x00060e09, 0x00050d08, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00050e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f0b, 0x00030f0b, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007130f, 0x0007130f, 0x0008120f, 0x0008120f, 0x00081310, 0x00081412, 0x00081412, 0x00081412, 0x00081513, 0x00081513, 0x00081412, 0x000c1816, 0x000c1816, 0x00081513, 0x00071711, 0x00081610, 0x000c1510, 0x000d1411, 0x00292c2b, 0x00444443, 0x004e4c4c, 0x004c4a48, 0x003c3c3a, 0x0041403f, 0x002e2c2b, 0x00201c1b, 0x00201d1c, 0x00252322, 0x002f2d2c, 0x00343031, 0x00353334, 0x003c3b3b, 0x003c3839, 0x00332c2c, 0x00342c27, 0x002e231d, 0x00382b24, 0x00342720, 0x0033251f, 0x00453830, 0x0044362c, 0x00322215, 0x002e1b0b, 0x002f1a08, 0x00311b08, 0x00341908, 0x003b1e09, 0x003f1f08, 0x0045230e, 0x004b250f, 0x004e2810, 0x0051280c, 0x00502807, 0x00522c08, 0x00593313, 0x00613b1e, 0x0059341c, 0x00441f08, 0x003c1b04, 0x003a1c07, 0x0041260f, 0x004d3115, 0x00472708, 0x00543010, 0x005f3817, 0x00552c0b, 0x005c3110, 0x00653a19, 0x00603614, 0x00542a0b, 0x00482405, 0x00422104, 0x003c1e04, 0x00381d08, 0x0039200d, 0x00301705, 0x003a1e0c, 0x003b1907, 0x005a341b, 0x005c3418, 0x00542d0c, 0x00542f0d, 0x00512d0e, 0x00472409, 0x00401f0a, 0x003b1d0c, 0x00381b0d, 0x00402212, 0x00401f0d, 0x0045220d, 0x0049270e, 0x004b290e, 0x0048250b, 0x004b290e, 0x004c290c, 0x00502d0f, 0x004d2c0d, 0x003e1e03, 0x00391d06, 0x00311a06, 0x00301806, 0x002e1805, 0x003a2311, 0x00311c0b, 0x00281506, 0x00241205, 0x00221407, 0x00201208, 0x00201409, 0x00201108, 0x00211309, 0x0022150b, 0x001d1006, 0x001a0d03, 0x001f1408, 0x0021160b, 0x0020160b, 0x001e150a, 0x001e150a, 0x001b1207, 0x001b1206, 0x001b1207, 0x0020170b, 0x0020170b, 0x0020170b, 0x001f160b, 0x001a1207, 0x00181105, 0x001a1308, 0x001f140b, 0x0021140c, 0x00251c13, 0x0026221a, 0x001b201a, 0x00101d18, 0x00101f1c, 0x00101e1d, 0x00101e1d, 0x00101e1d, 0x00101e1d, 0x00101e1d, 0x00111f1e, 0x00101e1d, 0x000e1c1b, 0x000e1c1b, 0x000e1c1b, 0x000e1c1b, 0x000f1c1b, 0x000d1a19, 0x000c1918, 0x000b1818, 0x000b1614, 0x000a1514, 0x000a1513, 0x00091412, 0x00091310, 0x00091310, 0x00081310, 0x0008120f, 0x0008120f, 0x0007100d, 0x0006100c, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081414, 0x00081414, 0x00081313, 0x00081311, 0x00081311, 0x00081410, 0x00081410, 0x00081410, 0x00081310, 0x00081311, 0x00081211, 0x00091211, 0x00091211, 0x00091211, 0x00091211, 0x000a1211, 0x000a1211, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0008120f, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x00070e0c, 0x00060e09, 0x00040c08, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f0b, 0x00030f0b, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007130f, 0x0007130f, 0x00081310, 0x0008120f, 0x00081310, 0x00081412, 0x00081412, 0x00081412, 0x00081513, 0x00081513, 0x00091513, 0x00101c1a, 0x000f1c19, 0x00081513, 0x00061711, 0x00081610, 0x000e1712, 0x001e2321, 0x00404442, 0x004f4d4c, 0x004f4949, 0x004b4646, 0x00413e3d, 0x003c3a39, 0x003c3a39, 0x00363434, 0x002e2c2a, 0x00262623, 0x00282827, 0x00303030, 0x00323135, 0x00333137, 0x003b363c, 0x003e363a, 0x00332a28, 0x00322623, 0x002e201b, 0x003c2f2a, 0x003a2c28, 0x00342720, 0x0044342c, 0x00433126, 0x00362213, 0x00351f0c, 0x00341c09, 0x00381e09, 0x00381904, 0x00422009, 0x0048230c, 0x004a240e, 0x00502911, 0x00542b10, 0x00532b0e, 0x00512b0b, 0x00552f0e, 0x005c3514, 0x0065401c, 0x0054300e, 0x00401f00, 0x00371b01, 0x00341a02, 0x00472d13, 0x0054341a, 0x004e2c0e, 0x00593415, 0x005c3314, 0x00522606, 0x005a2f0e, 0x005f3414, 0x00583012, 0x004b270a, 0x00442409, 0x003c1e07, 0x00321905, 0x00301b0a, 0x00341d0d, 0x00371c0d, 0x00371809, 0x004e2b16, 0x00543018, 0x00492509, 0x00452306, 0x00432205, 0x003c1c06, 0x00371808, 0x00381c10, 0x0031180c, 0x00361b0e, 0x00351608, 0x003e1d0c, 0x00442510, 0x0046280f, 0x003f2006, 0x004a2910, 0x004e2c11, 0x00533113, 0x0048290c, 0x00391c02, 0x00341a04, 0x00281605, 0x002c1a09, 0x002b1808, 0x00301d0f, 0x002b1a0c, 0x00231306, 0x00201305, 0x001e1407, 0x001d1408, 0x001f1308, 0x001e0f04, 0x0026150b, 0x0028170d, 0x002a180e, 0x002d1c11, 0x002d1c11, 0x002b1b10, 0x0028180e, 0x0024150a, 0x0024160b, 0x0026190e, 0x0026190e, 0x0025180c, 0x0022170b, 0x0022170a, 0x00201609, 0x00201609, 0x0021160a, 0x001f1408, 0x0020170b, 0x0024170e, 0x0024140c, 0x00281813, 0x00291f18, 0x001e1f18, 0x00111d18, 0x000e1e1c, 0x00101d1c, 0x00101c1c, 0x00101c1c, 0x00101c1c, 0x000f1d1c, 0x00101e1d, 0x000f1d1c, 0x000e1c1b, 0x000e1c1b, 0x000c1c1a, 0x000c1c1a, 0x000e1b1a, 0x000c1918, 0x000c1918, 0x000a1814, 0x000b1614, 0x000a1512, 0x00081411, 0x00081410, 0x0009140f, 0x0009130e, 0x0009120e, 0x0008120d, 0x0008120d, 0x0007110c, 0x0006100b, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091413, 0x00091413, 0x00081412, 0x00081311, 0x00071210, 0x00071310, 0x00071310, 0x00071310, 0x00081211, 0x00081211, 0x00091211, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00091110, 0x00091110, 0x00081010, 0x0008110e, 0x0007110e, 0x0007110c, 0x0008110c, 0x0007110c, 0x0005100b, 0x0005100a, 0x0005100b, 0x0005100b, 0x0004100b, 0x0004100b, 0x0005100b, 0x00060f0b, 0x00060e0a, 0x00050e0a, 0x00060e0a, 0x00060e0a, 0x00060e0a, 0x00060e0a, 0x00060e09, 0x00050e09, 0x00050e08, 0x00060d08, 0x00060d08, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00050d09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e08, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0005100a, 0x0004100a, 0x0006120c, 0x0008110d, 0x0008110d, 0x0008120f, 0x00091410, 0x00091210, 0x00091210, 0x00091211, 0x00081311, 0x00081412, 0x00081412, 0x00091412, 0x00091512, 0x000c1613, 0x0016201d, 0x00101c19, 0x00081612, 0x00091813, 0x000b1713, 0x0018201c, 0x003d3f3e, 0x004d4a4b, 0x00494645, 0x003f3a3a, 0x00332f2f, 0x002a2626, 0x00312f2e, 0x00393837, 0x00444442, 0x003e3e3c, 0x002c2d2b, 0x00222421, 0x00272828, 0x002c2f32, 0x002c2f34, 0x0036383c, 0x00383437, 0x00393030, 0x00372b28, 0x00352924, 0x00362a24, 0x00392c28, 0x003a2d27, 0x00332119, 0x00412d22, 0x00422d1d, 0x0038210d, 0x00381e09, 0x00442913, 0x003c1e08, 0x003c1903, 0x0049260e, 0x00512d15, 0x00532c13, 0x00562e14, 0x00583114, 0x00542c0e, 0x00502a08, 0x0058330c, 0x0058340f, 0x005f3a16, 0x00523011, 0x003b1d04, 0x00311703, 0x00381c09, 0x004d3018, 0x00543419, 0x004f2c0d, 0x00593112, 0x00572e0e, 0x004c2000, 0x00552c0c, 0x00552f10, 0x004c2b0f, 0x0048260e, 0x00381904, 0x00311804, 0x002d1809, 0x002c1508, 0x002d1608, 0x002e1504, 0x003c200c, 0x00462813, 0x003c2008, 0x00391c05, 0x00381b07, 0x00341807, 0x0030160a, 0x00331b10, 0x002c140a, 0x002d1408, 0x00351a0f, 0x0034190c, 0x00402511, 0x00391d05, 0x003b1d05, 0x00482910, 0x004e2e12, 0x004c2c10, 0x0044270c, 0x00341904, 0x002e1806, 0x00231406, 0x00251608, 0x002c1b0d, 0x002c1a0c, 0x00251608, 0x001e1103, 0x001d1203, 0x00201408, 0x0021170c, 0x00201409, 0x002b1b10, 0x002e1c10, 0x002f1a0d, 0x00361f11, 0x00382114, 0x00341f10, 0x002f1b0c, 0x002d190c, 0x0029180b, 0x0027170a, 0x00241509, 0x0024150a, 0x0024180c, 0x0022180b, 0x00201608, 0x001f1408, 0x00201408, 0x0022170c, 0x0023180c, 0x0022190e, 0x0028180e, 0x002c140c, 0x002c160e, 0x002c1c16, 0x001f1d18, 0x00121c18, 0x000e1e1b, 0x00101d1c, 0x000f1c1b, 0x000f1c1b, 0x00101c1c, 0x00101c1c, 0x00101d1c, 0x000e1c1b, 0x000d1c1a, 0x000c1c1a, 0x000c1b19, 0x000d1b19, 0x000d1a19, 0x000c1918, 0x000c1716, 0x000b1715, 0x000b1514, 0x00091414, 0x00081411, 0x00081510, 0x00081410, 0x0008140f, 0x0008120c, 0x0007100b, 0x0006100a, 0x0006100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d0a, 0x00050d09, 0x00050d09, 0x00050d07, 0x00050d06, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1513, 0x00091413, 0x00081412, 0x00081311, 0x00071210, 0x00071210, 0x00071210, 0x00071210, 0x00081211, 0x00091211, 0x00091211, 0x00081110, 0x00081010, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0007110d, 0x0007110c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00040f09, 0x00040f09, 0x00060f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x0005110b, 0x0007110d, 0x0007110d, 0x0007110d, 0x00091310, 0x00091211, 0x00091211, 0x00091211, 0x00081311, 0x00081412, 0x00081412, 0x00091412, 0x000a1511, 0x000c1613, 0x001b2420, 0x0018211e, 0x00091511, 0x000c1814, 0x0016201c, 0x00343938, 0x004d4c4c, 0x00443e40, 0x003b3736, 0x002c2828, 0x00252221, 0x001f1e1c, 0x00242221, 0x002a2b28, 0x00373836, 0x0040423f, 0x003c3d3b, 0x002d2e2c, 0x00232422, 0x00272827, 0x00282a29, 0x00353736, 0x003d3a39, 0x00352b2a, 0x003b2e2b, 0x00423530, 0x003f322c, 0x00392c27, 0x003e312a, 0x00402c24, 0x00342013, 0x00442b1c, 0x004b301c, 0x0041240f, 0x00472812, 0x004c2b15, 0x0045230d, 0x003c1801, 0x004c2810, 0x00532c14, 0x00573016, 0x00593217, 0x00563011, 0x00502c08, 0x00542f0a, 0x00512c08, 0x00502c0c, 0x00553315, 0x0043240e, 0x00341808, 0x002f1405, 0x003b1c0b, 0x0053321b, 0x00512d13, 0x004c2607, 0x00562f10, 0x00512a0b, 0x00482001, 0x004a2407, 0x0048250c, 0x0045240d, 0x00391b06, 0x00311706, 0x002a1508, 0x002a1608, 0x002c1608, 0x002c1606, 0x00341d0c, 0x003a2310, 0x00351c09, 0x00321906, 0x00301808, 0x002c1508, 0x002a1409, 0x002d170c, 0x002b150b, 0x002b1408, 0x00321a0e, 0x002f180a, 0x0037200e, 0x00331a04, 0x00351b04, 0x00482a13, 0x0047280f, 0x0045270d, 0x003c1e09, 0x002e1607, 0x00241206, 0x00201408, 0x0025180c, 0x002a1b0e, 0x00281808, 0x00211202, 0x001e1001, 0x00211406, 0x0024170a, 0x00281a10, 0x0026180c, 0x002a180c, 0x00301b0e, 0x00392213, 0x003a2010, 0x00381e0e, 0x00371c0c, 0x0031190b, 0x002e180a, 0x00291508, 0x00241409, 0x0024140c, 0x0022130b, 0x00201309, 0x001c1208, 0x001a1107, 0x001a1006, 0x00191005, 0x001a1005, 0x001a1006, 0x001c1308, 0x0026140c, 0x002f170f, 0x00341b11, 0x002c1c15, 0x00201c18, 0x00131c16, 0x000e1d1b, 0x00101d1c, 0x000f1c1b, 0x000e1b1a, 0x000e1b1a, 0x000e1b1a, 0x000e1b1a, 0x000d1c1a, 0x000c1c1a, 0x000c1c1a, 0x000d1a19, 0x000d1a19, 0x000c1918, 0x000b1818, 0x000c1716, 0x000c1716, 0x000b1515, 0x00081414, 0x00081412, 0x00081510, 0x00081410, 0x0007130e, 0x0007120c, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000a1513, 0x00091413, 0x00081412, 0x00081311, 0x00071210, 0x00071210, 0x00081210, 0x00081110, 0x00081110, 0x00091110, 0x00091110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0006100c, 0x0005100a, 0x00040e09, 0x00040e08, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x00030e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x0005110b, 0x0007110d, 0x0007110d, 0x0007110d, 0x0008120f, 0x00091110, 0x00091110, 0x00091211, 0x00091211, 0x00091312, 0x00091412, 0x00091412, 0x000b1411, 0x000c1613, 0x00202725, 0x00202724, 0x000d1411, 0x00171c1a, 0x00303534, 0x00464b48, 0x00454445, 0x00373435, 0x002c2b2a, 0x001d1c1b, 0x00141311, 0x000f100e, 0x000c0e0c, 0x0010110f, 0x00181a18, 0x002c2e2c, 0x003c3d3b, 0x003f3d3c, 0x0034302c, 0x00302a24, 0x003b332d, 0x0038302a, 0x00413833, 0x00423632, 0x003a2c27, 0x00473930, 0x0044372c, 0x0042342a, 0x00403127, 0x00493328, 0x00442c1d, 0x003e2411, 0x004f311c, 0x0054341d, 0x00502e18, 0x004c2813, 0x00512e16, 0x004a250d, 0x004b240b, 0x00542e14, 0x00573014, 0x00583114, 0x00593412, 0x0054300c, 0x00522e09, 0x00502c08, 0x00442000, 0x00462407, 0x00482813, 0x003b1f0f, 0x0034180c, 0x0036190c, 0x00442412, 0x00513018, 0x0049270c, 0x00482408, 0x00522c10, 0x00482106, 0x00432004, 0x00412008, 0x00432410, 0x003c1f0c, 0x00311909, 0x00241204, 0x00281608, 0x00281606, 0x00291605, 0x002f1a0b, 0x00321c0c, 0x00301a08, 0x002e1807, 0x002d1807, 0x00281406, 0x00271408, 0x0028150a, 0x00281509, 0x002a1508, 0x002c180b, 0x002c1709, 0x00301b0c, 0x00311a08, 0x00321804, 0x00452814, 0x003f2009, 0x003c2008, 0x00331906, 0x00291405, 0x00231308, 0x001c1409, 0x00241a0e, 0x0026180b, 0x00221404, 0x00201101, 0x00201203, 0x00241608, 0x00281a0c, 0x002b1b0f, 0x0028180c, 0x00301c0f, 0x00341c0c, 0x003d2211, 0x003c1f0e, 0x00371a09, 0x00381d0c, 0x00341909, 0x002d1709, 0x00291409, 0x0026140c, 0x0023140c, 0x0021110a, 0x0020120a, 0x001e140b, 0x001f150c, 0x001f140c, 0x001f140c, 0x001e140b, 0x001c1209, 0x001a1007, 0x001f1007, 0x00231208, 0x002a180c, 0x002c1c14, 0x00241c16, 0x00181a14, 0x00101b17, 0x000e1c1a, 0x000e1b1a, 0x000d1a19, 0x000d1918, 0x000d1919, 0x000d1919, 0x000c1a18, 0x000c1b19, 0x000d1c1a, 0x000d1a19, 0x000c1818, 0x000b1818, 0x000a1716, 0x000b1515, 0x000b1515, 0x000a1414, 0x00081414, 0x00071411, 0x00061410, 0x0006130f, 0x0006120d, 0x0007120c, 0x0006100b, 0x00050f0a, 0x0005100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e0a, 0x00060e09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091513, 0x00091413, 0x00081412, 0x00081311, 0x00071210, 0x00071210, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0007110d, 0x0007100d, 0x0005100a, 0x00040e09, 0x00040d08, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x00030f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x00030f09, 0x0005110b, 0x0007110d, 0x0008120e, 0x0008120f, 0x0008110e, 0x00091010, 0x00091010, 0x00091211, 0x000a1311, 0x00091312, 0x00091412, 0x000a1412, 0x000b1411, 0x000d1613, 0x00272e2c, 0x002c2f2e, 0x001f201f, 0x00393939, 0x004c4c4c, 0x00474848, 0x003a3939, 0x002e2f2f, 0x001f2020, 0x00111413, 0x000c100c, 0x000e110e, 0x000e100e, 0x00101210, 0x00101310, 0x00181b18, 0x00302f2d, 0x0044403e, 0x004a403c, 0x0040322a, 0x00403126, 0x0044372b, 0x003c2e24, 0x00463730, 0x00483830, 0x00403024, 0x004a3c2d, 0x00463829, 0x00443426, 0x00493124, 0x004c3322, 0x004c311c, 0x00472810, 0x004f2e15, 0x0058361c, 0x00573219, 0x00583017, 0x005c371b, 0x00532c0f, 0x00492204, 0x00502a0c, 0x005c3515, 0x005a3312, 0x0058310f, 0x0054300a, 0x00522d08, 0x004e2a08, 0x00432002, 0x003b1b04, 0x00371b0c, 0x00341910, 0x00301509, 0x003c200e, 0x00442510, 0x00472610, 0x00422009, 0x0047230d, 0x0047240d, 0x003d1d06, 0x00381a04, 0x003b1e0c, 0x00361c0a, 0x00301b0c, 0x00251506, 0x00241606, 0x00261506, 0x00261606, 0x002b1809, 0x002e1c0c, 0x002b1707, 0x002c1808, 0x002a1606, 0x00261406, 0x00261408, 0x00261408, 0x00271609, 0x00281809, 0x00291609, 0x002a1809, 0x002c1809, 0x002f1909, 0x00341d0c, 0x003c2210, 0x00381e08, 0x00371c08, 0x002c1504, 0x0029160a, 0x001f1108, 0x001c140a, 0x00241a0f, 0x0024180b, 0x00211406, 0x00201304, 0x00201304, 0x00241608, 0x00281a0c, 0x002a180c, 0x00331e10, 0x00341c0d, 0x00381e0d, 0x003c200c, 0x00381905, 0x003e200c, 0x003c1f0b, 0x00331806, 0x002d1407, 0x002b150a, 0x0026140c, 0x0021100a, 0x0021100a, 0x0022140c, 0x001f140c, 0x001e140b, 0x00221710, 0x001c120b, 0x001f140b, 0x001e140b, 0x0020130b, 0x001f160b, 0x001c1305, 0x00221708, 0x00281c0f, 0x00271d14, 0x001c1a14, 0x00101914, 0x000c1b17, 0x000d1a19, 0x000d1918, 0x000d1818, 0x000c1918, 0x000d181a, 0x000c1918, 0x000b1a18, 0x000d1c1a, 0x000c1918, 0x000a1817, 0x000b1817, 0x00091615, 0x000a1414, 0x000a1414, 0x00081414, 0x00081313, 0x00051310, 0x0005130f, 0x0006120e, 0x0006120c, 0x0008120c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081412, 0x00081412, 0x00081411, 0x00081311, 0x00081311, 0x00081311, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0006100e, 0x0007100d, 0x0008120e, 0x0007110b, 0x0005100a, 0x00040f09, 0x00050f0a, 0x00050f0a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x00060f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00040d08, 0x00040d08, 0x00050d09, 0x00050d09, 0x00060d09, 0x00060d09, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00060e08, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00050e09, 0x00040e09, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x00040f09, 0x0005110b, 0x0007110d, 0x0008130f, 0x00091310, 0x00091310, 0x0009110f, 0x0009120f, 0x00091210, 0x00081411, 0x00081412, 0x00091412, 0x000c1412, 0x000c1411, 0x000f1514, 0x002c3130, 0x00383a39, 0x00403e3d, 0x00534f4f, 0x004c4949, 0x003c3c3c, 0x00343434, 0x00292c2b, 0x001e2322, 0x00191d1d, 0x00181c1a, 0x00161917, 0x00111310, 0x00101110, 0x00101210, 0x00121311, 0x001b1918, 0x00342c2a, 0x004b3e37, 0x00534036, 0x004c3729, 0x004b3728, 0x0048372b, 0x003c2c23, 0x004e3e32, 0x00463428, 0x00463224, 0x004e392b, 0x004c3828, 0x004c3424, 0x004d3320, 0x00563823, 0x0053321b, 0x004c2a10, 0x00532e14, 0x005c351a, 0x005c3518, 0x005e3618, 0x005d3716, 0x00563010, 0x00462000, 0x00542d0d, 0x005c3414, 0x005b3410, 0x0058320c, 0x00542d0a, 0x00542e0a, 0x004b2708, 0x0043220b, 0x00371b09, 0x002f160b, 0x0030170a, 0x002f1504, 0x00381f0d, 0x003f2110, 0x003c1d0c, 0x00391a09, 0x00412310, 0x003c1e0a, 0x00361905, 0x00321804, 0x00321906, 0x00301a09, 0x0029190b, 0x00211304, 0x00241607, 0x00241606, 0x00261807, 0x00291a0a, 0x00271607, 0x00291909, 0x00281707, 0x00271708, 0x00241408, 0x00241508, 0x0027170a, 0x0028180a, 0x00281608, 0x002a1808, 0x002b1707, 0x002c1808, 0x00372010, 0x00341d0c, 0x00341b0a, 0x002e1807, 0x00281404, 0x0027170a, 0x001a0f04, 0x001c150a, 0x0022190d, 0x00201609, 0x00201407, 0x00211306, 0x00211307, 0x00251609, 0x0029180c, 0x00331e10, 0x00382011, 0x00361c0b, 0x003b1f0a, 0x0040210c, 0x003f1f0b, 0x00442410, 0x00381a05, 0x00331706, 0x0031190e, 0x002f1810, 0x0024140c, 0x0021130c, 0x001e1109, 0x001c1108, 0x00181007, 0x00140f04, 0x00150e06, 0x00150f06, 0x00150f06, 0x00150f06, 0x00180e06, 0x00161107, 0x00141305, 0x00191508, 0x0020180c, 0x00241a10, 0x001e1c14, 0x00141b11, 0x000f1a14, 0x000f1917, 0x000e1918, 0x000d1919, 0x000d191a, 0x000c181a, 0x000c1918, 0x000b1a18, 0x000c1c18, 0x000c1918, 0x000a1816, 0x000a1816, 0x00091614, 0x00091414, 0x00091414, 0x00081413, 0x00081312, 0x00051310, 0x0006130f, 0x0007120e, 0x0006110c, 0x0008120d, 0x0008120d, 0x0006100b, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f09, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050d09, 0x00040d07, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00061411, 0x00061411, 0x00071411, 0x00071411, 0x00081311, 0x00091311, 0x00091211, 0x00081110, 0x00081210, 0x0008120d, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110d, 0x0008110e, 0x0008120e, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0005100a, 0x00061009, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0007100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x0004100a, 0x0004100a, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110f, 0x0009130f, 0x00081410, 0x00081510, 0x00091511, 0x000a1511, 0x000c1411, 0x000e1513, 0x00151b19, 0x00303332, 0x00444444, 0x004c4b49, 0x004d4a49, 0x00423f3e, 0x00373735, 0x00333434, 0x002e3232, 0x00283030, 0x00262c2c, 0x00292c2b, 0x00222422, 0x00191817, 0x00131410, 0x00131310, 0x00151412, 0x001b1715, 0x002c2421, 0x003d3028, 0x0048372c, 0x00543e31, 0x004b3728, 0x004c3b2c, 0x00402f22, 0x00443428, 0x004f3b2f, 0x004a3426, 0x004a3023, 0x00543929, 0x00503524, 0x00513521, 0x00533620, 0x00583820, 0x00553418, 0x00522d10, 0x00552d10, 0x005d3415, 0x00663e1c, 0x00613a18, 0x00603917, 0x00552d0c, 0x00482000, 0x0057300e, 0x00643c19, 0x00603a16, 0x005c3410, 0x0058300b, 0x005b3515, 0x00502f15, 0x003f200d, 0x00301608, 0x002f1606, 0x002c1604, 0x002f1908, 0x00381d10, 0x00351b0c, 0x0034180a, 0x0036190c, 0x003a200e, 0x00341a06, 0x002f1604, 0x00311805, 0x00311c0b, 0x002d190c, 0x00241304, 0x00241406, 0x00231606, 0x00241808, 0x00281a0b, 0x00261708, 0x002b1b0c, 0x0028180c, 0x0028180a, 0x00241408, 0x00241407, 0x0028180b, 0x002a1a0c, 0x00271506, 0x002c1808, 0x002b1604, 0x002e1808, 0x00321b0c, 0x00311a0a, 0x002f180a, 0x002b1606, 0x00261505, 0x00211405, 0x001c1103, 0x001d1609, 0x001f1608, 0x00201408, 0x00221408, 0x00241508, 0x0026170b, 0x0028150b, 0x002b160c, 0x00321709, 0x00361b0b, 0x00381c09, 0x003c1f09, 0x0043230c, 0x00482810, 0x0041210c, 0x003a1c08, 0x00361a0b, 0x0031180e, 0x0028130c, 0x0023120c, 0x001c100a, 0x00161008, 0x00110f04, 0x000e0d03, 0x000c0d02, 0x000d0d02, 0x000d0d02, 0x000d0c04, 0x000c0c03, 0x000e0b04, 0x00090c02, 0x00060c02, 0x000a0e04, 0x00140d07, 0x0018120a, 0x001b1910, 0x001a1e12, 0x00131a12, 0x00101814, 0x00101818, 0x000e1819, 0x000d181a, 0x000c181a, 0x000a1819, 0x000a1916, 0x000a1916, 0x000a1814, 0x000a1814, 0x00081613, 0x00081412, 0x00081510, 0x00081510, 0x00081510, 0x00071410, 0x00051310, 0x0007130f, 0x0006100c, 0x0006100c, 0x0006100b, 0x0006100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00070f09, 0x00060e08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00051411, 0x00051411, 0x00071411, 0x00071411, 0x00081412, 0x000a1412, 0x00091211, 0x00081110, 0x0008120f, 0x0008120d, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0006100c, 0x00040e0b, 0x00040e09, 0x00051008, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x0004100a, 0x0004100a, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110d, 0x0009130e, 0x00081410, 0x00081510, 0x00081611, 0x000a1511, 0x000c1511, 0x00131816, 0x00202422, 0x00343534, 0x004e4e4e, 0x004e4c4d, 0x00444244, 0x00383839, 0x00343636, 0x00303535, 0x002d3434, 0x00272e30, 0x00252a2c, 0x00202224, 0x00242120, 0x00282724, 0x00201d1b, 0x00191513, 0x00181412, 0x0015120e, 0x001d1912, 0x002f241b, 0x003d2e22, 0x00443324, 0x004b3a2a, 0x004f3e30, 0x004a3a2c, 0x00412f23, 0x00453126, 0x00503b2e, 0x00472e21, 0x00493120, 0x004f3824, 0x004e3721, 0x00533720, 0x0054371d, 0x005e3f24, 0x005b381a, 0x00522c0e, 0x00542c0b, 0x005c3513, 0x006e4622, 0x00653d1a, 0x00603817, 0x00542c0c, 0x00482201, 0x005b3614, 0x00643e1c, 0x00643c1a, 0x00552e0b, 0x00573210, 0x005a381c, 0x0051311a, 0x0040230e, 0x00311502, 0x002c1403, 0x002e1708, 0x00321b0d, 0x0030180a, 0x002f1508, 0x00301809, 0x00371f0e, 0x00331c0a, 0x002f1605, 0x00301808, 0x00321b0c, 0x002e1909, 0x00291607, 0x00261406, 0x00241506, 0x00261708, 0x002b180b, 0x00281608, 0x002c190c, 0x002a180c, 0x0029180a, 0x00271408, 0x00261406, 0x0028180b, 0x002c1c0d, 0x00281506, 0x002c1707, 0x002c1504, 0x00301908, 0x00321b0b, 0x002f1809, 0x002e1709, 0x00281505, 0x00241404, 0x00201403, 0x00201406, 0x00211609, 0x00211408, 0x00241408, 0x00271509, 0x00271408, 0x0029170b, 0x002c180c, 0x002e160b, 0x0033180b, 0x0036190a, 0x00381c08, 0x003c200a, 0x00492912, 0x004c2b12, 0x0044240f, 0x0040240f, 0x003a2010, 0x002f170d, 0x0026130b, 0x001f1009, 0x00140d04, 0x000f0f04, 0x000c0d01, 0x00090f04, 0x00090f04, 0x000a0f04, 0x000b0e04, 0x000a0e05, 0x00080d05, 0x00080d04, 0x00060d04, 0x00050c04, 0x00050c02, 0x00090902, 0x000c0b03, 0x00111008, 0x00191912, 0x00181c15, 0x00101814, 0x000e1716, 0x000c1717, 0x000b1618, 0x00081717, 0x00091816, 0x00091814, 0x00091813, 0x000a1714, 0x000a1814, 0x00081412, 0x00051310, 0x00081510, 0x00081510, 0x00081410, 0x00071410, 0x00051310, 0x0006110e, 0x0005100c, 0x0005100b, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071411, 0x00071411, 0x00071411, 0x00071411, 0x00081412, 0x000a1412, 0x00091211, 0x00081110, 0x0008110e, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0007110d, 0x00050f0c, 0x0005100a, 0x00051008, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x0004100a, 0x0004100a, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110d, 0x0009130e, 0x0008140f, 0x00081410, 0x00081611, 0x000a1510, 0x000b120e, 0x00111512, 0x002c2e2b, 0x00484847, 0x004a4a4a, 0x00404244, 0x00363839, 0x00303335, 0x002e3234, 0x002c3234, 0x002b3434, 0x002b3235, 0x00292e30, 0x00292b2c, 0x00272524, 0x002a2622, 0x002a2521, 0x0025201c, 0x001c1713, 0x001b1813, 0x001e1a14, 0x00272014, 0x0034281c, 0x00392a1b, 0x003c2d1d, 0x00463628, 0x004f3d2f, 0x00473428, 0x003a281c, 0x00453224, 0x004a3427, 0x00422c1b, 0x004c3622, 0x004d3821, 0x004d361f, 0x0053391f, 0x00563a1d, 0x00604022, 0x005a3818, 0x00593413, 0x00562f0d, 0x00623a18, 0x0068401f, 0x005d3715, 0x005b3414, 0x004f2809, 0x00482103, 0x00563113, 0x00653e20, 0x0060381b, 0x00502a0c, 0x004c280c, 0x004c2c11, 0x004e2e15, 0x003f220c, 0x00341807, 0x002d1405, 0x002c1508, 0x002d160a, 0x002d160a, 0x002d1608, 0x002e1909, 0x00331e0e, 0x00301c0c, 0x002d1709, 0x0030190b, 0x00301c0d, 0x002c1809, 0x00271507, 0x00241506, 0x002a170a, 0x002a1609, 0x002c190c, 0x002e180c, 0x002b180c, 0x002b170c, 0x002c180b, 0x00271406, 0x0028170a, 0x002c1c0d, 0x002b1808, 0x002d1908, 0x00301a08, 0x00331c0c, 0x00341c0c, 0x0030190a, 0x002e1809, 0x002a1808, 0x00261404, 0x00231505, 0x00241709, 0x0025170b, 0x00241409, 0x00281509, 0x002c180d, 0x002c170c, 0x002f1a0e, 0x00392014, 0x00371b10, 0x00381b0d, 0x00351808, 0x00351905, 0x003f220d, 0x004b2a14, 0x004b2a12, 0x00492814, 0x00402410, 0x00311808, 0x00281308, 0x00221008, 0x00190f06, 0x00130d04, 0x000d0f03, 0x000c0f03, 0x00091003, 0x00081004, 0x00091008, 0x00091008, 0x00080f07, 0x00080f07, 0x00040f06, 0x00060e06, 0x00070e06, 0x00070e06, 0x00060e06, 0x00080d04, 0x000a0c04, 0x0014120d, 0x00181914, 0x00101714, 0x000c1414, 0x000c1515, 0x000b1517, 0x00091617, 0x00091615, 0x00091714, 0x00091712, 0x00081513, 0x00081513, 0x00081412, 0x00081412, 0x00081510, 0x00081510, 0x00071410, 0x0005130f, 0x0004120f, 0x0005100d, 0x0005100c, 0x0005100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00060e09, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071411, 0x00071411, 0x00071411, 0x00071411, 0x00081311, 0x00091211, 0x00081110, 0x00081110, 0x0008110e, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007100c, 0x0006100c, 0x0006100c, 0x00040d0a, 0x00040e0a, 0x0006100c, 0x00050f0c, 0x0005100a, 0x00051008, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c08, 0x00060c08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x0004100a, 0x0004100a, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110d, 0x0009130e, 0x0008140f, 0x00081410, 0x00081610, 0x000a1510, 0x00101713, 0x002d302e, 0x0050514f, 0x003e3c3c, 0x00313031, 0x002c2d2f, 0x00222426, 0x0024282b, 0x00282d2f, 0x00283032, 0x00263032, 0x00252d30, 0x0024292b, 0x00242628, 0x00252422, 0x0025231e, 0x0027201c, 0x0029231d, 0x002c261f, 0x001e1812, 0x001c180e, 0x0021180e, 0x002c2010, 0x00322616, 0x0037291a, 0x00372718, 0x00443224, 0x00443327, 0x00402f22, 0x00352315, 0x00473324, 0x0045301f, 0x003f2b18, 0x004d3823, 0x004e3822, 0x004a331a, 0x00563c20, 0x00543519, 0x005f3d1f, 0x005c3a1a, 0x005d3817, 0x0058300f, 0x005d3614, 0x005e3715, 0x00532c0c, 0x005c3517, 0x004a2408, 0x00401a00, 0x00532e13, 0x005d361c, 0x00593318, 0x004c280e, 0x00432107, 0x003c1c02, 0x003f2209, 0x00371c09, 0x0032190a, 0x002c1708, 0x002c170a, 0x002c180b, 0x002b1809, 0x002b1808, 0x002d190b, 0x00321e0f, 0x00311c0d, 0x002d180a, 0x00301a0d, 0x002e190c, 0x00281608, 0x00251406, 0x002d180b, 0x002d180b, 0x002e180c, 0x002e180c, 0x002d180c, 0x002c180c, 0x002c190c, 0x00291607, 0x00281708, 0x002e1d0d, 0x002f1a0b, 0x00321c0a, 0x00321c0a, 0x00331c0c, 0x00341d0d, 0x0030190a, 0x002f190a, 0x002d190a, 0x00281808, 0x00281809, 0x0028180b, 0x0028160c, 0x00281308, 0x0030170c, 0x00341b0d, 0x00361d0e, 0x00392010, 0x00432617, 0x00391c0c, 0x003a1c0c, 0x00361807, 0x003b1f0b, 0x00452812, 0x004a2a13, 0x004b2b13, 0x00472712, 0x00381c08, 0x002c1404, 0x00241306, 0x00201207, 0x00191007, 0x00140f06, 0x00121006, 0x00101008, 0x000c0f04, 0x000c1006, 0x000c0e08, 0x000c0e08, 0x000b0d07, 0x000a0e07, 0x00051008, 0x00070d08, 0x00090c08, 0x00080c08, 0x00050f06, 0x00060e06, 0x00080b04, 0x000e0e09, 0x00161814, 0x00101614, 0x000c1414, 0x000c1616, 0x000b1517, 0x00091617, 0x00091615, 0x00091714, 0x00091712, 0x00091513, 0x000a1513, 0x00081412, 0x00081412, 0x00081410, 0x00081410, 0x00081410, 0x0007130f, 0x0004120f, 0x0005100d, 0x0005100c, 0x0005100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00060e09, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071411, 0x00071411, 0x00071210, 0x00071210, 0x00081311, 0x00081311, 0x00081110, 0x0007100f, 0x0007100f, 0x0007110e, 0x0007110d, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0005100a, 0x00040e09, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040d09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00041008, 0x00031008, 0x00041008, 0x00041009, 0x00050f0c, 0x0007110d, 0x0008120f, 0x0008120f, 0x0008120f, 0x0008120f, 0x00081310, 0x0007140f, 0x0008150f, 0x000c1510, 0x00202622, 0x00484c48, 0x0040413d, 0x0032302f, 0x001e1d1e, 0x0019181b, 0x0027282c, 0x00292e30, 0x002a2f33, 0x00293034, 0x002a3537, 0x00283034, 0x00262b2d, 0x00242627, 0x00252422, 0x0024201e, 0x00201c18, 0x00231c17, 0x002b241c, 0x002b241b, 0x00231a10, 0x00271c0f, 0x002b1c0e, 0x002c1f0f, 0x00312415, 0x00312316, 0x00302014, 0x003f2f22, 0x00433125, 0x003e2c20, 0x003a2618, 0x003d2a1b, 0x003f2c1b, 0x003f2c1a, 0x004d3824, 0x004c3521, 0x00462e17, 0x00543921, 0x0054351c, 0x00614024, 0x005c381a, 0x00593314, 0x00593214, 0x00583010, 0x00572e0f, 0x005a3013, 0x005b3216, 0x00482107, 0x00441e06, 0x0048240d, 0x004f2b14, 0x004f2a14, 0x0044230c, 0x00391c01, 0x00371b04, 0x00371c0c, 0x00321a0c, 0x002f1a0c, 0x002c180b, 0x002d180b, 0x002c170a, 0x002c170a, 0x002e190b, 0x00331d0f, 0x00331d0f, 0x00301a0b, 0x0030180a, 0x002d180a, 0x002b1607, 0x002a1304, 0x0030180a, 0x00321b0d, 0x0030180a, 0x002e180c, 0x0030180c, 0x002e180c, 0x002f1a0b, 0x002c190a, 0x002f1b0b, 0x00321a0a, 0x00341809, 0x00361809, 0x00351c0a, 0x00341c09, 0x00331c0a, 0x00321c0b, 0x00321c0c, 0x00301909, 0x002d1808, 0x002e1a0b, 0x002e180b, 0x0030180c, 0x00361a0e, 0x003c1d0f, 0x0043200f, 0x00472510, 0x004a2810, 0x0048260f, 0x0043210a, 0x0043200c, 0x003c1c07, 0x0042230e, 0x00452811, 0x00482811, 0x0044210c, 0x003e1e09, 0x00381b08, 0x002e1807, 0x00271607, 0x00211407, 0x001c1207, 0x00181108, 0x00140f08, 0x00141008, 0x00141109, 0x00101007, 0x0013120b, 0x00111009, 0x00101009, 0x000c0d08, 0x000e100a, 0x000c0d08, 0x000b0d07, 0x00080c05, 0x00080c04, 0x00080c03, 0x00080b02, 0x000c1007, 0x00141814, 0x000f1514, 0x000b1514, 0x000c1714, 0x000c1614, 0x00091615, 0x00091615, 0x00081513, 0x00091513, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x000a1410, 0x000a1410, 0x0008120f, 0x0008120f, 0x00071210, 0x0006110d, 0x0004100c, 0x0004100b, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00040e07, 0x00030c06, 0x00030c06, 0x00030c06, 0x00040c09, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00040c0a, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071411, 0x00071411, 0x00071210, 0x00071210, 0x00071210, 0x00071210, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007110e, 0x0008120e, 0x00050f0b, 0x00030d08, 0x0005100a, 0x0005100a, 0x00040e09, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040d09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00041008, 0x00031008, 0x00041008, 0x00041009, 0x00050f0c, 0x0007110d, 0x0008120f, 0x0008120f, 0x0008120f, 0x0008120f, 0x00081310, 0x0008140f, 0x0009140f, 0x000f1813, 0x003c403d, 0x003c403c, 0x0021231f, 0x00181817, 0x00202020, 0x002c2b2e, 0x00292b2e, 0x002c2f31, 0x002a2f33, 0x00283033, 0x002b3537, 0x002c3437, 0x00282d2f, 0x00252728, 0x00262424, 0x0023201e, 0x00241f1d, 0x00271f1c, 0x00282018, 0x00342a20, 0x002c2014, 0x002b1c0e, 0x002e1d0e, 0x002f1e0f, 0x002f2011, 0x002f2013, 0x002c1d10, 0x002e2013, 0x003a2a1d, 0x00433226, 0x00413022, 0x00352416, 0x00362415, 0x003b2a19, 0x00402e1d, 0x00483423, 0x0047321f, 0x0049301c, 0x00573c24, 0x00513318, 0x00603e22, 0x00543014, 0x00583216, 0x00573114, 0x00542d0f, 0x00562e10, 0x00573014, 0x00502c12, 0x00432009, 0x00401e09, 0x0044220c, 0x00482711, 0x00482810, 0x003c1f06, 0x00371c07, 0x00341b0b, 0x00311b0c, 0x002f1b0d, 0x002c190c, 0x002a1408, 0x002d180b, 0x002d180b, 0x002d180a, 0x00331c0e, 0x00341c0f, 0x00321b0c, 0x002e1809, 0x002d1809, 0x002c1708, 0x002c1406, 0x0030180a, 0x00321b0d, 0x0030190b, 0x002f190c, 0x0030180c, 0x002e180c, 0x002f190b, 0x00331e0d, 0x00361e0d, 0x00381d0c, 0x003a1c0c, 0x003e1e0e, 0x003a1c08, 0x003b1f08, 0x003b1f0a, 0x00391e09, 0x00381e0a, 0x00361c08, 0x00341907, 0x00341c0a, 0x00371c0a, 0x003f2010, 0x00442310, 0x0047230f, 0x004c260e, 0x00502a0f, 0x00542e10, 0x00542e10, 0x00502a0c, 0x004c280c, 0x00462108, 0x004c2b14, 0x0044240d, 0x0044240c, 0x003f1f07, 0x003a1a05, 0x00381c08, 0x00301a07, 0x00281608, 0x00241408, 0x00201308, 0x001b1008, 0x00181008, 0x00171009, 0x00161109, 0x00120f07, 0x00100c04, 0x00131008, 0x0015130b, 0x00121008, 0x0014110a, 0x00111009, 0x00111009, 0x00101008, 0x000f0f06, 0x000f0f06, 0x000e0e04, 0x00111108, 0x00151811, 0x000f1511, 0x000a1410, 0x000a1511, 0x000b1412, 0x000a1514, 0x000a1414, 0x00081412, 0x00081412, 0x000a1412, 0x000a1412, 0x00091211, 0x00091211, 0x000a1410, 0x00091310, 0x0008120f, 0x0008120f, 0x00071210, 0x0006110e, 0x0005100c, 0x0004100b, 0x00060f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00040e07, 0x00030c06, 0x00030c06, 0x00030c06, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00071210, 0x00071210, 0x00071210, 0x00071210, 0x0007100f, 0x0007100f, 0x0007100f, 0x0007110e, 0x0007110d, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00041008, 0x00041008, 0x00051109, 0x00041008, 0x00040e0b, 0x0006100c, 0x0007110d, 0x00091310, 0x0008120f, 0x0007110d, 0x0008120e, 0x0008130e, 0x0008140e, 0x00202923, 0x003b403b, 0x002b2e29, 0x001f1f1b, 0x00242221, 0x002c2c2d, 0x0029292c, 0x0026272c, 0x0025282c, 0x00272c30, 0x00262e31, 0x002c3437, 0x002d3438, 0x002e3334, 0x002c2e30, 0x00282828, 0x00201d1c, 0x001f1a18, 0x00211815, 0x00251c14, 0x002c2116, 0x00362819, 0x00342212, 0x00301c0c, 0x00301d0d, 0x002e1f10, 0x002c1f11, 0x002c1d10, 0x002c1e11, 0x00312416, 0x00372a1c, 0x003c2d20, 0x003a2b1e, 0x00362819, 0x00382a1b, 0x003c2c1d, 0x003f2e20, 0x00402e1d, 0x00432e1b, 0x004c331e, 0x0052371f, 0x0054351c, 0x0058381d, 0x00512e15, 0x00543216, 0x00583417, 0x00542e0f, 0x00502c0f, 0x004b280e, 0x0044240c, 0x0040200a, 0x0040200c, 0x0040200c, 0x0043240d, 0x0041240e, 0x00391e0a, 0x00341c0b, 0x0030190b, 0x002e1a0c, 0x002e1a0e, 0x002c170a, 0x002d180b, 0x002c170a, 0x002d180b, 0x002f180c, 0x0030190c, 0x00361f10, 0x002d1608, 0x002e180a, 0x00301b0c, 0x002d1608, 0x0030180b, 0x00321b0d, 0x0030190b, 0x0030180c, 0x0030180c, 0x0030180c, 0x00311a0a, 0x00361f0d, 0x0039200d, 0x003c1f0a, 0x00422110, 0x00401d0b, 0x00401d06, 0x0044220a, 0x00402008, 0x00402009, 0x0040220a, 0x0040200b, 0x003c1e08, 0x003e200b, 0x0044240e, 0x00492810, 0x004c2810, 0x00572f14, 0x005c3114, 0x005d3310, 0x00603611, 0x005f340f, 0x005a300b, 0x00512907, 0x00492405, 0x00462309, 0x0044210a, 0x0044220b, 0x00401d06, 0x0040200c, 0x00351804, 0x00321807, 0x002c1608, 0x00281409, 0x0024140c, 0x0024150d, 0x001e140c, 0x001a110b, 0x00170f08, 0x0017100a, 0x001a140c, 0x0018130c, 0x0018120c, 0x0019140c, 0x001a150c, 0x00181209, 0x00161008, 0x00151108, 0x00151109, 0x0014110a, 0x0014120c, 0x0017140f, 0x00151610, 0x000d140d, 0x000b150e, 0x000a140e, 0x000a1410, 0x000a1412, 0x000a1412, 0x00091311, 0x00091311, 0x00091211, 0x00091211, 0x00081110, 0x00081110, 0x00091310, 0x000a1410, 0x0007110d, 0x0007110d, 0x0006110f, 0x0005100d, 0x0004100c, 0x0004100b, 0x00060f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00040e07, 0x00030c06, 0x00030c06, 0x00030c06, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00071210, 0x00071210, 0x00071210, 0x0007130f, 0x0007110d, 0x0007110d, 0x0007100e, 0x0007110e, 0x0007110d, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00050e08, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00041008, 0x00041008, 0x00051109, 0x00041008, 0x00040e0a, 0x0006100c, 0x0007110d, 0x00091310, 0x0008120f, 0x0007110d, 0x0008120e, 0x0008130e, 0x000b1610, 0x002b342e, 0x00313731, 0x00242621, 0x0022231f, 0x002b2b29, 0x00242526, 0x00242528, 0x0026282d, 0x0022252a, 0x00242a2c, 0x00262e2f, 0x00262e2f, 0x002a3034, 0x002f3334, 0x00323436, 0x00313233, 0x002a2827, 0x0024201c, 0x00211915, 0x00251d14, 0x002b1c11, 0x003a281a, 0x003b2715, 0x00321d0b, 0x00311c0b, 0x002c1c0d, 0x002b1c0f, 0x002b1c0f, 0x002b1e10, 0x002c2113, 0x00332819, 0x0033281a, 0x00372b1c, 0x003c2f21, 0x00382c1e, 0x00392d1f, 0x003d2f22, 0x00403021, 0x003f2d1e, 0x00432f1d, 0x00452f1b, 0x004b301b, 0x0052351e, 0x0053341d, 0x004d2f16, 0x004f2f13, 0x00523013, 0x004a2a0c, 0x004a2b12, 0x00462810, 0x0042250e, 0x003e200c, 0x003c1e09, 0x003d200a, 0x0040230e, 0x003f2410, 0x00381f0e, 0x00311a0c, 0x002f1b0c, 0x002f1b0f, 0x002f190c, 0x002c1709, 0x002b1507, 0x002c1709, 0x00311c0e, 0x00301a0b, 0x00341e10, 0x00301a0b, 0x00301b0c, 0x00301b0c, 0x002d1608, 0x0030190c, 0x00331c0e, 0x00311a0c, 0x00311a0d, 0x0030180c, 0x0030180c, 0x00321908, 0x00381e0c, 0x00402510, 0x0043240e, 0x0044230d, 0x0046220d, 0x00452007, 0x004d280c, 0x004c280c, 0x004c280d, 0x004b280d, 0x0048260d, 0x0046240b, 0x0048260c, 0x004d290f, 0x00542f14, 0x005c3517, 0x00633817, 0x00633512, 0x00653811, 0x00693c12, 0x0064370e, 0x00603309, 0x00582e06, 0x004e2804, 0x00482205, 0x0048240e, 0x0045240d, 0x0043220c, 0x00452510, 0x00381c09, 0x00341b08, 0x002d1507, 0x00291408, 0x0027160c, 0x0025160e, 0x0021160f, 0x001d140e, 0x001b130c, 0x001a130c, 0x0019120c, 0x001a130c, 0x0019120a, 0x0019120a, 0x00181008, 0x00160e06, 0x00181008, 0x00181008, 0x00171208, 0x00151208, 0x0015120a, 0x0017140d, 0x0015150f, 0x000e140c, 0x000b140c, 0x0009140d, 0x0008140f, 0x00091311, 0x00091311, 0x00091211, 0x00091211, 0x00091310, 0x00091310, 0x00081210, 0x00081210, 0x00091310, 0x000a1410, 0x0007110d, 0x0007110d, 0x0006100d, 0x00050f0c, 0x00050f0c, 0x0005100b, 0x00060f09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e08, 0x00040f08, 0x00051009, 0x00051008, 0x00040e07, 0x00030c06, 0x00030c06, 0x00030c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00081110, 0x0008120f, 0x0008120f, 0x0008120f, 0x0007110d, 0x0007110d, 0x0007100e, 0x0007110e, 0x0007110d, 0x0006100c, 0x0005100a, 0x0005100a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00040d06, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00050c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00030e07, 0x00020e07, 0x00020e07, 0x00020e07, 0x0005100a, 0x0005100a, 0x00040e09, 0x0006100b, 0x0007110d, 0x0007110d, 0x0008120e, 0x0008120e, 0x00101a14, 0x002b342c, 0x00282d27, 0x00242620, 0x0023241f, 0x00282827, 0x002a2c2c, 0x00282a2d, 0x00272a2c, 0x0024292c, 0x00202728, 0x00202728, 0x001d2425, 0x00212628, 0x00282c30, 0x002c2f32, 0x00303032, 0x0031302d, 0x00302c28, 0x002e2721, 0x002c2319, 0x002e1f14, 0x00341f10, 0x003b2414, 0x003c2513, 0x0035210f, 0x002f1d0f, 0x002d1d0e, 0x002c1e0e, 0x002f2211, 0x00322514, 0x00342817, 0x00352818, 0x00352818, 0x0038291a, 0x003b2c1d, 0x003b2c1e, 0x003c2c1f, 0x003c2c20, 0x003b2a1c, 0x003d2b1b, 0x0041301c, 0x0044311f, 0x0047311f, 0x004c3422, 0x0049301d, 0x00482e19, 0x004b2c18, 0x0050311b, 0x00482c13, 0x00442710, 0x00432510, 0x003e230d, 0x003b1f09, 0x00381c08, 0x00381c08, 0x0039200d, 0x00381f0f, 0x00311a0c, 0x00301a0d, 0x00301a0d, 0x00301b0d, 0x002e1b0c, 0x002f1c0c, 0x002c1809, 0x002c190a, 0x002e1c0c, 0x002d1c0c, 0x002f1c0d, 0x00311c0d, 0x00301a0c, 0x0030190b, 0x00331b0d, 0x00341c0e, 0x00331b0d, 0x00331a0e, 0x0033190d, 0x0034180c, 0x00351906, 0x0040200a, 0x0046270e, 0x0047280c, 0x0049280b, 0x004f2a0b, 0x004d2705, 0x00552d0c, 0x00542b09, 0x00562c0b, 0x00592f0f, 0x00582d0e, 0x00552b0c, 0x005a2e10, 0x005d3311, 0x00603713, 0x00663b14, 0x006c3d14, 0x006e3d14, 0x006f3d10, 0x006e3d10, 0x006e3c0f, 0x0068380b, 0x0060330b, 0x00582c07, 0x00542a0b, 0x004d250c, 0x0046240a, 0x0046240c, 0x0045240e, 0x00401f0c, 0x003a1c09, 0x00331808, 0x002c1708, 0x0028180a, 0x0026180d, 0x0024150c, 0x0020140b, 0x0020140c, 0x001c1209, 0x001f140c, 0x0020140c, 0x001f140c, 0x001f140c, 0x001e150c, 0x001e150c, 0x001e150b, 0x001c1309, 0x001c1309, 0x001c140a, 0x001c140b, 0x001a150c, 0x0018140d, 0x0014110e, 0x000d120d, 0x0009140c, 0x0006120c, 0x00081110, 0x00091211, 0x00091211, 0x00091310, 0x0009130d, 0x0008120c, 0x0009140d, 0x0009140d, 0x0007110c, 0x0008100c, 0x0007100b, 0x0007100b, 0x0007100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0a, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00081110, 0x0008120f, 0x0008120f, 0x0008120d, 0x0007110c, 0x0007110c, 0x0007110e, 0x0007110e, 0x0007110d, 0x0005100b, 0x0005100a, 0x0005100a, 0x00040e09, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00050c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00030e07, 0x00020e07, 0x00020e07, 0x00020e07, 0x0005100a, 0x0005100a, 0x00040e09, 0x0006100b, 0x0006100c, 0x0007110d, 0x0008120f, 0x0008120e, 0x000f1812, 0x00212822, 0x002a2e27, 0x002d3029, 0x002d2e28, 0x002c2f2c, 0x002c2f30, 0x002a2d30, 0x00282d31, 0x00292e31, 0x002b3234, 0x00282e30, 0x00242b2c, 0x00202426, 0x001f2126, 0x00232628, 0x00282a2c, 0x002b2a27, 0x002a2520, 0x002c241f, 0x0030271d, 0x0034251b, 0x00372316, 0x00372111, 0x0037200e, 0x00392210, 0x00342011, 0x00342111, 0x00342513, 0x00382815, 0x00382816, 0x003a2917, 0x003a2917, 0x003a2917, 0x003a2817, 0x003a2717, 0x003d2b1b, 0x003e2c1c, 0x003e2b1d, 0x003c281b, 0x003c2818, 0x003d2b18, 0x00402d1a, 0x00402f1b, 0x00402f1a, 0x00402f19, 0x004c3622, 0x00472a17, 0x00492c18, 0x00492c17, 0x00462b14, 0x00412611, 0x003d230d, 0x003a200a, 0x003a1f0b, 0x00381c09, 0x00351b0a, 0x00361d0e, 0x00321b0f, 0x00301a0d, 0x00321b0f, 0x00331c0f, 0x00331d0c, 0x00301b0a, 0x002e1808, 0x002d1808, 0x002f1c0a, 0x002f1c0a, 0x00301c0c, 0x00311b0b, 0x00321a0a, 0x0034190a, 0x00361b0c, 0x00371c0d, 0x00341a0c, 0x00351a0c, 0x00371b0d, 0x00391b0c, 0x003c1c08, 0x0047240a, 0x004c290c, 0x004e2909, 0x00552f0d, 0x005b320f, 0x00582c08, 0x005f320d, 0x005f300c, 0x0061320e, 0x00643510, 0x0062340e, 0x0061320c, 0x0065350f, 0x00693813, 0x006a3c12, 0x006d3d10, 0x00703c0f, 0x00733e0d, 0x0075400c, 0x0076400e, 0x0075400e, 0x00703c0a, 0x0069380c, 0x0061320b, 0x005b2c0c, 0x00512809, 0x004a2608, 0x0049260a, 0x0049250c, 0x0046220b, 0x00401f09, 0x00391c07, 0x00311a07, 0x002b1908, 0x00281809, 0x00251508, 0x00211307, 0x001f1205, 0x00201508, 0x0024170c, 0x0024170c, 0x00201509, 0x00201509, 0x0020140a, 0x0020140a, 0x001f150a, 0x0021170c, 0x0020160b, 0x0020150a, 0x001e150a, 0x001c1509, 0x001a150f, 0x00171410, 0x0010140d, 0x0008140c, 0x0006120c, 0x00081110, 0x00081110, 0x00091211, 0x00091310, 0x0008120c, 0x0008120c, 0x0008120b, 0x0008120b, 0x0009100c, 0x000a100c, 0x00090f0b, 0x00090f0b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00040c07, 0x00040c06, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00081110, 0x0008120f, 0x0008120f, 0x0008120d, 0x0008100c, 0x0008100c, 0x0008110c, 0x0007110d, 0x0006100c, 0x00050f0b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c05, 0x00040c04, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00050c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00030e07, 0x00020e07, 0x00020e07, 0x00020e07, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x00040e0b, 0x0007110d, 0x000a140f, 0x0009130d, 0x000f1710, 0x001f2720, 0x002b2f28, 0x0031332d, 0x0031302c, 0x002f302e, 0x00303434, 0x00303335, 0x002d3236, 0x002b3034, 0x00282f34, 0x00272b30, 0x00272c30, 0x00282c2e, 0x0025282b, 0x0026292c, 0x00242627, 0x00252320, 0x0024201a, 0x00271f18, 0x002c2118, 0x00392c20, 0x00413022, 0x00463020, 0x00432a18, 0x003b2210, 0x00371d0c, 0x00382310, 0x003d2a17, 0x0044301c, 0x0046301d, 0x00472f1d, 0x00452e1c, 0x00432b18, 0x00422b18, 0x00442c1a, 0x00442c1a, 0x00442c1c, 0x00422b1c, 0x0040281a, 0x00402917, 0x00402b16, 0x00402d17, 0x00402e18, 0x00402d16, 0x0043301a, 0x00442e19, 0x004a3320, 0x00442a18, 0x00442b17, 0x00442a16, 0x00402712, 0x003b240f, 0x0039220c, 0x0038200b, 0x003a1e0d, 0x00331809, 0x0031180b, 0x00311a0d, 0x00321a0e, 0x00341b10, 0x00351c0f, 0x00341c0c, 0x00331a09, 0x00321a08, 0x00311a08, 0x00301a08, 0x002f1908, 0x00301a08, 0x00321b09, 0x00341808, 0x00371b0b, 0x00371a0b, 0x00371a0b, 0x00361909, 0x00371a0b, 0x00391b0b, 0x003c1c0c, 0x00401f09, 0x004f2a10, 0x00573010, 0x00552c08, 0x005c310c, 0x0061340c, 0x00603009, 0x0067360f, 0x0068340d, 0x006c3810, 0x006e3b12, 0x006b3810, 0x006b370d, 0x006c380e, 0x006d390d, 0x00713e0f, 0x0074400e, 0x0079420e, 0x007e440f, 0x007e440e, 0x007e440f, 0x007d4410, 0x007a400d, 0x00713d0d, 0x0067350c, 0x0060300c, 0x00592e0c, 0x00502909, 0x004e2909, 0x004c2609, 0x00462108, 0x0044220b, 0x0041230e, 0x00371c0a, 0x002c1808, 0x00281808, 0x00251305, 0x00231205, 0x00231407, 0x00231608, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x0020160b, 0x0020160b, 0x001f1409, 0x001f1409, 0x00201409, 0x0020140a, 0x001f1409, 0x001d1409, 0x001c140e, 0x00181411, 0x00141610, 0x0009140c, 0x0005110c, 0x00091010, 0x00081110, 0x0008120f, 0x0009110f, 0x0008120c, 0x0008110b, 0x0007110a, 0x0008110a, 0x00090f0b, 0x00090f0b, 0x00080e0a, 0x00080e0a, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070c0b, 0x00070c0b, 0x00070c0b, 0x00070c0b, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081311, 0x00081311, 0x00091211, 0x0008120f, 0x0008120f, 0x0007110c, 0x0008100b, 0x0008100c, 0x0007100c, 0x0006100c, 0x00050f0c, 0x00050f0b, 0x0005100a, 0x00050f0a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c05, 0x00040c04, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00050c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00030e07, 0x00020e07, 0x00020e07, 0x00020e07, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x00040e0b, 0x0006100c, 0x0008120d, 0x0009140d, 0x00131c14, 0x001f261f, 0x00282b24, 0x0031312c, 0x00353530, 0x00313130, 0x002d3132, 0x00303335, 0x002e3337, 0x002d3238, 0x002c3338, 0x002e3338, 0x00292e33, 0x00292f30, 0x00292c2f, 0x00252829, 0x00242424, 0x00252220, 0x002a241f, 0x002c241e, 0x002b2018, 0x0034281c, 0x003d2d20, 0x00463020, 0x004c3120, 0x00492d1b, 0x00432917, 0x00442e1a, 0x0049331c, 0x004c341f, 0x00503420, 0x00523521, 0x00513420, 0x004d311d, 0x004b301c, 0x004b311c, 0x004b311c, 0x004c311f, 0x00482f1d, 0x00452c1b, 0x00442c18, 0x00452d17, 0x00442e16, 0x00432d15, 0x00412b14, 0x00422c16, 0x00402814, 0x00442b18, 0x00452d1a, 0x00422a18, 0x003f2915, 0x003d2713, 0x003a250f, 0x0038230c, 0x0037200c, 0x00371c0c, 0x00351b0c, 0x0031180b, 0x0030180c, 0x0031180c, 0x0034180c, 0x0035180c, 0x00371b0c, 0x00371c0b, 0x00371c0a, 0x00361c0a, 0x00341c09, 0x00331c08, 0x00341c08, 0x00381c0a, 0x00351806, 0x00381a09, 0x00371908, 0x00381a09, 0x003a1b0a, 0x003b1c0b, 0x00422210, 0x0043210e, 0x0048240d, 0x00563014, 0x005c3210, 0x0060340d, 0x00683811, 0x006c3c12, 0x006b370d, 0x00733c12, 0x00703a0f, 0x00733b10, 0x00743d11, 0x00723b0e, 0x00703a0c, 0x00773e10, 0x0077400f, 0x007b4411, 0x00804812, 0x00844a11, 0x00874a11, 0x00884a11, 0x00884912, 0x00854811, 0x0080430c, 0x00753f0e, 0x006b370a, 0x0063320b, 0x005d310e, 0x00562d0c, 0x00532c0c, 0x0050280b, 0x004f270d, 0x004d2810, 0x0044220c, 0x00391c0b, 0x00301807, 0x002a1607, 0x00281509, 0x0028170b, 0x00241406, 0x00201305, 0x001f1408, 0x001f1408, 0x00201609, 0x00201508, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201408, 0x001f1408, 0x001d140c, 0x00181411, 0x0014160f, 0x000a140c, 0x0006110c, 0x00091010, 0x00081110, 0x0008120f, 0x0008100d, 0x0008110b, 0x0007110a, 0x0007110a, 0x0007110a, 0x0006100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00080c0b, 0x00080c0b, 0x00080c0b, 0x00080c0b, 0x00070b07, 0x00060b06, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x00091310, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0a, 0x00040e09, 0x00050f0a, 0x00040e09, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d0a, 0x00070e0d, 0x00040c0a, 0x00040c0a, 0x00040c08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00070f08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060d08, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e0b, 0x00060d0b, 0x0008100c, 0x0008100d, 0x000b130d, 0x00182018, 0x001d231c, 0x00252923, 0x0033342e, 0x00343530, 0x00323432, 0x00303434, 0x002f3335, 0x002c3034, 0x002c3036, 0x002e3338, 0x0032373c, 0x0033363b, 0x00323538, 0x00303334, 0x002a2c2d, 0x00262626, 0x0024211f, 0x0028211e, 0x002e241f, 0x002c2118, 0x00322619, 0x003a2c1c, 0x00442f1e, 0x004a301d, 0x004e3320, 0x004f3520, 0x004e331e, 0x0050351d, 0x0053341c, 0x0054341c, 0x00593820, 0x00583821, 0x00593822, 0x00573720, 0x00573821, 0x00563820, 0x0054341e, 0x0050331c, 0x0050321b, 0x0050331c, 0x004c2f18, 0x00442a13, 0x00442b12, 0x00452c14, 0x00442913, 0x00412813, 0x003e2610, 0x003f2613, 0x00422a17, 0x003f2713, 0x003d2610, 0x003c2510, 0x003a2310, 0x0038210d, 0x00371f0d, 0x00341c0c, 0x00331c0c, 0x00301909, 0x00351c0c, 0x00371c0c, 0x003a200d, 0x003c220e, 0x003d220e, 0x003a1e0a, 0x003d220e, 0x00381c08, 0x003a1e0a, 0x00402410, 0x003d200c, 0x003a1a08, 0x003b1b08, 0x003c1c09, 0x003e1e0b, 0x00401e0b, 0x0044230f, 0x004b2711, 0x004f2a10, 0x00562f0f, 0x005d330f, 0x0064360f, 0x006b380f, 0x00713c10, 0x00753f12, 0x00763e0f, 0x00763e0d, 0x00753d0c, 0x00783f0f, 0x007b4110, 0x00783f0c, 0x007c4210, 0x007f4512, 0x00824814, 0x00874912, 0x00884910, 0x00874910, 0x008b4c13, 0x008b4c14, 0x008b4c14, 0x008a4a14, 0x00874810, 0x007c410c, 0x00703c08, 0x0067350a, 0x0060300c, 0x005c2c0c, 0x00582c0d, 0x0054280c, 0x00562d12, 0x004c240b, 0x0047220c, 0x003a1a07, 0x00321808, 0x002d1608, 0x002a160b, 0x00281609, 0x00271609, 0x00221407, 0x0022170a, 0x0023180b, 0x00221509, 0x00221509, 0x00221509, 0x00211408, 0x00241509, 0x00201207, 0x00211308, 0x00231409, 0x0023150a, 0x0023170a, 0x0020180c, 0x001a170f, 0x0015160f, 0x000f110c, 0x0009100b, 0x00091010, 0x0007130f, 0x0007110d, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x00040e09, 0x0005100a, 0x0007100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x000a1410, 0x0007110d, 0x0007110d, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x00050f0c, 0x0005100b, 0x00040f0a, 0x00040e09, 0x0006100b, 0x00040e09, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00080d08, 0x00080d0a, 0x00070e0c, 0x00040c0a, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00080f0b, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e0b, 0x00070e0c, 0x00070e0c, 0x0008100c, 0x000b130d, 0x00182018, 0x001f241d, 0x002b2c26, 0x0032332d, 0x0033342f, 0x00303230, 0x002f3233, 0x002c2f32, 0x00282c30, 0x00282d31, 0x002c3034, 0x002e3337, 0x00303338, 0x00303335, 0x002c3030, 0x002c2d2d, 0x002b2b29, 0x00282420, 0x0027201d, 0x002c211e, 0x002f241c, 0x0034281a, 0x00382819, 0x00422d1c, 0x00472e1b, 0x004b301e, 0x004e3420, 0x00523620, 0x00563820, 0x0059381d, 0x005e3b1f, 0x00633e22, 0x00664027, 0x00674228, 0x00603c22, 0x005f3b20, 0x005e3a20, 0x005d3a20, 0x005a381d, 0x0057351a, 0x00563419, 0x00533018, 0x004c2e14, 0x00492d12, 0x00482c12, 0x00492c15, 0x00472c14, 0x00442813, 0x00432812, 0x00412511, 0x003e240e, 0x003f250f, 0x003f2510, 0x003e2410, 0x003c220e, 0x003b210d, 0x003a200d, 0x00381e0c, 0x00351b0a, 0x00371c0a, 0x003b1f0b, 0x0040240d, 0x0041240d, 0x0040240c, 0x003e1f08, 0x0042230c, 0x0040200a, 0x0045240e, 0x00472610, 0x0042210c, 0x00401d08, 0x00401d08, 0x0044220c, 0x0046240e, 0x0048240e, 0x004c2710, 0x00512b10, 0x00562e0f, 0x00603511, 0x00683a10, 0x006c3a0e, 0x00713c10, 0x00784112, 0x007c4313, 0x00804412, 0x00804412, 0x007f440f, 0x00824712, 0x00844814, 0x00804510, 0x00834811, 0x00844a13, 0x00874b13, 0x008c4c14, 0x008b4c11, 0x008b4c11, 0x008e4e14, 0x008e4f16, 0x008e4f16, 0x008c4c14, 0x008a4b12, 0x0081450e, 0x0074400a, 0x006b380b, 0x0061310b, 0x005f2e0d, 0x005d3010, 0x005c3013, 0x00582c11, 0x0052280e, 0x0049230b, 0x00401f0b, 0x003a1d0e, 0x002e1508, 0x002c180c, 0x002b180c, 0x0027170a, 0x00221407, 0x00201408, 0x00201609, 0x00201609, 0x0022170a, 0x0023160c, 0x0022150b, 0x00201308, 0x001d1005, 0x001c1005, 0x00201208, 0x00201308, 0x001f1308, 0x001d150a, 0x001d1810, 0x00191710, 0x0011100c, 0x000c100c, 0x00091012, 0x0007130f, 0x0006110d, 0x0005100a, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x00050f0a, 0x00010c06, 0x00060f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x000a1410, 0x0008110e, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x0006100b, 0x00040e09, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00080d08, 0x00080d0a, 0x00070e0c, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00071007, 0x00071007, 0x00051008, 0x00051008, 0x00040f08, 0x00050f08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00050c06, 0x00040b04, 0x00040b04, 0x00030c04, 0x00030c04, 0x00040d07, 0x00040d07, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040e09, 0x0005100a, 0x00050f0c, 0x00070e0c, 0x00070e0c, 0x0008100c, 0x000b110c, 0x0019201a, 0x001f241e, 0x00242622, 0x002a2b27, 0x0030302c, 0x00313431, 0x00303434, 0x002d3034, 0x00292e32, 0x002d3236, 0x002d3236, 0x002b2e32, 0x00292c30, 0x002c2e30, 0x002c2e2f, 0x00282828, 0x002a2827, 0x002b2824, 0x002b2421, 0x002a201c, 0x0030241c, 0x003a2c20, 0x003c2c1c, 0x00412c1b, 0x0048301e, 0x004b3020, 0x004d3320, 0x00523420, 0x005d3c27, 0x00603c23, 0x00664023, 0x006a4224, 0x006c4426, 0x006d4528, 0x006b4425, 0x00684224, 0x00653f20, 0x00633c1e, 0x00603a19, 0x005d3717, 0x00593314, 0x00593214, 0x00563313, 0x00513010, 0x004d2c0f, 0x004c2b0f, 0x004c2b0f, 0x004a2b0f, 0x0048290e, 0x0045250e, 0x0042220a, 0x0046270f, 0x0040230b, 0x0041220c, 0x0042230c, 0x0042230d, 0x0041220d, 0x003f200c, 0x0040200c, 0x0044240e, 0x00482810, 0x0049270d, 0x0048270b, 0x004a280c, 0x0049260a, 0x00482409, 0x004b260b, 0x004f2a0f, 0x004e290d, 0x00492408, 0x00482106, 0x004a2409, 0x004d250b, 0x004c240b, 0x0050280d, 0x00582d12, 0x005e3113, 0x00633512, 0x00693910, 0x006d3b0f, 0x00744010, 0x007b4411, 0x007e4411, 0x00824710, 0x00854911, 0x0086480f, 0x00884a10, 0x00894c13, 0x008a4c13, 0x008b4d12, 0x008b4d13, 0x008a4d12, 0x008b4d12, 0x008d4e11, 0x008d4e11, 0x008e4f12, 0x00905116, 0x00905016, 0x008f5015, 0x008f4f14, 0x008d4f14, 0x00874c12, 0x007b440e, 0x006e3c0d, 0x0062320a, 0x0060300d, 0x00603210, 0x00603516, 0x00572c0f, 0x00542a0e, 0x00492309, 0x00482710, 0x00351806, 0x00341c0d, 0x002c180c, 0x0029180c, 0x0028180b, 0x00231508, 0x00201408, 0x001d1205, 0x001e1308, 0x001f1407, 0x001f1408, 0x001f1408, 0x001f1308, 0x001d1106, 0x001c1107, 0x001d1208, 0x001e1209, 0x001b1108, 0x00181005, 0x00171209, 0x0018160e, 0x0014130c, 0x000c100c, 0x00081010, 0x0006110d, 0x0006100c, 0x00070f0a, 0x0006100b, 0x0008120c, 0x0006100b, 0x0005100a, 0x0007110c, 0x0007110c, 0x00050e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x000a1410, 0x0008110e, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x0006100b, 0x00040e09, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00080d08, 0x00080d08, 0x00070f0a, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00080e08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040e09, 0x0005100a, 0x00050f0c, 0x00050f0c, 0x00070e0c, 0x0008100c, 0x000a100b, 0x00171d18, 0x001a201a, 0x00212520, 0x00292a26, 0x0030302c, 0x00313433, 0x00313437, 0x00313438, 0x002f3438, 0x002c3034, 0x00282d31, 0x0026282d, 0x00222529, 0x00242627, 0x00272928, 0x00272725, 0x00272623, 0x002e2926, 0x00362e2a, 0x002e221c, 0x002d2218, 0x003a2c20, 0x00423122, 0x00442f1d, 0x00493120, 0x004d3423, 0x00503623, 0x00543623, 0x0063422c, 0x006b462d, 0x0072492b, 0x00774c2d, 0x00764a2b, 0x00714726, 0x00704724, 0x006b4420, 0x0069421f, 0x00683e1b, 0x00663c18, 0x00643c17, 0x00623815, 0x00633715, 0x00603814, 0x005b3511, 0x0058310f, 0x00563010, 0x0054300f, 0x00532e10, 0x00522d0f, 0x004d280c, 0x00482509, 0x004c280d, 0x004b280d, 0x004a260e, 0x004a260e, 0x0049260e, 0x0047240b, 0x004c2810, 0x004c2810, 0x004d2a10, 0x00502b10, 0x00502c0e, 0x00532d0d, 0x00542d0d, 0x00542c0c, 0x00522a0b, 0x00562c0c, 0x00582d0f, 0x00572c0d, 0x00512708, 0x00532708, 0x0055290b, 0x0054290b, 0x0054290b, 0x005c2e10, 0x00623414, 0x00653613, 0x006a3912, 0x00703d10, 0x00794311, 0x00804813, 0x00824a12, 0x00844a10, 0x00884c10, 0x00894c0e, 0x00894c0d, 0x008c4c0f, 0x008d5010, 0x008c4e10, 0x008d4e10, 0x008d4e10, 0x008d4e10, 0x008d4e10, 0x00905013, 0x008f5011, 0x008f5011, 0x00905214, 0x00905114, 0x008f5014, 0x008f5013, 0x008e4f12, 0x00884e10, 0x007c470d, 0x006f3c0b, 0x0068380d, 0x0062320c, 0x0060320d, 0x005c330f, 0x0059300f, 0x00562c0d, 0x0050290c, 0x00422009, 0x0040240f, 0x00341b0a, 0x002b170c, 0x00281709, 0x00251508, 0x00221406, 0x00201308, 0x001c1104, 0x001b1005, 0x001b1104, 0x001a1105, 0x00191105, 0x00181105, 0x00181004, 0x00191006, 0x001c1208, 0x001c140a, 0x001e140b, 0x001c140a, 0x00181007, 0x0016120b, 0x0013130c, 0x000d100c, 0x00080f0e, 0x0005100c, 0x0006100b, 0x00080f0a, 0x0007100b, 0x0009130d, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00050d09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0007130f, 0x00081410, 0x0008130f, 0x0007110d, 0x0006100d, 0x0006100d, 0x0006100c, 0x0006100c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c09, 0x00040c08, 0x00040d08, 0x00040e07, 0x00040d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c07, 0x00060d06, 0x00050c06, 0x00050c05, 0x00050c05, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00060d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060f09, 0x00040e0a, 0x0005100a, 0x0005100b, 0x0008100c, 0x00080f09, 0x00161b16, 0x001c211c, 0x00212520, 0x002c2e2a, 0x0030322f, 0x00303232, 0x002e3134, 0x00303237, 0x002d3036, 0x002c2f34, 0x002b3034, 0x00272a2f, 0x0024282a, 0x00242525, 0x00222421, 0x0021221f, 0x0022201c, 0x0027221e, 0x00342c28, 0x00392e27, 0x0032261b, 0x0037291a, 0x00423120, 0x004a3424, 0x004a3422, 0x004c3422, 0x00503825, 0x005a3d2c, 0x00684834, 0x006f4932, 0x00754c2d, 0x007b4f2e, 0x007d4f2d, 0x007b4c29, 0x00784823, 0x0074441f, 0x0073441d, 0x0071421c, 0x006c3e18, 0x006a3c15, 0x00683b14, 0x00683a14, 0x00653a12, 0x00633910, 0x005f360c, 0x005e360d, 0x005c340f, 0x00593110, 0x00572f0d, 0x00542d0d, 0x00522c0c, 0x00512c0c, 0x00522e0e, 0x00512d0d, 0x00512d0d, 0x00512c0e, 0x00512a0c, 0x00542e10, 0x00542e0f, 0x00512b0b, 0x00542c0c, 0x00572f0e, 0x0059300d, 0x005b3210, 0x005c3110, 0x005c310f, 0x005d300f, 0x005e3110, 0x005f3210, 0x005e300f, 0x005c2e0d, 0x005d2f0c, 0x005e2f0c, 0x005e2f0b, 0x0062340d, 0x00673810, 0x006c3c10, 0x00713e11, 0x00774011, 0x007f4513, 0x00844910, 0x00874c10, 0x008c5013, 0x008e5014, 0x008e5010, 0x008c4d0e, 0x00904f0e, 0x00925010, 0x00935010, 0x00935010, 0x00925010, 0x00925010, 0x00925010, 0x00905311, 0x00905310, 0x00905110, 0x00905212, 0x00905111, 0x00905111, 0x00905010, 0x008f5010, 0x008a4c0e, 0x0081460c, 0x00743e09, 0x006d380c, 0x006a3911, 0x00633610, 0x005d310e, 0x005c3310, 0x005a300f, 0x00552b0d, 0x004c280d, 0x0040200b, 0x00341906, 0x002c1709, 0x002a170a, 0x00261408, 0x00211205, 0x001e1205, 0x001c1106, 0x001c1206, 0x001a1106, 0x001a1208, 0x001b1409, 0x001b1409, 0x001c140a, 0x001a1208, 0x00191208, 0x001c140a, 0x001e160d, 0x001f170e, 0x001c140c, 0x001c140c, 0x0018140d, 0x0011130d, 0x00080f0e, 0x0004100c, 0x0005100c, 0x00080e0a, 0x0006100b, 0x0006100b, 0x0007100a, 0x0007100a, 0x00050e09, 0x00050e09, 0x00040c08, 0x00040c08, 0x00040d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00060d08, 0x00060c08, 0x00050c08, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c08, 0x00070d09, 0x00060d08, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006130f, 0x0006130f, 0x0006110d, 0x0006110d, 0x0006110d, 0x0006110d, 0x0006100c, 0x0006100c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x0004100a, 0x0005100a, 0x000c120e, 0x000c130d, 0x00161c16, 0x00212520, 0x00282c28, 0x00303430, 0x002e322d, 0x00262828, 0x00232629, 0x00272a2e, 0x002c2f35, 0x0033353c, 0x0033383c, 0x002e3035, 0x002b2e30, 0x00292b2a, 0x00262825, 0x00242521, 0x00252420, 0x0026211d, 0x002a211d, 0x00352b21, 0x003c2e21, 0x00382819, 0x00433020, 0x004c3826, 0x004e3826, 0x004e3827, 0x00543e2d, 0x00624634, 0x006c4b38, 0x00704b34, 0x00795033, 0x007f5234, 0x00825231, 0x0080502c, 0x007d4a25, 0x007c4821, 0x007a4820, 0x0078461e, 0x0076441c, 0x0073421a, 0x00703f18, 0x006c3d13, 0x006c3d13, 0x006c3c11, 0x00683b10, 0x0066380d, 0x00643810, 0x00633610, 0x005f340f, 0x005c330e, 0x005c330e, 0x005b340e, 0x005b340e, 0x0058310d, 0x0058310d, 0x0059310d, 0x005a310d, 0x005c3410, 0x005e340f, 0x005c320c, 0x005f340f, 0x00623811, 0x00643813, 0x00643812, 0x00663812, 0x00673812, 0x00683812, 0x00683813, 0x00693914, 0x00683812, 0x00683711, 0x00683711, 0x00683810, 0x0068380e, 0x006c3c0e, 0x00704010, 0x00744110, 0x00794410, 0x00804710, 0x00874b14, 0x008b4e11, 0x008e5011, 0x008f5012, 0x00905113, 0x00905112, 0x00915010, 0x00935010, 0x00965111, 0x00975111, 0x00965211, 0x00955211, 0x00955211, 0x00945110, 0x00905110, 0x00905210, 0x00905111, 0x00905111, 0x00915110, 0x00915110, 0x0090500e, 0x0090500e, 0x008c4d10, 0x0086490d, 0x007c400d, 0x0070380b, 0x006b3810, 0x00663610, 0x00633410, 0x005d3310, 0x005a2f0d, 0x00562b0c, 0x004f280e, 0x0043200b, 0x00371906, 0x002d1808, 0x002b170a, 0x0029180c, 0x00251508, 0x00211408, 0x00201409, 0x001f150a, 0x001c140a, 0x001c140a, 0x001c140a, 0x001c1409, 0x001c1409, 0x00181207, 0x00181106, 0x00181108, 0x001b140c, 0x001c150c, 0x001d140c, 0x0020140e, 0x001c140e, 0x0014130c, 0x00080f0c, 0x0004100c, 0x00050f0c, 0x00080e0a, 0x0006100a, 0x0005100a, 0x0008100b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c08, 0x00080e08, 0x00070d07, 0x00070e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d02, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00071410, 0x00071410, 0x0007120e, 0x0006120e, 0x0006110d, 0x0005110c, 0x0006100c, 0x0006100c, 0x0005100b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x0004100a, 0x0005100a, 0x0009120d, 0x000c130e, 0x00181c18, 0x00262924, 0x002c302b, 0x002c2f2a, 0x002c2e2a, 0x002c2e2d, 0x002c2f32, 0x00313438, 0x0035383e, 0x0034373d, 0x0033363b, 0x00303136, 0x00282c2d, 0x002a2c2b, 0x002a2c2a, 0x002a2b28, 0x002c2a25, 0x002c2723, 0x002d2520, 0x002f2419, 0x003c2f21, 0x003e2e1f, 0x00443021, 0x004c3627, 0x004e3827, 0x004e3828, 0x00543c2c, 0x00614535, 0x006d4c3b, 0x0075503c, 0x0080573a, 0x00845739, 0x00835433, 0x0084512f, 0x00824e28, 0x00804c25, 0x007e4b23, 0x007c4a21, 0x007c4920, 0x007b481e, 0x0078451c, 0x00754218, 0x00734016, 0x00714014, 0x006e3c10, 0x006c3910, 0x006c3b10, 0x00693a0e, 0x0067370c, 0x0064370c, 0x0063370c, 0x0062350f, 0x0061360f, 0x0061370e, 0x0062370f, 0x0063360d, 0x0063370e, 0x00683810, 0x00673810, 0x0067380e, 0x00693c10, 0x006c3c12, 0x006c3c12, 0x006e3d12, 0x006f3d11, 0x00703d12, 0x00713e13, 0x00713e14, 0x00723e14, 0x00713d13, 0x00703c11, 0x00703c11, 0x00703c10, 0x00713c0e, 0x0075400f, 0x0079440f, 0x007d450e, 0x00834810, 0x00884a0f, 0x008c4c10, 0x008f4f10, 0x00925013, 0x00935113, 0x00935113, 0x00935112, 0x00945112, 0x00965011, 0x00985011, 0x00985111, 0x00975210, 0x00975211, 0x00965111, 0x00955211, 0x00935311, 0x00905210, 0x00905111, 0x00915111, 0x0090500e, 0x0090500e, 0x0090500f, 0x0090500e, 0x008d4e10, 0x00884a10, 0x007d420e, 0x00743c0e, 0x006c380d, 0x0068380f, 0x00683811, 0x0060330e, 0x00592c0a, 0x00562b0c, 0x004f280e, 0x0044200c, 0x00391c09, 0x00301b0b, 0x00291508, 0x0028170b, 0x00271709, 0x0024150a, 0x0021140a, 0x0020160c, 0x001e170d, 0x001d150c, 0x001d150c, 0x001b1409, 0x00181107, 0x00181208, 0x00141006, 0x00130e04, 0x00171108, 0x0018130a, 0x001b130c, 0x001f140e, 0x001c150f, 0x0015140d, 0x000c110d, 0x0007110c, 0x00050f0c, 0x00080e0b, 0x0006100a, 0x0005100a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050c08, 0x00050c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d06, 0x00050c05, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060c05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c08, 0x00080e08, 0x00070e05, 0x00070e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d02, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x0007130f, 0x0007130f, 0x0006110d, 0x0005110b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00030f09, 0x00050e09, 0x00070d09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x0004100a, 0x0005100a, 0x0009120c, 0x000e1610, 0x001e241e, 0x00282b27, 0x002a2c28, 0x002d302c, 0x002d302c, 0x002c2e2d, 0x002a2d30, 0x002a2d32, 0x002d3037, 0x002c3036, 0x002d3034, 0x002e2f34, 0x002d2f32, 0x002b2c2d, 0x002a2c2b, 0x002b2c28, 0x002c2b26, 0x002d2824, 0x00302622, 0x0035291f, 0x003b2c20, 0x00413021, 0x00493526, 0x004a3426, 0x004c3426, 0x00503829, 0x005c4335, 0x006b4e40, 0x00755445, 0x007b5644, 0x0080563a, 0x00835538, 0x00855434, 0x00875431, 0x0086512c, 0x00845028, 0x00824e25, 0x00804c24, 0x007f4b22, 0x007d481f, 0x007c481d, 0x007c471c, 0x007c4519, 0x007a4317, 0x00784013, 0x00753e10, 0x00743f10, 0x00723c0e, 0x006e3b0b, 0x006d3c0b, 0x006c3b0c, 0x006b3a0f, 0x006b3a10, 0x006b3a0e, 0x006c3c0f, 0x006c3c0e, 0x006d3b0e, 0x00703e10, 0x00713e0f, 0x00734010, 0x00764311, 0x00774413, 0x00784313, 0x00784312, 0x007a4311, 0x007a4412, 0x007c4312, 0x007c4313, 0x007c4313, 0x007b4211, 0x007c4010, 0x007c4010, 0x007c410f, 0x007c420d, 0x0080460f, 0x0082480f, 0x00874b11, 0x008c4d14, 0x00914f14, 0x00945013, 0x00965114, 0x00965415, 0x00975415, 0x00975414, 0x00985414, 0x00995312, 0x009b5212, 0x009c5212, 0x009c5211, 0x00985411, 0x00985412, 0x00985414, 0x00985414, 0x00945412, 0x00915110, 0x00915111, 0x00915111, 0x00945110, 0x00945211, 0x00915210, 0x00915110, 0x008d4e10, 0x00884910, 0x007d420e, 0x00753c0f, 0x006e380d, 0x006c380e, 0x006b3810, 0x0064350f, 0x005e300d, 0x00582c0e, 0x004c240b, 0x0046210c, 0x003a1d0a, 0x002e1808, 0x00281406, 0x00261408, 0x00231407, 0x00201307, 0x001d1106, 0x001a1007, 0x00181008, 0x00181006, 0x00171005, 0x001b1409, 0x001b140b, 0x001c160d, 0x0018140b, 0x00151208, 0x00120f06, 0x00130e06, 0x001a110b, 0x001f140e, 0x001d150f, 0x0016140e, 0x0010130f, 0x0009110d, 0x00070f0c, 0x00080e0c, 0x0006100a, 0x0005100a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d06, 0x00050d05, 0x00060d03, 0x00060d03, 0x00060d03, 0x00060d04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c06, 0x00080f06, 0x00070e04, 0x00070e04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d02, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x0008130f, 0x0008120e, 0x0006110c, 0x0006110b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051009, 0x00040f08, 0x00040d08, 0x00030d08, 0x00040d08, 0x00040d08, 0x00040e08, 0x00040e08, 0x00050d08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050c08, 0x00050c08, 0x00050d07, 0x00050d06, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00050c07, 0x00050c06, 0x00050c06, 0x00040c06, 0x00040c06, 0x00050c07, 0x00050c07, 0x00050c06, 0x00040c06, 0x00050c06, 0x00050c07, 0x00050c07, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040d09, 0x00040d09, 0x00040d09, 0x00040d09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040f09, 0x00050e09, 0x00060e09, 0x00080c09, 0x00060e09, 0x00050e09, 0x00050e08, 0x00040e08, 0x00041009, 0x00051009, 0x000b140d, 0x00161e18, 0x00242a24, 0x00252823, 0x001c1f1a, 0x001c1e19, 0x001a1c18, 0x001c1f1e, 0x00202325, 0x00292c30, 0x00303439, 0x00313439, 0x00313438, 0x002f3034, 0x002b2c30, 0x002a2c2d, 0x00282b29, 0x00262624, 0x00282722, 0x002d2824, 0x00312721, 0x0033271d, 0x003a2c1f, 0x00443323, 0x004c3728, 0x0050382b, 0x00543c2e, 0x00563f30, 0x005c4436, 0x006c5042, 0x00775748, 0x007c5847, 0x00825a40, 0x00865a3e, 0x00885838, 0x008a5734, 0x0088542e, 0x0086512b, 0x00855028, 0x00854f26, 0x00834c23, 0x00814b20, 0x0080491f, 0x0080481c, 0x0081481a, 0x00834918, 0x00834a18, 0x007e4612, 0x007c4410, 0x007a420f, 0x0076400c, 0x0074400c, 0x0074400b, 0x00723d0d, 0x00723f0c, 0x00723f0c, 0x0073400c, 0x00743f0c, 0x00743f0b, 0x0078420d, 0x0078420c, 0x007c4610, 0x007e4811, 0x00804811, 0x00804911, 0x00814810, 0x00814810, 0x00834810, 0x00844911, 0x00844911, 0x00844810, 0x00834810, 0x0083460f, 0x00844610, 0x0084470e, 0x0084480f, 0x0085490c, 0x00874a0d, 0x008e4d12, 0x00925014, 0x00975314, 0x00995414, 0x00995412, 0x00995411, 0x009a5412, 0x009a5412, 0x009a5411, 0x009b5411, 0x009c5310, 0x009c5210, 0x009c5310, 0x00995410, 0x009a5411, 0x009b5414, 0x00995515, 0x00945212, 0x0091500f, 0x00915111, 0x00935111, 0x00955312, 0x00965413, 0x00955413, 0x00935311, 0x008e5011, 0x00874b11, 0x007d420e, 0x00773c0e, 0x00703a0d, 0x006e380e, 0x006c380f, 0x0067360f, 0x0061330f, 0x00592e0e, 0x004f280c, 0x0046220b, 0x003c1c09, 0x002c1705, 0x002a1707, 0x00241407, 0x00201204, 0x001d1205, 0x001b1005, 0x00160c04, 0x00140c04, 0x00130c02, 0x00120b01, 0x00130c03, 0x00140d04, 0x00130f06, 0x00121108, 0x00141309, 0x0017150d, 0x0019140d, 0x001c110c, 0x00201410, 0x001f1711, 0x0018150f, 0x0010130e, 0x0009110c, 0x0008100c, 0x00080d0c, 0x00050f09, 0x00050f09, 0x00060e09, 0x00060e08, 0x00050d09, 0x00050d09, 0x00060d08, 0x00060d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c06, 0x00070e07, 0x00070d05, 0x00070d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c04, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x0008120f, 0x0008120d, 0x0007110c, 0x0007110c, 0x0006100b, 0x0005100a, 0x00051009, 0x00040f08, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c09, 0x00040c09, 0x00060e0b, 0x00060e0a, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050c07, 0x00060d07, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00041008, 0x0008110a, 0x00121b14, 0x00222822, 0x00191c18, 0x000b0d08, 0x0010130e, 0x00161814, 0x00222424, 0x00282c2e, 0x00272a2e, 0x002b2e32, 0x002d3034, 0x002e3035, 0x002d2e33, 0x002c2e31, 0x002a2c2c, 0x00272828, 0x00242423, 0x00282724, 0x002f2823, 0x00312721, 0x0034281e, 0x003d2d21, 0x00443022, 0x004d3628, 0x00543c2e, 0x00583f31, 0x005a4134, 0x005e4738, 0x00684d3f, 0x00735344, 0x007a5546, 0x00855c48, 0x00885d42, 0x0089593a, 0x008a5734, 0x0088532e, 0x0087512b, 0x00885129, 0x00885027, 0x00875026, 0x00864f24, 0x00885023, 0x00884e20, 0x00864c1b, 0x00864a16, 0x00864c15, 0x00884c15, 0x00834a12, 0x00814810, 0x007e450f, 0x007e440f, 0x007d440e, 0x007c430d, 0x007c430c, 0x007e450d, 0x007e450c, 0x007e440d, 0x007f440c, 0x0082480e, 0x0082480f, 0x00844a12, 0x00874a12, 0x00884c10, 0x00884c10, 0x00884d10, 0x008a4c10, 0x008a4c12, 0x00894b11, 0x00894b10, 0x00884b0f, 0x00884b0f, 0x008a4c10, 0x008a4c12, 0x008a4c12, 0x008b4d12, 0x008d5012, 0x008f5111, 0x00945010, 0x00955210, 0x009a5612, 0x009c5711, 0x009f5612, 0x00a05713, 0x009e5511, 0x009e5511, 0x009e5512, 0x009e5513, 0x009e5512, 0x009d5411, 0x009d5510, 0x009c5712, 0x009c5714, 0x00995412, 0x00995414, 0x00955213, 0x00915010, 0x00915010, 0x00945010, 0x00945211, 0x00965413, 0x00965413, 0x00935311, 0x008e5011, 0x00884c13, 0x007e430e, 0x00773d0e, 0x00743c0e, 0x006f390c, 0x006c380d, 0x006b3810, 0x0063350f, 0x005b300d, 0x0050290b, 0x0048240a, 0x003c1d07, 0x00301907, 0x002a1707, 0x00251406, 0x00201305, 0x001c1304, 0x001c1307, 0x001a1308, 0x001a1209, 0x00191209, 0x00181109, 0x00171008, 0x00140f06, 0x00100d04, 0x00100e05, 0x00121008, 0x00141109, 0x0017110a, 0x001c100c, 0x00201410, 0x00201812, 0x0018150f, 0x0010120c, 0x0008110a, 0x0008100b, 0x00070c0b, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00081410, 0x00081410, 0x0008120f, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100a, 0x0005100a, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040c04, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c08, 0x00040c08, 0x0008100b, 0x0008100b, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0004100a, 0x0005100b, 0x000c160f, 0x001e241f, 0x001c1f1a, 0x00171914, 0x001c1e1a, 0x002c2e2a, 0x00303330, 0x002f3333, 0x002b2d31, 0x002b2e32, 0x002c3034, 0x002d3034, 0x002e2f34, 0x002e2f32, 0x002c2d2f, 0x00292b2c, 0x00292a28, 0x002f2d2a, 0x002a241f, 0x00302520, 0x00372a20, 0x003f3023, 0x00453224, 0x004d3729, 0x00543c2e, 0x00583e31, 0x00583f32, 0x005c4436, 0x006b5042, 0x0078574b, 0x00805c4e, 0x00885f4b, 0x00895c44, 0x008a593a, 0x008a5634, 0x0089532c, 0x00875128, 0x008a5328, 0x008a5328, 0x00895227, 0x00885224, 0x008a5223, 0x00895221, 0x008b501c, 0x008c4f18, 0x008b4f17, 0x008c5015, 0x008c5015, 0x008a4e14, 0x00884c11, 0x00874b10, 0x00874a10, 0x00854a0f, 0x00854a0f, 0x00884c12, 0x00884c12, 0x008a4c10, 0x008a4c10, 0x008c4e13, 0x008c4f14, 0x008f4f15, 0x00905017, 0x00905014, 0x00905011, 0x00905011, 0x00905112, 0x00905113, 0x00905113, 0x00905213, 0x00905113, 0x00905112, 0x00905013, 0x00905015, 0x00905016, 0x00905114, 0x00905212, 0x00925311, 0x00965110, 0x00985310, 0x009d5811, 0x009f5810, 0x00a15812, 0x00a25914, 0x00a05813, 0x00a05713, 0x00a05713, 0x00a05713, 0x009f5612, 0x009f5612, 0x009e5611, 0x009d5712, 0x009c5713, 0x00995412, 0x00985313, 0x00965211, 0x00935010, 0x00925010, 0x0094500f, 0x00945010, 0x00955412, 0x00955412, 0x00935211, 0x008e5013, 0x00884d14, 0x00804410, 0x00783e0e, 0x00743c0d, 0x00703b0c, 0x00703c0f, 0x006e3c11, 0x0064370d, 0x005b300b, 0x00502a09, 0x00482509, 0x003d1d06, 0x00331a08, 0x00291304, 0x00271407, 0x00221306, 0x001e1405, 0x001e1308, 0x001d1108, 0x001c110a, 0x001c120b, 0x001c130c, 0x001d140c, 0x001b130a, 0x00191209, 0x00181109, 0x00140d06, 0x00140d06, 0x00170e08, 0x001a1009, 0x001f140e, 0x001e1710, 0x0018140c, 0x0011110c, 0x0008100a, 0x0007110c, 0x00080f0b, 0x00081009, 0x00081009, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x0008120e, 0x0007110c, 0x0006100b, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040c03, 0x00040c06, 0x00040d07, 0x00050e08, 0x00050d08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00050f0c, 0x0004100c, 0x00040f0c, 0x00050f0a, 0x00151a16, 0x00242520, 0x00252621, 0x00282824, 0x002d2f2b, 0x00303230, 0x00303334, 0x00303436, 0x00313438, 0x00323539, 0x00323539, 0x00313236, 0x002e2f32, 0x002e2f32, 0x002b2c2f, 0x002a2a2a, 0x00282623, 0x002c231f, 0x00302520, 0x00372821, 0x003f3024, 0x00453224, 0x004d382b, 0x00584034, 0x005e4238, 0x005f4438, 0x00684f44, 0x0075584c, 0x007f6054, 0x00815d52, 0x00885f4b, 0x008a5d44, 0x008c5b3c, 0x008a5533, 0x008a542d, 0x00895429, 0x00895325, 0x00895324, 0x00895324, 0x008a5322, 0x008a5320, 0x008a5320, 0x008c511b, 0x008f5018, 0x00915318, 0x00905116, 0x00905113, 0x00905113, 0x008f5011, 0x00905010, 0x00915013, 0x00915013, 0x00915012, 0x00905011, 0x00904f10, 0x00915011, 0x00914f11, 0x00935013, 0x00945214, 0x00945116, 0x00975215, 0x00965414, 0x00965413, 0x00965411, 0x00965411, 0x00945410, 0x0092520f, 0x00925210, 0x00935210, 0x00935211, 0x00935313, 0x00935214, 0x00935214, 0x00935314, 0x00985817, 0x009b5a16, 0x009e5814, 0x009f5812, 0x00a05910, 0x00a1590f, 0x00a05810, 0x00a05811, 0x00a15812, 0x00a15812, 0x00a15813, 0x00a05713, 0x009f5712, 0x009f5612, 0x009d5511, 0x009c5611, 0x009c5513, 0x009a5311, 0x0096500f, 0x0094500c, 0x0094500c, 0x0094500e, 0x0094510f, 0x0096500f, 0x00955210, 0x00955312, 0x00925112, 0x008e5013, 0x00884c14, 0x00844814, 0x007b4110, 0x00763e0e, 0x00713d0c, 0x00703c0d, 0x006e3c10, 0x00673a0e, 0x005d340b, 0x00522b08, 0x004a2507, 0x00401d05, 0x00381c0c, 0x002f1508, 0x002c180b, 0x0029190c, 0x0026190c, 0x0026190f, 0x0023160d, 0x0023150f, 0x0020150e, 0x0020150e, 0x0022160f, 0x0022160f, 0x0020150c, 0x0020140c, 0x001e1309, 0x001e1309, 0x001e140a, 0x001f140b, 0x0020150c, 0x001f160c, 0x0019140b, 0x0013110c, 0x00080f08, 0x00051008, 0x00070f0a, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d03, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x00091310, 0x0008120e, 0x0007110c, 0x0006100b, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c05, 0x00040c04, 0x00040c06, 0x00040d07, 0x00050e08, 0x00050d07, 0x00040c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050f0c, 0x00050f0c, 0x0004100c, 0x0005100c, 0x0005100d, 0x0007110e, 0x00101611, 0x001c1d18, 0x00272824, 0x002c2c28, 0x002c2c2b, 0x00303231, 0x00303335, 0x00303337, 0x00303338, 0x00303338, 0x00303438, 0x00323438, 0x002f3034, 0x002c2e31, 0x00282a2b, 0x00282827, 0x002e2c29, 0x002c2420, 0x00302420, 0x003a2b24, 0x00423228, 0x00453427, 0x00503c2f, 0x005c4438, 0x005c4238, 0x005f4439, 0x006c5246, 0x0074584c, 0x007d5d53, 0x00836054, 0x008c6450, 0x008b5e47, 0x008c5a3b, 0x008a5731, 0x008b552c, 0x008b5629, 0x008c5526, 0x008b5524, 0x008b5322, 0x008c5220, 0x008b521e, 0x008b521c, 0x008c5018, 0x00925318, 0x0097581c, 0x0097561a, 0x00945415, 0x00945211, 0x00945110, 0x00945211, 0x00965413, 0x00965413, 0x00965413, 0x00945110, 0x00945110, 0x00955211, 0x00955211, 0x00955211, 0x00955211, 0x00975013, 0x00985212, 0x00985414, 0x00995614, 0x00995611, 0x00995610, 0x00995610, 0x00995610, 0x00985512, 0x00985412, 0x00985412, 0x00985413, 0x00985414, 0x00985414, 0x00995515, 0x009a5713, 0x009c5813, 0x009f5812, 0x009f5811, 0x00a0580e, 0x00a35a0f, 0x00a25a10, 0x00a25a11, 0x00a15810, 0x00a15810, 0x00a15811, 0x00a15812, 0x009f5810, 0x009f5710, 0x009d5610, 0x009c5611, 0x009c5613, 0x00995311, 0x0096500f, 0x0095500b, 0x0094510c, 0x0094510d, 0x0094510d, 0x00975110, 0x00975310, 0x00955312, 0x00925212, 0x008e4f13, 0x00884c13, 0x00834811, 0x007f4514, 0x007b4310, 0x0076400f, 0x00723e0f, 0x006e3c0e, 0x00693b0d, 0x0060360c, 0x00542d08, 0x004c2605, 0x00401f04, 0x003a1d0b, 0x00311809, 0x002b1408, 0x00281609, 0x0024160a, 0x0023160b, 0x00201409, 0x0020120a, 0x001d1209, 0x001c1108, 0x001c1108, 0x001d1108, 0x001e1107, 0x00201409, 0x0022150b, 0x00201409, 0x001e1409, 0x001e1308, 0x001d1308, 0x001c1309, 0x001a140c, 0x0013120b, 0x000a0f08, 0x00050f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00091310, 0x0008120e, 0x0007110d, 0x0007110c, 0x0005100a, 0x00040f08, 0x00051008, 0x00051008, 0x00060f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050e06, 0x00060e06, 0x00050e06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x0005100a, 0x0005110b, 0x0005100c, 0x0004110c, 0x0006100e, 0x00091110, 0x000d130e, 0x0020221e, 0x002f302c, 0x00343433, 0x00343434, 0x002f3132, 0x002b2e30, 0x002b2e32, 0x002d3037, 0x00303238, 0x0032343b, 0x0034353a, 0x00323437, 0x002e3033, 0x002c2d30, 0x002b2b2c, 0x002a2827, 0x002c2320, 0x002e211f, 0x00372822, 0x00423229, 0x004c3a2e, 0x00544033, 0x005b4438, 0x005d4439, 0x0062483c, 0x00684d43, 0x0074574d, 0x0085645c, 0x0089645b, 0x008c6453, 0x008c624a, 0x008c5c3c, 0x008c5934, 0x008d582e, 0x008d572a, 0x008c5625, 0x008d5423, 0x00915523, 0x008f531f, 0x008e521c, 0x008f531a, 0x008f5218, 0x00905418, 0x0096561a, 0x0098561a, 0x00985616, 0x00995514, 0x00985413, 0x00975312, 0x00975312, 0x00985414, 0x00985414, 0x00985414, 0x00985414, 0x00965411, 0x00965510, 0x0098540e, 0x0098540e, 0x0098540e, 0x00985410, 0x009a5512, 0x009c5713, 0x009c5813, 0x009c5812, 0x009c5711, 0x009c5711, 0x009c5711, 0x009c5711, 0x009c5711, 0x009c5812, 0x009c5812, 0x009c5812, 0x009c5812, 0x00a05914, 0x00a35c17, 0x00a25c13, 0x00a35c14, 0x00a45a10, 0x00a45a10, 0x00a35b10, 0x00a15c10, 0x00a05b10, 0x00a05b10, 0x00a0580f, 0x009f570f, 0x009f5810, 0x009c5510, 0x009a530e, 0x009a530f, 0x009a5310, 0x0098530f, 0x0096500d, 0x0096510c, 0x0096500d, 0x0097520e, 0x0097520e, 0x0098530f, 0x00975311, 0x00955314, 0x00925212, 0x008c4d10, 0x00884c13, 0x00844912, 0x00804711, 0x007f4713, 0x007c4514, 0x00784413, 0x00713d10, 0x0069390c, 0x0064340c, 0x005a2d08, 0x004d2404, 0x00482408, 0x00381c07, 0x002f1704, 0x002a1406, 0x00241307, 0x00231509, 0x00211408, 0x00201409, 0x00201408, 0x001d1205, 0x001b1004, 0x001c1205, 0x001d1307, 0x001e1308, 0x001e1407, 0x001f1408, 0x001e1408, 0x001e1508, 0x001f150b, 0x0020160c, 0x00231710, 0x00201713, 0x0014130d, 0x000b0f08, 0x00071007, 0x00051008, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c07, 0x00080e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0008120e, 0x0007110d, 0x0007110d, 0x0007110c, 0x0005100a, 0x00040f08, 0x00051008, 0x00051008, 0x00060f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050e06, 0x00060e06, 0x00050e06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040d08, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x0005100a, 0x0005110b, 0x0004110b, 0x0004130c, 0x0006100b, 0x000a100d, 0x0010140f, 0x00272824, 0x00353633, 0x002e2e2e, 0x00272728, 0x002a2b2e, 0x002f3234, 0x00303237, 0x002c2f35, 0x00282a30, 0x0024272c, 0x00242529, 0x0028292c, 0x002a2c2f, 0x002e2f31, 0x002c2c2c, 0x002b2926, 0x002e2722, 0x00312522, 0x00372823, 0x00423229, 0x004c3a2f, 0x00544034, 0x005c4439, 0x005d453a, 0x0063493d, 0x006f5449, 0x007f6159, 0x008a6a62, 0x008a665d, 0x008e6656, 0x008f644d, 0x008f5f40, 0x00905c38, 0x00905c30, 0x00905a2c, 0x008f5828, 0x00905624, 0x00925523, 0x00915420, 0x0090541d, 0x0091551b, 0x0090541a, 0x0093561c, 0x0097571c, 0x00985819, 0x009a5718, 0x009b5815, 0x009a5714, 0x00995614, 0x00995614, 0x009a5615, 0x00995515, 0x009a5515, 0x009a5616, 0x00995614, 0x00995613, 0x00995610, 0x009b5711, 0x009c5711, 0x009c5613, 0x009c5714, 0x009c5814, 0x009c5814, 0x009c5812, 0x009c5712, 0x009c5711, 0x009c5711, 0x009c5711, 0x009c5711, 0x009d5813, 0x009d5813, 0x009d5813, 0x009c5812, 0x00a15a15, 0x00a35c17, 0x00a25c14, 0x00a35c14, 0x00a45a11, 0x00a45a10, 0x00a45c13, 0x00a45d13, 0x00a05b10, 0x009f580e, 0x009f570e, 0x009d540f, 0x009c5510, 0x009b540f, 0x009b5410, 0x009b540f, 0x00995310, 0x00985410, 0x0096500d, 0x0097520e, 0x0097520e, 0x0097520e, 0x0096500d, 0x0096500d, 0x0094500f, 0x00935011, 0x00904f0f, 0x008c4d10, 0x00884d13, 0x00844912, 0x00804711, 0x007e4510, 0x007b4310, 0x0075400e, 0x00713d0e, 0x006c3b0c, 0x0064340b, 0x005b2d08, 0x00502506, 0x00472207, 0x00371a04, 0x00301603, 0x002b1306, 0x00251207, 0x00231308, 0x00231308, 0x00231208, 0x00221208, 0x00201207, 0x00241509, 0x0025170c, 0x00221509, 0x00211509, 0x00201609, 0x0022170a, 0x0022170a, 0x0020180b, 0x0020170c, 0x0022160e, 0x00231710, 0x00201712, 0x0014130d, 0x000c0f08, 0x00071007, 0x00051007, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c07, 0x00080e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0008120e, 0x0007110d, 0x0007110d, 0x0007110c, 0x0005100a, 0x00040f08, 0x00070f08, 0x00070f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040f06, 0x00040f08, 0x00020e08, 0x0004100a, 0x00041009, 0x00030e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00041008, 0x00051109, 0x00051109, 0x00071009, 0x000a110b, 0x00141711, 0x002c2f29, 0x00313330, 0x002b2b2c, 0x002c2c2e, 0x002f3033, 0x00303335, 0x00303336, 0x002c3034, 0x002c2f33, 0x00282c30, 0x0027282a, 0x00282a2c, 0x002d2f30, 0x002e3031, 0x002b2b2b, 0x002c2926, 0x00302824, 0x00342822, 0x00392a24, 0x0043332b, 0x004c3a30, 0x00554335, 0x00584236, 0x0060473c, 0x00684e44, 0x00745b51, 0x0084665e, 0x00886862, 0x0088655f, 0x008d6457, 0x00906451, 0x00916045, 0x00905c3b, 0x00905a30, 0x008f582b, 0x008f5827, 0x00905624, 0x00915422, 0x00905420, 0x0091541f, 0x0092561d, 0x0092561c, 0x0095581e, 0x0098581c, 0x0099581a, 0x009e5a18, 0x009e5914, 0x009e5814, 0x009c5613, 0x009c5714, 0x009c5614, 0x009a5412, 0x009a5513, 0x009b5514, 0x009c5516, 0x009c5614, 0x009c5612, 0x009c5610, 0x009c5814, 0x009b5514, 0x00995412, 0x009c5715, 0x009c5814, 0x009c5814, 0x009c5814, 0x009c5814, 0x009d5814, 0x009d5814, 0x009e5915, 0x009d5814, 0x009e5915, 0x009d5814, 0x009f5a16, 0x00a05917, 0x00a15b17, 0x00a35c14, 0x00a35c15, 0x00a45a12, 0x00a45a12, 0x00a25a10, 0x00a45c12, 0x00a45c12, 0x00a35b10, 0x00a05810, 0x009f5712, 0x009e5613, 0x009c5412, 0x009b5411, 0x009c5512, 0x009c5512, 0x00995410, 0x009a5411, 0x009a5411, 0x009a5411, 0x00985410, 0x00985410, 0x00995412, 0x00965210, 0x00945112, 0x008d4d10, 0x008a4c10, 0x00874b11, 0x00834811, 0x00814611, 0x00804712, 0x007c430f, 0x00753f0d, 0x00713c0c, 0x006c3b0d, 0x0066380c, 0x005c300b, 0x00502607, 0x00472005, 0x003b1905, 0x00331604, 0x0030160a, 0x002d170c, 0x0029170d, 0x00261409, 0x0027140a, 0x0028150b, 0x0027170c, 0x0028180c, 0x0025140c, 0x0024150c, 0x0024150c, 0x0023160c, 0x0023160a, 0x0022160a, 0x00201508, 0x001e1408, 0x00190e04, 0x001c1008, 0x001d140e, 0x0015130c, 0x000d1009, 0x00080f07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c06, 0x00060c07, 0x00080e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0008120e, 0x0007110d, 0x0007110d, 0x0007110c, 0x0005100a, 0x00040f08, 0x00070f08, 0x00070f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040e06, 0x00040e06, 0x00040e06, 0x00040f07, 0x00040f08, 0x00020f09, 0x00020f08, 0x00020e08, 0x00020e08, 0x00020e08, 0x00020e08, 0x00030f09, 0x00030f09, 0x00040f08, 0x00040f08, 0x00051008, 0x00041008, 0x00041007, 0x00041007, 0x00071008, 0x000e150d, 0x001a1f18, 0x00222520, 0x00252724, 0x002e2e2e, 0x002d2d30, 0x002a2c2f, 0x00282c2e, 0x002b2e30, 0x00282b30, 0x00282d31, 0x00292d31, 0x0028292c, 0x0028292b, 0x002c2d2f, 0x002d2d30, 0x002b2b2a, 0x002d2a26, 0x00312823, 0x00342822, 0x003c2c28, 0x0047372e, 0x00503f34, 0x005a483b, 0x005a4438, 0x0060483d, 0x006c5248, 0x00755b51, 0x007f6159, 0x00866761, 0x008b6861, 0x008f675b, 0x00936756, 0x00906046, 0x008e5b3b, 0x008d5830, 0x008d5629, 0x008e5524, 0x008f5523, 0x00925523, 0x0090541f, 0x0091541f, 0x0092561d, 0x0092561c, 0x0095581e, 0x0098581c, 0x009b591b, 0x009e5a18, 0x009e5913, 0x009e5914, 0x009e5914, 0x009e5914, 0x009c5711, 0x009b5610, 0x009b5512, 0x009c5714, 0x009d5515, 0x009e5715, 0x009e5714, 0x009c5611, 0x009e5713, 0x009b5512, 0x00995410, 0x009c5714, 0x009c5813, 0x009c5812, 0x009c5812, 0x009c5813, 0x009e5915, 0x00a15c18, 0x00a05b18, 0x009e5915, 0x009f5a16, 0x009f5a14, 0x009e5914, 0x009f5813, 0x009f5813, 0x00a05911, 0x00a05a13, 0x00a35a11, 0x00a45a12, 0x00a0590f, 0x00a25a10, 0x00a45c12, 0x00a25a10, 0x009f5710, 0x009e5510, 0x009c5412, 0x009c5411, 0x009b5410, 0x009c5412, 0x009b5412, 0x00995410, 0x009a5511, 0x009c5713, 0x009c5713, 0x009a5511, 0x009a5411, 0x009b5514, 0x00985412, 0x00935112, 0x008e4e10, 0x0087490d, 0x0085490f, 0x00834810, 0x0080460f, 0x00804610, 0x007c4510, 0x00753f0d, 0x00713c0c, 0x006c3a0c, 0x00643409, 0x00592c08, 0x004f2506, 0x004a2409, 0x003e1d09, 0x00361907, 0x002f1509, 0x002c160c, 0x0029160c, 0x00261409, 0x002a180d, 0x0029180d, 0x0028170c, 0x0029170d, 0x0028170e, 0x0028180f, 0x00271910, 0x0022150b, 0x00201308, 0x001f1407, 0x001e1306, 0x001e1408, 0x001b0f04, 0x001b0f06, 0x001a100b, 0x00121009, 0x000a0c06, 0x00080f07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c07, 0x00080e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0007110c, 0x0007110c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00071009, 0x000e150f, 0x00181f17, 0x001f241c, 0x001f211e, 0x00272928, 0x00262828, 0x00242527, 0x00242428, 0x00242729, 0x002a2f33, 0x00282d30, 0x00262c2f, 0x002c3031, 0x002e302f, 0x00302f31, 0x002e2c2c, 0x002d2c2a, 0x002d2a26, 0x002d2820, 0x00342824, 0x003c2d28, 0x00493830, 0x00564438, 0x00574438, 0x00594238, 0x0061493f, 0x006c544b, 0x00735851, 0x007c5e58, 0x00856560, 0x0088655f, 0x008e675c, 0x008d6353, 0x008d5d45, 0x008c593a, 0x008d5730, 0x008d5528, 0x00905525, 0x008f5422, 0x00915321, 0x00945623, 0x00945620, 0x0094571d, 0x0094571d, 0x0096571d, 0x0098581b, 0x009c5819, 0x009d5817, 0x009d5814, 0x009d5813, 0x00a05b15, 0x00a05b15, 0x009d5813, 0x009c5711, 0x009d5612, 0x009f5715, 0x009e5716, 0x009f5816, 0x009e5714, 0x009d5611, 0x009c5611, 0x009c5611, 0x009d5612, 0x009d5614, 0x009d5712, 0x009c5812, 0x009c5712, 0x009c5614, 0x009c5614, 0x009a5714, 0x009a5814, 0x009d5a15, 0x009d5a15, 0x009e5914, 0x009f5a14, 0x009d5811, 0x009c5710, 0x00a05910, 0x00a05912, 0x00a05810, 0x00a05810, 0x00a15a10, 0x00a45c12, 0x00a35b12, 0x00a25a11, 0x009f5710, 0x009f5710, 0x009d5611, 0x009c5510, 0x009c5511, 0x009c5512, 0x009c5611, 0x009b5610, 0x009b5610, 0x009c5613, 0x009c5613, 0x009c5614, 0x00985411, 0x00985310, 0x00945111, 0x00935011, 0x008e4f0f, 0x008b4e10, 0x0085490e, 0x0084480f, 0x0080450f, 0x007f4610, 0x007d4511, 0x0078400f, 0x00723d0d, 0x006c390c, 0x00653409, 0x005d300c, 0x004f2407, 0x00452005, 0x003b1a07, 0x00341706, 0x002e150a, 0x002c160d, 0x0029160a, 0x00261408, 0x00261408, 0x00261408, 0x00271509, 0x0026150c, 0x0026160c, 0x0024170f, 0x0023160d, 0x0020140a, 0x001d1308, 0x001c1005, 0x001c1204, 0x001f1609, 0x0020140a, 0x001f120a, 0x001c130c, 0x0013100a, 0x000b0d07, 0x00091009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0c, 0x00060d0b, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d07, 0x00060e07, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0007110c, 0x0007110c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100b, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00040f08, 0x00051008, 0x00071008, 0x000e150e, 0x00181d16, 0x0020241d, 0x0020221e, 0x00212421, 0x00282a2a, 0x002e3031, 0x002f3033, 0x002e2f32, 0x002a2d31, 0x00252a2e, 0x002a2f32, 0x00353738, 0x00363535, 0x00353134, 0x00332e30, 0x00302c2b, 0x002c2823, 0x002d2720, 0x00342824, 0x003c2c27, 0x00493830, 0x00514035, 0x00544034, 0x005a4338, 0x00614940, 0x006c544b, 0x00745952, 0x007b5e58, 0x0084645f, 0x0088645e, 0x00906860, 0x008c6153, 0x008b5b45, 0x008a573a, 0x008c5530, 0x008d5427, 0x00905625, 0x00945827, 0x00965826, 0x00975824, 0x00975823, 0x00965820, 0x0096581f, 0x0095571d, 0x0098561a, 0x00995717, 0x009b5814, 0x009c5812, 0x009c5812, 0x009b5610, 0x009b5610, 0x009a5510, 0x009b5610, 0x009c5510, 0x009c5612, 0x009e5513, 0x009e5513, 0x009e5511, 0x009c530d, 0x009e5610, 0x009e5610, 0x00a15812, 0x00a05813, 0x00a05812, 0x009e5713, 0x009d5712, 0x009c5612, 0x009c5612, 0x009c5613, 0x009c5712, 0x009c5814, 0x009d5812, 0x009e5813, 0x00a05913, 0x00a35c16, 0x00a76017, 0x00a75f16, 0x00a75e18, 0x00a75c15, 0x00a75c15, 0x00a55d14, 0x00a55d14, 0x00a35b12, 0x00a25a11, 0x009f570f, 0x009f570f, 0x009d5610, 0x009c5610, 0x009c5611, 0x009c5611, 0x009c5611, 0x009b5610, 0x009c5711, 0x009c5613, 0x009c5613, 0x009c5614, 0x00985411, 0x00985310, 0x00955111, 0x00915010, 0x008e500f, 0x00884b0d, 0x00874c10, 0x00864a10, 0x00834810, 0x00804611, 0x00804815, 0x007c4414, 0x00743f10, 0x006f3c0f, 0x0068380d, 0x005c2f0b, 0x004d2306, 0x00441e05, 0x003b1b08, 0x00331707, 0x002c140a, 0x002a160c, 0x00241407, 0x00211104, 0x00241508, 0x00241408, 0x00231407, 0x00201309, 0x001f1308, 0x001d130a, 0x001d140a, 0x001c1308, 0x001d1409, 0x001e1508, 0x001f1608, 0x001f1509, 0x0020150b, 0x0022160d, 0x00201610, 0x0017140d, 0x000e110b, 0x00091009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0c, 0x00060d0b, 0x00040c09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d07, 0x00060e08, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006100b, 0x0006100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070e0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00050f0a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00051008, 0x00040f08, 0x00040f08, 0x00051008, 0x00070f08, 0x00070f08, 0x00070e08, 0x000e140c, 0x00181e17, 0x0021251e, 0x00252724, 0x002b2c2a, 0x002c2e2d, 0x002c2e2f, 0x002e3030, 0x00303134, 0x00333437, 0x0034383a, 0x00333437, 0x00323032, 0x00322e30, 0x00332c2e, 0x00342c2e, 0x00322b29, 0x00302924, 0x00332a23, 0x003a2e28, 0x0040322b, 0x00493830, 0x004e3c33, 0x00523f35, 0x005a433a, 0x00644c44, 0x006d544c, 0x00745c53, 0x00795d56, 0x0082635c, 0x00886660, 0x008e665f, 0x008a5f53, 0x008b5b47, 0x008b583c, 0x008c5531, 0x008f5728, 0x00915826, 0x00945828, 0x00975826, 0x00975824, 0x00975823, 0x00995c22, 0x009a5c23, 0x009b5c22, 0x009d5c1f, 0x009e5c1b, 0x00a05c17, 0x00a15b14, 0x00a15b14, 0x009f5812, 0x009f5812, 0x00a05912, 0x00a05912, 0x00a45b14, 0x00a45c17, 0x00a65b17, 0x00a65c17, 0x00a65c15, 0x00a35911, 0x00a35910, 0x00a35911, 0x00a15710, 0x009e540d, 0x009d540c, 0x009d550f, 0x009d540d, 0x009e560f, 0x009f5811, 0x009f5814, 0x00a05914, 0x00a05a15, 0x00a35c16, 0x00a45c16, 0x00a86017, 0x00a86018, 0x00a86016, 0x00a85f15, 0x00a85e16, 0x00a85c14, 0x00a85c14, 0x00a75d14, 0x00a55c12, 0x00a35911, 0x00a35911, 0x00a35b12, 0x00a05810, 0x009e5810, 0x009c5610, 0x009c550f, 0x009c5510, 0x009c5611, 0x009c5711, 0x009c5712, 0x009e5915, 0x009c5814, 0x009c5614, 0x009a5413, 0x00985213, 0x00955111, 0x00915010, 0x008e4f0f, 0x00884b0d, 0x00884c10, 0x00864a10, 0x00834710, 0x00804511, 0x00804714, 0x00804718, 0x00774012, 0x00703b0d, 0x0068360b, 0x0060330e, 0x00502609, 0x00441f05, 0x00391906, 0x00301605, 0x002c1409, 0x0028130a, 0x00251408, 0x00261509, 0x0028180b, 0x00241408, 0x00231508, 0x00201409, 0x00191007, 0x00150d05, 0x00150e06, 0x00181007, 0x00191208, 0x001b1407, 0x001d1507, 0x001c1307, 0x0020140a, 0x0020120b, 0x00201813, 0x00191710, 0x000c0f08, 0x00080e08, 0x00060e09, 0x00050e08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0c, 0x00060d0b, 0x00040c09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d07, 0x00060e08, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006100b, 0x0006100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e07, 0x00030d06, 0x00040f08, 0x00051008, 0x00070f08, 0x00081009, 0x00070e08, 0x000d140c, 0x00181e17, 0x00242821, 0x002d2e2b, 0x0030302f, 0x00303231, 0x002f3032, 0x00303133, 0x00313334, 0x00323437, 0x00333337, 0x00313034, 0x00322e30, 0x00362f31, 0x00382e31, 0x0034282b, 0x00342828, 0x00352b27, 0x00362c24, 0x00392f28, 0x003f322a, 0x00483930, 0x004f3e34, 0x00544338, 0x005c473e, 0x00665047, 0x0070584f, 0x00755d54, 0x00795d57, 0x0080625c, 0x00886661, 0x008e6660, 0x00895f54, 0x008c5c49, 0x008e5b42, 0x008f5834, 0x0091592c, 0x00925927, 0x00945825, 0x00955624, 0x00955623, 0x00955721, 0x00975920, 0x00995c22, 0x009b5c22, 0x009d5c20, 0x009e5c1b, 0x00a15b17, 0x00a25c14, 0x00a25c14, 0x00a45e15, 0x00a45d14, 0x00a35d14, 0x00a45c14, 0x00a45b14, 0x00a45b13, 0x00a85f17, 0x00a96017, 0x00aa5e14, 0x00a75c11, 0x00a95e14, 0x00aa5e15, 0x00aa5e15, 0x00a85c13, 0x00a45b10, 0x00a45b10, 0x00a55c11, 0x00a75d13, 0x00a65d14, 0x00a55c18, 0x00a55d17, 0x00a55d17, 0x00a65d15, 0x00a85e16, 0x00a96017, 0x00a96016, 0x00a96015, 0x00ac6017, 0x00ac6018, 0x00ab6016, 0x00ab6014, 0x00a95d14, 0x00a65b12, 0x00a45a12, 0x00a35b12, 0x00a35b12, 0x00a15910, 0x009e5710, 0x009f5811, 0x00a05913, 0x009f5813, 0x009f5814, 0x009d5813, 0x009d5813, 0x009e5915, 0x009d5814, 0x009c5715, 0x009b5614, 0x00995414, 0x00975312, 0x00915010, 0x008d4f0f, 0x00884c0e, 0x00874c10, 0x0085490f, 0x0083470f, 0x00804510, 0x00804714, 0x007f4617, 0x00794214, 0x00703c0e, 0x0068360b, 0x0060330f, 0x0052280b, 0x00452007, 0x003a1a08, 0x00321706, 0x002c1409, 0x00281309, 0x00251408, 0x00251709, 0x00261609, 0x0026180c, 0x00231709, 0x001e1409, 0x00171005, 0x00130d04, 0x00100c03, 0x00130d04, 0x00181208, 0x00191408, 0x001a1405, 0x001b1306, 0x001c1107, 0x00180c04, 0x001b140d, 0x00161710, 0x000d110a, 0x00080e08, 0x00060e08, 0x00040d07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0c, 0x00060d0b, 0x00040c09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d07, 0x00060e08, 0x00060e06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e07, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c08, 0x00080c08, 0x00080c07, 0x00080c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040a04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x000a120a, 0x00181f18, 0x00282a24, 0x0032302d, 0x00343433, 0x00343534, 0x00353738, 0x00323435, 0x00383839, 0x0038383a, 0x00373538, 0x00312f31, 0x00342c30, 0x00383033, 0x002e2528, 0x002e2426, 0x00382c2d, 0x00372d29, 0x00332b23, 0x00382f28, 0x0040332d, 0x00493b34, 0x0053433b, 0x005c4b42, 0x005f4942, 0x00675048, 0x006c554d, 0x00755c55, 0x007c5f58, 0x0082645e, 0x00856560, 0x0089675f, 0x008a6457, 0x00895e48, 0x008c5c41, 0x008f5835, 0x00935a30, 0x00935929, 0x00935824, 0x00945524, 0x00925420, 0x00975924, 0x00985a21, 0x00985b21, 0x00995b20, 0x009d5b1e, 0x009f5c1c, 0x009f5a14, 0x00a05b10, 0x00a05b10, 0x00a25a10, 0x00a1590f, 0x00a25a11, 0x00a15910, 0x00a35910, 0x00a65c13, 0x00a65c12, 0x00a85e13, 0x00a95e13, 0x00aa5f12, 0x00aa5f14, 0x00aa5f14, 0x00a95e13, 0x00a95e13, 0x00a96014, 0x00a85f13, 0x00a85e14, 0x00a75d14, 0x00a45c13, 0x00a45c14, 0x00a45c14, 0x00a85f17, 0x00a85e16, 0x00a95d14, 0x00ac6018, 0x00a95d14, 0x00ab6017, 0x00ab6015, 0x00ac6018, 0x00ac5f14, 0x00ab5e14, 0x00ab5e14, 0x00a95e13, 0x00a45b11, 0x00a45c12, 0x00a35b10, 0x00a1590f, 0x00a25a11, 0x00a25a11, 0x00a15a13, 0x00a05a13, 0x00a05912, 0x009f5813, 0x009f5813, 0x00a05814, 0x009f5814, 0x009c5514, 0x00995210, 0x00965010, 0x00945010, 0x00915010, 0x008f5010, 0x008c4f10, 0x00864b0c, 0x0084490e, 0x0082460e, 0x00814610, 0x00814813, 0x007f4714, 0x007a4312, 0x00703c0c, 0x00673509, 0x005c300b, 0x00512709, 0x00462008, 0x003a1a08, 0x002f1404, 0x002b1208, 0x002a170d, 0x00241507, 0x00231508, 0x00201409, 0x001c1408, 0x001c1408, 0x001b1408, 0x001a140a, 0x00181308, 0x00161106, 0x00131004, 0x00120f04, 0x00141005, 0x00151105, 0x00181106, 0x001b1108, 0x001b110a, 0x0018120b, 0x000e1008, 0x00090e07, 0x00060e06, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00060e09, 0x00060d0a, 0x00060e09, 0x00060e08, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e07, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c08, 0x00080c08, 0x00080c07, 0x00080c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040a04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00081109, 0x001d231c, 0x002d2d28, 0x0032302e, 0x00353434, 0x00343636, 0x00353738, 0x00323435, 0x0038383a, 0x0038383a, 0x00383638, 0x00383437, 0x00363034, 0x00342e30, 0x00342e31, 0x00362f30, 0x00342d2c, 0x00322925, 0x00322c25, 0x00383029, 0x003a2f2a, 0x00483b36, 0x0056473f, 0x0055443c, 0x005c4840, 0x00665149, 0x006f5850, 0x007b615b, 0x007f635c, 0x0081645d, 0x00856560, 0x0089665d, 0x008a6457, 0x00895f49, 0x008c5c42, 0x00905a38, 0x00925832, 0x0093582c, 0x00935726, 0x00955725, 0x00985925, 0x00985b25, 0x00985b22, 0x00985b21, 0x00995b20, 0x009d5c1f, 0x009f5c1c, 0x009f5914, 0x00a05a0f, 0x00a05a0f, 0x00a0580e, 0x00a1590f, 0x00a15810, 0x00a15810, 0x00a35910, 0x00a65c13, 0x00a75d14, 0x00a85e14, 0x00a95e13, 0x00aa5f14, 0x00aa5f14, 0x00aa5f14, 0x00a95e13, 0x00a95e13, 0x00a96014, 0x00a85f13, 0x00a85e14, 0x00a75d14, 0x00a45c12, 0x00a45c12, 0x00a35b11, 0x00a65c14, 0x00a75c15, 0x00a75d14, 0x00a65c13, 0x00a75c13, 0x00aa5e15, 0x00ac6016, 0x00ac6018, 0x00ac5f14, 0x00ab5e14, 0x00ac5f14, 0x00a95e13, 0x00a55c12, 0x00a25c12, 0x00a25b10, 0x00a25a10, 0x00a25a10, 0x00a25a11, 0x00a15a12, 0x00a05a13, 0x00a05a13, 0x00a05814, 0x00a05814, 0x00a05814, 0x00a05814, 0x009c5514, 0x009a5311, 0x00965011, 0x00945110, 0x00915010, 0x008f5010, 0x00894c0d, 0x00874c0e, 0x00864a0e, 0x0084480e, 0x0081470e, 0x007f460f, 0x007e4611, 0x007a4310, 0x00703c0b, 0x00673509, 0x005c300b, 0x00512709, 0x00452008, 0x00381908, 0x00321708, 0x002c140b, 0x0027140a, 0x00241508, 0x00221409, 0x001f150b, 0x001c140a, 0x001a140a, 0x00191407, 0x001a140a, 0x00181308, 0x00181207, 0x00181308, 0x00181308, 0x00181309, 0x00181308, 0x00171208, 0x00181109, 0x001a110c, 0x0016130c, 0x000d1209, 0x00091008, 0x00060e06, 0x00070e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060d0a, 0x00060d0a, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e07, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c07, 0x00080c07, 0x00080c05, 0x00080c04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00060f08, 0x00081008, 0x001b201a, 0x002e2e28, 0x0033302d, 0x00353434, 0x00343535, 0x00313436, 0x00303334, 0x00363839, 0x0037383a, 0x00323134, 0x00302f32, 0x002f2b30, 0x002f2a2f, 0x00353134, 0x00332f30, 0x00312d2b, 0x00322d28, 0x00312c25, 0x0038312c, 0x003f3530, 0x004e403c, 0x00574944, 0x0052433c, 0x00604d48, 0x0069544e, 0x00705953, 0x007c635e, 0x007e625c, 0x00846660, 0x00866660, 0x0089675e, 0x008a6558, 0x008c614d, 0x008c5d44, 0x0090583a, 0x00945a35, 0x0094592e, 0x00935828, 0x00925521, 0x00975823, 0x00985b24, 0x00985b21, 0x00985c20, 0x00995b1f, 0x009d5c1f, 0x009f5c1c, 0x009e5914, 0x009c570c, 0x009d570c, 0x009f580d, 0x00a0590f, 0x00a05810, 0x00a05810, 0x00a55b13, 0x00a55b14, 0x00a75b14, 0x00a85c15, 0x00a85c14, 0x00a95d14, 0x00aa5e15, 0x00aa5f14, 0x00a75c11, 0x00a75c11, 0x00a75c11, 0x00a85c12, 0x00a85d13, 0x00a65c13, 0x00a45a10, 0x00a35b10, 0x00a35b10, 0x00a25a11, 0x00a45c14, 0x00a85e14, 0x00a55c12, 0x00a55c12, 0x00a55c12, 0x00ac6016, 0x00ac6018, 0x00ad6016, 0x00ad6016, 0x00ac5f14, 0x00ac6016, 0x00a75d14, 0x00a25c11, 0x00a25a0f, 0x00a25a0e, 0x00a35b10, 0x00a35b10, 0x00a35b12, 0x00a35b12, 0x00a25913, 0x00a15812, 0x00a05912, 0x009f5811, 0x009d5711, 0x009c5412, 0x00995411, 0x00985210, 0x00965211, 0x00945313, 0x00905110, 0x00894c0d, 0x00874c0e, 0x00864a0e, 0x0084480e, 0x0081470c, 0x0080480f, 0x00804912, 0x007a4410, 0x00703c0b, 0x006c3a0d, 0x0062340f, 0x004f2406, 0x00462007, 0x00391a07, 0x002f1404, 0x002c160b, 0x00241108, 0x00201208, 0x001d1006, 0x001b100a, 0x001c120c, 0x00191408, 0x00191407, 0x001a140a, 0x0019140b, 0x00151005, 0x00151005, 0x00171006, 0x00181108, 0x00181208, 0x00181108, 0x0018100a, 0x001a120c, 0x0016140e, 0x000e110b, 0x000a0f08, 0x00070e06, 0x00070e06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060d0a, 0x00060d0a, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e07, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00080c07, 0x00070c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c05, 0x00080c05, 0x00080c04, 0x00080c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040b04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00060f08, 0x00081008, 0x0010140d, 0x00282824, 0x0033322f, 0x00353434, 0x00343536, 0x00303436, 0x002f3234, 0x002e3134, 0x002d3032, 0x00303134, 0x002d2e31, 0x00333337, 0x00343337, 0x00343335, 0x00313131, 0x0031302e, 0x0035322d, 0x00312d27, 0x0038322c, 0x00443a36, 0x004a3c39, 0x0050423e, 0x00544642, 0x0064514e, 0x0069554f, 0x00715a54, 0x00785f5b, 0x007c605a, 0x00846660, 0x00876761, 0x0088655d, 0x00886357, 0x008c614e, 0x008d5e45, 0x0090593d, 0x00915636, 0x0090552c, 0x00925628, 0x00945723, 0x00985924, 0x00985b24, 0x00985b21, 0x00985c20, 0x00995b1f, 0x009c5b1e, 0x009c5a1a, 0x009c5813, 0x009c570e, 0x009c570e, 0x009e560e, 0x00a1590f, 0x00a35b12, 0x00a35b12, 0x00a55b14, 0x00a55b14, 0x00a75b14, 0x00a95d16, 0x00a85c15, 0x00aa5e16, 0x00ac5f16, 0x00ab5e14, 0x00a85b11, 0x00a85b11, 0x00a85c11, 0x00a85d12, 0x00a85e14, 0x00a65c13, 0x00a45a10, 0x00a45b10, 0x00a55c12, 0x00a55b14, 0x00a65c14, 0x00a85e14, 0x00a85e14, 0x00a85f15, 0x00aa6017, 0x00ab6118, 0x00ac6118, 0x00ad6016, 0x00ad6016, 0x00ad6016, 0x00ac6016, 0x00a85f15, 0x00a45e14, 0x00a45d11, 0x00a45d11, 0x00a45c11, 0x00a35b10, 0x00a35b11, 0x00a35b12, 0x00a25a11, 0x00a15812, 0x00a05912, 0x00a05912, 0x009d5711, 0x009c5412, 0x00995410, 0x00985411, 0x00975312, 0x00945314, 0x00905111, 0x008a4d0e, 0x00874c0f, 0x0085490f, 0x0084480e, 0x0082480d, 0x0081480e, 0x007f4810, 0x007a440e, 0x00713d0a, 0x006a380a, 0x0062340f, 0x00522808, 0x00452006, 0x00391906, 0x00321707, 0x002c160b, 0x00241208, 0x00201208, 0x001c0f07, 0x00190e08, 0x00180e09, 0x00181008, 0x001a140a, 0x0019140b, 0x001b150c, 0x00171108, 0x00151005, 0x00160f06, 0x00181008, 0x00181008, 0x00161008, 0x0018110a, 0x0019110c, 0x0016140e, 0x000f120c, 0x000a0f08, 0x00080f07, 0x00080f07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e0a, 0x00060d0a, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050c07, 0x00060c07, 0x00060d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00050d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040d07, 0x00070e08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060d08, 0x00060d08, 0x00060c07, 0x00040c05, 0x00050c06, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00051009, 0x00051008, 0x00081008, 0x000a1108, 0x000c0f0a, 0x00202020, 0x00383639, 0x003d3b40, 0x00393b40, 0x00323739, 0x002f3234, 0x002c3032, 0x002c2f31, 0x002e3134, 0x00303335, 0x00313437, 0x00313436, 0x00313334, 0x00303332, 0x00313330, 0x0034342e, 0x0034312b, 0x0038312d, 0x00403733, 0x00493e3a, 0x00514340, 0x005c4e4a, 0x0063504c, 0x00685450, 0x00705a54, 0x00745b56, 0x007c5f5c, 0x00846660, 0x0084655e, 0x0087645c, 0x00886357, 0x008c614f, 0x008d5e46, 0x0090593c, 0x00905736, 0x0090562c, 0x0093582a, 0x00975a25, 0x00985b24, 0x00985a22, 0x00995922, 0x0098591f, 0x009a591e, 0x009c5a1b, 0x009c5817, 0x009c5713, 0x009e5710, 0x009f5710, 0x00a15810, 0x00a45b11, 0x00a75d14, 0x00a75d14, 0x00a55a11, 0x00a55a11, 0x00a85c14, 0x00a95d15, 0x00ac6018, 0x00ab6016, 0x00ac5f14, 0x00ad5f15, 0x00ac5e14, 0x00ac5e14, 0x00ab5f14, 0x00aa5f14, 0x00a85d14, 0x00a75c13, 0x00a75c13, 0x00a55a10, 0x00a85c14, 0x00a95e17, 0x00a95e17, 0x00a85e15, 0x00a85f16, 0x00ab6018, 0x00ac611a, 0x00ac6218, 0x00ac6118, 0x00ac5f14, 0x00ad6014, 0x00ad6014, 0x00ad6115, 0x00ac5f14, 0x00aa5e14, 0x00a85f14, 0x00a85f13, 0x00a75e13, 0x00a75d12, 0x00a65c14, 0x00a45a12, 0x00a35912, 0x00a25a14, 0x00a25a14, 0x00a15913, 0x009e5810, 0x009a540f, 0x00995410, 0x00985411, 0x00955210, 0x00925313, 0x00905112, 0x008a4d10, 0x00874a10, 0x00864910, 0x00854810, 0x00874c13, 0x00824810, 0x007e4610, 0x0079430f, 0x006f3b08, 0x006a3808, 0x0063330c, 0x00552b0b, 0x00462006, 0x003a1b06, 0x00341806, 0x002c1508, 0x00251408, 0x00211409, 0x0020140b, 0x00180c07, 0x00170d08, 0x00150d07, 0x00150f08, 0x0019120b, 0x001c140c, 0x001b140b, 0x00191209, 0x00181108, 0x00181008, 0x00181008, 0x00161007, 0x00160f08, 0x0019130c, 0x00181610, 0x0010100b, 0x000a0e07, 0x00070e06, 0x00080d06, 0x00080e08, 0x00060d08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d08, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00050d07, 0x00060d08, 0x00060d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00050c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x0005100a, 0x00051008, 0x00050f07, 0x00091008, 0x00181b16, 0x00303030, 0x003c3b40, 0x0038383e, 0x002e3034, 0x00252a2c, 0x0025282b, 0x00292c2f, 0x00292c2f, 0x002b2e30, 0x002f3234, 0x00303436, 0x00303335, 0x00303234, 0x00313433, 0x00333432, 0x00363730, 0x00383530, 0x003b3430, 0x003e3432, 0x00463a38, 0x00504240, 0x005e504c, 0x0064524e, 0x006b5852, 0x00705b55, 0x0079605c, 0x00806460, 0x00846661, 0x0085665e, 0x0088665e, 0x008b6559, 0x008f6450, 0x008f6049, 0x00905b3e, 0x00905837, 0x00915930, 0x00955c2d, 0x00975c28, 0x00985c24, 0x009a5a24, 0x009a5a24, 0x00995a21, 0x009c5c20, 0x009f5b1d, 0x009f5a19, 0x00a05916, 0x00a15814, 0x00a15812, 0x00a45a11, 0x00a65c12, 0x00a45b0e, 0x00a45b0d, 0x00a55a0e, 0x00a55a0e, 0x00a85c11, 0x00aa5f14, 0x00ad6018, 0x00ad6016, 0x00ad6014, 0x00af6116, 0x00ae6116, 0x00ae6116, 0x00ad6116, 0x00ac6014, 0x00ab6014, 0x00ab6015, 0x00ab6015, 0x00a95e14, 0x00ab6017, 0x00a95d14, 0x00a85c14, 0x00a85f15, 0x00ab6118, 0x00ac6219, 0x00b0651c, 0x00b0651c, 0x00af651a, 0x00af6418, 0x00af6417, 0x00af6315, 0x00af6315, 0x00af6315, 0x00af6215, 0x00ae6318, 0x00ac6318, 0x00ab6116, 0x00ab6015, 0x00ab6018, 0x00a85f17, 0x00a65c15, 0x00a45c16, 0x00a45c16, 0x00a35b14, 0x00a05811, 0x009d5812, 0x009c5814, 0x009a5714, 0x00965412, 0x00935413, 0x008f5214, 0x008c4e13, 0x00894c12, 0x00874911, 0x00884914, 0x00874a13, 0x00834913, 0x00804814, 0x007b4412, 0x00703c0a, 0x006c3809, 0x0063330c, 0x00552b0a, 0x00482207, 0x003c1c08, 0x00341805, 0x002b1508, 0x00251408, 0x00221408, 0x0020160a, 0x001e120a, 0x00191008, 0x00150e08, 0x00140d06, 0x00160e08, 0x001a120a, 0x001c140c, 0x001c140c, 0x001a130a, 0x00181008, 0x00171007, 0x00160f07, 0x00160f07, 0x00171109, 0x0016140e, 0x0010100b, 0x000a0d07, 0x00070e06, 0x00080d06, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00050c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060d08, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x0004100a, 0x00041008, 0x00030c04, 0x00091007, 0x00262a23, 0x003a3b38, 0x00343435, 0x0027262b, 0x001b1c1f, 0x00181d1e, 0x00202526, 0x002a2f30, 0x00292e2f, 0x00282b2d, 0x002e3134, 0x00303336, 0x00303236, 0x00323336, 0x00323434, 0x00343735, 0x00333330, 0x00302f2a, 0x0036312e, 0x00433b38, 0x004a3e3c, 0x00504341, 0x005e504e, 0x0064534e, 0x006b5852, 0x00745e58, 0x007d6461, 0x007f625f, 0x00826460, 0x0084655d, 0x0088655c, 0x008c655b, 0x00906454, 0x0090624c, 0x00915d40, 0x00905a38, 0x00935c32, 0x00945d2e, 0x00965c26, 0x00985c24, 0x009c5c26, 0x009d5d26, 0x009c5c24, 0x009d5d22, 0x00a05d1f, 0x00a25e1c, 0x00a55e1a, 0x00a65e18, 0x00a86017, 0x00ab6117, 0x00ac6417, 0x00ad6416, 0x00ad6416, 0x00ac6114, 0x00ac6114, 0x00ac6214, 0x00b06518, 0x00b06416, 0x00b06416, 0x00ae6114, 0x00ae6114, 0x00ac5f12, 0x00aa5c10, 0x00aa5e10, 0x00ab5f11, 0x00aa5e12, 0x00a95d11, 0x00a85d11, 0x00a75c10, 0x00aa6014, 0x00ac6218, 0x00ae641a, 0x00b1691e, 0x00b36b20, 0x00b46c21, 0x00b66e23, 0x00b46c21, 0x00b36a1e, 0x00b1681b, 0x00b36a1b, 0x00b36a1a, 0x00b36a19, 0x00b56a1b, 0x00b4691b, 0x00b2681a, 0x00ae6418, 0x00ab6116, 0x00aa6014, 0x00a95d14, 0x00a65b13, 0x00a55a12, 0x00a45c14, 0x00a45c14, 0x00a25a13, 0x00a05811, 0x009e5913, 0x009f5a14, 0x009c5814, 0x00965413, 0x00945414, 0x00905314, 0x008f5114, 0x008c4f14, 0x008a4c14, 0x00884a14, 0x00864913, 0x00824812, 0x00824a18, 0x00804817, 0x0074400e, 0x006c380a, 0x0064340b, 0x00552908, 0x00452003, 0x003c1b05, 0x00331704, 0x00291405, 0x00241406, 0x00231708, 0x0021170b, 0x001f140b, 0x001e140c, 0x001b130c, 0x0018110a, 0x00160e07, 0x00170f06, 0x00191209, 0x001c140c, 0x001e150d, 0x001e150d, 0x001c140c, 0x001b140c, 0x001c150d, 0x001c150e, 0x0019180f, 0x0012120c, 0x000b0d07, 0x00080d06, 0x00080d06, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060d04, 0x00050c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060d08, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x0004100a, 0x00041008, 0x00040e08, 0x00151c15, 0x0030342c, 0x00282b26, 0x001a1c19, 0x00151818, 0x00141818, 0x00181c1c, 0x00212625, 0x00252a2a, 0x00292f2f, 0x002e3134, 0x00313539, 0x0033363c, 0x0034373c, 0x0036383b, 0x00343638, 0x00343635, 0x00323331, 0x00323230, 0x00383434, 0x003e3836, 0x00443a39, 0x00514644, 0x00625453, 0x00615350, 0x00685650, 0x00715e58, 0x0079605e, 0x007e6060, 0x00836460, 0x0085655e, 0x0087645e, 0x008b655b, 0x00906454, 0x0090614c, 0x00905f40, 0x00905c3a, 0x00915d32, 0x00935e2e, 0x00945e26, 0x009a5e26, 0x009d5d26, 0x009e5e27, 0x009e5e26, 0x009e5e22, 0x00a15d20, 0x00a35e1c, 0x00a55e18, 0x00a86016, 0x00aa6218, 0x00ad6418, 0x00ae6415, 0x00ad6414, 0x00ac6414, 0x00ae6314, 0x00ad6314, 0x00b36919, 0x00b66c1d, 0x00b56b1b, 0x00b56b1b, 0x00b56a1b, 0x00b5691a, 0x00b66b1c, 0x00b26617, 0x00b06516, 0x00b36818, 0x00b36818, 0x00b3681a, 0x00b3681a, 0x00b36b1c, 0x00b56d1f, 0x00b66e21, 0x00b46c1f, 0x00b36c20, 0x00b36d20, 0x00b56f21, 0x00b56f21, 0x00b26c1d, 0x00ad6717, 0x00b16a19, 0x00b46c1b, 0x00b46d1a, 0x00b46c1a, 0x00b66c1c, 0x00b46c1b, 0x00b46a1b, 0x00b06718, 0x00ac6418, 0x00ab6015, 0x00a95e14, 0x00a85c14, 0x00a65b12, 0x00a45b13, 0x00a15910, 0x00a05810, 0x009e560e, 0x009d5810, 0x009e5a11, 0x009b5813, 0x00945310, 0x00945414, 0x00905314, 0x00905214, 0x008c5013, 0x008c4e14, 0x00894b13, 0x00874913, 0x00804811, 0x00804816, 0x007e4715, 0x00754110, 0x00703c0c, 0x0068360e, 0x00582c0a, 0x00462102, 0x003c1a04, 0x00321602, 0x00281404, 0x00231404, 0x00221808, 0x0022170b, 0x001e140b, 0x001e140c, 0x001c150b, 0x001c150a, 0x001c140a, 0x00191208, 0x00181007, 0x00181108, 0x001b130a, 0x001c140c, 0x001c140c, 0x001c140c, 0x001c150d, 0x001c170f, 0x0019170f, 0x00100f09, 0x00090c06, 0x00080d06, 0x00080d06, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c06, 0x00050c06, 0x00050d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c09, 0x00050d08, 0x00050d08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050e08, 0x00060d07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040d09, 0x00050e09, 0x00040e09, 0x0004100a, 0x00041009, 0x00060f08, 0x00101710, 0x001c211b, 0x001a1e18, 0x001b1f1b, 0x001c1f1d, 0x00181b1a, 0x001c201f, 0x00252928, 0x002c3131, 0x00303636, 0x0034383a, 0x0034373c, 0x0036383e, 0x0034383c, 0x00343438, 0x00303234, 0x00303332, 0x00323432, 0x00303030, 0x00313030, 0x003c3636, 0x00484040, 0x00544a49, 0x005a4e4d, 0x005b4e4a, 0x00665651, 0x00715e59, 0x00785f5c, 0x007e6160, 0x00856763, 0x00866760, 0x0088655c, 0x008a645a, 0x008e6454, 0x008e624e, 0x008f5e44, 0x008e5c3c, 0x00915d35, 0x00935e2f, 0x00955f29, 0x00995e28, 0x009c5f28, 0x009f5f27, 0x009f5e25, 0x009f5e23, 0x00a05f20, 0x00a35e1d, 0x00a46019, 0x00a86116, 0x00ab6417, 0x00ae6416, 0x00b06414, 0x00b16614, 0x00b26714, 0x00ac6210, 0x00ad6411, 0x00b06815, 0x00b36b18, 0x00b66c1a, 0x00b66c1a, 0x00b66c1a, 0x00b66c1a, 0x00b56b18, 0x00b86d1b, 0x00b86e1c, 0x00b86e1c, 0x00b86f1d, 0x00ba701f, 0x00b86f1e, 0x00b46e1c, 0x00b6701e, 0x00b46e1e, 0x00b36c1c, 0x00b06c1b, 0x00b06c1b, 0x00b46f1f, 0x00b46f1f, 0x00b46f1f, 0x00b26d1b, 0x00b36d1c, 0x00b06b18, 0x00b26c18, 0x00b36c18, 0x00b66f1c, 0x00b46c19, 0x00b16718, 0x00ae6418, 0x00ac6117, 0x00aa6018, 0x00a85f15, 0x00a55c13, 0x00a35a10, 0x00a05910, 0x009f580f, 0x009f570e, 0x009d570d, 0x009d580f, 0x009c5810, 0x00995713, 0x00955412, 0x00955513, 0x00925313, 0x00905213, 0x008e5012, 0x008c4f13, 0x00894c12, 0x00854b12, 0x00804710, 0x007d4510, 0x007c4513, 0x0074400f, 0x00703d0d, 0x006c3a11, 0x005c300c, 0x00492405, 0x003d1c05, 0x00331603, 0x00281404, 0x00231405, 0x00211708, 0x00211609, 0x001f150a, 0x001e140b, 0x001c1409, 0x001b1407, 0x001e170d, 0x001e180d, 0x001c150a, 0x00181207, 0x00171007, 0x00181108, 0x00181008, 0x00181209, 0x00181109, 0x00141009, 0x0014120b, 0x000c0d08, 0x00080c06, 0x00070e07, 0x00070e07, 0x00060e08, 0x00050d07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00050c07, 0x00050d07, 0x00050d07, 0x00050c07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00080c09, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00060f08, 0x00060e07, 0x000f140f, 0x00131812, 0x001d2220, 0x00202423, 0x00252928, 0x002c302f, 0x00303432, 0x002d3334, 0x002e3435, 0x00303437, 0x00313437, 0x00313438, 0x002f3234, 0x00303235, 0x002e3031, 0x002d302f, 0x002b2d2c, 0x002c2c2d, 0x00303030, 0x00383434, 0x00443d3e, 0x004d4545, 0x00534948, 0x005a4f4c, 0x00645752, 0x0074615c, 0x007a605e, 0x007f6260, 0x00856763, 0x00866760, 0x0088655c, 0x008a645b, 0x008c6457, 0x008e6352, 0x008e604a, 0x008e5d41, 0x00905e38, 0x00945e33, 0x00965e2c, 0x009a602c, 0x009c6029, 0x009e6028, 0x009f5e26, 0x009f5e24, 0x00a05f22, 0x00a25f20, 0x00a4601b, 0x00a56116, 0x00a96215, 0x00ae6416, 0x00b06515, 0x00b16414, 0x00b26514, 0x00b16715, 0x00b26b18, 0x00b36b18, 0x00b36b18, 0x00b56c1b, 0x00b56c1b, 0x00b46c19, 0x00b46c19, 0x00b56b19, 0x00b66c19, 0x00b56c19, 0x00b66c1a, 0x00b66d1c, 0x00b76d1c, 0x00b56d1c, 0x00b46d1c, 0x00b46c1c, 0x00b36c1c, 0x00b36c1c, 0x00b26d1d, 0x00b36e1d, 0x00b36e1e, 0x00b36e1e, 0x00b36e1e, 0x00b46f1d, 0x00b46f1d, 0x00b4701d, 0x00b46e1c, 0x00b46e1c, 0x00b46d1b, 0x00b36c19, 0x00af6718, 0x00ae6319, 0x00ab6018, 0x00a96018, 0x00a76017, 0x00a15c11, 0x009e580e, 0x00a0580f, 0x009f580f, 0x009f580f, 0x009f580f, 0x009f5810, 0x009c570f, 0x00995715, 0x00985614, 0x00955513, 0x00945212, 0x00915211, 0x008e5010, 0x008c5011, 0x00894d11, 0x00874c14, 0x00814810, 0x007c4410, 0x007c4511, 0x0073400c, 0x006e390b, 0x0069380f, 0x005d310c, 0x004c2808, 0x00401e09, 0x00331604, 0x00291407, 0x00241407, 0x001f1404, 0x001e1406, 0x001e140a, 0x001f140c, 0x001d160b, 0x001c1409, 0x00191408, 0x001b150a, 0x001a140a, 0x001a140a, 0x001a140c, 0x0019140a, 0x00171008, 0x00161008, 0x00141008, 0x0014100b, 0x0014130e, 0x000d0e0a, 0x00080d08, 0x00040f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00050d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00081009, 0x00080f0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00080c09, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00051009, 0x0005100a, 0x0008100a, 0x00080f09, 0x000d140f, 0x00161b17, 0x00222623, 0x00242827, 0x00323634, 0x00313534, 0x00303433, 0x002d3334, 0x002e3335, 0x00303337, 0x002f3234, 0x00303435, 0x002d3033, 0x002b2c30, 0x00282a2c, 0x002a2c2c, 0x00292b2c, 0x002a2c2d, 0x00313132, 0x003e3b3c, 0x00464141, 0x00484241, 0x004d4544, 0x005a4e4c, 0x00645853, 0x0075625d, 0x007b625f, 0x007f6461, 0x00856762, 0x00876760, 0x0087655c, 0x0089665d, 0x008d665b, 0x008c6557, 0x008e614d, 0x008d5f44, 0x00905f3c, 0x00936034, 0x00966030, 0x0099602e, 0x009b602c, 0x009d602b, 0x009f6028, 0x009f6025, 0x00a06022, 0x00a16020, 0x00a2601a, 0x00a46118, 0x00a86218, 0x00ad6418, 0x00b06417, 0x00b16616, 0x00b36818, 0x00b56d1c, 0x00b6701e, 0x00b36b19, 0x00b36b19, 0x00b36b19, 0x00b36b19, 0x00b46a19, 0x00b36918, 0x00b46918, 0x00b56a19, 0x00b46a19, 0x00b46b19, 0x00b46c1a, 0x00b46c1a, 0x00b46c1b, 0x00b36c1c, 0x00b36c1c, 0x00b46c1c, 0x00b46d1e, 0x00b46f1f, 0x00b46f1f, 0x00b46e1e, 0x00b36d1d, 0x00b36d1d, 0x00b46e1e, 0x00b67020, 0x00b67020, 0x00b56f1f, 0x00b46c1c, 0x00b16b1b, 0x00b06819, 0x00ae6518, 0x00ac6218, 0x00a75e15, 0x00a55e17, 0x00a45e17, 0x00a15b13, 0x009e5811, 0x009f5811, 0x009f5811, 0x009f5812, 0x00a05913, 0x009f5912, 0x009b5610, 0x009a5715, 0x00985514, 0x00955413, 0x00945210, 0x00905010, 0x008c4d0f, 0x008b4e10, 0x00884d11, 0x00884e14, 0x00844b13, 0x007e4611, 0x007c4511, 0x00733f0c, 0x006d390a, 0x00663409, 0x005d300a, 0x004f2a09, 0x00401e09, 0x00331705, 0x00291507, 0x00241408, 0x001d1205, 0x001c1105, 0x001c1209, 0x001c110b, 0x001b130b, 0x001c140d, 0x001c160e, 0x00171108, 0x00161008, 0x0019140b, 0x001a140b, 0x00181208, 0x00161008, 0x00151008, 0x00141008, 0x0015110c, 0x0014140f, 0x000c0f0b, 0x00080d08, 0x00050f08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00050d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00060c08, 0x00080c08, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00070f08, 0x00070f08, 0x00080e09, 0x00080f0b, 0x000f1410, 0x00151a17, 0x00222624, 0x00313534, 0x00343837, 0x00313534, 0x00303433, 0x002a3030, 0x002a3030, 0x00292c2e, 0x0025282a, 0x00242828, 0x00242828, 0x00262829, 0x00252728, 0x00282a2b, 0x002c2d2f, 0x002f3032, 0x00333334, 0x003a3738, 0x00403b3c, 0x00464040, 0x004e4644, 0x005b4f4d, 0x00645853, 0x0073605c, 0x007b625f, 0x007f6462, 0x00836761, 0x00886862, 0x0085665d, 0x00896860, 0x008d6961, 0x008c645c, 0x008c6250, 0x008c6046, 0x0090603d, 0x00916036, 0x00956031, 0x00996130, 0x009c602e, 0x009c602b, 0x009d6029, 0x009e6026, 0x009d6022, 0x009e601e, 0x009f601b, 0x00a3611a, 0x00a7621b, 0x00aa6218, 0x00ac6216, 0x00b16718, 0x00b46c1a, 0x00b46d1b, 0x00b06a18, 0x00b06918, 0x00b46c1a, 0x00b36918, 0x00b36918, 0x00b56b1a, 0x00b36918, 0x00b26515, 0x00b26515, 0x00b26718, 0x00b46918, 0x00b46a19, 0x00b46a19, 0x00b46a1a, 0x00b36a1b, 0x00b46b1c, 0x00b46b1c, 0x00b46c1c, 0x00b36c1c, 0x00b36c1c, 0x00b16b1b, 0x00b16b1b, 0x00b26b1b, 0x00b46d1e, 0x00b46c1d, 0x00b36c1c, 0x00b26b1c, 0x00b0681b, 0x00b0681b, 0x00ad6618, 0x00ac6418, 0x00a75f14, 0x00a35c12, 0x00a05c13, 0x00a05c15, 0x009e5813, 0x009e5712, 0x009f5813, 0x009f5813, 0x009f5813, 0x00a05914, 0x009e5814, 0x009b5512, 0x009a5714, 0x00985412, 0x00965413, 0x00945211, 0x00935111, 0x008e4e10, 0x008a4d10, 0x00884d11, 0x00884d14, 0x00854b13, 0x00814814, 0x007c4612, 0x0074400f, 0x00703b0c, 0x006b380d, 0x005d2f0a, 0x00502a09, 0x00401f08, 0x00341805, 0x002a1508, 0x00241409, 0x0021150c, 0x0020140c, 0x001c120c, 0x00190f0b, 0x00170f09, 0x0018100a, 0x0019130c, 0x001a140d, 0x0018130a, 0x00181309, 0x00181108, 0x00181108, 0x00181108, 0x00181109, 0x0018120c, 0x0018140f, 0x00181611, 0x000d100c, 0x00080e08, 0x00050f08, 0x00040c06, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00050d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e05, 0x00040d05, 0x00060c05, 0x00060c05, 0x00080c05, 0x00060c05, 0x00060c05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00060c08, 0x00060c08, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00060f08, 0x00070f08, 0x00080e09, 0x00080f0a, 0x00101611, 0x00171c18, 0x002c302e, 0x00313534, 0x00323534, 0x00303433, 0x002e3130, 0x00262b2c, 0x00212526, 0x00242726, 0x00232625, 0x00212526, 0x00242728, 0x00252728, 0x00282a2b, 0x00303133, 0x002d2f30, 0x002d2f30, 0x00313134, 0x00393838, 0x00403b3d, 0x00484243, 0x00534b48, 0x005d5250, 0x00655954, 0x00705d59, 0x007a605e, 0x007e6360, 0x00846863, 0x00876b64, 0x00876a60, 0x008b6a63, 0x008b6861, 0x008d6760, 0x008f6556, 0x008f624c, 0x00906040, 0x00926038, 0x00956032, 0x00986031, 0x009b602d, 0x009c6029, 0x009d6028, 0x009d6025, 0x009c5e20, 0x009b5d1c, 0x009d5d19, 0x00a2601a, 0x00a7621c, 0x00a66017, 0x00a86015, 0x00ab6214, 0x00ae6516, 0x00ac6616, 0x00aa6414, 0x00ab6414, 0x00ae6516, 0x00ae6314, 0x00ae6414, 0x00b16717, 0x00b16717, 0x00b26616, 0x00b36616, 0x00b16616, 0x00b16718, 0x00b06517, 0x00af6416, 0x00b06618, 0x00b36a1c, 0x00b3691c, 0x00b2681c, 0x00b1681b, 0x00af681a, 0x00ae6618, 0x00af6719, 0x00ae6719, 0x00af681a, 0x00b16b1c, 0x00af681a, 0x00af681c, 0x00af681c, 0x00af681c, 0x00ae681c, 0x00ab6418, 0x00a96115, 0x00a55e14, 0x00a05b12, 0x009e5a11, 0x009e5912, 0x009d5812, 0x009e5712, 0x009f5813, 0x009f5813, 0x009e5712, 0x009c5510, 0x009d5714, 0x009e5714, 0x009c5815, 0x00995513, 0x00985413, 0x00965312, 0x00945212, 0x00904f10, 0x008c4d10, 0x008a4c11, 0x00884c13, 0x00854a13, 0x00844815, 0x00804815, 0x0076400e, 0x00703c0c, 0x006d380d, 0x005e2f09, 0x00502a0a, 0x0043200b, 0x00341805, 0x002a1508, 0x0024140a, 0x0021150c, 0x0020150e, 0x001e140f, 0x001a0f0b, 0x00160e09, 0x00150f0a, 0x0015100a, 0x0018130c, 0x0018120b, 0x0018120b, 0x0018110a, 0x00171009, 0x00181208, 0x00181208, 0x001a140c, 0x001d1710, 0x001a1913, 0x000d100c, 0x00080e08, 0x00050f08, 0x00040c06, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c06, 0x00060c06, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00060c05, 0x00060c05, 0x00080c05, 0x00060c05, 0x00060c05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00090d0a, 0x00060c08, 0x00060c07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100a, 0x00040c08, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00040c06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00070f0a, 0x0008100c, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00070f08, 0x00080e08, 0x00080f09, 0x00101410, 0x00262b25, 0x0030332f, 0x00343734, 0x002f3130, 0x00282c2b, 0x00222624, 0x00232627, 0x00202424, 0x00252928, 0x001d2020, 0x001e2222, 0x00272a2b, 0x0028292b, 0x00313334, 0x002c2d2f, 0x002a2c2f, 0x002d3032, 0x00313334, 0x00363536, 0x003e3a3c, 0x00494244, 0x00534b4b, 0x005d5150, 0x00685c56, 0x00725f59, 0x007b605c, 0x007e6360, 0x00846764, 0x00856c64, 0x00876a60, 0x008b6a62, 0x008b6861, 0x008c6660, 0x0090645b, 0x00906150, 0x00905f42, 0x00935e39, 0x00965f35, 0x00985f32, 0x009a5f2c, 0x009c5f28, 0x009c5f26, 0x009c5f24, 0x009c5d20, 0x009b5c1b, 0x009c5c18, 0x009e5c16, 0x00a15c17, 0x00a15b16, 0x00a35a14, 0x00a55e14, 0x00a55e14, 0x00a55d13, 0x00a96014, 0x00a96014, 0x00a96014, 0x00aa5f14, 0x00ac6014, 0x00b06418, 0x00ac6214, 0x00b06617, 0x00b3681c, 0x00b2681b, 0x00af6417, 0x00ac6316, 0x00ac6217, 0x00ac6317, 0x00ac6418, 0x00ac6318, 0x00ac6318, 0x00ac6318, 0x00ac6217, 0x00ab6116, 0x00aa6115, 0x00ac6217, 0x00ab6218, 0x00ab6118, 0x00a86016, 0x00a96118, 0x00a96118, 0x00aa6218, 0x00a86117, 0x00a65f14, 0x00a55e14, 0x00a25b12, 0x009f5a12, 0x009e5a12, 0x009c5811, 0x009c5812, 0x009e5912, 0x00a05814, 0x00a05814, 0x009e5712, 0x009f5813, 0x009f5814, 0x009f5814, 0x009c5816, 0x009c5614, 0x00985412, 0x00985411, 0x00955312, 0x00905010, 0x008d4e11, 0x00894b11, 0x00874b13, 0x00864912, 0x00844814, 0x00804714, 0x00784210, 0x0075400f, 0x006f3a0f, 0x0062300a, 0x00582c0c, 0x0048220a, 0x003a1a08, 0x002b1507, 0x0024140a, 0x0020140c, 0x001f140d, 0x001f130e, 0x001e130e, 0x0018120d, 0x0014100a, 0x0015100b, 0x0014100a, 0x0017120c, 0x0016120a, 0x00151008, 0x00171008, 0x00181308, 0x001a1409, 0x001d170d, 0x001f1810, 0x00191710, 0x000c0e09, 0x00070d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c06, 0x00060d04, 0x00060d04, 0x00060d03, 0x00060e01, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c05, 0x00060d04, 0x00060d04, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00090d0a, 0x00060c08, 0x00060c07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100a, 0x00040c08, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c0a, 0x00040c08, 0x00060e09, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00070f0a, 0x0008100c, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00070f08, 0x00080e08, 0x00080f08, 0x00121711, 0x00252a24, 0x002d312d, 0x002d2f2c, 0x00222422, 0x00202422, 0x00202422, 0x001b1f20, 0x00222526, 0x00242828, 0x00262a2a, 0x002a2d30, 0x002d3034, 0x002f3034, 0x002e2f32, 0x002a2c2d, 0x002b2c30, 0x002d3132, 0x00313334, 0x00363435, 0x00413e40, 0x004c4648, 0x00504848, 0x005a4f4c, 0x006c5d58, 0x0074615c, 0x007b605c, 0x007d635f, 0x00846865, 0x00856c64, 0x00876a60, 0x008b6a63, 0x008b6861, 0x008b645f, 0x0090645c, 0x00906150, 0x00905f42, 0x00935e39, 0x00955e34, 0x00985d31, 0x009b5e2c, 0x009c5e28, 0x009d5e26, 0x009d5d24, 0x009c5c20, 0x009b5b19, 0x009a5a16, 0x009b5914, 0x009c5815, 0x009f5814, 0x00a05814, 0x009f5912, 0x00a05911, 0x00a35b14, 0x00a55d16, 0x00a65e16, 0x00a65e16, 0x00a45b12, 0x00a75d14, 0x00a85f15, 0x00a65d11, 0x00a75e12, 0x00aa6016, 0x00aa6218, 0x00a96118, 0x00ab6419, 0x00a96119, 0x00a55d15, 0x00a75f16, 0x00a86017, 0x00a86017, 0x00a86018, 0x00a65e15, 0x00a96119, 0x00a96118, 0x00a55d14, 0x00a45c14, 0x00a45c15, 0x00a55f18, 0x00a45e17, 0x00a45e17, 0x00a45e17, 0x00a45f17, 0x00a45d16, 0x00a15c14, 0x00a05912, 0x009e5813, 0x009c5814, 0x009b5814, 0x009c5812, 0x009c5913, 0x009d5814, 0x009e5915, 0x009f5a16, 0x009f5a16, 0x009e5916, 0x009d5816, 0x009d5816, 0x009c5614, 0x00985412, 0x00985411, 0x00955412, 0x00915111, 0x008f5013, 0x00894d13, 0x00874b13, 0x00854811, 0x00844814, 0x00804714, 0x00794210, 0x00784311, 0x00703c0f, 0x0066340d, 0x00582b0a, 0x004b2208, 0x0041200a, 0x002d1506, 0x00251408, 0x001e120b, 0x001c130c, 0x001e140c, 0x001e160d, 0x001e160e, 0x001c140e, 0x00150f08, 0x00171009, 0x0018120b, 0x0018100a, 0x0018110a, 0x0019140b, 0x001b150c, 0x001c170c, 0x00201910, 0x001c160f, 0x0013110b, 0x00080c07, 0x00040b05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d08, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d03, 0x00060d03, 0x00060d04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c04, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00090d0a, 0x00060c08, 0x00060c07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100a, 0x00040c08, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00060e08, 0x00051007, 0x00051007, 0x00051007, 0x00040e05, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070d08, 0x00070d08, 0x00080c08, 0x000a0e09, 0x00151915, 0x00242823, 0x00292d29, 0x002a2c2a, 0x00222422, 0x00212524, 0x00202423, 0x00272b2b, 0x00292c2d, 0x002b2e2f, 0x002c3030, 0x002b2e30, 0x00272a2c, 0x00292b2e, 0x0025282b, 0x0026282b, 0x002b2c30, 0x002c2f31, 0x002e3030, 0x003a383b, 0x00434043, 0x00484243, 0x0052494a, 0x00605452, 0x006c5d58, 0x0074605c, 0x007b605c, 0x007d625e, 0x00836864, 0x00866b64, 0x00886a62, 0x008c6b64, 0x008c6864, 0x008c6660, 0x008f645b, 0x00906150, 0x008f5d41, 0x00925d3a, 0x00955e34, 0x00985d31, 0x009b5e2c, 0x009c5e29, 0x009d5e25, 0x009a5b20, 0x0099591b, 0x00995918, 0x00995915, 0x00995817, 0x009a5716, 0x009b5415, 0x009c5414, 0x009c5614, 0x009b5613, 0x009c5714, 0x009e5815, 0x009e5814, 0x009f5814, 0x009d5712, 0x00a05813, 0x00a05913, 0x00a05a12, 0x00a05911, 0x00a05912, 0x00a05912, 0x00a45c15, 0x00a75f18, 0x00a65e18, 0x00a55d17, 0x00a45b15, 0x00a45c15, 0x00a55c16, 0x00a65e18, 0x00a65e18, 0x00a75f18, 0x00a45c16, 0x00a35a14, 0x00a45b17, 0x00a45c18, 0x00a35c18, 0x00a45c18, 0x00a35c17, 0x00a35c17, 0x00a15c17, 0x00a05914, 0x009f5813, 0x009c5411, 0x009a5412, 0x00995513, 0x00995514, 0x009a5714, 0x009a5614, 0x009a5513, 0x009c5614, 0x009c5815, 0x009e5817, 0x009e5818, 0x009c5716, 0x009b5514, 0x00995412, 0x00955210, 0x00955210, 0x00945110, 0x00925212, 0x008f5013, 0x00894d12, 0x00874b13, 0x00844912, 0x00814814, 0x007f4814, 0x007e4816, 0x007a4413, 0x00743f12, 0x00683710, 0x00633413, 0x00502409, 0x003f1a04, 0x00301404, 0x00261407, 0x001f130c, 0x001d110b, 0x001c120a, 0x001e140c, 0x001f150c, 0x0020160c, 0x001c140b, 0x001b1308, 0x001b1208, 0x001a1008, 0x001b1309, 0x001c140a, 0x001c140b, 0x001c140d, 0x001b130e, 0x0017120d, 0x0011100c, 0x00080c08, 0x00050c06, 0x00040d07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c08, 0x00060c05, 0x00060c04, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c08, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080e0a, 0x00060c08, 0x00060c07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0005100a, 0x00040c08, 0x00060c08, 0x00060c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00040c08, 0x00040c08, 0x00040d07, 0x00061007, 0x00051007, 0x00051007, 0x00040e05, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x0004100a, 0x0004100a, 0x0004100a, 0x0005100a, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d08, 0x0009100a, 0x00151a14, 0x00242822, 0x00272b28, 0x00272927, 0x00282b29, 0x00242827, 0x002e3131, 0x002f3334, 0x002c3030, 0x00242829, 0x00222526, 0x00272a2c, 0x00242729, 0x0027282b, 0x002a2c2e, 0x002d2f32, 0x002a2c2f, 0x002c2f31, 0x00343537, 0x003c3a3c, 0x00434041, 0x00484344, 0x00554c4d, 0x00645858, 0x006f5f5c, 0x0076605c, 0x007c615d, 0x007d625f, 0x00836864, 0x00856a64, 0x00886a63, 0x008c6b64, 0x008c6964, 0x008d6760, 0x008f6459, 0x00906150, 0x008f5d41, 0x00925d3a, 0x00955c34, 0x00975c30, 0x00995c2b, 0x009a5c28, 0x009a5c23, 0x0098581c, 0x00955718, 0x00965515, 0x00965714, 0x00955714, 0x00965515, 0x00985314, 0x00985314, 0x00985413, 0x00985413, 0x00985414, 0x009a5615, 0x00995513, 0x00995413, 0x00995413, 0x009c5814, 0x009d5814, 0x009d5814, 0x009d5814, 0x009d5814, 0x009f5813, 0x009f5813, 0x009f5813, 0x009f5813, 0x009d5712, 0x009c5512, 0x009c5612, 0x009d5713, 0x009f5814, 0x00a05814, 0x00a05915, 0x00a05915, 0x00a05814, 0x009f5916, 0x00a05a18, 0x00a05c18, 0x009f5a18, 0x009e5a15, 0x009d5814, 0x009c5815, 0x009a5513, 0x00985310, 0x00985311, 0x00985313, 0x00975414, 0x00955414, 0x00945413, 0x00965412, 0x00955213, 0x00965314, 0x00985515, 0x00995718, 0x009a5718, 0x00985414, 0x00985413, 0x00985413, 0x00945210, 0x00945110, 0x00945110, 0x00925212, 0x00905114, 0x008b4e11, 0x00884c14, 0x00834a12, 0x007f4611, 0x007c4512, 0x007c4814, 0x007d4816, 0x00764012, 0x006f3c13, 0x00643411, 0x00582a0c, 0x00472108, 0x00301503, 0x00271306, 0x001f140c, 0x001c120b, 0x00181008, 0x00180f07, 0x001a1208, 0x001c1409, 0x001d150b, 0x0020180c, 0x001d140b, 0x001b1308, 0x001c1208, 0x001c1309, 0x001b120b, 0x0018120c, 0x0018110c, 0x00171210, 0x0010110d, 0x00080c08, 0x00050c06, 0x00040d07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00070e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c08, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c09, 0x00060c08, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060c08, 0x000b110d, 0x00101612, 0x00141916, 0x00212423, 0x00242625, 0x00252726, 0x00282c2c, 0x00303434, 0x002d3033, 0x00232628, 0x00242729, 0x002a2d30, 0x00242729, 0x0024282a, 0x0025272a, 0x002c2c30, 0x002c2d30, 0x002c2e31, 0x0034383a, 0x0035383b, 0x00383639, 0x00403c3d, 0x00444041, 0x005a5252, 0x00675959, 0x00705e5c, 0x00755f5d, 0x007b605e, 0x007f6460, 0x00846764, 0x00836864, 0x00886a66, 0x008f6d6c, 0x00906c68, 0x00906a65, 0x0091665c, 0x00926451, 0x00916044, 0x00925d3a, 0x00945c31, 0x00985c30, 0x0096592a, 0x00955826, 0x00955920, 0x00935619, 0x00915416, 0x00905113, 0x008d5010, 0x008e5010, 0x00905010, 0x00914e0f, 0x00914d0e, 0x00904e0c, 0x00925010, 0x00955311, 0x00965514, 0x00975514, 0x00955412, 0x00945211, 0x00955412, 0x00985412, 0x00985311, 0x00995412, 0x00995412, 0x009a5411, 0x009b5410, 0x009a5310, 0x009a5310, 0x009a5412, 0x00985311, 0x0096500f, 0x00985311, 0x009a5513, 0x009c5614, 0x009b5514, 0x009a5413, 0x00995413, 0x00975514, 0x00985716, 0x00985716, 0x00975614, 0x00975614, 0x00965413, 0x00945414, 0x00935013, 0x00914e11, 0x00924e11, 0x00935014, 0x00904f13, 0x008a4b0f, 0x00884c0e, 0x008b4e10, 0x008c4d10, 0x008b4c0e, 0x008c4d10, 0x008e5012, 0x00905013, 0x00915113, 0x00925012, 0x00915012, 0x00945314, 0x00975618, 0x00965517, 0x00925214, 0x008f5010, 0x008b4d0f, 0x00884c13, 0x00834914, 0x007e4613, 0x007c4514, 0x007d4814, 0x007d4612, 0x00794211, 0x00723e10, 0x006c3c12, 0x005a2c0a, 0x004a2306, 0x00341804, 0x00281305, 0x001e1408, 0x001c1308, 0x00191208, 0x00151009, 0x00130d08, 0x00140f08, 0x0019130c, 0x001b140e, 0x001d140c, 0x001e140c, 0x0020140d, 0x0024140f, 0x00191008, 0x0015110a, 0x0016110c, 0x00181310, 0x0010120c, 0x00070e06, 0x00040c04, 0x00040e05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e07, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040c06, 0x00030c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040f08, 0x00040f08, 0x00060e08, 0x00070f0a, 0x0008100c, 0x000a0f0c, 0x00141815, 0x001c1e1d, 0x00222424, 0x002b2e2f, 0x002c2f30, 0x0025282b, 0x002b2e30, 0x00282c2e, 0x00232628, 0x001d2023, 0x0025272a, 0x00282a2d, 0x002f3033, 0x002c2d30, 0x002c2d31, 0x00313435, 0x00323437, 0x00353435, 0x003b3838, 0x00484444, 0x00595150, 0x00645756, 0x00725f5c, 0x0078605d, 0x007c615d, 0x00806561, 0x00846865, 0x00846965, 0x00896c69, 0x0090706f, 0x00916d6a, 0x00916b67, 0x0094685c, 0x00946654, 0x00946248, 0x00945f3c, 0x00985f36, 0x0094592e, 0x00905628, 0x00905624, 0x00905620, 0x008d541a, 0x008c5217, 0x008a4e14, 0x00884d11, 0x008a4e10, 0x008c4c10, 0x008c4b0f, 0x008c4b0e, 0x008c4c0e, 0x008f4e10, 0x00905011, 0x00915112, 0x00915011, 0x00905010, 0x00904f10, 0x00915112, 0x00955111, 0x00975011, 0x00975011, 0x00975011, 0x00965010, 0x00965010, 0x00965010, 0x0095500f, 0x00965110, 0x00955112, 0x00945010, 0x00945010, 0x00945111, 0x00965212, 0x00945111, 0x00945010, 0x00945010, 0x00905112, 0x00925414, 0x008e5011, 0x008e5011, 0x008e5010, 0x008d5012, 0x008c4e14, 0x00884b11, 0x00884810, 0x00884910, 0x00874a12, 0x007f440c, 0x00753c05, 0x00764006, 0x00784108, 0x00773e05, 0x00773d04, 0x00794006, 0x007c4409, 0x0080440a, 0x00804409, 0x00854a0e, 0x00884c10, 0x008c4f13, 0x00905215, 0x008f5114, 0x008b4e11, 0x008a4e11, 0x00894d11, 0x00874c13, 0x00834914, 0x00804814, 0x007e4817, 0x007f4814, 0x007c4511, 0x007a4312, 0x00754013, 0x00703f13, 0x0063330c, 0x00522a0a, 0x003a1c04, 0x002e1807, 0x00201305, 0x001d1406, 0x001a1308, 0x00171208, 0x00161008, 0x00140e08, 0x00160f08, 0x0019120b, 0x001b1109, 0x001e140b, 0x00251810, 0x002c1a13, 0x0020140c, 0x001a140a, 0x00171109, 0x0019150f, 0x0011130c, 0x00080f07, 0x00040c04, 0x00040e05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00030c06, 0x00030c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050d09, 0x00060c08, 0x00080e0b, 0x00181c19, 0x00282828, 0x002d2d2d, 0x002b2c2e, 0x00282c2c, 0x00272a2c, 0x00212728, 0x00212427, 0x00232628, 0x002a2b2e, 0x002c2e31, 0x002c2c30, 0x002c2d30, 0x002c2e30, 0x00333435, 0x00303437, 0x002e3031, 0x00353334, 0x003e3a3a, 0x004c4646, 0x005d5453, 0x00675956, 0x0073605c, 0x0078615c, 0x007b625d, 0x007e6360, 0x00846865, 0x00856b67, 0x008d706d, 0x00937372, 0x00916e6c, 0x008f6a65, 0x0092675c, 0x00926451, 0x00936248, 0x00945f3d, 0x00915a34, 0x008d562d, 0x008c5428, 0x00885021, 0x00834e1c, 0x00804c18, 0x00824d18, 0x00844e18, 0x00834c15, 0x00844b13, 0x00864a14, 0x00884a14, 0x00884912, 0x00894b10, 0x008c4d12, 0x008c4d12, 0x008b4c11, 0x008c4c11, 0x008a4c10, 0x008c4d11, 0x008d4e13, 0x00914f14, 0x00935014, 0x00945014, 0x00945015, 0x00945114, 0x00945114, 0x00935013, 0x00935013, 0x00925014, 0x00914f14, 0x00904e11, 0x00904e11, 0x00904e11, 0x008f4d10, 0x008f4d10, 0x008f4d10, 0x008e4d11, 0x00894d10, 0x00894e12, 0x00894f11, 0x00864c0f, 0x00844b10, 0x00824810, 0x007d4410, 0x007c4211, 0x007c4312, 0x00784010, 0x00703b0c, 0x006c380a, 0x006a380b, 0x0067380a, 0x00653408, 0x00673508, 0x00673506, 0x00683706, 0x006c3a07, 0x00713d09, 0x0077400d, 0x00743f0b, 0x00763f0a, 0x007a420d, 0x00804610, 0x007c430d, 0x007c420c, 0x00814812, 0x00844b15, 0x00854b14, 0x00844b14, 0x00834b18, 0x007e4918, 0x007d4714, 0x007c4410, 0x00794211, 0x00764214, 0x00724011, 0x006b3a0d, 0x00582e08, 0x00412105, 0x00311904, 0x00251605, 0x00201404, 0x001c1104, 0x00191206, 0x001a1207, 0x001a1209, 0x001b1109, 0x001c1208, 0x001c1107, 0x001e1006, 0x0025140c, 0x0027140a, 0x0025150c, 0x0020150c, 0x001c140c, 0x0019160d, 0x0010140b, 0x00071007, 0x00051008, 0x00040f08, 0x00040f08, 0x00060e06, 0x00060e06, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00080f0a, 0x000c110e, 0x001e2120, 0x00303131, 0x002b2b2b, 0x00282a2b, 0x0025282a, 0x0026292c, 0x00272c2e, 0x002b2e30, 0x002b2e30, 0x002c2e31, 0x002e2d31, 0x00292b2e, 0x002d2f32, 0x00303233, 0x00303234, 0x002d3030, 0x00303334, 0x00333032, 0x00403c3c, 0x00514a49, 0x00615856, 0x006b5d5a, 0x0074605c, 0x007c6460, 0x007c635f, 0x007e635f, 0x00846a66, 0x00886c69, 0x00927572, 0x00937373, 0x0091706c, 0x00906c67, 0x0090665a, 0x0090614f, 0x00906045, 0x00905d3c, 0x008b5632, 0x00804c26, 0x007d4920, 0x007a461c, 0x00764516, 0x00714210, 0x006f3f0e, 0x00754413, 0x007a4815, 0x007b4612, 0x007c4512, 0x007f4513, 0x00804411, 0x0081460f, 0x00844810, 0x00854912, 0x00844810, 0x00844910, 0x00834710, 0x00844910, 0x00864b12, 0x008a4c13, 0x008c4c13, 0x008c4c13, 0x008c4c14, 0x008c4d13, 0x008c4e13, 0x008d4e13, 0x008f4e14, 0x008d4e13, 0x008a4b12, 0x00884911, 0x00884911, 0x00884911, 0x00884810, 0x00884810, 0x00884810, 0x00864810, 0x00824a10, 0x007f480f, 0x007d470e, 0x007a440c, 0x0075400c, 0x00723d0c, 0x00703c0d, 0x006c380a, 0x00663409, 0x00613108, 0x005c2d05, 0x00582b04, 0x00542a04, 0x00542c08, 0x00582d09, 0x00582d08, 0x00582d06, 0x005b3006, 0x00603408, 0x00643409, 0x0068380c, 0x0068380a, 0x00683808, 0x00683607, 0x00673303, 0x006c3808, 0x00723f0e, 0x007b4515, 0x007d4816, 0x007f4813, 0x00844c16, 0x00844d1a, 0x007e4917, 0x007c4614, 0x007b4310, 0x00784110, 0x00774213, 0x00764314, 0x006e3c0c, 0x0062350c, 0x00492606, 0x00351901, 0x00291604, 0x00231405, 0x00211406, 0x00201407, 0x00201408, 0x00201409, 0x0023170c, 0x0023170c, 0x0024150c, 0x0026150b, 0x0029150b, 0x002e180c, 0x00321e13, 0x00291910, 0x0020140b, 0x0018140b, 0x000b1007, 0x00071007, 0x00051008, 0x00031008, 0x00040f08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e06, 0x00060e06, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e06, 0x00060e06, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0009100c, 0x00151a17, 0x00232524, 0x00282828, 0x00222222, 0x00242726, 0x00242728, 0x00262b2d, 0x00282d2f, 0x0024282b, 0x00232428, 0x0029292c, 0x002c2b2f, 0x002c2e30, 0x002d2f30, 0x002f3032, 0x002e3030, 0x002d2f30, 0x002f2f2f, 0x00323031, 0x00433e3d, 0x00514a49, 0x00635958, 0x006d605c, 0x0076645f, 0x007e6761, 0x007d6460, 0x007d625e, 0x00856b67, 0x00886e6b, 0x00917572, 0x00917471, 0x00906f6a, 0x008c6963, 0x008d6758, 0x008b6250, 0x00865940, 0x00845637, 0x00825534, 0x00764926, 0x006e411e, 0x006c3f1d, 0x00714421, 0x006d401c, 0x00683b18, 0x00683a16, 0x006c3f14, 0x006e3f10, 0x00713f10, 0x00733e10, 0x00743d0f, 0x00753c0d, 0x00783e0f, 0x007b4112, 0x007f4515, 0x007b420f, 0x007b420d, 0x007e450f, 0x0080480f, 0x00834910, 0x00834910, 0x00844910, 0x00844910, 0x0084490f, 0x00884c11, 0x0084480d, 0x00874a0e, 0x00894c11, 0x00884812, 0x00854712, 0x00814411, 0x00824513, 0x00844713, 0x00834411, 0x007f440f, 0x007a410c, 0x0077400c, 0x0077400d, 0x0074400f, 0x006c3a0c, 0x0065360b, 0x0060330b, 0x005d330c, 0x0058300b, 0x00542b0a, 0x00522b0b, 0x004f2908, 0x004c2907, 0x004c2906, 0x004f2808, 0x00502808, 0x00542807, 0x00542805, 0x00542806, 0x005d320e, 0x00643814, 0x00643712, 0x005f340e, 0x005e320b, 0x0060310b, 0x0060320c, 0x0064340c, 0x0067380e, 0x006e3e12, 0x00744114, 0x00784413, 0x007d4815, 0x007f4918, 0x007e4918, 0x007b4714, 0x00794310, 0x00784211, 0x00784212, 0x00764212, 0x00743d0d, 0x006d3a10, 0x00542b09, 0x00381800, 0x002c1304, 0x00281408, 0x00251509, 0x00261507, 0x00261508, 0x002a190d, 0x002e190f, 0x002c150c, 0x002c150c, 0x00311b10, 0x00341d10, 0x00331b0d, 0x003c2518, 0x002c1a0f, 0x001e1308, 0x00131006, 0x00080d04, 0x00060e08, 0x00040f08, 0x00031008, 0x00040f08, 0x00070f09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060d0b, 0x00060d0b, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00080f08, 0x00070d08, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040c06, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x000f130b, 0x000f130b, 0x0014180d, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130b, 0x000f130b, 0x000f130b, 0x0014180f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e06, 0x00060f04, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x000b110d, 0x00181e1a, 0x00242624, 0x00282828, 0x00242424, 0x00242625, 0x00242527, 0x001c2124, 0x001b2021, 0x001f2324, 0x00282a2d, 0x002d2c30, 0x00323135, 0x00323234, 0x00303133, 0x002d2f30, 0x002c2e2f, 0x00262828, 0x002c2c2c, 0x00373333, 0x003f3a3a, 0x00544d4e, 0x00665c5c, 0x00716260, 0x00796864, 0x007e6764, 0x00806863, 0x00806561, 0x00846865, 0x00856c68, 0x008c726e, 0x008f706e, 0x00886864, 0x0084645c, 0x007c594a, 0x00795441, 0x007c563e, 0x00754d33, 0x00704729, 0x00684020, 0x00643c1c, 0x00633a1c, 0x00653d1e, 0x00673d1e, 0x0064391a, 0x00603414, 0x005e330e, 0x0063370d, 0x0065370c, 0x0067380d, 0x0069360c, 0x006a360b, 0x006c360b, 0x006e380c, 0x00713b0f, 0x00733c0c, 0x00733d0b, 0x0077400b, 0x0078420c, 0x0078420c, 0x0078410c, 0x007c430d, 0x007c440c, 0x0080450f, 0x00844910, 0x0081460e, 0x0083480e, 0x00854911, 0x00844711, 0x00804510, 0x007b400f, 0x007b4010, 0x007a3f10, 0x00763d0d, 0x00733c0c, 0x006e3b09, 0x006c3808, 0x006b3909, 0x0068390c, 0x0060340a, 0x00592f08, 0x00552c09, 0x00502909, 0x004c2809, 0x004a270a, 0x004a270c, 0x0049280c, 0x004a280a, 0x004b2a09, 0x004c2909, 0x004f2809, 0x00512708, 0x00522807, 0x00532908, 0x00572d0a, 0x00582e0b, 0x005c3310, 0x005c340e, 0x0059300a, 0x00582d08, 0x00582c08, 0x005c2f09, 0x0060340c, 0x0064360c, 0x00693a0c, 0x006f3f10, 0x00754312, 0x007a4516, 0x007c4617, 0x007a4513, 0x00784210, 0x00784212, 0x00794314, 0x00784414, 0x00784010, 0x00733d10, 0x005c300e, 0x003b1b02, 0x002b0f01, 0x00261105, 0x00261409, 0x002c180c, 0x002f1b0d, 0x00321e10, 0x0030180c, 0x0034180d, 0x0031180c, 0x00371d11, 0x00382012, 0x00301808, 0x00381f13, 0x00301d12, 0x001a0f04, 0x00100c03, 0x00080d04, 0x00060e08, 0x00040f08, 0x00031008, 0x00040f08, 0x00070f0a, 0x00050d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060f08, 0x00070e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x000f130b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x00191c0b, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00071007, 0x00040e04, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x000a110c, 0x001b201c, 0x00242624, 0x00242323, 0x00201f20, 0x001d1e1e, 0x00202123, 0x00202426, 0x00222729, 0x00272a2c, 0x00303134, 0x002e2d31, 0x00303033, 0x00323032, 0x00303032, 0x002b2b2b, 0x002a2b2b, 0x00282828, 0x002b2b2a, 0x00343030, 0x003e3939, 0x00565050, 0x006b5f60, 0x00756665, 0x007b6864, 0x007e6864, 0x00816864, 0x00806664, 0x00816866, 0x00846d68, 0x008c736f, 0x008a6e6c, 0x007c5f59, 0x00785950, 0x006d503f, 0x006c4d3a, 0x00694834, 0x006b4630, 0x00654328, 0x00664428, 0x00634225, 0x005c3b1e, 0x00603c1f, 0x00603d20, 0x00603c1e, 0x005c3818, 0x005c3613, 0x005c3612, 0x005c340e, 0x005b310c, 0x00643711, 0x0063360f, 0x0061340b, 0x0063340c, 0x0063350c, 0x00693b0f, 0x006d3e10, 0x006c3d0d, 0x006f3f0c, 0x00723e0e, 0x00743e0c, 0x0075400e, 0x00794110, 0x007b4310, 0x007b420f, 0x007b420e, 0x007c430e, 0x007c440e, 0x007d4410, 0x007a4210, 0x00743d0e, 0x006f390c, 0x006e3810, 0x0069360f, 0x0068380e, 0x0061340a, 0x005e3207, 0x005d3308, 0x005d350c, 0x005a340f, 0x00552f0e, 0x00522c0f, 0x004e2a10, 0x004b2910, 0x0046240b, 0x0045230c, 0x0045240c, 0x0048280e, 0x004b2910, 0x00502c14, 0x00522a10, 0x00502809, 0x00532909, 0x00542808, 0x00552908, 0x005d310f, 0x00643816, 0x005c300d, 0x00572c09, 0x00562c08, 0x005b300c, 0x005c300d, 0x005a2f0a, 0x005d330b, 0x00603409, 0x0064390c, 0x006c3e10, 0x00754416, 0x00794418, 0x00794314, 0x00784112, 0x00784112, 0x00794314, 0x00794412, 0x0078410f, 0x00703b0b, 0x00633711, 0x00442509, 0x002f1301, 0x00261106, 0x0027140c, 0x0029140a, 0x002c160b, 0x002f170b, 0x00321708, 0x00371b09, 0x00341808, 0x003f2517, 0x00351c0e, 0x00301609, 0x00381f14, 0x00342016, 0x00180c02, 0x000f0c04, 0x00080e07, 0x00051008, 0x0005100a, 0x0004100a, 0x0005100a, 0x00070f08, 0x00050d06, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040d07, 0x00050d07, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180b, 0x00191c0b, 0x0014180a, 0x00191c0a, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x00191c0a, 0x00141809, 0x00191c0b, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00060c08, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00071007, 0x00040e04, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e06, 0x00060e06, 0x00060e06, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00080f0a, 0x00121714, 0x00212321, 0x00232222, 0x00222222, 0x00262827, 0x00292b2c, 0x002c2f31, 0x002d3334, 0x00323538, 0x00343538, 0x00323034, 0x00323134, 0x00353336, 0x002c2b2d, 0x002b2b2b, 0x002b2b2b, 0x00282928, 0x002c2c2a, 0x00363332, 0x00413d3c, 0x00595352, 0x006e6262, 0x00796866, 0x007c6864, 0x007f6864, 0x00806964, 0x00806664, 0x00826967, 0x00846d68, 0x00846c69, 0x007c615e, 0x00755953, 0x006f5348, 0x006e5440, 0x006e5440, 0x00674a37, 0x0061422d, 0x005b3e25, 0x00573a20, 0x005a3c20, 0x005c3e22, 0x005a3c1e, 0x00583a1c, 0x0058391b, 0x00573718, 0x00583817, 0x00583513, 0x00573211, 0x00593412, 0x00583210, 0x0057300d, 0x0058320e, 0x005c3410, 0x005c3410, 0x005e350f, 0x00613810, 0x0063380d, 0x00643a0c, 0x0069380e, 0x006c380e, 0x006c3910, 0x00703b12, 0x00723d0f, 0x00743e0c, 0x0075400f, 0x00773f0f, 0x0076400c, 0x0074400c, 0x00713f0c, 0x006d3c0d, 0x0066370c, 0x00623410, 0x005c310e, 0x005a300d, 0x0059340c, 0x00573109, 0x00553209, 0x00563610, 0x00563614, 0x004d2d0f, 0x004a2a0e, 0x0044240c, 0x003d2009, 0x003c1d06, 0x003c1b04, 0x003c1d04, 0x003f2008, 0x0041220c, 0x00482511, 0x0049240c, 0x004e2708, 0x00542a08, 0x005b2f0d, 0x005c2f0d, 0x005a2e0c, 0x005a2f0c, 0x005c300c, 0x005d320d, 0x005d330c, 0x00603410, 0x005c3310, 0x00542b05, 0x005b310b, 0x005d340a, 0x0062390d, 0x00693f11, 0x00734317, 0x00754117, 0x00784014, 0x00774011, 0x00784112, 0x007a4414, 0x007b4514, 0x007b440d, 0x00733d0a, 0x00693c15, 0x004a2b0c, 0x00321701, 0x00271105, 0x0028150d, 0x0029140d, 0x002e160d, 0x0033190d, 0x00381c0b, 0x003b1e08, 0x003d230f, 0x003a2111, 0x002c1406, 0x002c1408, 0x00361f14, 0x00382419, 0x00140b00, 0x00100c06, 0x00081008, 0x00051008, 0x0005100a, 0x0004100a, 0x0005100a, 0x00071008, 0x00050e04, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00040c06, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050f08, 0x00050f08, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060d04, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180e, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x001d200a, 0x00191c09, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2008, 0x00202309, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d200a, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c0a, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d08, 0x00040d08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00050e06, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00070e09, 0x000a100c, 0x00181c1a, 0x00252726, 0x00292b2a, 0x002c2d2c, 0x002a2e2c, 0x002b2e2f, 0x002e3132, 0x00353738, 0x0039393b, 0x00353235, 0x00343033, 0x002f2d2e, 0x002c2a2b, 0x00302f2f, 0x00302f2e, 0x00302e2d, 0x00323030, 0x00383735, 0x00413e3e, 0x005c5454, 0x00736464, 0x007b6967, 0x007d6964, 0x007f6964, 0x00816866, 0x00806865, 0x00816a67, 0x00846d6b, 0x00836b6a, 0x007a615d, 0x00735a50, 0x006a5345, 0x0067503c, 0x0068503b, 0x00664c39, 0x00604530, 0x0062472f, 0x00604429, 0x005d4024, 0x005a3b1d, 0x00533517, 0x00503314, 0x004e3214, 0x00513415, 0x00523412, 0x00583714, 0x005b3918, 0x00543314, 0x004d2c0d, 0x004e2c0c, 0x00523010, 0x00523010, 0x00543412, 0x0054340f, 0x0058350e, 0x0059360c, 0x005b360b, 0x005f340a, 0x0063340a, 0x0065360b, 0x006a390d, 0x006c3a10, 0x00703c12, 0x00764214, 0x007a4514, 0x00794311, 0x00743e0d, 0x00703c0c, 0x006b3c0e, 0x0062360a, 0x0059310b, 0x00552f0a, 0x00573410, 0x00573411, 0x00573310, 0x00502d0c, 0x004c2a0c, 0x00442609, 0x003b2007, 0x00381c08, 0x00341a08, 0x00331a09, 0x00361c0c, 0x00341a08, 0x00391e0b, 0x00391f0b, 0x00442917, 0x00482c18, 0x0050331a, 0x00503111, 0x0054340e, 0x005a340e, 0x005c340e, 0x005c320d, 0x005e3410, 0x005e350e, 0x005e350e, 0x005e350e, 0x0060340f, 0x005b310c, 0x005b310c, 0x005c320d, 0x005d340c, 0x005e3710, 0x00643c14, 0x006b3e15, 0x006e3f14, 0x00734012, 0x00784112, 0x00794314, 0x007b4516, 0x007d4816, 0x007e4711, 0x007a4310, 0x006f3f15, 0x00562d0f, 0x00381700, 0x002b1304, 0x0025140c, 0x0027130d, 0x002e170c, 0x00351c0f, 0x003e200e, 0x0040200c, 0x00412713, 0x00301808, 0x00281104, 0x00281007, 0x00382016, 0x00372418, 0x00130d03, 0x000a1007, 0x00051008, 0x0005100a, 0x00060f0a, 0x0005100a, 0x0004100a, 0x00051007, 0x00040e04, 0x00040f04, 0x00040f06, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00050e07, 0x00050e07, 0x00060e08, 0x00050e07, 0x00040f06, 0x00050f07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00030c08, 0x00030c08, 0x00030c08, 0x00030c08, 0x00040e08, 0x00040e08, 0x00040d08, 0x00040d08, 0x00040e08, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060f09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00060e08, 0x00060e07, 0x00060e08, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00030c04, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00060d07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00050c06, 0x00040c07, 0x00070e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2009, 0x001d2008, 0x001d2008, 0x00202308, 0x00202308, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202308, 0x00202308, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c09, 0x00191c0a, 0x00191c0a, 0x00191c0c, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d05, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x000b100d, 0x001c201f, 0x002c302f, 0x00323534, 0x00303434, 0x00303334, 0x00333737, 0x00343536, 0x00313032, 0x002c282a, 0x00292528, 0x002e2c2c, 0x00333030, 0x00343231, 0x00353432, 0x00333130, 0x00353432, 0x00393836, 0x00413e3e, 0x005f5454, 0x00746463, 0x007c6966, 0x007d6a64, 0x00806964, 0x00816866, 0x00826967, 0x00806966, 0x00806865, 0x007a6261, 0x00745c58, 0x006f584f, 0x00695445, 0x0066503d, 0x0068503c, 0x00664c38, 0x00614630, 0x005e4129, 0x005d4024, 0x00604022, 0x00684427, 0x00644121, 0x005c3c1d, 0x00563818, 0x00543716, 0x00543714, 0x00563816, 0x005a3c1c, 0x0056381b, 0x00503114, 0x0046290d, 0x00422509, 0x0043260a, 0x00452a0c, 0x004c3210, 0x00533612, 0x00583914, 0x005a3912, 0x005c360e, 0x005d340c, 0x0062380c, 0x0064380c, 0x0068380e, 0x006d3c14, 0x00733f13, 0x00764010, 0x0078400f, 0x00753c0c, 0x00703b0d, 0x0068380c, 0x005f340a, 0x0059310a, 0x00542f0a, 0x00522f0e, 0x00502f10, 0x004c2b0c, 0x00462408, 0x00402108, 0x00371a03, 0x00341c07, 0x002f1907, 0x00291707, 0x00271708, 0x00261609, 0x00281708, 0x00281507, 0x002e1b0b, 0x002f1c0c, 0x0034200d, 0x003c240f, 0x00442c10, 0x004c3112, 0x00533313, 0x00563312, 0x00583210, 0x005b3512, 0x005b3611, 0x005c3710, 0x005c3510, 0x005e3410, 0x005c320d, 0x005c320d, 0x005b310c, 0x005b310c, 0x005b330f, 0x00603614, 0x00673b14, 0x006c3f13, 0x00734113, 0x007a4414, 0x007b4514, 0x007c4516, 0x007e4817, 0x007e4713, 0x007c4411, 0x00724016, 0x00603213, 0x00401c04, 0x002c1403, 0x00241309, 0x0024130a, 0x002b1609, 0x00331c0c, 0x003f2010, 0x00472615, 0x00381b09, 0x002c1301, 0x002b1003, 0x002c1108, 0x003d2418, 0x00362317, 0x00121005, 0x00081209, 0x0004110b, 0x0006100c, 0x00080f0b, 0x0005100a, 0x0004100a, 0x00040f08, 0x00040e05, 0x00040f05, 0x00040f06, 0x00040d07, 0x00040c08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00050e07, 0x00040f05, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00060d07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00040c06, 0x00030d06, 0x00051008, 0x00040f08, 0x00040f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180e, 0x0014180b, 0x0014180b, 0x00191c0b, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2008, 0x001d2008, 0x00202308, 0x00202309, 0x00202309, 0x0024250b, 0x0024250b, 0x0024250b, 0x0024250c, 0x0024250c, 0x0026280c, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280c, 0x0026280c, 0x0024250c, 0x0024250c, 0x0024250b, 0x0024250b, 0x0024250b, 0x0024250b, 0x00202309, 0x00202309, 0x00202308, 0x001d2008, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c09, 0x00191c0a, 0x00191c0c, 0x0014180b, 0x0014180c, 0x0014180d, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00050d08, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00070f0b, 0x00111815, 0x00282d2b, 0x00343936, 0x00313534, 0x00303334, 0x00363638, 0x00373838, 0x00302e30, 0x00322e30, 0x00332f30, 0x00333030, 0x00343030, 0x003a3535, 0x00393635, 0x003b3938, 0x00363433, 0x00353331, 0x00403c3b, 0x00605456, 0x00746363, 0x007d6966, 0x00806a64, 0x00816965, 0x00826967, 0x00826868, 0x007e6764, 0x007a6460, 0x00735c59, 0x006d5652, 0x006e5850, 0x00685348, 0x00654e3f, 0x00674e3c, 0x00674d38, 0x00644830, 0x005f4226, 0x005e3d20, 0x00623e1e, 0x00643e1e, 0x00623c1c, 0x005d3b1c, 0x005a381a, 0x0059391a, 0x00563919, 0x004d3214, 0x004a2e14, 0x00442a10, 0x00402510, 0x003c230d, 0x00381f0c, 0x0038200c, 0x0039220b, 0x003b250b, 0x0040270a, 0x00472c0e, 0x004e3112, 0x00553412, 0x005a3511, 0x00623c17, 0x00603810, 0x0063350c, 0x006c3c11, 0x00744012, 0x00774310, 0x007a4310, 0x00743c0c, 0x006f3a0c, 0x0067380a, 0x005e3408, 0x00583008, 0x00522c0a, 0x004b270b, 0x0048260c, 0x00402209, 0x003a1d08, 0x00351a06, 0x002c1503, 0x00261403, 0x00221302, 0x001d1104, 0x001a1105, 0x00191407, 0x001c170b, 0x00160f03, 0x00180e02, 0x00140b00, 0x00190f02, 0x00201104, 0x00261606, 0x0033210e, 0x003f2812, 0x00472c16, 0x004c3017, 0x00513518, 0x00533414, 0x00523410, 0x00563412, 0x005a3413, 0x005a3311, 0x005b3210, 0x0059300e, 0x00582f0c, 0x0058300f, 0x005e3412, 0x00663a14, 0x006c3f13, 0x00714011, 0x00774012, 0x00784313, 0x007b4415, 0x007d4718, 0x007c4716, 0x007b4412, 0x00734014, 0x00663714, 0x00462105, 0x002e1402, 0x00261509, 0x00241409, 0x002a1508, 0x00321809, 0x003f2011, 0x004a2819, 0x00381808, 0x00341405, 0x00341405, 0x00321404, 0x00422518, 0x00332015, 0x00110e05, 0x0008120c, 0x0004120c, 0x0008100c, 0x00090f0c, 0x0008100b, 0x0005100b, 0x00051009, 0x00040f07, 0x00051008, 0x00051008, 0x00050d09, 0x00040c09, 0x00060d0a, 0x00060d0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f07, 0x00070f08, 0x00070f08, 0x00060f08, 0x00040f05, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00041008, 0x00041008, 0x00041008, 0x00050f08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00050d07, 0x00050d07, 0x00040c07, 0x00040c07, 0x00040d07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x00202308, 0x0024250b, 0x0024250b, 0x0024250c, 0x0026280c, 0x0026280b, 0x0026280b, 0x00292b0b, 0x0026280a, 0x00292b0b, 0x00292b0b, 0x00292b0a, 0x002c2d0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x00292b0a, 0x002c2d0a, 0x002c2d0b, 0x00292b0b, 0x00292b0b, 0x0026280a, 0x00292b0b, 0x0026280a, 0x00292b0b, 0x0026280b, 0x0026280b, 0x0026280b, 0x0026280c, 0x0024250c, 0x0024250b, 0x0024250b, 0x00202309, 0x001d2008, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c09, 0x00040c09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d09, 0x0008100d, 0x00161d1a, 0x002c322e, 0x00383d3c, 0x00383a3c, 0x003d3d3f, 0x00363636, 0x00323031, 0x00343032, 0x00383435, 0x00383434, 0x00363130, 0x00383232, 0x00393535, 0x003b3838, 0x00343332, 0x00343130, 0x00433f3e, 0x00645758, 0x00756162, 0x007f6966, 0x00816a65, 0x00836a66, 0x00826967, 0x00826968, 0x00806868, 0x007d6663, 0x006e5851, 0x0068514b, 0x00665048, 0x00644d44, 0x0061493c, 0x00644938, 0x00654b34, 0x00654b2f, 0x00634425, 0x00613f1e, 0x0065401c, 0x00663d1b, 0x00643b1a, 0x005f381a, 0x005c3819, 0x00593718, 0x00513415, 0x00442d12, 0x003c260e, 0x00301905, 0x002e1807, 0x002b1808, 0x002b1809, 0x002d190b, 0x002d1a0a, 0x00301e0a, 0x00341f08, 0x00372008, 0x003d240c, 0x0046290c, 0x004f2f0f, 0x005c3a19, 0x005e3815, 0x00683c14, 0x00714013, 0x00744110, 0x0076400b, 0x0078400c, 0x00743b0b, 0x006e390c, 0x006a3b0d, 0x0061360b, 0x00593109, 0x00542d0c, 0x0049240c, 0x00401f0b, 0x00381c08, 0x00311a06, 0x00291504, 0x00241303, 0x00201304, 0x001e1406, 0x001b1206, 0x00181208, 0x0017140b, 0x0018160f, 0x00141009, 0x00110d04, 0x000f0e07, 0x000a0a03, 0x000d0c06, 0x00140f09, 0x0018100b, 0x00170c01, 0x00231407, 0x002c1c08, 0x0038230b, 0x00442c10, 0x004c3113, 0x004c2e11, 0x00523113, 0x00543010, 0x00542e0f, 0x00542f0f, 0x00563010, 0x00593210, 0x005f3513, 0x00643911, 0x006c4013, 0x00744314, 0x00794314, 0x00794313, 0x007c4517, 0x007e481b, 0x007d4719, 0x007c4414, 0x00733f12, 0x006a3b14, 0x004b2708, 0x00341a04, 0x002c1a0b, 0x00281709, 0x002b1609, 0x0032180b, 0x00402011, 0x004c2819, 0x00421d10, 0x003e190c, 0x003c1808, 0x003d1907, 0x004c2b1c, 0x002f1c10, 0x00121008, 0x0008120e, 0x0005130c, 0x0008100d, 0x0009100c, 0x0008100b, 0x0005110b, 0x0006100b, 0x00041009, 0x00051009, 0x00051009, 0x00060d0b, 0x00050d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060f07, 0x00060f08, 0x00060e08, 0x00060f08, 0x00040f05, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040f08, 0x00021008, 0x00021008, 0x00021008, 0x00041008, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00070f08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040d06, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c09, 0x00191c09, 0x001d2008, 0x00202308, 0x00202308, 0x0020230a, 0x0024250b, 0x0024250b, 0x0026280b, 0x00292b0b, 0x00292b0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x002d2f0b, 0x0030310c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x002d2f0c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x002d2f0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x00292b0a, 0x00292b0a, 0x002c2d0a, 0x00292b0b, 0x00292b0b, 0x0026280b, 0x0026280c, 0x0024250c, 0x0024250b, 0x00202309, 0x00202308, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f09, 0x00060e08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c09, 0x00040c09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00040d08, 0x00040d08, 0x00040d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d06, 0x00050d06, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c07, 0x00070c07, 0x00070c07, 0x00070c07, 0x00070c07, 0x00050c07, 0x00050c07, 0x00040d07, 0x00040e07, 0x00040c08, 0x00040c08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00060e0a, 0x00060e0a, 0x00060e0a, 0x00060f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050e08, 0x00050e08, 0x00050d09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040d09, 0x00040d09, 0x00040d09, 0x00040d09, 0x00040d09, 0x00040d09, 0x00050e0a, 0x000b1410, 0x00141c18, 0x00272f2a, 0x00383d39, 0x00393c3c, 0x00404040, 0x00393838, 0x00343132, 0x00343032, 0x00373233, 0x003d3836, 0x003d3836, 0x003b3735, 0x003d3a39, 0x00373534, 0x00383635, 0x00373332, 0x00454040, 0x0066595b, 0x00766363, 0x007f6866, 0x00826b66, 0x00846c67, 0x00826968, 0x00836a69, 0x00846c6a, 0x007d6560, 0x006e5850, 0x00654f47, 0x00644d45, 0x00614b43, 0x0060483a, 0x00624834, 0x0064472e, 0x00634526, 0x00654420, 0x00603f1a, 0x005e3a15, 0x005f3b14, 0x005e3816, 0x00583416, 0x004d2d11, 0x0043250c, 0x00341c04, 0x00241400, 0x00231304, 0x001a0b00, 0x00201105, 0x00211207, 0x00231409, 0x0025160b, 0x0027180b, 0x00281909, 0x002c1b08, 0x00301c08, 0x00341e0a, 0x00381e07, 0x0043240a, 0x00543113, 0x00613c19, 0x006f421a, 0x00784417, 0x00784210, 0x007b410b, 0x007c420c, 0x00783f0c, 0x00743d0a, 0x00703e0b, 0x00693908, 0x0062340c, 0x0059300d, 0x0049240b, 0x003e1d0b, 0x00301a07, 0x00281403, 0x00241304, 0x00221207, 0x0022150b, 0x001d1108, 0x001c1109, 0x001f150d, 0x00231a14, 0x002c231c, 0x00211811, 0x001d140d, 0x0014100c, 0x0010110f, 0x00292825, 0x00120f0c, 0x001c130f, 0x0020140d, 0x002c1d14, 0x00261507, 0x00200d00, 0x00281300, 0x00321b04, 0x0039200c, 0x003f240c, 0x0042250c, 0x0045270c, 0x0049280c, 0x004e2c10, 0x00563011, 0x00603712, 0x00643910, 0x006c3f10, 0x00754312, 0x00794210, 0x007a4312, 0x007c4517, 0x007e471b, 0x007d461b, 0x007c4315, 0x00713c10, 0x006d3d13, 0x00522d09, 0x003a1d02, 0x00311c09, 0x002c190b, 0x002c170b, 0x0031180a, 0x003f1f10, 0x004c2819, 0x004f2618, 0x00471d0d, 0x00431908, 0x004d2412, 0x00533020, 0x0028170e, 0x0010110d, 0x0009110f, 0x0008110f, 0x00081010, 0x0009100f, 0x0007100c, 0x0005110b, 0x0006110b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f0b, 0x00050d0a, 0x00050d0a, 0x00050d0a, 0x00050d09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040f07, 0x00040f07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d09, 0x00040d09, 0x00040e0a, 0x00040e0a, 0x0005100a, 0x00050f0a, 0x00040f09, 0x00040e08, 0x00040f08, 0x00041008, 0x00041008, 0x00041008, 0x00040f08, 0x00060e09, 0x00050d09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060d08, 0x00060d08, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d06, 0x00050d06, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e08, 0x00040e08, 0x00040e08, 0x00040e08, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00060c07, 0x00060c07, 0x00050c06, 0x00050c06, 0x00060c04, 0x00060c04, 0x00060c04, 0x00060c05, 0x00050c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x0020230a, 0x0024250c, 0x0026280c, 0x0026280b, 0x00292b0a, 0x00292b0a, 0x002d2f0a, 0x002d2f0b, 0x0030310c, 0x0030310c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0034350c, 0x0034350c, 0x0032330c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0b, 0x0026280a, 0x0026280b, 0x0024250b, 0x0024250b, 0x00202309, 0x00202308, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c09, 0x0014180a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e0b, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x0008100c, 0x000d1510, 0x001c2420, 0x00323834, 0x0030322f, 0x00383735, 0x003f3a3c, 0x00342e30, 0x00363031, 0x00363030, 0x00403837, 0x00413c39, 0x00373430, 0x00393837, 0x003a3837, 0x00393535, 0x00383333, 0x00464040, 0x0066595b, 0x00776464, 0x007f6867, 0x00836b66, 0x00856c68, 0x00836a68, 0x00836a69, 0x00806766, 0x00765e58, 0x0071594f, 0x006b5248, 0x00674e44, 0x00644c3f, 0x00644a39, 0x00634631, 0x0064452b, 0x00634224, 0x0060401c, 0x00593916, 0x00553713, 0x00563815, 0x00482b0d, 0x00381f05, 0x00291502, 0x001c0d00, 0x00140900, 0x00130b03, 0x00140c04, 0x00171007, 0x001c140a, 0x0024170e, 0x0023150c, 0x0021140a, 0x0021140a, 0x00241409, 0x0028170b, 0x002b170a, 0x00311b0d, 0x00391e0d, 0x00462711, 0x00543114, 0x0068401f, 0x00784822, 0x00824c1f, 0x00884c1a, 0x008f5018, 0x00915118, 0x008c4f15, 0x00884c13, 0x00844c11, 0x007b440d, 0x006b370a, 0x005f300b, 0x00512a0c, 0x00432109, 0x00331b07, 0x00291502, 0x00281404, 0x00251508, 0x0023140b, 0x00201009, 0x0022110b, 0x00281810, 0x00302015, 0x003d2d21, 0x00372619, 0x002e1c10, 0x002c1f14, 0x00251d14, 0x002c2118, 0x002c1e12, 0x002d1c0d, 0x003b2113, 0x00482e1c, 0x00402814, 0x0037200b, 0x002c1401, 0x00291000, 0x002f1705, 0x00321a06, 0x00341a06, 0x00391d06, 0x0048270f, 0x004f2c12, 0x005a3310, 0x00653b14, 0x006a3d10, 0x00704010, 0x00774410, 0x007b4410, 0x007b4313, 0x007c4417, 0x007f471a, 0x007d461b, 0x007b4216, 0x00713c0f, 0x006d3c10, 0x005c330c, 0x00401f00, 0x00361b05, 0x002e1909, 0x002f190d, 0x0033190c, 0x0040200f, 0x004e2916, 0x00562c18, 0x004c200d, 0x00491d09, 0x005d311c, 0x004e2c1a, 0x001f120c, 0x000e1311, 0x000a120f, 0x000c1010, 0x00091111, 0x00091110, 0x0008110e, 0x0006120b, 0x0006120a, 0x0004100a, 0x0005110b, 0x0005110b, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040f07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060d03, 0x00060d04, 0x00060c06, 0x00040b04, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280c, 0x0026280b, 0x00292b0a, 0x002c2d0a, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0034350c, 0x0036370c, 0x0036370c, 0x0036370c, 0x0036370c, 0x0036370b, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0036370c, 0x0036370c, 0x0036370c, 0x0038380c, 0x0038380c, 0x0036370c, 0x0034350c, 0x0034350c, 0x0034350c, 0x0032330c, 0x0034350c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x00292b0a, 0x00292b0b, 0x0026280b, 0x0024250b, 0x0024250b, 0x00202309, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e0b, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00040c08, 0x00040c08, 0x00050e09, 0x0008100b, 0x0009110c, 0x00141c17, 0x002b302c, 0x0030332e, 0x00343330, 0x00423b3b, 0x00312828, 0x00322828, 0x00322928, 0x00372e2c, 0x00403935, 0x003d3938, 0x003c3a39, 0x003c3c3b, 0x003b3838, 0x00373131, 0x00484142, 0x00655658, 0x00796464, 0x00806a68, 0x00846b67, 0x00866c69, 0x00846a68, 0x00826868, 0x007c6262, 0x00735954, 0x00705649, 0x006c5345, 0x00684d40, 0x00654a3b, 0x00644837, 0x005e432f, 0x00593d24, 0x00553920, 0x0054381c, 0x004c3316, 0x0041280c, 0x002e1500, 0x00261200, 0x001c0d01, 0x00170c03, 0x00100a04, 0x001d1a19, 0x001f1c1c, 0x00120e08, 0x00181104, 0x00241a0a, 0x002d2011, 0x0028170c, 0x0026160e, 0x0022130c, 0x00211108, 0x00261409, 0x00281409, 0x002d180b, 0x003c2010, 0x004b2a14, 0x00553315, 0x006e4623, 0x00825029, 0x008a5226, 0x0092551f, 0x009a581a, 0x009c5b18, 0x00985615, 0x00945314, 0x00905014, 0x00844a10, 0x00733a09, 0x00633206, 0x00562c09, 0x00482407, 0x003a1c04, 0x00301701, 0x002f1804, 0x002c1706, 0x002b1608, 0x002c1508, 0x002d1408, 0x002e1508, 0x00331b0b, 0x003f2414, 0x00402715, 0x00361e0c, 0x003b2310, 0x00402812, 0x004a3017, 0x004f3217, 0x00543418, 0x00613c20, 0x00654224, 0x00613f1e, 0x00583816, 0x004e2c11, 0x0046250c, 0x00412008, 0x0044240a, 0x00442309, 0x004a2409, 0x004e2608, 0x00582c0d, 0x0062340d, 0x006c3d0f, 0x00744012, 0x00774310, 0x007b4511, 0x007c4511, 0x007c4512, 0x007c4416, 0x007d4519, 0x007d461b, 0x007c4318, 0x00733c10, 0x006f3c10, 0x0061340c, 0x00482300, 0x00391c04, 0x00301907, 0x00311b0e, 0x00351b0c, 0x003f1f0c, 0x004d2811, 0x00583017, 0x0050240c, 0x004b2006, 0x005f341a, 0x00462512, 0x001c130c, 0x000c1513, 0x00081310, 0x000c1210, 0x00091213, 0x000a1211, 0x0008120f, 0x0007130c, 0x0006120b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040f07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060d04, 0x00060d04, 0x00060c06, 0x00060c07, 0x00040b05, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280b, 0x00292b0b, 0x002c2d0a, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0032330c, 0x0034350c, 0x0038380c, 0x0038380c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x003b3c0d, 0x003b3c0d, 0x003b3c0c, 0x003b3c0d, 0x003b3c0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003c3e0d, 0x003b3c0d, 0x003b3c0d, 0x003c3e0d, 0x003b3c0c, 0x003c3e0d, 0x003b3c0d, 0x003b3c0d, 0x00393b0d, 0x003b3c0d, 0x00393b0c, 0x0038380c, 0x0038380c, 0x0036370c, 0x0036370c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x002c2d0a, 0x00292b0b, 0x0026280b, 0x0024250b, 0x0020230a, 0x00202309, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e0b, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00050d09, 0x00050d08, 0x0009110d, 0x000c140f, 0x0020241f, 0x0032332f, 0x00312f2b, 0x00443938, 0x00302423, 0x00281d1a, 0x002a1f1b, 0x0028201c, 0x0038302d, 0x0045403f, 0x00403e3f, 0x00404040, 0x003d3a3b, 0x00383133, 0x004c4444, 0x00645555, 0x00796564, 0x00806967, 0x00846b68, 0x00866c6a, 0x00846b68, 0x00836768, 0x007e6363, 0x00745954, 0x006c5144, 0x00674c3c, 0x00684b3c, 0x00634537, 0x005e402f, 0x00543925, 0x004d3420, 0x00432c17, 0x0034200b, 0x002b1904, 0x002e1c08, 0x00301e09, 0x0033200f, 0x00291b0c, 0x0022170d, 0x0019140c, 0x0022201f, 0x00242322, 0x00261f17, 0x00231808, 0x003a2b16, 0x003a2a15, 0x002a1706, 0x00251207, 0x00210f06, 0x00211006, 0x00271408, 0x002c1709, 0x002e1808, 0x003e2110, 0x004e2d18, 0x005b3518, 0x00724926, 0x0085532c, 0x008c5526, 0x00985c24, 0x00a3621e, 0x00a7641a, 0x00a45e15, 0x00a15a18, 0x00995415, 0x008c4b10, 0x00783e09, 0x00683505, 0x005a2e07, 0x004f2806, 0x00432005, 0x00381900, 0x003b1d06, 0x003a1e0a, 0x003c1d0b, 0x003e1e0c, 0x003f1e0c, 0x003f1d0b, 0x003e1d09, 0x0046240f, 0x004d2c15, 0x0054321b, 0x0058361c, 0x005e3a1b, 0x00653e1c, 0x006a421e, 0x00683f1a, 0x00623813, 0x00613810, 0x00643b10, 0x0060380d, 0x005d3410, 0x005d3412, 0x005c3512, 0x005f3814, 0x00643816, 0x00693c16, 0x006b3a13, 0x006e3c13, 0x00744110, 0x007c4814, 0x00804915, 0x00824914, 0x00814813, 0x007f4812, 0x00804615, 0x007c4413, 0x007b4215, 0x007b4419, 0x00794318, 0x00723c12, 0x00703c11, 0x0064370b, 0x00502803, 0x00422106, 0x00371c08, 0x0033190a, 0x00341908, 0x003f1e08, 0x004d280e, 0x00583014, 0x005a2f10, 0x00502506, 0x005d3414, 0x003e2008, 0x001a140d, 0x00081311, 0x00071512, 0x000b1410, 0x00091213, 0x00091213, 0x00071310, 0x0007130d, 0x0006130c, 0x0005110b, 0x0005110b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00040e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040f07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c08, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280b, 0x00292b0b, 0x002d2f0a, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0036370c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x003c3e0d, 0x003e400d, 0x003e400c, 0x003e400c, 0x0040400d, 0x0040400d, 0x0041420d, 0x0040400d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0041420d, 0x0040400d, 0x0040400d, 0x0040400d, 0x0040400d, 0x0041420d, 0x0040400d, 0x0040400e, 0x0040400d, 0x003e400c, 0x003e400c, 0x003e400c, 0x003e400d, 0x003c3e0d, 0x003b3c0d, 0x00393b0d, 0x00393b0c, 0x0038380c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002c2d0a, 0x002c2d0b, 0x0026280b, 0x0026280b, 0x0024250c, 0x00202309, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c07, 0x0008100c, 0x0008100b, 0x00141a14, 0x002a2d28, 0x002c2924, 0x00413633, 0x00302520, 0x001e120c, 0x0021150f, 0x00231a13, 0x0038302c, 0x004a4545, 0x00444244, 0x00404042, 0x003e3a3b, 0x003e3738, 0x004f4544, 0x00655754, 0x00796765, 0x00806a68, 0x00846c6b, 0x00866c6c, 0x00846969, 0x00836664, 0x007f6360, 0x00765851, 0x006c503d, 0x00664834, 0x005d402c, 0x00583826, 0x004d311d, 0x00432a16, 0x003a2410, 0x00301d0b, 0x00332111, 0x00342313, 0x00392614, 0x0044301b, 0x004b341f, 0x00402912, 0x0034200b, 0x00312010, 0x00302416, 0x0038291c, 0x00342414, 0x0035200c, 0x00402811, 0x003c240b, 0x00301801, 0x00311a07, 0x00321c0a, 0x00301b0a, 0x00351e0c, 0x0038200c, 0x003a200a, 0x0044240f, 0x00543019, 0x005f3618, 0x00744826, 0x0087542e, 0x008f5728, 0x009c6025, 0x00a6661f, 0x00ab6618, 0x00a85f12, 0x00a55b14, 0x009e5414, 0x00924b10, 0x007c410a, 0x006d3807, 0x00633309, 0x00592f0a, 0x0050290a, 0x00482305, 0x004a260c, 0x004b280f, 0x004c2810, 0x004e2810, 0x004f2710, 0x00502810, 0x004f270c, 0x00502a0d, 0x00542c0d, 0x00582f10, 0x005c3312, 0x005f3510, 0x005e340d, 0x0060350c, 0x0063380f, 0x0060350c, 0x0063380e, 0x00653c0f, 0x0064380c, 0x0064370c, 0x0068390f, 0x006c3c11, 0x00714014, 0x007a4819, 0x00804b1b, 0x00804a17, 0x00854c17, 0x008a5118, 0x008c5218, 0x008b5017, 0x00884c16, 0x00864b14, 0x00824913, 0x00814814, 0x007c4414, 0x007a4113, 0x00784115, 0x00744014, 0x00703d12, 0x006e3c11, 0x0065380c, 0x00512802, 0x00452407, 0x003b1e08, 0x00341909, 0x00341909, 0x003c1c08, 0x004a260c, 0x00583012, 0x00643817, 0x005c3010, 0x005c3412, 0x00341901, 0x0016140b, 0x00081514, 0x00071614, 0x000b1510, 0x000a1314, 0x00081412, 0x00071410, 0x0008140f, 0x0004130c, 0x0005110b, 0x0005110b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00040e09, 0x00040d08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0a, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c08, 0x00060c08, 0x00050c07, 0x00050c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250c, 0x0026280b, 0x00292b0b, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003b3c0d, 0x003c3e0d, 0x003e400c, 0x0040400d, 0x0041420d, 0x0043440e, 0x0043440e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0044450e, 0x0043440e, 0x0043440e, 0x0041420e, 0x0041420e, 0x0040400d, 0x0040400d, 0x003e400c, 0x003c3e0c, 0x003c3e0d, 0x00393b0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0b, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0024250c, 0x00202308, 0x00202308, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x0006100a, 0x000c130e, 0x0020241c, 0x002c2c24, 0x003e3731, 0x003e342e, 0x0024180f, 0x001f1208, 0x00281c14, 0x00382d2c, 0x00494444, 0x00464448, 0x00444146, 0x00403b3f, 0x003f3736, 0x004e4340, 0x006d5e5b, 0x007c6b67, 0x007f6a68, 0x00846c6c, 0x00886d70, 0x00866b6c, 0x00846865, 0x0081645c, 0x00765548, 0x006c4b34, 0x0066422c, 0x005c3822, 0x0054321b, 0x0043270f, 0x003e240f, 0x00462e1b, 0x004e3826, 0x00533b2c, 0x00593f2e, 0x005b3e28, 0x005e4025, 0x00614223, 0x00644424, 0x00644524, 0x00634122, 0x00603f20, 0x005c3c1f, 0x0059381f, 0x00512f18, 0x004c2813, 0x0048220e, 0x00442009, 0x00422108, 0x00442509, 0x0045260c, 0x004c2810, 0x00502c12, 0x004e290d, 0x004f2a0d, 0x005f381a, 0x00683c1c, 0x00784725, 0x008b5632, 0x0094592d, 0x00a06228, 0x00a86822, 0x00ab6619, 0x00ac6417, 0x00ae6119, 0x00a95c1a, 0x009c5417, 0x00874a13, 0x00773f0d, 0x006b380c, 0x0063350d, 0x005c330d, 0x00592f0d, 0x00592e10, 0x005e3116, 0x005f3318, 0x005e3116, 0x005c3015, 0x00603419, 0x00603413, 0x00592e0a, 0x00582d07, 0x005a2f09, 0x005c300a, 0x005d300b, 0x005e320c, 0x005c340c, 0x005c360d, 0x005c350d, 0x005c340c, 0x0061350f, 0x00663710, 0x006f3c11, 0x00784415, 0x007c4414, 0x00844918, 0x008b4c17, 0x008e5015, 0x00945418, 0x00985719, 0x00985919, 0x00975718, 0x00935418, 0x008d5017, 0x00884d14, 0x00854913, 0x00834815, 0x007d4412, 0x007b4214, 0x00764114, 0x00713d11, 0x006c3c10, 0x00683a10, 0x0062370c, 0x00502904, 0x003f1d00, 0x00371802, 0x0034180a, 0x00341910, 0x00391a0c, 0x0048240e, 0x00562e10, 0x00663918, 0x00653816, 0x00603718, 0x00331a04, 0x0013130c, 0x00071615, 0x00081517, 0x000c1411, 0x000a1414, 0x00081412, 0x00071411, 0x0005130f, 0x0004130c, 0x0005120c, 0x0007110c, 0x0007110c, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00021009, 0x00021009, 0x00021009, 0x00030f09, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00051007, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0b, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0045470e, 0x0047480e, 0x0047480e, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0048490f, 0x0047480e, 0x0048490e, 0x0047480e, 0x0047480e, 0x0045470e, 0x0045470e, 0x0044450e, 0x0043440e, 0x0041420e, 0x0041420e, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x00292b0a, 0x0026280b, 0x0024250c, 0x00202308, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040d08, 0x00040f09, 0x0006100b, 0x00121911, 0x00242820, 0x0038342f, 0x00463e37, 0x0031241c, 0x00231208, 0x00291811, 0x003c302e, 0x004d4446, 0x0048444a, 0x00464148, 0x00423c40, 0x00403837, 0x004f4440, 0x006c5d58, 0x007b6a66, 0x00806b6a, 0x00846c6f, 0x00886e71, 0x00886e6f, 0x008a6c66, 0x00846257, 0x00744e3c, 0x006e4629, 0x00643c1f, 0x005d3518, 0x00542c0f, 0x00532f12, 0x005e3d23, 0x006c4c35, 0x006c4d39, 0x00694836, 0x0065412d, 0x00664027, 0x00653c20, 0x00643915, 0x00643a13, 0x00653c14, 0x00643c14, 0x00603810, 0x005c340f, 0x00593010, 0x00542b10, 0x00522911, 0x00522810, 0x00552c10, 0x0058300f, 0x00593311, 0x005a3210, 0x00603414, 0x00643716, 0x00623412, 0x00613713, 0x006b401c, 0x00734623, 0x007c4c29, 0x008e5834, 0x00985f33, 0x00a0642c, 0x00a86826, 0x00ad681d, 0x00af671a, 0x00af651a, 0x00aa5e19, 0x009c5514, 0x008d4d14, 0x007d420c, 0x00763f10, 0x006e3b0f, 0x00693b10, 0x0065390f, 0x0062340e, 0x00633411, 0x00673817, 0x006c3c1c, 0x006f401f, 0x006e401c, 0x0070411b, 0x006a3c14, 0x0063340d, 0x0060300a, 0x005f2e08, 0x005e3009, 0x005d300b, 0x005b300b, 0x005b320a, 0x0060350d, 0x0065380f, 0x006a3a12, 0x006f3d13, 0x00774415, 0x00804a18, 0x00874d1a, 0x008d501c, 0x00935417, 0x00955414, 0x00995716, 0x009b5915, 0x009c5915, 0x009a5616, 0x00945315, 0x008f5014, 0x008b4d13, 0x00864912, 0x00834815, 0x007e4514, 0x007b4214, 0x00754013, 0x00703d10, 0x0069390e, 0x0064380e, 0x005a3209, 0x004e2805, 0x003e1d02, 0x00381b07, 0x00321709, 0x0031180e, 0x00381c0d, 0x0046240f, 0x00562e0f, 0x00663a15, 0x00683c18, 0x005f3818, 0x002f1801, 0x0013140c, 0x00081716, 0x00081517, 0x000c1410, 0x000a1513, 0x00081412, 0x00051411, 0x0004140f, 0x0004130c, 0x0005130c, 0x0006100b, 0x0006100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00021009, 0x00021009, 0x00021009, 0x00030f09, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d04, 0x00040d07, 0x00040d07, 0x00040c06, 0x00040c06, 0x00040c06, 0x00040c06, 0x00060e08, 0x00070f08, 0x00050e08, 0x00040d07, 0x00050e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00051007, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180b, 0x00191c0a, 0x00191c08, 0x001d2008, 0x0024250b, 0x0024250b, 0x00292b0b, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0040400d, 0x0043440e, 0x0044450e, 0x0047480e, 0x0048490f, 0x0048490f, 0x00494a0f, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d10, 0x004c4d10, 0x004c4d10, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004c4d10, 0x004c4d10, 0x004c4d10, 0x004c4d10, 0x004d4e10, 0x004c4d10, 0x004c4d0f, 0x004c4d0f, 0x004b4c0f, 0x004b4c0f, 0x004b4c0f, 0x004b4c10, 0x00494a0f, 0x00494a0f, 0x0048490f, 0x0047480e, 0x0045470e, 0x0045470e, 0x0043440e, 0x0041420e, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x003b3c0d, 0x0038380c, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0a, 0x0026280b, 0x0024250c, 0x00202308, 0x001d2008, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040d09, 0x0002100b, 0x00030f09, 0x0008120b, 0x00181d16, 0x002c2c24, 0x00474039, 0x0043342c, 0x002d1911, 0x0028140f, 0x00402f2f, 0x00504449, 0x004a444c, 0x0048404a, 0x00433c42, 0x00413737, 0x004f433f, 0x006b5c57, 0x007a6964, 0x007f6a6a, 0x00826c6f, 0x00866e72, 0x008a6e70, 0x008d6c67, 0x00896152, 0x007e5038, 0x007b4c27, 0x00774721, 0x00764620, 0x0074441f, 0x00774826, 0x007b4e31, 0x007b5036, 0x00795038, 0x00774e36, 0x0071472e, 0x006f4123, 0x006c3e1b, 0x006b3c12, 0x006a3c0e, 0x00673b0c, 0x0064390b, 0x0064390c, 0x0064390d, 0x00643810, 0x00603311, 0x005d3010, 0x005d2f0c, 0x00653610, 0x006a3910, 0x006c3c10, 0x006b3b0f, 0x00703d11, 0x00733e11, 0x00703c0e, 0x00704010, 0x00734417, 0x00794920, 0x00815028, 0x00905c37, 0x00986034, 0x00a0642c, 0x00a96824, 0x00af691f, 0x00b0681c, 0x00b0671a, 0x00ae6418, 0x00a25a12, 0x00944e10, 0x0088470c, 0x00804411, 0x0078400f, 0x00713e0b, 0x006e3c0b, 0x006e3a0c, 0x006e3a10, 0x00703b12, 0x00744017, 0x00754018, 0x00784318, 0x007b471b, 0x007a461b, 0x00774318, 0x00744015, 0x00713e14, 0x006c390f, 0x0068380f, 0x0067390f, 0x00683b0e, 0x006a3b0d, 0x006d3c0e, 0x00723c10, 0x00764010, 0x007f4714, 0x00874e16, 0x008e5118, 0x00935418, 0x00975515, 0x00995714, 0x009d5915, 0x009e5914, 0x009e5914, 0x009c5713, 0x00985412, 0x00915012, 0x008c4e13, 0x00874912, 0x00844815, 0x007d4412, 0x00784012, 0x00743e12, 0x006e3b10, 0x0068380f, 0x0063370f, 0x0058310a, 0x00472404, 0x003c1e04, 0x00391d0b, 0x00301809, 0x00301a0e, 0x00341a0b, 0x0040210b, 0x00542d0c, 0x00673912, 0x006a3d15, 0x00603814, 0x002f1801, 0x0014140c, 0x00081716, 0x00091618, 0x000c1410, 0x00081412, 0x00061514, 0x00071411, 0x0006130f, 0x0004140f, 0x0006120e, 0x0006100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00021009, 0x00021009, 0x00021009, 0x00030f09, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040e04, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00051007, 0x00040e05, 0x00040e05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x0048490f, 0x00494a0f, 0x004b4c0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00515110, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00515110, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x004f5010, 0x004f5010, 0x004d4e0f, 0x004d4e0f, 0x004c4d0f, 0x004c4d0f, 0x004b4c0f, 0x00494a0f, 0x0048490f, 0x0047480e, 0x0045470e, 0x0044450e, 0x0041420e, 0x0040400d, 0x003e400d, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0a, 0x0026280c, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00060c07, 0x00070c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040d09, 0x00030f0b, 0x00030f09, 0x00041008, 0x000d160d, 0x0020211b, 0x003c3630, 0x0050423b, 0x003c271f, 0x002f1813, 0x00463434, 0x0055484c, 0x004d464e, 0x0048414b, 0x00443c41, 0x00403536, 0x004c403c, 0x00695b54, 0x00796865, 0x007e696c, 0x00826c70, 0x00886e73, 0x008c6e70, 0x008f6c65, 0x008a5e4d, 0x00855437, 0x008a582c, 0x008b572c, 0x00885429, 0x00865128, 0x00844f28, 0x0084502f, 0x00835233, 0x00825335, 0x007e5034, 0x00784a2c, 0x00704320, 0x006c3f16, 0x00683c10, 0x00653c0d, 0x00653d0e, 0x00673d10, 0x00653c10, 0x0062380d, 0x0060360c, 0x0061350d, 0x00663810, 0x006f3e13, 0x00784417, 0x00784111, 0x007c4514, 0x007a4511, 0x007d4812, 0x007b440d, 0x007e4810, 0x00804c16, 0x00824f1d, 0x00825022, 0x0088562c, 0x00925d38, 0x00975f33, 0x00a0642b, 0x00aa6924, 0x00af681c, 0x00af6718, 0x00b36a1c, 0x00b1671a, 0x00a65d13, 0x00995110, 0x008e480c, 0x0088480f, 0x0080430c, 0x007b4109, 0x00784008, 0x007c430e, 0x007b4210, 0x00794210, 0x007c4614, 0x007c4412, 0x007c4413, 0x007b4412, 0x007d4714, 0x00814a18, 0x00854e1e, 0x00865120, 0x00824f1c, 0x007c4b18, 0x007b4c19, 0x007a4c18, 0x007c4a18, 0x007f4815, 0x00804814, 0x00854b16, 0x008b5016, 0x0094571a, 0x00935415, 0x00965414, 0x00985413, 0x009f5a18, 0x00a05a17, 0x00a05a14, 0x009e5914, 0x009c5713, 0x00975412, 0x00905111, 0x008d4f14, 0x00894c16, 0x00844917, 0x007e4413, 0x00784213, 0x00743f14, 0x006e3c11, 0x00683810, 0x00623710, 0x0055300a, 0x00442102, 0x003a1c05, 0x00371c0b, 0x0030180a, 0x00301a0c, 0x00341c0c, 0x0040220c, 0x00552d0b, 0x00683910, 0x006c3d14, 0x00603814, 0x00301801, 0x0014140c, 0x00081817, 0x00091618, 0x000b1510, 0x00081412, 0x00061514, 0x00071411, 0x0006130f, 0x0004140f, 0x0005130f, 0x0008130f, 0x0009120e, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040e04, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00051007, 0x00040e05, 0x00040e05, 0x00040d05, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004b4c0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00525310, 0x00535410, 0x00535410, 0x00535410, 0x00545510, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00545510, 0x00545510, 0x00545510, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00525310, 0x00525310, 0x00515110, 0x00515110, 0x00505010, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004c4d0f, 0x004b4c0f, 0x00494a0f, 0x0047480e, 0x0045470e, 0x0043440e, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0024250c, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x00141810, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060c0b, 0x00080c0b, 0x00080d08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00070c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00051008, 0x0008110b, 0x0010140c, 0x002c2821, 0x0051443c, 0x0048352c, 0x0039221c, 0x004c3735, 0x00584b4c, 0x004a4549, 0x00484348, 0x00423a3e, 0x00403534, 0x004b3f3a, 0x00685953, 0x00796867, 0x007d686e, 0x00826b71, 0x00886f74, 0x008d6f71, 0x00906b67, 0x00906454, 0x00946143, 0x00946031, 0x00955f2e, 0x00945b29, 0x00925525, 0x00905425, 0x0090542a, 0x008e542e, 0x008a512d, 0x0085502a, 0x007d4b22, 0x0077441b, 0x00703e14, 0x006c3b0e, 0x006b3a0d, 0x006a3b0c, 0x006a3a0d, 0x006a3a0d, 0x006a3a0e, 0x006a3c0e, 0x00734414, 0x007e4c1b, 0x008a531d, 0x00885019, 0x008c531c, 0x008c531c, 0x008a4f16, 0x00884c10, 0x008a4d0e, 0x00894d11, 0x00874d14, 0x00885020, 0x0089542b, 0x008d5b34, 0x00936039, 0x00955e33, 0x00a0642a, 0x00ac6a23, 0x00af681c, 0x00af6718, 0x00b2691c, 0x00b06419, 0x00a45b10, 0x009a5010, 0x0090490b, 0x008c490d, 0x008a4910, 0x00864810, 0x0080440e, 0x00814510, 0x00814512, 0x00844814, 0x00874c18, 0x00874d18, 0x00844a15, 0x00824814, 0x00824814, 0x00844916, 0x00844a19, 0x00884d1b, 0x00844b17, 0x00834b15, 0x00844c16, 0x00844c17, 0x00854c18, 0x00884c16, 0x008c4e17, 0x00935118, 0x00985418, 0x009b5618, 0x009c5816, 0x009e5b17, 0x00a05a18, 0x00a05c19, 0x00a15c18, 0x009e5915, 0x009c5814, 0x00985410, 0x00945310, 0x00905111, 0x008d4e14, 0x00874c15, 0x00834815, 0x007e4715, 0x00784214, 0x00703c14, 0x006c3911, 0x0066370f, 0x005f340c, 0x00512907, 0x00441f03, 0x003a1a04, 0x00371b0b, 0x0035190d, 0x00321809, 0x00371c0a, 0x00472412, 0x005f3313, 0x006c3c10, 0x00714115, 0x006a401c, 0x00331803, 0x0014140c, 0x00081817, 0x00091618, 0x000c1610, 0x00081513, 0x00071614, 0x00081413, 0x00081410, 0x00051310, 0x00061411, 0x00061311, 0x0005110f, 0x0008110d, 0x0008100d, 0x00070e0c, 0x00060d0b, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f0a, 0x00050e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x0049490f, 0x00605710, 0x00645a10, 0x00645b10, 0x00665d10, 0x00685e10, 0x00685e11, 0x00685f11, 0x00686011, 0x00696012, 0x00696012, 0x00696011, 0x00696111, 0x00696112, 0x00696112, 0x00696011, 0x00696011, 0x00686011, 0x00686012, 0x00686012, 0x00686012, 0x00685f12, 0x00685f11, 0x00686011, 0x00686011, 0x00686012, 0x00685f12, 0x00665e12, 0x00665f11, 0x00655e11, 0x00655e11, 0x00645d11, 0x00645c10, 0x00635b10, 0x00605810, 0x00545210, 0x004d4e10, 0x004d4e10, 0x004c4d0f, 0x004b4c10, 0x0048490f, 0x0045470e, 0x0044450e, 0x0041420e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0024250b, 0x0020230a, 0x001d2008, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060d09, 0x00080c09, 0x00080d09, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00080c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f08, 0x000c100c, 0x00282620, 0x0041372e, 0x00524138, 0x00402a21, 0x0045322c, 0x004f4140, 0x00484042, 0x00494245, 0x0040393b, 0x00403534, 0x004b3f3a, 0x00665852, 0x00786867, 0x007c696f, 0x00816c72, 0x00897074, 0x008d7074, 0x008f6c6a, 0x00906557, 0x00946344, 0x00976336, 0x00996232, 0x00985f2b, 0x00995c28, 0x00995a28, 0x0097592a, 0x00915628, 0x008c5426, 0x00885325, 0x00814c1e, 0x007d481a, 0x007e4819, 0x007d4a19, 0x00784413, 0x00754210, 0x00774412, 0x00784514, 0x007e4b1b, 0x00855220, 0x008c5924, 0x00915d24, 0x00945d23, 0x00915b20, 0x00945b20, 0x00945c20, 0x0093571c, 0x00925516, 0x008f5213, 0x008e5115, 0x008c501b, 0x008c5426, 0x008c5732, 0x00905d3b, 0x0094603b, 0x00935d32, 0x009e6028, 0x00a86720, 0x00ae681b, 0x00ad6617, 0x00b2681d, 0x00af641b, 0x00a45a14, 0x0098510f, 0x00904a0c, 0x008c490e, 0x008a4910, 0x00884a13, 0x00884a13, 0x00884912, 0x00864811, 0x008a4d16, 0x008f521b, 0x0092541e, 0x008f521b, 0x008c5018, 0x008b4e16, 0x00894c17, 0x00874814, 0x00864a15, 0x00864b15, 0x00874c15, 0x00874c15, 0x00884c16, 0x008c5019, 0x008d5017, 0x00935219, 0x0098541b, 0x009a5619, 0x00a25c1d, 0x00a4601d, 0x00a5601c, 0x00a6601d, 0x00a6611d, 0x00a35e1a, 0x009f5a16, 0x00995512, 0x00945110, 0x00935212, 0x00905014, 0x008c4e17, 0x00874a18, 0x00834718, 0x007c4316, 0x00774015, 0x006d3912, 0x00683610, 0x0063340d, 0x005c310c, 0x004f2708, 0x00421c04, 0x00391906, 0x00371b0d, 0x00381c10, 0x00371b0b, 0x003a1a07, 0x00502813, 0x00673814, 0x00734010, 0x00784717, 0x00794c25, 0x00371c05, 0x0014140c, 0x00081817, 0x00091618, 0x000c1610, 0x00081513, 0x00071614, 0x00081413, 0x00081410, 0x00051310, 0x00071411, 0x00061411, 0x0005120f, 0x0008110d, 0x0008100d, 0x00070e0c, 0x00060d0b, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x0014180f, 0x0014180b, 0x0014180a, 0x001d200a, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x00494a10, 0x00836f10, 0x00c39c15, 0x00c69d15, 0x00c69e15, 0x00c69e15, 0x00c59f15, 0x00c59f15, 0x00c59f16, 0x00c59f16, 0x00c59f16, 0x00c59f16, 0x00c49f16, 0x00c49f16, 0x00c49f16, 0x00c49f16, 0x00c49f17, 0x00c49f17, 0x00c49e17, 0x00c49e17, 0x00c49e17, 0x00c49e17, 0x00c49e17, 0x00c49e16, 0x00c49e16, 0x00c49e16, 0x00c49e16, 0x00c39d17, 0x00c39d17, 0x00c39d17, 0x00c39d16, 0x00c29c16, 0x00c29c16, 0x00c29c15, 0x00c19c15, 0x00bd9815, 0x00b19014, 0x00967c13, 0x00665d10, 0x00505010, 0x004d4e0f, 0x004b4c0f, 0x00494a10, 0x0047480e, 0x0044450d, 0x0041420e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060d09, 0x00080c09, 0x00080d09, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00080c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x0008100a, 0x00252620, 0x00322b24, 0x00504238, 0x00543f34, 0x004c362f, 0x004f3f3b, 0x004a3e3e, 0x004c4343, 0x00403838, 0x00403634, 0x00483d3a, 0x00625653, 0x00736766, 0x00786870, 0x00806d74, 0x00877378, 0x008d727a, 0x00906e6f, 0x0091665c, 0x00936349, 0x0098633b, 0x009a6334, 0x00995f29, 0x009b5e25, 0x009d5e28, 0x00985823, 0x0093561f, 0x00915620, 0x008c551e, 0x008c5420, 0x008a511e, 0x00874f1a, 0x00854d18, 0x00854c16, 0x00864e17, 0x0089511b, 0x008b521d, 0x008b531d, 0x008d541f, 0x0090561d, 0x0090571c, 0x00905719, 0x0091581a, 0x0094591c, 0x00975c1e, 0x00965a1c, 0x00945616, 0x00935618, 0x0093551c, 0x00945826, 0x00925830, 0x008e5838, 0x00905c3f, 0x00935f3d, 0x00945e33, 0x009c6027, 0x00a8651e, 0x00ad681b, 0x00aa6314, 0x00b3691f, 0x00af641c, 0x00a25b14, 0x0095500e, 0x008e4c0e, 0x008a4c0f, 0x00894c10, 0x00884b10, 0x00884b10, 0x008a4b11, 0x008b4c12, 0x008d4e12, 0x00915217, 0x0095561a, 0x0098591d, 0x00995a1d, 0x00955619, 0x00925318, 0x008d4d16, 0x00884a14, 0x00884912, 0x00884a12, 0x008a4c15, 0x008f5019, 0x00905019, 0x00925018, 0x00975418, 0x009a5619, 0x009c561a, 0x00a05a1b, 0x00a15c1a, 0x00a4601c, 0x00a86320, 0x00a5601c, 0x00a35e1a, 0x00a05b18, 0x00995514, 0x00935012, 0x00925015, 0x008c4d14, 0x00874914, 0x00814514, 0x007d4214, 0x00784014, 0x00753f15, 0x006c3810, 0x0068350e, 0x0062350c, 0x005c330d, 0x004e280a, 0x003f1c04, 0x00351806, 0x00341c0f, 0x00381c0f, 0x003c1e0e, 0x00421f09, 0x005b2d13, 0x00734018, 0x00834d18, 0x00804b16, 0x007b4b20, 0x00402309, 0x0014150d, 0x00081818, 0x000a1719, 0x000c1713, 0x00091714, 0x00081717, 0x000b1415, 0x00091411, 0x00071411, 0x00081412, 0x00061411, 0x0005120f, 0x0008110d, 0x0008100d, 0x0008100c, 0x00050c0a, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280c, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x00645810, 0x00c49c14, 0x00cca215, 0x00cba116, 0x00caa216, 0x00caa216, 0x00cba216, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba317, 0x00cba216, 0x00cba217, 0x00cca316, 0x00cca316, 0x00cba216, 0x00c49d16, 0x00987e12, 0x005c5710, 0x004f5010, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450d, 0x0041420e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002d2f0b, 0x00292b0a, 0x0026280b, 0x0020230a, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130d, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00060d08, 0x00080d08, 0x00080d08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00080c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f0a, 0x0005100b, 0x00232721, 0x0028251d, 0x0042382c, 0x005e4a3f, 0x00523c32, 0x0054403c, 0x00504040, 0x004e4441, 0x00403835, 0x003d3434, 0x00433a38, 0x005c5452, 0x006f6466, 0x0074666e, 0x007c6c72, 0x00847177, 0x008c737c, 0x00907074, 0x00906a60, 0x0090644c, 0x0094603a, 0x00966032, 0x00996029, 0x009c5f24, 0x009f5d25, 0x009e5d24, 0x009c5d20, 0x00955818, 0x008f5416, 0x008f5419, 0x0090541c, 0x0092551c, 0x008f5118, 0x008e5017, 0x008e5016, 0x00905218, 0x0092541c, 0x0093541c, 0x0094551c, 0x00905417, 0x00905415, 0x00905314, 0x0096581a, 0x00995c1c, 0x009c5f20, 0x009c5f1f, 0x009a5c1b, 0x0096591c, 0x00965822, 0x00965a2f, 0x00945b39, 0x008f583c, 0x00905c44, 0x00915f3f, 0x00935e33, 0x009c6128, 0x00aa6821, 0x00b16b1e, 0x00ab6316, 0x00b0651c, 0x00ac631c, 0x00a05b14, 0x0093500c, 0x008d4c0d, 0x00884a0d, 0x00874b0f, 0x00884b0f, 0x00884b10, 0x0088480c, 0x008e5011, 0x00935214, 0x00985718, 0x009a591a, 0x009d5c1d, 0x009c5c1b, 0x009b5a19, 0x009a581a, 0x0097561a, 0x00935219, 0x00905017, 0x008e4d14, 0x008d4d14, 0x00905017, 0x00905118, 0x00935016, 0x00985318, 0x009c5519, 0x009c5718, 0x00a05a1a, 0x00a15c1a, 0x00a45f1b, 0x00a35e18, 0x00a05a17, 0x009d5814, 0x00995513, 0x00955211, 0x00904e10, 0x008f4e13, 0x00894a12, 0x00834613, 0x007f4212, 0x007b4013, 0x00773f15, 0x00744015, 0x006b3910, 0x0068360e, 0x0063350c, 0x005d330e, 0x004b270b, 0x00391a04, 0x00311706, 0x00321b0f, 0x00381c0f, 0x003d1f0d, 0x004d260e, 0x00663416, 0x00814c1e, 0x0090581f, 0x00854e15, 0x00804e1f, 0x0046280d, 0x0014150d, 0x00081818, 0x000a1719, 0x000c1713, 0x00091714, 0x00081717, 0x000a1415, 0x00091411, 0x00071411, 0x00081412, 0x00061411, 0x0005120f, 0x0008110d, 0x0008100d, 0x0008100c, 0x0008100c, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f0a, 0x00050e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c10, 0x006c5f10, 0x00cca215, 0x00c59e15, 0x00927b13, 0x00927c13, 0x00927c14, 0x00927c14, 0x00937d14, 0x00947e14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f15, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00947f14, 0x00937d14, 0x00937d14, 0x00937d14, 0x00988014, 0x00a68914, 0x00bc9815, 0x00c9a116, 0x00cca316, 0x00cba216, 0x00b69315, 0x006f6210, 0x004f5010, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450d, 0x0041420e, 0x003c3e0c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050c06, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x0020241e, 0x00292a22, 0x00302b1e, 0x005c4c40, 0x00584139, 0x005d413f, 0x00593f40, 0x0054403f, 0x00433634, 0x003d3534, 0x00443b3c, 0x00514a4b, 0x006a6365, 0x0072676e, 0x007a6d73, 0x00817077, 0x00846d77, 0x00896c72, 0x008d6a67, 0x008e6454, 0x00915f41, 0x00925c37, 0x009a6030, 0x009c6027, 0x009e5e25, 0x00a36228, 0x00a66625, 0x00a36421, 0x009b5c1c, 0x0096581a, 0x0098581d, 0x0099581e, 0x0099581c, 0x00975519, 0x00965418, 0x00965519, 0x0096541a, 0x00945318, 0x00905013, 0x00905112, 0x00905212, 0x00975718, 0x009c5c1c, 0x009f5e1f, 0x00a26121, 0x00a1601e, 0x009c5e1c, 0x00995c20, 0x00965c2a, 0x00945d3b, 0x00935d46, 0x008e5a49, 0x008e5e4c, 0x00905f44, 0x00915c34, 0x009a5f28, 0x00a66520, 0x00ab641a, 0x00ab6119, 0x00aa6218, 0x00a96119, 0x00a05c14, 0x0092500c, 0x008b4a0b, 0x0087480c, 0x00864a0f, 0x00864a10, 0x00884a10, 0x008c4c11, 0x00905013, 0x00965314, 0x009b5815, 0x009d5a15, 0x00a05c16, 0x00a3601a, 0x00a35f1c, 0x00a15d1c, 0x009f5c1c, 0x009e5b1f, 0x009c591d, 0x009b581c, 0x00985519, 0x00985418, 0x0099561a, 0x009d581c, 0x00a15d20, 0x009e5a1c, 0x009f5919, 0x00a35d1c, 0x00a15c1a, 0x00a05b18, 0x00a05917, 0x009b5514, 0x00975411, 0x0092500e, 0x00904e0c, 0x008b4b0c, 0x0088480c, 0x0084450f, 0x007f4412, 0x007b4213, 0x00774114, 0x00723f15, 0x006d3c13, 0x00683910, 0x0064360e, 0x00633410, 0x005d3210, 0x004a260c, 0x00351802, 0x002e1605, 0x0030190c, 0x00381c0e, 0x00472411, 0x00592e11, 0x0074401c, 0x00904f20, 0x009c581b, 0x008f5213, 0x00814c1b, 0x004c2d12, 0x0013140b, 0x00091818, 0x00091618, 0x000c1512, 0x000a1714, 0x00071518, 0x00081416, 0x00081411, 0x00071411, 0x00051310, 0x00051310, 0x00061310, 0x0008120e, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0a, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003e400d, 0x0041420d, 0x0044450d, 0x0048490f, 0x004c4d0f, 0x006d6011, 0x00cca215, 0x00c29c15, 0x00595711, 0x00585810, 0x00595a12, 0x005b5b12, 0x005c5d11, 0x005c5d11, 0x005d5e12, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005e5f13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005d5e13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e13, 0x005d5e12, 0x005d5e12, 0x005c5d12, 0x005c5d12, 0x005c5d11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x00615e12, 0x007e7013, 0x00af8f14, 0x00caa216, 0x00cca316, 0x00c09a15, 0x00786911, 0x004f5010, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0043440e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x002c2d0b, 0x0026280c, 0x0020230a, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050c06, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c08, 0x00202420, 0x00252720, 0x00262418, 0x0052433a, 0x00644d46, 0x00684c48, 0x00583b3a, 0x00503938, 0x00423431, 0x00423a38, 0x00433c3b, 0x004c4645, 0x00696266, 0x00736870, 0x00796d74, 0x00807077, 0x00836d78, 0x00886c74, 0x008c6c6a, 0x008c6557, 0x008f5f48, 0x00905c3c, 0x009a6035, 0x009c602d, 0x009e5f29, 0x009d5d24, 0x00a05f20, 0x00a36420, 0x00a46424, 0x00a26123, 0x009c5b1d, 0x009c5a1c, 0x009c591c, 0x00985518, 0x00965416, 0x00955315, 0x00965416, 0x00935214, 0x00925114, 0x00945416, 0x00955414, 0x009b5a1a, 0x009d5c1c, 0x00a05f1d, 0x00a26220, 0x00a2601c, 0x009d5e1d, 0x00955920, 0x0092592c, 0x00945c40, 0x00915d4b, 0x0089584c, 0x008b5c4e, 0x008d5d44, 0x008e5a33, 0x00945b24, 0x00a05f1b, 0x00a65f17, 0x00a75d17, 0x00a65e16, 0x00a55e16, 0x009d5813, 0x00904e0b, 0x00874708, 0x0087480c, 0x0085480f, 0x00854910, 0x00884b13, 0x008c4c12, 0x00925014, 0x00975312, 0x009b5814, 0x009d5a14, 0x00a05d15, 0x00a36018, 0x00a3601a, 0x00a35f1d, 0x00a35f1f, 0x00a35f20, 0x00a05c1e, 0x00a05c1d, 0x00a05c1e, 0x00a05c1e, 0x00a25d1f, 0x00a25d1f, 0x00a15d1d, 0x009e5a1a, 0x009f5a18, 0x009d5816, 0x009a5413, 0x00995410, 0x00985311, 0x00924f0e, 0x0090500e, 0x008c4e0c, 0x00894c09, 0x00864808, 0x0084470c, 0x00824610, 0x007d4413, 0x00784314, 0x00764116, 0x00703f15, 0x006b3c14, 0x00653910, 0x0063360f, 0x00623411, 0x005c3111, 0x004c250f, 0x00341802, 0x002c1402, 0x0030180a, 0x00341908, 0x004a260f, 0x00653716, 0x007d451e, 0x0093501c, 0x009e5818, 0x008e500f, 0x007f4818, 0x004c2b10, 0x0014140b, 0x000a1818, 0x00091619, 0x000c1512, 0x000b1614, 0x00071518, 0x00081416, 0x00081511, 0x00071411, 0x00051310, 0x00051310, 0x00061310, 0x0008120e, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x006e6011, 0x00cca215, 0x00c29c16, 0x005c5910, 0x00595a12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5c11, 0x005b5b12, 0x005d5c12, 0x008b7713, 0x00c39c16, 0x00cca316, 0x00c29b15, 0x00746611, 0x004f5010, 0x004c4d0f, 0x0048490f, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130d, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050c06, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060d07, 0x001c1f1a, 0x00272821, 0x00232118, 0x00443831, 0x006f5853, 0x00694b46, 0x005a3936, 0x004d3732, 0x00483a34, 0x003b352f, 0x00403b38, 0x00454040, 0x00676164, 0x00736971, 0x00776b73, 0x007d6f76, 0x00806e7a, 0x00856c75, 0x00886b69, 0x00896558, 0x008e604e, 0x00905c42, 0x00965f3a, 0x009a5f31, 0x009f602e, 0x009f5f28, 0x009e5d22, 0x009d5d1c, 0x009e5e1c, 0x009f5f1d, 0x00a05e1f, 0x009e5c1d, 0x009c5819, 0x009a5618, 0x00985515, 0x00985515, 0x00975414, 0x009a5617, 0x009e5a1b, 0x00a25f1e, 0x00a05d1c, 0x00a05c1b, 0x00a05c1a, 0x00a05c1a, 0x00a05d1a, 0x009e5d1a, 0x009c5e1e, 0x00985d28, 0x00945c34, 0x00946047, 0x00936150, 0x00895c50, 0x00865b4f, 0x008c5c46, 0x008c5834, 0x00925824, 0x009c5c1a, 0x00a45d16, 0x00a65e17, 0x00a86018, 0x00a45c16, 0x0098540d, 0x008c4b08, 0x00874708, 0x0085460b, 0x0084480d, 0x0084490f, 0x00894c12, 0x008d4d13, 0x00935014, 0x00985413, 0x009a5713, 0x009d5a14, 0x009e5c13, 0x00a15e18, 0x00a25f19, 0x00a25e1d, 0x00a46020, 0x00a66221, 0x00a4601f, 0x00a5601f, 0x00a4611f, 0x00a76120, 0x00a76220, 0x00a66320, 0x00a25f1c, 0x00a05c1a, 0x009f5a16, 0x009c5614, 0x00985414, 0x00975111, 0x00945011, 0x008e4e0e, 0x008c4e0d, 0x00884c0c, 0x0086490a, 0x0084480a, 0x0081470f, 0x007e4511, 0x00784213, 0x00744014, 0x00704016, 0x006c3e17, 0x00653a14, 0x00623811, 0x00613612, 0x005e3413, 0x00593012, 0x004a230d, 0x00341501, 0x002a1201, 0x00301609, 0x003d1f09, 0x00542f10, 0x00703d18, 0x00854b1e, 0x00934f18, 0x0097510f, 0x00894809, 0x007b4417, 0x00482810, 0x0011130a, 0x00091715, 0x00081517, 0x000b1413, 0x00081514, 0x00081415, 0x00071314, 0x00051411, 0x00071411, 0x00051310, 0x00051310, 0x00061310, 0x0008120e, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x00494a0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005c5c12, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00606013, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x007a6c13, 0x00c09a15, 0x00cca316, 0x00bc9815, 0x00655d10, 0x004d4e10, 0x004b4c0f, 0x0048490f, 0x0044450e, 0x0040400d, 0x003c3e0c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x00292b0a, 0x0026280c, 0x00202309, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00050c06, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050c07, 0x001b1e19, 0x00272822, 0x0023211a, 0x00362d28, 0x006e5754, 0x00674642, 0x00593531, 0x00533b32, 0x00473930, 0x0037322a, 0x003b3833, 0x00403c3a, 0x00605c5e, 0x0070666c, 0x0074696f, 0x00776b70, 0x007c6c75, 0x00826d74, 0x00836865, 0x00856458, 0x008c6053, 0x008e5d47, 0x00915c3b, 0x00945c32, 0x00995c2c, 0x009c5c28, 0x009c5b23, 0x009c5c1e, 0x009c5c1b, 0x009c5c19, 0x009d5c19, 0x009f5d1b, 0x00a05d1c, 0x009e5a18, 0x009e5a18, 0x00a05d1b, 0x00a05d1b, 0x00a25e1c, 0x00a25e1c, 0x00a6601f, 0x00a7621f, 0x00a4601c, 0x00a25d19, 0x009f5c18, 0x009f5c17, 0x009c5c1a, 0x009b5c1e, 0x00975c2a, 0x00945b37, 0x00915f46, 0x00905f50, 0x008c5f54, 0x00845b50, 0x00885a47, 0x008a5636, 0x00915627, 0x009c5a1d, 0x00a55d18, 0x00a9611b, 0x00ac641c, 0x00a15913, 0x0094500a, 0x008c4a08, 0x0088470a, 0x0085460c, 0x0084470d, 0x00854910, 0x008b4c13, 0x008e4c12, 0x00944f13, 0x00985314, 0x00975310, 0x009a5811, 0x009c5b12, 0x009e5c16, 0x00a05c18, 0x00a05c1c, 0x00a25e1d, 0x00a4601e, 0x00a4601e, 0x00a6601d, 0x00a5611d, 0x00a7611e, 0x00a7611e, 0x00a5621e, 0x00a4611d, 0x00a25f1a, 0x009f5a16, 0x009c5715, 0x00985414, 0x00945011, 0x00935013, 0x008d4e10, 0x00884c0e, 0x0084480a, 0x00824709, 0x00804508, 0x007e450e, 0x007b4311, 0x00764114, 0x00703e15, 0x006c3c15, 0x00683c16, 0x00643814, 0x00603712, 0x005e3412, 0x005c3414, 0x00583013, 0x0049220d, 0x00331401, 0x00281001, 0x002f1608, 0x0048280f, 0x00613818, 0x00764117, 0x00874919, 0x008d490e, 0x00904a06, 0x00864608, 0x007c4219, 0x00482710, 0x0011130b, 0x000b1615, 0x00081417, 0x000b1413, 0x00081514, 0x00081415, 0x00071314, 0x00051412, 0x00071411, 0x00051310, 0x00051310, 0x00061310, 0x0008120f, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x007c6e13, 0x00c49e16, 0x00cca316, 0x00ab8c14, 0x00545210, 0x004d4e0f, 0x00494a10, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d08, 0x00040d08, 0x00040d08, 0x00040c09, 0x00040c0a, 0x00060d0b, 0x00060d0a, 0x00070d09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080d09, 0x00080c09, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00060d09, 0x00060d09, 0x00060d09, 0x00060d09, 0x00060d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00080c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060d07, 0x00070d08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040c06, 0x00171c15, 0x00282b24, 0x0021201a, 0x002d2824, 0x006c5657, 0x00684642, 0x00653f2c, 0x00644431, 0x004c382c, 0x003c342f, 0x003b3833, 0x003c3836, 0x005a5458, 0x006b6268, 0x0073686d, 0x0073666b, 0x00786970, 0x007c696e, 0x007f6463, 0x00826259, 0x00886053, 0x008b5c48, 0x008d5a3d, 0x008e5833, 0x0093582a, 0x00945623, 0x00985822, 0x0098581f, 0x00975818, 0x00995c17, 0x009f5f19, 0x00a2601b, 0x00a35d1c, 0x00a35e1c, 0x00a45f1d, 0x00a35c1a, 0x00a05c18, 0x00a4601c, 0x00a6601d, 0x00a7611e, 0x00a4601c, 0x00a45f1b, 0x00a35f1b, 0x009f5c1a, 0x009c5918, 0x00995a19, 0x00985920, 0x00965c2d, 0x00935c38, 0x00905c44, 0x008d5c4d, 0x008b5d52, 0x00875c52, 0x00885a48, 0x008a5638, 0x00905628, 0x009c5c1f, 0x00a5601b, 0x00ac641c, 0x00ab631b, 0x00a15813, 0x00944f09, 0x008c4a08, 0x0088470a, 0x0087480c, 0x0084480e, 0x00854910, 0x008a4c11, 0x008d4c11, 0x00934e12, 0x00975113, 0x00975312, 0x00975411, 0x009a5814, 0x009d5c17, 0x009f5c19, 0x00a05c1a, 0x00a15d1c, 0x00a45f1c, 0x00a4601c, 0x00a7611d, 0x00a7621c, 0x00a5601b, 0x00a6601d, 0x00a6601d, 0x00a4601c, 0x00a05c18, 0x009d5915, 0x009a5714, 0x00975312, 0x00935011, 0x00905113, 0x008c4f11, 0x00864a0e, 0x0083480c, 0x0082450a, 0x0080440b, 0x007c4410, 0x00784212, 0x00724016, 0x006e3d17, 0x006c3d18, 0x00653917, 0x00603513, 0x00603514, 0x005e3413, 0x005d3414, 0x00593013, 0x0049220d, 0x00331403, 0x00281001, 0x00301807, 0x00533012, 0x006c3f18, 0x007c4415, 0x00864814, 0x008c4b10, 0x008c4806, 0x0087460c, 0x007c421a, 0x0044250e, 0x0011130a, 0x000a1614, 0x00081516, 0x000a1513, 0x00081513, 0x000a1414, 0x00081414, 0x00071412, 0x00081210, 0x00081110, 0x00081110, 0x0006100f, 0x0005100e, 0x0005100e, 0x0005100e, 0x0005100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0a, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e08, 0x00040e08, 0x00040d08, 0x00040d08, 0x00050e08, 0x00060e08, 0x00050e08, 0x00040e08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00050c08, 0x00060c08, 0x00060c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c09, 0x00040c09, 0x00040c08, 0x00040e08, 0x00040e08, 0x00040e08, 0x00040e08, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005d5b12, 0x005c5c11, 0x005c5d11, 0x00606013, 0x00606012, 0x00606012, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00626313, 0x00626313, 0x00626313, 0x00626313, 0x00626313, 0x00626313, 0x00626312, 0x00626312, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x00937c14, 0x00cba216, 0x00caa116, 0x00857212, 0x004d4e10, 0x004b4c0f, 0x0048490f, 0x0044450e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050f08, 0x00031008, 0x00031008, 0x00031008, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c09, 0x00060e0a, 0x00060e09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d07, 0x00060e06, 0x00060e06, 0x00040f06, 0x00031008, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00080d09, 0x00080d09, 0x00080d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070c07, 0x00070c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040c06, 0x000e130c, 0x002b2c27, 0x00282621, 0x00282320, 0x00634f51, 0x0075524e, 0x00754c34, 0x006e4830, 0x00593e2e, 0x0044362e, 0x003f3831, 0x003c3836, 0x00534e50, 0x006c6368, 0x0073686c, 0x0071656a, 0x00786970, 0x007c686d, 0x007e6363, 0x007f6058, 0x00845d51, 0x00875b48, 0x0088573d, 0x00895534, 0x008d542a, 0x008f5322, 0x0091531f, 0x0092541c, 0x00925516, 0x00965816, 0x009c5a17, 0x009d5a17, 0x009e5917, 0x00a25c1b, 0x00a45e1c, 0x00a55e1c, 0x00a6601c, 0x00a6601d, 0x00a6601d, 0x00a4601c, 0x00a25c19, 0x009d5814, 0x009c5916, 0x009c5919, 0x00985619, 0x00955719, 0x00945620, 0x0094592f, 0x00935c38, 0x00905c43, 0x008e5c4c, 0x008a5c51, 0x00885e52, 0x008a5c49, 0x008b5839, 0x0091582a, 0x009c5c20, 0x00a6601c, 0x00ab641c, 0x00ab621b, 0x00a25812, 0x00954e0b, 0x00904c0c, 0x008b490d, 0x0088480d, 0x0085480f, 0x00854a0f, 0x00894c10, 0x008c4c10, 0x00904c13, 0x00944f13, 0x00955114, 0x00955412, 0x00985614, 0x009c5a17, 0x009e5c18, 0x00a05c18, 0x00a15c18, 0x00a35d1a, 0x00a45d1a, 0x00a4601c, 0x00a55f1a, 0x00a35e19, 0x00a4601c, 0x00a4601c, 0x00a3601b, 0x00a3601b, 0x009c5914, 0x009a5713, 0x00965212, 0x00915010, 0x008d4f11, 0x00894c10, 0x00874a0e, 0x0084470c, 0x0084440c, 0x0080430d, 0x007b4111, 0x00764014, 0x00703f16, 0x006b3c18, 0x00683916, 0x00623714, 0x005e3210, 0x005e3311, 0x005f3312, 0x005d3412, 0x005a3012, 0x0048230c, 0x00331405, 0x002b1104, 0x003a1f0e, 0x00593411, 0x0078481c, 0x00824915, 0x00834712, 0x0085470e, 0x008d4b0e, 0x00884811, 0x007a431a, 0x0040220b, 0x0012140a, 0x000b1514, 0x00091516, 0x000a1513, 0x00081513, 0x000a1414, 0x00081414, 0x00071412, 0x00081110, 0x00081110, 0x00081110, 0x0006100e, 0x00051010, 0x0005100e, 0x0005100e, 0x0005100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050c08, 0x00070c08, 0x00080c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005c5c12, 0x005c5d11, 0x00606013, 0x00606012, 0x00606012, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00626314, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00626313, 0x00626312, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x005e5f13, 0x005c5d11, 0x005c5c11, 0x00605c12, 0x00b79515, 0x00cca316, 0x00b69315, 0x00595510, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00141809, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050f08, 0x00031008, 0x00031008, 0x00031008, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d07, 0x00060e06, 0x00060e06, 0x00040f06, 0x00031008, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00060c07, 0x00050d07, 0x00040e08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040d07, 0x00090e08, 0x00232620, 0x0024241e, 0x0024201a, 0x005a4a49, 0x007c5d58, 0x00754c38, 0x0070472d, 0x0066432d, 0x00523929, 0x0045372c, 0x00403935, 0x004c484a, 0x00686265, 0x0070666a, 0x0070646a, 0x0075656c, 0x0078656a, 0x007d6264, 0x007f605c, 0x00825c52, 0x00845948, 0x0085563d, 0x00865432, 0x00885128, 0x00894f20, 0x008d501d, 0x008f501c, 0x00935519, 0x00945717, 0x00985616, 0x00985513, 0x009b5614, 0x009f5816, 0x00a05a17, 0x00a15b14, 0x00a45d18, 0x00a45f1a, 0x00a45f1b, 0x00a35e1a, 0x00a25c19, 0x00a15c18, 0x00a05c1b, 0x009a5818, 0x00975618, 0x0094571b, 0x00945621, 0x0092592f, 0x00935c3a, 0x008f5b41, 0x008e5c49, 0x008b5d50, 0x00885f50, 0x008c5e49, 0x008c5a3c, 0x0092592c, 0x009f6024, 0x00aa641f, 0x00af681f, 0x00b06820, 0x00a95f19, 0x009b5410, 0x00945010, 0x008e4d10, 0x008b4c12, 0x00874a10, 0x0083490e, 0x00864c10, 0x008a4c11, 0x008d4c14, 0x008f4d14, 0x00904f14, 0x00935013, 0x00965414, 0x009a5815, 0x009e5a18, 0x00a05a17, 0x00a05916, 0x00a15a17, 0x00a35b18, 0x00a45c18, 0x00a55c18, 0x00a45c18, 0x00a45e1b, 0x00a45f1b, 0x00a05d18, 0x009b5814, 0x009c5913, 0x00995512, 0x00955312, 0x00915011, 0x008d4e12, 0x008a4c10, 0x00874a0e, 0x0084460b, 0x0082420c, 0x00804110, 0x007a4014, 0x00743d15, 0x006e3d18, 0x00683b16, 0x00623713, 0x00603513, 0x005e3210, 0x005c3211, 0x005d3311, 0x005c3311, 0x00593010, 0x0049240c, 0x00351404, 0x00301404, 0x004c2c1a, 0x006c421e, 0x007b491b, 0x007d4411, 0x00783e0c, 0x007d420e, 0x008c4c14, 0x00894b15, 0x0078431a, 0x003a1e06, 0x0013140c, 0x000b1413, 0x00081415, 0x00081513, 0x00081513, 0x000a1414, 0x00081413, 0x00071412, 0x00081210, 0x00081110, 0x00081110, 0x0006100e, 0x00051010, 0x0005100e, 0x0004100d, 0x0004100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00050c08, 0x00070c08, 0x00080c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006e6011, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00626314, 0x00626313, 0x00616112, 0x00616112, 0x00606013, 0x00606013, 0x005d5e12, 0x005c5d11, 0x005b5b12, 0x008c7914, 0x00caa116, 0x00cba216, 0x007b6a11, 0x004d4e10, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0036370c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0024250b, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040f08, 0x00031008, 0x00031008, 0x00031008, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d07, 0x00060e06, 0x00060e06, 0x00040f06, 0x00031008, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00080f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050d07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00061008, 0x00061008, 0x00050f08, 0x00050f08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00050e08, 0x00070d08, 0x001b1f18, 0x0022261f, 0x00222018, 0x004c423e, 0x007e6760, 0x00704937, 0x007d5034, 0x007a4f33, 0x0064422a, 0x004c3727, 0x00403833, 0x00474446, 0x00645e62, 0x006b6268, 0x0071656c, 0x0073656c, 0x00736165, 0x00786061, 0x007d605b, 0x00805b53, 0x00805748, 0x0082543c, 0x00825132, 0x00844f29, 0x00884f21, 0x008c501e, 0x008e501d, 0x0092541b, 0x00935518, 0x00955417, 0x00975414, 0x009b5514, 0x009e5814, 0x00a15c16, 0x00a45e16, 0x00a45f18, 0x00a15c18, 0x00a15c18, 0x00a05b18, 0x00a05b18, 0x009d5814, 0x009c5817, 0x00995718, 0x00955417, 0x0094541b, 0x00915423, 0x00905730, 0x00915b3c, 0x008e5a3f, 0x008e5c48, 0x008c5f4e, 0x0088604e, 0x008c5e48, 0x008f5c3d, 0x00945a2d, 0x00a16125, 0x00af6924, 0x00b46e23, 0x00b26a20, 0x00ab601b, 0x009c5411, 0x00965413, 0x00905012, 0x008c4e14, 0x00864c11, 0x0081490e, 0x0082490d, 0x00874c10, 0x00894c14, 0x00894c14, 0x00894d13, 0x008d4d12, 0x00945114, 0x00995314, 0x009e5616, 0x00a15818, 0x00a15816, 0x00a15815, 0x00a35a16, 0x00a45c18, 0x00a45c18, 0x00a25c17, 0x00a35c18, 0x00a25c18, 0x00a05b18, 0x009e5a15, 0x009c5812, 0x00985512, 0x00955312, 0x00925012, 0x008c4d11, 0x00894b10, 0x00874a0e, 0x00824509, 0x0080400c, 0x007f3e10, 0x00783e13, 0x00723b15, 0x006c3b16, 0x00653c15, 0x00633914, 0x00603513, 0x005e3410, 0x005c3311, 0x005c3311, 0x005c3110, 0x00582f0f, 0x004d280e, 0x003a1804, 0x003a1909, 0x0055301c, 0x006f421c, 0x00713d0f, 0x00713807, 0x006f3808, 0x00763c0d, 0x00854614, 0x00884a18, 0x00724016, 0x00331a01, 0x0013160e, 0x000b1413, 0x00081415, 0x00081412, 0x000a1513, 0x000b1412, 0x00081411, 0x00081412, 0x00081210, 0x00081110, 0x00081110, 0x0007100f, 0x00051010, 0x0005100e, 0x0004100d, 0x0004100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d06, 0x00040d06, 0x00050d06, 0x00070c06, 0x00080c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0047480e, 0x00494a10, 0x004d4e0f, 0x006e6011, 0x00cca216, 0x00c39d16, 0x00685f11, 0x00656012, 0x00686112, 0x00696412, 0x006a6414, 0x006b6513, 0x006b6513, 0x006b6513, 0x006c6613, 0x006c6613, 0x006c6613, 0x006c6613, 0x006c6613, 0x006c6713, 0x006c6813, 0x006c6713, 0x006c6713, 0x006c6713, 0x006c6713, 0x006c6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006d6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006c6814, 0x006a6614, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00616112, 0x00606012, 0x005e5f13, 0x005c5d11, 0x005c5c11, 0x00646012, 0x00c49e16, 0x00cca316, 0x009f8213, 0x004c4d10, 0x004c4d0f, 0x0048490f, 0x0044450d, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f09, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d06, 0x00040d06, 0x00050e07, 0x00050e07, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00060d08, 0x00050d07, 0x00050e06, 0x00050e06, 0x00050e06, 0x00050e08, 0x00050d09, 0x00050d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x0004100a, 0x0004100a, 0x00040f0a, 0x00040f0a, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f09, 0x00060e08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050e08, 0x00040e08, 0x00040f08, 0x00031008, 0x00040f09, 0x00050f08, 0x00050f08, 0x00050f08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00050d07, 0x00050d07, 0x00060d08, 0x00060e08, 0x00060e09, 0x00050e09, 0x00050e09, 0x00040d09, 0x00060f09, 0x00060e09, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050f08, 0x00060e08, 0x00060d08, 0x00121812, 0x00222820, 0x00222118, 0x003e3834, 0x0076635e, 0x006e4e3c, 0x0081543b, 0x00815031, 0x006d4525, 0x00573a23, 0x0046382f, 0x00444041, 0x005f5b5f, 0x00686168, 0x006e646a, 0x0072646b, 0x00705e64, 0x00755e60, 0x00775c59, 0x007b5952, 0x007c5649, 0x007e543f, 0x007f5035, 0x0083502d, 0x00864f26, 0x008a5022, 0x008d5020, 0x008e521c, 0x00905218, 0x00965518, 0x00985618, 0x009d5817, 0x00a05b18, 0x00a25d17, 0x00a05c14, 0x009f5a14, 0x00a05c16, 0x00a05b18, 0x009e5915, 0x009e5915, 0x009f5917, 0x009c5818, 0x00975415, 0x00925215, 0x0090511b, 0x008e5121, 0x008c5430, 0x008d583c, 0x008f5d44, 0x008c5d4a, 0x008b5f50, 0x008b6150, 0x008d5f4b, 0x00905c41, 0x00975d32, 0x00a46228, 0x00b06924, 0x00b16c20, 0x00b1681e, 0x00b0661e, 0x00a55e16, 0x00985611, 0x00915313, 0x008c4e12, 0x00854a10, 0x0084480f, 0x0082480e, 0x00844910, 0x00854b13, 0x00854c15, 0x00854c14, 0x00884c11, 0x008d4d10, 0x00965014, 0x009c5215, 0x009d5415, 0x009d5514, 0x009f5714, 0x00a15917, 0x00a35b19, 0x00a25a18, 0x00a25b19, 0x00a35b19, 0x00a25c18, 0x009f5916, 0x009e5815, 0x009c5714, 0x00985411, 0x00945312, 0x00915010, 0x008a4c10, 0x0088480e, 0x0084460d, 0x0080430b, 0x007c3f0d, 0x00793c10, 0x00753e14, 0x006e3c15, 0x00693b16, 0x00653b17, 0x00643816, 0x00603514, 0x005d3411, 0x005c3311, 0x005c3311, 0x005c3210, 0x005a3111, 0x004e280f, 0x003d1a04, 0x00401a05, 0x005a301a, 0x00663512, 0x006c360b, 0x006d3608, 0x006c360d, 0x0070360d, 0x007e4012, 0x0081481b, 0x00663814, 0x002b1604, 0x00121510, 0x000b1412, 0x00081414, 0x00081412, 0x00081411, 0x000b1410, 0x00081410, 0x00071410, 0x00081210, 0x0008110f, 0x0008110f, 0x0007100e, 0x0008120f, 0x0007110f, 0x0005100c, 0x00040f0b, 0x0007110c, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x00050f0a, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040e0a, 0x00040e09, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f09, 0x00050f09, 0x00060f09, 0x00050e08, 0x00050e08, 0x00040f08, 0x00040f07, 0x00040f07, 0x00040f07, 0x00040f07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00040f07, 0x00040f07, 0x00040f07, 0x00040f07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f09, 0x00060e08, 0x00040d07, 0x00040d06, 0x00040d08, 0x00040d08, 0x00040d06, 0x00050c06, 0x00050d05, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00040d05, 0x00040e06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00050d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250b, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x00393b0c, 0x003c3e0c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004c4d0f, 0x006c6011, 0x00caa116, 0x00cba216, 0x00c69f16, 0x00c6a016, 0x00c6a017, 0x00c5a018, 0x00c5a018, 0x00c5a018, 0x00c5a018, 0x00c5a018, 0x00c5a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c4a018, 0x00c49f18, 0x00c49f19, 0x00c49f19, 0x00c39f18, 0x00c39f18, 0x00c3a018, 0x00c3a018, 0x00c29f18, 0x00c29e18, 0x00c29e18, 0x00c29e18, 0x00bc9b18, 0x009e8716, 0x00696614, 0x00636414, 0x00626312, 0x00616112, 0x00606013, 0x00606013, 0x005e5f12, 0x005c5c11, 0x005c5b12, 0x00b49315, 0x00cca316, 0x00ae8d14, 0x004c4d10, 0x004c4d0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003c3e0c, 0x00393b0c, 0x0034350c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0024250b, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00070f0a, 0x00050d09, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x000b110b, 0x001b2219, 0x00212219, 0x00302c28, 0x006e625d, 0x00735a4b, 0x00835847, 0x00805032, 0x00744824, 0x00644023, 0x004a3428, 0x00443b3c, 0x005c585c, 0x00646068, 0x006b6369, 0x006e6169, 0x00706065, 0x00725d5f, 0x00745b59, 0x00785953, 0x007b584c, 0x007c5443, 0x007c513a, 0x00804f32, 0x00844e29, 0x00884f25, 0x008d5124, 0x008f5220, 0x0090531c, 0x0096571c, 0x00995819, 0x009c5919, 0x00a05c1a, 0x00a15d18, 0x00a05c15, 0x00a05c16, 0x00a15c18, 0x00a15c18, 0x009e5915, 0x009e5915, 0x009e5717, 0x00995415, 0x00945315, 0x00905014, 0x008d501a, 0x008b5023, 0x008d5634, 0x008d593f, 0x008b5c47, 0x00895c4c, 0x008b6051, 0x008d6354, 0x00916352, 0x00935f47, 0x00985e34, 0x00a66228, 0x00af6823, 0x00b26c1f, 0x00b46b1e, 0x00b0661a, 0x00a86114, 0x009c580f, 0x00955614, 0x008d4f11, 0x0086480e, 0x0082440d, 0x0080440c, 0x007f430c, 0x007c430c, 0x007a430c, 0x0079420c, 0x007e440c, 0x00854810, 0x008c4b14, 0x00914e15, 0x00955012, 0x00975310, 0x009b5514, 0x009d5618, 0x009e5718, 0x00a0581a, 0x00a35c1b, 0x00a45c1b, 0x00a35c1b, 0x00a05818, 0x009f5817, 0x009b5514, 0x00985412, 0x00945111, 0x008f4f0e, 0x00894a0f, 0x00884810, 0x0082430d, 0x007d400d, 0x00793f10, 0x00743c10, 0x00733f15, 0x006c3c18, 0x00683c17, 0x00653916, 0x00623714, 0x005e3414, 0x005c3211, 0x005c3311, 0x005c3110, 0x005a3010, 0x00583011, 0x004f280e, 0x00401b01, 0x00471e07, 0x005b2e17, 0x00653110, 0x00683208, 0x00683108, 0x006b3410, 0x00713711, 0x007a3c11, 0x007c451d, 0x005a3114, 0x00231206, 0x00101412, 0x00091514, 0x00081414, 0x00081414, 0x00081410, 0x000a120f, 0x0007130e, 0x0005130f, 0x0007120e, 0x0007110d, 0x0007110d, 0x0007110d, 0x0008110e, 0x0006100c, 0x0006100b, 0x00051009, 0x0007110b, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040d07, 0x00040d06, 0x00040c08, 0x00040c09, 0x00040d08, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0020230a, 0x00292b0b, 0x002c2d0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0048490f, 0x004c4d0f, 0x00535110, 0x009f8414, 0x00caa216, 0x00cba216, 0x00cba317, 0x00cba317, 0x00cba417, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cba418, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cba419, 0x00a88d16, 0x00656414, 0x00626313, 0x00616112, 0x00616112, 0x00606012, 0x005e5f13, 0x005d5e11, 0x005c5c12, 0x00a78a14, 0x00cca316, 0x00b08f14, 0x004c4d10, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00040d06, 0x00040d06, 0x00040d06, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00070f0a, 0x00050d09, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00060e0a, 0x00060e09, 0x00070f08, 0x00111911, 0x001f211a, 0x00282823, 0x0068605b, 0x007d685e, 0x00846052, 0x007e5136, 0x007c4f28, 0x006e4624, 0x00503322, 0x00463835, 0x005c5559, 0x00645f68, 0x00696169, 0x006c6068, 0x006f6065, 0x00715e61, 0x00725c5b, 0x00745954, 0x0078584d, 0x007b5545, 0x007c523c, 0x007e4f34, 0x00814e2b, 0x00875027, 0x008c5226, 0x008e5322, 0x0090531f, 0x0096571f, 0x0098581c, 0x009b5718, 0x009e5a1b, 0x00a15e1b, 0x00a05c18, 0x00a05c16, 0x00a05c17, 0x00a15c18, 0x009d5814, 0x009d5816, 0x00985415, 0x00945214, 0x00904f14, 0x008b4c12, 0x00894e17, 0x00874d1f, 0x0085502c, 0x00845337, 0x00845641, 0x00855a4c, 0x00885f54, 0x008c6355, 0x00926657, 0x00926148, 0x00975e34, 0x00a56429, 0x00b06a25, 0x00b26c1f, 0x00b46a1c, 0x00b1661a, 0x00a85f14, 0x00a15b12, 0x00985613, 0x00904f11, 0x0088470d, 0x0081410b, 0x007e3f0a, 0x007b3c08, 0x00773c08, 0x00743c08, 0x00733c09, 0x00743c0a, 0x00773f0c, 0x007f4513, 0x00874a15, 0x008c4c12, 0x00904e10, 0x00945011, 0x00985216, 0x00995418, 0x00985315, 0x009c5819, 0x009f5818, 0x00a05818, 0x00a05819, 0x009e5718, 0x00995414, 0x00955212, 0x00905011, 0x008b4c0d, 0x0088490f, 0x00864610, 0x00804410, 0x007e4210, 0x00763d0e, 0x00703b0e, 0x00703e14, 0x006b3d17, 0x00663b15, 0x00633814, 0x00603513, 0x005c3311, 0x005c3211, 0x005d3412, 0x005b3010, 0x00582f0f, 0x00562f10, 0x004e290c, 0x00401c00, 0x0050280e, 0x005c3017, 0x0064300f, 0x00673109, 0x006a3309, 0x006b3410, 0x00733812, 0x00783c11, 0x0074411c, 0x004a290f, 0x00170d05, 0x000e1412, 0x00091413, 0x00071413, 0x00071413, 0x00081410, 0x0009120e, 0x0007130c, 0x0005130e, 0x0006110d, 0x0006100c, 0x0007100d, 0x0007100d, 0x00040e0b, 0x00040d0a, 0x0005100b, 0x0008110b, 0x00050f09, 0x0005100a, 0x0005100a, 0x00050f0a, 0x00050f0a, 0x00050f0a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e0a, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040d07, 0x00040d06, 0x00040d06, 0x00040d08, 0x00040d06, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c06, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c06, 0x00060c06, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0048490e, 0x004b4c0f, 0x004d4e0f, 0x00585410, 0x008b7612, 0x00957d13, 0x00967e13, 0x00978014, 0x00978014, 0x00988114, 0x00988214, 0x00998215, 0x009a8314, 0x009a8315, 0x009a8315, 0x009b8415, 0x009b8415, 0x009b8415, 0x009c8416, 0x009c8416, 0x009c8515, 0x009c8515, 0x009c8615, 0x009c8615, 0x009d8515, 0x009e8615, 0x009e8616, 0x009e8716, 0x009e8716, 0x009f8816, 0x009f8816, 0x009f8816, 0x009f8815, 0x00a08816, 0x00a08916, 0x00ba9918, 0x00cca519, 0x00c8a318, 0x00756c14, 0x00636414, 0x00626312, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5e11, 0x005c5c11, 0x00a08514, 0x00cca316, 0x00b09014, 0x004d4e10, 0x004f5010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x001d2009, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00080c07, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00060e08, 0x00060f06, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060c07, 0x00060c07, 0x00070d08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00070f0a, 0x00050d09, 0x00050d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060d0b, 0x00060e08, 0x000b130b, 0x00181d17, 0x00242720, 0x005a544f, 0x00816e6c, 0x007d5e59, 0x00785038, 0x007a4e28, 0x00784a25, 0x005f3c25, 0x0045332a, 0x00554c4e, 0x00645e68, 0x00676069, 0x006b6068, 0x006c5f65, 0x00705d60, 0x00705a58, 0x00725854, 0x0075584e, 0x00795747, 0x007a543f, 0x007c5036, 0x00804f2c, 0x00855128, 0x008a5329, 0x008d5425, 0x00905321, 0x0094561f, 0x0097561c, 0x009b591c, 0x009e5a1c, 0x009e5a1b, 0x009e5b18, 0x009c5814, 0x009d5814, 0x009e5915, 0x009b5612, 0x00985411, 0x00945214, 0x00904f14, 0x008a4c12, 0x0083460e, 0x00804711, 0x0080491a, 0x007c4924, 0x007e4e32, 0x007c4f3c, 0x007b5045, 0x0080584f, 0x00886055, 0x00906758, 0x0093644a, 0x00965f35, 0x00a6672c, 0x00b36e28, 0x00b26c20, 0x00b36a1c, 0x00b4671b, 0x00ac6117, 0x00a45c12, 0x009a5410, 0x00944f10, 0x0088450c, 0x00803f09, 0x007c3b08, 0x007c3c09, 0x007a3d0b, 0x00703607, 0x00693304, 0x00673204, 0x00673508, 0x006e3b0e, 0x00764010, 0x007e440f, 0x00884a10, 0x008f4d11, 0x00925014, 0x00945016, 0x00985418, 0x009a561b, 0x009c5818, 0x009c5818, 0x009b5518, 0x00985315, 0x00945011, 0x00904f10, 0x008c4d0f, 0x00894c0e, 0x00864810, 0x00834510, 0x007f4410, 0x007c4210, 0x00753f10, 0x00703c11, 0x006e3d14, 0x006a3d17, 0x00653a14, 0x00623713, 0x00603413, 0x005d3412, 0x005e3413, 0x005d3412, 0x005b3010, 0x00572e0d, 0x00552f0e, 0x004f2a0b, 0x00482102, 0x00572e10, 0x00613618, 0x00673411, 0x006c360e, 0x006f370e, 0x006e3813, 0x00713812, 0x00743c11, 0x00673a15, 0x00371d05, 0x00140e06, 0x000d1411, 0x00081412, 0x00051312, 0x00051312, 0x0008120f, 0x0009110d, 0x0007110c, 0x0006110d, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00040d0a, 0x0005100a, 0x0007110a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d0a, 0x00040d08, 0x00040e09, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040d07, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d05, 0x00040e04, 0x00040e04, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040e04, 0x00040e05, 0x00040e05, 0x00040e05, 0x00040e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c06, 0x00060c05, 0x00060c05, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c09, 0x00191c09, 0x001d2008, 0x0024250b, 0x0024250b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x0036370c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x00505010, 0x00525310, 0x00535411, 0x00555610, 0x00565711, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d13, 0x005d5e13, 0x005d5e13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606012, 0x00606012, 0x00606012, 0x00606013, 0x00606012, 0x00606012, 0x00616114, 0x00616114, 0x00616114, 0x00626314, 0x00626314, 0x00626314, 0x00636414, 0x00636414, 0x00736c14, 0x00c7a218, 0x00cca519, 0x00796f14, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x00606013, 0x005e5f12, 0x005c5c11, 0x00a08514, 0x00cca316, 0x00b09014, 0x004d4e10, 0x004f5010, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0036370c, 0x0034350c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c08, 0x00040c08, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e08, 0x00060f05, 0x00040e04, 0x00040e04, 0x00040e04, 0x00050d06, 0x00060c07, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d09, 0x00080e0a, 0x00060c08, 0x00080e0a, 0x00070c09, 0x00070c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060e0a, 0x00060e08, 0x00081008, 0x0010140e, 0x00242720, 0x004c4542, 0x00806e70, 0x007c5f5d, 0x00744f3c, 0x00774a28, 0x00794a26, 0x0069442c, 0x004e362d, 0x00514444, 0x00605860, 0x00666069, 0x006c6168, 0x006a5c62, 0x006e5c5e, 0x006c5859, 0x00705955, 0x0073584f, 0x0077584a, 0x00795644, 0x007a5139, 0x007e5030, 0x0083522c, 0x0088542b, 0x008c5427, 0x008e5523, 0x0090541f, 0x0093551c, 0x00965519, 0x00985418, 0x00985414, 0x00995413, 0x009c5715, 0x009c5615, 0x00995412, 0x00985411, 0x0092500e, 0x008c4c0f, 0x00884910, 0x0082450d, 0x007c400b, 0x00773e0b, 0x00723c0e, 0x006e3c16, 0x00784628, 0x00784934, 0x00784c3c, 0x007c5147, 0x00835a50, 0x008e6758, 0x0092674e, 0x00946038, 0x00a3662c, 0x00b06e27, 0x00b36d20, 0x00b3691c, 0x00b7691d, 0x00b06418, 0x00a45b12, 0x009c5410, 0x00954e11, 0x0089450c, 0x007d3b05, 0x007f3f08, 0x00925019, 0x0090501b, 0x008f501e, 0x00763b0d, 0x005f2800, 0x005f2e07, 0x0066360f, 0x006d3a11, 0x00733d0f, 0x007b400e, 0x0082450f, 0x00894a12, 0x008d4c14, 0x00904e14, 0x00945016, 0x00945214, 0x00945114, 0x00925013, 0x00914f11, 0x00915012, 0x008f4f11, 0x00884b0f, 0x00874b0f, 0x00834710, 0x0080440f, 0x007a400f, 0x00794110, 0x00743f12, 0x00703d12, 0x006c3d14, 0x006a3c16, 0x00653a14, 0x00623713, 0x00603513, 0x005d3412, 0x005e3413, 0x005f3414, 0x005b3110, 0x00552d0c, 0x00542e0d, 0x00502b0a, 0x004e2707, 0x005c3111, 0x00673a19, 0x006d3815, 0x00713914, 0x00733a11, 0x00743b14, 0x00753c14, 0x00703c12, 0x0056300f, 0x00231100, 0x0011100a, 0x000c1411, 0x00081410, 0x00051312, 0x00071210, 0x0008120f, 0x0008110d, 0x0007110c, 0x0006110d, 0x00050f0d, 0x00050f0c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00040e0b, 0x00040e09, 0x00051008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d09, 0x00040d08, 0x00040e09, 0x00040f08, 0x00050e09, 0x00060e09, 0x00060e08, 0x00050e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f0a, 0x00060e09, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040e05, 0x00040e05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c06, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060d06, 0x00060c05, 0x00060c05, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x002c2d0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x004f5010, 0x00515110, 0x00545510, 0x00565711, 0x00585810, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00686514, 0x00c6a219, 0x00cca519, 0x00796f14, 0x00636414, 0x00636414, 0x00626312, 0x00606013, 0x00606013, 0x005d5e12, 0x005c5c11, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d0f, 0x0048490f, 0x0044450e, 0x0040400d, 0x003b3c0c, 0x0038380c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0020230a, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x000c100b, 0x00161812, 0x003a3632, 0x00776868, 0x007b625f, 0x00714f3d, 0x00734829, 0x00764828, 0x00684130, 0x00593e36, 0x0052403f, 0x005d5359, 0x00645c64, 0x00685d64, 0x00695c62, 0x006c5a5c, 0x006c5858, 0x006e5855, 0x00705750, 0x0074584c, 0x00775849, 0x0079523d, 0x007d5137, 0x00805232, 0x0085542e, 0x00885429, 0x008a5424, 0x008c5420, 0x00905520, 0x0094561c, 0x0097561a, 0x00985517, 0x00995414, 0x00995414, 0x00985313, 0x00965214, 0x00905010, 0x008a4c0d, 0x0083480c, 0x007d440c, 0x0078400b, 0x00763e0f, 0x0070380a, 0x006d370c, 0x0075421c, 0x00895633, 0x008c5834, 0x008b5838, 0x0083543d, 0x00855a49, 0x008f6655, 0x00926852, 0x0094603e, 0x00a0632c, 0x00ad6b24, 0x00b46c20, 0x00b3681c, 0x00b4651a, 0x00b26519, 0x00a85d14, 0x009e5512, 0x00964e10, 0x008b440c, 0x0084410b, 0x008b4c12, 0x0098551c, 0x009c531a, 0x009d5418, 0x00904c15, 0x0071370b, 0x00572200, 0x00582507, 0x00613011, 0x00693612, 0x00703e14, 0x00794414, 0x00804812, 0x00844812, 0x00894b14, 0x008d4e14, 0x00904f15, 0x00904f15, 0x008e4f14, 0x008e4f13, 0x008f5014, 0x00884a0e, 0x0086480f, 0x0084460d, 0x007e430e, 0x0079400c, 0x00753d0b, 0x00723e0e, 0x00703f11, 0x006c3c10, 0x006c3c14, 0x006a3c16, 0x00663914, 0x00623713, 0x00603513, 0x005d3412, 0x00603514, 0x00603414, 0x005b3011, 0x00542c0c, 0x00542d0c, 0x00512a0c, 0x00502709, 0x005c3010, 0x006c3b19, 0x00703b15, 0x00733c14, 0x00743c11, 0x00753d10, 0x00744014, 0x00683c17, 0x003a2008, 0x00150d04, 0x000c100e, 0x00081410, 0x00081410, 0x0007130f, 0x0007130f, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100d, 0x00070e0f, 0x00070e0f, 0x00070e0d, 0x00070e0c, 0x00070e0d, 0x00070e0c, 0x00060e09, 0x00060e08, 0x00040e09, 0x00030f09, 0x0004100a, 0x00040f09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040c08, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x00393b0d, 0x003c3e0c, 0x0041420e, 0x0044450d, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00515110, 0x00535410, 0x00555611, 0x00585810, 0x00585911, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca519, 0x00796f14, 0x00646414, 0x00626314, 0x00626312, 0x00616112, 0x00606012, 0x005d5e12, 0x005c5c11, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d0f, 0x00484910, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d09, 0x00080c08, 0x000a0e07, 0x002c2b26, 0x00736666, 0x007b625c, 0x00714f3c, 0x00734829, 0x00754828, 0x006d4632, 0x00604038, 0x00503936, 0x0056484c, 0x0060585e, 0x00655b62, 0x00685a60, 0x0068585a, 0x006a5656, 0x006a5654, 0x006c5650, 0x0071564d, 0x00745748, 0x00795441, 0x007c523b, 0x00805335, 0x00835430, 0x0085522b, 0x00865125, 0x00875020, 0x008c5420, 0x0090541c, 0x00915418, 0x00925214, 0x00925010, 0x00945011, 0x00935012, 0x00915014, 0x00894c10, 0x0082470e, 0x0078420b, 0x00733d09, 0x006c3607, 0x006c370b, 0x00683309, 0x007f4a20, 0x008e5830, 0x00945f36, 0x00945c30, 0x00945c33, 0x008f5c3a, 0x00906046, 0x00916752, 0x00966852, 0x0096603c, 0x00a0612b, 0x00aa6720, 0x00b0681c, 0x00b2661a, 0x00b4651a, 0x00b3661a, 0x00ac6016, 0x00a25815, 0x00964e11, 0x008b440c, 0x0089460f, 0x00925315, 0x009b581b, 0x009f5719, 0x00a05618, 0x00955018, 0x00854818, 0x005a2500, 0x00502001, 0x00572708, 0x0060300f, 0x00683812, 0x006e3c10, 0x00723d0b, 0x0078400d, 0x007f4410, 0x00834710, 0x00884810, 0x00884811, 0x008a4b13, 0x008a4c12, 0x00884a10, 0x0082440b, 0x0082440d, 0x007f410c, 0x00783f0b, 0x00733c09, 0x00733d0c, 0x00713f0f, 0x006f3e12, 0x006a3c10, 0x006a3c14, 0x00693c16, 0x00663914, 0x00633713, 0x00603513, 0x005c3311, 0x005e3413, 0x005e3113, 0x005a3010, 0x00542c0d, 0x00512b0c, 0x0050290a, 0x00502809, 0x005b3010, 0x006a3b19, 0x006f3d14, 0x00703d11, 0x006e3c0f, 0x006c3d0e, 0x006c3c13, 0x00532c0d, 0x00251000, 0x00100e06, 0x000b1310, 0x00081410, 0x0006120e, 0x0007130f, 0x0007130f, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x00070e0e, 0x00070e0d, 0x00070e0c, 0x00070f0a, 0x00070e0c, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00030c08, 0x0005100a, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0c, 0x0040400d, 0x0044450e, 0x0048490f, 0x004b4c0f, 0x004d4e10, 0x00505010, 0x00535410, 0x00545510, 0x00565710, 0x00585911, 0x00595a12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x00797014, 0x00636414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004f5010, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450d, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00141809, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e06, 0x00262521, 0x00736968, 0x00786058, 0x00704e39, 0x00744827, 0x00774925, 0x00724a33, 0x0067453b, 0x00503631, 0x00524244, 0x005f5659, 0x00645c61, 0x00685c61, 0x0069585b, 0x006b5858, 0x00695758, 0x006c5753, 0x006f584f, 0x0072584a, 0x00795444, 0x007d5440, 0x007f533a, 0x00825434, 0x0083522e, 0x00834f26, 0x00855024, 0x00885120, 0x008a511c, 0x008b5118, 0x008d5015, 0x008f4f12, 0x00905010, 0x008e4f10, 0x00884a0f, 0x0080450e, 0x0077400b, 0x00703c08, 0x00673305, 0x00623005, 0x005d2b04, 0x00713f18, 0x008b5730, 0x00935c33, 0x00986034, 0x009d602f, 0x009d6030, 0x009a613a, 0x00996444, 0x00996b53, 0x00976850, 0x00965e38, 0x00a26028, 0x00ac6820, 0x00ae671a, 0x00b06518, 0x00b06216, 0x00ae6115, 0x00a75c13, 0x00a25814, 0x00954d0f, 0x008c470c, 0x008c490d, 0x00945415, 0x009a5515, 0x009c5414, 0x009c5411, 0x00944f14, 0x00864817, 0x00643007, 0x00592c09, 0x00532508, 0x00562809, 0x005f3010, 0x00653710, 0x006c3c0d, 0x006f3c0c, 0x00743f0d, 0x007b4210, 0x00824510, 0x00844812, 0x00864913, 0x00854811, 0x0083450d, 0x0081430c, 0x0080410e, 0x007d3f0d, 0x00773f0e, 0x00713d0d, 0x006f3c0d, 0x006c3c10, 0x006b3c11, 0x006a3d12, 0x00683c14, 0x00673a14, 0x00643813, 0x00613613, 0x005f3411, 0x005c3311, 0x005a3010, 0x005a2d10, 0x00582e10, 0x00522b0c, 0x004d280b, 0x004c2809, 0x004c2808, 0x00562d0d, 0x00633714, 0x006b3b10, 0x006b3b10, 0x006a3e14, 0x00643c12, 0x00603615, 0x0044200a, 0x001d0c00, 0x000c0e08, 0x00081310, 0x0006110d, 0x0006110d, 0x0006110d, 0x0005100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00060d0c, 0x00060d0b, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00050c08, 0x00060c08, 0x00060c08, 0x00070d09, 0x00070d09, 0x00060c08, 0x00080f0b, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060d09, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004d4e0f, 0x00515110, 0x00525310, 0x00545511, 0x00565710, 0x00585910, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x00797014, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00031008, 0x00031008, 0x00031008, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f06, 0x0023241f, 0x00706665, 0x00745d55, 0x006e4c35, 0x00734825, 0x00764924, 0x00784c34, 0x00684638, 0x004c3129, 0x004d3d3c, 0x005b5154, 0x00625a5c, 0x00675b5f, 0x0068595b, 0x006b5859, 0x00685858, 0x006a5754, 0x006c554f, 0x006e544a, 0x00745345, 0x00795140, 0x007c503c, 0x007f5136, 0x00815130, 0x0081502a, 0x00814e23, 0x00864e20, 0x00874e1c, 0x00884e18, 0x00884e15, 0x00894d14, 0x008b4d11, 0x00874b0c, 0x0080470d, 0x00773f0c, 0x00703b0c, 0x0068380b, 0x00603006, 0x00542600, 0x00562703, 0x007b4b27, 0x00905f38, 0x00956035, 0x009c6338, 0x00a36132, 0x00a06234, 0x009e643e, 0x009d6748, 0x009c6c53, 0x0099684e, 0x00965c34, 0x00a05e24, 0x00aa651c, 0x00ac6418, 0x00ae6316, 0x00ac5e13, 0x00a6590d, 0x00a3580f, 0x009e5510, 0x00934c0c, 0x00904a0d, 0x008c4b0d, 0x00945414, 0x009a5613, 0x009c5412, 0x0098520d, 0x00904d0f, 0x007f430e, 0x006b370b, 0x005c2f0b, 0x00592e0d, 0x00572b0c, 0x00542809, 0x005c300c, 0x0065370d, 0x006b3b10, 0x006d3a0c, 0x00743f0f, 0x007c420e, 0x007e4410, 0x00804410, 0x0080440e, 0x0080430e, 0x007e420c, 0x007c3e0c, 0x00783c0b, 0x00753f10, 0x00703d0f, 0x006e3c0d, 0x006c3c10, 0x006a3d12, 0x00683e13, 0x00673c14, 0x00643913, 0x00613611, 0x00603512, 0x005e3412, 0x005c3212, 0x00572c0e, 0x00562b0e, 0x00562c0f, 0x00502b0b, 0x004c280a, 0x004c290b, 0x004c2808, 0x00522b0b, 0x00603412, 0x00623610, 0x00613612, 0x005c3514, 0x004f2c0c, 0x004f2a11, 0x00442613, 0x001c1002, 0x000b100a, 0x0007130f, 0x0007110d, 0x0007110d, 0x0007110d, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00060d0b, 0x00060e09, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e06, 0x00060f05, 0x00060e08, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00050c08, 0x00060c08, 0x00060c08, 0x00070d09, 0x00070d09, 0x00080c08, 0x000a0e0b, 0x00080c09, 0x00080c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00090c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00050d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004c4d0f, 0x00515110, 0x00525310, 0x00545511, 0x00565710, 0x00585910, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00626312, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x00797014, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00050e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x0008100b, 0x00060e0a, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100b, 0x0005110b, 0x0004100a, 0x0004100a, 0x00051009, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00050f06, 0x0010120c, 0x00564d4c, 0x006e5b53, 0x006c4c37, 0x00724828, 0x00784827, 0x00754a2d, 0x006c4833, 0x00573e31, 0x0050423e, 0x0058514f, 0x00605a5a, 0x00655c5d, 0x00695b5c, 0x00695858, 0x00685857, 0x00685553, 0x006a544f, 0x006c544c, 0x00715246, 0x00755143, 0x0078503e, 0x007a503b, 0x007e5134, 0x0080512e, 0x00835028, 0x00874e24, 0x00884c1d, 0x00884a18, 0x00894b18, 0x00884b18, 0x00844911, 0x007c450c, 0x0076400b, 0x006d3b09, 0x0066370b, 0x005e340e, 0x00542b05, 0x00542804, 0x005c300e, 0x00805230, 0x0094633e, 0x0095623b, 0x009a643b, 0x009d603b, 0x009c603e, 0x00996446, 0x00986850, 0x009b6c56, 0x00976447, 0x00955d30, 0x009b5b1f, 0x00a15b15, 0x00a55c13, 0x00a75c11, 0x00a4580e, 0x00a0560a, 0x009e540b, 0x0099520b, 0x00904a08, 0x008e4a0c, 0x008e4c10, 0x00915112, 0x00945412, 0x0091500d, 0x008e4c0b, 0x0088480e, 0x00783f0c, 0x00683409, 0x0063340f, 0x00623514, 0x005f3110, 0x00562908, 0x00582c0a, 0x005b300d, 0x00633610, 0x0068390d, 0x006b3b0c, 0x00703c0c, 0x00743d0c, 0x00763e0b, 0x00783e0c, 0x00773d0b, 0x00783d0c, 0x00773c0c, 0x00763c0c, 0x00733e10, 0x00703c10, 0x006c3b0e, 0x006a3c0e, 0x00693c15, 0x00673c16, 0x00663b14, 0x00633812, 0x00603613, 0x005e3412, 0x005c3313, 0x00562f10, 0x00532b0c, 0x00512a0c, 0x00532c0d, 0x00502b0d, 0x004d280b, 0x004d280e, 0x00472107, 0x004d270c, 0x00563014, 0x00583317, 0x00532f15, 0x0047260e, 0x003c1c06, 0x00442814, 0x003f2b17, 0x00251f0d, 0x000b1202, 0x00081409, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00090d0a, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00090d0a, 0x00090d0a, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00080c08, 0x00070c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004d4e0f, 0x00515110, 0x00525310, 0x00545511, 0x00565710, 0x00585910, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x00797014, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00616112, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00060e09, 0x0008100b, 0x0008100c, 0x0008100c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005110b, 0x0005110b, 0x0004100a, 0x0004100a, 0x00041009, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00051008, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00041006, 0x00010800, 0x002e2927, 0x00645750, 0x006a523e, 0x00734f32, 0x00754c30, 0x0072492f, 0x00694530, 0x00533b2c, 0x00463832, 0x00544d4a, 0x005a5452, 0x00605756, 0x0068595b, 0x006b5b5b, 0x00665656, 0x00685453, 0x006a5450, 0x006c544c, 0x00705246, 0x00745042, 0x0076503c, 0x00784f39, 0x007a4e33, 0x007d4f2d, 0x00824e29, 0x00854e25, 0x00864c1f, 0x00854a1a, 0x00844918, 0x00804614, 0x007b440e, 0x00713d08, 0x006b3a07, 0x00673708, 0x005c3108, 0x00542b05, 0x00542a05, 0x005a2f0a, 0x00623614, 0x007f5034, 0x00906246, 0x00966548, 0x00946244, 0x00966044, 0x00956047, 0x0094624c, 0x00946452, 0x00936450, 0x008d5c3f, 0x008c5529, 0x0092541b, 0x00985412, 0x009c5410, 0x009e540f, 0x009e540e, 0x0098520c, 0x00945009, 0x008f4c09, 0x00894808, 0x0086480c, 0x00874b11, 0x008b4f14, 0x00884b10, 0x0084470c, 0x0080440d, 0x007b400e, 0x0070390c, 0x00643108, 0x0063320c, 0x006b3c18, 0x00643411, 0x00643410, 0x00552704, 0x00562a04, 0x005c3109, 0x00603409, 0x00643709, 0x0068390b, 0x006c3a0c, 0x00703b0b, 0x00703a0a, 0x00713c0c, 0x00713b0c, 0x00733d0e, 0x00743d0e, 0x00713d12, 0x006e3c10, 0x006c3c10, 0x00693c10, 0x00683c15, 0x00673c17, 0x00653a14, 0x00613712, 0x005f3511, 0x005d3512, 0x00593112, 0x00562f10, 0x00532c0f, 0x004e290b, 0x004c2709, 0x004c2609, 0x00482308, 0x004b230c, 0x00421c06, 0x0046220e, 0x00452611, 0x003e200e, 0x00381e0c, 0x002f1808, 0x00291405, 0x00352413, 0x00362919, 0x00282416, 0x0010150b, 0x00071008, 0x00060e09, 0x0009110d, 0x0008100c, 0x0008100b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00080e0a, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00070d09, 0x00070d09, 0x00080e0a, 0x00080e0a, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00060c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0041420d, 0x0044450e, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00505010, 0x00535410, 0x00555611, 0x00585810, 0x00585911, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f12, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00696614, 0x00c6a219, 0x00cca619, 0x007a7014, 0x00646414, 0x00646414, 0x00636414, 0x00616112, 0x00616112, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00031008, 0x00031008, 0x00031008, 0x00031008, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x00050f0a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120d, 0x0008130d, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006110b, 0x0007110a, 0x0008110b, 0x0008120c, 0x0008120c, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x00061009, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00051008, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00031006, 0x0008130a, 0x000b0e08, 0x003f3a31, 0x00625441, 0x00654b32, 0x006b4834, 0x006e4831, 0x00633f29, 0x00503829, 0x00453831, 0x004f4846, 0x00565150, 0x005c5453, 0x00635456, 0x0069595a, 0x00675757, 0x00675452, 0x0067514c, 0x00685148, 0x00705144, 0x00735040, 0x00754e3c, 0x00784e38, 0x00784f33, 0x007a4f2f, 0x007f4e2b, 0x00804b26, 0x007e481c, 0x007c4517, 0x007b4414, 0x00784111, 0x00713f0c, 0x00693a08, 0x00643708, 0x005e330a, 0x00562d08, 0x00542d08, 0x005c340e, 0x00643915, 0x00643817, 0x0073472b, 0x00865940, 0x008e604b, 0x00875a44, 0x00845640, 0x00885a44, 0x00885b46, 0x00865b46, 0x00875c47, 0x00845739, 0x00875329, 0x008c501c, 0x008d4c11, 0x00904c0f, 0x00914c0e, 0x00934e10, 0x0090500e, 0x008d4f0f, 0x00884c0e, 0x0083480d, 0x007c440d, 0x00794510, 0x007a4614, 0x00754110, 0x00733d10, 0x00713b14, 0x0069340d, 0x005e2c06, 0x00602f08, 0x00693710, 0x006c3813, 0x006c3913, 0x006c3913, 0x00663510, 0x00592a03, 0x00562a02, 0x00582e05, 0x005c3108, 0x0062370c, 0x0065380e, 0x0069390c, 0x006c3b0d, 0x006d3b0c, 0x006f3c0e, 0x006d3c0d, 0x006e3c0d, 0x006d3c12, 0x006c3c12, 0x00693d12, 0x00683c11, 0x00643912, 0x00643914, 0x00633814, 0x00613514, 0x005d3411, 0x00583311, 0x00552f10, 0x00512c0f, 0x00502b0d, 0x004d280c, 0x004b250a, 0x004b270c, 0x00462108, 0x004c240f, 0x00371504, 0x00291001, 0x00241203, 0x00201104, 0x00201309, 0x00221810, 0x001c130b, 0x00241c12, 0x00262014, 0x00202018, 0x00101714, 0x00060f0c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00070f0a, 0x00050d08, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d08, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0036370c, 0x00393b0d, 0x003c3e0c, 0x0041420e, 0x0044450d, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00525310, 0x00535410, 0x00555611, 0x00585810, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00636413, 0x00636414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00696614, 0x00c6a218, 0x00cca619, 0x007a7014, 0x00646414, 0x00646414, 0x00636414, 0x00616112, 0x00616112, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00021008, 0x00021008, 0x00021008, 0x00021008, 0x00021009, 0x00021009, 0x00021009, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120d, 0x0008130d, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006110b, 0x0007110a, 0x0008110b, 0x0008120c, 0x0008120c, 0x0007110c, 0x0006100b, 0x0007110c, 0x0007110c, 0x00061009, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00051008, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e08, 0x00041006, 0x00041007, 0x00060e08, 0x00101208, 0x00393120, 0x0056432d, 0x005e4433, 0x0064412e, 0x005f3d28, 0x00503b2c, 0x00443933, 0x004a4440, 0x00544e4c, 0x005c5252, 0x00605354, 0x00655555, 0x00675757, 0x00675452, 0x0067514c, 0x00685148, 0x006f5042, 0x00714f3e, 0x00724c38, 0x00744b34, 0x00744c31, 0x00764c2d, 0x007a4c28, 0x007b4924, 0x0079471b, 0x00784416, 0x00744113, 0x006f3c0e, 0x006a3a0c, 0x00643808, 0x005c3308, 0x00562d08, 0x00542c09, 0x005b340f, 0x00603912, 0x00673d17, 0x00673c18, 0x006a3c1f, 0x006f4328, 0x00754c34, 0x00734b36, 0x00714a34, 0x00744e35, 0x00785138, 0x00785138, 0x007c533c, 0x007e5136, 0x00804f28, 0x00844a19, 0x00844710, 0x0086470f, 0x0088480f, 0x008a480f, 0x0087480e, 0x0080460c, 0x007b430c, 0x0074400c, 0x006e3c0c, 0x006c3c0e, 0x006c3e13, 0x00693912, 0x00623010, 0x005a290c, 0x00542405, 0x005c2c0a, 0x00683611, 0x00703c13, 0x00703c12, 0x00713c14, 0x00703b13, 0x006c3810, 0x0064340b, 0x00582c04, 0x00542903, 0x00572f08, 0x005b320c, 0x00603710, 0x0064380f, 0x0068390e, 0x00693b0c, 0x006a3c0e, 0x006a3c0d, 0x006a3c0e, 0x00693b11, 0x00683c13, 0x00673c13, 0x00643b12, 0x00613810, 0x00623812, 0x00613614, 0x00603412, 0x005b3210, 0x0056300f, 0x00583113, 0x00532e10, 0x004c280c, 0x004d280c, 0x004b250c, 0x0048240a, 0x00422007, 0x00452310, 0x002c1404, 0x00120700, 0x00121002, 0x00151105, 0x001a150c, 0x001b1911, 0x00181710, 0x0019170f, 0x001c1b14, 0x00191c18, 0x000f1314, 0x00070f0d, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00050d09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00040d07, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00050c08, 0x00050c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0024250b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x004f5010, 0x00525310, 0x00555611, 0x00565710, 0x00585911, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f13, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00696614, 0x00c6a218, 0x00cca619, 0x007a7014, 0x00646514, 0x00646414, 0x00636414, 0x00626312, 0x00606012, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x00494a10, 0x0045470e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006110c, 0x0005110b, 0x0006120c, 0x0007130d, 0x0006100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00040f08, 0x00040f08, 0x00060e08, 0x000b1008, 0x000c0d03, 0x001f1c0f, 0x00302c1c, 0x00413224, 0x00463426, 0x003d2f24, 0x00403630, 0x00423b38, 0x004e4845, 0x00584f4d, 0x00605452, 0x00645454, 0x00645454, 0x00675653, 0x0064504b, 0x00665048, 0x006c4f40, 0x00704f3e, 0x00704c37, 0x00704932, 0x00714a2f, 0x00714828, 0x00704320, 0x0070421c, 0x00734216, 0x00714012, 0x006f4013, 0x00683c10, 0x0062370c, 0x005b320a, 0x00562d07, 0x00562b07, 0x005d310f, 0x00653913, 0x00693d14, 0x006c3e10, 0x006d3c0f, 0x00683714, 0x00603414, 0x0060381f, 0x005c3822, 0x005b3724, 0x00603c29, 0x00684430, 0x00714d36, 0x00754f38, 0x00774c34, 0x00784829, 0x006e3c14, 0x00764012, 0x00773f0e, 0x00783f0e, 0x00793f0d, 0x00783f0d, 0x00753e0c, 0x006e3b0e, 0x00683b13, 0x00613814, 0x00572f10, 0x004c2507, 0x00471f03, 0x00411900, 0x004a2006, 0x00582a0e, 0x00683715, 0x006e3b14, 0x00733e12, 0x00744010, 0x00753f13, 0x00763f13, 0x00713c0d, 0x006b3808, 0x0065360b, 0x005b2e09, 0x00562c0b, 0x00592f10, 0x005d3412, 0x00603511, 0x00613710, 0x0061380d, 0x0061380c, 0x00643b0c, 0x00653c0d, 0x00663c12, 0x00663b14, 0x00653a14, 0x00633913, 0x00613811, 0x00613812, 0x00613814, 0x005c3210, 0x00582f0e, 0x00583112, 0x00583114, 0x00522b0f, 0x004e260d, 0x004c260c, 0x0048240a, 0x0047230a, 0x0044230c, 0x00402414, 0x00241405, 0x00100e00, 0x000e1406, 0x0015170a, 0x001c180e, 0x001c180e, 0x0018160e, 0x0013140f, 0x00131513, 0x00151914, 0x000d120c, 0x00081009, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050c08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00080c07, 0x00080c07, 0x00080c07, 0x00060c07, 0x00040d06, 0x00040d06, 0x00040d06, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d0a, 0x00080d09, 0x00080d09, 0x00080d08, 0x00080d0a, 0x00080c09, 0x00080c07, 0x00080c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c09, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x00292b0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a10, 0x004d4e0f, 0x00515110, 0x00525310, 0x00565610, 0x00595a11, 0x005b5b12, 0x005c5c12, 0x005e5f11, 0x00605f11, 0x00616012, 0x00626113, 0x00626113, 0x00636213, 0x00646313, 0x00646212, 0x00646313, 0x00646413, 0x00646413, 0x00656413, 0x00666412, 0x00666412, 0x00686513, 0x00686513, 0x00686613, 0x00696614, 0x00696614, 0x006b6814, 0x006b6814, 0x006c6814, 0x006c6914, 0x006c6914, 0x006d6a14, 0x006e6b14, 0x00938115, 0x00c9a419, 0x00cca619, 0x00797014, 0x00646414, 0x00646414, 0x00636414, 0x00626312, 0x00616112, 0x005e5f13, 0x005d5d12, 0x00a08514, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130c, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006110c, 0x0005110b, 0x0006120c, 0x0007130d, 0x0007100c, 0x0009110d, 0x0009110d, 0x0008100c, 0x0008100c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e06, 0x00080e05, 0x000c0f05, 0x00100f04, 0x00201a10, 0x002d251a, 0x002f261e, 0x002e2823, 0x00433e38, 0x0048413c, 0x00514744, 0x00615454, 0x00605251, 0x00615050, 0x00655451, 0x00624e49, 0x00644e45, 0x00684d40, 0x006d4d3f, 0x006f4c38, 0x006e4833, 0x006f472d, 0x006d4427, 0x006c401e, 0x006c4018, 0x006d3d13, 0x006b3b0f, 0x00683a10, 0x0061350e, 0x005b330c, 0x00573009, 0x00542b06, 0x00572c07, 0x00643710, 0x006b3c14, 0x006f3f13, 0x00724010, 0x00724010, 0x00703c15, 0x00683914, 0x0054290c, 0x0048240c, 0x0042200c, 0x003f1d08, 0x003f1f0c, 0x00543420, 0x00684631, 0x006f4832, 0x006c4229, 0x00653919, 0x0064340d, 0x0066350c, 0x0068340c, 0x0068350d, 0x0068350d, 0x0064340c, 0x005f310c, 0x00593010, 0x00482206, 0x00381600, 0x00351400, 0x003c1902, 0x00432009, 0x00512a0f, 0x00603414, 0x006c3a17, 0x00733e14, 0x00774111, 0x00784310, 0x007b4413, 0x007c4212, 0x0079420e, 0x00723f0a, 0x006e3b0d, 0x00663610, 0x005b2d0b, 0x00582e0c, 0x005b310f, 0x005c330f, 0x005d340f, 0x005e350d, 0x005e350c, 0x0060370c, 0x0060380c, 0x00623910, 0x00623812, 0x00623811, 0x00603710, 0x00603710, 0x00603711, 0x005e3411, 0x00592f0d, 0x0058300f, 0x00593112, 0x00593114, 0x0052280e, 0x004d240c, 0x004c240d, 0x0047220a, 0x0046230a, 0x0044240d, 0x003b2213, 0x001f1007, 0x00100d04, 0x000d1506, 0x00121306, 0x0021180f, 0x00241a10, 0x001c180d, 0x00151510, 0x00111310, 0x00101410, 0x000b1009, 0x0009100a, 0x0005100a, 0x00040f09, 0x0005100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070c0b, 0x00070d09, 0x00070d09, 0x00070d08, 0x00080e0a, 0x00070d09, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004d4e10, 0x00706411, 0x00b79414, 0x00bd9815, 0x00be9a16, 0x00be9a16, 0x00be9b16, 0x00be9b17, 0x00bf9b18, 0x00bf9b18, 0x00bf9b18, 0x00bf9b18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00bf9c18, 0x00c09d18, 0x00c09d18, 0x00c09d18, 0x00c09d18, 0x00c09d18, 0x00c09d18, 0x00c09e18, 0x00c09e18, 0x00c09e18, 0x00c09e18, 0x00c09f18, 0x00c8a418, 0x00cca619, 0x00c09e18, 0x00716c14, 0x00646514, 0x00646414, 0x00636414, 0x00626313, 0x00606013, 0x00606013, 0x005d5d12, 0x00a38814, 0x00cca417, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d10, 0x00484910, 0x0044450e, 0x0040400d, 0x003b3c0c, 0x0038380c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040f09, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006110c, 0x0005110b, 0x0005110b, 0x0007130c, 0x000a140f, 0x000c140f, 0x000c140f, 0x0009110d, 0x0008100b, 0x0008120d, 0x0008120d, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00060e06, 0x00080d06, 0x00090c06, 0x000d0e09, 0x0022211c, 0x00282620, 0x00282620, 0x003c3833, 0x00443c38, 0x00544948, 0x005c504f, 0x005f5050, 0x00605050, 0x0062514e, 0x00624f49, 0x00604c43, 0x0062493d, 0x0066473a, 0x006c4a39, 0x006c4733, 0x006c452d, 0x006a4326, 0x00683f1d, 0x00683d18, 0x006a3c14, 0x0066380e, 0x0061340c, 0x005c320c, 0x0058300c, 0x00542c09, 0x00562c08, 0x00603510, 0x00683b11, 0x006c3d10, 0x00714010, 0x00733f10, 0x00743f10, 0x00764014, 0x006f3d15, 0x005f3211, 0x004f290a, 0x00442108, 0x003d1f07, 0x003c200b, 0x003a1d0b, 0x00432614, 0x00533421, 0x005b3924, 0x005c381e, 0x00593114, 0x005a2e10, 0x0054290a, 0x00582f10, 0x00593010, 0x00593013, 0x004c250a, 0x003e1a00, 0x00371700, 0x00361a09, 0x00391c0a, 0x003e1e09, 0x0048240c, 0x00542c0f, 0x00643715, 0x00703e17, 0x00744014, 0x00784210, 0x0079440f, 0x007c4410, 0x007e4410, 0x007c4410, 0x0077400e, 0x00703c0d, 0x006b3910, 0x0063340d, 0x00582e0a, 0x00582c09, 0x00582e0c, 0x005a300f, 0x005c3210, 0x005e3410, 0x005d340e, 0x005d340d, 0x00603610, 0x00623912, 0x00613811, 0x005e350e, 0x005c320c, 0x005d3410, 0x00603514, 0x005b3010, 0x00572d0f, 0x00593014, 0x00583014, 0x00582f15, 0x004f260f, 0x004f2611, 0x004f2a13, 0x0043200b, 0x003c1d08, 0x002e180b, 0x00180803, 0x00130e08, 0x00111409, 0x00161305, 0x0024180e, 0x00281c10, 0x00211a0d, 0x0018150e, 0x0012120f, 0x000e120e, 0x0009100c, 0x0008100c, 0x0005100a, 0x00040f09, 0x0005100a, 0x00050f0a, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070c0b, 0x00070d09, 0x00070d09, 0x00070d08, 0x00080e0a, 0x00070d09, 0x00060c07, 0x00060c05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x00615910, 0x00bc9815, 0x00cca316, 0x00cca316, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00c2a018, 0x008b7c14, 0x00656614, 0x00646514, 0x00646514, 0x00636414, 0x00626313, 0x00616112, 0x00606012, 0x00605f12, 0x00ac8f15, 0x00cca417, 0x00b09014, 0x004f5010, 0x00505010, 0x004c4d0f, 0x00484910, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0036370c, 0x0034350c, 0x002d2f0b, 0x00292b0a, 0x0026280b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00040e09, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006110c, 0x0005110b, 0x0006120c, 0x0008140e, 0x0008120d, 0x0009110d, 0x0009110d, 0x0008100c, 0x0009110d, 0x0008120d, 0x0008110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00031006, 0x00031008, 0x00060e08, 0x00070c0a, 0x00070c0b, 0x00101512, 0x001c201a, 0x001e1e17, 0x00343129, 0x003e3832, 0x00504542, 0x00584c4b, 0x005a4c4b, 0x005c4d4c, 0x0062504e, 0x00604d48, 0x005d4c42, 0x0060493e, 0x0064483b, 0x00694b3b, 0x00694834, 0x0066442c, 0x00664024, 0x00663e1e, 0x00673d19, 0x00663b13, 0x0061350c, 0x005c330b, 0x0058300c, 0x00542d0c, 0x00542c0d, 0x005d3410, 0x00653a12, 0x006c3e12, 0x00703e0d, 0x0074400f, 0x00774010, 0x00784010, 0x00774011, 0x00713d12, 0x00653811, 0x00562f0c, 0x0048270a, 0x00402409, 0x003b1f0a, 0x00351b0a, 0x00341c0b, 0x00361e0c, 0x00412614, 0x0050311f, 0x00502f1a, 0x00502c17, 0x004c2511, 0x004e2915, 0x00492611, 0x0040200a, 0x00361702, 0x00341400, 0x00341801, 0x00381e0c, 0x003f220c, 0x004a260f, 0x00542c10, 0x005d3311, 0x00663813, 0x006f3d12, 0x00723e0f, 0x00744009, 0x0076400a, 0x0079410c, 0x007b420c, 0x007b420e, 0x0078400d, 0x00733d0c, 0x006c3a0c, 0x0067380c, 0x005e340e, 0x00582c09, 0x00542a09, 0x00552b0c, 0x00582e0f, 0x005b3010, 0x005c3210, 0x005d3410, 0x005e350e, 0x005d340d, 0x005d340d, 0x005c330c, 0x005b320b, 0x005e3410, 0x00582d0c, 0x005c3111, 0x00542a0d, 0x00542c10, 0x00532a0f, 0x00542c11, 0x0050260f, 0x004c250e, 0x004a240e, 0x00421f0a, 0x003c1c0a, 0x00281408, 0x00140703, 0x00130d09, 0x00131308, 0x00191404, 0x0025180c, 0x002f2014, 0x002a2011, 0x001e170e, 0x00181410, 0x00101410, 0x00081210, 0x0007120d, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060f09, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00040d05, 0x00040d06, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00070d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x006e6011, 0x00cca215, 0x00c8a016, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48815, 0x00a48915, 0x00a48915, 0x00a48916, 0x00a48916, 0x00a48916, 0x00a48916, 0x00a38a15, 0x00a38a15, 0x00a38915, 0x00a38915, 0x00a28915, 0x00a28915, 0x00a28916, 0x00a28916, 0x00a18817, 0x00a18816, 0x00a18915, 0x00a18915, 0x00a18816, 0x00a18916, 0x00a08916, 0x00a08916, 0x00a08916, 0x00a08916, 0x00a08916, 0x00a08916, 0x00988416, 0x00787114, 0x00656614, 0x00656614, 0x00656614, 0x00646514, 0x00646414, 0x00626313, 0x00626312, 0x00606012, 0x00616012, 0x00bc9916, 0x00cca417, 0x00aa8b14, 0x004f5010, 0x00505010, 0x004c4d0f, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040f0a, 0x00040f09, 0x00040e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040f09, 0x0008110c, 0x0005100a, 0x00040d08, 0x00040d08, 0x0007110c, 0x0007110c, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0007110c, 0x0005100a, 0x0008120c, 0x0008120d, 0x0007120c, 0x0006120c, 0x0007130c, 0x0008140e, 0x0007130d, 0x0007110c, 0x0009120d, 0x0008120d, 0x0007110c, 0x0009130e, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x00061009, 0x00061009, 0x00040f08, 0x00051008, 0x0007100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040e05, 0x00040e05, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00031006, 0x00060e09, 0x00060e09, 0x0006100c, 0x000c120f, 0x00161a14, 0x0021211a, 0x002e2c22, 0x00352f28, 0x00493f3b, 0x00544845, 0x005a4d4c, 0x00544644, 0x00584945, 0x005c4a45, 0x005c4a43, 0x0060483d, 0x00604538, 0x0065483a, 0x00664838, 0x0067442f, 0x00644026, 0x00633d1f, 0x00633b18, 0x00633815, 0x005e3410, 0x0058320d, 0x0054300c, 0x00542f0e, 0x005c3014, 0x00633513, 0x006b3c12, 0x00724113, 0x0076400e, 0x0077410e, 0x007a4312, 0x00793f10, 0x00783e10, 0x00713c0f, 0x00693b11, 0x00603810, 0x00523111, 0x00482a0e, 0x0040240b, 0x003f250f, 0x003a2410, 0x0035210d, 0x00331e0a, 0x0038200c, 0x00422715, 0x00442818, 0x00452617, 0x00432414, 0x003d1f10, 0x00341605, 0x00351804, 0x003c1e0a, 0x00432510, 0x00482914, 0x004d2c14, 0x00522c11, 0x00582e11, 0x00643815, 0x00683b11, 0x006d3c10, 0x00703c0c, 0x00703c09, 0x00703c08, 0x00733c09, 0x0078400c, 0x00733d0c, 0x006c3808, 0x006c390b, 0x0068360a, 0x0066360e, 0x0061340e, 0x005b2f0d, 0x00562b0e, 0x00542b10, 0x00582f14, 0x00572c10, 0x005b3011, 0x005b3010, 0x005b320c, 0x005b310c, 0x005d3410, 0x005d3410, 0x005d3410, 0x005c3411, 0x00582f0e, 0x00582f10, 0x00542b0e, 0x00532c10, 0x0050280d, 0x00512a10, 0x00502910, 0x004b250c, 0x004c2610, 0x0044200b, 0x00381c0a, 0x00231206, 0x00120902, 0x00110f07, 0x00171408, 0x001f1708, 0x002c1c0f, 0x00342412, 0x0030220d, 0x00281c0f, 0x001f1810, 0x0012140f, 0x00091110, 0x00071310, 0x0006120c, 0x0004100a, 0x00030f09, 0x00040e08, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00060d09, 0x00080c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070e08, 0x00070e08, 0x00060c07, 0x00060c07, 0x00050c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c07, 0x00050d07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x00494a0f, 0x004d4e0f, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005b5811, 0x00595a12, 0x005b5b11, 0x005c5d12, 0x005d5e13, 0x005e5f13, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00606012, 0x00616113, 0x00616113, 0x00616114, 0x00616114, 0x00616114, 0x00616114, 0x00626314, 0x00626314, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00646513, 0x00656614, 0x00656614, 0x00656613, 0x00666713, 0x00666713, 0x00666713, 0x00656614, 0x00646513, 0x00646414, 0x00636414, 0x00616112, 0x00606013, 0x00786c14, 0x00c8a116, 0x00cca417, 0x00927b13, 0x00515110, 0x00505010, 0x004c4d0f, 0x0047480e, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0038380c, 0x0030310c, 0x002d2f0a, 0x0026280a, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f09, 0x00040d08, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x0006100b, 0x00040f09, 0x00040d08, 0x00040d08, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0007110c, 0x0005100a, 0x0008120c, 0x0008120d, 0x0008120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0007110c, 0x0009130e, 0x0007110c, 0x0008120d, 0x0009130e, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x00061009, 0x00061009, 0x0008110b, 0x00040f08, 0x00040c07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040e05, 0x00040e05, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00050f08, 0x00040e09, 0x00080f0b, 0x000e140f, 0x001b1c16, 0x0026251c, 0x00353028, 0x0048403a, 0x004e443e, 0x00524641, 0x00544743, 0x00584945, 0x00574640, 0x0056463d, 0x005e473c, 0x0062473b, 0x005e4334, 0x00604232, 0x0063412d, 0x00633f26, 0x00633c20, 0x00623b18, 0x005e3614, 0x005a3210, 0x0058300e, 0x0057310f, 0x00593110, 0x00613416, 0x00683914, 0x006c3d12, 0x00734011, 0x00794311, 0x00784311, 0x00784110, 0x00794110, 0x00763e10, 0x00703c10, 0x006b3c12, 0x00613810, 0x00573311, 0x00502d10, 0x00462508, 0x0047290f, 0x00402710, 0x003b240f, 0x0037200b, 0x00351e0a, 0x00341c08, 0x00341b0b, 0x00361b0c, 0x00391c0c, 0x003b1c0d, 0x00371908, 0x00391c09, 0x0040210c, 0x00482812, 0x004c2b12, 0x00502c13, 0x00542c11, 0x005b2e12, 0x00653514, 0x00683811, 0x006c380d, 0x006c3a0b, 0x006d3b0a, 0x006e3c0b, 0x006f390c, 0x00733c0e, 0x006e3a0b, 0x006c3b0c, 0x0068360b, 0x00613109, 0x005d2f08, 0x005d2e0b, 0x00582c0b, 0x00572a0f, 0x00552c12, 0x00562d13, 0x00592f13, 0x005a3012, 0x005b3010, 0x005a300c, 0x00582f0c, 0x005c3310, 0x005c3311, 0x005c3412, 0x005b3311, 0x0058300f, 0x00542c0d, 0x0050280b, 0x00532c10, 0x004f280c, 0x004e260c, 0x004d250b, 0x004a260b, 0x004d2810, 0x0044200c, 0x00361c0a, 0x001a0d00, 0x00100c04, 0x000d0d04, 0x00151306, 0x0023180b, 0x002f1d11, 0x003a2412, 0x0038240c, 0x002d1d0d, 0x0022180f, 0x0015140e, 0x000c1110, 0x00081310, 0x0006120c, 0x0004100a, 0x00030f09, 0x00020e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00060d09, 0x00080c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070e08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c07, 0x00050e08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x00202309, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606012, 0x00606012, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666713, 0x00666713, 0x00666714, 0x00666714, 0x00666714, 0x00666714, 0x00666713, 0x00666713, 0x00656614, 0x00646514, 0x00636414, 0x00626312, 0x00616113, 0x00a18815, 0x00cca417, 0x00c59f16, 0x006e6412, 0x00535410, 0x00505010, 0x004c4d0f, 0x0048490e, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130e, 0x000f130f, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f0a, 0x0005100a, 0x00040f09, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x0008110c, 0x0008120d, 0x0008120d, 0x0007130c, 0x0007130d, 0x0007130d, 0x0005110b, 0x0008120c, 0x0008120d, 0x0008120c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120c, 0x0008120c, 0x0008120c, 0x0008120c, 0x0008120c, 0x0007110c, 0x00061009, 0x00061009, 0x00061009, 0x00040f08, 0x00060f09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00060e08, 0x00040e07, 0x00040f08, 0x00050e08, 0x00090e09, 0x0010120e, 0x001c1c17, 0x0034322b, 0x0048433b, 0x004b423c, 0x004c413a, 0x0050443c, 0x0050413a, 0x0053423a, 0x00534439, 0x005b463a, 0x0060483a, 0x005d4434, 0x005c412f, 0x005e3e2b, 0x00603c25, 0x005f391e, 0x005e3718, 0x005a3312, 0x0058300e, 0x00572f0d, 0x0059300f, 0x005c3010, 0x00633814, 0x00693a14, 0x006a3a0e, 0x006e3c0e, 0x00744012, 0x00733e10, 0x00733e10, 0x00794416, 0x00764113, 0x006d3c0f, 0x006a3a10, 0x00643611, 0x005c3010, 0x005c3417, 0x0050290f, 0x00522c13, 0x004b2b12, 0x00482b14, 0x003f230c, 0x003c1f09, 0x003b1e0a, 0x003b1e0b, 0x00381b08, 0x003a1c0c, 0x003f200e, 0x0040210d, 0x0040200a, 0x0045250c, 0x004d2c12, 0x004f2b11, 0x00542c11, 0x00562b0e, 0x005e3010, 0x00643413, 0x00693813, 0x006c3c12, 0x006f3c11, 0x006d3c0e, 0x006c3b0d, 0x006b370c, 0x006c380d, 0x00643306, 0x00633307, 0x00613308, 0x00643811, 0x005d300b, 0x00562908, 0x00582c0c, 0x0054290b, 0x00552c10, 0x00562c10, 0x00562b10, 0x005b3012, 0x005b3010, 0x00582f0c, 0x00572d0a, 0x005a300d, 0x00582f0d, 0x0059300f, 0x0058300f, 0x00552d0e, 0x00512a0c, 0x0050280c, 0x00502a10, 0x004d280d, 0x004f290f, 0x00502b10, 0x004a270b, 0x004a240c, 0x00411e0b, 0x00331909, 0x00140c01, 0x000e0e07, 0x000c0c06, 0x00141106, 0x0024170c, 0x00321c11, 0x003d2413, 0x003d260f, 0x00311e0e, 0x0026180e, 0x0019140e, 0x0010110e, 0x000a120e, 0x0005110c, 0x0004100a, 0x0004100a, 0x00040f09, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00060d09, 0x00080c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070e08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00050e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c07, 0x00050e08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005d5b12, 0x005c5d11, 0x005c5d11, 0x00606013, 0x00606012, 0x00606012, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00666714, 0x00656614, 0x00656614, 0x00646414, 0x00626313, 0x00756c14, 0x00c49f18, 0x00cca417, 0x00a68914, 0x00585811, 0x00535410, 0x00505010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f09, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x0005100a, 0x00040e08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x0007110c, 0x0008110c, 0x0007110c, 0x0005110b, 0x0006120c, 0x0008140e, 0x0008140e, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007110c, 0x00061009, 0x00061009, 0x0007110a, 0x00040f08, 0x00040e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00051007, 0x00050e08, 0x00040e06, 0x00040f06, 0x00050f06, 0x00060e08, 0x00080c09, 0x000e100c, 0x00282721, 0x003c3932, 0x0048433a, 0x004b4338, 0x004e4439, 0x00504238, 0x0055443c, 0x00504136, 0x00584538, 0x005c4537, 0x00594030, 0x00583e2b, 0x00593c2a, 0x005c3c28, 0x005c3920, 0x005a3618, 0x00583212, 0x0055300e, 0x00572f0d, 0x005b300e, 0x005b310c, 0x0061360d, 0x00673810, 0x006b3b10, 0x006c3c10, 0x00703d11, 0x006c390d, 0x00703f13, 0x00734114, 0x00703f11, 0x006c3b0f, 0x006b3a11, 0x006b3b17, 0x006b3c1a, 0x00653818, 0x005b3012, 0x005c3416, 0x00543016, 0x004d2c14, 0x00492811, 0x0043220c, 0x0040210b, 0x003d200b, 0x003d1f0b, 0x003e1e0b, 0x003f1e0b, 0x0041200c, 0x0044220c, 0x0048260c, 0x004f2c10, 0x00532d10, 0x00552c0f, 0x005a2d0c, 0x0060300f, 0x00683717, 0x00683614, 0x00683810, 0x006c3c12, 0x0068380d, 0x0069380d, 0x0068370e, 0x0069370e, 0x005f3007, 0x005c2f06, 0x0060320c, 0x005f3310, 0x00542806, 0x00522407, 0x0053270a, 0x0054280b, 0x00542c0e, 0x00542b0f, 0x00552a0f, 0x00592f10, 0x005c3110, 0x005c320f, 0x00592f0d, 0x005a300e, 0x00592f0e, 0x00582f0d, 0x00542c0c, 0x00542c0c, 0x00502a0c, 0x0050280e, 0x004f2810, 0x004c260c, 0x004a240b, 0x00482208, 0x00482408, 0x00462009, 0x00401b0a, 0x002b1204, 0x000f0c02, 0x00090d07, 0x000c0e08, 0x00151009, 0x0025170c, 0x00341c12, 0x003e2212, 0x00402610, 0x00372311, 0x002a1c10, 0x001e160d, 0x0014140d, 0x000b120e, 0x0006120c, 0x0004100a, 0x0004100a, 0x0004100a, 0x00040e09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00060d09, 0x00080c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070e08, 0x00080e08, 0x00060c07, 0x00060c07, 0x00060c07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c07, 0x00050e08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060e09, 0x00060e09, 0x00060e08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005d5b12, 0x005c5c11, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00626313, 0x00636413, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00666713, 0x00656614, 0x00646414, 0x00686413, 0x00b09317, 0x00cca418, 0x00c39e17, 0x00706612, 0x00565711, 0x00535410, 0x00505010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d08, 0x00070f0a, 0x00040d08, 0x00050e09, 0x00050e09, 0x00040f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050e08, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00040f0a, 0x00060f0a, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050f09, 0x00050e09, 0x00060d09, 0x00070e09, 0x00060d08, 0x00050c08, 0x00040c08, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100b, 0x0005100b, 0x0005100a, 0x0006100b, 0x0007120c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008110c, 0x0008110c, 0x0008110c, 0x0008110c, 0x0008120d, 0x0008110c, 0x0007110c, 0x0007100c, 0x0006100b, 0x0006110b, 0x00051009, 0x00051009, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00040e07, 0x00040f06, 0x00050e06, 0x00070e08, 0x00060c08, 0x00080d09, 0x001f1f1b, 0x0038352f, 0x00474339, 0x00484136, 0x004c4238, 0x0051433a, 0x0058483f, 0x00504034, 0x00564438, 0x00594334, 0x00543c2c, 0x004f3623, 0x00573d29, 0x005b3f2a, 0x00593b21, 0x0058361a, 0x00543313, 0x0054300e, 0x00542d0a, 0x005c330f, 0x005c320b, 0x0060360c, 0x0063360d, 0x0064350c, 0x00693a11, 0x00683910, 0x0066380e, 0x006c3b12, 0x006e3c14, 0x006b3b10, 0x006b3b10, 0x0067380f, 0x00683812, 0x006d3f1a, 0x00633611, 0x005f330f, 0x00603514, 0x005a3315, 0x00522c11, 0x00512a14, 0x0048240e, 0x0043200b, 0x0043230c, 0x0042230c, 0x0043210b, 0x00401e08, 0x00401e06, 0x0047250c, 0x004b270c, 0x004f2a0c, 0x00552f0d, 0x00572d0b, 0x00603410, 0x005e300f, 0x00683818, 0x00673715, 0x00643410, 0x00683911, 0x0064350d, 0x00643510, 0x00663611, 0x00643410, 0x005c2f0a, 0x005a2e08, 0x00592d0a, 0x00572c0c, 0x0054290b, 0x0055290d, 0x00502408, 0x0052280b, 0x0053280c, 0x0051280c, 0x00562c0f, 0x00592f0f, 0x005c3110, 0x005c3310, 0x005b3110, 0x005a3010, 0x0059300e, 0x00552e0c, 0x00542c0c, 0x00542c0d, 0x00542d10, 0x0050280f, 0x004f2910, 0x004d280f, 0x0049240b, 0x00462208, 0x00442308, 0x00421f0a, 0x00391c0b, 0x00200e00, 0x000d0d04, 0x00080e07, 0x000c0f09, 0x0016100a, 0x0024160c, 0x00311d10, 0x00392210, 0x003c2711, 0x00362313, 0x002c1d11, 0x00221a10, 0x0018150e, 0x0010140d, 0x000a130d, 0x0008100b, 0x00061009, 0x00050f09, 0x00040e0a, 0x00040e0a, 0x00040e0a, 0x00040e0a, 0x00050e09, 0x00050e09, 0x00070f09, 0x00060e09, 0x00060d09, 0x00060d09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00070e09, 0x00060d08, 0x00050c08, 0x00060c08, 0x00070c08, 0x00070c08, 0x00080c08, 0x00070d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00080c09, 0x00080d09, 0x00060d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00060f09, 0x00070f09, 0x00060d08, 0x00060d08, 0x00070c08, 0x00080c08, 0x00080c08, 0x00070c08, 0x00050e08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00050d09, 0x00050d09, 0x00050d09, 0x00040c08, 0x00040c07, 0x00050d07, 0x00050e08, 0x00050e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00050d08, 0x00050d08, 0x00050d09, 0x00050d0a, 0x00060e0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00050f08, 0x00050f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00050e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050f08, 0x00050f08, 0x00070e09, 0x00060e08, 0x00050e08, 0x00050e07, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00050c08, 0x00070c08, 0x00080c09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x001d200a, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0038380c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005d5e11, 0x005e5f13, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646414, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00686614, 0x00a28916, 0x00cba418, 0x00caa418, 0x00907c14, 0x00595a11, 0x00585810, 0x00535410, 0x00505010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f07, 0x00040f07, 0x00040f07, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00050c08, 0x00050c08, 0x00050c08, 0x00040d08, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008120d, 0x0007110c, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x00050f0a, 0x0007100b, 0x00070f0a, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f07, 0x00050e07, 0x00070f09, 0x00040c08, 0x00090f0a, 0x0013140e, 0x002e2b24, 0x003b372d, 0x00463f34, 0x004d4339, 0x0051433a, 0x005a4941, 0x0058463c, 0x005a4539, 0x00573f30, 0x00543c2b, 0x004c321f, 0x00593f2b, 0x005e432d, 0x005a3c22, 0x0058361a, 0x00543213, 0x0054300d, 0x00532c09, 0x0058300c, 0x00502702, 0x005c320c, 0x005c310c, 0x005c300b, 0x00643814, 0x00623610, 0x00643712, 0x00683915, 0x006b3c18, 0x006a3c15, 0x006a3c14, 0x00693c15, 0x00693c15, 0x006c3e18, 0x00643811, 0x0060340d, 0x00603512, 0x005e3312, 0x005b3214, 0x00552c11, 0x00512811, 0x0049230b, 0x004c280f, 0x0047240b, 0x0048230a, 0x0049250c, 0x00452107, 0x00482408, 0x00502a0d, 0x00542d0c, 0x0059310c, 0x005b300c, 0x0060340f, 0x00603310, 0x00643413, 0x00643512, 0x0062340f, 0x0064350f, 0x0062340f, 0x00603210, 0x00603210, 0x005b2e0c, 0x00582c0b, 0x00562b0b, 0x0054290a, 0x0051280b, 0x00502609, 0x0051280c, 0x0053280c, 0x0054290f, 0x00542b10, 0x0053280c, 0x00582d10, 0x005b3010, 0x005b300f, 0x005a330f, 0x005a3210, 0x0056300d, 0x00542e0c, 0x00512c09, 0x00522c0b, 0x0050290a, 0x0050280c, 0x004b240b, 0x004c270e, 0x004b250d, 0x00441e07, 0x00462209, 0x003f2009, 0x003b1d0b, 0x00301a0c, 0x001a0e01, 0x000c0e04, 0x00090e06, 0x000c0f08, 0x0016100a, 0x00211608, 0x00281c0c, 0x002d1e0c, 0x0034210f, 0x00312113, 0x002a1c12, 0x00241a12, 0x001a170f, 0x0013140d, 0x000e130d, 0x000a100b, 0x00081009, 0x00060e09, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00050d09, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060d0b, 0x00060d0b, 0x00060e08, 0x00060e08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050d09, 0x00050d09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e06, 0x00060e06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c08, 0x00070c08, 0x00080c09, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x00494a0f, 0x004f500f, 0x006f6111, 0x00cca216, 0x00c29c16, 0x005c5a11, 0x005b5b12, 0x005c5c11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606012, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00626312, 0x00616112, 0x00626312, 0x00626312, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646514, 0x00646513, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x006c6914, 0x00a48c17, 0x00caa419, 0x00cba418, 0x00a58b16, 0x00616012, 0x00595a11, 0x00585810, 0x00535410, 0x00505010, 0x004c4d0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00050d08, 0x00040c08, 0x0008100b, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00041004, 0x00041004, 0x00041004, 0x00041004, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d09, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d09, 0x00050f0a, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x00040f09, 0x00040f09, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0008120c, 0x0008120c, 0x0008120c, 0x0008120c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x00040e09, 0x00050e09, 0x00070f0a, 0x00070f0a, 0x00060f09, 0x00050d08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00060f08, 0x00040d07, 0x00080e08, 0x0010110b, 0x0027241e, 0x0038342a, 0x004b433a, 0x004c4238, 0x0051433c, 0x0057463f, 0x00544239, 0x00554035, 0x00553e30, 0x00543929, 0x004c321e, 0x005b412d, 0x005e432d, 0x005c3e24, 0x0058381b, 0x00543011, 0x00542e0e, 0x00542d0d, 0x00583010, 0x00522a0b, 0x005e3414, 0x005c3311, 0x00582d0e, 0x005d3212, 0x005c3010, 0x00643817, 0x00613514, 0x00653817, 0x00683b18, 0x006a3d19, 0x00683c17, 0x00693d18, 0x006a4019, 0x00643913, 0x00613610, 0x00613611, 0x005f340e, 0x005e3210, 0x005c2f10, 0x00582d10, 0x00542b0e, 0x00542c0f, 0x0050290c, 0x004e2708, 0x00522b0d, 0x0050280b, 0x00532c0c, 0x00572f0c, 0x00582f09, 0x0060360f, 0x0060330d, 0x005f310b, 0x00643710, 0x00633410, 0x0062340e, 0x005e300c, 0x00603210, 0x005f320f, 0x005d300f, 0x005a2f0e, 0x00572b0c, 0x00542a0b, 0x0051280b, 0x004f2709, 0x004c240a, 0x004a2108, 0x004b2309, 0x004d240b, 0x004f260c, 0x004f260c, 0x00542b10, 0x00592f11, 0x005a3010, 0x005c310f, 0x005b3410, 0x005b3310, 0x00552f0c, 0x00512b08, 0x00512c08, 0x00512b0a, 0x0050290a, 0x00522c10, 0x004b240c, 0x004b250d, 0x004b250f, 0x00462009, 0x0044220c, 0x003a1f0a, 0x00361b0c, 0x00291409, 0x00180d05, 0x000d0e04, 0x00090e05, 0x000d1007, 0x0016100a, 0x00201709, 0x0024190a, 0x00251708, 0x002a190c, 0x002c1e14, 0x00281c14, 0x00211b14, 0x00191710, 0x00141410, 0x000e140e, 0x000a110c, 0x00081009, 0x00060e0a, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00050d09, 0x00050d09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060d0b, 0x00060d0b, 0x00060e08, 0x00060e08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e06, 0x00060e06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c08, 0x00060c08, 0x00070d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x006e6011, 0x00cca215, 0x00c29c15, 0x005c5911, 0x00595a12, 0x005b5b12, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x00626313, 0x00636414, 0x00636414, 0x00646414, 0x00646514, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00686814, 0x00847815, 0x00b59718, 0x00cba519, 0x00cba419, 0x00ac9016, 0x00686413, 0x005d5e12, 0x005b5b12, 0x00585810, 0x00545511, 0x00505010, 0x004c4d0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00051008, 0x00051007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f07, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0006100b, 0x00050e09, 0x00070f0a, 0x0008100b, 0x00060e09, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00040e07, 0x00080e08, 0x000c0d07, 0x001c1812, 0x00332e26, 0x00463e36, 0x004d4239, 0x0053443d, 0x0056453e, 0x00534239, 0x0058443a, 0x005a4234, 0x004f3422, 0x004e3420, 0x005c422e, 0x005d412c, 0x005e4025, 0x005a381b, 0x00563010, 0x00542d0d, 0x00572f13, 0x00572e14, 0x00532c11, 0x00563013, 0x00552f13, 0x00563014, 0x00542d0f, 0x00583012, 0x00603818, 0x005a3112, 0x005e3414, 0x00623817, 0x00663c1b, 0x00623816, 0x00623815, 0x00653b16, 0x00643a14, 0x00663c15, 0x00653a14, 0x0060350d, 0x0060340c, 0x0060320d, 0x00603210, 0x005f3310, 0x005c320f, 0x00562e0a, 0x00572f0b, 0x0058300c, 0x005b320f, 0x005f3610, 0x00623810, 0x0063380e, 0x006b3d14, 0x006a3c13, 0x00673810, 0x00683910, 0x0064360d, 0x0062340e, 0x005f310d, 0x005e3110, 0x005a2e0e, 0x00582c0e, 0x00542b0d, 0x0051280c, 0x0050270b, 0x004d250c, 0x004b240a, 0x0048210a, 0x00441e08, 0x00441e06, 0x00482209, 0x00502812, 0x00532b13, 0x00582f13, 0x00542c0d, 0x00592f0e, 0x005c3310, 0x005d3511, 0x005d3511, 0x0057310c, 0x00512c06, 0x00502a07, 0x004f2809, 0x00512b10, 0x004f2a10, 0x0049240c, 0x004c2810, 0x004c2a14, 0x00482510, 0x00452510, 0x00381f0c, 0x00341b0e, 0x00241108, 0x00140c04, 0x000d0f07, 0x00080f05, 0x000c1008, 0x0016110a, 0x001f1809, 0x00261c0d, 0x00281c10, 0x0024150c, 0x0022140d, 0x001e1610, 0x001b1511, 0x00151511, 0x00121510, 0x000f140e, 0x000b120c, 0x0008110a, 0x00070f0a, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00070f0a, 0x0008100b, 0x00050d09, 0x00040c08, 0x00040c08, 0x00060c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080d09, 0x00070d09, 0x00060e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c0a, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c0a, 0x00040c0a, 0x00060d0b, 0x00060d0b, 0x00060e08, 0x00060e08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e06, 0x00060e06, 0x00040f06, 0x00040f06, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00050c08, 0x00050c08, 0x00060d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003c3e0d, 0x0041420d, 0x0044450e, 0x0048490f, 0x004c4d0f, 0x006d6011, 0x00cca215, 0x00c29c15, 0x005c5911, 0x005b5910, 0x005c5c11, 0x005e5d12, 0x00605e12, 0x00605e12, 0x00605f12, 0x00616012, 0x00616012, 0x00616012, 0x00626113, 0x00626113, 0x00626113, 0x00626113, 0x00626113, 0x00626113, 0x00626113, 0x00636213, 0x00636213, 0x00646413, 0x00646412, 0x00646412, 0x00656514, 0x00666614, 0x00666614, 0x00686714, 0x00686814, 0x00696814, 0x006a6914, 0x006b6a14, 0x006c6b14, 0x00706d14, 0x007b7315, 0x008f7f16, 0x00af9418, 0x00c6a319, 0x00cca61a, 0x00caa519, 0x00a88d17, 0x006a6713, 0x00606013, 0x005d5e12, 0x005b5b12, 0x00585810, 0x00545511, 0x00505010, 0x004c4d10, 0x0047480e, 0x0043440e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00040c08, 0x00060e09, 0x00060e09, 0x00040e07, 0x00040e06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0004100a, 0x0004100a, 0x0005100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100b, 0x0005100b, 0x0005100b, 0x0005100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00060f09, 0x00070f0a, 0x0008100b, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070e08, 0x000c0c07, 0x0012100a, 0x002e2921, 0x003a332a, 0x00453b32, 0x004c3e36, 0x0057453f, 0x00524238, 0x00544134, 0x00553e2f, 0x004c321f, 0x004f3520, 0x005d442f, 0x00644830, 0x005c3f25, 0x0059381a, 0x00583212, 0x00532c0f, 0x00522b10, 0x00502910, 0x004a250c, 0x004c280e, 0x004c280d, 0x004f2c11, 0x004f2c10, 0x004f2a0e, 0x00522e10, 0x00573012, 0x00603a1c, 0x005d3718, 0x00603a19, 0x00623919, 0x00613918, 0x00633916, 0x00633a15, 0x00683e18, 0x00683c14, 0x00673b11, 0x00683a10, 0x00673810, 0x00673811, 0x00653812, 0x00633811, 0x00603610, 0x005f350f, 0x005f350f, 0x00623811, 0x00653c14, 0x00673d13, 0x00693d12, 0x006c3f14, 0x006c3c13, 0x006c3c13, 0x0068380f, 0x0063340c, 0x0061330d, 0x0060330f, 0x005c2f0f, 0x00542a0c, 0x0051280c, 0x0050270b, 0x004e270c, 0x004e270c, 0x004b230a, 0x00492108, 0x004a220b, 0x00461e07, 0x00461d06, 0x00482109, 0x0049230c, 0x00512a13, 0x00532a0f, 0x00522809, 0x00592f0d, 0x005c330f, 0x005e370f, 0x005d360e, 0x0059320c, 0x00542d08, 0x00502908, 0x004c2406, 0x004c280c, 0x0048240a, 0x0049260c, 0x0044230c, 0x0043220c, 0x0040200c, 0x003c1c0a, 0x00361e0c, 0x00301b10, 0x001e1007, 0x00100c04, 0x000c1008, 0x00091007, 0x000c1006, 0x00141309, 0x001d1809, 0x00261c10, 0x002c2015, 0x002a1c14, 0x0020140f, 0x001c140f, 0x00181410, 0x00131510, 0x00111410, 0x000e140e, 0x000b120c, 0x0008110a, 0x00070f09, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00040c08, 0x00050c08, 0x00080c08, 0x00080c08, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070d09, 0x00060e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080d09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00050d08, 0x00050c0a, 0x00050d09, 0x00040c08, 0x00040d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c09, 0x00040c0a, 0x00060d0b, 0x00060e0a, 0x00060e08, 0x00060e08, 0x00040f08, 0x00031008, 0x00031008, 0x00031008, 0x00040f08, 0x00050e08, 0x00060e08, 0x00060e09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e07, 0x00060e06, 0x00040f06, 0x00031006, 0x00050f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d08, 0x00040c08, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a0f, 0x006c5f10, 0x00cca215, 0x00c9a016, 0x00ba9615, 0x00ba9615, 0x00ba9715, 0x00ba9716, 0x00ba9716, 0x00ba9716, 0x00ba9816, 0x00ba9815, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00ba9817, 0x00bb9818, 0x00bb9818, 0x00bb9818, 0x00bb9818, 0x00bb9817, 0x00bb9917, 0x00bb9917, 0x00bb9a18, 0x00bb9a18, 0x00bb9b18, 0x00bb9b18, 0x00bb9b18, 0x00bc9b18, 0x00bc9c19, 0x00bc9c19, 0x00bd9d18, 0x00c4a119, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00c3a119, 0x00978415, 0x00686714, 0x00636414, 0x00616112, 0x005e5f12, 0x005b5b11, 0x00585910, 0x00545511, 0x00515110, 0x004c4d10, 0x0048490e, 0x0044450e, 0x003e400c, 0x00393b0d, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050c07, 0x00080c08, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x0008100b, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050f08, 0x00051008, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x0004100a, 0x00041009, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f0b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060f09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050f08, 0x00070e08, 0x00090e08, 0x000e0e08, 0x0027241c, 0x00322c24, 0x003e342d, 0x004a3d36, 0x00504038, 0x0049392f, 0x004e3c2f, 0x004c3726, 0x004b301d, 0x00493019, 0x0058412a, 0x00614830, 0x005d4026, 0x005a381b, 0x00553111, 0x00542f10, 0x00552f13, 0x00502a11, 0x0046230a, 0x0044220b, 0x0044220b, 0x0045230a, 0x00462409, 0x0049280b, 0x00502d11, 0x00583416, 0x005c381b, 0x005b3617, 0x005c3618, 0x005d3618, 0x00603818, 0x00613818, 0x00633918, 0x00643915, 0x00653813, 0x00663910, 0x00673a10, 0x00673810, 0x00673811, 0x00673912, 0x00673a15, 0x00683c17, 0x00663b17, 0x00633813, 0x00603510, 0x0060340f, 0x00603410, 0x00603410, 0x00623510, 0x00633411, 0x0060310e, 0x005c2c0b, 0x00582806, 0x00582806, 0x00502301, 0x004c2000, 0x004b2003, 0x00461d01, 0x00451c00, 0x004b2102, 0x00512708, 0x00582d0f, 0x00592f13, 0x005c3115, 0x00562b0e, 0x0052280a, 0x004f250b, 0x0048220a, 0x004c240c, 0x00502708, 0x00542909, 0x0059300c, 0x005c340c, 0x0060370c, 0x005d340a, 0x00583008, 0x00562c08, 0x0050280b, 0x004c270a, 0x004a260b, 0x00462408, 0x0045230b, 0x0042220b, 0x0040210c, 0x003d200d, 0x00351c0b, 0x00321b0d, 0x0026150a, 0x00130a03, 0x00100e07, 0x000b1208, 0x000a1008, 0x000c1005, 0x00141409, 0x00191409, 0x00251910, 0x002d1c15, 0x002f2018, 0x00251910, 0x001c140b, 0x0018140c, 0x0012140c, 0x000f130e, 0x000e140e, 0x000c140e, 0x0009110b, 0x00070f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070e0c, 0x00070f0a, 0x00060e09, 0x00060e08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280c, 0x002c2d0b, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0044450d, 0x0048490f, 0x00565210, 0x00b08d14, 0x00cca215, 0x00cca216, 0x00cca316, 0x00cca316, 0x00cca316, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca518, 0x00cca518, 0x00cca519, 0x00cca519, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00caa61a, 0x00c3a119, 0x00a99017, 0x007c7315, 0x00656614, 0x00646514, 0x00636414, 0x00616112, 0x005e5f12, 0x005c5c11, 0x00585910, 0x00555610, 0x00515110, 0x004c4d10, 0x0048490f, 0x0044450e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050c07, 0x00060c08, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x0004100a, 0x00041009, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f0b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110c, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060f0a, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f08, 0x00080e08, 0x000c0f08, 0x001c1a14, 0x002a251e, 0x003c342d, 0x004b4038, 0x004e4038, 0x00473a30, 0x00534435, 0x00543d2c, 0x00543a27, 0x00503721, 0x005c432c, 0x00644b33, 0x00604328, 0x005c3c1d, 0x00563211, 0x00573211, 0x00583414, 0x00502a0f, 0x00482409, 0x0049250c, 0x004a240b, 0x00472108, 0x00441e03, 0x00482406, 0x00502b0c, 0x00522d0e, 0x00512c0e, 0x00532e10, 0x00542f10, 0x00542d0f, 0x00552d10, 0x00552c0f, 0x00572c0f, 0x00582e0d, 0x00582e09, 0x00582e07, 0x00582d07, 0x00582c07, 0x005a2c09, 0x005a2d0a, 0x005b2e0c, 0x005c2f0e, 0x005a2e0f, 0x00572b0c, 0x00512507, 0x00502406, 0x004f2304, 0x00502407, 0x00532408, 0x00542508, 0x00522204, 0x004e1d00, 0x004c1c00, 0x004c1d00, 0x004c1c00, 0x004f1f01, 0x00502104, 0x004f2304, 0x00542706, 0x00603210, 0x00683b15, 0x006c3f19, 0x0070421c, 0x0070411c, 0x00693b16, 0x00623410, 0x00582e0c, 0x004e2508, 0x004c240b, 0x00522a0b, 0x00572d0b, 0x005c340f, 0x00603610, 0x005d340c, 0x00582f07, 0x00562c08, 0x00532908, 0x0052280c, 0x00522c10, 0x00472208, 0x00412006, 0x0044240c, 0x0041220c, 0x003f210c, 0x003c200d, 0x00341c0b, 0x002d170a, 0x00211409, 0x00130c04, 0x000e0e07, 0x000c1108, 0x000c100a, 0x000e0f07, 0x00151409, 0x001d150b, 0x0023140a, 0x0029170d, 0x00312014, 0x00302416, 0x00281f14, 0x00211c13, 0x001c1b14, 0x00151711, 0x000d120c, 0x00091009, 0x00070f08, 0x00060e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040c0a, 0x00040c08, 0x00060e09, 0x00060e08, 0x00050d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x0014180f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0045470e, 0x00494a10, 0x00605810, 0x00a08212, 0x00a48613, 0x00a58814, 0x00a58814, 0x00a58814, 0x00a58814, 0x00a58814, 0x00a48814, 0x00a58814, 0x00a48914, 0x00a58914, 0x00a48914, 0x00a48914, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48814, 0x00a48915, 0x00a48815, 0x00a48815, 0x00a48915, 0x00a48916, 0x00a48a15, 0x00a48b15, 0x00a48b16, 0x00a48b16, 0x00a48b16, 0x00a48c16, 0x00a48c18, 0x00a48c18, 0x00a48c18, 0x009e8917, 0x00908016, 0x00777114, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00646414, 0x00626312, 0x005e5f13, 0x005c5c11, 0x00585911, 0x00555610, 0x00515110, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d08, 0x00060c08, 0x00060d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00020e08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x0004100a, 0x00041009, 0x00040d08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060f09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e0b, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00061009, 0x00061009, 0x00061009, 0x00061009, 0x00070f08, 0x00070f08, 0x00081009, 0x00060f08, 0x00040d05, 0x00071007, 0x00071007, 0x00071007, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00051009, 0x00051008, 0x00061009, 0x00070f0a, 0x00070f0a, 0x0007100b, 0x000a100a, 0x00191c16, 0x0025241e, 0x00342e28, 0x00433932, 0x00493e34, 0x0044382d, 0x004c3c2f, 0x00553f30, 0x00503724, 0x00503420, 0x00573d27, 0x00634932, 0x00604429, 0x005c3b1d, 0x005c3815, 0x0058330f, 0x00532d0c, 0x004f280a, 0x004b2607, 0x004b2406, 0x00522c0d, 0x00542e0f, 0x00532b0c, 0x00542c0c, 0x00572f0d, 0x00512908, 0x004d2605, 0x004c2507, 0x004c2506, 0x004d2406, 0x004e2508, 0x0051260b, 0x0050250a, 0x00502408, 0x004f2504, 0x004f2504, 0x004e2403, 0x004c2102, 0x004c2000, 0x004b1e00, 0x004c1f02, 0x004b1c00, 0x00481c00, 0x00481c01, 0x00471b00, 0x00451800, 0x00421600, 0x00431800, 0x00461900, 0x004b1c01, 0x004c1d01, 0x00542408, 0x005c2c10, 0x005d2c10, 0x005e2c0f, 0x00643114, 0x00643011, 0x00653311, 0x006b3814, 0x00744018, 0x00713e13, 0x00744214, 0x00764416, 0x00744013, 0x00703d10, 0x0065360a, 0x005d3008, 0x00582c0c, 0x00542b0f, 0x00542c0b, 0x005c3210, 0x005e3510, 0x005e350e, 0x005c330c, 0x00572d08, 0x00512806, 0x004f2407, 0x0051280d, 0x004e280f, 0x0048240c, 0x00401f06, 0x0040220b, 0x003e200a, 0x003c1f0c, 0x003e2210, 0x00321a0a, 0x002a160a, 0x001c1006, 0x00130f08, 0x000e100a, 0x000e100a, 0x000f100a, 0x00141009, 0x0019150c, 0x0021170d, 0x0028160d, 0x002a1408, 0x002e1b0a, 0x00312211, 0x002d2012, 0x00271e14, 0x001e1a13, 0x0013140f, 0x000c110c, 0x0009100a, 0x00081009, 0x00060e08, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060d0b, 0x00060e09, 0x00070f0a, 0x00070f09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00050e08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250b, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x003c3e0c, 0x0040400d, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4c0f, 0x004d4d10, 0x00505010, 0x00515110, 0x00535410, 0x00545411, 0x00555511, 0x00555511, 0x00565711, 0x00565710, 0x00585810, 0x00585810, 0x00585810, 0x00585810, 0x00585810, 0x00585811, 0x00585811, 0x00585811, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x005c5c12, 0x005d5d12, 0x005e5f13, 0x00606013, 0x00606013, 0x00626213, 0x00636314, 0x00646414, 0x00656514, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00686814, 0x00686814, 0x00646513, 0x00646414, 0x00616112, 0x005e5f13, 0x005c5c11, 0x00595a11, 0x00555610, 0x00515110, 0x004d4e0f, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x0026280a, 0x0024250b, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040d08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040f09, 0x0005100b, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x0004100a, 0x00041009, 0x00040d08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060f09, 0x00040d08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060d08, 0x00070d09, 0x00060e0b, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110c, 0x0009110d, 0x00070f0b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x00061009, 0x00061009, 0x00061009, 0x00061009, 0x00071007, 0x00071007, 0x0009120a, 0x00081008, 0x00040d05, 0x00071007, 0x00071007, 0x00071007, 0x0007110a, 0x0007110c, 0x0005100a, 0x0005100a, 0x00051009, 0x00051008, 0x00061009, 0x00070f0a, 0x00070f0a, 0x0006100b, 0x0009110b, 0x00161b15, 0x00282923, 0x002c2c25, 0x00353129, 0x00443c33, 0x00443c30, 0x00554538, 0x00554030, 0x00543928, 0x004c301c, 0x00573d29, 0x005e442e, 0x005e4227, 0x005a3b1c, 0x00573410, 0x0058340e, 0x00583210, 0x00542e0d, 0x00552d0d, 0x00532b09, 0x005b3210, 0x00633917, 0x00653c18, 0x00683e1c, 0x006c421f, 0x00683f1e, 0x00623818, 0x005e3618, 0x005e3618, 0x005e3519, 0x005d3519, 0x005e3418, 0x005c3015, 0x005c3010, 0x0054290a, 0x00532707, 0x00522507, 0x00502206, 0x00502004, 0x004d1d01, 0x004c1c00, 0x004c1d00, 0x004c1d00, 0x004d1e00, 0x00512103, 0x00542507, 0x00552809, 0x005c2f10, 0x005e3011, 0x00623414, 0x00663818, 0x00653617, 0x00673717, 0x00683616, 0x00693616, 0x006a3514, 0x006a3411, 0x006d3812, 0x00713a12, 0x00743f12, 0x00723c0c, 0x0076410c, 0x0078430e, 0x00753f0a, 0x00703d08, 0x006a3a08, 0x00633308, 0x005c2f0c, 0x005a2e10, 0x00572d0c, 0x005c3310, 0x005c340e, 0x005c340c, 0x005b320b, 0x00542a05, 0x00512806, 0x004e2508, 0x004e240a, 0x0048220a, 0x00431f08, 0x00412109, 0x0040210c, 0x003d1e09, 0x003b1d0b, 0x00361808, 0x00341c0c, 0x0028180c, 0x00170e04, 0x00121108, 0x000e110b, 0x000f100a, 0x00100f09, 0x0017130b, 0x001e170e, 0x00251810, 0x0028180d, 0x002a1609, 0x002e1c0b, 0x0030210f, 0x002b1e0e, 0x00261c10, 0x001d1810, 0x0013140f, 0x000c140d, 0x0009130c, 0x0007110a, 0x00061009, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00030f09, 0x00040e09, 0x00060e09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e07, 0x00050e06, 0x00050e06, 0x00050e06, 0x00060e08, 0x00060e09, 0x00050d09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00050d08, 0x00060e09, 0x00060e09, 0x00040f08, 0x00040f08, 0x00031008, 0x00021008, 0x00031008, 0x00040f08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0a, 0x002c2d0a, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x004f5010, 0x00505010, 0x00515110, 0x00525310, 0x00535410, 0x00545510, 0x00545510, 0x00555611, 0x00545511, 0x00555611, 0x00565711, 0x00555610, 0x00555611, 0x00565710, 0x00565710, 0x00565710, 0x00585910, 0x00585911, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005d5e11, 0x005e5f12, 0x00606013, 0x00616112, 0x00626313, 0x00646414, 0x00646514, 0x00666714, 0x00686815, 0x006b6a14, 0x008a7c15, 0x008d7e15, 0x008d7e15, 0x008d7e15, 0x008c7d15, 0x008c7d16, 0x008c7c14, 0x008b7b14, 0x008b7a14, 0x00897814, 0x007c6f13, 0x005b5a11, 0x00555610, 0x00525310, 0x004d4e0f, 0x0048490f, 0x0045470e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00080d09, 0x00080c09, 0x00080d09, 0x00050e09, 0x00040e09, 0x00030d08, 0x00010d08, 0x00030f09, 0x00030f09, 0x0004100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x00090f0b, 0x00090f0b, 0x000a100c, 0x000a100c, 0x00081009, 0x00081009, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110a, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x0008110a, 0x0008110a, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x0008100b, 0x000c130f, 0x00131913, 0x002a2e29, 0x002e2f2a, 0x00323029, 0x00383329, 0x00403a2d, 0x00504434, 0x00534030, 0x0058402e, 0x00503422, 0x00533824, 0x00543924, 0x005c4025, 0x00563819, 0x0052310e, 0x005c3814, 0x005a3310, 0x0058300d, 0x005b3110, 0x005d330e, 0x00613610, 0x00673c14, 0x00683e14, 0x006c4219, 0x00744822, 0x00764a28, 0x00744728, 0x00714729, 0x006e4428, 0x006a4125, 0x00673d23, 0x006b401b, 0x0070431b, 0x00744218, 0x00764017, 0x00754018, 0x00743e19, 0x00743d1b, 0x00733d18, 0x00703d15, 0x006f3c14, 0x006c3910, 0x006c3910, 0x006c3a10, 0x006f3c13, 0x00703e15, 0x00703d16, 0x00703c15, 0x006d3b14, 0x006c3a13, 0x00693810, 0x00673610, 0x0067350f, 0x0068350f, 0x006a350f, 0x006a3510, 0x006c370f, 0x006c370c, 0x006e370a, 0x00703809, 0x00723a0a, 0x00743c0c, 0x00773f0d, 0x00753d0c, 0x00713b0c, 0x006d3c11, 0x0066360d, 0x005c2f09, 0x00592e0a, 0x005b320e, 0x005b330f, 0x005a330d, 0x005c320d, 0x005b320c, 0x00502804, 0x004e2805, 0x004f2809, 0x004c240b, 0x0048220a, 0x00411f07, 0x0040230c, 0x003e210c, 0x003c1f0a, 0x003c200e, 0x00351709, 0x0032180c, 0x001c1003, 0x00161004, 0x00111208, 0x0010140b, 0x0012110a, 0x00161008, 0x001e140b, 0x0024180d, 0x002a1a11, 0x002d1b11, 0x0028170a, 0x002a1908, 0x00302110, 0x002d2011, 0x00271d10, 0x00201710, 0x00151510, 0x000e150f, 0x000b130c, 0x0008120b, 0x0007110a, 0x0006100b, 0x0006100b, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0009120c, 0x0009120c, 0x0009130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a120c, 0x0009110c, 0x0009110c, 0x000a120e, 0x000a120e, 0x0009110d, 0x0008100c, 0x0008100c, 0x0008100c, 0x0009120b, 0x000a130c, 0x000a130c, 0x000a130c, 0x00081109, 0x00081109, 0x00081108, 0x00081008, 0x0009100b, 0x00080f0a, 0x00060e09, 0x00060f0a, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d09, 0x00040d09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00080f0a, 0x00081009, 0x00060e08, 0x00040d07, 0x00040e07, 0x00030e07, 0x00030e07, 0x00041008, 0x00041008, 0x0004100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00060b07, 0x00050b05, 0x00070c06, 0x00070d06, 0x00060f08, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040e07, 0x00020e07, 0x00020e07, 0x00031008, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280a, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004b4c0f, 0x004c4d0f, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00525310, 0x00535410, 0x00535410, 0x00535410, 0x00545510, 0x00535410, 0x00545510, 0x00555611, 0x00545510, 0x00565711, 0x00565711, 0x00585810, 0x00585911, 0x00595a12, 0x005c5c11, 0x005d5e11, 0x005e5f13, 0x00606013, 0x00616112, 0x00636414, 0x00646514, 0x00666713, 0x00686714, 0x00a48c17, 0x00c8a519, 0x00caa51a, 0x00caa51a, 0x00caa51a, 0x00caa51a, 0x00caa41a, 0x00c9a419, 0x00c9a419, 0x00c9a418, 0x00c9a318, 0x00c7a017, 0x008e7a13, 0x00545511, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0040400d, 0x003c3e0d, 0x0036370c, 0x0032330c, 0x002d2f0a, 0x0026280a, 0x0026280c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00080d09, 0x00080c09, 0x00080c09, 0x00050e09, 0x00040e09, 0x00030d08, 0x00010d08, 0x00030f09, 0x00030f09, 0x0004100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x00081009, 0x00081009, 0x0008110b, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120b, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x00081108, 0x0008110a, 0x0008110a, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0009100b, 0x00080f0a, 0x000b100c, 0x000e1310, 0x001a1e1b, 0x00303532, 0x0031322e, 0x002e2c26, 0x002d2920, 0x003d372a, 0x00473c2c, 0x00483928, 0x00503b28, 0x00533826, 0x0049301a, 0x0050351f, 0x00583c23, 0x0056381b, 0x00523211, 0x005b3716, 0x00593412, 0x005a310e, 0x005c320e, 0x00623711, 0x00693c14, 0x00683c12, 0x006e4218, 0x0070441a, 0x00784b24, 0x00764a28, 0x00754829, 0x0075482b, 0x0072462b, 0x006e4428, 0x006b4124, 0x006b411c, 0x006d4018, 0x00704015, 0x00743f14, 0x00763d13, 0x00783c13, 0x00783c13, 0x00783d13, 0x007c4217, 0x007c4317, 0x00774012, 0x00753d11, 0x00743c10, 0x00743c10, 0x00743c10, 0x00743c11, 0x00723a10, 0x006e350c, 0x006c360b, 0x0069340b, 0x0068350b, 0x0066360c, 0x0066370c, 0x0067370f, 0x0067370f, 0x0067360d, 0x0068360a, 0x006a3709, 0x006f3909, 0x00703a09, 0x00713b0a, 0x00743e0c, 0x00733d0c, 0x006f3a0b, 0x006d3c11, 0x0066360e, 0x005a2c06, 0x005c310c, 0x005e3511, 0x005c3511, 0x0058310c, 0x0058310c, 0x00552f09, 0x00512b06, 0x00492604, 0x00492708, 0x004a260c, 0x00432008, 0x003c1c05, 0x0040220c, 0x003d200c, 0x003c1f0b, 0x003c200e, 0x00371b0d, 0x002c170a, 0x00140c00, 0x00141006, 0x00141309, 0x0014140c, 0x0018140b, 0x001c1209, 0x0024170d, 0x00291b11, 0x002d1c12, 0x002d1d11, 0x002b1b0e, 0x0029190b, 0x002b1c0e, 0x002a1c10, 0x00271d12, 0x00211811, 0x00161610, 0x000f150e, 0x000c140e, 0x000b150e, 0x000a140d, 0x0009130e, 0x0009130e, 0x0008120c, 0x0008120c, 0x0008120d, 0x0008120d, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x0009110d, 0x0009110d, 0x000a120e, 0x000a120e, 0x000a120e, 0x000a120e, 0x000a120e, 0x000a120e, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x00081109, 0x00081108, 0x0009120a, 0x000a130b, 0x000b120d, 0x0009100c, 0x00070f0a, 0x00060f0a, 0x0006100b, 0x0006100b, 0x00050f0a, 0x0006100b, 0x0006100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00080f0a, 0x00091009, 0x00060e08, 0x00040d07, 0x00040e07, 0x00020e07, 0x00020e07, 0x00041008, 0x00041008, 0x0004100a, 0x0005100a, 0x00060e09, 0x00060e09, 0x00080c09, 0x00080c08, 0x00070d08, 0x00070e06, 0x00050f08, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040e07, 0x00020e07, 0x00020e07, 0x00031008, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0c, 0x00191c09, 0x001d2009, 0x00202308, 0x0020230a, 0x0026280b, 0x00292b0a, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003c3e0c, 0x0040400d, 0x0041420e, 0x0044450d, 0x0047480e, 0x0048490f, 0x00494a0f, 0x004b4c0f, 0x004c4d0f, 0x004f5010, 0x004f5010, 0x00505010, 0x004f5010, 0x00515110, 0x00505010, 0x00505010, 0x00515110, 0x00515110, 0x00525310, 0x00535410, 0x00535410, 0x00545510, 0x00545511, 0x00555611, 0x00565710, 0x00585911, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00626313, 0x00646414, 0x00656614, 0x006a6714, 0x00c5a219, 0x00cca71a, 0x00c4a019, 0x00c1a019, 0x00c1a019, 0x00c1a018, 0x00c19f18, 0x00c19f18, 0x00c19f18, 0x00c19f18, 0x00c6a018, 0x00cca418, 0x00b09014, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003b3c0c, 0x0036370b, 0x0034350c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040f09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00080d09, 0x00080c09, 0x00080c09, 0x00050e09, 0x00040e09, 0x00030d08, 0x00010d08, 0x00030f09, 0x0004100a, 0x0004100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x0008110a, 0x0008110a, 0x0009110d, 0x0009110d, 0x000a120e, 0x000a120e, 0x000a130c, 0x000a130c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009140b, 0x0009140b, 0x0009130b, 0x0009140b, 0x000b130c, 0x000b130c, 0x000b130c, 0x000b140b, 0x0009120c, 0x0009120c, 0x0009130c, 0x0009130c, 0x0009130c, 0x0009130c, 0x000b130e, 0x000b130f, 0x000b130e, 0x000b130e, 0x000b110e, 0x00101412, 0x00151918, 0x001c201e, 0x00222624, 0x00303230, 0x00343734, 0x00363733, 0x002d2b26, 0x0029251c, 0x00353024, 0x0041392a, 0x00403322, 0x00493523, 0x004c3521, 0x004b311a, 0x00523720, 0x00553b23, 0x0053351c, 0x00563519, 0x00573416, 0x005a3312, 0x005c320d, 0x005b310a, 0x005e340b, 0x00643a0f, 0x00693d10, 0x006c4013, 0x0070441b, 0x00754822, 0x00754925, 0x00714624, 0x00744728, 0x00744728, 0x00764c2c, 0x00734928, 0x006c4320, 0x006a3f19, 0x006c3e16, 0x00703d13, 0x00713b10, 0x0074390d, 0x0074390d, 0x0074390c, 0x00743a0d, 0x00743c0e, 0x00743c10, 0x00733b0f, 0x0070380c, 0x0070380c, 0x0070390c, 0x0070380e, 0x006d350c, 0x006a3208, 0x00693308, 0x00683309, 0x00663409, 0x0062360b, 0x0062370b, 0x0061370c, 0x0062370d, 0x0062360b, 0x0064380a, 0x006b3c0c, 0x006e3d0c, 0x006f3c0a, 0x00703d0b, 0x00713e0c, 0x006e3b09, 0x006b3808, 0x0068370d, 0x0062320a, 0x00582c05, 0x00582d08, 0x00562e08, 0x0058310c, 0x0059320c, 0x00562f09, 0x00522c09, 0x004c2907, 0x00462505, 0x00442608, 0x003c1d04, 0x003c1f07, 0x003c2008, 0x003a1e08, 0x003b1d09, 0x003e210f, 0x00371d0e, 0x00291405, 0x00201104, 0x00100c00, 0x000f0c02, 0x0015120c, 0x001a150e, 0x00241c12, 0x002a1d14, 0x002c1c11, 0x002d1c11, 0x002d1d11, 0x002e1e11, 0x002e1e10, 0x002f1f10, 0x002c1e11, 0x002a1d12, 0x00281e15, 0x00231914, 0x001a1812, 0x00131610, 0x000e140e, 0x000d140e, 0x000c140d, 0x000a120e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0008120c, 0x0008120d, 0x0009110c, 0x0009110d, 0x000a120e, 0x000a120e, 0x000c140d, 0x000c140d, 0x000c140e, 0x000c140d, 0x000c140d, 0x000c140e, 0x000d150f, 0x000d150f, 0x000c140f, 0x000c1410, 0x000c1410, 0x000d1510, 0x000d1510, 0x000d1510, 0x000d1510, 0x000c140f, 0x000a120e, 0x0009120c, 0x0009120c, 0x000c140d, 0x000c140d, 0x000a120b, 0x000c140c, 0x000a130b, 0x000a130b, 0x000b120d, 0x000b120e, 0x0009110d, 0x0008110c, 0x0008120c, 0x0009130e, 0x0009130e, 0x0008120c, 0x0008110c, 0x0009100c, 0x0009110c, 0x0008100c, 0x00070f0a, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f09, 0x00080e08, 0x00070f08, 0x00070f08, 0x00051008, 0x00031008, 0x00041008, 0x00041008, 0x00041008, 0x00030f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00090e0b, 0x00091009, 0x00080f08, 0x00061008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040e07, 0x00020e07, 0x00020e07, 0x00031008, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280a, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0040400d, 0x0043440e, 0x0044450d, 0x0045470e, 0x0047480f, 0x0048490f, 0x00494a0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004c4d0f, 0x004f5010, 0x004f5010, 0x004d4e10, 0x00505010, 0x00505010, 0x00505010, 0x00515110, 0x00515110, 0x00525310, 0x00535410, 0x00545511, 0x00555611, 0x00565710, 0x00585911, 0x005b5b12, 0x005c5d11, 0x005d5e12, 0x00606012, 0x00616112, 0x00626314, 0x00646414, 0x006a6714, 0x00c6a219, 0x00cca61a, 0x00847715, 0x00736e14, 0x00736e14, 0x00736e14, 0x00726d14, 0x00716c14, 0x00706a14, 0x006e6814, 0x009f8615, 0x00cca418, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x0030310c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040e09, 0x00080d09, 0x00080c09, 0x00080c09, 0x00050e09, 0x00040e09, 0x00030d08, 0x00010d08, 0x00030f09, 0x0004100a, 0x0006120c, 0x0007120c, 0x00070f08, 0x00070f08, 0x0008110a, 0x0008110a, 0x0008120d, 0x0008120d, 0x0009130e, 0x0009130e, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x0009120c, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x0008140b, 0x0008140b, 0x0009150c, 0x000a150c, 0x000c150c, 0x000c150c, 0x000c150c, 0x000c150c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c1410, 0x000c1410, 0x000c1411, 0x000d1412, 0x000e1411, 0x00141816, 0x001b1f1c, 0x00282c29, 0x00353837, 0x00393b3b, 0x00363837, 0x00343434, 0x002d2c28, 0x0026241b, 0x002a281b, 0x00383324, 0x00423827, 0x00493826, 0x0049341f, 0x004d341c, 0x0050341c, 0x00563b24, 0x0052351f, 0x00573820, 0x005a381c, 0x005c3614, 0x005b330c, 0x005e340a, 0x0063380e, 0x0064390c, 0x006a3f10, 0x006d4213, 0x0074471d, 0x00794b24, 0x00754824, 0x00744624, 0x00704422, 0x00704423, 0x00734928, 0x00704724, 0x006b441f, 0x00693f1a, 0x006c3f19, 0x00693a11, 0x0068380b, 0x006c380b, 0x006c380c, 0x006c380c, 0x006b370c, 0x006a370c, 0x006a380d, 0x0069370d, 0x0066340b, 0x0067340b, 0x0067350c, 0x0068350c, 0x0064320a, 0x00633008, 0x00613108, 0x00613108, 0x005f3208, 0x005d3409, 0x005c3409, 0x0060370c, 0x0060380c, 0x0061380c, 0x00643b0c, 0x006a3e0d, 0x006c3e0d, 0x006d3c0b, 0x00703e0c, 0x00713f0c, 0x006c3c09, 0x00693808, 0x0065340a, 0x005e2e06, 0x00582c05, 0x00562c08, 0x00522c07, 0x00542f08, 0x004e2904, 0x00512c08, 0x004c2907, 0x00482506, 0x00442608, 0x0042260a, 0x003a1e05, 0x003b2007, 0x00391e08, 0x00381b07, 0x003c1d0c, 0x00371b0a, 0x00321b0c, 0x00241204, 0x00150c00, 0x000e0d00, 0x000e0c03, 0x0018140d, 0x00201811, 0x002a1f14, 0x002f2015, 0x00302014, 0x00312014, 0x00312014, 0x00322214, 0x00322214, 0x00322213, 0x00302114, 0x002d2016, 0x002a2018, 0x00241b16, 0x001b1813, 0x00141510, 0x0010140f, 0x000f140e, 0x000c120c, 0x000a140f, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x000b1410, 0x000b1510, 0x000c140f, 0x000c140f, 0x000b130e, 0x000a120e, 0x000c140d, 0x000c140e, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000c1410, 0x000c1410, 0x000d1510, 0x000d1510, 0x000d1510, 0x000d1510, 0x000d1510, 0x000c140f, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140c, 0x000d160e, 0x000b130c, 0x000a130c, 0x000b120d, 0x000b120e, 0x000a120e, 0x000b130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0009110d, 0x0009110d, 0x0009100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f09, 0x00080e08, 0x00070f08, 0x00070f08, 0x00051008, 0x00041008, 0x00051009, 0x00041008, 0x00041008, 0x00040f09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00080f0b, 0x0008100a, 0x00070f08, 0x00061008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00040e07, 0x00030e07, 0x00030e07, 0x00041008, 0x00041008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250c, 0x0026280b, 0x002c2d0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003b3c0c, 0x003e400c, 0x0040400d, 0x0043440e, 0x0044450d, 0x0045470d, 0x0047480e, 0x0048490f, 0x00494a10, 0x004b4c10, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e10, 0x004f5010, 0x00505010, 0x00515110, 0x00515110, 0x00525310, 0x00545510, 0x00555611, 0x00585810, 0x00585911, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00626313, 0x00646414, 0x00696614, 0x00c6a218, 0x00cca61a, 0x007c7315, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00646514, 0x00646414, 0x00616112, 0x009b8415, 0x00cca418, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e09, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x00050f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e07, 0x00060e08, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070e09, 0x00080c09, 0x00080c0a, 0x00070c0b, 0x00060e0b, 0x0005100a, 0x0004100a, 0x0007110d, 0x0008120d, 0x0008110b, 0x0008120a, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0008120c, 0x0008120c, 0x0009140c, 0x0009140c, 0x000c140d, 0x000c140d, 0x000b140d, 0x000b140d, 0x000b140d, 0x000b140d, 0x000c140d, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d160d, 0x000d160d, 0x000c150c, 0x000c150c, 0x000d140c, 0x000d140c, 0x000e140c, 0x000e140c, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c1510, 0x000b1410, 0x000f1614, 0x00151b18, 0x00171b17, 0x0020231e, 0x00292c27, 0x00343632, 0x00363636, 0x00323234, 0x002f2f2f, 0x0023231f, 0x001b1a11, 0x00242418, 0x002a2819, 0x00373020, 0x00403220, 0x0046341e, 0x00483018, 0x004f341c, 0x00593e28, 0x00543624, 0x00573723, 0x005b381f, 0x005c3718, 0x005b340e, 0x005c340c, 0x00603810, 0x00643a10, 0x006a3e14, 0x006e4016, 0x00774820, 0x00754720, 0x00754823, 0x00744823, 0x00704520, 0x00704520, 0x006d441f, 0x0069401b, 0x00673d18, 0x00633a13, 0x00613810, 0x0062360d, 0x0062360a, 0x00603508, 0x0060340a, 0x0060340c, 0x0060340c, 0x005f330a, 0x005b3108, 0x00582f06, 0x00593008, 0x005a3008, 0x00593008, 0x00593008, 0x005c320c, 0x005b310b, 0x00582d08, 0x005d2f08, 0x005f3108, 0x00603308, 0x00613409, 0x0064350b, 0x0063360b, 0x0064380c, 0x00683c0f, 0x006b3c0e, 0x006c3c0c, 0x00703d0b, 0x006e3c09, 0x006c3a08, 0x006b3a09, 0x00653808, 0x005a2f04, 0x00562c02, 0x0058310a, 0x0058310a, 0x00542e08, 0x00502c08, 0x004a2804, 0x004c2c08, 0x00402000, 0x00402104, 0x0043240b, 0x00371a02, 0x00381d06, 0x00391c07, 0x00381c08, 0x00381c08, 0x003b1d0b, 0x00351a09, 0x002c1708, 0x00201207, 0x00100c01, 0x000c0f06, 0x000e0d05, 0x00171208, 0x0022170c, 0x002e2013, 0x00342519, 0x002c1f14, 0x002a1e14, 0x00302118, 0x00332518, 0x00332517, 0x00302212, 0x002d2012, 0x002c2115, 0x002b221a, 0x00221c16, 0x001a1812, 0x00171511, 0x00121410, 0x0011140f, 0x000f140f, 0x000a140f, 0x000a140f, 0x000a140f, 0x000a140f, 0x000b150e, 0x000b150e, 0x000b150e, 0x000b150e, 0x000d150f, 0x000e1610, 0x000d150f, 0x000d150f, 0x000e1610, 0x000e1710, 0x000f1710, 0x000d150f, 0x000e1710, 0x000f1811, 0x000f1811, 0x000e1710, 0x000e1710, 0x000e1612, 0x000e1612, 0x000e1612, 0x000f1713, 0x000e1612, 0x000e1612, 0x000e1612, 0x000e1612, 0x000e1710, 0x000f1610, 0x000e150f, 0x000e150f, 0x000e1510, 0x000e1510, 0x000e1510, 0x000e1510, 0x000e140f, 0x000d130d, 0x000c120c, 0x000c130d, 0x000c140e, 0x000c140d, 0x000b130c, 0x0009120c, 0x0009120c, 0x0009130e, 0x0009130e, 0x0008120c, 0x0008110c, 0x0007110c, 0x0006100b, 0x0007110c, 0x0007110c, 0x0008120d, 0x0007130d, 0x0006120c, 0x0005100b, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040f09, 0x0005100a, 0x00040d08, 0x00040e09, 0x00040e09, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060f0a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100d, 0x0008100c, 0x0008100b, 0x00090f0b, 0x00080f0a, 0x00070f0a, 0x00060e0a, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040c06, 0x00040c08, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100a, 0x00051008, 0x00040f08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x0038380c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0047480e, 0x0047480f, 0x00484910, 0x00484910, 0x00494a10, 0x004b4c10, 0x004b4c0f, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00525310, 0x00525310, 0x00545510, 0x00555611, 0x00585810, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00626312, 0x00636414, 0x00686514, 0x00c6a219, 0x00cca619, 0x007c7215, 0x00686814, 0x00686814, 0x00666714, 0x00656613, 0x00656614, 0x00636414, 0x00626312, 0x009b8415, 0x00cca418, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x004b4c10, 0x0047480e, 0x0041420e, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e0a, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0006100b, 0x0006100b, 0x0005100b, 0x0005100a, 0x00050f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00060e06, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00080f0b, 0x000a0f0b, 0x000a0f0c, 0x00090f0c, 0x00080f0b, 0x00070f08, 0x00051009, 0x0007110c, 0x0008120c, 0x0008130a, 0x0008130a, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c140e, 0x000c140e, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e170e, 0x000e170e, 0x000f1810, 0x000f1810, 0x0010160e, 0x0010160e, 0x0010160e, 0x0010160e, 0x000f1610, 0x000e1610, 0x000e1610, 0x000d1711, 0x000c1612, 0x00111815, 0x00151a17, 0x00181c16, 0x00272921, 0x00303028, 0x0034342e, 0x00323230, 0x002e2e2e, 0x00282828, 0x001b1c18, 0x0011130a, 0x001f2015, 0x0028281c, 0x00363024, 0x003b301f, 0x0042311c, 0x00432c15, 0x00472d16, 0x00523822, 0x00523625, 0x00563924, 0x0058391e, 0x00583616, 0x005b3713, 0x0059340e, 0x005c350f, 0x00613911, 0x006b3f17, 0x006e4218, 0x00754720, 0x00784a23, 0x00754823, 0x00744823, 0x00714620, 0x0070441e, 0x0069401c, 0x00673d18, 0x00643b14, 0x00603710, 0x005d340d, 0x005c340c, 0x005c3409, 0x005b3208, 0x00583107, 0x00562f08, 0x00562f0b, 0x00542e0a, 0x00502b09, 0x004e2807, 0x004f2908, 0x00502a08, 0x00502a08, 0x00502b08, 0x00522f0c, 0x0054300c, 0x00522c05, 0x005b300a, 0x0060340b, 0x0062340a, 0x0066360c, 0x0067380d, 0x0067380d, 0x0069390d, 0x006d3c10, 0x006f3c0e, 0x00703b0c, 0x00703c0c, 0x006f3c0a, 0x006b3909, 0x0068390a, 0x00603306, 0x005b3006, 0x005b320c, 0x0057310c, 0x0057310c, 0x00532f0a, 0x00502c09, 0x00492807, 0x004b2c0c, 0x00391c00, 0x003b1d01, 0x003d2008, 0x00381c06, 0x003b1d08, 0x00391c07, 0x00381c08, 0x00381c0b, 0x003a1d0c, 0x00341b0b, 0x00281708, 0x001c1106, 0x00110f07, 0x000b0f06, 0x000c0e06, 0x00171208, 0x0021170b, 0x002e2013, 0x00342619, 0x00281c12, 0x00241b13, 0x002a1f16, 0x002e2318, 0x00312518, 0x002e2213, 0x002e2416, 0x00292015, 0x00221c13, 0x001e1a14, 0x001a1813, 0x00161512, 0x00121410, 0x0011140f, 0x0010140f, 0x000c1410, 0x000c1410, 0x000d1510, 0x000d1510, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x00101711, 0x00101711, 0x000f150f, 0x000f150f, 0x000f1610, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1710, 0x000f1811, 0x000f1811, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x000f1811, 0x000f1811, 0x00101812, 0x00101812, 0x00121812, 0x00131712, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00101610, 0x000f150f, 0x000e150f, 0x000d150f, 0x000d150f, 0x000c140e, 0x000b130c, 0x000a130c, 0x000a140f, 0x000a140f, 0x000a140f, 0x000a140f, 0x0009130e, 0x0009130e, 0x0008120c, 0x0007110c, 0x0007130d, 0x0007130d, 0x0007130d, 0x0007130d, 0x0006110c, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040f09, 0x0005100a, 0x00040d08, 0x00040e09, 0x00040f09, 0x0008100b, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00060e09, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005100e, 0x0006100c, 0x0008100b, 0x00090f0b, 0x00080f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040c06, 0x00040c08, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100a, 0x00051008, 0x00040f08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x00191c08, 0x00202308, 0x0024250a, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0030310c, 0x0034350c, 0x0038380c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0040400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0047480d, 0x0047480e, 0x00484910, 0x00484910, 0x00494a10, 0x00494a10, 0x00494a10, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00515110, 0x00525310, 0x00535410, 0x00555611, 0x00585810, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00606013, 0x00636413, 0x00686414, 0x00c6a219, 0x00cca619, 0x007c7114, 0x00666714, 0x00666714, 0x00666713, 0x00656614, 0x00646414, 0x00646414, 0x00616112, 0x009b8415, 0x00cca417, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0047480f, 0x0041420e, 0x003e400d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250b, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f09, 0x0008110a, 0x00081009, 0x00070f08, 0x00070f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060f0b, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x0008100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0005100a, 0x00050f0a, 0x00060e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e06, 0x00060e06, 0x00060e06, 0x00081009, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f08, 0x00070f08, 0x00081009, 0x000a0f09, 0x000b0f0b, 0x000b0f0c, 0x000a100a, 0x000a100a, 0x0009120b, 0x0009120c, 0x000a130c, 0x000a130b, 0x000b140b, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000f150f, 0x00101610, 0x00101610, 0x00101710, 0x00101711, 0x00101711, 0x00111812, 0x00101711, 0x000f1510, 0x00111812, 0x00111812, 0x00121813, 0x00121813, 0x00121911, 0x00121911, 0x00131a12, 0x00131a12, 0x00141811, 0x00111610, 0x0010150e, 0x0010150e, 0x00101711, 0x00101711, 0x00101711, 0x00121913, 0x00101814, 0x00131a16, 0x00161914, 0x001c1d14, 0x0025251b, 0x002f2c24, 0x002f2d26, 0x00302d2a, 0x002e2c2b, 0x00252422, 0x00242420, 0x00181a14, 0x0013140c, 0x0024241a, 0x002e2b20, 0x0031281a, 0x003f301d, 0x0048351d, 0x003f2710, 0x00442c18, 0x004c3321, 0x00543924, 0x0055381c, 0x00543518, 0x00563416, 0x00573313, 0x005b3613, 0x00603b14, 0x00683f18, 0x00693f17, 0x006f421b, 0x00754923, 0x00744824, 0x00734823, 0x006e4520, 0x006b421d, 0x00683f1a, 0x00693e19, 0x00663c16, 0x00623912, 0x005f3710, 0x005d360e, 0x005d360c, 0x00583108, 0x00512a04, 0x00522c08, 0x00522c0c, 0x00502b0b, 0x00502a0c, 0x004e280b, 0x004e290c, 0x004d280b, 0x004d280b, 0x00542e10, 0x0053300f, 0x0054300c, 0x00552f09, 0x005e340d, 0x0064380e, 0x0065370c, 0x0067380d, 0x0067380d, 0x0068380e, 0x006b3a0f, 0x006f3d10, 0x00703c0e, 0x006f3b0b, 0x006e3a09, 0x006c3b0b, 0x0068390a, 0x00633508, 0x0062360b, 0x00603610, 0x005a300c, 0x005c3410, 0x0058300e, 0x00522c0b, 0x00502d0c, 0x00482709, 0x0047280b, 0x003a1d04, 0x003a1d04, 0x003c200b, 0x003a1e0a, 0x00381c0b, 0x00381c0b, 0x00381c0a, 0x00361a08, 0x00381c0b, 0x00311909, 0x00241507, 0x00181006, 0x00131209, 0x000c1107, 0x000d0f05, 0x00161107, 0x0020160b, 0x002b1e12, 0x00312418, 0x00271c11, 0x00231912, 0x00251d15, 0x002a2018, 0x002d2519, 0x0030271a, 0x002f261a, 0x00272116, 0x001f1c13, 0x001d1d15, 0x001a1b16, 0x00141813, 0x00141713, 0x00141612, 0x00131712, 0x00111814, 0x00101713, 0x00101512, 0x00101511, 0x00101711, 0x00111812, 0x00111812, 0x00111812, 0x00111611, 0x00111611, 0x00131712, 0x00131712, 0x00121812, 0x00111812, 0x00111812, 0x00101711, 0x00111812, 0x00111813, 0x00121813, 0x00121813, 0x00121813, 0x00111812, 0x00111812, 0x00101812, 0x00101812, 0x00101811, 0x00101811, 0x00111812, 0x00111812, 0x00131714, 0x00141614, 0x00131513, 0x00131513, 0x00131513, 0x00131513, 0x00131513, 0x00131513, 0x00121612, 0x00111711, 0x00101710, 0x00101610, 0x000e1610, 0x000d150f, 0x000d150f, 0x000d150f, 0x000d150f, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000b1510, 0x000b1510, 0x0008140f, 0x0007130d, 0x0008140d, 0x0008140e, 0x0008120c, 0x0006100b, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00050d08, 0x00040c08, 0x00050d09, 0x00040c08, 0x00040f09, 0x0005100a, 0x0004100a, 0x0003100d, 0x0004100c, 0x0006100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00060f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x00060e08, 0x00030d06, 0x00040d09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x00040e09, 0x0006100a, 0x00051008, 0x00040f08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180a, 0x00191c09, 0x00191c08, 0x001d2008, 0x00202308, 0x0026280c, 0x00292b0b, 0x00292b0a, 0x0030310b, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003b3c0d, 0x003e400c, 0x003e400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0045470e, 0x0047480d, 0x0047480e, 0x00484910, 0x00484910, 0x00494a10, 0x00494a10, 0x00494a10, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545511, 0x00565711, 0x00585911, 0x00595a12, 0x005c5c11, 0x005e5f13, 0x00606012, 0x00616112, 0x00686414, 0x00c6a219, 0x00cca619, 0x007b7014, 0x00666713, 0x00666713, 0x00656614, 0x00646514, 0x00646414, 0x00626313, 0x00606013, 0x009b8415, 0x00cca417, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0047480f, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e0a, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e0b, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00050e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0007100b, 0x00060e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e06, 0x00081008, 0x00081008, 0x00070f08, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00081009, 0x00071009, 0x0008100a, 0x000a100a, 0x000b100a, 0x000c0f0a, 0x000b100a, 0x000d130c, 0x000d140c, 0x000c140c, 0x000d140c, 0x000d140b, 0x000d140b, 0x000f140d, 0x000f140e, 0x0010140f, 0x0010140f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x00101711, 0x00111812, 0x00111812, 0x00121813, 0x00121813, 0x00121813, 0x00121813, 0x00131914, 0x00141a14, 0x00141914, 0x00141914, 0x00151a14, 0x00151a14, 0x00151a13, 0x00151a13, 0x00141912, 0x00141912, 0x00161812, 0x00161812, 0x00171913, 0x00171913, 0x00141914, 0x00141914, 0x00141914, 0x00141a14, 0x00141a14, 0x00161a14, 0x00181a14, 0x001d1c13, 0x00211f14, 0x0028241a, 0x002a251e, 0x002d2923, 0x002f2b28, 0x00282724, 0x002c2b26, 0x00181914, 0x0011140d, 0x0023251e, 0x0026251c, 0x002e281c, 0x003c3122, 0x0046351f, 0x00402d15, 0x0048321c, 0x00493320, 0x004f361e, 0x0050351a, 0x00503318, 0x0053341a, 0x00513115, 0x00502e0c, 0x0058340f, 0x00633b15, 0x00684018, 0x00684017, 0x006c441c, 0x00744a25, 0x00704822, 0x006c4520, 0x006b411c, 0x00673d18, 0x00683c18, 0x00673e17, 0x00643b14, 0x00603710, 0x00613710, 0x0060380f, 0x005c330b, 0x00562c08, 0x00572c0c, 0x00572e0e, 0x00542c0c, 0x00542c0e, 0x00542b0d, 0x00542b0d, 0x0050280a, 0x00502809, 0x00522a0b, 0x00573010, 0x005a3310, 0x005c320e, 0x0060330c, 0x0064360d, 0x0066360c, 0x0067380d, 0x0067380d, 0x0067390e, 0x0067390b, 0x006b3c0c, 0x006b3c0a, 0x006c3a08, 0x006b3a08, 0x006a390b, 0x0068390d, 0x00623409, 0x0061340c, 0x00592e09, 0x00572d0a, 0x00583010, 0x00593111, 0x004f2809, 0x004d290c, 0x00452408, 0x003d2005, 0x003a1f06, 0x00381e08, 0x00381e09, 0x00361c0b, 0x00371c0a, 0x00381c0b, 0x00381c0c, 0x00341908, 0x00341b09, 0x002d1907, 0x00251809, 0x00161104, 0x00121408, 0x000c1107, 0x000d0f05, 0x00161008, 0x001f170b, 0x00281c0f, 0x002d2014, 0x00281d13, 0x00241a13, 0x00201813, 0x001f1912, 0x00241f15, 0x00282318, 0x00282418, 0x00242318, 0x00201f16, 0x001c1d14, 0x001b1c17, 0x00181a16, 0x00161814, 0x00161814, 0x00161814, 0x00141815, 0x00141815, 0x00141814, 0x00131714, 0x00141813, 0x00141914, 0x00141814, 0x00141813, 0x00141813, 0x00141813, 0x00141813, 0x00141612, 0x00141814, 0x00141914, 0x00141914, 0x00141813, 0x00141813, 0x00141914, 0x00141914, 0x00151a14, 0x00151a14, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00141913, 0x00141914, 0x00141914, 0x00141813, 0x00141813, 0x00141814, 0x00141814, 0x00141814, 0x00141814, 0x00141814, 0x00131813, 0x00121813, 0x00101812, 0x00101812, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000e1813, 0x000d1712, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000b1510, 0x000b1510, 0x000b1710, 0x0008140f, 0x0008140e, 0x0008140e, 0x0008130d, 0x0008110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00060e09, 0x00050d09, 0x00060e09, 0x00060e09, 0x0005100a, 0x0005100a, 0x0004100a, 0x0003100d, 0x0003100c, 0x00040f0a, 0x00040e09, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f08, 0x00070f08, 0x00060e08, 0x00040e07, 0x00040d09, 0x00040e09, 0x00040c08, 0x00040c08, 0x00040d08, 0x00040d08, 0x00040e09, 0x0005100a, 0x00051009, 0x00051008, 0x00040f08, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180a, 0x00191c09, 0x00191c08, 0x001d2008, 0x00202308, 0x0026280c, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0c, 0x003b3c0d, 0x003e400c, 0x003e400c, 0x0041420e, 0x0043440e, 0x0044450e, 0x0045470e, 0x0045470d, 0x0047480d, 0x0047480e, 0x00484910, 0x00484910, 0x00494a10, 0x00494a10, 0x00494a10, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00525310, 0x00535410, 0x00545511, 0x00565710, 0x00585911, 0x00595a12, 0x005c5c11, 0x005e5f13, 0x00606013, 0x00616112, 0x00666413, 0x00c6a219, 0x00cca619, 0x007b7014, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00636413, 0x00606013, 0x009a8215, 0x00cca417, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0047480f, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050d07, 0x00050e08, 0x00081008, 0x00071007, 0x00071007, 0x00060e08, 0x00040c07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x00050d07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060f08, 0x00060e0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050e09, 0x00080c09, 0x00080c09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060e08, 0x00071007, 0x00071007, 0x00070f08, 0x00070f08, 0x00081009, 0x00061009, 0x0007110a, 0x0007110a, 0x0008120b, 0x0008120c, 0x000a110c, 0x000b110c, 0x000b110c, 0x000c120c, 0x000c130c, 0x000e120d, 0x000e120d, 0x000e130c, 0x000f140c, 0x00101610, 0x00101610, 0x00101610, 0x00101610, 0x00101510, 0x00111611, 0x00121712, 0x00131812, 0x00111812, 0x00121813, 0x00121813, 0x00131914, 0x00131913, 0x00131a12, 0x00131a13, 0x00121912, 0x00151c14, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161b14, 0x00181a14, 0x00181a15, 0x00181a15, 0x00181a15, 0x00171914, 0x00181a15, 0x00191c17, 0x00191c16, 0x00181c15, 0x00181a14, 0x00181a14, 0x00181b15, 0x00171914, 0x00181a14, 0x001e1c15, 0x00211e14, 0x00211c12, 0x00241d13, 0x00252016, 0x0027211a, 0x0028241e, 0x0026241f, 0x00292924, 0x0012140e, 0x00191d17, 0x0032342e, 0x0025241c, 0x00353127, 0x003b3226, 0x003d301e, 0x0040311c, 0x0045331c, 0x00432e17, 0x00473017, 0x004b3219, 0x004f361d, 0x004f341e, 0x004d3016, 0x004c2d0c, 0x00543210, 0x0054300c, 0x00623d17, 0x00643e18, 0x0069411c, 0x006b441e, 0x006b4420, 0x006b431f, 0x0069401d, 0x00673d1a, 0x00683c18, 0x00683d17, 0x00653b12, 0x00623810, 0x0060380f, 0x005e350c, 0x00593008, 0x00542b07, 0x00512707, 0x00582e0f, 0x00572d11, 0x00562f10, 0x00593111, 0x0058300d, 0x00512808, 0x00502708, 0x00532808, 0x005a2e10, 0x005e3210, 0x005e330d, 0x0060340c, 0x0064360c, 0x0066360e, 0x0066370c, 0x0068380c, 0x0068380c, 0x0069390c, 0x006a390a, 0x006a390b, 0x0069380c, 0x0069380c, 0x0067380d, 0x0064340c, 0x0061330a, 0x0060340c, 0x00562b07, 0x005d320f, 0x00582d0c, 0x00572d0e, 0x00542c0d, 0x00522e11, 0x00442408, 0x003c2005, 0x00391e08, 0x003b1f0b, 0x00371c08, 0x00371b09, 0x00371b09, 0x00381c0a, 0x00361c0b, 0x00321908, 0x00301807, 0x002c1a08, 0x00271a09, 0x00161002, 0x000c0d00, 0x00080c02, 0x00111309, 0x00171309, 0x001c1408, 0x0024180e, 0x002d2014, 0x00281d14, 0x00241b13, 0x001f1a13, 0x001f1c15, 0x001e1c14, 0x001f1c14, 0x00202014, 0x00212318, 0x00202219, 0x001d2019, 0x001c1e18, 0x00191c16, 0x00171a14, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00151a14, 0x00151a14, 0x00141914, 0x00151a14, 0x00141914, 0x00141912, 0x00141912, 0x00141912, 0x00141912, 0x00151a14, 0x00151b15, 0x00151c15, 0x00141a14, 0x00141914, 0x00171914, 0x00171914, 0x00181a15, 0x00161b15, 0x00151c14, 0x00151c14, 0x00141b13, 0x00121810, 0x00141912, 0x00141912, 0x00161b14, 0x00161b14, 0x00131815, 0x00131816, 0x00131917, 0x00131917, 0x00141a16, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141813, 0x00111812, 0x000f1912, 0x000f1912, 0x000d1710, 0x000c160f, 0x000c1712, 0x000e1814, 0x000c1713, 0x000c1713, 0x000c1610, 0x000d1510, 0x000c1410, 0x000c140f, 0x000a140f, 0x0008120d, 0x0007110c, 0x0007110c, 0x0007100c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x000a100c, 0x00070f0a, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100a, 0x0008110b, 0x0008120b, 0x00061009, 0x0006100b, 0x0007100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e08, 0x00040e09, 0x00040e09, 0x00040c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060f09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x00141810, 0x0014180b, 0x0014180a, 0x00191c09, 0x00191c08, 0x00202308, 0x0024250b, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0034350c, 0x0038380c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0040400d, 0x0043440f, 0x0043440e, 0x0045470e, 0x0045470e, 0x0047480d, 0x0047480e, 0x00484910, 0x00494a10, 0x00494a10, 0x00494a10, 0x00494a0f, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00525310, 0x00545510, 0x00555611, 0x00565711, 0x00585911, 0x00595a12, 0x005c5c11, 0x005e5f13, 0x00606013, 0x00606013, 0x00666413, 0x00c6a218, 0x00cca519, 0x007a7014, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00636414, 0x00616112, 0x00606013, 0x009a8215, 0x00cca417, 0x00b09015, 0x00515111, 0x00525310, 0x004f5010, 0x00494a0f, 0x0047480f, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00050e07, 0x00060e06, 0x00060e06, 0x00040c06, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x00040d07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00070f09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e07, 0x00060e09, 0x00040e09, 0x00080c09, 0x00080c09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e06, 0x00060e08, 0x00060e08, 0x00071007, 0x00071007, 0x00060e08, 0x00060e08, 0x0008110b, 0x0008120b, 0x0008130c, 0x0008130c, 0x0009140c, 0x000a140d, 0x000c130d, 0x000c130d, 0x000c130d, 0x000d140e, 0x000d140e, 0x000f140e, 0x000f140e, 0x0010140f, 0x0010140f, 0x00101510, 0x00101510, 0x00111611, 0x00111611, 0x00111611, 0x00131712, 0x00141813, 0x00141813, 0x00121813, 0x00131914, 0x00131914, 0x00141a14, 0x00141a14, 0x00141b13, 0x00141b13, 0x00121911, 0x00151c14, 0x00161b15, 0x00161b14, 0x00181c14, 0x00181d14, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c17, 0x00181a16, 0x00181b17, 0x00191c16, 0x00191c16, 0x001b1c14, 0x001b1c14, 0x001c1d16, 0x001c1c15, 0x001a1b14, 0x001c1c15, 0x00201d17, 0x00231f15, 0x00241e14, 0x00272018, 0x0028201a, 0x0028211b, 0x00272219, 0x0025231b, 0x0022231c, 0x0010120c, 0x001c211a, 0x00383b34, 0x002c2c24, 0x002d2920, 0x00362e24, 0x002f2417, 0x00372917, 0x0041321a, 0x00412e15, 0x0048341a, 0x00503820, 0x00513822, 0x004b311a, 0x004a2f14, 0x00523414, 0x00593818, 0x0054320f, 0x00623e19, 0x00623c18, 0x0066401a, 0x0067411b, 0x0067411c, 0x0068401c, 0x0068401c, 0x00693d1b, 0x00683d19, 0x00683d17, 0x00663c13, 0x00623810, 0x0061380e, 0x0061380e, 0x005d340c, 0x00562d09, 0x00502706, 0x00552d0f, 0x00542c12, 0x00573013, 0x005b3314, 0x00582f0f, 0x00502608, 0x0054290c, 0x00562a0d, 0x005d3013, 0x005f330f, 0x005f320c, 0x0062350d, 0x0064370f, 0x0065370e, 0x0066380d, 0x0067390c, 0x00683a0d, 0x00693a0c, 0x006a390c, 0x0069380d, 0x0068380f, 0x0068370f, 0x0063340c, 0x00613209, 0x00603209, 0x005f330b, 0x005c2f09, 0x00592e0b, 0x00542b09, 0x005c3112, 0x00552c0e, 0x00502b0e, 0x00402004, 0x00391d03, 0x00371c05, 0x003a1e0a, 0x00371b08, 0x00371b09, 0x00371c0a, 0x00371c0a, 0x00331c09, 0x002e1707, 0x002d1708, 0x002c190a, 0x00271a09, 0x00161000, 0x000c0c00, 0x00090d03, 0x00101008, 0x0018140b, 0x001b1408, 0x0022160c, 0x002b1e14, 0x00291e14, 0x00241c14, 0x00201c14, 0x001d1c14, 0x001b1b12, 0x00181911, 0x00181a11, 0x001b1d14, 0x001b1d17, 0x001c1e18, 0x001c1e18, 0x00191c16, 0x00181c15, 0x00171c17, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161b15, 0x00161b15, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a13, 0x00151a13, 0x00161b14, 0x00161b14, 0x00161c16, 0x00171d18, 0x00171d18, 0x00161c17, 0x00171b16, 0x00181b17, 0x00181b16, 0x00181a15, 0x00181a15, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00171c15, 0x00171c15, 0x00161b14, 0x00161b14, 0x00141b17, 0x00141b17, 0x00151b17, 0x00151b17, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00131914, 0x00121b12, 0x00111b12, 0x00101810, 0x000e1710, 0x00101814, 0x00101814, 0x000f1713, 0x000f1713, 0x000f1713, 0x000d1510, 0x000e1611, 0x000c1410, 0x000b1410, 0x0009130e, 0x0007110c, 0x0007110c, 0x0007100c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00080f0b, 0x0008100c, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x00040f08, 0x00061009, 0x0007110a, 0x00061009, 0x0006100c, 0x0007110d, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x001d2008, 0x0020230a, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0036370c, 0x0038380c, 0x003b3c0d, 0x003c3e0c, 0x0040400c, 0x0041420e, 0x0043440e, 0x0045470e, 0x0047480e, 0x0047480e, 0x00484910, 0x00484910, 0x00494a0f, 0x00494a0f, 0x004b4c0f, 0x004c4d0f, 0x004b4c0f, 0x004c4d0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00515110, 0x00525310, 0x00545510, 0x00565711, 0x00585810, 0x00585911, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00606013, 0x00616112, 0x00666413, 0x00c6a218, 0x00cca519, 0x007a7014, 0x00646514, 0x00646514, 0x00646514, 0x00646414, 0x00626313, 0x00616112, 0x00606013, 0x009a8214, 0x00cca417, 0x00b09015, 0x00515110, 0x00525310, 0x004f5010, 0x004b4c10, 0x0047480f, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e07, 0x00050d07, 0x00040d06, 0x00040d05, 0x00071007, 0x00070f08, 0x00081009, 0x00081009, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00050d07, 0x00070f08, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e07, 0x00060e09, 0x00040e09, 0x00080c09, 0x00080c09, 0x00070c08, 0x00050d08, 0x00040d08, 0x00070f0a, 0x00070f0a, 0x00050e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e06, 0x00070f08, 0x00070f08, 0x00081008, 0x00071007, 0x00060e07, 0x00050d07, 0x0009120c, 0x0009120c, 0x000a130c, 0x000b120c, 0x000c130c, 0x000c140c, 0x000c140d, 0x000d140e, 0x000e140e, 0x000f150f, 0x000f150f, 0x0010140f, 0x0010140f, 0x00101510, 0x00101510, 0x00131611, 0x00131611, 0x00141813, 0x00141712, 0x00141813, 0x00141813, 0x00141813, 0x00151814, 0x00151814, 0x00161914, 0x00161914, 0x00171914, 0x00171a14, 0x00171a14, 0x00181b14, 0x00181b14, 0x00181c15, 0x00181c16, 0x001a1d15, 0x001a1e14, 0x001a1d15, 0x001c1d18, 0x001c1d18, 0x001c1d18, 0x001c1d18, 0x001b1c18, 0x001b1c16, 0x001c1d17, 0x001c1d16, 0x001d1c15, 0x001c1c15, 0x001c1c15, 0x001e1d16, 0x001c1d17, 0x001d1d17, 0x00201d16, 0x00231e14, 0x00241d14, 0x00272017, 0x002a221c, 0x0028201a, 0x00241f15, 0x001c1a11, 0x00151610, 0x0010140e, 0x00242621, 0x003c3d38, 0x0036352e, 0x0027231b, 0x00282218, 0x0030261a, 0x003b3020, 0x00423420, 0x0044341b, 0x00432f16, 0x0047331a, 0x004f3820, 0x0048321a, 0x00452d13, 0x004f3014, 0x00543314, 0x00583616, 0x005c3815, 0x005f3915, 0x00633d18, 0x0065401b, 0x0066401c, 0x0067401c, 0x0068401c, 0x00693d1c, 0x00683c18, 0x00663b15, 0x00663c13, 0x00643a11, 0x00643a10, 0x0062380e, 0x005c340c, 0x0058300c, 0x00562e0a, 0x00572f0f, 0x00582e10, 0x005c3213, 0x005c3110, 0x005c300d, 0x005c2f0e, 0x005d3010, 0x005a2c0c, 0x00603210, 0x0060340c, 0x0061340d, 0x0063360f, 0x00643710, 0x0064380f, 0x0065380d, 0x00653a0c, 0x00663a0d, 0x00673b0c, 0x0067380c, 0x0066380e, 0x00673810, 0x0064370e, 0x0060340a, 0x005f3309, 0x005f340a, 0x005f340c, 0x005e320c, 0x005a2f0c, 0x00572b0b, 0x005d3213, 0x00562d0f, 0x004f290c, 0x00432207, 0x003d2107, 0x00351904, 0x00371b07, 0x003a1e0a, 0x00371c0a, 0x00351c09, 0x00341c0a, 0x002c1807, 0x002a1707, 0x002c1809, 0x002c190b, 0x0025180b, 0x00170e02, 0x000e0b00, 0x000c0f04, 0x000f0f04, 0x0018150c, 0x001b140a, 0x001f140b, 0x00251a10, 0x00271d14, 0x00272018, 0x00221d14, 0x001f1b14, 0x001d1b13, 0x001d1c15, 0x001b1c13, 0x00191c14, 0x00191c16, 0x00191c16, 0x00191d16, 0x00181d16, 0x00171c16, 0x00171c17, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00171c17, 0x00171c17, 0x00171c14, 0x00171c15, 0x00171c15, 0x00171c15, 0x00161c16, 0x00161c16, 0x00171d16, 0x00181f18, 0x001b1f18, 0x00191c17, 0x00181c15, 0x00181c16, 0x00181c16, 0x00181c14, 0x00171b13, 0x00171b13, 0x00171b13, 0x00161c13, 0x00161c13, 0x00171c14, 0x00171c14, 0x00161c16, 0x00151b15, 0x00151c16, 0x00151c16, 0x00151c15, 0x00141b15, 0x00141a14, 0x00141b15, 0x00161c17, 0x00151c16, 0x00151c16, 0x00151c16, 0x00151c16, 0x00161b15, 0x00161b15, 0x00151a14, 0x00141914, 0x00141b13, 0x00141b13, 0x00131b13, 0x00111912, 0x00121815, 0x00121814, 0x00121814, 0x00101814, 0x00101814, 0x00101813, 0x000e1611, 0x000e1611, 0x000c1510, 0x000a140f, 0x0008120d, 0x0008120c, 0x0007100b, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00070d09, 0x0008100c, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040e08, 0x00040f08, 0x00051008, 0x00061009, 0x0006100c, 0x0007110d, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0005100a, 0x0005100a, 0x00040e09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00040c08, 0x00060c08, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x0038380c, 0x00393b0d, 0x003c3e0c, 0x003e400c, 0x0041420e, 0x0044450e, 0x0045470e, 0x0047480e, 0x0048490f, 0x00494a10, 0x004b4c10, 0x004b4c0f, 0x004b4c0f, 0x004c4d0f, 0x004d4e0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x004d4e10, 0x004f5010, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00545511, 0x00555611, 0x00565711, 0x00585910, 0x00595a12, 0x005c5c12, 0x005c5d11, 0x005d5e12, 0x00606013, 0x00606013, 0x00666413, 0x00c6a218, 0x00cca519, 0x00796f14, 0x00646514, 0x00646514, 0x00646414, 0x00636414, 0x00626313, 0x00606013, 0x005e5f13, 0x009a8214, 0x00cca417, 0x00b09015, 0x00515110, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e06, 0x00050e06, 0x00060e08, 0x00060e08, 0x00050e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00040d07, 0x00070f08, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e07, 0x00060e06, 0x00060e06, 0x00060e07, 0x00060e09, 0x00040e09, 0x00080c09, 0x00080c09, 0x00070c08, 0x00040c08, 0x00050d08, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e06, 0x00070f08, 0x00081009, 0x00081108, 0x00081008, 0x00081008, 0x00081009, 0x000b130c, 0x000c140d, 0x000d140c, 0x000e140c, 0x000f140d, 0x000f140d, 0x000f140e, 0x000e140f, 0x000f150f, 0x00101610, 0x00101610, 0x00101510, 0x00101510, 0x00111611, 0x00111611, 0x00151814, 0x00151814, 0x00171914, 0x00171914, 0x00171814, 0x00171814, 0x00171814, 0x00171814, 0x00181915, 0x00181915, 0x00181914, 0x00181814, 0x00181914, 0x00181a14, 0x00181a14, 0x00191b15, 0x00191b15, 0x001a1c15, 0x001c1e15, 0x001b1d14, 0x001c1d14, 0x001d1d17, 0x001d1d17, 0x001d1d17, 0x001d1d17, 0x001c1c18, 0x001c1c17, 0x001d1d17, 0x001d1d16, 0x001f1e16, 0x001e1c14, 0x001e1c14, 0x001e1c15, 0x001e1d17, 0x001f1c16, 0x00201c15, 0x00201c12, 0x00211b13, 0x00231c14, 0x00241c16, 0x00231c15, 0x001f1910, 0x0019170e, 0x0014130c, 0x0012140e, 0x0020241e, 0x00373831, 0x00383730, 0x002b271f, 0x001f1a10, 0x002c261c, 0x00393023, 0x003c311f, 0x0041341d, 0x0045341c, 0x00453218, 0x0047331a, 0x0049351c, 0x00452c14, 0x00482910, 0x00543118, 0x005c381c, 0x005c3716, 0x00603917, 0x00603b18, 0x00613c18, 0x00643d1b, 0x00643e1a, 0x00653d1b, 0x00673d1a, 0x006a3c19, 0x00663b15, 0x00663c13, 0x00653b12, 0x00653b10, 0x00633a10, 0x0060370c, 0x005c340d, 0x005e3412, 0x005d3410, 0x005e340e, 0x0063370f, 0x0067390f, 0x00673a0f, 0x006a3b12, 0x006a3b12, 0x0064350c, 0x0067380f, 0x0064350b, 0x0065380e, 0x0063350e, 0x00643711, 0x0063360f, 0x0062380c, 0x0062380b, 0x0062380b, 0x0062370a, 0x0061370c, 0x0062370e, 0x0061360d, 0x0060350c, 0x005d3409, 0x005c3208, 0x005f340a, 0x005e340b, 0x005b310b, 0x005b300d, 0x005c3110, 0x00582e0f, 0x00552c0d, 0x004c280c, 0x00442408, 0x003e2208, 0x00351904, 0x00361a06, 0x003a1e0b, 0x00381c0a, 0x00331b09, 0x00301b08, 0x00281704, 0x00281808, 0x002a1809, 0x0028170b, 0x00221509, 0x00160d04, 0x000e0a00, 0x000c0e02, 0x00121207, 0x0019150c, 0x001b150b, 0x0021170c, 0x00251c12, 0x00241d13, 0x00241d15, 0x00231c14, 0x001f1a13, 0x001d1b13, 0x001c1c14, 0x001a1b14, 0x00181c14, 0x00191c15, 0x00191c16, 0x00191c16, 0x00181d16, 0x00181c16, 0x00181c18, 0x00181c18, 0x00181c18, 0x00181c18, 0x00171c16, 0x00171c16, 0x00161b14, 0x00161b14, 0x00171c17, 0x00171c17, 0x00171c15, 0x00171c14, 0x00171c14, 0x00171c14, 0x00161c14, 0x00161d14, 0x00171d14, 0x00171e15, 0x00181c15, 0x00191c15, 0x00191c15, 0x00191c15, 0x00191c15, 0x00191d14, 0x00191c13, 0x00191c13, 0x00191c13, 0x00181d13, 0x00181d13, 0x00181d13, 0x00181d14, 0x00181f16, 0x00161d14, 0x00151c13, 0x00151c13, 0x00151c15, 0x00151c15, 0x00141b14, 0x00151c16, 0x00161c17, 0x00161c17, 0x00171d18, 0x00181e18, 0x00181d18, 0x00181c18, 0x00181c18, 0x00171c16, 0x00161b15, 0x00141c14, 0x00141c14, 0x00141b13, 0x00141b13, 0x00151c15, 0x00151c16, 0x00151b16, 0x00131914, 0x00101814, 0x00101814, 0x00101814, 0x000e1611, 0x000c1610, 0x000c1610, 0x000b1510, 0x000a140f, 0x0008110c, 0x0009110c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00050d09, 0x00080f0b, 0x0008100b, 0x0008100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040f08, 0x00040f08, 0x00051008, 0x00061009, 0x0006100c, 0x0007110d, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0005100a, 0x0005100a, 0x00040e09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00050d09, 0x00060d09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x00191c08, 0x00202308, 0x0020230a, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0045470e, 0x0048490f, 0x00494a10, 0x004b4c10, 0x004b4c0f, 0x004d4e0f, 0x004d4e10, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x004f5010, 0x00505010, 0x00515110, 0x00515110, 0x00505010, 0x00525310, 0x00515110, 0x00525310, 0x00535410, 0x00545510, 0x00555611, 0x00565711, 0x00585810, 0x00595a11, 0x005b5b12, 0x005c5c11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00616112, 0x00666413, 0x00c6a218, 0x00cca519, 0x00796f14, 0x00646414, 0x00646414, 0x00646414, 0x00636414, 0x00616112, 0x00616112, 0x005e5f13, 0x009a8214, 0x00cca417, 0x00b09015, 0x00515110, 0x00515110, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003c3e0c, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00050e07, 0x00060e07, 0x00050e08, 0x00050e08, 0x00040d07, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x0008100b, 0x00070f09, 0x00070f09, 0x00040d08, 0x00050d08, 0x00050e08, 0x0008100b, 0x00060e09, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e07, 0x00060e09, 0x00050e09, 0x00080d09, 0x00080d09, 0x00070d09, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070e0b, 0x00070f09, 0x00070f09, 0x00070f08, 0x0008100a, 0x0008100a, 0x0009120b, 0x000a130c, 0x000b130b, 0x000c140c, 0x000c140d, 0x000c140d, 0x000f140e, 0x0010140e, 0x0011140f, 0x0013140f, 0x00111510, 0x00111510, 0x00111510, 0x00121510, 0x00121510, 0x00141510, 0x00141610, 0x00141611, 0x00141611, 0x00181914, 0x00181914, 0x00191b15, 0x00181a14, 0x00181814, 0x00181814, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181914, 0x00181914, 0x00181a14, 0x00181a14, 0x00181a14, 0x00191a14, 0x00191b14, 0x001b1c16, 0x001c1e18, 0x001c1c14, 0x001c1c14, 0x001c1c15, 0x001d1e16, 0x001e1d15, 0x001f1e15, 0x00201d17, 0x00201d17, 0x00201e16, 0x00201e15, 0x00201e14, 0x00201e14, 0x00201e14, 0x00201e14, 0x001f1e16, 0x00201d15, 0x00201c14, 0x00201b13, 0x00201b13, 0x00211b14, 0x00221c14, 0x00221c15, 0x001b180f, 0x0018150d, 0x0014140c, 0x0012140c, 0x001c1d17, 0x0034342c, 0x0036342c, 0x002c2920, 0x00201c12, 0x00241e16, 0x002e271c, 0x00352c1b, 0x003c301a, 0x00483820, 0x0048361c, 0x00443015, 0x00473018, 0x0049301b, 0x004a2c17, 0x004c2c16, 0x004c2a13, 0x00502c10, 0x00603a1b, 0x005f3918, 0x005f3815, 0x00603a16, 0x00623b17, 0x00633b17, 0x00643b17, 0x00673c18, 0x00643c14, 0x00653b12, 0x00663b11, 0x00663a10, 0x00663a10, 0x00643a10, 0x0063380f, 0x00643910, 0x00673910, 0x00693b10, 0x006f4013, 0x00734012, 0x00724010, 0x00734111, 0x00754313, 0x00723f10, 0x00713d0e, 0x006d390b, 0x006b380c, 0x0068350c, 0x0068370f, 0x0064370c, 0x0063360a, 0x00623508, 0x00613608, 0x005f3408, 0x0060340b, 0x00623710, 0x0060360e, 0x005e340c, 0x005d330a, 0x005d330a, 0x0061360d, 0x005c3109, 0x00572e07, 0x00582f09, 0x005c3311, 0x00542b0b, 0x00522c0c, 0x00492608, 0x00412106, 0x003c2007, 0x00381904, 0x00351804, 0x00381c0a, 0x00341c0b, 0x002f1b08, 0x00281704, 0x00241504, 0x00241504, 0x00271709, 0x0026170b, 0x0020140a, 0x00150c03, 0x000e0901, 0x000d0c04, 0x0014130c, 0x0018140f, 0x0019140e, 0x00211a0f, 0x00241d13, 0x00241d13, 0x00211c13, 0x00201c14, 0x00201b14, 0x001e1b14, 0x001c1b15, 0x001b1c15, 0x00191c15, 0x00191c16, 0x00191c16, 0x00191c17, 0x00181c17, 0x00191d18, 0x00181c18, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161c16, 0x00161c16, 0x00151c14, 0x00151b14, 0x00181e16, 0x00181e16, 0x00181e15, 0x00181e15, 0x00171d14, 0x00161d14, 0x00161d14, 0x00161d14, 0x00171e14, 0x00161d14, 0x00171c13, 0x00181c14, 0x00191c14, 0x00181c14, 0x00191c14, 0x00191c14, 0x00191c14, 0x00191c14, 0x00191c14, 0x00181c14, 0x00181c14, 0x00191c14, 0x00181d14, 0x00181f15, 0x00182016, 0x00171d14, 0x00171d14, 0x00181d16, 0x00181c16, 0x00181c15, 0x00181c16, 0x00181d17, 0x00181d16, 0x00181d17, 0x00181e18, 0x00181d18, 0x00191d18, 0x00191e18, 0x00191d18, 0x00171c15, 0x00181c16, 0x00181d17, 0x00181c17, 0x00171c16, 0x00161c17, 0x00151d17, 0x00141c16, 0x00131a14, 0x00101813, 0x00101813, 0x00101813, 0x00101813, 0x000e1711, 0x000d1610, 0x000d1710, 0x000d1610, 0x000a130d, 0x000a130d, 0x000a120d, 0x0009110c, 0x0009110c, 0x0009110c, 0x0008100b, 0x0008100b, 0x00060f0a, 0x00090f0b, 0x00080f0b, 0x00070f0a, 0x0005100a, 0x00060f0a, 0x00060f0a, 0x00060f0a, 0x00060f0a, 0x00050e08, 0x00050e08, 0x00050f08, 0x00050f08, 0x00050f08, 0x00050f0b, 0x00040e0a, 0x00040e0a, 0x00040f0a, 0x0005100a, 0x00060f0a, 0x00050e09, 0x00050e09, 0x00050e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x0006100a, 0x00050e09, 0x00030c08, 0x00040e09, 0x0008100b, 0x0008100b, 0x0008100b, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x00141810, 0x0014180b, 0x00191c0b, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250c, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x00393b0c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x0048490f, 0x004b4c10, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00515110, 0x00515110, 0x00525310, 0x00525310, 0x00525310, 0x00525310, 0x00535410, 0x00535410, 0x00535410, 0x00545510, 0x00555611, 0x00555611, 0x00565710, 0x00585910, 0x00585911, 0x00595a12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x00606013, 0x00606013, 0x00616112, 0x00666413, 0x00c6a218, 0x00cca519, 0x00796f14, 0x00646414, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x009a8114, 0x00cca417, 0x00b09015, 0x004f5010, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0c, 0x00393b0c, 0x0034350c, 0x0030310c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00070f0a, 0x0008100c, 0x00050d09, 0x00040c08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00050d09, 0x00060e09, 0x00060e09, 0x00070e0c, 0x00070f0a, 0x0008100b, 0x00081009, 0x0008110b, 0x0009120c, 0x000a130c, 0x000c140d, 0x000c140c, 0x000c150c, 0x000e150d, 0x000e150d, 0x0011140f, 0x0013130f, 0x00131410, 0x00141410, 0x00141511, 0x00141712, 0x00141712, 0x00141712, 0x00141712, 0x00171812, 0x00171812, 0x00171812, 0x00171812, 0x00181813, 0x00181a14, 0x001a1b15, 0x00181914, 0x00181813, 0x00181813, 0x00181a14, 0x00181a14, 0x00191a14, 0x00191a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00191c18, 0x001c1d18, 0x001c1c17, 0x001c1c14, 0x001c1c15, 0x00201e17, 0x00201e15, 0x00221e15, 0x00231e18, 0x00231e17, 0x00231e16, 0x00231e14, 0x00201e14, 0x00201e14, 0x00201e14, 0x00201e14, 0x00201d14, 0x00201d14, 0x00201d14, 0x00211c14, 0x00221c14, 0x00211c14, 0x00211c14, 0x00201c14, 0x0018160e, 0x0016140c, 0x0014140b, 0x0012130a, 0x00181810, 0x002a2a22, 0x00302e25, 0x0029281f, 0x0026231a, 0x00201b13, 0x00221b10, 0x00342c1d, 0x003a2f1d, 0x00453722, 0x004a3821, 0x00453117, 0x0047301a, 0x0049301c, 0x004c301d, 0x004d311c, 0x0053341d, 0x0056351a, 0x005e3b1c, 0x005e3818, 0x005f3715, 0x00623815, 0x00633b16, 0x00643c18, 0x00653c18, 0x00643c17, 0x00633b14, 0x00643911, 0x00673a10, 0x00673a10, 0x00683b10, 0x006b3e14, 0x006c3e11, 0x00704010, 0x00724312, 0x00774416, 0x007c4a19, 0x00814c18, 0x0078440e, 0x007d4813, 0x00804914, 0x007e4712, 0x007f4712, 0x007b4310, 0x0078400f, 0x00733c0e, 0x006f3a0d, 0x006c380a, 0x00683808, 0x00663608, 0x00643508, 0x0060340a, 0x0060330c, 0x0061340e, 0x0060350f, 0x0061360f, 0x0062370f, 0x0062370f, 0x00643810, 0x005a3007, 0x00542c05, 0x00562e08, 0x0059300e, 0x00522a0a, 0x004d280a, 0x00442005, 0x003d1d04, 0x003e2008, 0x003b1c08, 0x00361806, 0x00361c0c, 0x002d1809, 0x00271607, 0x00221404, 0x00231404, 0x00231404, 0x00241508, 0x00241508, 0x001e1409, 0x00150c04, 0x00130c06, 0x0015100c, 0x00181310, 0x00181310, 0x0018140f, 0x001d180f, 0x001f1b10, 0x001f1c11, 0x001e1b12, 0x001e1a13, 0x001d1b14, 0x001c1b14, 0x001c1b16, 0x001b1c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c17, 0x00181c18, 0x00191d18, 0x00181d18, 0x00161b15, 0x00161c17, 0x00161c17, 0x00161c15, 0x00161c15, 0x00161c15, 0x00171d16, 0x00171e14, 0x00171e14, 0x00181f15, 0x00171e14, 0x00171e14, 0x00161d14, 0x00161d14, 0x00161d14, 0x00161d14, 0x00161d14, 0x00161c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00181c14, 0x00171e15, 0x00171e15, 0x00181e15, 0x00181e15, 0x001c1e18, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d15, 0x00181d14, 0x001a1f16, 0x001a1f15, 0x00191e16, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00161d18, 0x00151e18, 0x00141d17, 0x00131b14, 0x00121a14, 0x00111913, 0x00111913, 0x00111913, 0x00101811, 0x000e170e, 0x000e1710, 0x000e1710, 0x000c140d, 0x000c140d, 0x000c140e, 0x000c140f, 0x000c140f, 0x000a120e, 0x0008100b, 0x0008100b, 0x0008100b, 0x00090f0b, 0x00080f0b, 0x00070f0a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d08, 0x00040c08, 0x00040c08, 0x00040e09, 0x00040e09, 0x0005100a, 0x00070f0a, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060f0a, 0x00050f0a, 0x0005100a, 0x00040e09, 0x00040d08, 0x0007100b, 0x00070f0a, 0x00070f0a, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00515110, 0x00515110, 0x00525310, 0x00535410, 0x00535410, 0x00545510, 0x00545511, 0x00545510, 0x00545510, 0x00545510, 0x00545510, 0x00555611, 0x00555611, 0x00555611, 0x00565711, 0x00585810, 0x00585810, 0x00585911, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00616112, 0x00626312, 0x00666414, 0x00c6a219, 0x00cca519, 0x00796f14, 0x00646414, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005d5e12, 0x009a8114, 0x00cca417, 0x00b09014, 0x00505010, 0x00515110, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040c06, 0x00050e08, 0x00050d07, 0x00050e08, 0x00050e08, 0x00060e09, 0x00060e09, 0x00050d08, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e0a, 0x00070f0a, 0x00050d09, 0x00050d09, 0x00040c08, 0x00050d08, 0x00050d08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00070e0c, 0x0008100b, 0x0008100c, 0x0008100a, 0x0009120c, 0x000a130c, 0x000c130d, 0x000c140d, 0x000d140c, 0x000e150d, 0x0010150d, 0x0010150e, 0x00121510, 0x00131410, 0x00141511, 0x00151512, 0x00151713, 0x00161814, 0x00161814, 0x00161814, 0x00171814, 0x00171812, 0x00171812, 0x00181a14, 0x00181a14, 0x00181813, 0x00181a14, 0x00191b14, 0x00181a14, 0x00181813, 0x00181813, 0x00181914, 0x00181914, 0x00181a14, 0x00181a14, 0x00181914, 0x00181914, 0x00191a14, 0x001a1b15, 0x00191a14, 0x00181914, 0x00181a14, 0x00191c17, 0x001b1c16, 0x001c1b16, 0x001c1b14, 0x00201c17, 0x00241e18, 0x00241d16, 0x00241e14, 0x00241d16, 0x00241d16, 0x00241e14, 0x00241e13, 0x00221e14, 0x00201f14, 0x00201e14, 0x00201e14, 0x00211e14, 0x00211e14, 0x00201e14, 0x00221d14, 0x00231c14, 0x00221c14, 0x00211c14, 0x001e1a13, 0x0017150c, 0x0017140c, 0x0014140a, 0x00141209, 0x0015150b, 0x001f1e15, 0x0029271f, 0x0026241c, 0x00201e15, 0x00201d14, 0x001a180e, 0x00231c11, 0x0032281c, 0x003a2d1d, 0x0041321c, 0x00402e16, 0x0046301b, 0x004b3321, 0x004d3423, 0x004f3420, 0x0051341d, 0x0055351c, 0x005c3a1c, 0x005d3818, 0x005e3614, 0x00603614, 0x00643c16, 0x00663f19, 0x00643d18, 0x00643c17, 0x00623b14, 0x00643911, 0x00663910, 0x00683a10, 0x006b3c11, 0x00714114, 0x00754415, 0x00794715, 0x007b4814, 0x007d4914, 0x00814d17, 0x00824b11, 0x007c450b, 0x007e450c, 0x007f460c, 0x0081470e, 0x00854a11, 0x00834811, 0x007f4610, 0x007c4410, 0x00753f0d, 0x00703c0a, 0x006d3b08, 0x006c380a, 0x0069370b, 0x0064340c, 0x0063340c, 0x0064370f, 0x0062350d, 0x005f330b, 0x0060340c, 0x0060340c, 0x0062350e, 0x005b300a, 0x00562e09, 0x00522a07, 0x00542c0c, 0x0051280b, 0x004e280c, 0x00452209, 0x0041200b, 0x003e200b, 0x003c1e0c, 0x00381c0c, 0x00341d0d, 0x00281608, 0x00221408, 0x00201306, 0x00211407, 0x00211407, 0x00221407, 0x00201407, 0x001d1208, 0x001a1008, 0x0018110a, 0x0017130c, 0x0018130e, 0x0018130f, 0x0019140f, 0x001b170f, 0x001d1a11, 0x001c1912, 0x001c1911, 0x001a1811, 0x001b1812, 0x001b1a15, 0x001b1b16, 0x001b1c16, 0x001a1c16, 0x00191c16, 0x00181c15, 0x00181c16, 0x00181c18, 0x00181c18, 0x00181c18, 0x00161c16, 0x00161c17, 0x00161c17, 0x00161c16, 0x00171e17, 0x00171d17, 0x00181e17, 0x00151c14, 0x00151c14, 0x00161c16, 0x00161c16, 0x00151c14, 0x00151c14, 0x00151c15, 0x00151c15, 0x00151c16, 0x00151c15, 0x00161c15, 0x00171c15, 0x00171c15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00171c15, 0x00171c15, 0x00161c16, 0x00171d17, 0x00171d17, 0x00171d16, 0x001b1d17, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d15, 0x00181d14, 0x001a1f16, 0x001a1f16, 0x001a1f17, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00171e18, 0x00161e18, 0x00151d17, 0x00141c15, 0x00141c15, 0x00131b14, 0x00141c15, 0x00121a14, 0x00111a12, 0x00101810, 0x000f1810, 0x000f1811, 0x000c140e, 0x000c140e, 0x000c140f, 0x000c1410, 0x000c1410, 0x000b130f, 0x0008100c, 0x0008100c, 0x0008100c, 0x0009100c, 0x0008100b, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00060e08, 0x00050d07, 0x00040d07, 0x00050d08, 0x00050d08, 0x00050d09, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x00070f0a, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00070f0a, 0x0005100a, 0x00040f09, 0x0006100b, 0x0006100b, 0x00050f0a, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a0f, 0x004c4d0f, 0x004f5010, 0x00505010, 0x00525310, 0x00535410, 0x00545510, 0x00555611, 0x00555611, 0x00565711, 0x00565710, 0x00565710, 0x00585810, 0x00585810, 0x00585810, 0x00585810, 0x00565710, 0x00585810, 0x00585911, 0x00585910, 0x00595a11, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00616112, 0x00626312, 0x00626313, 0x00666414, 0x00c6a219, 0x00cca519, 0x00796f14, 0x00646414, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606012, 0x005d5e12, 0x009a8114, 0x00cca417, 0x00b09014, 0x00505010, 0x00515110, 0x004d4e0f, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x00393b0c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040c06, 0x00040d07, 0x00040d07, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00050e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00070f0a, 0x00070f0b, 0x00040c08, 0x00050d09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00070d09, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100c, 0x0009110d, 0x000b130e, 0x000b130c, 0x000a130c, 0x000c140e, 0x000f150f, 0x000f150f, 0x0010160f, 0x00111710, 0x00131610, 0x00141710, 0x00151813, 0x00151813, 0x00171814, 0x00171814, 0x00171814, 0x00181a15, 0x00181a15, 0x00181a15, 0x00181a15, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181813, 0x00181a14, 0x00181a14, 0x00181a14, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181913, 0x00181914, 0x00181913, 0x00181813, 0x00181914, 0x00181b16, 0x001a1b15, 0x001b1a15, 0x001b1a14, 0x00201c16, 0x00231e18, 0x00241c16, 0x00241d14, 0x00241d16, 0x00241d14, 0x00241d13, 0x00241d12, 0x00241f13, 0x00242013, 0x00231f13, 0x00231f12, 0x00231f12, 0x00231f12, 0x00221e12, 0x00221d14, 0x00231c14, 0x00231c14, 0x00231c14, 0x001d1912, 0x001a1810, 0x0018150d, 0x0015130a, 0x00141208, 0x00131308, 0x0017150d, 0x001f1c14, 0x00211f17, 0x001d1c13, 0x001c1c13, 0x001c1b13, 0x0017130c, 0x00241c14, 0x0032281b, 0x003b2f19, 0x003c2e16, 0x0044311c, 0x00452f1e, 0x0048321d, 0x004a321c, 0x0051371f, 0x0055371d, 0x005d3a1e, 0x005e3818, 0x005e3614, 0x005e3411, 0x00633914, 0x00643d18, 0x00663e18, 0x00643c17, 0x00653c18, 0x00663c16, 0x00693d14, 0x006d4014, 0x00714014, 0x00784518, 0x007d4918, 0x007c4714, 0x007b4511, 0x0078420d, 0x007c4510, 0x00854d14, 0x00844910, 0x007c420a, 0x007c4109, 0x007e420a, 0x0081450c, 0x00854a10, 0x0081470e, 0x007c440c, 0x007c440e, 0x0078420c, 0x00733f09, 0x00703c0c, 0x006e3b0c, 0x006a380e, 0x0066360e, 0x0064360d, 0x0063340c, 0x0060340b, 0x0060340c, 0x0060340b, 0x005d3009, 0x005c310d, 0x005c3311, 0x00582f0f, 0x0052290d, 0x004c2409, 0x00462008, 0x0044200a, 0x0041200d, 0x003a1c0a, 0x003a1c0d, 0x00351c0e, 0x002a170a, 0x00241408, 0x001e1307, 0x001c1106, 0x001d1308, 0x001f1408, 0x00201408, 0x001f1408, 0x001e1409, 0x001c1209, 0x0019140b, 0x0017140b, 0x0016120a, 0x0016120a, 0x0018140d, 0x0019180f, 0x001c1a13, 0x001c1a14, 0x001c1a14, 0x001a1913, 0x00191913, 0x001a1a14, 0x001a1b15, 0x001b1c16, 0x001a1c16, 0x00181c15, 0x00181a14, 0x00181b15, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161c16, 0x00151c15, 0x00161c17, 0x00161c17, 0x00161c16, 0x00161c17, 0x00151c16, 0x00141b15, 0x00141b15, 0x00151c17, 0x00151c16, 0x00141b15, 0x00141a15, 0x00141c15, 0x00141c15, 0x00141c15, 0x00131b14, 0x00131a14, 0x00141a14, 0x00151a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00151b15, 0x00151b15, 0x00161c16, 0x00161c17, 0x00161c16, 0x00151b15, 0x00181b14, 0x00181b14, 0x00181b14, 0x00181b14, 0x00181c15, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d15, 0x00181d14, 0x001a1f16, 0x001b2017, 0x001a1f18, 0x00191d18, 0x00191d18, 0x001a1f19, 0x00191e18, 0x00181e18, 0x00171f18, 0x00171f18, 0x00171f18, 0x00161e18, 0x00161e18, 0x00161e18, 0x00131b14, 0x00121a12, 0x00121b12, 0x00111a12, 0x000f1811, 0x000e1710, 0x000e1710, 0x000e1610, 0x000d1510, 0x000d1510, 0x000c1410, 0x000b130f, 0x000a120e, 0x000a120e, 0x0009120e, 0x0008120d, 0x0005110b, 0x0005110b, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f09, 0x00070f08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060e09, 0x00070f0a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x00070f0a, 0x00080e0a, 0x00070d09, 0x00070d09, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0007110c, 0x00040c08, 0x00050d08, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002d2f0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a0f, 0x004c4d0f, 0x004b4c10, 0x004d4e10, 0x00505010, 0x00525311, 0x00535411, 0x00545510, 0x00555610, 0x00565711, 0x00585812, 0x00585811, 0x00585912, 0x00585912, 0x00585911, 0x00585911, 0x00585912, 0x00595a11, 0x00595a11, 0x00595a12, 0x00595a12, 0x005c5c12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005d5d11, 0x00606012, 0x00606013, 0x00616113, 0x00626213, 0x00636312, 0x00646412, 0x00646414, 0x00847714, 0x00c8a318, 0x00cca519, 0x00797014, 0x00646414, 0x00646414, 0x00636414, 0x00626313, 0x00616112, 0x00606012, 0x005d5e12, 0x009a8114, 0x00cca417, 0x00b09014, 0x00505010, 0x00515110, 0x004c4d10, 0x00494a10, 0x0045470e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0020230a, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060d0a, 0x00060e0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00070f08, 0x00040d07, 0x00040c07, 0x00040d08, 0x00040d08, 0x00070f0a, 0x00060e0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x0008100b, 0x0008100c, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060f08, 0x00060f08, 0x00060e08, 0x00060e08, 0x00060e07, 0x00060e07, 0x00060e08, 0x00060e08, 0x00060e09, 0x00050e08, 0x00060d08, 0x00070d09, 0x00070d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0009110c, 0x000c140e, 0x000c140f, 0x000c140e, 0x000c140e, 0x000d150f, 0x00101711, 0x00101711, 0x00131811, 0x00141811, 0x00141811, 0x00151812, 0x00181814, 0x00181814, 0x00181914, 0x00181915, 0x00181a15, 0x00181a15, 0x00181a15, 0x00181a15, 0x00181a14, 0x00181a13, 0x00181a13, 0x00181a13, 0x00181a13, 0x00181913, 0x00181a14, 0x00181a14, 0x00181a13, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00181813, 0x00171813, 0x00171812, 0x00171813, 0x00181813, 0x00181813, 0x00181a14, 0x001a1b15, 0x001b1a15, 0x001a1a15, 0x001c1c15, 0x001f1d16, 0x00201c14, 0x00211c13, 0x00241e14, 0x00241e13, 0x00241e13, 0x00241e11, 0x00241f12, 0x00261f12, 0x00251e11, 0x00251d11, 0x00241e11, 0x00241e11, 0x00241e11, 0x00241e11, 0x00241d13, 0x00231c15, 0x00231c14, 0x001f1a13, 0x001c1810, 0x0018160d, 0x0015140a, 0x00131308, 0x00141408, 0x0014130a, 0x0017150d, 0x001a1910, 0x001b1b12, 0x001b1b12, 0x001b1a13, 0x0015140d, 0x0016120c, 0x0020190f, 0x00352c1c, 0x00372b18, 0x0040311e, 0x0040301c, 0x0043301c, 0x0046321b, 0x0050381f, 0x0051361b, 0x00583418, 0x005b3616, 0x005d3612, 0x00603611, 0x00633914, 0x00653d18, 0x00673d18, 0x00673c18, 0x00683d19, 0x00683d17, 0x006f4319, 0x00714419, 0x00774418, 0x007c4718, 0x00804919, 0x007c4614, 0x007a4411, 0x00753d0b, 0x00743c09, 0x007d440f, 0x007c410c, 0x007e420d, 0x007e420d, 0x007c400c, 0x007d430c, 0x00834b10, 0x007f480f, 0x007c450e, 0x007a440d, 0x0078440d, 0x00743f08, 0x00703c08, 0x006e3a0a, 0x006c380e, 0x0069370f, 0x0066360e, 0x0067370f, 0x0063340b, 0x0061340b, 0x0060340b, 0x005c300a, 0x005c2f0c, 0x00582f0d, 0x00542c0e, 0x0050270b, 0x00482006, 0x00411c04, 0x00411f09, 0x003b1c0a, 0x00341908, 0x00361c10, 0x002c150c, 0x00201005, 0x001e1107, 0x001c1108, 0x001a1007, 0x001b1208, 0x001c1308, 0x001e1309, 0x001f1409, 0x001e1409, 0x001b1309, 0x0019140b, 0x0018140b, 0x0017140a, 0x0017130b, 0x0018160e, 0x0019170f, 0x001c1913, 0x001b1a15, 0x001a1b15, 0x001a1914, 0x00181a14, 0x00181a14, 0x00181c14, 0x00181c16, 0x00191c16, 0x001a1c16, 0x00191a14, 0x00181b15, 0x00171c17, 0x00161c17, 0x00151c16, 0x00141c15, 0x00131b14, 0x00141a14, 0x00151c15, 0x00151a14, 0x00151b16, 0x00141a16, 0x00141a15, 0x00141915, 0x00131915, 0x00131915, 0x00141a16, 0x00141a16, 0x00141c15, 0x00141c15, 0x00141c15, 0x00121a14, 0x00121913, 0x00131813, 0x00131813, 0x00121813, 0x00131813, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00141814, 0x00141814, 0x00141814, 0x00141914, 0x00141a14, 0x00141a14, 0x00141a14, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a14, 0x00161b14, 0x00171c15, 0x00181d16, 0x00181c16, 0x00181d16, 0x001a1e18, 0x00191d17, 0x00181d16, 0x00181d18, 0x00191d18, 0x001b201a, 0x001b201a, 0x00181e18, 0x00181e18, 0x00181e18, 0x00181e18, 0x00171f18, 0x00171f18, 0x00161e18, 0x00141c16, 0x00131b14, 0x00141c15, 0x00141b15, 0x00101812, 0x00101812, 0x00111812, 0x00101610, 0x000f1410, 0x000f1410, 0x000e1510, 0x000d1410, 0x000b120e, 0x000a120e, 0x0009130e, 0x0009130e, 0x0006100b, 0x0005110b, 0x0006100a, 0x00070f0b, 0x00070f0b, 0x00070f0b, 0x0008100b, 0x00081009, 0x00081009, 0x00070f09, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x00060f0a, 0x00070e0a, 0x00070d09, 0x00070e09, 0x0007100a, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040c08, 0x00060e09, 0x00050d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x003e400d, 0x0043440e, 0x0045470e, 0x00494a0f, 0x004c4d0f, 0x00685e10, 0x00aa8b14, 0x00af8e14, 0x00af8f14, 0x00b09014, 0x00b09014, 0x00b09014, 0x00b09115, 0x00b09115, 0x00b09115, 0x00b09115, 0x00b19315, 0x00b19215, 0x00b19215, 0x00b19215, 0x00b19216, 0x00b29316, 0x00b29316, 0x00b29316, 0x00b29316, 0x00b39316, 0x00b39317, 0x00b39317, 0x00b39417, 0x00b49417, 0x00b49417, 0x00b49417, 0x00b49417, 0x00b49517, 0x00b49518, 0x00b49518, 0x00b59518, 0x00c4a119, 0x00cca519, 0x00c4a019, 0x00746c14, 0x00646514, 0x00646414, 0x00636414, 0x00636413, 0x00616112, 0x00606012, 0x005d5e12, 0x009b8314, 0x00cca417, 0x00b09014, 0x00505010, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450d, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00060e09, 0x00070f0a, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040d07, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x0008110a, 0x0008110a, 0x000a130c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000e1610, 0x000e1610, 0x000f1811, 0x00101812, 0x00141813, 0x00141811, 0x00141912, 0x00141910, 0x00181813, 0x00181813, 0x00181914, 0x00181a14, 0x00191b14, 0x001a1b14, 0x00191b14, 0x00181a12, 0x00181a12, 0x00181910, 0x0017180f, 0x00181910, 0x00181910, 0x00181b12, 0x00181b12, 0x00181a12, 0x00161811, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00181814, 0x00181814, 0x00181813, 0x00181a14, 0x00181a14, 0x001a1815, 0x00181a14, 0x001b1c15, 0x001f1e14, 0x00211c13, 0x00221c11, 0x00251d11, 0x00261d11, 0x00261d11, 0x00261d11, 0x00271e10, 0x00271e10, 0x00271f0f, 0x00271e10, 0x00271e10, 0x00271e10, 0x00261d10, 0x00241c10, 0x00241c12, 0x00241c12, 0x00241e14, 0x00231c14, 0x001f1910, 0x001b180e, 0x0018170c, 0x0015150a, 0x00141408, 0x00141408, 0x00141408, 0x00191810, 0x00181810, 0x00181810, 0x00181710, 0x00161510, 0x00161410, 0x0016120a, 0x00282217, 0x00372d1f, 0x003f3320, 0x00453823, 0x0043321d, 0x0043301a, 0x004e3820, 0x004d341b, 0x0055341a, 0x005d3b1c, 0x005e3815, 0x005e3812, 0x00623a13, 0x00663c16, 0x00673c16, 0x00693c18, 0x00683c18, 0x00683c16, 0x0070441c, 0x006f4117, 0x0079481b, 0x00804a1e, 0x007c4619, 0x00763e11, 0x00733c0c, 0x00743c0d, 0x00703808, 0x00743b0b, 0x00773d0d, 0x00733909, 0x00753c0a, 0x00773e0c, 0x00743e0a, 0x00744009, 0x0074410c, 0x00764310, 0x0074410d, 0x00703d09, 0x006d3905, 0x006c3907, 0x006c3908, 0x006c390d, 0x0068360d, 0x0068370e, 0x00683810, 0x00603108, 0x00603208, 0x005c2f08, 0x005a2d08, 0x00592d0b, 0x00562c0c, 0x00542c0d, 0x004c2409, 0x00421d03, 0x00432007, 0x003c1e08, 0x00351c0a, 0x0030190c, 0x0025130c, 0x001e0d06, 0x001c1007, 0x001b1108, 0x00191108, 0x00191208, 0x00191208, 0x001c1309, 0x001c1309, 0x001c1208, 0x001c1307, 0x001a130b, 0x0019140b, 0x0018140b, 0x00171409, 0x0018140c, 0x001b170f, 0x001c1810, 0x001c1914, 0x001b1a17, 0x00181915, 0x00181915, 0x00181915, 0x00181a15, 0x00141a14, 0x00141c14, 0x00161b14, 0x00171a14, 0x00181712, 0x00161811, 0x00141812, 0x00111812, 0x00131915, 0x00131b16, 0x00121a15, 0x00131914, 0x00141914, 0x00151a14, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00131914, 0x00131914, 0x00131914, 0x00131914, 0x00121a14, 0x00121a14, 0x00111913, 0x00101812, 0x00121812, 0x00131712, 0x00121712, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00121511, 0x00131511, 0x00131511, 0x00131511, 0x00131511, 0x00141612, 0x00141813, 0x00131914, 0x00131b14, 0x00131b14, 0x00131b14, 0x00131b14, 0x00131a14, 0x00141a14, 0x00141b14, 0x00151c15, 0x00161c15, 0x00181b17, 0x00191c18, 0x00191c18, 0x00181b17, 0x00171c17, 0x00191e19, 0x001a1f18, 0x001a1f16, 0x001a1f16, 0x001a1f18, 0x001a201a, 0x001a1f19, 0x00181f17, 0x00181f17, 0x00181f17, 0x00161c15, 0x00151c14, 0x00151b17, 0x00151b17, 0x00141a16, 0x00141914, 0x00141914, 0x00131712, 0x00101510, 0x0010140f, 0x0010140f, 0x000e140e, 0x000c130d, 0x000c140d, 0x000b140d, 0x000a130c, 0x0008110a, 0x00081009, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x0006100b, 0x0005100a, 0x00040d08, 0x00040d08, 0x00040d08, 0x0006100b, 0x00040d08, 0x0005100a, 0x00040d09, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003c3e0d, 0x0041420e, 0x0044450d, 0x0048490f, 0x004c4d0f, 0x005c5710, 0x00b69314, 0x00cca316, 0x00cca316, 0x00cca417, 0x00cca417, 0x00cca417, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca418, 0x00cca518, 0x00cca518, 0x00cca518, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca619, 0x00cca619, 0x00c8a418, 0x00978315, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00626313, 0x00626312, 0x00606012, 0x005e5f12, 0x00a48914, 0x00cca417, 0x00b09014, 0x004f5010, 0x00505010, 0x004c4d10, 0x00484910, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0036370b, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x00081009, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060f0a, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e08, 0x00040c06, 0x00040c06, 0x00040d07, 0x00040d07, 0x00060e08, 0x00070f08, 0x00081009, 0x00081009, 0x00081009, 0x0009120b, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c140d, 0x000e1610, 0x000e1610, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00141813, 0x00141811, 0x00141912, 0x00141910, 0x00181813, 0x00181813, 0x00181914, 0x00181a14, 0x001a1b14, 0x001c1c15, 0x001b1c14, 0x00181a12, 0x00181a12, 0x00181910, 0x0017180f, 0x00181910, 0x00181910, 0x00181a14, 0x00181a14, 0x00171914, 0x00161812, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00161814, 0x00141813, 0x00131712, 0x00141612, 0x00151612, 0x00161713, 0x00161712, 0x00171812, 0x00191813, 0x001a1b12, 0x001c1c12, 0x001f1e12, 0x00221c10, 0x00241c10, 0x00281c11, 0x00291c12, 0x00291c12, 0x00291c10, 0x00291d10, 0x002a1e10, 0x002a1e11, 0x002a1e11, 0x002a1d13, 0x00291c11, 0x00281c13, 0x00281c13, 0x00281c13, 0x00251c10, 0x00261d11, 0x00241d11, 0x00221b0f, 0x001d190c, 0x001b190b, 0x0018180b, 0x00141508, 0x00121205, 0x00121206, 0x0018170c, 0x0017160d, 0x0016160d, 0x0014140c, 0x0014140b, 0x0014140c, 0x0016140b, 0x00151107, 0x00282315, 0x00352d1d, 0x003c3220, 0x00423421, 0x0044331f, 0x004c3823, 0x004c341d, 0x0055361e, 0x005c3c20, 0x005a3817, 0x005c3814, 0x005f3a15, 0x00633c18, 0x00653b18, 0x00683c1a, 0x00673c18, 0x00683c16, 0x006e411a, 0x006d3f16, 0x0078461c, 0x00764218, 0x006f3c11, 0x006e380f, 0x006f3a0e, 0x006e380c, 0x006b360a, 0x006e390b, 0x00703a0c, 0x006a3508, 0x006c3708, 0x00713c0c, 0x006c3808, 0x006c3b0a, 0x006d3c0c, 0x006d3c0d, 0x006d3c0d, 0x00693809, 0x00683808, 0x00683609, 0x0068370c, 0x0069380c, 0x0068380c, 0x0069390f, 0x0068380f, 0x005f3006, 0x00603209, 0x00582c06, 0x005a2d09, 0x00572c09, 0x0053280a, 0x0050290c, 0x00462107, 0x00401d04, 0x00402208, 0x00391f0b, 0x00311d0c, 0x00241408, 0x001d1108, 0x001c1009, 0x001a0f08, 0x00191008, 0x00181006, 0x00191107, 0x00191208, 0x001a1208, 0x001a1108, 0x00191006, 0x00181205, 0x00181408, 0x00181408, 0x00181408, 0x00181408, 0x001a160b, 0x001c180c, 0x001f190f, 0x001e1913, 0x001b1814, 0x00191816, 0x00181917, 0x00181917, 0x00191816, 0x00171814, 0x00161814, 0x00141811, 0x0013150f, 0x0010120c, 0x0010120a, 0x0010140b, 0x000d120b, 0x00101610, 0x00121914, 0x00111913, 0x00121813, 0x00131712, 0x00121812, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00131914, 0x00131914, 0x00131914, 0x00131914, 0x00131914, 0x00131914, 0x00111813, 0x00101711, 0x00121712, 0x00131712, 0x00121712, 0x00111611, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00121611, 0x00131712, 0x00111812, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00101812, 0x00111813, 0x00131914, 0x00141b14, 0x00151c15, 0x00151c15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00141a14, 0x00171d18, 0x00181f17, 0x00181f15, 0x00181f15, 0x00181f17, 0x00181e18, 0x00181f19, 0x00181f17, 0x00181f17, 0x00181f17, 0x00171e16, 0x00161c16, 0x00161c17, 0x00161c17, 0x00141b15, 0x00141a14, 0x00141914, 0x00131712, 0x00111611, 0x0010140f, 0x0010140f, 0x000e140e, 0x000c130d, 0x000c140d, 0x000c140d, 0x000b140d, 0x0008110a, 0x0008100a, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0005100a, 0x00040e09, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x0006100b, 0x00040e09, 0x0005100a, 0x00040e09, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x00202309, 0x00202309, 0x0026280c, 0x00292b0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00706211, 0x00cca316, 0x00caa216, 0x00b59414, 0x00b39315, 0x00b39316, 0x00b39416, 0x00b39417, 0x00b39417, 0x00b39417, 0x00b39417, 0x00b39417, 0x00b29317, 0x00b29317, 0x00b19217, 0x00b19317, 0x00b19316, 0x00b19316, 0x00b09216, 0x00b09216, 0x00b09216, 0x00b09117, 0x00b09117, 0x00b09116, 0x00b09116, 0x00b09216, 0x00b09217, 0x00b09217, 0x00b09218, 0x00b09218, 0x00b09218, 0x00b09217, 0x00af9318, 0x00a88e17, 0x00857814, 0x00666713, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00636414, 0x00616112, 0x00606013, 0x00605e12, 0x00b49416, 0x00cca417, 0x00ac8c15, 0x004f5010, 0x00505010, 0x004c4d10, 0x00484910, 0x0045470e, 0x0040400d, 0x003c3e0d, 0x0036370c, 0x0034350c, 0x002d2f0a, 0x00292b0b, 0x0026280b, 0x00202309, 0x001d2008, 0x001d2009, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040c08, 0x00040c08, 0x00050d08, 0x00050d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00050d05, 0x00060e06, 0x00060e06, 0x00060e08, 0x00060e08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x0008100a, 0x000a130c, 0x000c140e, 0x000d140e, 0x00101610, 0x00101610, 0x00101610, 0x00101610, 0x00101610, 0x00121812, 0x00131914, 0x00141a14, 0x00161b15, 0x00161b14, 0x00171c15, 0x00171c14, 0x00181a14, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x001a1b14, 0x001a1b14, 0x00191b13, 0x00181a12, 0x00181a12, 0x00181a10, 0x00181a10, 0x0017180f, 0x00161810, 0x00141913, 0x00141914, 0x00141813, 0x00111611, 0x00131712, 0x00111611, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101610, 0x00101610, 0x00111510, 0x00141712, 0x00161814, 0x00161815, 0x00181613, 0x00191710, 0x001c1b0f, 0x001e1c0f, 0x00221d10, 0x00251c0e, 0x00281d0d, 0x002b1d0c, 0x002d1d0d, 0x002c1c0c, 0x002d1e0e, 0x002f200d, 0x0030210f, 0x00322310, 0x00332411, 0x00322312, 0x00302010, 0x002e1e0f, 0x002c1f10, 0x002c1f10, 0x002a1e0f, 0x00281c0d, 0x00281e0f, 0x00231a0c, 0x001f180a, 0x001d1a0a, 0x001b190a, 0x00171708, 0x00171408, 0x00141208, 0x0016140a, 0x001a180e, 0x001a180e, 0x0016150b, 0x00141408, 0x00141408, 0x00131308, 0x00141207, 0x00141105, 0x00241e13, 0x00342b1d, 0x00413424, 0x00403020, 0x0043301e, 0x004f3824, 0x00523520, 0x0054351c, 0x00573718, 0x00553412, 0x00573413, 0x005d3a18, 0x00623c18, 0x00643c1a, 0x00663b18, 0x00693c18, 0x006b3c17, 0x006c3d14, 0x00704118, 0x006f3f15, 0x006c3b11, 0x006d3b12, 0x006d3c12, 0x0066360d, 0x00623208, 0x00643409, 0x00613107, 0x00633308, 0x0064340a, 0x006a3b0e, 0x0066370a, 0x00643508, 0x0067380b, 0x006a3a10, 0x00633308, 0x0067380d, 0x0067380c, 0x0065350c, 0x0065350d, 0x0066360c, 0x0067390c, 0x0067390d, 0x00623709, 0x005c3005, 0x00582c04, 0x00542904, 0x00542908, 0x00532909, 0x004c2306, 0x004b2509, 0x00462309, 0x003f1f06, 0x003a210a, 0x00311e0a, 0x00221404, 0x00180f04, 0x00150f07, 0x00150f06, 0x00180e07, 0x00180e07, 0x00180f05, 0x00191108, 0x001a1208, 0x00191208, 0x00191208, 0x00181207, 0x00161307, 0x00161408, 0x00161408, 0x00171507, 0x001a1709, 0x001c170a, 0x001d170b, 0x00221b0e, 0x00221b12, 0x001e1913, 0x001c1812, 0x001a1913, 0x001b1812, 0x001b1711, 0x001d1810, 0x001d1912, 0x001c180f, 0x001c1b10, 0x0018190f, 0x00121408, 0x00101408, 0x000d1008, 0x000c100b, 0x000c130d, 0x00101610, 0x00101610, 0x00101610, 0x000e1611, 0x000c1710, 0x000c1710, 0x000c1710, 0x000c1710, 0x00101812, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000e1710, 0x000e1610, 0x000f1610, 0x00101610, 0x00101610, 0x000f150f, 0x000f150f, 0x0010140f, 0x0010140f, 0x0010140f, 0x0010140f, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101510, 0x00101711, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x00101913, 0x00121a14, 0x00131b14, 0x00141c15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00151a14, 0x00141a14, 0x00161c16, 0x00171d16, 0x00171e14, 0x00171e14, 0x00171d16, 0x00171d18, 0x00171d18, 0x00181f17, 0x00181f17, 0x00182018, 0x00182018, 0x00171e18, 0x00171d18, 0x00171d18, 0x00161c17, 0x00151c15, 0x00151a14, 0x00141914, 0x00141813, 0x00111611, 0x00111611, 0x00101610, 0x000f150f, 0x000d150f, 0x000e1610, 0x000c140e, 0x000a130c, 0x000a130c, 0x000a1210, 0x0009110f, 0x0008100d, 0x0008100d, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0006100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x0005100a, 0x00040e09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x0005100a, 0x0006100b, 0x00040e09, 0x0006100b, 0x00060c07, 0x000f130f, 0x000f130f, 0x0014180f, 0x0014180b, 0x00191c0a, 0x001d200a, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004f5010, 0x00515110, 0x00706411, 0x00cca316, 0x00c7a016, 0x006d6612, 0x00605f12, 0x00626013, 0x00636212, 0x00646413, 0x00646413, 0x00656414, 0x00656414, 0x00656414, 0x00656414, 0x00656414, 0x00646413, 0x00646413, 0x00646413, 0x00646313, 0x00646312, 0x00646313, 0x00646313, 0x00646313, 0x00646313, 0x00646313, 0x00646413, 0x00646413, 0x00646414, 0x00656414, 0x00656414, 0x00656414, 0x00666514, 0x00666513, 0x00686714, 0x00686813, 0x00666713, 0x00666713, 0x00656614, 0x00656614, 0x00656614, 0x00646514, 0x00636414, 0x00626313, 0x00616112, 0x006c6613, 0x00c4a017, 0x00cca417, 0x00988014, 0x00515110, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e08, 0x00040d07, 0x00050d07, 0x00060e08, 0x00060e08, 0x0008100b, 0x0008100b, 0x00050d08, 0x00050d09, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d05, 0x00060e06, 0x00060e06, 0x00050d05, 0x00060e08, 0x00060e08, 0x00081009, 0x00070f08, 0x00070f08, 0x0009110b, 0x0008100a, 0x0008100a, 0x0008110a, 0x0008110b, 0x000a130c, 0x000c140e, 0x000d140e, 0x00101510, 0x00101510, 0x00131712, 0x00131712, 0x00131712, 0x00141914, 0x00151a14, 0x00151a14, 0x00161b15, 0x00181a14, 0x00181c15, 0x00181c14, 0x00181813, 0x001a1c15, 0x001c1d18, 0x001b1c16, 0x001a1b14, 0x001a1b14, 0x00191a13, 0x00181911, 0x00181911, 0x00171810, 0x00171810, 0x00161710, 0x00141810, 0x00131812, 0x00121813, 0x00111812, 0x00101610, 0x00101711, 0x00101610, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x00101510, 0x00131713, 0x00161815, 0x00161815, 0x00181712, 0x001a1810, 0x001e1b10, 0x00201c0f, 0x00241d10, 0x00281c0c, 0x002b1c0a, 0x002f1c05, 0x00311f05, 0x00322004, 0x00312005, 0x0038260a, 0x0038270b, 0x00362509, 0x00352408, 0x00352408, 0x00352408, 0x00342408, 0x00342409, 0x0033230b, 0x0030220a, 0x002d200a, 0x002b1e09, 0x00261b08, 0x00241b0a, 0x00211c0a, 0x00201c0b, 0x001c1908, 0x0018170c, 0x0017140a, 0x0017140b, 0x0017140a, 0x0019180c, 0x0017170a, 0x00141408, 0x00131408, 0x00111408, 0x00111308, 0x00131208, 0x00141008, 0x00221c10, 0x00393021, 0x00423525, 0x003f2f1f, 0x0044311e, 0x004a321f, 0x004c311a, 0x0055371d, 0x00543415, 0x00553515, 0x00563414, 0x00603a1a, 0x00633c1c, 0x00643a18, 0x00673c18, 0x00683b15, 0x00673b12, 0x00693c13, 0x006c3d14, 0x006b3c14, 0x00683a11, 0x0064360f, 0x005e300a, 0x00582c05, 0x00572b04, 0x00542803, 0x00572b06, 0x005f320c, 0x0062340c, 0x0062350c, 0x005f3109, 0x005f310a, 0x0061340d, 0x005d300a, 0x005c2f08, 0x005d3009, 0x005f320c, 0x005f320c, 0x0061340c, 0x0064380e, 0x0064380e, 0x005d3308, 0x00592e05, 0x00572c06, 0x00542a08, 0x00542c0c, 0x00542c0d, 0x00492308, 0x00431f05, 0x003e1c06, 0x00381b06, 0x00341f0b, 0x00201200, 0x00181002, 0x00141004, 0x00141008, 0x00151007, 0x00160e06, 0x00170e04, 0x00171005, 0x00181208, 0x00191308, 0x00181308, 0x00181308, 0x00161307, 0x00141407, 0x00141506, 0x00161408, 0x00191709, 0x001c1809, 0x001d1707, 0x001e1607, 0x00251c0d, 0x00281d10, 0x00231a0f, 0x001e180c, 0x001c190c, 0x001d190b, 0x001d1609, 0x00261c0c, 0x002c200f, 0x002e2411, 0x00322a18, 0x002a2514, 0x00181606, 0x00131307, 0x00101308, 0x000f1009, 0x000e1109, 0x0010150e, 0x00101510, 0x00101610, 0x000e1611, 0x000c1810, 0x000c1810, 0x000c1810, 0x000c1810, 0x000e1811, 0x000c160f, 0x000c160f, 0x000c160f, 0x000c160f, 0x000c1710, 0x000c1710, 0x000d1810, 0x000d1610, 0x000c140e, 0x000c140e, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000e150f, 0x000d150f, 0x000c160f, 0x000f1811, 0x000f1811, 0x000f1811, 0x000f1811, 0x000e1811, 0x000e1811, 0x000f1912, 0x000f1912, 0x00101912, 0x00111812, 0x00111812, 0x00111812, 0x00101812, 0x00131b14, 0x00141c15, 0x00131c13, 0x00131c13, 0x00131c13, 0x00131c13, 0x00151e18, 0x00151e18, 0x00181f17, 0x00181f17, 0x00182018, 0x00182018, 0x00181e17, 0x00171d16, 0x00181e17, 0x00182018, 0x00181f18, 0x00161b15, 0x00151a14, 0x00141914, 0x00131712, 0x00131712, 0x00111711, 0x00101610, 0x000e1610, 0x000f1710, 0x000c140e, 0x000c140e, 0x000c140e, 0x000a120f, 0x0009110f, 0x0008100d, 0x0008100d, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0007100b, 0x0006100b, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x00040e09, 0x0008110c, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003e400c, 0x0043440e, 0x0047480e, 0x004c4d10, 0x004f5010, 0x00535410, 0x00716512, 0x00cca417, 0x00c7a116, 0x006c6713, 0x00606013, 0x00626313, 0x00646414, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666713, 0x00656614, 0x00646514, 0x00656614, 0x00646414, 0x00646514, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00636414, 0x00646414, 0x00646514, 0x00646514, 0x00646513, 0x00656614, 0x00666714, 0x00666713, 0x00666714, 0x00666714, 0x00666714, 0x00666714, 0x00666713, 0x00656614, 0x00646513, 0x00646414, 0x00626313, 0x00606013, 0x00947f14, 0x00caa317, 0x00c8a117, 0x00746811, 0x00535410, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x0026280a, 0x0026280c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00081009, 0x00060e08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d07, 0x00070f08, 0x00070f08, 0x00081009, 0x0008100b, 0x0008100c, 0x000b130e, 0x000c1410, 0x000c140f, 0x000e140e, 0x000f150f, 0x000f150f, 0x00101510, 0x00121611, 0x00121711, 0x00141814, 0x00151a14, 0x00151a13, 0x00161b14, 0x00171c15, 0x00171c15, 0x001a1b15, 0x001a1b15, 0x001b1c16, 0x001b1c16, 0x001c1c18, 0x001b1c16, 0x00191b14, 0x001a1b14, 0x00171811, 0x00171812, 0x00161711, 0x00151610, 0x00151610, 0x00131611, 0x00131611, 0x00131510, 0x00131510, 0x00101510, 0x00101510, 0x00111611, 0x00101610, 0x000d1510, 0x000d1510, 0x000c1410, 0x000c1410, 0x000f150f, 0x000f150f, 0x000f150f, 0x000e140e, 0x000c140d, 0x000e150f, 0x00101610, 0x00101510, 0x00131714, 0x00161814, 0x00191711, 0x001c180f, 0x001e190e, 0x00241b10, 0x002c1c10, 0x00321b0d, 0x003c200d, 0x004f3414, 0x00583d1a, 0x004f340e, 0x00482f08, 0x00503812, 0x00503814, 0x004a330f, 0x00442c08, 0x00442b09, 0x00482d0c, 0x00462f0c, 0x0045300c, 0x00422f0c, 0x00382805, 0x00342404, 0x002f2104, 0x002a1e03, 0x00261b08, 0x00251c09, 0x00251d0b, 0x00231c0a, 0x001b190b, 0x00181609, 0x00181709, 0x00161407, 0x0019180a, 0x0019180c, 0x00141408, 0x00111406, 0x00101407, 0x000f1307, 0x00101207, 0x00101107, 0x00131107, 0x00211b10, 0x0033291c, 0x003a2d1f, 0x00483828, 0x0046311f, 0x00442e18, 0x00563d24, 0x00553920, 0x0058391c, 0x00553517, 0x005d391a, 0x005f3818, 0x00603718, 0x00653a18, 0x00623712, 0x00643911, 0x0064380f, 0x0064380f, 0x00653910, 0x005e320a, 0x00592c07, 0x00592c0b, 0x00582c0d, 0x00542b0c, 0x004d2408, 0x0051280c, 0x00552a0c, 0x00582d0e, 0x005c310c, 0x005d320c, 0x005b300b, 0x00582d09, 0x005c300c, 0x00542804, 0x005a2f0b, 0x005d320e, 0x005a2f09, 0x005f340e, 0x00623810, 0x0061370e, 0x005c3008, 0x00542a03, 0x00562b07, 0x00542c0a, 0x00542c0d, 0x004b2608, 0x004b260c, 0x0041210a, 0x00361c09, 0x002e1808, 0x00200e01, 0x00190e04, 0x00141005, 0x00121008, 0x00131008, 0x00151008, 0x00161007, 0x00171106, 0x00171207, 0x00181308, 0x00171408, 0x00151408, 0x00151408, 0x00141408, 0x00161408, 0x00181408, 0x0019140b, 0x001d160c, 0x001f170a, 0x00201806, 0x00261b09, 0x002d200e, 0x00342511, 0x00311f08, 0x002a1901, 0x002b1c05, 0x002e2007, 0x00302003, 0x003d2a08, 0x00463413, 0x00433415, 0x0040321a, 0x002f2410, 0x00181104, 0x00110f05, 0x00121006, 0x00110f05, 0x000f0d04, 0x000f100b, 0x0010140f, 0x000f1410, 0x000d1510, 0x000c1710, 0x000b1710, 0x000b1710, 0x000b1710, 0x000c1610, 0x000c1610, 0x000c1610, 0x000c1610, 0x000b1510, 0x000b1510, 0x000a140f, 0x0009130e, 0x000a140f, 0x000a140d, 0x000a140d, 0x000a140d, 0x000a140d, 0x0009140b, 0x0008130a, 0x0009140b, 0x0009140b, 0x000c140c, 0x000c140c, 0x000c140c, 0x000c140c, 0x000a140d, 0x000b150e, 0x000b150e, 0x000b150e, 0x000c1410, 0x000c1410, 0x000d1510, 0x000d1510, 0x000c1610, 0x000b170f, 0x000c1810, 0x000c1810, 0x000c1811, 0x000d1712, 0x000d1711, 0x000e1813, 0x000f1812, 0x00111913, 0x00131b14, 0x00131b14, 0x00131b14, 0x00131b15, 0x00131b14, 0x00141c15, 0x00141c14, 0x00161c16, 0x00181c18, 0x00191d18, 0x00191e18, 0x00191d18, 0x00181c18, 0x00181c17, 0x00181d15, 0x00181c15, 0x00171c17, 0x00171c17, 0x00161b15, 0x00141914, 0x00141612, 0x00131712, 0x00101812, 0x000e1710, 0x00101610, 0x00101610, 0x000c140e, 0x000b140d, 0x000a140d, 0x0009140d, 0x0008120c, 0x0008120c, 0x0009110c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0007100b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0004100a, 0x0004100a, 0x00030f09, 0x00030f09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0044450d, 0x00494a0f, 0x004d4e0f, 0x00515110, 0x00555610, 0x00726612, 0x00cca417, 0x00c7a118, 0x006f6913, 0x00636413, 0x00646514, 0x00656614, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00686814, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00656614, 0x00646514, 0x00636414, 0x006b6613, 0x00bc9917, 0x00cca418, 0x00ad8e15, 0x005b5911, 0x00545510, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0038380c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00081009, 0x00060e08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d05, 0x00060e06, 0x00060e06, 0x00060e06, 0x00040d07, 0x00070f08, 0x0009110b, 0x0009120b, 0x0008100c, 0x0008100c, 0x000b130e, 0x000c1410, 0x000e1510, 0x000f150f, 0x00101610, 0x00101710, 0x00111711, 0x00141814, 0x00141814, 0x00151a14, 0x00161a14, 0x00181a14, 0x00181a14, 0x00181c15, 0x00181c15, 0x001a1b15, 0x001a1b15, 0x001b1c16, 0x001b1c16, 0x001a1b17, 0x00181914, 0x00181913, 0x001a1b14, 0x00191b14, 0x00181813, 0x00161711, 0x00151610, 0x00141610, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x000f150f, 0x000f150f, 0x000e140e, 0x000e140e, 0x000c140d, 0x000c140d, 0x000b130c, 0x000b130c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140e, 0x000f1610, 0x00101510, 0x00121814, 0x00141711, 0x001a1811, 0x001e1910, 0x0020190c, 0x00281b0e, 0x00301c0a, 0x00402508, 0x005c3c16, 0x00755324, 0x0074501d, 0x0066440e, 0x00603f07, 0x00684811, 0x00684814, 0x0064430f, 0x005f3c08, 0x005c3a08, 0x005e3b0b, 0x005c3a0c, 0x005a3a0f, 0x00573a10, 0x00483008, 0x003b2704, 0x00332204, 0x002d1f05, 0x002b1d09, 0x00291d0a, 0x00281e09, 0x00241c08, 0x001e1c0b, 0x001b1909, 0x001b1a0a, 0x001c1c0c, 0x001b1a0a, 0x00191809, 0x00181809, 0x00101404, 0x000d1204, 0x000e1205, 0x000e1207, 0x000e1107, 0x00121308, 0x00151206, 0x001a1408, 0x002d2416, 0x003e3121, 0x00443220, 0x0045301d, 0x00523a25, 0x00583c27, 0x00563a1f, 0x00543518, 0x005a3818, 0x005a3415, 0x005d3415, 0x00613816, 0x005f3511, 0x00663c15, 0x0060370e, 0x0060340c, 0x005c320b, 0x005c320b, 0x00572b06, 0x0057290b, 0x0056290c, 0x00542a10, 0x004c250b, 0x004e250c, 0x004e250a, 0x00532a0c, 0x005a3110, 0x005c3310, 0x005a300d, 0x00562c09, 0x00552b08, 0x00562c09, 0x005c3310, 0x00603613, 0x005a310d, 0x005b310c, 0x00603611, 0x005f350f, 0x005c330c, 0x00552c07, 0x00542c09, 0x00532c0b, 0x00492607, 0x00411f04, 0x0042230c, 0x0039200b, 0x00291505, 0x001c0d01, 0x00160b00, 0x00160e06, 0x00140f09, 0x00120f0a, 0x00141009, 0x00161109, 0x00161208, 0x00171407, 0x00171408, 0x00171408, 0x00161408, 0x00161408, 0x00161407, 0x00151406, 0x00171406, 0x001a1408, 0x001b1308, 0x001e150c, 0x0021170a, 0x00281b08, 0x002b1d08, 0x00362410, 0x003f2a0f, 0x00432b08, 0x00462d03, 0x004e3407, 0x005a4010, 0x00563e0b, 0x0058400f, 0x00543d13, 0x0044300d, 0x0032230a, 0x00241707, 0x00170f04, 0x00110f05, 0x00121006, 0x00111005, 0x000f0d04, 0x00101009, 0x0011140e, 0x000f1410, 0x000d1410, 0x00091410, 0x00091410, 0x00091410, 0x00091410, 0x000a1410, 0x000a1410, 0x000a1410, 0x000a1410, 0x000a1410, 0x00091310, 0x00091310, 0x0008120f, 0x0009130f, 0x0009130e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0008120c, 0x0008120c, 0x0009140c, 0x0009140c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000a140d, 0x000b150e, 0x000a140d, 0x000a140d, 0x000c140f, 0x000c140f, 0x000c1410, 0x000c1410, 0x000b150f, 0x000a160e, 0x000b170f, 0x000c1810, 0x000c1811, 0x000c1713, 0x000c1711, 0x000c1711, 0x000d1710, 0x00101812, 0x00111913, 0x00131b14, 0x00131b14, 0x00141a16, 0x00141a14, 0x00151c15, 0x00151c14, 0x00161b15, 0x00161b15, 0x00171c17, 0x00181c17, 0x00181c18, 0x00181d17, 0x00181d15, 0x00181d14, 0x00181c14, 0x00171c17, 0x00171c17, 0x00161b15, 0x00141914, 0x00141813, 0x00121712, 0x00101812, 0x000e1710, 0x00101610, 0x00101610, 0x000e1710, 0x000c140e, 0x000a140d, 0x0009140c, 0x0008120c, 0x0008120c, 0x0009110c, 0x0009110d, 0x0008100b, 0x0008100b, 0x0007100b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0004100a, 0x0004100a, 0x00030f09, 0x00030f09, 0x00040e09, 0x0005100a, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0026280c, 0x00292b0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x004b4c0f, 0x00505010, 0x00535410, 0x00565711, 0x00746812, 0x00cca418, 0x00c7a118, 0x00706b14, 0x00646414, 0x00656614, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00666713, 0x00656614, 0x00646513, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00646514, 0x00646414, 0x00a28915, 0x00cba418, 0x00c6a118, 0x00786c13, 0x00565711, 0x00545511, 0x00505010, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00081009, 0x00060e08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060e06, 0x00071007, 0x00060e06, 0x00060e06, 0x00081009, 0x00081009, 0x0009120c, 0x0009120c, 0x000a120e, 0x000b130e, 0x000c1410, 0x000d1510, 0x000e1510, 0x00101610, 0x00101711, 0x00111812, 0x00131812, 0x00161812, 0x00161812, 0x00181c15, 0x00191c15, 0x001a1b14, 0x001a1b14, 0x001a1b14, 0x001a1b14, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x001a1b17, 0x00181914, 0x00181813, 0x00181912, 0x00161810, 0x00141710, 0x00131610, 0x0012150f, 0x0011150f, 0x0010150f, 0x000f150f, 0x000e140f, 0x000c130d, 0x000c140d, 0x000c140e, 0x000a130c, 0x000a130c, 0x000a130c, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008130c, 0x0008130c, 0x0008120c, 0x0008120c, 0x0009130c, 0x000b140d, 0x000e150f, 0x00101510, 0x00111613, 0x00141510, 0x001b1811, 0x00201810, 0x0023190d, 0x002e1e0f, 0x003c2408, 0x00634414, 0x007f581b, 0x0091651c, 0x008e6212, 0x008c600f, 0x00895f0b, 0x00916814, 0x00916815, 0x008c6410, 0x008a600d, 0x008a600c, 0x00895e0c, 0x00855a11, 0x007e5514, 0x00684209, 0x00513302, 0x00432b02, 0x00372405, 0x002e1e06, 0x002e1e09, 0x002d1e0a, 0x002b1f09, 0x0029200b, 0x00221e0b, 0x001f1c0a, 0x00201c0b, 0x00201d0b, 0x001e1c09, 0x001a1908, 0x001a1b09, 0x00161a09, 0x000c1002, 0x000c1004, 0x000c1005, 0x000c1006, 0x000e1006, 0x00121108, 0x00151208, 0x00181307, 0x00292012, 0x003f3020, 0x00402e1e, 0x004b3623, 0x00503824, 0x0050351d, 0x00503419, 0x00563719, 0x00563417, 0x005d3417, 0x005f3414, 0x00623816, 0x00643c16, 0x005d350e, 0x005b330c, 0x00572f0a, 0x005b330d, 0x005b300e, 0x00582b0e, 0x0054280e, 0x0050270c, 0x004c240c, 0x004c240d, 0x004b250a, 0x00532c0e, 0x00532c0c, 0x00502808, 0x00512908, 0x00572c0c, 0x00562c0c, 0x00512807, 0x00572d0c, 0x005d3313, 0x005c3210, 0x00572d0a, 0x00582e0a, 0x0059300c, 0x00582f0a, 0x00512806, 0x004e2809, 0x00502c10, 0x0049270d, 0x003c1f08, 0x00331c0b, 0x00281608, 0x00190c02, 0x00140c04, 0x00120d05, 0x00110d08, 0x00120e0c, 0x00100f0c, 0x00120f0b, 0x00131009, 0x00141208, 0x00151406, 0x00161407, 0x00161408, 0x00161408, 0x00161407, 0x00181508, 0x00191507, 0x001b1406, 0x001d1408, 0x0020160b, 0x0024180c, 0x00281a0c, 0x002e1f0a, 0x00312008, 0x003f280d, 0x00503510, 0x006e4e1b, 0x008d682a, 0x009d7128, 0x00a0762a, 0x008e6b24, 0x006e4e16, 0x004d340a, 0x00352103, 0x00211400, 0x00180f02, 0x00131006, 0x00111005, 0x00100f04, 0x00111005, 0x00100e05, 0x000e0f08, 0x000e110b, 0x000e130e, 0x000c1410, 0x00081311, 0x00081312, 0x00081312, 0x00081312, 0x00091312, 0x00091312, 0x00091312, 0x00091312, 0x00091211, 0x00091111, 0x00091211, 0x00091211, 0x00091310, 0x00091310, 0x00091310, 0x0008120f, 0x0008120f, 0x0009130e, 0x0008120c, 0x0008110c, 0x0008110c, 0x0009110e, 0x0009110e, 0x0009110e, 0x0009110e, 0x0008130c, 0x0009140c, 0x0009140c, 0x0009140c, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009140e, 0x0009160e, 0x000a160e, 0x000b160e, 0x000b1610, 0x000c1511, 0x000c1610, 0x000c1610, 0x000c160f, 0x000d150f, 0x000f1710, 0x000f1811, 0x00111913, 0x00141815, 0x00151a14, 0x00141914, 0x00151a13, 0x00161a14, 0x00161a15, 0x00171c17, 0x00181c17, 0x00171c16, 0x00171c14, 0x00171c14, 0x00171c13, 0x00171c14, 0x00171c17, 0x00171c17, 0x00171c17, 0x00151a14, 0x00161b15, 0x00141a14, 0x00131914, 0x00101812, 0x00101610, 0x00101710, 0x000e1610, 0x000e1610, 0x000c1610, 0x000b150e, 0x000a140d, 0x0008120c, 0x0009110c, 0x0009110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110b, 0x0005110b, 0x0006120c, 0x0004100a, 0x0004100a, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00141809, 0x00191c09, 0x00202309, 0x00202309, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003e400d, 0x0043440e, 0x0048490e, 0x004c4d0f, 0x00505010, 0x00545510, 0x00585911, 0x00756a13, 0x00cca418, 0x00c7a218, 0x00716c14, 0x00656614, 0x00686814, 0x00696914, 0x006a6a14, 0x006b6b14, 0x006b6b14, 0x006b6b14, 0x006b6b14, 0x006b6b14, 0x006a6a14, 0x006a6a14, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00696914, 0x00686814, 0x00686814, 0x00686814, 0x00656614, 0x00907e15, 0x00c8a418, 0x00cba418, 0x009c8415, 0x005c5c12, 0x00585810, 0x00545511, 0x00515110, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00081009, 0x00060e08, 0x00070f08, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x0005100a, 0x00050f0a, 0x00040d08, 0x00040d08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060e06, 0x00071007, 0x00081108, 0x00081108, 0x00081009, 0x00081009, 0x0009120c, 0x000a130c, 0x000c1410, 0x000d1510, 0x000d1510, 0x000e1610, 0x000f1610, 0x00101610, 0x00111812, 0x00141914, 0x00151a14, 0x00191a13, 0x00191a13, 0x001a1b14, 0x001a1b14, 0x001b1a14, 0x001b1a14, 0x001b1a14, 0x001b1a14, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x00181915, 0x00171813, 0x00161712, 0x00161710, 0x00141610, 0x00111610, 0x0011160f, 0x0010150e, 0x0010150e, 0x000d150f, 0x000d150f, 0x000c140e, 0x000c140d, 0x0009140c, 0x0009140c, 0x0009140c, 0x0009140c, 0x0009120a, 0x00081108, 0x00081108, 0x00081108, 0x0007110a, 0x0006120a, 0x0007120b, 0x0008130c, 0x0008130c, 0x000a150d, 0x000d1510, 0x000f1510, 0x00111613, 0x00141510, 0x001c1711, 0x00201810, 0x00261c0e, 0x0031200c, 0x00462a08, 0x007c571b, 0x00a97e2c, 0x00be8c28, 0x00c08e24, 0x00c09023, 0x00bd8e1d, 0x00c29422, 0x00c39523, 0x00c29423, 0x00c19421, 0x00c0931b, 0x00bd9018, 0x00bc8e22, 0x00b08223, 0x007c5003, 0x00583400, 0x004a2e00, 0x003c2707, 0x00322109, 0x00311f0a, 0x0030200a, 0x002d1f08, 0x002b1f08, 0x0024210c, 0x00222009, 0x00201d08, 0x00201d08, 0x00221e09, 0x001e1c09, 0x001a1b06, 0x00141803, 0x00151909, 0x000f1208, 0x000c0f04, 0x000c1007, 0x000c0f08, 0x000e0e07, 0x00100e06, 0x00141108, 0x00171004, 0x002c2314, 0x00382c1c, 0x0040301e, 0x003f2c17, 0x004f3720, 0x004d321b, 0x0055371d, 0x00553418, 0x005c3416, 0x005b3213, 0x00613916, 0x00603914, 0x005f3810, 0x00573009, 0x005c3410, 0x00572f0b, 0x005c3312, 0x00582b10, 0x0054280f, 0x0050270c, 0x004c240d, 0x0049240d, 0x004a250c, 0x00522b11, 0x00522b0e, 0x004f280a, 0x00572f10, 0x0053280c, 0x00572c0f, 0x00582e10, 0x00592e11, 0x00572e0e, 0x0059300f, 0x00572c0c, 0x00582e0c, 0x00562c0c, 0x00512808, 0x00492104, 0x00472008, 0x0048250f, 0x003d1e0a, 0x00311705, 0x00201004, 0x00170c04, 0x00130c07, 0x0013110b, 0x000f0e08, 0x000f0e08, 0x000f0e0b, 0x00110d0d, 0x0010100c, 0x00121109, 0x00141408, 0x00141407, 0x00161408, 0x00161408, 0x00151407, 0x0019170a, 0x001c190a, 0x001d1807, 0x001e1707, 0x00201608, 0x0024180a, 0x00281b0c, 0x002b1c0a, 0x00312109, 0x00352308, 0x00442c0c, 0x0055370a, 0x008c6528, 0x00b98c40, 0x00be862c, 0x00af7a1d, 0x008d6016, 0x005d3504, 0x00351a00, 0x00221200, 0x001a1103, 0x00131206, 0x00101108, 0x00110f05, 0x000e0c02, 0x000e0c02, 0x00101007, 0x0011130b, 0x000e110b, 0x000e120d, 0x000c1310, 0x00081110, 0x00071210, 0x00071210, 0x00071210, 0x00081110, 0x00081110, 0x00081110, 0x00081110, 0x0007100f, 0x0007100f, 0x00081110, 0x00081110, 0x00081210, 0x0008120f, 0x0008120e, 0x0007110d, 0x0007110d, 0x0008120d, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110b, 0x0008120c, 0x0009140d, 0x0009140d, 0x0008140e, 0x0008140e, 0x0007130d, 0x0007130d, 0x0008140d, 0x0008140d, 0x0008140d, 0x0008150e, 0x0008140f, 0x000a1410, 0x000b1410, 0x000c1610, 0x000c160f, 0x000d150f, 0x000d150f, 0x000d140e, 0x000e1610, 0x00121613, 0x00141813, 0x00121712, 0x00141811, 0x00141914, 0x00141914, 0x00151a14, 0x00161b16, 0x00171c15, 0x00171c14, 0x00171c13, 0x00161c12, 0x00161c13, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161b15, 0x00161c16, 0x00161c15, 0x00151b15, 0x00141914, 0x00131712, 0x00111813, 0x000f1610, 0x000f1610, 0x000d1710, 0x000c1710, 0x000c160f, 0x000a140d, 0x0009120c, 0x0008100c, 0x0008100b, 0x0008100c, 0x0007100c, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110b, 0x0005110b, 0x0006120c, 0x0004100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0020230a, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003e400c, 0x0043440e, 0x0048490f, 0x004c4d10, 0x00515110, 0x00555610, 0x00595a11, 0x00756a13, 0x00cca418, 0x00c7a218, 0x00726d14, 0x00686814, 0x00696914, 0x006b6b14, 0x006c6c14, 0x006c6c15, 0x006c6c15, 0x006c6c15, 0x006c6c15, 0x006c6c15, 0x006b6b14, 0x006a6a14, 0x006a6a14, 0x00686814, 0x00686814, 0x00686814, 0x00666713, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x006a6a14, 0x00696914, 0x00696914, 0x00686814, 0x00686814, 0x00938115, 0x00c6a219, 0x00cca518, 0x00b09217, 0x00646212, 0x005b5b11, 0x00585910, 0x00545510, 0x00515110, 0x004c4d10, 0x00484910, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040c08, 0x00040c08, 0x00040c08, 0x00040c08, 0x00050d09, 0x00050d08, 0x00040c08, 0x00040c08, 0x00080f0a, 0x00070f08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00081009, 0x0008110a, 0x00081009, 0x00060e08, 0x00040f08, 0x00081009, 0x000c120c, 0x000c130d, 0x000c130d, 0x000f150f, 0x00101610, 0x0010170f, 0x00121911, 0x00141912, 0x00151812, 0x00171910, 0x00181b12, 0x001a1b14, 0x001a1b14, 0x001b1c14, 0x001b1c14, 0x001a1b14, 0x001a1b14, 0x001b1c14, 0x001b1c14, 0x00181c15, 0x00181c15, 0x00171a14, 0x00161913, 0x00141813, 0x00141714, 0x00141714, 0x00121510, 0x00101510, 0x00101510, 0x0010140f, 0x0010140f, 0x000f140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000c130d, 0x0008120b, 0x0008120b, 0x0007110a, 0x0007110a, 0x00061009, 0x0007110a, 0x0007110a, 0x0007110a, 0x00061008, 0x00070f08, 0x00081009, 0x0009120b, 0x000b140e, 0x000c140f, 0x000c1210, 0x000d1211, 0x00101412, 0x00141510, 0x001b1610, 0x00201810, 0x00271c0c, 0x00351f0a, 0x004c2d0f, 0x00856021, 0x00c49936, 0x00c9a124, 0x00cca622, 0x00cca81d, 0x00cca819, 0x00cba817, 0x00cba817, 0x00cba918, 0x00c9a818, 0x00c8a914, 0x00c9a90e, 0x00cba615, 0x00c3981d, 0x00906208, 0x00633b01, 0x00523108, 0x00442c0c, 0x0038260f, 0x0034230b, 0x0034230b, 0x0033230b, 0x00302108, 0x002a2108, 0x00272008, 0x00241d08, 0x00241d09, 0x00241f0b, 0x00221e09, 0x001a1a08, 0x00151a08, 0x00141809, 0x000e1106, 0x000b0e04, 0x000c0f07, 0x000c0f08, 0x000d0f07, 0x00100f08, 0x00100f08, 0x00131007, 0x00151004, 0x00211a0c, 0x00322817, 0x003b2c18, 0x003f2c18, 0x0049311c, 0x0051341d, 0x00543419, 0x00563214, 0x00583312, 0x00583410, 0x0056310b, 0x0059340c, 0x0059340e, 0x0058320f, 0x0055300d, 0x00532c0c, 0x0052280c, 0x004d2408, 0x004f260c, 0x00502a10, 0x0048240b, 0x00442006, 0x00512c12, 0x00512c0f, 0x004c2508, 0x0050290a, 0x00542e0f, 0x00522a0c, 0x00532b0f, 0x00572f10, 0x00512c0b, 0x00532d0a, 0x00542d09, 0x00502907, 0x004e2708, 0x004b240c, 0x0046220b, 0x003e1e08, 0x00341c08, 0x00271703, 0x001a1000, 0x00171009, 0x00140e09, 0x00100d07, 0x00100e08, 0x00100e08, 0x00100d07, 0x000f0e06, 0x00101008, 0x00131009, 0x00131008, 0x00161309, 0x0018140b, 0x0018140a, 0x00181409, 0x001b170b, 0x00201c0c, 0x00201c0a, 0x00201807, 0x00221708, 0x00251809, 0x00281b09, 0x002d1f05, 0x002f2008, 0x0033240b, 0x003b2a0d, 0x00432b0a, 0x0055390c, 0x00805c20, 0x00a77b33, 0x00a77420, 0x0084540c, 0x00623604, 0x003d1800, 0x00291103, 0x00201004, 0x00181107, 0x00121208, 0x00111108, 0x000f0e05, 0x000b0b01, 0x00121108, 0x00101008, 0x00101109, 0x000e110b, 0x000d110c, 0x000c120d, 0x0009110e, 0x0009120f, 0x00081010, 0x00061110, 0x00091211, 0x00081110, 0x0007100f, 0x0007100f, 0x00091310, 0x0007110d, 0x0006100c, 0x0006100c, 0x0007100d, 0x0008120e, 0x0008110e, 0x0006110d, 0x0007110d, 0x0007110c, 0x00040e09, 0x00040f09, 0x0005100a, 0x0008120c, 0x0006100b, 0x0008110c, 0x0009130e, 0x0008120e, 0x0008120f, 0x0007110d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0008120e, 0x0008120e, 0x0008120f, 0x0007130f, 0x0007130f, 0x0007130f, 0x0007130f, 0x0008120f, 0x000b1411, 0x000a1410, 0x000a1410, 0x000b1510, 0x000c1610, 0x000c1610, 0x000c1610, 0x000e1410, 0x00101512, 0x00111611, 0x00111610, 0x00121911, 0x00131a12, 0x00131a12, 0x00131a12, 0x00141a13, 0x00151a13, 0x00161b14, 0x00161b14, 0x00161c15, 0x00181e18, 0x00181e18, 0x00171d16, 0x00181d15, 0x00191c16, 0x00181c15, 0x00181b14, 0x00161913, 0x00141914, 0x00141813, 0x00111611, 0x0010140f, 0x000f1410, 0x000e1610, 0x000c160f, 0x000a140c, 0x000a130d, 0x000b120e, 0x0009110d, 0x0009110d, 0x0008120c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00040e09, 0x0005100a, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250c, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x003b3c0d, 0x0040400d, 0x0044450e, 0x00494a0f, 0x004d4e0f, 0x00525310, 0x00565711, 0x005c5c12, 0x00776c14, 0x00cca518, 0x00c7a218, 0x00736e14, 0x00696914, 0x006b6b14, 0x006c6c15, 0x006d6d15, 0x006d6d15, 0x006e6e15, 0x006d6d15, 0x006d6d15, 0x006c6c15, 0x006c6c15, 0x006b6b14, 0x006b6b14, 0x00696914, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x006a6a14, 0x006a6a14, 0x006a6a14, 0x00686814, 0x00757014, 0x00a58d17, 0x00c8a419, 0x00cca619, 0x00b79817, 0x006f6813, 0x005e5f12, 0x005c5c12, 0x00585910, 0x00555610, 0x00515110, 0x004c4d10, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040d08, 0x00040d08, 0x00040d08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d07, 0x00070f08, 0x00070f08, 0x00070f0a, 0x00050d09, 0x00040d07, 0x00040d05, 0x00040c08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00050d09, 0x00040c08, 0x0008100a, 0x00070f08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00070f08, 0x00081009, 0x00070f08, 0x00081009, 0x00051008, 0x0008110b, 0x000d140e, 0x000d140e, 0x000d140e, 0x00101610, 0x00101710, 0x00111810, 0x00131810, 0x00151812, 0x00171812, 0x00191b12, 0x001b1c13, 0x001a1b14, 0x001a1b14, 0x001b1c14, 0x001b1c14, 0x001a1b15, 0x001a1b15, 0x001b1c16, 0x001b1c16, 0x00181c15, 0x00171c15, 0x00151a13, 0x00141811, 0x00111613, 0x00111613, 0x00121714, 0x00101512, 0x00101510, 0x000f150f, 0x000f150f, 0x000d140e, 0x000d140e, 0x000c120c, 0x000c120c, 0x000c120c, 0x000a110c, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00040f08, 0x00051008, 0x00051008, 0x00051008, 0x00070f08, 0x00070f08, 0x00081009, 0x0009120b, 0x000a130c, 0x000a120e, 0x000b1110, 0x000d1211, 0x00101412, 0x00141510, 0x001b1610, 0x00201810, 0x00271c0c, 0x0035200b, 0x004c2c0e, 0x00876123, 0x00c39c33, 0x00cbab24, 0x00ccb020, 0x00ccb219, 0x00ccb414, 0x00ccb412, 0x00ccb412, 0x00ccb411, 0x00cbb410, 0x00cbb40e, 0x00cbb30b, 0x00ccb011, 0x00c09b18, 0x008a6102, 0x00684006, 0x0058360c, 0x0048300e, 0x003c2b10, 0x0037250a, 0x0037250a, 0x0038260b, 0x00342408, 0x00302407, 0x002d2207, 0x002b1f08, 0x002a1f09, 0x00281f09, 0x00241d09, 0x0020200d, 0x00191c0b, 0x00151a09, 0x00111508, 0x000c1004, 0x000b0e05, 0x000c0f07, 0x000d0f07, 0x000f1008, 0x000f1008, 0x00111109, 0x00141006, 0x00151105, 0x001b1404, 0x00261d0c, 0x00362915, 0x00422f1c, 0x004f3520, 0x0051341c, 0x00533417, 0x00543414, 0x00543110, 0x00502d08, 0x0058350f, 0x0056330d, 0x00502c0a, 0x004c2808, 0x004c280a, 0x004d270a, 0x004a2306, 0x00482406, 0x004d280c, 0x00482408, 0x004a260a, 0x004f2c10, 0x00502c0e, 0x004b2508, 0x004d2809, 0x004f2b0b, 0x004c2808, 0x004c2808, 0x00502c0c, 0x004c2a06, 0x004e2d08, 0x004d2a04, 0x00492602, 0x00472505, 0x00432409, 0x0040220c, 0x00301804, 0x00231000, 0x001b1000, 0x00160f02, 0x00131009, 0x00121009, 0x00110f08, 0x00100d07, 0x000f0f05, 0x000f0f05, 0x000e0e04, 0x00111008, 0x00131107, 0x00131107, 0x0018140b, 0x001a160c, 0x001b150d, 0x001c160d, 0x001e180c, 0x00221c0c, 0x00241c0c, 0x00251b09, 0x00271b08, 0x002b1c08, 0x002e1f0a, 0x00302209, 0x0032240a, 0x0038290f, 0x0038290d, 0x00392409, 0x00412704, 0x00543308, 0x00633d0b, 0x005d3504, 0x00482200, 0x00381800, 0x002c1104, 0x0025120d, 0x001d100d, 0x0018100b, 0x00141108, 0x00121107, 0x00111007, 0x00101007, 0x00131209, 0x000f0f05, 0x000d0f07, 0x000c1009, 0x000c100c, 0x000c120c, 0x0008100a, 0x000b1310, 0x00091310, 0x00081311, 0x00091310, 0x0008120f, 0x0007110d, 0x0007110d, 0x00091310, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110d, 0x0006110d, 0x0006100b, 0x0005100a, 0x0006100b, 0x0006100b, 0x0007110c, 0x0006100b, 0x0005100a, 0x0008110c, 0x0007100d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0007110e, 0x0007130f, 0x0007130f, 0x0007130f, 0x0007130f, 0x0008110d, 0x000a1410, 0x00091310, 0x00091310, 0x0009130e, 0x000a140f, 0x000b1510, 0x000b1410, 0x000c130f, 0x000f1410, 0x00101610, 0x0010160e, 0x00121911, 0x00121911, 0x00111810, 0x00111810, 0x00131812, 0x00141813, 0x00141913, 0x00141913, 0x00151b15, 0x00161c17, 0x00161c16, 0x00171d16, 0x00181d14, 0x00191c16, 0x00181c15, 0x001a1d17, 0x00181b14, 0x00161b16, 0x00151a14, 0x00141813, 0x00111611, 0x00101411, 0x0010150f, 0x000e150f, 0x000c150d, 0x000c130e, 0x000b120e, 0x0009110d, 0x0009110d, 0x0008120c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008110c, 0x0008110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0b, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x0040400e, 0x0045470e, 0x004b4c0f, 0x004f5010, 0x00535410, 0x00585811, 0x005c5d12, 0x00786c14, 0x00cca518, 0x00c7a318, 0x00746f14, 0x006a6a14, 0x006c6c14, 0x006d6d15, 0x006e6e15, 0x006f6f14, 0x006f6f14, 0x006f6f14, 0x006e6e15, 0x006d6d15, 0x006c6c15, 0x006c6c14, 0x006b6b14, 0x006a6a14, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00656614, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00656614, 0x00656614, 0x00666713, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x006a6a14, 0x006c6b14, 0x00716e14, 0x007d7414, 0x009f8a16, 0x00c09e19, 0x00cca71a, 0x00cba51a, 0x00b49618, 0x00716c14, 0x00626313, 0x005e5f13, 0x005c5c11, 0x00585911, 0x00555610, 0x00515110, 0x004d4e0f, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x000f130b, 0x000f130f, 0x000f130f, 0x0008100b, 0x00040c08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040f09, 0x0005100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00070f08, 0x00081009, 0x00060e08, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d05, 0x00040c08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00060e08, 0x0008110b, 0x0008110a, 0x0008110b, 0x00061009, 0x000a130c, 0x000f150f, 0x000f150f, 0x00101510, 0x00121712, 0x00141812, 0x00141810, 0x00161912, 0x00181913, 0x00181913, 0x001a1a12, 0x001c1c14, 0x001b1c14, 0x001b1c14, 0x001a1b14, 0x001a1b14, 0x001b1c16, 0x001b1c16, 0x001a1b15, 0x001a1b15, 0x00171913, 0x00151a13, 0x00141811, 0x00111610, 0x00101411, 0x00101411, 0x00121613, 0x00101512, 0x000e140f, 0x000d140e, 0x000d140e, 0x000c120c, 0x000b110c, 0x0009120c, 0x00081009, 0x0008110a, 0x00070f08, 0x00040f08, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040e07, 0x00040f08, 0x00040f08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x0008110a, 0x0009120c, 0x000a110d, 0x000d1210, 0x00101410, 0x0015140e, 0x001c1510, 0x0020170f, 0x00271b0a, 0x00311f08, 0x0044280c, 0x006f4c14, 0x00aa8628, 0x00c5a524, 0x00cbae20, 0x00ccb017, 0x00cbb310, 0x00ccb410, 0x00ccb410, 0x00cbb50c, 0x00cab408, 0x00cbb508, 0x00cbb508, 0x00ccb112, 0x00b99513, 0x00845b00, 0x00683e04, 0x005a380c, 0x004a310c, 0x00402e0c, 0x003b2a09, 0x003b2a09, 0x003c2b0a, 0x00392808, 0x00372808, 0x00342508, 0x00332307, 0x0033220a, 0x002f220b, 0x00261e08, 0x00201e08, 0x001e1f0b, 0x001b1f0c, 0x00141807, 0x000c1002, 0x000b0d04, 0x000a0d04, 0x000c0e06, 0x000d0f07, 0x000d0f07, 0x00101009, 0x00101008, 0x00141208, 0x00161105, 0x00181203, 0x00221908, 0x00372817, 0x00483421, 0x004c331c, 0x00503218, 0x00543417, 0x00583718, 0x00533310, 0x0050300c, 0x004c2c09, 0x004b2809, 0x004a270b, 0x00482509, 0x004a260a, 0x00492608, 0x004a2709, 0x004c280a, 0x004e290b, 0x004e290c, 0x004d280a, 0x004c2808, 0x00482606, 0x00482505, 0x004b2908, 0x004e2d0b, 0x00502f0c, 0x004c2c08, 0x004b2b08, 0x004d2f0a, 0x0051310f, 0x00492a0b, 0x00402408, 0x003d230c, 0x002d1704, 0x00211000, 0x001c0f04, 0x00191005, 0x00151108, 0x0013120b, 0x00101009, 0x00101008, 0x000e0e06, 0x000e0d04, 0x000e0d04, 0x00100e06, 0x00121207, 0x00161409, 0x00171408, 0x001a160b, 0x001b150b, 0x001c150b, 0x001f170b, 0x00251c0d, 0x0028200d, 0x00281e0a, 0x002c200a, 0x0030220b, 0x00312109, 0x00312109, 0x00302108, 0x00302308, 0x00302206, 0x002d1e04, 0x002d1a03, 0x00321902, 0x00381a01, 0x00381600, 0x00331804, 0x002c1605, 0x00241106, 0x001d0e08, 0x001a0e0c, 0x001a100d, 0x0018100b, 0x00161008, 0x00141108, 0x00131108, 0x00121008, 0x00111108, 0x000e0e05, 0x000d0f07, 0x000c1008, 0x000a0f08, 0x000c120b, 0x000c140d, 0x0008110b, 0x0009130f, 0x00081410, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x00091310, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0004100c, 0x0005100c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100c, 0x0006100c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0007100d, 0x00050f0c, 0x0005100c, 0x0006110d, 0x0006110d, 0x0006110d, 0x0006110d, 0x0007110d, 0x0007110d, 0x00091310, 0x00091310, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x000b130e, 0x000c1410, 0x000d150f, 0x000d160d, 0x00101710, 0x00111810, 0x00111810, 0x00101710, 0x00121711, 0x00131712, 0x00141813, 0x00141914, 0x00141a14, 0x00151c15, 0x00151c15, 0x00161c15, 0x00171c14, 0x00181c15, 0x00181c15, 0x001a1d17, 0x00181c15, 0x00171c17, 0x00161b15, 0x00151a14, 0x00141813, 0x00141614, 0x00111611, 0x00101610, 0x000e160e, 0x000d1410, 0x000c1410, 0x000c140f, 0x000a120e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120c, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120d, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f1612, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x0014180a, 0x001d2009, 0x001d2008, 0x0024250b, 0x00292b0b, 0x002d2f0b, 0x0030310c, 0x0036370c, 0x003b3c0d, 0x0040400d, 0x0045470e, 0x004b4c0f, 0x00505010, 0x00545510, 0x00585911, 0x005c5d12, 0x00786c14, 0x00cca518, 0x00caa419, 0x00b19518, 0x00af9418, 0x00b09418, 0x00b09418, 0x00b09518, 0x00b09518, 0x00b09518, 0x00b09518, 0x00b09518, 0x00b09518, 0x00b09418, 0x00b09418, 0x00af9418, 0x00af9318, 0x00af9318, 0x00af9318, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00ae9117, 0x00ae9117, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00ae9217, 0x00af9218, 0x00af9318, 0x00af9318, 0x00af9418, 0x00b39618, 0x00bc9c18, 0x00c8a519, 0x00cca71a, 0x00cca71a, 0x00c8a419, 0x00a48c17, 0x006d6a14, 0x00646514, 0x00626314, 0x00606013, 0x005c5d11, 0x00595a11, 0x00555610, 0x00525310, 0x004d4e0f, 0x0048490f, 0x0044450e, 0x0040400e, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x0006100b, 0x00040d08, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e08, 0x00081009, 0x00081009, 0x00060e08, 0x00060e09, 0x00060e09, 0x00040d07, 0x00040d06, 0x00040c08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00040c08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x00081009, 0x00060e08, 0x0009120b, 0x0008110a, 0x0008110b, 0x0009130c, 0x000c140d, 0x00101711, 0x00101711, 0x00101510, 0x00141612, 0x00141812, 0x00151811, 0x00181a12, 0x00181a14, 0x00191a13, 0x001a1a12, 0x001d1c14, 0x001c1c14, 0x001b1c14, 0x001a1b14, 0x001a1b14, 0x001b1c16, 0x001b1c16, 0x001a1b15, 0x001a1b15, 0x00161913, 0x00151a13, 0x00141811, 0x00111610, 0x00101411, 0x00101411, 0x00101411, 0x000f1310, 0x000d120e, 0x000a130c, 0x000a130c, 0x0008110a, 0x0008110a, 0x00061009, 0x00040f08, 0x00051008, 0x00040e07, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x00081109, 0x0009120a, 0x000a120c, 0x000d130f, 0x0012140f, 0x0015140e, 0x001c160f, 0x0020160c, 0x00261b08, 0x002d1c04, 0x003c2109, 0x00542f06, 0x00734d04, 0x0099710d, 0x00b68f1d, 0x00be981a, 0x00c5a318, 0x00caaa14, 0x00ccb013, 0x00ccb10e, 0x00ccb208, 0x00ccb208, 0x00ccb00b, 0x00caaa12, 0x00ac8208, 0x00805100, 0x00683e04, 0x0058380b, 0x004a3308, 0x00403008, 0x003f2f09, 0x003f2f0a, 0x00402f0a, 0x003e2c08, 0x003c2b07, 0x003b2807, 0x00382508, 0x00382409, 0x0034250c, 0x002b2109, 0x00241e08, 0x00201f09, 0x001c1f0b, 0x00161b08, 0x00111405, 0x000c0f03, 0x000c0e04, 0x000c0e06, 0x000d0f07, 0x000d0f07, 0x000e1109, 0x000f1009, 0x0012120a, 0x00141208, 0x00151306, 0x00171402, 0x00181100, 0x002d210e, 0x0044301c, 0x004f341c, 0x00523418, 0x00503415, 0x004f3210, 0x004f310e, 0x004b2c0b, 0x0048280a, 0x004c2a0d, 0x004b290c, 0x00472507, 0x00482707, 0x004c2a0a, 0x004b2a09, 0x004b2808, 0x004a2808, 0x00492706, 0x00492805, 0x00472605, 0x00462605, 0x00492b09, 0x004d2f0b, 0x0050320c, 0x004d3009, 0x004b2e0b, 0x004d300e, 0x004b2f10, 0x0041280e, 0x00371e0c, 0x00281102, 0x001e0d00, 0x001a1004, 0x00181106, 0x00181108, 0x0016140b, 0x0012140c, 0x0010120a, 0x00101009, 0x000d0f07, 0x000c0e04, 0x000e0d04, 0x00100e06, 0x00121207, 0x00161406, 0x00161406, 0x00181609, 0x00181808, 0x00201705, 0x00251a05, 0x002c2008, 0x002e2408, 0x002f2207, 0x00332308, 0x0036240b, 0x00352108, 0x00332107, 0x00302005, 0x002f2105, 0x002f2105, 0x002d1e04, 0x002c1b03, 0x002f1905, 0x00301808, 0x002e1408, 0x00271809, 0x00231707, 0x00201609, 0x001c1408, 0x00181105, 0x00171106, 0x00171008, 0x00171009, 0x00141008, 0x00131008, 0x00121008, 0x000f0f05, 0x000e0e04, 0x000c0d05, 0x000b0e05, 0x000a0f08, 0x000c120b, 0x000b130b, 0x0009120b, 0x0009130c, 0x0007120c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008120f, 0x0007100d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100c, 0x0005100c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100c, 0x0006100c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x00040f0c, 0x00050f0c, 0x0006100d, 0x0006110d, 0x0006110d, 0x0005100c, 0x0005100c, 0x0007110d, 0x0007110d, 0x00091310, 0x00091310, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009130e, 0x0009110c, 0x000a120e, 0x000c140e, 0x000d160d, 0x000f150d, 0x0010160e, 0x0010170f, 0x00101710, 0x00121711, 0x00141813, 0x00141813, 0x00141813, 0x00141a14, 0x00151c15, 0x00151c15, 0x00161c15, 0x00171c14, 0x00181c15, 0x00181c15, 0x001a1d17, 0x00181c15, 0x00171c17, 0x00161b15, 0x00151a14, 0x00151a14, 0x00161815, 0x00141813, 0x00131712, 0x00101710, 0x00101510, 0x000e1510, 0x000d1510, 0x000b130f, 0x0009130e, 0x0008120d, 0x0008120d, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0008120c, 0x0005100a, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0041420d, 0x0045470e, 0x004b4c0f, 0x00505010, 0x00545511, 0x00585911, 0x005d5e12, 0x006d6813, 0x00bd9c18, 0x00cca61a, 0x00cca71a, 0x00cca71a, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca71a, 0x00cca71a, 0x00cca61a, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca519, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca619, 0x00cca61a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cba61a, 0x00c9a41a, 0x00b59818, 0x00887a16, 0x00686814, 0x00686814, 0x00646514, 0x00626313, 0x00606013, 0x005c5d11, 0x00595a11, 0x00555611, 0x00525310, 0x004d4e0f, 0x00494a10, 0x0045470e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00050f0a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x0005100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070e0c, 0x00070f0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x00081009, 0x00081009, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050d08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00070f08, 0x00050e08, 0x00091009, 0x0009120c, 0x000b130c, 0x000b150e, 0x000c140e, 0x000c140e, 0x00101610, 0x00131813, 0x00161814, 0x00181814, 0x00181814, 0x00191a14, 0x001b1b14, 0x001d1b14, 0x001c1b14, 0x001b1a14, 0x001e1d16, 0x001e1e18, 0x001c1b16, 0x001a1b15, 0x001a1b15, 0x00181c15, 0x00181c15, 0x00171812, 0x00171812, 0x00111711, 0x00111711, 0x00101610, 0x000e140e, 0x000f140e, 0x000f140e, 0x000f140e, 0x000d110d, 0x000b110c, 0x0009120a, 0x00081108, 0x00081008, 0x00081009, 0x0006100a, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00071008, 0x00071007, 0x00071007, 0x00081008, 0x0008110a, 0x000a110b, 0x000d130d, 0x0012140f, 0x0015140e, 0x001b150e, 0x001e140b, 0x00241809, 0x002a1a08, 0x00371d09, 0x00442203, 0x00552e00, 0x00683d00, 0x00764a01, 0x00845801, 0x00946806, 0x00aa800b, 0x00b8910f, 0x00c39e12, 0x00c9a510, 0x00cba814, 0x00cca81a, 0x00bd9410, 0x00946800, 0x00784c02, 0x0064400c, 0x00573a0b, 0x004a3408, 0x00433309, 0x00413209, 0x00413209, 0x00413209, 0x00413208, 0x00423007, 0x003d2d06, 0x003b2b06, 0x00392b08, 0x00352808, 0x002d2406, 0x00261f05, 0x00211e07, 0x00201e0a, 0x001e1d0c, 0x00181709, 0x000c1002, 0x000c0f04, 0x000d0f05, 0x000d0f05, 0x000c0e05, 0x000f1008, 0x000d1008, 0x00101008, 0x0016140b, 0x0017140c, 0x0018140b, 0x00191509, 0x00181002, 0x00241807, 0x00382610, 0x00432f14, 0x00442f13, 0x00472f11, 0x00482d0e, 0x004c2c0e, 0x00482809, 0x004c280b, 0x004d2b0c, 0x004b2b0c, 0x004a2a0b, 0x00462707, 0x00472808, 0x00472808, 0x00482809, 0x00482809, 0x00482809, 0x00482c0c, 0x00472c0c, 0x00482c0c, 0x004b2f0e, 0x004b300c, 0x00503414, 0x00493012, 0x0044290f, 0x003b230c, 0x002e1807, 0x00241204, 0x00201004, 0x001c1106, 0x00181105, 0x00171107, 0x00171008, 0x0014130a, 0x00131209, 0x00101007, 0x00101008, 0x000e0f08, 0x000d0f07, 0x000f0f05, 0x00131107, 0x00161409, 0x00181408, 0x00181407, 0x001a1507, 0x001d1707, 0x00261908, 0x002a1b08, 0x0030200a, 0x00403014, 0x003d2c0c, 0x003d2b09, 0x003e2b05, 0x00402a07, 0x00402a0c, 0x00392307, 0x00352006, 0x00321f06, 0x00301e04, 0x002e1c04, 0x002c1a06, 0x002b1908, 0x00271606, 0x00241705, 0x00221604, 0x00201605, 0x001b1302, 0x00181304, 0x00181106, 0x00181109, 0x0017100a, 0x0016100a, 0x00141109, 0x00121008, 0x00100e05, 0x00100f06, 0x000e0f05, 0x000c0f06, 0x000c1007, 0x000c1108, 0x000a1008, 0x000a1008, 0x0009120c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x00060e0b, 0x0008100c, 0x0008120d, 0x0007110c, 0x0005100b, 0x0007100c, 0x0008100c, 0x0005100b, 0x0006100b, 0x0005110b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f0a, 0x0008110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0006110c, 0x0008100c, 0x00050d09, 0x00060f0a, 0x000a120e, 0x0009110d, 0x0008100c, 0x0009130e, 0x0005100b, 0x0008120c, 0x0007110a, 0x0009140c, 0x000a140b, 0x000c150c, 0x000d160d, 0x000f150d, 0x0010160e, 0x00101710, 0x00111812, 0x00131812, 0x00141914, 0x00141914, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161c12, 0x00171c14, 0x00171c14, 0x00171c14, 0x00171c14, 0x00171c17, 0x00171c17, 0x00171c17, 0x00171c17, 0x00161b15, 0x00151a14, 0x00141813, 0x00131712, 0x00101510, 0x000f150f, 0x000e140f, 0x000c140e, 0x000a130c, 0x0009120c, 0x0009120c, 0x0008110a, 0x00070f08, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x0007100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0038380c, 0x003b3c0c, 0x0041420d, 0x0047480f, 0x004c4d0f, 0x00505010, 0x00545511, 0x00595a12, 0x005d5e12, 0x00606013, 0x007d7314, 0x00b09418, 0x00b29618, 0x00b39718, 0x00b39818, 0x00b49819, 0x00b49819, 0x00b49819, 0x00b49819, 0x00b49819, 0x00b49819, 0x00b39819, 0x00b39718, 0x00b39618, 0x00b29618, 0x00b29618, 0x00b19518, 0x00b19518, 0x00b19418, 0x00b19317, 0x00b19317, 0x00b19317, 0x00b09317, 0x00b09317, 0x00b19317, 0x00b19317, 0x00b19317, 0x00b19417, 0x00b19518, 0x00b19518, 0x00b19518, 0x00b29618, 0x00b29618, 0x00b19518, 0x00ad9218, 0x009f8a17, 0x00837815, 0x006c6b14, 0x00696914, 0x00686814, 0x00666714, 0x00656614, 0x00626313, 0x00606013, 0x005c5d11, 0x00595a11, 0x00565711, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00030f09, 0x00040f09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00050e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x0006100a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070e0c, 0x00070f0a, 0x00060e09, 0x00060e08, 0x00060e08, 0x00070f08, 0x00081009, 0x00081009, 0x00081009, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x0008110a, 0x000a1009, 0x0009130c, 0x000b130c, 0x000b150e, 0x000d150f, 0x000d150f, 0x00101610, 0x00141813, 0x00181814, 0x00181814, 0x00181814, 0x00191b14, 0x001b1b14, 0x001c1c14, 0x001c1b14, 0x001c1b14, 0x001e1d16, 0x001d1e18, 0x001b1c16, 0x001a1b15, 0x001a1b15, 0x00181c15, 0x00181c15, 0x00161812, 0x00161812, 0x00111611, 0x00101711, 0x00101610, 0x000d140e, 0x000d130d, 0x000c130d, 0x000c120c, 0x000b100b, 0x0009110a, 0x00081108, 0x00081108, 0x00081008, 0x00081009, 0x0006100b, 0x00040d08, 0x00040e09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100a, 0x00081009, 0x00081008, 0x00081007, 0x0008110a, 0x0009120c, 0x000a120c, 0x000c120c, 0x0011140f, 0x0015140e, 0x001b150c, 0x001c1409, 0x00221708, 0x0028180a, 0x00311a08, 0x00391c01, 0x00442201, 0x00502c05, 0x00583204, 0x005e3700, 0x00684000, 0x00714800, 0x007b5200, 0x00886001, 0x00966d07, 0x00a2780c, 0x00ab8013, 0x00996e09, 0x007d5200, 0x006c4406, 0x005d3d0d, 0x0054390a, 0x004c3609, 0x0048350a, 0x0048360b, 0x0048360b, 0x0048350a, 0x00483509, 0x00463408, 0x00413106, 0x003c2f06, 0x003b2f08, 0x00372c08, 0x00302705, 0x00272003, 0x00241e05, 0x00221d0a, 0x00201c0c, 0x0018180a, 0x000f1104, 0x000d1004, 0x000f1007, 0x000d0f05, 0x000c0e04, 0x000d0f05, 0x000c1005, 0x00101008, 0x00141109, 0x0017130b, 0x0016140c, 0x0018140b, 0x001c140a, 0x001d1407, 0x00241906, 0x00271803, 0x0033210a, 0x00402a13, 0x00432c10, 0x00472c12, 0x00492c10, 0x0049280b, 0x0048280a, 0x0047280c, 0x0046280c, 0x0045270b, 0x0045280c, 0x0047280c, 0x0048290d, 0x0047280c, 0x0047280c, 0x00442a0d, 0x00442a0e, 0x00432a0d, 0x00442b0e, 0x003c2308, 0x003d240c, 0x00381e09, 0x00311705, 0x002b1404, 0x00241003, 0x00201004, 0x00201408, 0x001d1408, 0x001a1508, 0x00181308, 0x00171008, 0x00151109, 0x00131008, 0x00100e05, 0x00110f07, 0x00100f08, 0x000f0e07, 0x00100e05, 0x00131107, 0x00181408, 0x00191408, 0x001b1407, 0x001e1508, 0x00221809, 0x002a1c0c, 0x002d1d0c, 0x00382411, 0x004b3519, 0x0049300e, 0x004e3209, 0x00533706, 0x00563808, 0x0058390a, 0x004f3305, 0x00452b04, 0x003c2406, 0x00362006, 0x00301d06, 0x002c1c07, 0x00291b08, 0x00261808, 0x00241506, 0x00241508, 0x00221608, 0x001c1404, 0x00191204, 0x00181107, 0x00181109, 0x0017100b, 0x0016100b, 0x0014100a, 0x00121008, 0x00110f07, 0x00110f07, 0x000f0f05, 0x000d0f05, 0x000c1007, 0x000b1007, 0x000b1007, 0x000b1008, 0x000a110b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0009110e, 0x0008100c, 0x0008100b, 0x00071009, 0x00061009, 0x00051109, 0x0008100b, 0x0008100c, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x0006100b, 0x00040f09, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0007100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x0007110c, 0x0006120c, 0x0008120c, 0x0007110a, 0x0008130a, 0x00081308, 0x000a130b, 0x000c150c, 0x000f150d, 0x000d140c, 0x000e150e, 0x00111812, 0x00121812, 0x00141813, 0x00141914, 0x00141914, 0x00161b15, 0x00161b14, 0x00161c12, 0x00161c12, 0x00161c12, 0x00171c14, 0x00171c14, 0x00171c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00161b15, 0x00151a14, 0x00141813, 0x00131712, 0x00101510, 0x000f150f, 0x000d140e, 0x000e150f, 0x000b140d, 0x000a130c, 0x0009120c, 0x0009120c, 0x00081009, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x003b3c0c, 0x0041420d, 0x0047480f, 0x004c4d0f, 0x00505010, 0x00555610, 0x00595a12, 0x005d5e12, 0x00606013, 0x00646314, 0x00686614, 0x006c6914, 0x006d6b14, 0x00706d15, 0x00706e15, 0x00716f16, 0x00716f16, 0x00716f16, 0x00716f15, 0x00706e15, 0x006f6c15, 0x006f6d15, 0x006e6c15, 0x006c6b14, 0x006c6a14, 0x006a6814, 0x00686714, 0x00686614, 0x00656414, 0x00656413, 0x00646312, 0x00646313, 0x00646313, 0x00646312, 0x00646313, 0x00656414, 0x00666514, 0x00686714, 0x00696813, 0x006a6814, 0x006c6a14, 0x006c6a14, 0x00706d14, 0x00706d14, 0x006f6d14, 0x006f6d14, 0x006f6d14, 0x006e6c14, 0x006d6c14, 0x006c6914, 0x006a6814, 0x00686713, 0x00656413, 0x00626011, 0x005e5d11, 0x00565711, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0040400d, 0x003b3c0c, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00031008, 0x00041008, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00060f0a, 0x00070f0a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x00040e09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x00081009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00050e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00040d07, 0x00081009, 0x0009120c, 0x000a120c, 0x000b140d, 0x000c140e, 0x000c1710, 0x000e1610, 0x000f160f, 0x00111610, 0x00151812, 0x00181914, 0x00181a14, 0x00191a14, 0x001a1b14, 0x001c1c15, 0x001c1d16, 0x001c1d15, 0x001c1d15, 0x001c1c15, 0x001b1c16, 0x001a1b15, 0x00181a14, 0x00181a14, 0x00171913, 0x00161913, 0x00141811, 0x00141811, 0x00101510, 0x000f1510, 0x000e150f, 0x000c140d, 0x000b130c, 0x000a130c, 0x000a120c, 0x00081009, 0x00071008, 0x00081008, 0x00081008, 0x00071007, 0x00071009, 0x0005100a, 0x00040e09, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100a, 0x00081008, 0x0008110a, 0x0009120c, 0x000a120c, 0x000c110c, 0x0011130e, 0x0015140d, 0x001a140c, 0x001c1308, 0x001f1408, 0x00241608, 0x002a1809, 0x00311a05, 0x00371c04, 0x003b2108, 0x00402408, 0x00482907, 0x004f2e04, 0x00583405, 0x005a3602, 0x005f3900, 0x00633f00, 0x00694400, 0x00704700, 0x00694200, 0x005c3700, 0x00543201, 0x004e3406, 0x004b3204, 0x004b3104, 0x004c3509, 0x004c3508, 0x004a3407, 0x00483306, 0x00493407, 0x00463408, 0x0047370c, 0x0041340c, 0x0040340c, 0x003c310a, 0x00382b08, 0x002c2204, 0x00281f04, 0x0026200c, 0x00221f0c, 0x001b1b0a, 0x00141508, 0x00101104, 0x000d0f04, 0x000c0d04, 0x000c1005, 0x000c1007, 0x000d1008, 0x00101008, 0x00131008, 0x00141008, 0x0014130a, 0x0018140b, 0x001d160b, 0x0021180b, 0x0023180a, 0x00241505, 0x00241302, 0x00281403, 0x00291701, 0x0034210a, 0x003f2811, 0x0040280d, 0x0041270c, 0x0043280e, 0x0045280f, 0x00462810, 0x00462810, 0x0045280f, 0x0044260d, 0x0041240c, 0x003f2309, 0x003c250c, 0x003a2209, 0x00351d04, 0x00351d04, 0x00301802, 0x002c1401, 0x002c1303, 0x002c1408, 0x002a150a, 0x0027160c, 0x00211408, 0x001f1406, 0x001c1708, 0x001b1608, 0x00191408, 0x00171108, 0x0016120a, 0x00141008, 0x00100e05, 0x00110f07, 0x00100f08, 0x00100f08, 0x00110f06, 0x00151108, 0x00191408, 0x001b1408, 0x001c1307, 0x00201507, 0x00251808, 0x002b1d0b, 0x0032220e, 0x003d2910, 0x004c3410, 0x00593b0b, 0x006c480c, 0x007c5810, 0x00896616, 0x00947020, 0x007e5b0f, 0x00583600, 0x004c2e04, 0x0041280c, 0x00342008, 0x002f1d09, 0x002a1c09, 0x0029190b, 0x00241608, 0x00241409, 0x00211408, 0x001c1305, 0x00191105, 0x00181108, 0x0018110b, 0x0017100b, 0x0016100b, 0x0014100a, 0x00141008, 0x00121008, 0x00110f07, 0x000e0e04, 0x000d0f05, 0x000c1007, 0x000c1108, 0x000c1007, 0x000c0f08, 0x000a0f09, 0x0009100a, 0x0008100c, 0x0008100c, 0x0009110c, 0x000a120e, 0x0008110a, 0x0007100a, 0x00061009, 0x00051109, 0x0008100c, 0x0008100c, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x0006100b, 0x00040e09, 0x0005100a, 0x0007110c, 0x0006110c, 0x0005110b, 0x0006120c, 0x0006120c, 0x0006100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100b, 0x00070f0a, 0x0007110c, 0x0003100a, 0x00061009, 0x00051008, 0x00071208, 0x00081308, 0x0009120a, 0x000a120a, 0x000c130b, 0x000c140c, 0x000c130c, 0x00101610, 0x00111711, 0x00111611, 0x00121712, 0x00131812, 0x00141813, 0x00141912, 0x00151a11, 0x00161c12, 0x00161c12, 0x00171c13, 0x00171c14, 0x00181d16, 0x00181d16, 0x00171c15, 0x00171c15, 0x00171c16, 0x00151a14, 0x00141914, 0x00131712, 0x00111611, 0x00101510, 0x000f150f, 0x000e150f, 0x000c140e, 0x000b140d, 0x000a130c, 0x0009120c, 0x00081009, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x003b3c0c, 0x0041420d, 0x0047480f, 0x004c4d0f, 0x00505010, 0x00545511, 0x00595a12, 0x005d5e12, 0x00756c14, 0x00c29f18, 0x00c2a019, 0x00c2a119, 0x00c2a11a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x00c3a31a, 0x009e8918, 0x006a6a14, 0x00686814, 0x00686814, 0x00656614, 0x00646514, 0x00636413, 0x00616112, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x00616112, 0x00626312, 0x00636413, 0x00646414, 0x00646514, 0x00656614, 0x00686814, 0x006b6914, 0x00bc9c18, 0x00c4a119, 0x00c4a119, 0x00c4a119, 0x00c4a119, 0x00c4a119, 0x00c4a019, 0x00c4a019, 0x00c4a019, 0x00c39f18, 0x00c39e18, 0x00c39e18, 0x00aa8c14, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003b3c0c, 0x0036370c, 0x0032330c, 0x002d2f0a, 0x0026280a, 0x0026280c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00031008, 0x00041008, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x0006100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00050f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f08, 0x00070f08, 0x00070f08, 0x00081009, 0x00081009, 0x00081009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00040d07, 0x00040d07, 0x00040d07, 0x00060e08, 0x00081009, 0x0009120c, 0x000b130c, 0x000c140d, 0x000c160f, 0x000c1710, 0x000e1610, 0x00111810, 0x00141911, 0x00181b14, 0x001b1c16, 0x001b1c16, 0x001c1c17, 0x001c1d17, 0x001c1e16, 0x001c1e16, 0x001c1e16, 0x001c1c15, 0x001a1b14, 0x001b1a15, 0x001b1a15, 0x00181913, 0x00171812, 0x00151812, 0x00141710, 0x00141710, 0x00131610, 0x0010140f, 0x000f150f, 0x000c140e, 0x000b130c, 0x0009120c, 0x0008120c, 0x0008120c, 0x00071009, 0x00060f08, 0x00081008, 0x00081008, 0x00071007, 0x00070f08, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100d, 0x0008100c, 0x0008100c, 0x0008100a, 0x0008110a, 0x0009120c, 0x000a120c, 0x000c110c, 0x0011130e, 0x0014140c, 0x0019140b, 0x001c1208, 0x001e1407, 0x0021140a, 0x0026170c, 0x00291808, 0x002e1b08, 0x00331d0a, 0x00371e0a, 0x003c2008, 0x00412406, 0x00492a07, 0x004a2b05, 0x004c2d04, 0x00513105, 0x00543103, 0x00543004, 0x00543005, 0x00503008, 0x004a2f06, 0x00483306, 0x004f3809, 0x005b3d10, 0x005e4012, 0x005b3e10, 0x00573c0d, 0x004e3304, 0x004c3103, 0x00443104, 0x003f3004, 0x003d3004, 0x0040340b, 0x0041340d, 0x003c2f0b, 0x00332708, 0x002c2004, 0x00282008, 0x0024200c, 0x00201f0c, 0x00181909, 0x00101104, 0x000c0e03, 0x000b0c03, 0x000c1005, 0x000c1007, 0x000d1008, 0x00101007, 0x00131008, 0x00151109, 0x00141109, 0x0018140b, 0x001c150b, 0x0020180c, 0x0023190d, 0x0024190e, 0x0028180e, 0x0029190c, 0x00251708, 0x00231704, 0x00281905, 0x002a1801, 0x002c1700, 0x00361c05, 0x003c230c, 0x003e240e, 0x003f250e, 0x003c230c, 0x003b200a, 0x00381f08, 0x00351c05, 0x00301b04, 0x00311b04, 0x002f1902, 0x002d1800, 0x002c1600, 0x002d1804, 0x002c1807, 0x00291406, 0x002b180f, 0x0027180f, 0x00211608, 0x001f1506, 0x001d1707, 0x001a1508, 0x00181308, 0x00181108, 0x0016120a, 0x00141008, 0x00100e05, 0x00110f07, 0x00100f08, 0x00111009, 0x00140f07, 0x00181207, 0x00191408, 0x001b1406, 0x001f1406, 0x00221706, 0x00261808, 0x002d2008, 0x0037280a, 0x0046300c, 0x00583c0c, 0x008a6825, 0x00aa872d, 0x00b9982b, 0x00c6a62c, 0x00c8a62d, 0x00b48b21, 0x00785001, 0x00553400, 0x00462908, 0x0038240c, 0x00311f09, 0x002c1c09, 0x002a1b0a, 0x00261808, 0x00241507, 0x00201404, 0x001b1302, 0x00181204, 0x00181106, 0x0018110b, 0x0017100c, 0x0016100b, 0x00151009, 0x00141008, 0x00121008, 0x00111008, 0x00101007, 0x000f1007, 0x000d1008, 0x000c1108, 0x000c1007, 0x000c0f08, 0x000b0e09, 0x000a0f09, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100c, 0x0008110b, 0x0007110a, 0x00061009, 0x00051109, 0x0008110c, 0x0008100c, 0x0005100a, 0x0006100b, 0x0005110b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x0006100b, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0005110b, 0x0006120c, 0x0007130c, 0x0006100a, 0x00060e09, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00060e09, 0x0006100b, 0x00030f09, 0x00051008, 0x00051008, 0x00061108, 0x00061106, 0x00081008, 0x00081108, 0x000b110a, 0x000c120b, 0x000c120c, 0x00101610, 0x00101610, 0x00111611, 0x00111611, 0x00111611, 0x00111611, 0x00121710, 0x00141810, 0x00161c12, 0x00161c12, 0x00161c12, 0x00171c13, 0x00181d15, 0x00181d15, 0x00181d15, 0x00171c14, 0x00171c17, 0x00161b15, 0x00151a14, 0x00141813, 0x00131712, 0x00101711, 0x00101610, 0x000f1610, 0x000e1610, 0x000c140d, 0x000a130c, 0x0009120c, 0x00081009, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x003b3c0c, 0x0041420d, 0x0047480f, 0x004c4d0f, 0x00505010, 0x00545511, 0x00585911, 0x005d5e12, 0x00786d14, 0x00cca519, 0x00cca619, 0x00cca71a, 0x00cca71a, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00cca81b, 0x00a48c18, 0x00696914, 0x00686814, 0x00666714, 0x00646514, 0x00636413, 0x00616112, 0x00606013, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00606013, 0x00616112, 0x00636413, 0x00646414, 0x00646514, 0x00656614, 0x006b6814, 0x00c4a119, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca71a, 0x00cca61a, 0x00cca619, 0x00cca619, 0x00cca519, 0x00cca418, 0x00cca418, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003b3c0c, 0x0036370b, 0x0034350c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00041008, 0x00041008, 0x00051009, 0x00051009, 0x00051009, 0x00051009, 0x0006100a, 0x0006100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0b, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00070f09, 0x00070f09, 0x0008100a, 0x0008100a, 0x00081009, 0x00071008, 0x00071008, 0x00071008, 0x00070f08, 0x00070f08, 0x00060e08, 0x00050e08, 0x00050e08, 0x00050e08, 0x00070f08, 0x0008110b, 0x0009130c, 0x000c140d, 0x000c150e, 0x000c1710, 0x000c180f, 0x00101912, 0x00131a12, 0x00161b14, 0x00181c15, 0x001c1c17, 0x001d1c17, 0x001d1d17, 0x001d1d16, 0x001d1d16, 0x001d1d16, 0x001d1d16, 0x001c1c15, 0x001a1a13, 0x001b1a15, 0x001b1a15, 0x00181813, 0x00151811, 0x00141711, 0x00131611, 0x00111510, 0x0010140f, 0x000f150f, 0x000d140e, 0x000b130c, 0x000a120c, 0x0008110b, 0x0008110b, 0x0008110a, 0x00071009, 0x00060f08, 0x0006100a, 0x0007100a, 0x0006100a, 0x0006100a, 0x0005100a, 0x00051009, 0x00040f08, 0x00040f08, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0007100b, 0x0007100c, 0x0007100b, 0x0007100b, 0x0007100a, 0x0008110b, 0x000a120c, 0x000c110b, 0x0010130c, 0x0013140b, 0x0017140a, 0x00191408, 0x001b1408, 0x0020150c, 0x0023160c, 0x0026180c, 0x002a190b, 0x002d1a0a, 0x00301b09, 0x00341c07, 0x00371e04, 0x003d2207, 0x00402308, 0x0044270b, 0x00472b0c, 0x00482c0b, 0x00482c0b, 0x00482e0c, 0x004b320e, 0x004d3410, 0x0052370f, 0x00644612, 0x006e4c0c, 0x006b4805, 0x006c480c, 0x00644308, 0x005f3f08, 0x00543404, 0x00443000, 0x003c2c00, 0x00392b00, 0x003c2e07, 0x00433611, 0x003f300d, 0x00382a09, 0x002f2303, 0x00292005, 0x0025210a, 0x0024220e, 0x001c1c0a, 0x00121404, 0x000c0f02, 0x000b0d04, 0x000c0f05, 0x000b0f06, 0x000c1008, 0x00101008, 0x0013100a, 0x0016110b, 0x0014110a, 0x0018140c, 0x001c140b, 0x0020180c, 0x00231a0f, 0x00241a0e, 0x00281c0f, 0x002b1d0f, 0x002b1c0c, 0x002d1f0c, 0x002c1e0a, 0x002c1d07, 0x002f1a04, 0x00301701, 0x00321903, 0x00321a04, 0x00341c05, 0x00341b05, 0x00301803, 0x00331c06, 0x00341d07, 0x00301905, 0x00321b07, 0x00341c08, 0x00331b06, 0x00301b04, 0x00301b07, 0x002c1807, 0x002c1808, 0x002c190e, 0x0028180e, 0x00241709, 0x00201607, 0x001e1607, 0x001b1407, 0x00191308, 0x00181008, 0x00141008, 0x00141008, 0x00121008, 0x00121008, 0x00111008, 0x00121008, 0x00141007, 0x00181207, 0x001a1407, 0x001b1204, 0x00201704, 0x00241a07, 0x00281c08, 0x00322309, 0x003d2b09, 0x0050360a, 0x00715114, 0x00b7983a, 0x00c9ae30, 0x00ccb321, 0x00ccb41b, 0x00ccb11b, 0x00c3a01f, 0x00876002, 0x005c3500, 0x004e2f0b, 0x003e280b, 0x0035220b, 0x002c1c06, 0x002a1b09, 0x00251705, 0x00241604, 0x00201404, 0x001b1202, 0x00191104, 0x00181106, 0x00181109, 0x0017100a, 0x00151009, 0x00141008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00101008, 0x000f1008, 0x000d1008, 0x000c0d07, 0x000c0e08, 0x000c0f08, 0x000a100a, 0x0008100b, 0x0007100b, 0x0006100b, 0x0007100c, 0x0008100a, 0x00081009, 0x00071009, 0x00061009, 0x0007100b, 0x0007100b, 0x0006100b, 0x0007100c, 0x0007100b, 0x00060f0a, 0x0007100b, 0x0007100b, 0x0007100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0007110c, 0x0006100c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100b, 0x0007110c, 0x0007120c, 0x0005100a, 0x00060f0a, 0x0006100b, 0x0006100b, 0x0006100b, 0x00050f0a, 0x00040d08, 0x0005100a, 0x0005100a, 0x0006100a, 0x0006100a, 0x0007110a, 0x00071109, 0x00071008, 0x00071008, 0x0008120b, 0x000a120b, 0x000a120c, 0x000e150f, 0x000f1610, 0x00101610, 0x00101610, 0x00111410, 0x00111410, 0x00121510, 0x00121510, 0x00141812, 0x00151a14, 0x00151a14, 0x00151b14, 0x00181c14, 0x00191d15, 0x00191c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00171b15, 0x00161913, 0x00141812, 0x00131711, 0x00121610, 0x00101610, 0x000f160f, 0x000d140e, 0x000c140d, 0x000b130c, 0x0008110b, 0x0009110c, 0x0009110c, 0x0008110b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008110c, 0x0008110c, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0007100b, 0x0007100b, 0x0007100c, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x004b4c0f, 0x00505010, 0x00545511, 0x00585910, 0x005c5d12, 0x00786c14, 0x00cca518, 0x00c8a418, 0x008b7c16, 0x00897c16, 0x00897c17, 0x00887c16, 0x00887c16, 0x00887c16, 0x00887c17, 0x00867b16, 0x00b19618, 0x00cca71a, 0x00a48c17, 0x00686814, 0x00666714, 0x00646514, 0x00636413, 0x00616112, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005c5d11, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x00616112, 0x00636413, 0x00646414, 0x00656614, 0x006a6814, 0x00c4a019, 0x00cca71a, 0x00958316, 0x00887c15, 0x00887a16, 0x00867915, 0x00857816, 0x00847714, 0x00827514, 0x00807414, 0x00998315, 0x00c9a218, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x00292b0b, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0004100a, 0x0006100a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x00071007, 0x00071007, 0x00071007, 0x00071008, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00081009, 0x0009120c, 0x000a140c, 0x000c140e, 0x000c1710, 0x000c1710, 0x000d180f, 0x00131b12, 0x00131a13, 0x00171c15, 0x00191c16, 0x001c1b16, 0x001c1c17, 0x001e1c16, 0x001e1d16, 0x001e1d16, 0x001d1d16, 0x001d1d16, 0x001c1c14, 0x001b1912, 0x001b1a15, 0x001b1a15, 0x00171813, 0x00141810, 0x00101610, 0x00101610, 0x000f1610, 0x000c140e, 0x000c140e, 0x000b130c, 0x0009120b, 0x0008100a, 0x00080f09, 0x00080f09, 0x00071008, 0x00070f08, 0x00060f09, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00061009, 0x00040f08, 0x00040f07, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x00061009, 0x0009120b, 0x000b130c, 0x000b1109, 0x000e1109, 0x00101208, 0x00131208, 0x00151308, 0x00181408, 0x001e150c, 0x001f1409, 0x0024180b, 0x0027180b, 0x002a180a, 0x002c1909, 0x00301c09, 0x00301c06, 0x00371f08, 0x003b200a, 0x003d2309, 0x003e260b, 0x003f280c, 0x0040290d, 0x00432c0c, 0x0048340e, 0x00503612, 0x00624115, 0x008d6d2c, 0x00a4842c, 0x00a07e1d, 0x008f6a13, 0x00815d08, 0x00745004, 0x00654204, 0x00573d03, 0x00483404, 0x003d2c01, 0x00342603, 0x003c300d, 0x003f3010, 0x00392b09, 0x00342604, 0x002b2105, 0x00282108, 0x0027230c, 0x00201e0a, 0x00151605, 0x000c1002, 0x000b0e04, 0x000c0f06, 0x000a0f06, 0x000c1007, 0x000f0f08, 0x0014100b, 0x0018120c, 0x0014110b, 0x0018140c, 0x001a130a, 0x001e170c, 0x0022190e, 0x00241a0d, 0x00281c0c, 0x002c1e0d, 0x002c1c0a, 0x002e1d0c, 0x00301f0c, 0x0032200a, 0x00331f08, 0x00372008, 0x0038210a, 0x0039230c, 0x003c260e, 0x003c260f, 0x0038240c, 0x003a230d, 0x0038220c, 0x0038200b, 0x0038200c, 0x0039200c, 0x00341a07, 0x00341c08, 0x00311b07, 0x002c1706, 0x00291808, 0x002a180c, 0x0028170b, 0x00251709, 0x00221508, 0x001f1407, 0x001c1407, 0x001a1308, 0x00181008, 0x00140e08, 0x00131008, 0x00131008, 0x00121008, 0x00131008, 0x00121008, 0x00151108, 0x00181308, 0x001b1407, 0x001d1606, 0x00221c08, 0x00241c06, 0x00281e06, 0x0035260c, 0x00442f0c, 0x00583c0c, 0x007c5a15, 0x00bfa034, 0x00cbb424, 0x00ccb713, 0x00cab810, 0x00cab714, 0x00c4ab1b, 0x00906a01, 0x00643c00, 0x00503208, 0x00422d08, 0x0039260a, 0x00301f04, 0x002b1c08, 0x00271805, 0x00241605, 0x00201406, 0x001c1104, 0x001a1105, 0x00181108, 0x00181009, 0x00171009, 0x00141109, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00111108, 0x000e1008, 0x000e0f08, 0x000f100a, 0x000f100a, 0x000c1009, 0x000a100a, 0x0007100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0009100a, 0x00081009, 0x00081009, 0x00071009, 0x0006100a, 0x0006100b, 0x0007100b, 0x0008100c, 0x0007100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100b, 0x0007110c, 0x0007110c, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006100b, 0x00061009, 0x00061009, 0x00061108, 0x00081109, 0x000c140d, 0x000c140e, 0x000c140e, 0x000f140f, 0x0010140f, 0x0010140f, 0x00121511, 0x00121611, 0x00131712, 0x00151a14, 0x00151a14, 0x00151a14, 0x00181a14, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181c15, 0x00181c15, 0x00181c15, 0x00171913, 0x00171812, 0x00161812, 0x00141811, 0x0012160f, 0x0010140e, 0x000d140e, 0x000d140e, 0x000c140d, 0x0008120c, 0x0009120c, 0x0009120c, 0x0008110a, 0x0008100b, 0x0008100d, 0x0008100d, 0x0007110d, 0x0006110d, 0x0008120d, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x0041420d, 0x0045470e, 0x004b4c0f, 0x004f5010, 0x00545510, 0x00585811, 0x005c5c12, 0x00776c14, 0x00cca518, 0x00c6a219, 0x006b6814, 0x006a6a14, 0x006b6b14, 0x006c6c15, 0x006c6c15, 0x006d6d15, 0x006c6c15, 0x006a6a14, 0x00a99018, 0x00cca71a, 0x00a38b18, 0x00666714, 0x00656614, 0x00636414, 0x00616112, 0x00606013, 0x005d5e12, 0x005c5d11, 0x005c5c11, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e12, 0x00606013, 0x00616112, 0x00636413, 0x00646414, 0x00686614, 0x00c4a019, 0x00cca61a, 0x007c7315, 0x00686814, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00646414, 0x00626313, 0x00887814, 0x00c8a218, 0x00b09015, 0x00525311, 0x00525310, 0x004f5010, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00050f08, 0x00050f08, 0x00050f08, 0x00051008, 0x00051008, 0x00051008, 0x00050f09, 0x00050f0a, 0x00040f0a, 0x0004100a, 0x0004100a, 0x0004100a, 0x00050f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00050d08, 0x00050d09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081008, 0x00071007, 0x00071007, 0x00071008, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00071009, 0x0008110a, 0x000a130c, 0x000c140e, 0x000e150f, 0x000f1610, 0x000f1610, 0x00111911, 0x00141b13, 0x00141b12, 0x00181c14, 0x001b1d16, 0x001c1c16, 0x001d1c16, 0x001e1c16, 0x001e1d16, 0x001d1d16, 0x001c1e16, 0x001c1d16, 0x001a1b14, 0x00181912, 0x00191914, 0x00191a14, 0x00151812, 0x00111610, 0x000f1610, 0x000f150f, 0x000d150f, 0x000c140d, 0x0008120c, 0x0008120b, 0x00071009, 0x00071008, 0x00060f08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00060f09, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00061009, 0x00040f08, 0x00040f07, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100a, 0x000a130c, 0x000c140d, 0x000c110a, 0x000d1008, 0x000f1007, 0x00111006, 0x00131107, 0x00161307, 0x001b1208, 0x001c1307, 0x00211609, 0x00231608, 0x00251708, 0x0028180a, 0x002c1c0a, 0x002e1e08, 0x00311c06, 0x00341d07, 0x00361f08, 0x00382209, 0x003b250c, 0x003d270c, 0x00432c0d, 0x0048330b, 0x00543b0e, 0x00705118, 0x00b0923d, 0x00caae3d, 0x00c8ac2b, 0x00c4a528, 0x00b8981f, 0x00ac881a, 0x0094700f, 0x006d4e00, 0x00543901, 0x00443004, 0x00382806, 0x00342504, 0x003c2e0d, 0x003b2c0b, 0x00362807, 0x002d2203, 0x002a2006, 0x002a230b, 0x00242009, 0x00181806, 0x000d1002, 0x000c0f04, 0x000b0f06, 0x000a0f07, 0x000c1008, 0x000e0e07, 0x00141009, 0x0018110c, 0x0014110b, 0x0018130c, 0x00191209, 0x001c150b, 0x0021180c, 0x0024180c, 0x00281c0c, 0x002b1e0d, 0x002d1c0b, 0x002e1d0c, 0x002e1d0a, 0x002e1d06, 0x00321c06, 0x00382008, 0x0039210b, 0x00382008, 0x003a230b, 0x003d250c, 0x00392108, 0x003c240c, 0x003c240c, 0x003a220b, 0x0039200a, 0x003a210a, 0x00381e09, 0x00341c08, 0x00321b07, 0x002e1908, 0x002a1707, 0x00281508, 0x00271509, 0x00251609, 0x00221407, 0x00201406, 0x001c1406, 0x001a1208, 0x00171008, 0x00140f08, 0x00131008, 0x00131008, 0x00121008, 0x00131008, 0x00131008, 0x00171108, 0x001a1408, 0x001c1408, 0x00221a0a, 0x0028200d, 0x00271e08, 0x00281e06, 0x0038280d, 0x0048320d, 0x005c3e0d, 0x00836018, 0x00c3a236, 0x00ccb421, 0x00cbb710, 0x00cab80c, 0x00cab80f, 0x00c7ae18, 0x00987303, 0x00684000, 0x00543707, 0x00443006, 0x003b2608, 0x00342304, 0x002d1c05, 0x002b1c08, 0x00241806, 0x00201406, 0x001c1104, 0x001a1105, 0x00181108, 0x00181009, 0x00181009, 0x00141008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00141008, 0x0014130a, 0x000e0f08, 0x000f1008, 0x0010100b, 0x0010100b, 0x000c0f08, 0x000b1009, 0x0007100a, 0x0006100a, 0x0006100a, 0x0008110c, 0x0009100a, 0x00081009, 0x00080f09, 0x00061009, 0x0006100a, 0x0006100b, 0x0007100b, 0x0008100b, 0x0006100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005100a, 0x0006100b, 0x0006100b, 0x00050f0a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0005100a, 0x0005100a, 0x0005100a, 0x00061009, 0x00061009, 0x00061008, 0x00071008, 0x000a120c, 0x000b140d, 0x000c140e, 0x000c140e, 0x000f140f, 0x0010150f, 0x00101610, 0x00101610, 0x00121712, 0x00141914, 0x00151a14, 0x00151a14, 0x00181a14, 0x00181c15, 0x00191c16, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181a14, 0x00171813, 0x00171813, 0x00151811, 0x0012160f, 0x0010140e, 0x000e140f, 0x000e140f, 0x000c140e, 0x0009130c, 0x0009120c, 0x0009120c, 0x0008110a, 0x0008100b, 0x0008100d, 0x0008100d, 0x0007100d, 0x0006110d, 0x0008120c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x00292b0b, 0x002d2f0b, 0x0030310c, 0x0036370c, 0x003b3c0d, 0x0040400d, 0x0045470e, 0x00494a0f, 0x004f5010, 0x00535410, 0x00585811, 0x005c5c12, 0x00776c14, 0x00cca518, 0x00c6a118, 0x006a6714, 0x00696914, 0x006a6a14, 0x006b6b14, 0x006c6c15, 0x006c6c15, 0x006c6c14, 0x00686814, 0x00a99017, 0x00cca71a, 0x00a38b17, 0x00646514, 0x00646414, 0x00616113, 0x00606013, 0x005d5e12, 0x005c5c11, 0x005b5b12, 0x00595a12, 0x00585911, 0x00585911, 0x00585911, 0x00585911, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00616112, 0x00636413, 0x00686514, 0x00c3a018, 0x00cca619, 0x007c7114, 0x00686814, 0x00686814, 0x00666714, 0x00656614, 0x00646514, 0x00646414, 0x00616112, 0x00887814, 0x00c8a217, 0x00b09015, 0x00525311, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e06, 0x00060e06, 0x00060e08, 0x00040f08, 0x00040f08, 0x00040f08, 0x00040e09, 0x00040e09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00050e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00050d09, 0x00070f0a, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081008, 0x00081008, 0x00081008, 0x00081008, 0x00081009, 0x00081009, 0x00081009, 0x0008110a, 0x0009120b, 0x000a130c, 0x000c140d, 0x000d140e, 0x00101510, 0x00111610, 0x00121812, 0x00141a13, 0x00151a13, 0x00171a11, 0x00191c14, 0x001d1f17, 0x001e1c15, 0x001d1c15, 0x001e1d16, 0x001d1d17, 0x001c1d17, 0x001b1e16, 0x001b1e15, 0x00181c14, 0x00171810, 0x00161812, 0x00151812, 0x00111610, 0x0010160e, 0x000c150f, 0x000c140d, 0x000b140d, 0x0008110b, 0x0007110a, 0x0007110a, 0x00061009, 0x00061009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060f09, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00061009, 0x00040f08, 0x00040f07, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110c, 0x0009110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007100a, 0x0009110b, 0x000a120c, 0x000b1109, 0x000c1006, 0x000e0f05, 0x00121107, 0x00131107, 0x00151307, 0x00191208, 0x001b1307, 0x001f1508, 0x001e1404, 0x00201408, 0x0024180b, 0x00271908, 0x002b1c08, 0x002f1c07, 0x00311e08, 0x00321f08, 0x0034210b, 0x003a250e, 0x003c260c, 0x00432d0c, 0x004a350b, 0x00583e0a, 0x00795c13, 0x00bba038, 0x00ccb42a, 0x00ccb818, 0x00ccb612, 0x00c8b111, 0x00cbb01b, 0x00c4a41e, 0x0099750e, 0x00674700, 0x004c3400, 0x003d2c05, 0x00342504, 0x00302100, 0x003c2d0c, 0x003a2c0a, 0x00302403, 0x002e2406, 0x002c2309, 0x00272008, 0x001e1b07, 0x00101406, 0x000d1007, 0x000a0f06, 0x000a0f08, 0x000c1008, 0x000d0f07, 0x00100f08, 0x0016100b, 0x0014100b, 0x00161109, 0x001a120a, 0x001c140a, 0x0020170c, 0x0021170a, 0x00261b0b, 0x00291c0b, 0x002e1d0c, 0x002f1e0c, 0x002e1d0b, 0x00301f08, 0x00342009, 0x003a230c, 0x003b230c, 0x003a230a, 0x003c240c, 0x003e250c, 0x003c230a, 0x003d2409, 0x003f250b, 0x003a2109, 0x00381f07, 0x00381f06, 0x00371d05, 0x00341c05, 0x00301a06, 0x002f1a08, 0x002c1909, 0x00281608, 0x00261508, 0x00241608, 0x00211406, 0x001f1306, 0x001b1305, 0x00181108, 0x00170f07, 0x00151008, 0x00131008, 0x00131008, 0x00121008, 0x00121008, 0x00141109, 0x00181309, 0x001c1408, 0x001c1608, 0x00241c0a, 0x002f2711, 0x00291f08, 0x002a1d05, 0x0039290c, 0x0048330a, 0x005d400b, 0x00836017, 0x00c0a030, 0x00ccb420, 0x00cbb80e, 0x00cab80b, 0x00cab80c, 0x00cab215, 0x00a17d05, 0x006e4700, 0x00563804, 0x00483104, 0x003c2704, 0x00372402, 0x002f1d04, 0x002c1c08, 0x00261808, 0x00211406, 0x001d1204, 0x001a1105, 0x00181108, 0x00181009, 0x00161008, 0x00141008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00141008, 0x00141109, 0x00100f08, 0x000f1008, 0x000f100a, 0x000f100a, 0x000d1009, 0x00090f08, 0x00060f08, 0x00070f08, 0x00061009, 0x0008120c, 0x000a100a, 0x00080f08, 0x00070f08, 0x00061008, 0x00051009, 0x0005100a, 0x0006100a, 0x0007100b, 0x0006100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00040f09, 0x00040f09, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00040e09, 0x00040f08, 0x00051008, 0x00051008, 0x00071008, 0x0008110b, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c130d, 0x000d140e, 0x00101610, 0x00101610, 0x00111611, 0x00131712, 0x00141814, 0x00141814, 0x00171913, 0x00171913, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181b14, 0x00181a14, 0x00181913, 0x00151811, 0x00121610, 0x0010150e, 0x00101610, 0x00101610, 0x000d150f, 0x000a140d, 0x000a130c, 0x000a130c, 0x0008110b, 0x0008100a, 0x0008100d, 0x0008100d, 0x0006100c, 0x0005100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0006100b, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x0024250b, 0x00292b0b, 0x002d2f0b, 0x0030310c, 0x0036370c, 0x003b3c0d, 0x0040400e, 0x0045470e, 0x00494a10, 0x004d4e0f, 0x00525310, 0x00565711, 0x005b5b12, 0x00766a13, 0x00cca418, 0x00c6a118, 0x00696614, 0x00686814, 0x00696914, 0x006a6a14, 0x006a6a14, 0x006a6a14, 0x006a6a14, 0x00686814, 0x00a99017, 0x00cca61a, 0x00a28a16, 0x00636414, 0x00626313, 0x00606013, 0x005d5e12, 0x005c5c11, 0x00595a12, 0x00585911, 0x00585810, 0x00565710, 0x00565710, 0x00565710, 0x00565710, 0x00585810, 0x00585911, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00616112, 0x00656314, 0x00c3a018, 0x00cca619, 0x007a7014, 0x00656613, 0x00656613, 0x00656614, 0x00656614, 0x00646514, 0x00626313, 0x00606012, 0x00887814, 0x00c8a217, 0x00b09015, 0x00515110, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00060e06, 0x00060e06, 0x00060e08, 0x00040f08, 0x00040f08, 0x00030f08, 0x00030f09, 0x00030f09, 0x00030f09, 0x00030f09, 0x00040f09, 0x00040f09, 0x00040e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00080f0a, 0x0008100b, 0x0008100b, 0x00060e0a, 0x00040d08, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x0008100a, 0x000c140e, 0x000d140e, 0x000f140f, 0x0010150f, 0x00111610, 0x00131812, 0x00151813, 0x00171913, 0x00161b14, 0x00181b13, 0x001c1c15, 0x001f1e16, 0x001e1c15, 0x001e1c15, 0x001e1d16, 0x001c1d17, 0x001c1d17, 0x00191e16, 0x00181d15, 0x00161c13, 0x00141811, 0x00111610, 0x00101610, 0x000e170e, 0x000c170e, 0x000a140d, 0x0009140c, 0x0008110b, 0x00061009, 0x00061009, 0x0007110a, 0x00061009, 0x00061009, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060f09, 0x0006100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00061009, 0x00050f08, 0x00050f08, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0005100a, 0x0005100a, 0x0007110c, 0x0007110c, 0x0007100a, 0x0008100a, 0x0009110a, 0x000b1008, 0x000b0f06, 0x000d1006, 0x00111108, 0x00121107, 0x00141207, 0x00181207, 0x00191306, 0x001b1306, 0x001b1104, 0x001d1308, 0x00201508, 0x00231808, 0x00261907, 0x00281806, 0x002c1b06, 0x002f1d06, 0x00332009, 0x0038250c, 0x003b270b, 0x0044300c, 0x004d380b, 0x005d440c, 0x00836618, 0x00baa12e, 0x00ccb720, 0x00cbba09, 0x00cbbb05, 0x00cbbb07, 0x00ccb80c, 0x00ccb518, 0x00b79618, 0x00755400, 0x00543a00, 0x00443203, 0x00382a04, 0x002c1c00, 0x00392b0a, 0x003d300c, 0x00372b08, 0x00312807, 0x002f2608, 0x00282006, 0x0024200b, 0x00171608, 0x00101106, 0x000c0f06, 0x000a0f08, 0x000c1007, 0x000d1007, 0x00100f08, 0x00141009, 0x0014110b, 0x00161109, 0x00191209, 0x001c140a, 0x001f150a, 0x00201608, 0x00251909, 0x00281a0b, 0x002c1c0c, 0x002f1d0c, 0x002e1d0b, 0x0032200a, 0x0038240c, 0x003a220c, 0x003a220c, 0x003b230b, 0x003d240c, 0x003e250c, 0x003e250b, 0x003d2309, 0x003d2309, 0x00392008, 0x00371e06, 0x00381f08, 0x00371e08, 0x00341b06, 0x00301805, 0x002d1806, 0x002e1b09, 0x002b180a, 0x00261607, 0x00251608, 0x00211406, 0x00201406, 0x001c1306, 0x00191108, 0x00170f08, 0x00151008, 0x00141008, 0x00131008, 0x00121008, 0x00121008, 0x00141008, 0x0019140a, 0x001e170a, 0x001f1807, 0x0028200c, 0x00352c14, 0x00291e05, 0x002b1d03, 0x0039290a, 0x00483309, 0x005c3f0b, 0x00805d13, 0x00bc9c2c, 0x00cab41d, 0x00cbb80c, 0x00cab908, 0x00cab80a, 0x00cab314, 0x00a88408, 0x00754e00, 0x00573a00, 0x00483303, 0x003e2804, 0x00372401, 0x00301e03, 0x002c1c08, 0x00261808, 0x00221608, 0x001e1407, 0x001a1105, 0x00171208, 0x00161008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00140f08, 0x00110f06, 0x00100f08, 0x000f1008, 0x000f100a, 0x000f1009, 0x000f120b, 0x00080d06, 0x00080f08, 0x00070f08, 0x00071009, 0x0008120b, 0x0008110a, 0x00080f08, 0x00060f08, 0x00061008, 0x00051009, 0x0006100a, 0x0006100a, 0x0008100c, 0x0009120d, 0x0009110c, 0x0009110c, 0x0009110c, 0x0009110c, 0x0009110c, 0x0009110c, 0x0008100b, 0x0008100b, 0x0005100c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0007100c, 0x00050f0c, 0x00050f0c, 0x0006100b, 0x00050f0a, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040e09, 0x00040e09, 0x00040d08, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00040f08, 0x00051008, 0x00051007, 0x00061008, 0x0008100a, 0x0009120c, 0x0009120c, 0x000a130c, 0x000c130d, 0x000c130d, 0x000e150f, 0x00101610, 0x00101510, 0x00121712, 0x00141812, 0x00141812, 0x00161913, 0x00171913, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181b14, 0x00171a14, 0x00141812, 0x00131710, 0x00111610, 0x00101610, 0x00101610, 0x000e150f, 0x000c140e, 0x000b140d, 0x000a130c, 0x0009120b, 0x00081009, 0x0008100c, 0x0008100c, 0x0006100c, 0x0005100c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x0040400d, 0x0044450e, 0x00494a10, 0x004d4e0f, 0x00515110, 0x00555610, 0x00595a11, 0x00756a13, 0x00cca418, 0x00c6a118, 0x00686514, 0x00666714, 0x00686814, 0x00686814, 0x00696914, 0x00696914, 0x00696914, 0x00656614, 0x00a88f17, 0x00cca619, 0x00a28917, 0x00616113, 0x00606013, 0x005e5f13, 0x005c5c11, 0x00595a12, 0x00585810, 0x00585810, 0x00555610, 0x00545511, 0x00545511, 0x00545511, 0x00545511, 0x00555611, 0x00565710, 0x00585911, 0x00595a12, 0x005c5c11, 0x005d5e12, 0x00606013, 0x00646113, 0x00c3a018, 0x00cca519, 0x007a7014, 0x00646514, 0x00656614, 0x00646514, 0x00646514, 0x00636414, 0x00626312, 0x00606013, 0x00887714, 0x00c8a117, 0x00b09015, 0x00515110, 0x00525310, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040e07, 0x00020e07, 0x00020e07, 0x00020e08, 0x00020e08, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081009, 0x00081009, 0x0008110a, 0x0008110a, 0x000c130d, 0x000f150f, 0x0010140f, 0x00111510, 0x00141810, 0x00151912, 0x00181813, 0x00181913, 0x00181c13, 0x001a1d14, 0x001d1c15, 0x00201c14, 0x001f1c14, 0x001f1c14, 0x001e1c17, 0x001c1c17, 0x001a1d17, 0x00171b14, 0x00151812, 0x00141912, 0x00121911, 0x00101811, 0x000e1610, 0x000c160f, 0x0008150d, 0x0009140c, 0x0008120b, 0x00051008, 0x00051008, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00081009, 0x00081009, 0x00081009, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0006100b, 0x0007100c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0009100b, 0x000a100a, 0x000a1009, 0x00091007, 0x00091006, 0x000b1007, 0x000e1108, 0x00101108, 0x00121006, 0x00151005, 0x00161006, 0x00181105, 0x001a1307, 0x001c1408, 0x001c1408, 0x00201608, 0x00241809, 0x00261809, 0x00291b08, 0x002c1d07, 0x00312006, 0x00382508, 0x003c2809, 0x0046300b, 0x00503a0a, 0x005f460c, 0x00846819, 0x00bda432, 0x00ccb81e, 0x00ccbc09, 0x00cbbc09, 0x00cbbc0a, 0x00caba0c, 0x00cbb910, 0x00b79c0f, 0x00795800, 0x00573c00, 0x00453400, 0x00392c02, 0x002e2000, 0x00382908, 0x003f330d, 0x003b3009, 0x00352c08, 0x00302808, 0x002c2409, 0x00271e08, 0x001f1705, 0x00141104, 0x000d0f07, 0x000b1008, 0x000c1007, 0x000d1007, 0x00101008, 0x00101008, 0x0014110b, 0x00161109, 0x00181108, 0x001b1308, 0x001e1409, 0x00201608, 0x00231809, 0x0028180a, 0x002b1a0a, 0x002e1c0c, 0x00311e0c, 0x00321f09, 0x00341d07, 0x00372008, 0x0039210a, 0x003a220c, 0x003c250e, 0x003e240c, 0x003f250d, 0x003c240a, 0x003c2309, 0x00382008, 0x0038200a, 0x00371f0c, 0x00361e0e, 0x00371c0c, 0x00331a08, 0x00301a08, 0x002e1b08, 0x002c1a08, 0x00281706, 0x00261808, 0x00231507, 0x00201407, 0x001d1407, 0x001b1108, 0x00181008, 0x00171009, 0x00141109, 0x00141109, 0x00131008, 0x00121009, 0x00141008, 0x001a150b, 0x001e1809, 0x00201806, 0x002b210c, 0x00382d14, 0x00281c02, 0x002f2004, 0x003a2808, 0x0048330a, 0x005a3c09, 0x007e5b13, 0x00bc9c2c, 0x00c9b21c, 0x00cbb80c, 0x00cab908, 0x00cab808, 0x00cbb314, 0x00ae880b, 0x00775100, 0x00583b00, 0x004a3401, 0x003f2a04, 0x00382401, 0x00301f04, 0x002d1c08, 0x00271807, 0x00241506, 0x00201307, 0x00181105, 0x00171208, 0x00171109, 0x00141008, 0x00141009, 0x00151109, 0x00151109, 0x00151109, 0x00151109, 0x00141008, 0x00131008, 0x00101009, 0x00101009, 0x00100f08, 0x00100f08, 0x000f1009, 0x000a0f06, 0x000a0f08, 0x00091008, 0x00081008, 0x00071208, 0x0008110a, 0x00061008, 0x00061009, 0x00051109, 0x0008100b, 0x0008100c, 0x0006100a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0009100c, 0x0007110c, 0x0005100a, 0x0007110c, 0x0007110c, 0x0006100b, 0x0008120d, 0x0005100a, 0x0005100a, 0x0005100b, 0x0006100b, 0x0005100b, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00040f09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051008, 0x00051008, 0x00040e06, 0x00050e07, 0x00070f08, 0x0008110a, 0x0008110a, 0x0008110b, 0x000a120c, 0x000c140e, 0x000c140e, 0x000d150f, 0x000f140f, 0x00101610, 0x00121710, 0x00131810, 0x00131712, 0x00151a14, 0x00161b15, 0x00161b15, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181d16, 0x00181c17, 0x00151a14, 0x00151a14, 0x00141814, 0x00131712, 0x00131712, 0x00101510, 0x00101510, 0x00101510, 0x000d150f, 0x000a120c, 0x0008110b, 0x0008110a, 0x00081009, 0x0008100a, 0x0007110a, 0x00051109, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008110c, 0x0008110c, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003e400c, 0x0044450e, 0x0048490f, 0x004c4d10, 0x00515110, 0x00555611, 0x00585911, 0x00746913, 0x00cca418, 0x00c6a118, 0x00666414, 0x00646514, 0x00666714, 0x00686814, 0x00686814, 0x00686814, 0x00686814, 0x00646514, 0x00a88e16, 0x00cca519, 0x00a18816, 0x00606012, 0x005e5f13, 0x005c5d11, 0x005b5b12, 0x00585910, 0x00565710, 0x00555611, 0x00535410, 0x00525310, 0x00525310, 0x00525310, 0x00535410, 0x00545510, 0x00555611, 0x00565710, 0x00585911, 0x005b5b12, 0x005c5d11, 0x005e5f13, 0x00636013, 0x00c39f18, 0x00cca518, 0x00786e14, 0x00646414, 0x00646414, 0x00646414, 0x00646414, 0x00626313, 0x00616112, 0x00606013, 0x00887614, 0x00c8a117, 0x00b09015, 0x00505010, 0x00515110, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00040d05, 0x00040d05, 0x00040d07, 0x00040e07, 0x00020e07, 0x00020e07, 0x00020e08, 0x00020e08, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100a, 0x00081009, 0x00081009, 0x0008110a, 0x0009110a, 0x000c130d, 0x00101610, 0x00111610, 0x00121712, 0x00141812, 0x00161913, 0x00181913, 0x00181a14, 0x001a1c14, 0x001c1e16, 0x001e1d16, 0x00201c14, 0x00201c14, 0x001f1c14, 0x001d1c16, 0x001a1c16, 0x00191c16, 0x00181b14, 0x00151812, 0x00131811, 0x00111810, 0x00101711, 0x000e1610, 0x0009140c, 0x0008140d, 0x0009140c, 0x0007110a, 0x00040f08, 0x00040e07, 0x00070f08, 0x00070f08, 0x00060e08, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f09, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00081009, 0x00081009, 0x00081008, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0006100b, 0x0006100b, 0x00040e09, 0x0007110c, 0x000a140f, 0x0008120d, 0x0007110c, 0x0007110c, 0x0009100b, 0x000a100a, 0x000a1009, 0x00091008, 0x00091006, 0x000a0f06, 0x000d1007, 0x00101108, 0x00121006, 0x00141007, 0x00151008, 0x00151006, 0x00181207, 0x00191409, 0x001a140a, 0x001f1509, 0x0022170a, 0x0025180b, 0x00281c0a, 0x002c1d08, 0x00302008, 0x00352508, 0x003b2908, 0x0044310a, 0x00503a09, 0x0062470c, 0x00886b1a, 0x00c0a835, 0x00ccb820, 0x00ccbb0c, 0x00cbbc09, 0x00cabb0b, 0x00caba0d, 0x00cbb910, 0x00b6980b, 0x007c5900, 0x005c3e00, 0x004a3802, 0x003d3004, 0x00322400, 0x003a2c0a, 0x00413410, 0x003f340a, 0x003b3008, 0x00352b0a, 0x0031250a, 0x002c230b, 0x00211a07, 0x00181404, 0x000f0f05, 0x000c1007, 0x000c1005, 0x000e1208, 0x00101108, 0x00101008, 0x0014110b, 0x00161009, 0x00181108, 0x001b1308, 0x001e1409, 0x001f1406, 0x00221608, 0x00281809, 0x002b190a, 0x002e1c0c, 0x00301d0c, 0x00321f09, 0x00341d08, 0x00371f08, 0x0039210a, 0x003a220c, 0x003c240d, 0x003e240c, 0x003e240d, 0x003c230b, 0x003c230a, 0x003a230a, 0x00382108, 0x00371f0b, 0x00371f0c, 0x00371c0c, 0x00331a08, 0x00301a08, 0x002f1a08, 0x002c1a08, 0x00281706, 0x00261807, 0x00231607, 0x00201407, 0x001d1407, 0x001b1108, 0x00181008, 0x00171009, 0x00141109, 0x00141109, 0x00131008, 0x00131009, 0x00141109, 0x001c170d, 0x001f1809, 0x00201805, 0x00302610, 0x00382c14, 0x002b1d01, 0x00332205, 0x003c2a08, 0x0048340b, 0x005a3d0d, 0x007b5812, 0x00b7972b, 0x00c9b21e, 0x00ccb80c, 0x00cab908, 0x00cbb808, 0x00cbb516, 0x00b08b0c, 0x00785000, 0x005a3b00, 0x004c3501, 0x00412c04, 0x00382401, 0x00301f04, 0x002d1c07, 0x00281806, 0x00241506, 0x00201305, 0x00181105, 0x00171208, 0x00171109, 0x00151008, 0x00141009, 0x00151109, 0x00151109, 0x00151109, 0x00151109, 0x00141008, 0x00131008, 0x00111009, 0x00101009, 0x00100f08, 0x00100f08, 0x000f1009, 0x000c0f05, 0x000a0f06, 0x00091008, 0x000a1008, 0x00081108, 0x0008110a, 0x00061008, 0x00061009, 0x00051109, 0x0008100b, 0x0008100b, 0x0006100a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0007110c, 0x0005100a, 0x0007110c, 0x0007110c, 0x0006100b, 0x0008120d, 0x0005100a, 0x0005100a, 0x00040f09, 0x00040e09, 0x00040f09, 0x0006100b, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x00040f09, 0x00040f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051008, 0x00051008, 0x00040e06, 0x00050e07, 0x00070f08, 0x0008110a, 0x0008110a, 0x0008110a, 0x0009120c, 0x000c140e, 0x000c140d, 0x000c140e, 0x000d140e, 0x00101610, 0x0010170f, 0x00111810, 0x00131712, 0x00131712, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161b14, 0x00181c15, 0x00181d16, 0x00181c17, 0x00151a14, 0x00151a14, 0x00141814, 0x00131712, 0x00131712, 0x00101510, 0x00101510, 0x00101510, 0x000c140e, 0x0009120b, 0x0008110a, 0x0008110a, 0x0009120c, 0x0009120c, 0x0008130c, 0x00051109, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008110c, 0x0008110c, 0x0005100a, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250c, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0036370c, 0x00393b0c, 0x003e400c, 0x0043440e, 0x0048490e, 0x004c4d0f, 0x00505010, 0x00545511, 0x00585810, 0x00746813, 0x00cca418, 0x00c6a018, 0x00656313, 0x00646414, 0x00646514, 0x00666713, 0x00656613, 0x00666713, 0x00666714, 0x00636414, 0x00a88e16, 0x00cca519, 0x00a18815, 0x005e5f13, 0x005c5d11, 0x005b5b12, 0x00585911, 0x00585810, 0x00555611, 0x00535410, 0x00525310, 0x00515110, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00545510, 0x00555611, 0x00565710, 0x00585911, 0x005b5b12, 0x005c5d11, 0x00626013, 0x00c39e18, 0x00cca518, 0x00786e14, 0x00636414, 0x00636414, 0x00636414, 0x00626313, 0x00616112, 0x00606013, 0x005e5f13, 0x00887614, 0x00c8a117, 0x00b09015, 0x00505010, 0x00515110, 0x004d4e0f, 0x0048490f, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e06, 0x00060e06, 0x00070d08, 0x00050e08, 0x00040f08, 0x00031008, 0x00030f09, 0x00030f09, 0x00040e09, 0x00040e09, 0x00050f0a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008110a, 0x0008110a, 0x0009120c, 0x0009120c, 0x000d140e, 0x00101610, 0x00111611, 0x00121712, 0x00171912, 0x00171913, 0x00181a14, 0x001b1c16, 0x001c1e16, 0x001c1e16, 0x001f1c16, 0x00201c14, 0x00201c14, 0x00201c14, 0x001c1b14, 0x00191b16, 0x00181a15, 0x00151811, 0x0012160f, 0x0010150e, 0x0010160e, 0x000f150f, 0x000b140d, 0x0009140c, 0x0008140c, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x0008100a, 0x00070f0a, 0x00060f0a, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008110a, 0x00081009, 0x00070f08, 0x0008100b, 0x0008100b, 0x00060e09, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008120d, 0x0008120d, 0x0007110c, 0x0007100a, 0x00081009, 0x00091008, 0x000a0f08, 0x000a0f08, 0x000b1008, 0x00090e05, 0x000a0f06, 0x000c0f04, 0x000f1007, 0x00101005, 0x00141008, 0x00141008, 0x00141006, 0x00171008, 0x0019140b, 0x0019140b, 0x001c1308, 0x00201508, 0x00231809, 0x00271b0b, 0x002b1c08, 0x00302008, 0x00342408, 0x003c2a08, 0x00443109, 0x0051390b, 0x0063470c, 0x00896c18, 0x00c0a835, 0x00ccb721, 0x00cbba0d, 0x00cbba08, 0x00cab90a, 0x00cbb90d, 0x00ccb811, 0x00b6950b, 0x007d5700, 0x00603e00, 0x004b3702, 0x00403006, 0x00342502, 0x003c2e0b, 0x00443610, 0x0040340a, 0x003e3208, 0x00382c08, 0x00342709, 0x0030240a, 0x00271e08, 0x001a1505, 0x00100e04, 0x000c0e06, 0x000c1005, 0x000e1208, 0x00101208, 0x00121108, 0x00131008, 0x00141008, 0x00170f07, 0x00181108, 0x001e1409, 0x001f1406, 0x00211507, 0x00271809, 0x002b1a0b, 0x002e1b0a, 0x00301c0b, 0x00331e09, 0x0037200a, 0x00382009, 0x0039210a, 0x0039220a, 0x003b240b, 0x003c230b, 0x003f260d, 0x003c220a, 0x00392006, 0x00392207, 0x00372005, 0x00372008, 0x00361e09, 0x00361c0a, 0x00331a08, 0x00301a08, 0x002f1a08, 0x002d1a08, 0x00281808, 0x00261807, 0x00241607, 0x00231709, 0x001f1408, 0x001a1108, 0x00181008, 0x00170f08, 0x00151109, 0x00151109, 0x00141008, 0x0015100b, 0x0016130b, 0x001c170d, 0x001e180a, 0x00221a06, 0x00342811, 0x003c2e14, 0x002e1f03, 0x00342206, 0x003c2b08, 0x0048340b, 0x005a3e0d, 0x00785712, 0x00b49529, 0x00ccb220, 0x00ccb80f, 0x00cab809, 0x00cab808, 0x00cbb416, 0x00b18a0c, 0x007b5000, 0x005d3b00, 0x004e3403, 0x00432c04, 0x00382401, 0x00311f04, 0x002d1d05, 0x00291a06, 0x00261808, 0x00201406, 0x00181204, 0x00171208, 0x00171109, 0x00161109, 0x00141209, 0x0014130a, 0x0014120a, 0x00141109, 0x00141109, 0x00141008, 0x00141008, 0x00121009, 0x00101009, 0x00110f08, 0x00111009, 0x00101009, 0x000d0f05, 0x000c1006, 0x000a0f06, 0x000a1008, 0x00081108, 0x00081009, 0x00061009, 0x0007110a, 0x00061009, 0x0007100a, 0x0007100b, 0x0006100a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0008120d, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008120d, 0x0007110c, 0x0006100b, 0x0006100b, 0x00051008, 0x00051008, 0x00061008, 0x00071008, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x0008100a, 0x000a130c, 0x000a130c, 0x000c140e, 0x000d140e, 0x00101610, 0x00101610, 0x00111810, 0x00131712, 0x00131712, 0x00141914, 0x00141914, 0x00151a13, 0x00151a13, 0x00171c15, 0x00171c15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00141914, 0x00141814, 0x00121711, 0x00101510, 0x00101510, 0x000d150f, 0x000d150f, 0x000b130c, 0x0009120c, 0x00081009, 0x00081009, 0x0008120b, 0x00051109, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250c, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x00393b0c, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x00535410, 0x00565710, 0x00736812, 0x00cca418, 0x00c6a018, 0x00646212, 0x00626313, 0x00646414, 0x00646514, 0x00646514, 0x00646514, 0x00646514, 0x00616114, 0x00a88d16, 0x00cca518, 0x00a08716, 0x005d5e12, 0x005c5c11, 0x00595a11, 0x00585810, 0x00555611, 0x00535410, 0x00525310, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00545510, 0x00555610, 0x00585810, 0x00595a12, 0x005c5c11, 0x00615f12, 0x00c39e17, 0x00cca418, 0x00786c14, 0x00616112, 0x00616112, 0x00626312, 0x00616112, 0x00606013, 0x00606013, 0x005e5f12, 0x00877514, 0x00c8a117, 0x00b09014, 0x00505010, 0x00515110, 0x004d4e0f, 0x00494a10, 0x0045470e, 0x0041420d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e06, 0x00060e07, 0x00070d08, 0x00060e08, 0x00040f08, 0x00031008, 0x00040e09, 0x00040e09, 0x00040e09, 0x00040e09, 0x00050f09, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008110b, 0x0009120c, 0x0009120c, 0x0009120c, 0x000d140e, 0x00101610, 0x00131712, 0x00141813, 0x00171913, 0x00171913, 0x001a1b15, 0x001c1c17, 0x001c1e16, 0x001c1e16, 0x001f1c16, 0x001f1c14, 0x00201c14, 0x001f1c14, 0x001c1b14, 0x001a1b14, 0x00181a14, 0x00151811, 0x0012160f, 0x0010150e, 0x000f150f, 0x000b130e, 0x000a120e, 0x0009130e, 0x0008140d, 0x00061009, 0x00061009, 0x00051008, 0x00051008, 0x00060e08, 0x00060e08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00060f09, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008110a, 0x00081009, 0x00070f08, 0x0008100b, 0x0008100b, 0x0008100b, 0x0009110d, 0x0006100b, 0x0006100b, 0x0009130d, 0x0006100b, 0x0006100b, 0x0008110c, 0x0008100b, 0x00081009, 0x000a0f08, 0x000a0f08, 0x000a0f08, 0x000b1008, 0x00090e05, 0x000b0e05, 0x000c0f06, 0x000f1007, 0x00101007, 0x00131008, 0x00131008, 0x00141006, 0x00151108, 0x00171309, 0x00171309, 0x00191308, 0x001d1509, 0x00201808, 0x00241b0a, 0x00291c08, 0x002e2008, 0x00342508, 0x003c2a09, 0x0045320a, 0x0051390b, 0x0064480b, 0x00896c16, 0x00c0a834, 0x00ccb721, 0x00cbb90e, 0x00cbba0a, 0x00cab909, 0x00cbb90d, 0x00ccb810, 0x00b5950b, 0x007e5800, 0x00603f00, 0x004d3703, 0x00403005, 0x00342601, 0x003e300c, 0x00473913, 0x0043360c, 0x00403309, 0x003c2e09, 0x00362808, 0x00312709, 0x00292008, 0x001c1705, 0x00111002, 0x000d0f05, 0x000c1005, 0x000f1308, 0x00101208, 0x00121108, 0x00131008, 0x00161109, 0x00181008, 0x00181108, 0x001c1408, 0x001e1407, 0x00201507, 0x00251709, 0x002b1a0c, 0x002d1a0a, 0x002f1c09, 0x00321d08, 0x0037200b, 0x003a220c, 0x003b240c, 0x003b240c, 0x003b230a, 0x003c230b, 0x00392008, 0x003c220a, 0x00392007, 0x00392104, 0x00382004, 0x00381f08, 0x00381e09, 0x00371c08, 0x00331a08, 0x00301a08, 0x002f1a08, 0x002d1a08, 0x00281808, 0x00271708, 0x00241608, 0x00221708, 0x001f1408, 0x001a1108, 0x00181008, 0x00161008, 0x00151109, 0x00151109, 0x00141008, 0x0016110c, 0x0016130b, 0x001d180e, 0x001d1709, 0x00221a06, 0x00342910, 0x003c2f14, 0x002f2004, 0x00342206, 0x003c2c0a, 0x0049350c, 0x005c3f0f, 0x00785712, 0x00b4942a, 0x00ccb320, 0x00ccb70e, 0x00ccb80a, 0x00ccb809, 0x00cbb415, 0x00b18a0c, 0x007b5000, 0x005e3c00, 0x004f3404, 0x00442c05, 0x00382501, 0x00312004, 0x002d1d05, 0x00291a06, 0x00261808, 0x00201504, 0x00191104, 0x00171307, 0x00161209, 0x00151109, 0x00141109, 0x0014130a, 0x0014120a, 0x00141109, 0x00141109, 0x00141008, 0x00141008, 0x00121009, 0x00101009, 0x00110f08, 0x00121009, 0x00101009, 0x000f0f06, 0x000c0f05, 0x000c1007, 0x000b1008, 0x00081108, 0x00081009, 0x00061009, 0x0007110a, 0x0006100a, 0x0007100a, 0x0007100b, 0x0007100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0007110c, 0x0005100a, 0x0006100b, 0x0006100b, 0x0005100a, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008110c, 0x0007110c, 0x0006100b, 0x00061009, 0x00061009, 0x00061009, 0x00061008, 0x00070f08, 0x00070f08, 0x00070f08, 0x00070f08, 0x00081009, 0x0009120c, 0x0008110a, 0x000a130c, 0x000c140d, 0x000d150f, 0x000e1710, 0x00101810, 0x00111711, 0x00121711, 0x00141914, 0x00141914, 0x00151a14, 0x00151a13, 0x00171c15, 0x00171c15, 0x00161b14, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151a14, 0x00151a14, 0x00131712, 0x00101510, 0x00101510, 0x000d150f, 0x000d150f, 0x000b130c, 0x0009120c, 0x0008100a, 0x0008100b, 0x0008120c, 0x0005110b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x000f1612, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003e400d, 0x0041420e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x00525310, 0x00565711, 0x00736812, 0x00cca417, 0x00c6a018, 0x00646113, 0x00616112, 0x00626313, 0x00646414, 0x00646414, 0x00646414, 0x00636414, 0x00606013, 0x00a78c16, 0x00cca418, 0x00a08715, 0x005c5d11, 0x005b5b12, 0x00585910, 0x00565711, 0x00545510, 0x00525310, 0x00515110, 0x004f5010, 0x004f5010, 0x004d4e0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545511, 0x00565711, 0x00585810, 0x00595a12, 0x00605d11, 0x00c39e17, 0x00cca418, 0x00776c14, 0x00616112, 0x00606012, 0x00616112, 0x00606013, 0x00606013, 0x005e5f13, 0x005c5d11, 0x00877514, 0x00c8a117, 0x00b09014, 0x004f5010, 0x00505010, 0x004d4e10, 0x0048490f, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00040e0b, 0x00040e0b, 0x00050e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00041007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00060e09, 0x00060e09, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x0009120c, 0x000a130c, 0x000c120c, 0x000d140d, 0x000f150d, 0x00101710, 0x00141811, 0x00151a13, 0x00181c15, 0x00181c15, 0x001b1c14, 0x001e1d14, 0x00201e15, 0x00201e15, 0x001f1c14, 0x001e1d14, 0x001e1d14, 0x001c1c14, 0x00191812, 0x00181810, 0x00171812, 0x00141611, 0x0011140f, 0x0010140f, 0x000b130e, 0x000a1410, 0x000a1410, 0x0008120f, 0x0007100c, 0x00051009, 0x00040f08, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051008, 0x00061009, 0x00061009, 0x00061009, 0x00061009, 0x0008110b, 0x00081009, 0x00081009, 0x0006100b, 0x0007110c, 0x0007110c, 0x0008100a, 0x00081008, 0x000a0f08, 0x000a0f08, 0x000a0f07, 0x000a0f06, 0x000c0f06, 0x000c0d08, 0x000c0d08, 0x000c0f08, 0x000c0f08, 0x000f1008, 0x000f1007, 0x00111008, 0x00141208, 0x00161409, 0x00161409, 0x00171308, 0x001a1508, 0x001f180a, 0x00241b0a, 0x00271c07, 0x002e1f08, 0x0034240a, 0x003b2b0a, 0x0045330b, 0x00513b0c, 0x0064480b, 0x00886b14, 0x00c0a730, 0x00cbb620, 0x00cbba0c, 0x00cbba0a, 0x00cbba0a, 0x00cbb90c, 0x00ccb810, 0x00b2930a, 0x00805a00, 0x00604000, 0x004c3803, 0x00403006, 0x00342701, 0x003e300b, 0x00483913, 0x0046370e, 0x0043340c, 0x003f300c, 0x00322503, 0x00342a0a, 0x002d250b, 0x00201c06, 0x00111000, 0x000d1004, 0x000c1005, 0x000f1308, 0x00101208, 0x00111008, 0x00131008, 0x00161108, 0x00181009, 0x00191209, 0x001c1208, 0x001e1407, 0x00211509, 0x00241609, 0x00241607, 0x002b190a, 0x002f1b0a, 0x00321d0a, 0x00371f0b, 0x003a200b, 0x003d240c, 0x003c230b, 0x003c230b, 0x0040240e, 0x003d220b, 0x003c210a, 0x003c2208, 0x003b2007, 0x003c2009, 0x003b1f09, 0x003a1e0a, 0x00381f08, 0x00341c08, 0x00311a06, 0x002f1a08, 0x002d190a, 0x002a180b, 0x00261509, 0x00231409, 0x00201408, 0x001d1508, 0x001a1308, 0x00181108, 0x0018120b, 0x0018110a, 0x00140e07, 0x00161009, 0x0016120a, 0x0018140b, 0x001c170c, 0x001c1408, 0x00241b07, 0x00362c10, 0x003f3214, 0x002f2004, 0x00342208, 0x003c2b0a, 0x0049350d, 0x005c400f, 0x00785614, 0x00b4942a, 0x00ccb321, 0x00ccb60d, 0x00ccb80a, 0x00ccb809, 0x00cbb414, 0x00ab8305, 0x007b5000, 0x005f3c00, 0x004f3404, 0x00452c08, 0x00382600, 0x00312004, 0x002d1d05, 0x00291a06, 0x00251908, 0x001e1506, 0x00191306, 0x00181207, 0x00171208, 0x00141209, 0x00141109, 0x00141109, 0x00141109, 0x00131008, 0x00131008, 0x00140f09, 0x00121009, 0x00121009, 0x00120f0b, 0x00120f0b, 0x00120f0b, 0x00110f08, 0x00121108, 0x00141008, 0x000f1007, 0x000c1108, 0x00091008, 0x00081009, 0x00081009, 0x0009110c, 0x0008110c, 0x0007100b, 0x0008100b, 0x0008100c, 0x0008100d, 0x00070e0c, 0x0008100c, 0x0008100d, 0x0008100d, 0x0008100d, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00060f0b, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0007110d, 0x0006100c, 0x00050f0c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110b, 0x0005110b, 0x00030f09, 0x00030f09, 0x0004100a, 0x0005100b, 0x00040f09, 0x0004100a, 0x0005100a, 0x0006100b, 0x0007110c, 0x0008100b, 0x000a120e, 0x0009110d, 0x000c140f, 0x000f150f, 0x00101610, 0x00101811, 0x00101811, 0x00101812, 0x00121a14, 0x00141814, 0x00151a14, 0x00171c17, 0x00171c15, 0x00181e15, 0x00181f16, 0x00171e15, 0x00161d14, 0x00171c14, 0x00171913, 0x00141813, 0x00141614, 0x00131714, 0x000e1811, 0x000e1811, 0x000a140d, 0x0009140d, 0x00091310, 0x0008120e, 0x0008120f, 0x0008120f, 0x0008100b, 0x0008100b, 0x0008100b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280b, 0x00292b0a, 0x002d2f0c, 0x0032330c, 0x00393b0c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x00525310, 0x00555611, 0x00726612, 0x00cca417, 0x00c6a017, 0x00636013, 0x00606013, 0x00616112, 0x00626313, 0x00636413, 0x00636413, 0x00626313, 0x00606012, 0x00a78c15, 0x00cca418, 0x00a08615, 0x005b5b12, 0x00595a12, 0x00585810, 0x00555611, 0x00535410, 0x00515110, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004c4d0e, 0x004d4e0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00525310, 0x00545510, 0x00565711, 0x00585910, 0x00595a12, 0x00605c12, 0x00c39e17, 0x00cca418, 0x00766c14, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005e5f12, 0x005c5d11, 0x00867414, 0x00c8a116, 0x00b09014, 0x004d4e10, 0x00505010, 0x004c4d0f, 0x00484910, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0024250c, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00040e09, 0x00040e09, 0x00060d0b, 0x00060d0b, 0x00060e0a, 0x00050f08, 0x00040f08, 0x00040f08, 0x00041007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00040c08, 0x00040c08, 0x00060e09, 0x00060e09, 0x00060e0a, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x00050d09, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100a, 0x0009120c, 0x000c130d, 0x000e140e, 0x000f150f, 0x0010170f, 0x00121911, 0x00141912, 0x00161b14, 0x00181c15, 0x00181c15, 0x001c1d15, 0x001e1d14, 0x00201e15, 0x00201e15, 0x001e1d14, 0x001d1e14, 0x001c1c14, 0x001a1b14, 0x00181913, 0x00171812, 0x00161812, 0x00131610, 0x0010140e, 0x000e150f, 0x000a120e, 0x0008120f, 0x0008120f, 0x0007100d, 0x0006100c, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0005100a, 0x00051009, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100c, 0x0008100b, 0x0008100b, 0x0006100b, 0x0007110d, 0x0007110c, 0x0008100a, 0x00091008, 0x000a0f08, 0x000a0f08, 0x000a0f07, 0x000a0f06, 0x000c0f06, 0x000c0e06, 0x000c0e06, 0x000c1007, 0x000c1007, 0x000f1008, 0x000f1007, 0x00111108, 0x00141208, 0x00141308, 0x00141308, 0x00151208, 0x00191408, 0x001d1809, 0x00221a09, 0x00271c07, 0x002e1e08, 0x0035250b, 0x003b2c0b, 0x0045340c, 0x00523b0c, 0x0064480b, 0x00886a15, 0x00c0a730, 0x00cbb61f, 0x00cbba0b, 0x00cbba0a, 0x00cbba0a, 0x00cbba0c, 0x00ccb910, 0x00af9008, 0x007c5800, 0x00604100, 0x004c3903, 0x003e2f04, 0x00342701, 0x003e300b, 0x00483912, 0x0047380f, 0x0044350e, 0x0040300c, 0x00322602, 0x00352b0b, 0x0031280d, 0x00231e08, 0x00121101, 0x00101005, 0x000c1005, 0x000e1208, 0x00101208, 0x00111008, 0x00131008, 0x00171208, 0x0018100a, 0x00191209, 0x001b1108, 0x001d1205, 0x00211408, 0x00241508, 0x00251608, 0x002a1909, 0x002e1909, 0x00301c08, 0x00351c09, 0x00381d08, 0x00392009, 0x003c220a, 0x003e250c, 0x0040240e, 0x003d220b, 0x003c210a, 0x003c2208, 0x003c210a, 0x003b2008, 0x003b1f09, 0x003a1e0a, 0x00381f08, 0x00341c08, 0x00301a06, 0x002f1a08, 0x002c1909, 0x00281609, 0x00261509, 0x00241409, 0x00201408, 0x001c1407, 0x00191208, 0x00181108, 0x00171009, 0x00161009, 0x00161009, 0x00161009, 0x0018130c, 0x0019160c, 0x001c160d, 0x001f180b, 0x00271f0a, 0x00382e10, 0x00423414, 0x00312204, 0x00342206, 0x003c2b0a, 0x0049350c, 0x005c4010, 0x00785614, 0x00b4942b, 0x00ccb322, 0x00cbb50d, 0x00ccb90c, 0x00ccb80a, 0x00cbb414, 0x00aa8305, 0x007b5000, 0x00603c00, 0x004e3404, 0x00462d08, 0x00392701, 0x00332104, 0x002d1d04, 0x00291a06, 0x00251908, 0x001e1506, 0x001b1407, 0x00181207, 0x00171208, 0x00141309, 0x00141009, 0x00131008, 0x00131008, 0x00121008, 0x00121008, 0x00140f09, 0x00121009, 0x00121009, 0x00120f0b, 0x00120f0b, 0x00120f0b, 0x00121008, 0x00141209, 0x00141108, 0x00101008, 0x000a0d05, 0x000a1109, 0x0008110a, 0x00081009, 0x000a130c, 0x0009130c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0008100c, 0x00060e09, 0x0008100b, 0x0009110d, 0x0008100c, 0x0008100c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0007100d, 0x0008100b, 0x0008100b, 0x0008100b, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x0007100b, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005110b, 0x0004100a, 0x00040f09, 0x0004100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0008100b, 0x0009110d, 0x0008100c, 0x0009110d, 0x000c130d, 0x000d140e, 0x000d150f, 0x000e1710, 0x000f1811, 0x00101812, 0x00141815, 0x00141914, 0x00161b15, 0x00161b14, 0x00171d14, 0x00171e14, 0x00171e14, 0x00161d14, 0x00171c13, 0x00171912, 0x00141812, 0x00141612, 0x00131714, 0x000e1811, 0x000e1811, 0x000a140d, 0x0009130d, 0x00091310, 0x0008120e, 0x0008120f, 0x0008120f, 0x0008100b, 0x0008100b, 0x0008100b, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0045470e, 0x00494a10, 0x004d4e0f, 0x00515110, 0x00545510, 0x00726612, 0x00cca417, 0x00c6a016, 0x00615f12, 0x00606013, 0x00606013, 0x00616112, 0x00616112, 0x00616112, 0x00616112, 0x005e5f13, 0x00a78b15, 0x00cca418, 0x00a08614, 0x00595a12, 0x00585910, 0x00565711, 0x00545510, 0x00525310, 0x00515110, 0x004f5010, 0x004d4e0f, 0x004c4d0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545511, 0x00565710, 0x00585911, 0x005e5c12, 0x00c39e17, 0x00cca418, 0x00766b14, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005c5c11, 0x00867414, 0x00c8a116, 0x00b09014, 0x004f5010, 0x00505010, 0x004c4d0f, 0x0048490f, 0x0044450e, 0x0040400d, 0x003b3c0c, 0x0038380c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x0020230a, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060d0b, 0x00060d0b, 0x00060e09, 0x00050f08, 0x00040f08, 0x00040f08, 0x00041007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00040c08, 0x00040c08, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00060e09, 0x0008100b, 0x00060e09, 0x00050d09, 0x00070f0a, 0x0008100c, 0x000a120e, 0x000a120d, 0x000c140d, 0x000d140f, 0x00101610, 0x0010160f, 0x00101710, 0x00111810, 0x00151a13, 0x00171c15, 0x00191c16, 0x001b1d18, 0x001c1e16, 0x001e1d14, 0x001f1c14, 0x001e1d14, 0x001d1e16, 0x001b1c15, 0x00181c13, 0x00181b12, 0x00141810, 0x00131610, 0x00131612, 0x00101411, 0x000c140f, 0x000c140f, 0x0008110c, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x00040f08, 0x00040f08, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x0009110e, 0x0009110e, 0x0008100c, 0x0007100d, 0x0006100d, 0x0007110c, 0x0008100a, 0x000a0f07, 0x000b0f06, 0x000c0f06, 0x000c0f06, 0x000c0f06, 0x000c0f06, 0x000c0e06, 0x000c0e06, 0x000c1007, 0x000c1007, 0x000f1008, 0x000f1007, 0x00101008, 0x00131107, 0x00141208, 0x0014130a, 0x00151108, 0x00191408, 0x001e1809, 0x00221a09, 0x00271c07, 0x002d1f08, 0x0034240a, 0x003b2d0b, 0x0044340c, 0x00523b0c, 0x0066480c, 0x00876814, 0x00c2a732, 0x00ccb61f, 0x00ccb90c, 0x00ccb90a, 0x00ccb90c, 0x00ccb90c, 0x00ccb810, 0x00af9009, 0x007c5800, 0x00604200, 0x004c3903, 0x003f3005, 0x00352801, 0x0042340d, 0x00483811, 0x0044350c, 0x0043340c, 0x0040310d, 0x00342805, 0x00322809, 0x00342a10, 0x0027210c, 0x00191707, 0x00101105, 0x000d0f05, 0x000d1107, 0x00101208, 0x00131209, 0x00121006, 0x00161108, 0x0018100a, 0x0019110b, 0x001b1108, 0x001d1205, 0x00221609, 0x00241609, 0x00251608, 0x00281808, 0x002e1a0a, 0x00311b08, 0x00341b07, 0x00381d09, 0x0039200a, 0x003a2108, 0x003b2209, 0x003e230d, 0x003c2109, 0x00391e07, 0x003c2007, 0x00391e06, 0x00391e06, 0x00381c07, 0x00381c08, 0x00371d07, 0x00341c06, 0x00311b07, 0x002f1907, 0x002c1808, 0x00281408, 0x00241408, 0x00221207, 0x001f1307, 0x001c1306, 0x00181108, 0x00181108, 0x0018110a, 0x00181009, 0x00170f08, 0x00170f08, 0x0018120b, 0x001a150c, 0x001c140c, 0x0021180c, 0x0029200b, 0x00382f0e, 0x00443815, 0x00322402, 0x00352304, 0x003c2c09, 0x00483409, 0x005b3f0f, 0x00785514, 0x00b4922b, 0x00ccb122, 0x00cbb40e, 0x00ccb80b, 0x00ccb80a, 0x00cbb214, 0x00ab8205, 0x007a4e00, 0x00603b00, 0x004e3104, 0x00472d0b, 0x00392602, 0x00322104, 0x002d1d04, 0x00291a06, 0x00251908, 0x001e1506, 0x001b1407, 0x00181207, 0x00171208, 0x00141309, 0x00131109, 0x00121108, 0x00111108, 0x00101008, 0x00111008, 0x00121009, 0x00121009, 0x00121009, 0x00120f0b, 0x00120d0a, 0x00120d0a, 0x00130f08, 0x00141109, 0x00151208, 0x00101008, 0x000c0e06, 0x000c1009, 0x000b130c, 0x0008110b, 0x0008110b, 0x000c140e, 0x0008110b, 0x0008110a, 0x0008110b, 0x0009120b, 0x0009120c, 0x0008110a, 0x0008110a, 0x0008110a, 0x0008110b, 0x0007110c, 0x0006100b, 0x0006100b, 0x0008120c, 0x0009120c, 0x00081009, 0x00081009, 0x00081009, 0x00061009, 0x00061009, 0x00061009, 0x00061009, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00060f0a, 0x00040e0b, 0x00050f0c, 0x00050f0c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x0006100c, 0x0007130d, 0x0007130d, 0x0006120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0005110b, 0x0005110b, 0x0006100b, 0x0006100b, 0x00050d09, 0x0008100c, 0x0009110c, 0x000a120e, 0x000c120e, 0x000d1410, 0x000c140e, 0x000c140e, 0x000d150f, 0x000f1811, 0x00141815, 0x00141914, 0x00151a14, 0x00161b14, 0x00171d14, 0x00171e14, 0x00171e14, 0x00161c13, 0x00171c11, 0x00181b11, 0x00161811, 0x00141711, 0x00131712, 0x000e1811, 0x000e1811, 0x000b150e, 0x000a140e, 0x000a1410, 0x00091310, 0x0008120f, 0x0008120f, 0x0008100c, 0x0008100c, 0x0008100c, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280b, 0x00292b0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0c, 0x0040400d, 0x0044450d, 0x0048490f, 0x004c4d10, 0x00505010, 0x00545510, 0x00716512, 0x00cca417, 0x00c6a016, 0x00605d11, 0x005e5f13, 0x00606013, 0x00606013, 0x00606012, 0x00606012, 0x00606013, 0x005d5e13, 0x00a78b15, 0x00cca418, 0x00a08614, 0x00595a12, 0x00585810, 0x00555610, 0x00535410, 0x00525310, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004c4d0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00525310, 0x00545510, 0x00565710, 0x00595a11, 0x005e5c13, 0x00c39e17, 0x00cca418, 0x00756a13, 0x005e5f13, 0x00606013, 0x00606013, 0x005e5f13, 0x005d5e12, 0x005c5d11, 0x005b5b11, 0x00867414, 0x00c8a116, 0x00b09014, 0x004d4e10, 0x004f5010, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0036370c, 0x0032330c, 0x002d2f0c, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180e, 0x000f130f, 0x00060e08, 0x00060e08, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e08, 0x00050e08, 0x00040f08, 0x00040f08, 0x00041007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f07, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060e09, 0x00060f09, 0x00060e09, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x00060e09, 0x0008100b, 0x00060e09, 0x00070f0a, 0x0009110c, 0x0009110c, 0x0009110e, 0x000c140e, 0x000c140e, 0x000f1610, 0x00101710, 0x00101711, 0x00111810, 0x00131a12, 0x00161b14, 0x00171c15, 0x001a1c17, 0x001c1e18, 0x001c1e16, 0x001e1d14, 0x001e1d14, 0x001d1e14, 0x001b1c14, 0x00181c13, 0x00181a13, 0x00171913, 0x00141611, 0x00131410, 0x00101410, 0x000e1410, 0x000b130f, 0x000a130e, 0x0006100b, 0x0007110d, 0x0007110d, 0x0006100c, 0x0006100c, 0x00040f09, 0x00040e08, 0x00051009, 0x00051009, 0x0005100a, 0x0005100a, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0007110d, 0x0007110d, 0x0008120f, 0x0008120f, 0x000b1310, 0x000b1310, 0x000b1310, 0x00091310, 0x0008120f, 0x0007110c, 0x0009100a, 0x000a0f08, 0x000b0f07, 0x000c0f06, 0x000c0f06, 0x000c0f05, 0x000c0f04, 0x000c0e04, 0x000c0f04, 0x000c1005, 0x000c1005, 0x000f1008, 0x000f1007, 0x00101008, 0x00131107, 0x00131308, 0x0014130a, 0x00141208, 0x00181408, 0x001e1809, 0x00221a09, 0x00271c07, 0x002d1f08, 0x00342509, 0x003c2d0c, 0x0044340c, 0x00523b0c, 0x0068480c, 0x00876813, 0x00c2a732, 0x00ccb61e, 0x00ccb90c, 0x00ccb90a, 0x00ccb90c, 0x00cbbb0c, 0x00ccb910, 0x00af9009, 0x007d5800, 0x00604400, 0x004c3a04, 0x00413208, 0x00382b04, 0x0044370f, 0x0047380f, 0x0044340b, 0x0042340c, 0x00413410, 0x00342806, 0x002e2304, 0x00342a11, 0x002b2510, 0x00191605, 0x00111104, 0x000e1006, 0x000d1007, 0x00101208, 0x00111208, 0x00121006, 0x00161108, 0x0018100a, 0x0019110a, 0x001b1108, 0x001d1205, 0x00221609, 0x00241608, 0x00251608, 0x00281808, 0x002d1a09, 0x00301a08, 0x00331a06, 0x00351c08, 0x00381f09, 0x00381f08, 0x00392008, 0x003c210b, 0x003b2008, 0x003c2008, 0x003a1f06, 0x00371c04, 0x00381c05, 0x00371c06, 0x00371b08, 0x00371c08, 0x00341c06, 0x00321b07, 0x002f1907, 0x002c1809, 0x00281408, 0x00241408, 0x00221207, 0x001f1306, 0x001b1305, 0x00181107, 0x00181108, 0x0018110a, 0x00181009, 0x00170f08, 0x00170f08, 0x0018120b, 0x001a150c, 0x001c140c, 0x0021180c, 0x0029200a, 0x00382f0c, 0x00443813, 0x00342502, 0x00352401, 0x003e2d09, 0x0048340a, 0x005c3f0e, 0x00785514, 0x00b3932b, 0x00ccb222, 0x00cab40e, 0x00ccb80c, 0x00ccb80a, 0x00cbb214, 0x00ab8205, 0x007a4f00, 0x00603b00, 0x004d3003, 0x00472d0b, 0x003a2802, 0x00322104, 0x002d1d04, 0x00291a06, 0x00251908, 0x001e1506, 0x001b1407, 0x00181207, 0x00171208, 0x00141309, 0x00131109, 0x00121108, 0x00111108, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00121009, 0x00120f0b, 0x00140f0b, 0x00130e0a, 0x00140f08, 0x0015110a, 0x00151208, 0x00111008, 0x000d0f07, 0x00080e06, 0x000a120c, 0x000c140e, 0x000d140f, 0x00101711, 0x000d150e, 0x000e150e, 0x000c140c, 0x000a110a, 0x00091109, 0x00091008, 0x00091008, 0x00091008, 0x00081109, 0x0007110a, 0x00061009, 0x00061009, 0x0008130c, 0x0009120c, 0x00081009, 0x00081009, 0x00081008, 0x00061008, 0x00061108, 0x00061009, 0x0006100a, 0x0008110a, 0x0008110a, 0x0008100b, 0x0008100c, 0x0008100c, 0x0006100d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00050f0c, 0x00050f0c, 0x00040e0b, 0x0006100c, 0x0008120d, 0x0007130d, 0x0006120c, 0x0006120c, 0x0006120c, 0x0006120c, 0x0007120c, 0x0007120c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100c, 0x0009110d, 0x0009110d, 0x000a120e, 0x000a120e, 0x000c1410, 0x000c140f, 0x000c140f, 0x000d1510, 0x000f1812, 0x00141815, 0x00141914, 0x00151a14, 0x00161b14, 0x00171c14, 0x00171e14, 0x00171e14, 0x00161c13, 0x00161c12, 0x00181b11, 0x00161810, 0x00141710, 0x00131810, 0x000f1811, 0x000e1811, 0x000c150e, 0x000a140e, 0x000a1410, 0x00091310, 0x0008120f, 0x0008120f, 0x0008100c, 0x0008100c, 0x0008100c, 0x00070f0a, 0x0008100b, 0x0008100b, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00141809, 0x00191c09, 0x00202309, 0x00202309, 0x0026280c, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0038380c, 0x003b3c0d, 0x0040400e, 0x0044450e, 0x0048490f, 0x004c4d0f, 0x00505010, 0x00535410, 0x00716412, 0x00cca316, 0x00c5a016, 0x00605d11, 0x005d5e12, 0x00606013, 0x00606012, 0x00606013, 0x00606013, 0x00606013, 0x005c5d13, 0x00a68b15, 0x00cca418, 0x00a08514, 0x00585912, 0x00585910, 0x00555610, 0x00535410, 0x00525310, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004d4e0f, 0x004c4d0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545510, 0x00565710, 0x00585910, 0x005e5c12, 0x00c39e17, 0x00cca418, 0x00756a13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005b5b12, 0x00867414, 0x00c8a016, 0x00b09014, 0x004c4d10, 0x004f5010, 0x004c4d0f, 0x0048490e, 0x0044450e, 0x0040400e, 0x003c3e0d, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x00060e08, 0x00060e08, 0x00070d08, 0x00060e08, 0x00060e08, 0x00040f08, 0x00060e09, 0x00060e09, 0x00080f0b, 0x00080f0a, 0x00060e08, 0x00050e07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f07, 0x00040f07, 0x00051008, 0x00051008, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00081009, 0x00081009, 0x00060e08, 0x00060e08, 0x00081009, 0x00081009, 0x00081009, 0x0008110a, 0x000b130c, 0x000e140e, 0x00101610, 0x00111812, 0x00121813, 0x00151a13, 0x00151a13, 0x00161b14, 0x00191c16, 0x001d1c18, 0x001e1c18, 0x001e1d16, 0x001e1d14, 0x001e1d16, 0x001c1e16, 0x001b1c14, 0x00181b12, 0x00151a13, 0x00141811, 0x00121710, 0x0010150f, 0x000e1410, 0x000c1410, 0x000c140f, 0x000a140f, 0x0008130e, 0x0006110d, 0x0006110d, 0x0005100c, 0x0005100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00040e0b, 0x0006100b, 0x00061009, 0x00051008, 0x00051008, 0x0005100a, 0x0005100a, 0x0006110b, 0x0006120c, 0x0005120c, 0x0005110b, 0x0005110b, 0x0005120c, 0x0006120c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0006110c, 0x0006120c, 0x0008130d, 0x0008120d, 0x0007100c, 0x0009120e, 0x000a120e, 0x000a120e, 0x000a1210, 0x0008100c, 0x00091009, 0x000a0f08, 0x000a0f08, 0x000a0f07, 0x000b0f05, 0x000c0f04, 0x000c0f04, 0x000b0f04, 0x000a1004, 0x000b1005, 0x000b1005, 0x000c1007, 0x000c1005, 0x000d0f05, 0x00101108, 0x00131209, 0x00131209, 0x00141208, 0x00181408, 0x001c1709, 0x00211808, 0x00271c08, 0x002c1f08, 0x00322408, 0x003a2e0b, 0x0044340c, 0x00523b0c, 0x0066480c, 0x00856611, 0x00c0a630, 0x00cbb61f, 0x00cbba0b, 0x00cbba0c, 0x00ccbb0c, 0x00ccba0e, 0x00cbb80e, 0x00ac8d09, 0x007c5700, 0x00614400, 0x004d3c04, 0x00413209, 0x00382b04, 0x0044370e, 0x0045380e, 0x0045380c, 0x00413409, 0x003f320c, 0x003a2f0d, 0x00281d01, 0x0033280f, 0x002a240f, 0x001c1a08, 0x00121204, 0x000f1007, 0x000e1006, 0x000e1208, 0x00101108, 0x00131107, 0x00151007, 0x00181009, 0x00181009, 0x001c1208, 0x001d1205, 0x00211509, 0x00241609, 0x00241608, 0x0028180a, 0x002c1a0a, 0x002f1a08, 0x00311807, 0x00351806, 0x00371b08, 0x00371b08, 0x00351c08, 0x00381f08, 0x00381f08, 0x00371e08, 0x00371e07, 0x00381e06, 0x00361c07, 0x00351c07, 0x00341907, 0x00351807, 0x00341907, 0x00311908, 0x002e1708, 0x002b1709, 0x0028140a, 0x0024130a, 0x00221209, 0x001d1107, 0x001c1106, 0x00191007, 0x00181108, 0x0018100a, 0x00171009, 0x00151008, 0x00151008, 0x0018120b, 0x00191409, 0x001b130a, 0x0020180a, 0x00281f08, 0x003c330f, 0x00453914, 0x00342603, 0x00362404, 0x003e2d09, 0x00483409, 0x005c400d, 0x00785514, 0x00b3932b, 0x00ccb222, 0x00cbb40e, 0x00ccb80c, 0x00ccb80a, 0x00cbb213, 0x00ab8204, 0x007b4f00, 0x00603c00, 0x00513408, 0x00462c0a, 0x003b2804, 0x002e1d01, 0x002d1d05, 0x00291a06, 0x00251908, 0x001e1504, 0x001a1305, 0x00181308, 0x0018130a, 0x00141209, 0x00121008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00121009, 0x00121009, 0x00140f09, 0x00140f09, 0x00140f09, 0x00151009, 0x00140f08, 0x00121008, 0x000d0e06, 0x000c0d08, 0x000e120b, 0x0010140e, 0x00151712, 0x00171712, 0x00181711, 0x00171710, 0x00171710, 0x0016160f, 0x0015150e, 0x0014140c, 0x0012140c, 0x0010140b, 0x000c1209, 0x000a140a, 0x000b140d, 0x000a140c, 0x0008120c, 0x0008120c, 0x0007110c, 0x0007110c, 0x0007110d, 0x0006110e, 0x0006110e, 0x0007110d, 0x0007100d, 0x0006100a, 0x00061009, 0x00061009, 0x00071008, 0x0008100b, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100c, 0x0007110c, 0x0007110c, 0x0006100b, 0x0006100b, 0x0006100b, 0x0008100b, 0x0008100c, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0008120c, 0x000c140f, 0x000c140f, 0x000c1511, 0x000c1512, 0x000c1713, 0x000e1814, 0x00121816, 0x00141815, 0x00151916, 0x00151a14, 0x00181c17, 0x00191d17, 0x00181d15, 0x00171c14, 0x00171c14, 0x00171c15, 0x00171c15, 0x00141912, 0x00141811, 0x00121812, 0x00111812, 0x000f150f, 0x000c140f, 0x000c1411, 0x000c1310, 0x00091310, 0x00081410, 0x0009110d, 0x0009110d, 0x0008100c, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002d2f0a, 0x0030310c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x00525310, 0x00716412, 0x00cca316, 0x00c5a017, 0x00605c12, 0x005d5e11, 0x005e5f13, 0x00606013, 0x00606013, 0x00606013, 0x00606013, 0x005c5c13, 0x00a68b15, 0x00cca417, 0x00a08514, 0x00585912, 0x00585810, 0x00565711, 0x00535410, 0x00525310, 0x00515110, 0x00505010, 0x004f5010, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004f5010, 0x004f5010, 0x00505010, 0x00525310, 0x00535410, 0x00555611, 0x00585810, 0x00585911, 0x005e5c13, 0x00c39d17, 0x00cca417, 0x00756a12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5c11, 0x005b5b12, 0x00867414, 0x00c8a016, 0x00b09014, 0x004c4d10, 0x004f5010, 0x004b4c0f, 0x0047480e, 0x0043440e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002d2f0a, 0x00292b0a, 0x0026280b, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00070f08, 0x00070f08, 0x00080e08, 0x00070f08, 0x00070f08, 0x00051008, 0x00051008, 0x00051008, 0x00070d08, 0x00080f0b, 0x0008100a, 0x00050f07, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00051007, 0x00051008, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x00081009, 0x0008100a, 0x000a130c, 0x000c140e, 0x000f150f, 0x00101711, 0x00111812, 0x00131813, 0x00151a13, 0x00151a13, 0x00171c14, 0x00191c16, 0x001d1c18, 0x001e1c18, 0x001e1d16, 0x001e1d14, 0x001e1d16, 0x001c1c14, 0x001b1c14, 0x00181b12, 0x00151a13, 0x00141811, 0x00131810, 0x0012160f, 0x000e150f, 0x000b1510, 0x000b1410, 0x0008120d, 0x0006100b, 0x0004100c, 0x0004100c, 0x0005100c, 0x0005100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x00040e0b, 0x0006100b, 0x00061009, 0x0008110b, 0x0008110b, 0x0008110c, 0x0008110c, 0x0007110c, 0x0006100b, 0x0006100a, 0x00051109, 0x00061109, 0x0006120a, 0x0007110a, 0x000b110c, 0x000b110c, 0x000a100a, 0x0009100a, 0x000b130c, 0x000b130c, 0x000c140d, 0x000c140d, 0x000d140e, 0x00101610, 0x000e140e, 0x000e140e, 0x000c130f, 0x0009100b, 0x00090f08, 0x000a0f08, 0x000a0f06, 0x000a0f06, 0x000b0f05, 0x000c0f04, 0x000c0f04, 0x000a1004, 0x000a1004, 0x000b1005, 0x000b1005, 0x000b1007, 0x000c1005, 0x000d0f05, 0x00101108, 0x00111309, 0x00111309, 0x00131308, 0x00171509, 0x001c170a, 0x00231809, 0x00271c08, 0x002c2009, 0x00322408, 0x003a2e0b, 0x0044350c, 0x00523c0c, 0x0066480e, 0x00856611, 0x00c0a630, 0x00cbb61f, 0x00cab90a, 0x00cbba0c, 0x00cbba0c, 0x00cbbb0e, 0x00c9b810, 0x00ac8c08, 0x007c5700, 0x00624500, 0x004f3c05, 0x0044340c, 0x003b2d07, 0x0044380f, 0x0045380d, 0x0045390b, 0x00403408, 0x003e330c, 0x00392f0e, 0x00261c00, 0x002e240b, 0x002a240f, 0x00201e0b, 0x00111302, 0x000c0e04, 0x000c0e04, 0x000d1107, 0x00101208, 0x00121107, 0x00141007, 0x00181009, 0x00181009, 0x001c1208, 0x001d1205, 0x00211509, 0x00231709, 0x00231708, 0x0026180a, 0x002a1a0b, 0x002c1a08, 0x00301806, 0x00331906, 0x00351c08, 0x00351c09, 0x00351c09, 0x00361f08, 0x00361f08, 0x00361f08, 0x00361f08, 0x00381e08, 0x00361c08, 0x00351c08, 0x00341907, 0x00331806, 0x00321808, 0x00301808, 0x002e1808, 0x002c1709, 0x0027150a, 0x0024140a, 0x0021140a, 0x001e1208, 0x001c1307, 0x00181107, 0x00181108, 0x0017110a, 0x00151109, 0x00141008, 0x00151009, 0x0017130b, 0x00191409, 0x001b1308, 0x00201808, 0x00282008, 0x003d3210, 0x00453914, 0x00352804, 0x00362404, 0x003f2e08, 0x00493609, 0x005c400c, 0x00775512, 0x00b2932b, 0x00cab322, 0x00c9b50e, 0x00cab80c, 0x00ccb80a, 0x00cbb313, 0x00ac8406, 0x007c5000, 0x00603c00, 0x00513408, 0x00462c09, 0x003c2805, 0x002f1d02, 0x002d1d05, 0x00291a06, 0x00251908, 0x001e1504, 0x001a1304, 0x00181309, 0x0018130a, 0x00141209, 0x00121008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00121009, 0x00121009, 0x0013100a, 0x00121009, 0x00121009, 0x00141209, 0x00140f09, 0x00121008, 0x000e0d06, 0x000c0f06, 0x000e110a, 0x0012140e, 0x00151410, 0x0016140f, 0x0018140d, 0x0018130d, 0x0018130c, 0x0017120b, 0x0017120b, 0x0014130a, 0x0014130a, 0x0016180e, 0x0014180f, 0x0013180f, 0x0012170e, 0x0010150e, 0x000e140c, 0x000b110c, 0x000a110c, 0x0009100b, 0x0009100c, 0x0007110c, 0x0006110c, 0x0007110c, 0x0007110c, 0x0008120c, 0x0008120c, 0x0008100b, 0x00070f08, 0x00081009, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0006100b, 0x0007100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0008100c, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0006100b, 0x0007110c, 0x000a140f, 0x000a140f, 0x000b1411, 0x000b1411, 0x000c1713, 0x000c1713, 0x00101614, 0x00141814, 0x00141815, 0x00151914, 0x00161b17, 0x00171b18, 0x00171c16, 0x00171c14, 0x00171c14, 0x00171c15, 0x00171c15, 0x00161b14, 0x00141811, 0x00131712, 0x00111812, 0x000f150f, 0x000c140f, 0x000c1411, 0x000c1411, 0x00091310, 0x00081410, 0x0008120d, 0x0008120d, 0x0008120d, 0x0008110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002c2d0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x0040400c, 0x0043440e, 0x0047480e, 0x004b4c0f, 0x004f5010, 0x00525310, 0x00706411, 0x00cca316, 0x00c5a017, 0x00605c12, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x00606013, 0x005e5f13, 0x005e5f13, 0x005c5c13, 0x00a68a14, 0x00cca417, 0x00a08514, 0x00585912, 0x00585910, 0x00565711, 0x00545511, 0x00535410, 0x00515110, 0x00505010, 0x004f5010, 0x004f5010, 0x004d4e10, 0x004f5010, 0x004f5010, 0x00505010, 0x00515110, 0x00535410, 0x00545510, 0x00555611, 0x00565710, 0x00595a11, 0x005e5c13, 0x00c39e17, 0x00cca417, 0x00756a12, 0x005d5e12, 0x005e5f13, 0x005e5f12, 0x005d5e11, 0x005d5e11, 0x005c5c11, 0x00595a12, 0x00867413, 0x00c8a016, 0x00b09014, 0x004c4d10, 0x004d4e0f, 0x004b4c10, 0x0047480e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x00080e08, 0x00080e08, 0x00080e08, 0x00070f08, 0x00070f08, 0x00051008, 0x00051008, 0x00051008, 0x0009100b, 0x0009100c, 0x0008110b, 0x00071008, 0x00051007, 0x00051007, 0x00051007, 0x00040f06, 0x00040f06, 0x00040f06, 0x00040f06, 0x00061108, 0x00041008, 0x0008100b, 0x0008100b, 0x00070f0a, 0x00070f0a, 0x00081009, 0x00081009, 0x0009120c, 0x0008120c, 0x0008110b, 0x0008110a, 0x0008110a, 0x000a130c, 0x000c140e, 0x00101610, 0x00101711, 0x00131712, 0x00141813, 0x00181a14, 0x00181c15, 0x00191c16, 0x001a1d17, 0x001c1d18, 0x001c1d18, 0x001c1e16, 0x001c1e14, 0x001c1d15, 0x001a1b14, 0x001a1b14, 0x00171913, 0x00141813, 0x00131811, 0x00101610, 0x0010150e, 0x000c140e, 0x00091310, 0x0008120e, 0x0006100c, 0x0006100c, 0x00030f0b, 0x00030f0b, 0x0005100c, 0x0005100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100b, 0x00061009, 0x0007110a, 0x0007110a, 0x0007110c, 0x0007110c, 0x0007110b, 0x00061009, 0x00050f08, 0x00081009, 0x0009120b, 0x000a130b, 0x000b130b, 0x000c130c, 0x000c130c, 0x000f130c, 0x000e130c, 0x0010150e, 0x00111610, 0x0010150e, 0x0010150e, 0x00141811, 0x00161912, 0x0011160f, 0x0010140d, 0x000d120b, 0x00090e07, 0x00090e06, 0x00090f05, 0x000a1004, 0x000a1004, 0x000b1005, 0x000c0f06, 0x000c0f06, 0x000a1004, 0x000a1004, 0x000b1005, 0x000b1005, 0x000b1007, 0x000c1005, 0x000d0f05, 0x00101108, 0x00111309, 0x0013120b, 0x00141109, 0x0018140b, 0x001d160a, 0x00231809, 0x00271c08, 0x002c2009, 0x00322408, 0x003a2d0b, 0x0044350c, 0x00503c0d, 0x0065480d, 0x00846311, 0x00c0a430, 0x00ccb520, 0x00ccb80b, 0x00cab90a, 0x00cbb90c, 0x00cbb90d, 0x00cbb810, 0x00aa8a08, 0x007c5700, 0x00624500, 0x004f3c04, 0x0044350b, 0x003c2e07, 0x00483a11, 0x0045380d, 0x0044380a, 0x00403408, 0x00392e08, 0x003b3010, 0x002b2104, 0x00291f06, 0x0028220c, 0x00201e0b, 0x00141404, 0x000d0d02, 0x000c0e04, 0x000c1005, 0x00101109, 0x00131208, 0x00161108, 0x00181009, 0x00181009, 0x001c1208, 0x001d1205, 0x00211408, 0x00231708, 0x00241809, 0x00241809, 0x00281a0a, 0x002c1a08, 0x002e1906, 0x00311906, 0x00341b08, 0x00341b08, 0x00341b08, 0x00341c08, 0x00341c08, 0x00341c08, 0x00341c08, 0x00341b06, 0x00341b08, 0x00341a0a, 0x00341a0a, 0x00331806, 0x00311908, 0x00311a09, 0x002e1908, 0x002a1709, 0x00261509, 0x00231409, 0x00211409, 0x001c1308, 0x001a1308, 0x00181207, 0x00151108, 0x00141109, 0x00141109, 0x00131008, 0x00141109, 0x0017140c, 0x00181409, 0x001b1308, 0x00211709, 0x002a2008, 0x003c3110, 0x00443812, 0x00352804, 0x00382505, 0x00402f09, 0x0049370a, 0x005c400c, 0x00755410, 0x00af8f27, 0x00ccb323, 0x00cab40e, 0x00ccb80c, 0x00ccb80a, 0x00cbb412, 0x00ac8606, 0x007c5100, 0x00603c00, 0x004f3308, 0x00432b09, 0x003b2804, 0x002e1c01, 0x002d1d05, 0x00291a06, 0x00251908, 0x001e1504, 0x001a1304, 0x00181309, 0x0018130a, 0x00141209, 0x00121008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00121009, 0x00110f08, 0x00101009, 0x000f0e08, 0x00100f08, 0x00110f08, 0x00121009, 0x00100e08, 0x000e0d06, 0x000e1109, 0x000d1209, 0x0010140b, 0x0014140c, 0x0014130a, 0x0016110a, 0x00181309, 0x00181309, 0x00181309, 0x00181108, 0x00171309, 0x00161409, 0x00151409, 0x0014140a, 0x0015170d, 0x0016170f, 0x00171810, 0x0015170f, 0x0014160f, 0x00141610, 0x0014150f, 0x0010130e, 0x000c140d, 0x000c140d, 0x000c140d, 0x0009120b, 0x0008110a, 0x0008110a, 0x0009120b, 0x00081009, 0x00081009, 0x0006100b, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x00070f0a, 0x0008100c, 0x0006100b, 0x0005100a, 0x0005100a, 0x0006100b, 0x0007100a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x00070f0a, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0008100b, 0x0007110c, 0x0007110c, 0x0009130e, 0x0009130e, 0x00091310, 0x00091310, 0x000b1411, 0x000c1713, 0x00101614, 0x00111613, 0x00111613, 0x00141813, 0x00151916, 0x00151917, 0x00171b17, 0x00171c16, 0x00171c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00151a14, 0x00131712, 0x00111812, 0x00101710, 0x000d150f, 0x000d1510, 0x000d1510, 0x000a140f, 0x000a140f, 0x0009130e, 0x0009130e, 0x0008120d, 0x0008120d, 0x0009110d, 0x0009110d, 0x0008100c, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x0026280a, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x00515110, 0x00706412, 0x00cca316, 0x00c5a016, 0x005e5c12, 0x005c5c11, 0x005d5e11, 0x005e5f12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005b5b12, 0x00a68a14, 0x00cca417, 0x00a08514, 0x00585912, 0x00585810, 0x00565711, 0x00555611, 0x00535410, 0x00525310, 0x00515110, 0x00505010, 0x00505010, 0x004f5010, 0x00505010, 0x00505010, 0x00515110, 0x00525310, 0x00535410, 0x00545511, 0x00565711, 0x00585910, 0x00595a12, 0x005e5c12, 0x00c39e17, 0x00cca418, 0x00756a13, 0x005d5e12, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x005b5b12, 0x00867413, 0x00c8a016, 0x00b08f14, 0x004c4d10, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x0040400c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x002c2d0a, 0x0026280a, 0x0026280c, 0x00202309, 0x00202309, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x000a100a, 0x000a100a, 0x000a100a, 0x0008110a, 0x0008110a, 0x0007110a, 0x0007110a, 0x0007110a, 0x0009100b, 0x0009100c, 0x0008110b, 0x00081109, 0x00061108, 0x00071208, 0x00071208, 0x00061108, 0x00061108, 0x00061108, 0x00061108, 0x00071208, 0x00051008, 0x0008100b, 0x0008100b, 0x0009110c, 0x0008100c, 0x0008110a, 0x0008110a, 0x0009120c, 0x0009140c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000c140e, 0x000e1510, 0x00101711, 0x00131813, 0x00141914, 0x00151a14, 0x00181c15, 0x001a1d17, 0x001b1e18, 0x001c1f18, 0x001c1d18, 0x001c1d18, 0x001c1e16, 0x001c1d14, 0x001a1b14, 0x001a1b14, 0x00181813, 0x00141811, 0x00131712, 0x00101610, 0x000f150f, 0x000d140e, 0x000a120d, 0x0007110d, 0x0006100c, 0x0006100c, 0x0006100c, 0x0004100c, 0x00030f0b, 0x0005100c, 0x0005100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100c, 0x0006100a, 0x00061009, 0x0007110a, 0x0007110a, 0x0009130d, 0x0009130e, 0x0009120c, 0x000a130c, 0x000d140d, 0x000f150e, 0x0010160f, 0x0011170e, 0x0012170e, 0x0014170f, 0x0013160e, 0x0013140c, 0x0012150c, 0x0012150c, 0x0013160d, 0x0012150c, 0x0012150c, 0x0014160d, 0x0016180e, 0x0013160c, 0x0011140c, 0x000e1209, 0x00090f05, 0x00080e04, 0x00070e03, 0x00090e02, 0x000b0e03, 0x000c0f05, 0x000c0f07, 0x000c0f06, 0x000a1004, 0x000a1004, 0x000b1005, 0x000b1005, 0x000b1007, 0x000c1005, 0x000d0f05, 0x00101108, 0x00111309, 0x0013120b, 0x00141109, 0x0018140b, 0x001d160a, 0x00231809, 0x00271c08, 0x002c2008, 0x00332408, 0x003a2d0b, 0x0044350c, 0x00523c0d, 0x0064460e, 0x00846210, 0x00c0a330, 0x00ccb420, 0x00ccb80c, 0x00cab90a, 0x00cab80c, 0x00cab80c, 0x00ccb811, 0x00a68606, 0x00795400, 0x00604300, 0x004c3a02, 0x00413208, 0x00382b04, 0x00463810, 0x0045380d, 0x00423509, 0x003f3307, 0x003b3008, 0x003a3010, 0x002e2407, 0x00281f07, 0x0028220c, 0x00201e0b, 0x00141404, 0x000e0e03, 0x000c0e04, 0x000c0f04, 0x0010120a, 0x00131208, 0x00161108, 0x00181009, 0x00181009, 0x001c1208, 0x001d1206, 0x00201408, 0x00221608, 0x00231809, 0x00231808, 0x00261909, 0x002b1b08, 0x002c1a06, 0x002e1a05, 0x00301c07, 0x00311c08, 0x00321c08, 0x00331a07, 0x00331a07, 0x00331a07, 0x00331a07, 0x00341b08, 0x00341b08, 0x00341a0a, 0x00341a0b, 0x00311906, 0x00311908, 0x00301808, 0x002c1707, 0x00281608, 0x00241409, 0x00211308, 0x001f1308, 0x001b1307, 0x00181208, 0x00161106, 0x00131107, 0x00121108, 0x00131008, 0x00111008, 0x00131209, 0x0017140c, 0x00181409, 0x001b1308, 0x00211709, 0x002b2008, 0x003c300f, 0x00433710, 0x00332400, 0x00342303, 0x003c2c07, 0x00473407, 0x005b3f0c, 0x0074520c, 0x00af8f26, 0x00ccb224, 0x00cbb510, 0x00ccb80b, 0x00ccb80a, 0x00ccb411, 0x00b08909, 0x007d5200, 0x00603c00, 0x004f3207, 0x00422a08, 0x003a2704, 0x00301d02, 0x002d1c05, 0x00291a06, 0x00251907, 0x001e1504, 0x001a1304, 0x00181308, 0x0018130a, 0x00141209, 0x00121008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00121009, 0x00121009, 0x00101009, 0x00100f08, 0x000f100a, 0x000d0f08, 0x000f100a, 0x000f1008, 0x00121009, 0x00100d07, 0x000e0d04, 0x00101108, 0x0010140a, 0x00101409, 0x00121308, 0x00141309, 0x0016140a, 0x00161409, 0x00161409, 0x00151408, 0x00161307, 0x00161408, 0x00161408, 0x00141408, 0x00141409, 0x00151409, 0x0017140a, 0x0017140c, 0x0018160d, 0x0018170e, 0x0018170e, 0x001b1b12, 0x00181810, 0x00171810, 0x00171810, 0x00171810, 0x0014150e, 0x0010140c, 0x000c140c, 0x000a130b, 0x0009120a, 0x0008100a, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x000a120e, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0008100c, 0x0009110c, 0x0008100c, 0x0008100b, 0x0008100b, 0x0008100b, 0x00070f0a, 0x0009110d, 0x0007110c, 0x0007110c, 0x0008120d, 0x0008120d, 0x00091310, 0x00091310, 0x000b1410, 0x000c1512, 0x00101614, 0x00111613, 0x00111613, 0x00141813, 0x00151917, 0x00161a18, 0x00171b18, 0x00171c18, 0x00171c16, 0x00171c15, 0x00171c15, 0x00181d16, 0x00171c15, 0x00141813, 0x00121813, 0x00111812, 0x000f1810, 0x000e1611, 0x000e1611, 0x000b1510, 0x000b1510, 0x0008140e, 0x0008140e, 0x0007130d, 0x0007130d, 0x0009110d, 0x0009110d, 0x0008100c, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x00393b0c, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004d4e0f, 0x00515110, 0x00706311, 0x00cca316, 0x00c59f16, 0x005e5c12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005c5c12, 0x00a68a15, 0x00cca417, 0x00a48814, 0x005b5b12, 0x00585910, 0x00565710, 0x00555611, 0x00545511, 0x00535410, 0x00525310, 0x00515110, 0x00515110, 0x00515110, 0x00515110, 0x00515110, 0x00525310, 0x00535410, 0x00545510, 0x00555611, 0x00585810, 0x00585911, 0x00595a12, 0x00615e12, 0x00c5a017, 0x00cca418, 0x00756b13, 0x005e5f12, 0x005e5f13, 0x005d5e11, 0x005d5e11, 0x005c5d11, 0x005b5b12, 0x00595a12, 0x008c7813, 0x00caa116, 0x00af8f14, 0x004b4c10, 0x004d4e0f, 0x00494a0f, 0x0045470e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x0008110a, 0x0008110a, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x0009130c, 0x0009120a, 0x0009120a, 0x000a130b, 0x000a130b, 0x0009140b, 0x0009140b, 0x0008130a, 0x0008130a, 0x0009120c, 0x0009120c, 0x000a130c, 0x000c120c, 0x000a100a, 0x000a100a, 0x000a130c, 0x0009140c, 0x000b140d, 0x000d140e, 0x000f150f, 0x00101510, 0x00121611, 0x00141813, 0x00151a14, 0x00171914, 0x00181a15, 0x001a1d17, 0x001a1d17, 0x001d1e18, 0x001d1e18, 0x001c1e16, 0x001c1e16, 0x001c1e16, 0x001b1c14, 0x001a1b14, 0x00181a14, 0x00141811, 0x00111611, 0x00101511, 0x00101511, 0x000e1411, 0x000b120e, 0x0008120e, 0x0006120d, 0x0005110b, 0x0005110b, 0x0005110b, 0x0005100a, 0x0006100b, 0x0008100c, 0x0008100c, 0x0009100c, 0x0009100c, 0x0008100c, 0x0009110c, 0x00081009, 0x0009120c, 0x000a140d, 0x000a140d, 0x000f140e, 0x00121410, 0x00131610, 0x00131710, 0x0012170e, 0x0011170e, 0x0012170e, 0x0013160c, 0x0013160c, 0x0015150c, 0x0014140c, 0x0014130a, 0x0014130a, 0x0013140b, 0x0012140b, 0x0013140c, 0x0013140c, 0x0012140a, 0x0013140b, 0x000f1308, 0x0011140a, 0x000c1208, 0x00090e04, 0x00070e03, 0x00070e03, 0x000a0e02, 0x000b0e03, 0x000c0e04, 0x000c0e06, 0x000c0e06, 0x000c1007, 0x000c1007, 0x000c0f08, 0x000c0f08, 0x000f100a, 0x000f1008, 0x000e0f08, 0x00101108, 0x00131209, 0x00131209, 0x0014130a, 0x0019150b, 0x001e1809, 0x00231909, 0x00271c08, 0x002c2008, 0x00342407, 0x003b2d0a, 0x0044350c, 0x00523c0f, 0x0064460d, 0x00846311, 0x00c0a430, 0x00ccb420, 0x00ccb80c, 0x00ccb80a, 0x00ccb80c, 0x00cab80c, 0x00c8b40d, 0x00a48404, 0x00785300, 0x005f4200, 0x004b3802, 0x003f3005, 0x003c2e05, 0x00473910, 0x0045370c, 0x00423408, 0x003e3108, 0x00392e09, 0x00342a0a, 0x002e2408, 0x00231b02, 0x002c2510, 0x00231e0c, 0x00171505, 0x000c0d02, 0x000b0e04, 0x000b0f05, 0x000d1209, 0x0014120c, 0x0016110c, 0x0018100b, 0x00181009, 0x001a1008, 0x001b1007, 0x001c1005, 0x001f1406, 0x00221708, 0x00231708, 0x00251708, 0x00271706, 0x00281805, 0x002c1906, 0x002e1b08, 0x002f1a08, 0x00301a06, 0x00311b08, 0x00331a08, 0x00341908, 0x00341908, 0x00331a07, 0x00331a07, 0x00341b08, 0x00341b08, 0x00341c08, 0x00301807, 0x002d1809, 0x002c180b, 0x00261509, 0x0024140b, 0x00201409, 0x001d1409, 0x001a1208, 0x00181107, 0x00161106, 0x00141007, 0x00121007, 0x00121008, 0x00121008, 0x0014120a, 0x0017140c, 0x0018140b, 0x001b120a, 0x0021180b, 0x002b210b, 0x003b3010, 0x00413510, 0x00342702, 0x00332000, 0x003a2905, 0x00463309, 0x00593d0c, 0x0074520d, 0x00ad8c24, 0x00ccb224, 0x00ccb610, 0x00ccb80a, 0x00ccb808, 0x00cbb411, 0x00b08b0a, 0x007c5300, 0x005f3b00, 0x004e3307, 0x00412b09, 0x00382603, 0x00311e03, 0x002f1d06, 0x002a1c05, 0x00241704, 0x00201604, 0x001b1405, 0x00171106, 0x00161309, 0x00131308, 0x00111007, 0x00101006, 0x00121107, 0x00101006, 0x000e0e05, 0x000f0d06, 0x000f0d07, 0x0010100b, 0x0010100c, 0x000f0f0c, 0x000f0f0c, 0x000d100c, 0x000d100c, 0x00100f08, 0x00101007, 0x000f0f06, 0x00131209, 0x00111309, 0x00101208, 0x00121108, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014140a, 0x00141408, 0x00141407, 0x00141308, 0x00141308, 0x00141408, 0x00141408, 0x0014130a, 0x0014130a, 0x00141308, 0x00141308, 0x00161408, 0x00161408, 0x00171509, 0x0019150c, 0x0019150c, 0x0019160c, 0x0018170c, 0x0018170e, 0x0018180f, 0x00181811, 0x00181810, 0x0016150f, 0x0011130d, 0x000d130e, 0x000c140d, 0x00081009, 0x0008100a, 0x0009120c, 0x00081009, 0x00061009, 0x0008120c, 0x0008120d, 0x0008120d, 0x0008110c, 0x0008120d, 0x0008120f, 0x0008120f, 0x0007110d, 0x0007110d, 0x0008110d, 0x0009110d, 0x0009110c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x0008100c, 0x000a110f, 0x000b100f, 0x000c1110, 0x000d1411, 0x00101513, 0x00101513, 0x00111514, 0x00141716, 0x00141815, 0x00141a16, 0x00151c15, 0x00151c15, 0x00161b15, 0x00181a15, 0x00181b15, 0x00171c17, 0x00151a14, 0x00151a14, 0x00141914, 0x00111812, 0x00111812, 0x000f1713, 0x000f1713, 0x000c1410, 0x000b1510, 0x000c1410, 0x000c1310, 0x000a1410, 0x00091310, 0x000a1210, 0x000a1210, 0x000a1210, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003e400d, 0x0041420e, 0x0045470e, 0x0048490f, 0x004c4d10, 0x00515110, 0x006e6210, 0x00cba216, 0x00c69f15, 0x00646012, 0x005b5b12, 0x005c5d11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005c5c11, 0x00a08615, 0x00cca417, 0x00b09115, 0x005d5c12, 0x00585911, 0x00585810, 0x00565710, 0x00555611, 0x00545511, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00535410, 0x00545511, 0x00555611, 0x00565710, 0x00585910, 0x00595a12, 0x005b5b12, 0x007b6e12, 0x00c8a116, 0x00c49f18, 0x006f6612, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x005c5c12, 0x00595a11, 0x009c8314, 0x00cca316, 0x00ab8c14, 0x004c4d10, 0x004c4d10, 0x00494a0f, 0x0045470e, 0x0041420e, 0x003c3e0c, 0x00393b0c, 0x0036370c, 0x0030310c, 0x002c2d0a, 0x0026280a, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130e, 0x000f130f, 0x0009120c, 0x0009120c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000b140d, 0x000c140d, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x000a130c, 0x0009120a, 0x0009120a, 0x000a130b, 0x000a130b, 0x000a140c, 0x000a140c, 0x0009140b, 0x0009140b, 0x000a130c, 0x000a130c, 0x000a130c, 0x000c120c, 0x000c120c, 0x000b110c, 0x000c140d, 0x000a140d, 0x000c130d, 0x000d140e, 0x00101510, 0x00111611, 0x00121712, 0x00141914, 0x00151a14, 0x00171914, 0x00191c18, 0x001a1d17, 0x001b1e18, 0x001d1e18, 0x001c1d18, 0x001c1e16, 0x001c1e16, 0x001c1e16, 0x001b1c14, 0x001a1b14, 0x00181a14, 0x00141811, 0x00111611, 0x00101511, 0x00101512, 0x000e1411, 0x000a110e, 0x0008120d, 0x0008110c, 0x00051009, 0x00081009, 0x00081009, 0x00081009, 0x0008110a, 0x000a100a, 0x000b110c, 0x000d110c, 0x000e120d, 0x000e120d, 0x000e140e, 0x000d140d, 0x00101710, 0x00101710, 0x00101710, 0x00141610, 0x0016160f, 0x0016160f, 0x0015150e, 0x0014150c, 0x0013140b, 0x0012140a, 0x0014130a, 0x0014130a, 0x00141408, 0x00141408, 0x00141308, 0x00141308, 0x0014130a, 0x0013130a, 0x00121209, 0x00121108, 0x00111108, 0x00131209, 0x00101208, 0x0012140a, 0x00101409, 0x000c1005, 0x000b0e04, 0x00090d03, 0x000a0e03, 0x000b0e04, 0x000c0e04, 0x000c0e04, 0x000c0e05, 0x000c1007, 0x000c1007, 0x000c0f08, 0x000d0e0a, 0x00100f0a, 0x000f1008, 0x000e0f08, 0x00101108, 0x0014130a, 0x0014130a, 0x00161409, 0x001a160b, 0x001f180a, 0x00241b0a, 0x00271c07, 0x002c2008, 0x00342508, 0x003c2e0a, 0x0044340c, 0x00523c0f, 0x0064460d, 0x00846311, 0x00c0a430, 0x00ccb420, 0x00ccb80c, 0x00ccb80a, 0x00ccb80c, 0x00cab80c, 0x00c8b40d, 0x00a48404, 0x00785300, 0x00604300, 0x004c3903, 0x003f3005, 0x003c2e05, 0x00463810, 0x0044370c, 0x00413408, 0x003d3108, 0x00382d0a, 0x0033290a, 0x002c2509, 0x001f1a00, 0x0025200b, 0x00211e0c, 0x00191809, 0x000d1004, 0x00090e03, 0x00090f06, 0x000b1008, 0x0012120b, 0x0014130c, 0x0016100b, 0x00171009, 0x00181108, 0x00181107, 0x001a1105, 0x001d1408, 0x00211808, 0x00231708, 0x00251708, 0x00261807, 0x00271706, 0x00281808, 0x002c1808, 0x002d1806, 0x002d1806, 0x00301808, 0x00301808, 0x00311809, 0x00341909, 0x00321a07, 0x00311b07, 0x00311b07, 0x00311b07, 0x00311b08, 0x00301808, 0x002c1609, 0x002a160b, 0x00241408, 0x00201409, 0x001f1308, 0x001c1308, 0x00191208, 0x00181107, 0x00171106, 0x00141007, 0x00121006, 0x00120e07, 0x00120e07, 0x0015120a, 0x0017140c, 0x0018140b, 0x001b130a, 0x0020180b, 0x002b210b, 0x003a2f10, 0x0040340f, 0x00342702, 0x00332001, 0x00392808, 0x0048330d, 0x005a3d0f, 0x0073510e, 0x00ac8c23, 0x00ccb224, 0x00ccb610, 0x00ccb808, 0x00ccb806, 0x00cbb40f, 0x00b18c09, 0x007c5300, 0x005e3b00, 0x004c3306, 0x00412c09, 0x00372502, 0x00332004, 0x002f1d06, 0x002a1c05, 0x00241704, 0x00211504, 0x001c1505, 0x00181106, 0x00161308, 0x00141308, 0x00131207, 0x00111006, 0x000f0f04, 0x00101005, 0x00101008, 0x00121009, 0x00111009, 0x0010100b, 0x0010100c, 0x00100f0a, 0x00100f0a, 0x000f100a, 0x0010100b, 0x00100f08, 0x00101007, 0x00141109, 0x0014130a, 0x00131008, 0x00141109, 0x00141109, 0x00141109, 0x0014120a, 0x0016120b, 0x00161209, 0x00161208, 0x00161307, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x0016120a, 0x0016120a, 0x00161208, 0x00161208, 0x00171309, 0x00171309, 0x00181408, 0x00181408, 0x00181309, 0x00181309, 0x00161409, 0x0016150b, 0x0017160c, 0x0019170f, 0x00191710, 0x00181710, 0x00191811, 0x00181a14, 0x00171914, 0x00131811, 0x00121710, 0x000f140d, 0x000c110a, 0x000b1009, 0x000a1009, 0x000a100b, 0x000b110c, 0x000a100a, 0x000a100b, 0x000a100c, 0x000a100c, 0x0008100c, 0x0008100c, 0x0009110c, 0x0009110d, 0x0009110c, 0x0008100c, 0x0008100c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0008100c, 0x0009110f, 0x0009110f, 0x000a1210, 0x000c1411, 0x000e1613, 0x000e1613, 0x00101513, 0x00131615, 0x00131815, 0x00131914, 0x00141b14, 0x00151c15, 0x00151c15, 0x00161b15, 0x00161b15, 0x00171c17, 0x00161b15, 0x00151c15, 0x00141a14, 0x00121813, 0x00111812, 0x00101814, 0x00101814, 0x000d1510, 0x000c1711, 0x000f1412, 0x000c1210, 0x000c1411, 0x000a1310, 0x000a120f, 0x000a120e, 0x000a120e, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c09, 0x00191c09, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0041420d, 0x0044450e, 0x0048490f, 0x004c4d0f, 0x004f5010, 0x006b6010, 0x00c8a015, 0x00c8a015, 0x00736812, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005e5f12, 0x005e5f13, 0x005c5d11, 0x008c7914, 0x00cba417, 0x00c49f17, 0x00696312, 0x00595a12, 0x00585910, 0x00585810, 0x00565710, 0x00555611, 0x00545511, 0x00545511, 0x00535410, 0x00535410, 0x00545510, 0x00545511, 0x00545511, 0x00555610, 0x00565710, 0x00585910, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x00a28814, 0x00cca418, 0x00b79617, 0x00646213, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005b5b12, 0x005b5911, 0x00b09015, 0x00cca316, 0x00a38613, 0x004b4c10, 0x004c4d0f, 0x0048490f, 0x0045470e, 0x0041420d, 0x003e400d, 0x0038380c, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x00292b0b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x000f130e, 0x000f130f, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c130d, 0x000c130d, 0x000c140d, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140d, 0x000b140c, 0x000c140c, 0x000c140c, 0x000c140c, 0x000c140c, 0x000c140c, 0x000b140c, 0x000a130b, 0x000a130c, 0x000a130c, 0x000c140d, 0x000c130d, 0x000c120c, 0x000c130d, 0x000c140d, 0x000b170f, 0x000d160f, 0x00101610, 0x00121812, 0x00141813, 0x00141813, 0x00141914, 0x00161b15, 0x00191a17, 0x001c1c18, 0x001c1c17, 0x001d1e18, 0x001d1e18, 0x001d1e18, 0x001c1e16, 0x001c1e16, 0x001c1e16, 0x001a1c15, 0x00181b12, 0x00171913, 0x00131712, 0x00101511, 0x00111611, 0x00101510, 0x000d1310, 0x000a100b, 0x000a100b, 0x000a1009, 0x00091008, 0x000b1008, 0x000b1009, 0x000f140c, 0x000f140c, 0x0010130c, 0x0010130d, 0x0012140e, 0x0012140e, 0x0013140f, 0x00141510, 0x00141610, 0x00161810, 0x0015160f, 0x0014150f, 0x0014120c, 0x0016140c, 0x0017140d, 0x0018140d, 0x0016140c, 0x0014120c, 0x0014120b, 0x0014120b, 0x0014120b, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x00151208, 0x00161208, 0x00171309, 0x00171309, 0x00141008, 0x00121007, 0x00131108, 0x00131308, 0x0014140a, 0x00101309, 0x000f1007, 0x000c0f04, 0x000c0e04, 0x000c0e04, 0x000c0e04, 0x000d0f05, 0x000d0f06, 0x000e1108, 0x000e1109, 0x000e100b, 0x000f100c, 0x0011100c, 0x0010110a, 0x000f1008, 0x00101208, 0x0014130a, 0x0014130a, 0x00171409, 0x001b150b, 0x001f180a, 0x00241b0a, 0x00271c07, 0x002c2008, 0x00342508, 0x003c2e09, 0x0045340c, 0x00503c10, 0x0064470e, 0x00866413, 0x00c0a432, 0x00ccb420, 0x00ccb80c, 0x00ccb80a, 0x00ccb80c, 0x00ccb80c, 0x00c8b40d, 0x00a48404, 0x00785200, 0x005f4100, 0x004c3803, 0x003d2f04, 0x003a2d05, 0x0044380f, 0x0041340a, 0x0042350c, 0x003c300a, 0x00342b0b, 0x0030280c, 0x002b240b, 0x001d1802, 0x001d1b08, 0x00211f0f, 0x001a190c, 0x00101208, 0x000a0e03, 0x00090e05, 0x000a0e07, 0x000f1009, 0x0013100c, 0x0014100c, 0x00150f0a, 0x0018100a, 0x00181108, 0x00181107, 0x001c1407, 0x00201708, 0x00211707, 0x00221606, 0x00261808, 0x00251605, 0x00281708, 0x00291808, 0x002b1807, 0x002b1807, 0x002d1809, 0x002e1709, 0x00301709, 0x00301809, 0x00301906, 0x00301905, 0x00301905, 0x00301905, 0x00301908, 0x002c1808, 0x002b1709, 0x0028150b, 0x0024140a, 0x00211409, 0x001f1308, 0x001c1308, 0x001a1108, 0x00191008, 0x00181008, 0x00141007, 0x00121008, 0x00120e07, 0x00120e07, 0x0016120a, 0x0017140c, 0x0018140b, 0x001b130a, 0x001f170a, 0x002b210c, 0x00382d11, 0x003f3210, 0x00342602, 0x00321f04, 0x00392809, 0x00453210, 0x00573c11, 0x00725110, 0x00ad8c25, 0x00ccb024, 0x00ccb510, 0x00ccb809, 0x00ccb806, 0x00cbb40f, 0x00b08e0a, 0x007c5400, 0x005e3b00, 0x004c3104, 0x00402c09, 0x00372502, 0x00342005, 0x002f1c05, 0x002b1c06, 0x00261805, 0x00221604, 0x001e1506, 0x00181104, 0x00171308, 0x00151207, 0x00141106, 0x00131107, 0x00121106, 0x00121106, 0x00131107, 0x00131008, 0x0013100a, 0x0012100a, 0x0012100a, 0x00110f09, 0x000f0c06, 0x00100d07, 0x00121008, 0x00121008, 0x00151309, 0x00161409, 0x00141308, 0x00141208, 0x00141208, 0x00141108, 0x00141008, 0x00151108, 0x00161208, 0x00171307, 0x00181206, 0x00181306, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00171408, 0x00171408, 0x00171408, 0x00171408, 0x00181208, 0x00161208, 0x00161309, 0x00151409, 0x0015140a, 0x0015140b, 0x0015140b, 0x0015140b, 0x0015140c, 0x0014140c, 0x0014140c, 0x0016160f, 0x00181710, 0x00181810, 0x00181811, 0x00151710, 0x0014150e, 0x0010110b, 0x0010110c, 0x0010110c, 0x000d100b, 0x000c0f09, 0x000c100c, 0x000c100c, 0x000a110c, 0x000b110c, 0x000a110c, 0x0008110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0007110c, 0x0006120c, 0x0006120c, 0x0005110b, 0x0005110b, 0x0006120c, 0x0007110c, 0x0008110d, 0x0008110d, 0x0009120f, 0x000b1410, 0x000c1411, 0x000c1411, 0x000e1513, 0x00101614, 0x00111814, 0x00111913, 0x00131a14, 0x00141c15, 0x00151c15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00161b15, 0x00151c15, 0x00151c15, 0x00141a14, 0x00111812, 0x00101812, 0x00101813, 0x000f1811, 0x000e1610, 0x00111414, 0x000f1311, 0x000f1412, 0x000c1411, 0x000c1410, 0x000c1410, 0x000c1410, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0048490e, 0x004b4c0f, 0x004f5010, 0x00635b10, 0x00c09b14, 0x00c9a116, 0x008a7613, 0x00595a12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e12, 0x005d5e11, 0x006d6612, 0x00c49f17, 0x00cba417, 0x00988114, 0x005b5b12, 0x00595a12, 0x00585910, 0x00585810, 0x00565710, 0x00565711, 0x00555611, 0x00565711, 0x00555611, 0x00555611, 0x00555611, 0x00565710, 0x00585810, 0x00585910, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x00756b13, 0x00c4a018, 0x00cca418, 0x009e8415, 0x005c5d13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x00605c11, 0x00c39c16, 0x00cca216, 0x00917912, 0x004d4e10, 0x004b4c0f, 0x0048490f, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x000f130b, 0x000f130f, 0x000f130f, 0x000b140d, 0x000b140d, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000e140e, 0x000e140e, 0x000d140e, 0x000c140e, 0x000c140e, 0x000c140e, 0x000c140d, 0x000c140c, 0x000c140c, 0x000c150c, 0x000c150c, 0x000c140c, 0x000c140c, 0x000c150c, 0x000c140c, 0x000c140e, 0x000c140e, 0x000c140d, 0x000c130d, 0x000c130d, 0x000e140f, 0x000c140e, 0x000c1710, 0x000e1610, 0x00101710, 0x00131813, 0x00141914, 0x00141914, 0x00151a14, 0x00181a16, 0x001b1c18, 0x001c1c18, 0x001e1c18, 0x001d1e18, 0x001e1e18, 0x001d1e18, 0x001c1e16, 0x001b1d15, 0x00191c14, 0x00181c14, 0x00181b12, 0x00171913, 0x00141711, 0x00121410, 0x00101410, 0x00111610, 0x00111610, 0x0010140e, 0x0010140d, 0x0010140c, 0x0010140c, 0x0012140c, 0x0014140e, 0x0014150e, 0x0014160f, 0x00141610, 0x00151610, 0x00181710, 0x00181710, 0x0014140c, 0x0016140f, 0x0017150e, 0x0018150e, 0x0018140d, 0x0018140d, 0x0016130b, 0x00181209, 0x0017130c, 0x0018140c, 0x0017140c, 0x0017130c, 0x0017130c, 0x0017140d, 0x0017140d, 0x0016140b, 0x0016140b, 0x00161309, 0x00161309, 0x00151308, 0x00141208, 0x00141007, 0x00151108, 0x00151108, 0x00151208, 0x00141308, 0x00141308, 0x0014140a, 0x00131209, 0x00101208, 0x000f1007, 0x000c0e04, 0x000c0e04, 0x000c0e04, 0x000d0f05, 0x000d1006, 0x000e1109, 0x000e1109, 0x000e110b, 0x0010100c, 0x0012100c, 0x0010120a, 0x00101109, 0x0012140a, 0x0014130a, 0x0015140b, 0x0018140b, 0x001c160c, 0x0021180b, 0x00241c0b, 0x00291f09, 0x002e2209, 0x00352708, 0x003d2f0a, 0x0044360c, 0x00503c0f, 0x0064480e, 0x00866414, 0x00c1a433, 0x00ccb421, 0x00ccb80c, 0x00ccb80a, 0x00ccb80c, 0x00cbb80c, 0x00c8b40d, 0x00a48404, 0x00765300, 0x005f4000, 0x004b3704, 0x003d2e04, 0x00392c04, 0x0044380e, 0x003d3007, 0x003c3008, 0x00342c08, 0x00302809, 0x002c250c, 0x0028220b, 0x001c1904, 0x001b1a08, 0x001e1d0f, 0x0017180c, 0x000f1108, 0x000a0f04, 0x00080e05, 0x00090e07, 0x000d0d08, 0x0011100a, 0x0014100b, 0x0014100a, 0x0018110a, 0x00181108, 0x00181107, 0x001a1304, 0x001e1506, 0x001e1505, 0x00201504, 0x00241807, 0x00221404, 0x00271608, 0x00281708, 0x00291807, 0x002a1706, 0x002b1808, 0x002c1708, 0x002d1708, 0x002f1708, 0x002e1805, 0x002d1804, 0x002d1804, 0x002d1804, 0x002e1808, 0x002c1608, 0x0029150a, 0x0027140b, 0x0023140a, 0x00201309, 0x001f1308, 0x001c1207, 0x001a1008, 0x00191008, 0x00170f07, 0x00141007, 0x00110f07, 0x00120e07, 0x00120e07, 0x0016120a, 0x0018140c, 0x0018140b, 0x001a1409, 0x001c1407, 0x00271e08, 0x00362c10, 0x003d3010, 0x00332404, 0x00311e03, 0x0038260a, 0x0044310f, 0x00553910, 0x00704f0f, 0x00ac8b28, 0x00ccaf2a, 0x00ccb416, 0x00ccb70e, 0x00ccb80a, 0x00cbb40d, 0x00b08e0a, 0x007b5400, 0x005e3b00, 0x004b3004, 0x00402b09, 0x00372502, 0x00342005, 0x002e1c05, 0x002b1c06, 0x00281b07, 0x00241806, 0x00201705, 0x001c1204, 0x00191408, 0x00181307, 0x00151308, 0x00141308, 0x00141308, 0x00141308, 0x00141308, 0x00141108, 0x00131008, 0x00131009, 0x00141109, 0x00141108, 0x00110e04, 0x00110e04, 0x00141007, 0x00141307, 0x00141207, 0x00161408, 0x00161408, 0x00141308, 0x00141307, 0x00151408, 0x00161408, 0x00181308, 0x001a1307, 0x001a1305, 0x00191305, 0x00191305, 0x00191306, 0x00191307, 0x00191307, 0x00191208, 0x00191208, 0x00191208, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x00171408, 0x00171408, 0x00181108, 0x00161208, 0x00141208, 0x00141308, 0x00141309, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x00141309, 0x00141309, 0x00141409, 0x00141409, 0x00161309, 0x00161309, 0x001a170d, 0x0018150c, 0x0018150e, 0x0018150e, 0x0018160e, 0x0014140c, 0x0014130c, 0x0012140c, 0x0012140e, 0x000f120c, 0x000a100a, 0x00080f08, 0x0007100a, 0x0006100b, 0x0007110c, 0x0006120c, 0x0006120c, 0x0005130c, 0x0005130c, 0x0004110b, 0x0004110b, 0x0005130c, 0x0005120c, 0x0006110d, 0x0006110d, 0x0006110d, 0x0008130f, 0x000a1511, 0x000a1511, 0x000c1512, 0x000f1714, 0x000f1714, 0x00101912, 0x00101a13, 0x00111b14, 0x00141c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00131914, 0x00111913, 0x00121a14, 0x000f1811, 0x00101812, 0x00111514, 0x00101211, 0x00101412, 0x000f1412, 0x000d1410, 0x000d150f, 0x000c140f, 0x00060c07, 0x000f130f, 0x000f130f, 0x0014180f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x002c2d0b, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0047480e, 0x004b4c10, 0x004d4e0f, 0x00585510, 0x00b69314, 0x00cca316, 0x00a48814, 0x005b5a12, 0x005b5b12, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5d11, 0x009f8615, 0x00cca417, 0x00c49f17, 0x00736813, 0x00595a12, 0x00595a12, 0x00585910, 0x00585910, 0x00585810, 0x00585810, 0x00565711, 0x00565711, 0x00565710, 0x00585810, 0x00585810, 0x00585911, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x00646112, 0x00b19316, 0x00cca418, 0x00c7a118, 0x00766c14, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x00595a12, 0x007f7012, 0x00c8a016, 0x00cba216, 0x00786811, 0x004d4e10, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0032330c, 0x0030310c, 0x00292b0a, 0x0026280b, 0x0024250b, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x000c140e, 0x000c140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000d140e, 0x000f150f, 0x000f150f, 0x000d150f, 0x000d150f, 0x000c140e, 0x000c140e, 0x000c140d, 0x000c140c, 0x000c140c, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000c140d, 0x000d140d, 0x000d140d, 0x000e140e, 0x000f150f, 0x000f150f, 0x0010140f, 0x000f1410, 0x00101510, 0x00131713, 0x00141714, 0x00151814, 0x00171814, 0x00171814, 0x00181914, 0x00191a17, 0x001c1c18, 0x001d1c18, 0x001f1e18, 0x001d1e18, 0x001d1f18, 0x001b1d16, 0x001b1d15, 0x001a1d15, 0x00181c13, 0x00171a11, 0x00161910, 0x00161811, 0x00151711, 0x00141610, 0x0012140d, 0x0012160e, 0x00141810, 0x00141710, 0x0014160d, 0x0015150d, 0x0015150d, 0x0017150d, 0x0017150d, 0x0017150e, 0x0017150d, 0x0014130b, 0x0015140b, 0x0016130c, 0x0017140c, 0x0014130b, 0x0015130b, 0x0016140a, 0x0016140b, 0x0016140b, 0x0017140b, 0x0017140a, 0x00151308, 0x0017140b, 0x0018140c, 0x0018140b, 0x0018140b, 0x0018140b, 0x0018140c, 0x0018140c, 0x0017140b, 0x0017140a, 0x00161409, 0x00161409, 0x00151409, 0x00151409, 0x0017130a, 0x0017130a, 0x0017140b, 0x0017130a, 0x00151209, 0x0016130a, 0x0017130a, 0x0016130a, 0x00141208, 0x00111108, 0x000f1006, 0x000f0d04, 0x000f0d05, 0x00111008, 0x00101008, 0x00101209, 0x00101209, 0x0010120a, 0x0010110a, 0x00121109, 0x00121109, 0x00141209, 0x00151309, 0x00161309, 0x0018140a, 0x001a150a, 0x001e1809, 0x00231808, 0x00271a09, 0x002c1e08, 0x00302208, 0x00372708, 0x003e2f09, 0x0044370b, 0x004f3d0c, 0x0064480c, 0x00866414, 0x00bea130, 0x00ccb421, 0x00ccb80c, 0x00cbb80a, 0x00cbb80c, 0x00cbb90d, 0x00c9b60f, 0x00a48604, 0x00765200, 0x005f4000, 0x004a3604, 0x003c2f05, 0x00382c04, 0x0044370f, 0x003b2f06, 0x00352b04, 0x00342c08, 0x0030290c, 0x0029230b, 0x0024210c, 0x001c1a08, 0x00191808, 0x001a1b0c, 0x00131509, 0x000d1107, 0x00090f04, 0x00070e04, 0x00080e05, 0x000c0e07, 0x00100f08, 0x0013100b, 0x0014100a, 0x0016100a, 0x00181108, 0x00181207, 0x00181305, 0x001c1407, 0x001c1405, 0x001e1406, 0x00201508, 0x00211407, 0x00251709, 0x0028180a, 0x00281708, 0x00281708, 0x00281708, 0x00281708, 0x00291708, 0x002b1608, 0x002b1706, 0x002b1706, 0x002c1806, 0x002c1806, 0x002b1708, 0x00291509, 0x00261409, 0x0024130a, 0x0021140a, 0x001e1309, 0x001d1208, 0x001c110a, 0x001b1008, 0x00191008, 0x00170f07, 0x00141008, 0x00120e07, 0x00110f08, 0x00110f08, 0x00141109, 0x0016140a, 0x0018140b, 0x00191408, 0x001c1407, 0x00231b08, 0x00322711, 0x003b2e14, 0x00312408, 0x002f1e03, 0x00382809, 0x0044310c, 0x0052370c, 0x006d4b0c, 0x00ac8a28, 0x00ccb12b, 0x00ccb417, 0x00cbb50f, 0x00cbb60a, 0x00cbb60e, 0x00af8e0a, 0x007a5300, 0x005e3a00, 0x004c2f04, 0x00402b09, 0x00362602, 0x00342005, 0x002f1c07, 0x002c1c08, 0x00291b08, 0x00261808, 0x00221706, 0x00201408, 0x001c1508, 0x001a1407, 0x00181306, 0x00181208, 0x00181208, 0x00171107, 0x00151208, 0x00151208, 0x00141208, 0x00121108, 0x00141308, 0x00151408, 0x00181409, 0x00151206, 0x00151106, 0x00181208, 0x00161005, 0x00171207, 0x00181208, 0x00171208, 0x00181409, 0x00171408, 0x00181508, 0x001b1408, 0x001c1408, 0x001c1405, 0x001c1405, 0x001c1405, 0x001d1405, 0x001d1407, 0x001e1408, 0x001d1408, 0x001c1408, 0x001c1409, 0x001c1408, 0x001d1508, 0x001c1508, 0x001c1608, 0x00181307, 0x00171408, 0x00181108, 0x00171109, 0x00161109, 0x00141108, 0x00141209, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x00141309, 0x00141309, 0x00151008, 0x00171109, 0x00171109, 0x0018120a, 0x0019130b, 0x0019130b, 0x0017140c, 0x0017140c, 0x0019170f, 0x0018160e, 0x0017150f, 0x0017150f, 0x00181710, 0x00181710, 0x00141510, 0x00101510, 0x00101410, 0x000c120d, 0x000b110c, 0x0008100b, 0x0008110b, 0x0006130c, 0x0006130c, 0x0006110a, 0x0006110a, 0x0007110b, 0x0007110b, 0x0006110a, 0x0008120c, 0x0006120b, 0x0006130c, 0x0008140f, 0x000b1510, 0x000b1510, 0x000d1712, 0x000e1812, 0x000f1812, 0x00101a13, 0x00111c14, 0x00131c15, 0x00141c14, 0x00141c14, 0x00161c15, 0x00161c15, 0x00161c15, 0x00161c15, 0x00161c14, 0x00151a14, 0x00131a14, 0x00131914, 0x00101812, 0x00101812, 0x00131714, 0x00111412, 0x00101512, 0x00101411, 0x000d140f, 0x000d150f, 0x000c140e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x00494a0f, 0x004c4d0f, 0x004d4e10, 0x00a48714, 0x00cca316, 0x00be9915, 0x00615d12, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x00696412, 0x00b99816, 0x00cca417, 0x00b49415, 0x00696312, 0x005b5b12, 0x00595a12, 0x00585911, 0x00585910, 0x00585910, 0x00585910, 0x00585910, 0x00585910, 0x00585911, 0x00595a12, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x00605e12, 0x00a38815, 0x00cca418, 0x00cca418, 0x00a48815, 0x00605f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5c11, 0x005b5b12, 0x00595a11, 0x00a08514, 0x00cca316, 0x00bf9915, 0x00615a10, 0x004d4e0f, 0x00494a0f, 0x0047480e, 0x0043440e, 0x003e400c, 0x003b3c0d, 0x0036370b, 0x0034350c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180f, 0x000f130f, 0x000f130f, 0x000d150f, 0x000c150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x000f150f, 0x00101610, 0x00101610, 0x000e150f, 0x000d150f, 0x000d150f, 0x000e1610, 0x000d150f, 0x000d150f, 0x000d150f, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x000e1610, 0x0010160d, 0x0010160d, 0x00101710, 0x00101710, 0x00101610, 0x00101510, 0x00141613, 0x00151613, 0x00161714, 0x00171814, 0x00171814, 0x00181814, 0x00181814, 0x001a1a15, 0x001c1b17, 0x001e1c17, 0x001f1e18, 0x001f1e18, 0x001f1e18, 0x001e2018, 0x001c1e16, 0x00191c13, 0x00171a10, 0x0017190f, 0x0014170c, 0x0013150d, 0x0014150d, 0x0015150f, 0x0014140d, 0x0013140b, 0x0013140b, 0x0012140b, 0x0014140b, 0x0014140b, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0015130a, 0x0015130a, 0x0014130a, 0x0014130a, 0x00151108, 0x00151108, 0x00141108, 0x00151208, 0x00141308, 0x00161409, 0x00151409, 0x00151409, 0x00151408, 0x00171408, 0x00171409, 0x00181409, 0x00181409, 0x00181408, 0x001a1408, 0x001b1408, 0x00191408, 0x00181408, 0x00181408, 0x00181408, 0x00181409, 0x00181308, 0x00181309, 0x0018130a, 0x0018130a, 0x0018130a, 0x0018130a, 0x00181309, 0x00181109, 0x00181008, 0x00181007, 0x00161208, 0x00141207, 0x00141108, 0x00141108, 0x00141008, 0x00131007, 0x00131108, 0x00131409, 0x00121308, 0x00121308, 0x00131308, 0x00141208, 0x00151108, 0x00181308, 0x00191408, 0x001a1408, 0x001b1409, 0x001e1708, 0x00221808, 0x00261808, 0x002b1a08, 0x002f1e08, 0x00342208, 0x00382709, 0x003e2f09, 0x0044360b, 0x00503c0c, 0x0064480c, 0x00876414, 0x00bca02e, 0x00ccb421, 0x00ccb80c, 0x00cab90a, 0x00cbb90c, 0x00cbba0e, 0x00cab810, 0x00a48805, 0x00745100, 0x00604100, 0x004a3505, 0x003c2f07, 0x00382c04, 0x0042370f, 0x003b2f07, 0x00342803, 0x002e2605, 0x002b2509, 0x00262009, 0x00221f0c, 0x001b1809, 0x00161507, 0x0017180b, 0x00131509, 0x000e1208, 0x000a1006, 0x00070e04, 0x00070e04, 0x000c0e08, 0x00100f08, 0x00100e0a, 0x00101009, 0x00140f09, 0x00141008, 0x00171207, 0x00181205, 0x001a1407, 0x001b1407, 0x001d1408, 0x0020140a, 0x00201409, 0x00241809, 0x0026170a, 0x0027170a, 0x0027170a, 0x00241708, 0x00241708, 0x00261608, 0x00261508, 0x00261607, 0x00261607, 0x00281708, 0x00281809, 0x0028160a, 0x00251409, 0x0023140a, 0x0021140a, 0x0020140a, 0x001d140a, 0x001c120a, 0x001b1008, 0x001a1008, 0x00181008, 0x00161007, 0x00140e08, 0x00110f07, 0x00100f08, 0x00100f08, 0x00131109, 0x00141409, 0x0017140b, 0x00181408, 0x001c1507, 0x00221a0a, 0x002b2010, 0x00342713, 0x0030210a, 0x002f1d04, 0x00382708, 0x00422e0a, 0x0053350b, 0x006e4c0b, 0x00a98823, 0x00caac24, 0x00cbb10f, 0x00cab408, 0x00cbb406, 0x00ccb411, 0x00ae8c0b, 0x00785000, 0x005c3800, 0x004c3004, 0x00412c09, 0x00372703, 0x00342006, 0x00301c07, 0x002f1c08, 0x002c1c08, 0x002b1b08, 0x00251806, 0x00231708, 0x00201609, 0x001c1408, 0x001c1306, 0x001c1306, 0x001b1307, 0x00191108, 0x00181108, 0x00181308, 0x00171408, 0x00141308, 0x00161408, 0x001a170b, 0x001e1a0e, 0x001d180c, 0x001b1509, 0x001d1409, 0x001c1208, 0x001d1409, 0x001d1409, 0x001d1409, 0x001d150a, 0x001d160a, 0x001d1709, 0x00201708, 0x00201706, 0x00201707, 0x00221708, 0x00221708, 0x00241708, 0x00241708, 0x00241808, 0x00241808, 0x00231809, 0x0023180a, 0x00221708, 0x00211707, 0x00211807, 0x00201808, 0x001c1407, 0x001a1409, 0x001a140a, 0x0019120b, 0x00181209, 0x00171109, 0x0017120a, 0x0015130a, 0x0015130a, 0x0014130a, 0x0014130a, 0x0015120a, 0x0016120a, 0x00161109, 0x00161109, 0x0018110a, 0x0018110a, 0x0018110a, 0x0018110a, 0x0016120a, 0x0015140a, 0x0015140b, 0x0016140c, 0x0017140d, 0x0018140d, 0x0018140e, 0x0018150f, 0x00171610, 0x00161812, 0x00161813, 0x00141611, 0x0011140e, 0x0010140d, 0x000f150c, 0x000b140b, 0x00091409, 0x00091208, 0x000a1208, 0x00091108, 0x00091008, 0x00081007, 0x000a1309, 0x00081309, 0x00081409, 0x0008120c, 0x0009140d, 0x000b150f, 0x000c1710, 0x000e1811, 0x000f1812, 0x000f1912, 0x00101b14, 0x00121c14, 0x00141c14, 0x00151c14, 0x00171c15, 0x00181c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00171c14, 0x00151c16, 0x00141b14, 0x00121813, 0x00121813, 0x00141914, 0x00141814, 0x00131713, 0x00111511, 0x00101610, 0x00101710, 0x000f1610, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180b, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x00292b0b, 0x002d2f0a, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0041420d, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x004d4e10, 0x00847011, 0x00cba216, 0x00c9a116, 0x00827113, 0x00595a12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x00786e13, 0x00c19c17, 0x00cca417, 0x00b09115, 0x006c6412, 0x00595a12, 0x005b5b12, 0x00595a12, 0x00595a12, 0x00595a12, 0x00595a12, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x005c5c12, 0x005b5b11, 0x00646112, 0x00a38815, 0x00caa418, 0x00cca418, 0x00b89717, 0x006b6513, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x005b5b12, 0x00615d11, 0x00be9916, 0x00cca316, 0x00a88914, 0x00505010, 0x004c4d0f, 0x00494a0f, 0x0045470e, 0x0041420e, 0x003c3e0c, 0x003b3c0d, 0x0036370c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x00202309, 0x001d2008, 0x001d200a, 0x00191c0b, 0x0014180b, 0x000f130d, 0x000f130f, 0x000f130f, 0x000e150f, 0x000e150f, 0x00101610, 0x00101610, 0x00101610, 0x00101610, 0x00101611, 0x00101711, 0x00101610, 0x000f1610, 0x000f1710, 0x00101811, 0x00101711, 0x000f1610, 0x000f1710, 0x00101811, 0x00101811, 0x00101811, 0x00101811, 0x000f1610, 0x000f1610, 0x00101710, 0x00101710, 0x00101710, 0x00101710, 0x00101710, 0x00111610, 0x00161813, 0x00181814, 0x00181814, 0x00181713, 0x001a1813, 0x001c1a14, 0x001c1b14, 0x001c1c16, 0x001d1c14, 0x001d1d15, 0x001e1d15, 0x001d1c14, 0x001c1c14, 0x00181911, 0x00161810, 0x0016180e, 0x0016180e, 0x0015170d, 0x0014150c, 0x0014140c, 0x0014120c, 0x0014120c, 0x0014120c, 0x0014130a, 0x0013130a, 0x0014140a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x0014130a, 0x00141109, 0x00141107, 0x00141107, 0x00141108, 0x00151208, 0x00151308, 0x00161409, 0x0017140a, 0x00181309, 0x00181408, 0x00181408, 0x001a1408, 0x001b1408, 0x001b1408, 0x001c1407, 0x001c1408, 0x001d1508, 0x001c1406, 0x001c1405, 0x001c1405, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1308, 0x001c1309, 0x001c130a, 0x001c130a, 0x001c130a, 0x001c140b, 0x001c140b, 0x001e150a, 0x001d150a, 0x001b1409, 0x00191509, 0x001b160b, 0x001b160c, 0x001b160c, 0x00181409, 0x00141006, 0x00151408, 0x00151408, 0x00141408, 0x00151408, 0x00171408, 0x00181308, 0x001a1308, 0x001b1408, 0x001d1508, 0x001d1508, 0x00201708, 0x00241a08, 0x00281908, 0x002d1c08, 0x00311f08, 0x00362308, 0x003b2808, 0x00402e09, 0x0047340b, 0x00513a0a, 0x0064460b, 0x00846312, 0x00bca02e, 0x00ccb421, 0x00ccb80c, 0x00cab90a, 0x00cab80c, 0x00caba0d, 0x00c9b810, 0x00a68908, 0x00745200, 0x005e4000, 0x004a3406, 0x003c2c06, 0x00362a04, 0x0040350e, 0x003c3109, 0x00332904, 0x002a2103, 0x00251f06, 0x00241f0a, 0x00201d0e, 0x0018180c, 0x00131407, 0x00111408, 0x0012160c, 0x000e1409, 0x000a1007, 0x00060f04, 0x00070f04, 0x000b0e08, 0x000f1009, 0x0010100b, 0x00101109, 0x00121009, 0x00141008, 0x00151206, 0x00171305, 0x00191306, 0x001b1407, 0x001c1408, 0x001c1308, 0x001d1308, 0x00201508, 0x00231608, 0x00241508, 0x00241508, 0x00211508, 0x00231408, 0x00241408, 0x00241408, 0x00241407, 0x00241406, 0x00251608, 0x00261708, 0x00241408, 0x00211308, 0x00201409, 0x001f1409, 0x001c1309, 0x001b1309, 0x001a1108, 0x00191008, 0x00181008, 0x00161008, 0x00140f07, 0x00120f07, 0x00100f08, 0x000f0f07, 0x000f0f07, 0x00121309, 0x00131408, 0x0015140a, 0x00171407, 0x001a1507, 0x00201909, 0x00261c0c, 0x002a1c0b, 0x002e2009, 0x002e1c05, 0x0037260a, 0x00402b09, 0x0052340b, 0x00684506, 0x00ab8726, 0x00ccac28, 0x00cbb012, 0x00ccb10c, 0x00cbb00b, 0x00cbac1c, 0x00a9810e, 0x00764c01, 0x00593600, 0x004c3004, 0x00412c0a, 0x003a2804, 0x00382107, 0x00341e06, 0x00301c05, 0x002f1c06, 0x002d1c07, 0x00291906, 0x00271808, 0x00241809, 0x00211608, 0x00201407, 0x00201408, 0x00201407, 0x001c1306, 0x001a1207, 0x00191308, 0x00181407, 0x00171306, 0x00191408, 0x001d180c, 0x00231c0f, 0x00231b0f, 0x0021190c, 0x0024180c, 0x0024180b, 0x0025180c, 0x0027190c, 0x0026190c, 0x00271a0c, 0x00281b0c, 0x00281b0a, 0x00281a08, 0x00281a0a, 0x00281b0b, 0x002a1b0c, 0x00291a09, 0x002a1a09, 0x002a1a09, 0x002b1b09, 0x002b1b09, 0x002a1b0b, 0x002a1b0b, 0x00281a0a, 0x00271808, 0x00241906, 0x00231807, 0x00201708, 0x001e1708, 0x001d150a, 0x001c130a, 0x001a1309, 0x00181208, 0x00181109, 0x0018110a, 0x0017120a, 0x0017120a, 0x0016120a, 0x0016120a, 0x0016120a, 0x0016120a, 0x00141008, 0x00151008, 0x00151008, 0x00151109, 0x00141109, 0x00141008, 0x00131008, 0x00141109, 0x00141109, 0x0014120b, 0x0014120c, 0x0014120b, 0x0014130c, 0x0016140f, 0x00161510, 0x0014140f, 0x0014140e, 0x0014140e, 0x0016160f, 0x0015180f, 0x0014180e, 0x0010160c, 0x0010140b, 0x0010140b, 0x000e1309, 0x000c1108, 0x000c1007, 0x000d1208, 0x000c1308, 0x000a1308, 0x000a130b, 0x000a130c, 0x0009130c, 0x000b140d, 0x000c170f, 0x000d1810, 0x000e1810, 0x000f1911, 0x00111b13, 0x00141b13, 0x00161c14, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00161c17, 0x00161c17, 0x00141a14, 0x00141a14, 0x00161b15, 0x00141914, 0x00141914, 0x00141813, 0x00121712, 0x00121812, 0x00111711, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003c3e0d, 0x0040400d, 0x0044450e, 0x0047480e, 0x004b4c0f, 0x004d4e10, 0x00605911, 0x00c09a14, 0x00cca316, 0x00ae8e14, 0x005c5b12, 0x005c5c12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x007c7013, 0x00bf9b17, 0x00cca417, 0x00bc9916, 0x00847413, 0x00605d12, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005c5c12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x00786d13, 0x00b39317, 0x00cca418, 0x00cca418, 0x00bb9917, 0x00736a14, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5c12, 0x00595a12, 0x00887512, 0x00caa116, 0x00caa016, 0x007c6c11, 0x004d4e10, 0x004b4c0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0036370c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x00191c0b, 0x0014180b, 0x000f130e, 0x000f130f, 0x000f130f, 0x00101610, 0x00101610, 0x00101710, 0x00101710, 0x00101710, 0x00101710, 0x00111611, 0x00121611, 0x00111711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00101711, 0x00111711, 0x00111711, 0x00121812, 0x00121812, 0x00121810, 0x00121810, 0x00121810, 0x00121810, 0x00131910, 0x00151910, 0x00171810, 0x00191810, 0x00191810, 0x00191710, 0x001b1811, 0x001c1912, 0x001b1811, 0x00191810, 0x0018180f, 0x0018170e, 0x0018170e, 0x0018150c, 0x00141309, 0x00111309, 0x00111309, 0x00131309, 0x00141209, 0x00141209, 0x00141209, 0x0014100a, 0x00131009, 0x0013100a, 0x0013100a, 0x00111008, 0x00121108, 0x00121108, 0x00131109, 0x00141209, 0x0014130a, 0x0014130a, 0x0013120a, 0x0013120a, 0x0013120a, 0x0013120a, 0x00131209, 0x00131209, 0x00141208, 0x00141208, 0x00141207, 0x00151308, 0x00181309, 0x00181309, 0x001a140b, 0x001a140a, 0x001c140a, 0x001d1609, 0x001e160a, 0x0020160a, 0x00201609, 0x00201708, 0x00201708, 0x00201809, 0x00201808, 0x00221807, 0x00221807, 0x00241808, 0x00241809, 0x00241809, 0x00241809, 0x0024180c, 0x0024180c, 0x0024180c, 0x0024180c, 0x0024180d, 0x0024190e, 0x0025190e, 0x0023180c, 0x0021180c, 0x00211a0d, 0x00201a0f, 0x0020190e, 0x001f190e, 0x001b1409, 0x00181206, 0x00171508, 0x00171508, 0x00161407, 0x00171407, 0x001a150a, 0x001c140a, 0x001d1509, 0x001e1708, 0x0020180a, 0x00201809, 0x00241a09, 0x00281c08, 0x002c1c09, 0x00311e0a, 0x00352109, 0x003b2508, 0x0040290b, 0x00452f0c, 0x004a340c, 0x0054390a, 0x00644409, 0x00805e0d, 0x00ba9c2c, 0x00ccb421, 0x00ccb80c, 0x00cab90a, 0x00cab80c, 0x00c8b90c, 0x00c9b810, 0x00a88b09, 0x00755200, 0x005c3d00, 0x004b3407, 0x003a2a04, 0x00302400, 0x003d310a, 0x003d330a, 0x00342b08, 0x002c2207, 0x00241e08, 0x00201a08, 0x001b190b, 0x0014150b, 0x00101207, 0x000e1308, 0x0010150c, 0x000c1209, 0x00091006, 0x00071005, 0x00080f05, 0x00090d06, 0x000c0f07, 0x0010100b, 0x00101109, 0x0012110a, 0x00131008, 0x00151307, 0x00151305, 0x00181406, 0x001a1407, 0x001b1407, 0x001c1307, 0x001c1306, 0x001c1407, 0x00201408, 0x00201308, 0x00201308, 0x001e1307, 0x001f1207, 0x00211308, 0x00221208, 0x00201307, 0x00201406, 0x00221408, 0x00211407, 0x00211408, 0x001f1308, 0x001d1309, 0x001c1408, 0x00191308, 0x00191208, 0x00181208, 0x00181008, 0x00171008, 0x00151008, 0x00130f08, 0x00100f07, 0x00100f08, 0x000d0f05, 0x000d0f05, 0x00101308, 0x00111308, 0x00141208, 0x00161306, 0x00181306, 0x001c1408, 0x0022170b, 0x0027190b, 0x002c1d0a, 0x002e1c06, 0x00352405, 0x00402c06, 0x004e300a, 0x00644008, 0x00a27b28, 0x00c49e2c, 0x00c2a019, 0x00bf9f14, 0x00be9b13, 0x00c2941d, 0x009c6d0c, 0x006e4201, 0x00563400, 0x00493106, 0x00432e0b, 0x003d2907, 0x003b2208, 0x00382008, 0x00341e06, 0x00301c05, 0x00301c05, 0x002e1b06, 0x002b1908, 0x00281909, 0x00251808, 0x00251707, 0x00251607, 0x00241707, 0x00221508, 0x00201408, 0x001f150a, 0x001d160a, 0x001a1407, 0x00181206, 0x001b1305, 0x001d1407, 0x001e1508, 0x001e1406, 0x00231608, 0x00251808, 0x00251807, 0x00291a0b, 0x002c1c0c, 0x002e1c0c, 0x002f1d0b, 0x002f1d0a, 0x00301e0a, 0x00311e0b, 0x00321e0d, 0x00311e0c, 0x00301c08, 0x00301c08, 0x00311c09, 0x00321d0a, 0x00311d0a, 0x00301d0b, 0x00301d0c, 0x002e1c09, 0x002c1b08, 0x00291a07, 0x00281b08, 0x00271b08, 0x00241908, 0x00201608, 0x001d1408, 0x001e150b, 0x001c140a, 0x001a1208, 0x001a1208, 0x00191208, 0x0018120a, 0x0018130a, 0x0017130b, 0x0017130b, 0x0016130b, 0x00141008, 0x00111008, 0x00121008, 0x00121008, 0x00131009, 0x00131009, 0x00131009, 0x00131009, 0x00131009, 0x0013120b, 0x0013120b, 0x0012110a, 0x0013120b, 0x0013120a, 0x0012110a, 0x0013120b, 0x0013120a, 0x0014110a, 0x00141209, 0x0015140b, 0x0013140a, 0x0013140a, 0x0013140a, 0x0013140a, 0x0014140b, 0x0013140a, 0x0013140a, 0x0013140a, 0x0012150a, 0x00101409, 0x000d150b, 0x000c150c, 0x000c140c, 0x000c150c, 0x000c170d, 0x000e1810, 0x000f1910, 0x000e1810, 0x00121a11, 0x00151a11, 0x00171c12, 0x00191c14, 0x00191c14, 0x001b1c16, 0x00181c16, 0x00191c16, 0x00181d16, 0x00161c17, 0x00161c17, 0x00151c15, 0x00151c15, 0x00161b14, 0x00151a14, 0x00151a14, 0x00141813, 0x00131712, 0x00131712, 0x00131712, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x0024250b, 0x0026280c, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x00494a0f, 0x004c4d0f, 0x00505010, 0x009e8213, 0x00cca316, 0x00c8a015, 0x007b6d12, 0x00595a12, 0x005c5c12, 0x005c5c11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x00736a13, 0x00b49415, 0x00cba417, 0x00c9a318, 0x00b19216, 0x00897714, 0x00686212, 0x00605d11, 0x00605d12, 0x00605e12, 0x00636012, 0x007c7013, 0x00a68916, 0x00c6a118, 0x00cca418, 0x00cba418, 0x00b39317, 0x00706813, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5d12, 0x005b5b12, 0x00605c11, 0x00b49314, 0x00cca316, 0x00b69314, 0x00595510, 0x004d4e0f, 0x00494a10, 0x0045470e, 0x0043440e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0032330c, 0x002d2f0b, 0x00292b0a, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x00101711, 0x00101711, 0x00121812, 0x00121812, 0x00121812, 0x00111812, 0x00131712, 0x00121712, 0x00111611, 0x00111611, 0x00111611, 0x00121712, 0x00121712, 0x00111712, 0x00121712, 0x00121712, 0x00131712, 0x00141712, 0x00121611, 0x00141812, 0x00141812, 0x00141811, 0x00141811, 0x00141810, 0x00141810, 0x00161810, 0x00161810, 0x0016180e, 0x0017170e, 0x0018160e, 0x0018160e, 0x0017150c, 0x0016140c, 0x0016140b, 0x0016140b, 0x0015140b, 0x0018170e, 0x0018170e, 0x0016140b, 0x00131308, 0x00101208, 0x00101208, 0x00101006, 0x00121006, 0x00121008, 0x00131008, 0x00141009, 0x00130f08, 0x00130f09, 0x00111009, 0x00111008, 0x00111008, 0x00111108, 0x00131109, 0x0014120a, 0x0014120a, 0x0014120c, 0x0013120c, 0x0014120c, 0x0014120b, 0x0014130c, 0x0014130c, 0x0014130b, 0x00171108, 0x00181208, 0x00171005, 0x00181207, 0x00191208, 0x001a1209, 0x001b130a, 0x001c1308, 0x00201509, 0x00241609, 0x0024170b, 0x0024180b, 0x0024180a, 0x0025180b, 0x0026190c, 0x00271a0c, 0x00271b0a, 0x00281c08, 0x00281c08, 0x002a1c0a, 0x002a1c0a, 0x002a1c0a, 0x00281b09, 0x00271a0a, 0x00271a0a, 0x00271b0a, 0x00261a09, 0x00261a09, 0x00251a09, 0x0024190c, 0x0020180c, 0x001c1509, 0x001a1508, 0x00191508, 0x00181406, 0x00191407, 0x00191406, 0x001b1407, 0x001a1408, 0x001a1407, 0x00191407, 0x001a1407, 0x001d170a, 0x001f1709, 0x00201708, 0x00231808, 0x00241c09, 0x00241c08, 0x00271d09, 0x002c200a, 0x002f2008, 0x00342008, 0x00382408, 0x003e2706, 0x00442b0a, 0x0048300c, 0x004f350c, 0x00573a0b, 0x0064430a, 0x007c590d, 0x00b8992d, 0x00ccb423, 0x00ccb810, 0x00c9b80c, 0x00cab80c, 0x00c8ba0a, 0x00cbba11, 0x00ab8e0b, 0x00745400, 0x005b3e00, 0x00493204, 0x003b2a05, 0x002e2100, 0x00382c0a, 0x00392e0c, 0x0033280b, 0x002c240b, 0x00241c08, 0x001b1706, 0x00181609, 0x00111409, 0x000e1207, 0x000d1208, 0x000d140a, 0x000c1208, 0x00080f05, 0x00080e04, 0x00080e04, 0x00090d04, 0x00080c03, 0x000c0e06, 0x000c0f06, 0x00100f08, 0x00120f07, 0x00151108, 0x00171207, 0x00181407, 0x00191307, 0x00191307, 0x001b1307, 0x001b1207, 0x001b1207, 0x001c1308, 0x001c1107, 0x001c1107, 0x001c1207, 0x001c1107, 0x001e1108, 0x001e1108, 0x001e1108, 0x001e1108, 0x001e1107, 0x001d1107, 0x001e1408, 0x001c1308, 0x001b1409, 0x00191408, 0x00181308, 0x00181209, 0x00181108, 0x00171008, 0x00161008, 0x00130f08, 0x00110f07, 0x000f0e05, 0x000f0e06, 0x000c0f04, 0x000c1005, 0x000e1007, 0x00101207, 0x00131208, 0x00161208, 0x00181308, 0x00191308, 0x0020170b, 0x0025180a, 0x002a1b08, 0x002c1b05, 0x00352204, 0x00402a04, 0x004b2d09, 0x005b370a, 0x00724b08, 0x0088600b, 0x008a6102, 0x008b6303, 0x008b5f00, 0x00845300, 0x00754700, 0x005f3400, 0x00573406, 0x004a3008, 0x00442e0a, 0x00402a08, 0x003c2408, 0x00392207, 0x00361f06, 0x00341e06, 0x00321d04, 0x00311c05, 0x002e1c07, 0x002b1b07, 0x00281906, 0x00271804, 0x00271804, 0x00261804, 0x00261707, 0x00241809, 0x0024180b, 0x0023190b, 0x0020160a, 0x001c1406, 0x001b1204, 0x001c1104, 0x001c1305, 0x001c1304, 0x001d1101, 0x00201301, 0x00241404, 0x00271706, 0x002c1b08, 0x002f1c08, 0x00301d09, 0x0034200b, 0x0038220c, 0x0039230d, 0x003a230d, 0x003a230c, 0x0039210b, 0x003a210a, 0x0039210a, 0x00382009, 0x00382009, 0x00372009, 0x00352009, 0x00332009, 0x002f1f08, 0x002c1d07, 0x002b1c08, 0x002c1c08, 0x00291b08, 0x00261908, 0x00231608, 0x0022170a, 0x0022170b, 0x001f1408, 0x001d1206, 0x001c1108, 0x001a1208, 0x0019130a, 0x0017130b, 0x0016140b, 0x0014130a, 0x00111008, 0x00131209, 0x0014110a, 0x0012110a, 0x0012110a, 0x0013100a, 0x0013100a, 0x0012110a, 0x0012110a, 0x0013110b, 0x0013110b, 0x0012110a, 0x00101009, 0x00101008, 0x00121109, 0x0014120a, 0x00141109, 0x00141109, 0x00141008, 0x00131108, 0x00131108, 0x00121108, 0x00121108, 0x00121108, 0x00131208, 0x00141409, 0x0017140a, 0x0016140a, 0x0016150b, 0x0014150a, 0x0012160c, 0x0012170e, 0x0012180e, 0x0013180f, 0x00121810, 0x00121911, 0x00101810, 0x00101810, 0x00141911, 0x00181b12, 0x00191a12, 0x001a1b14, 0x001b1c14, 0x001b1c16, 0x00181b14, 0x001a1d17, 0x00191e17, 0x00161c17, 0x00161c17, 0x00151c15, 0x00151c15, 0x00161b14, 0x00151b14, 0x00141a13, 0x00141912, 0x00131812, 0x00131813, 0x00141813, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x001d200a, 0x001d2008, 0x00202309, 0x0024250b, 0x0026280a, 0x002d2f0a, 0x0032330c, 0x0034350c, 0x00393b0d, 0x003c3e0c, 0x0041420d, 0x0044450d, 0x0048490f, 0x004b4c0f, 0x004f5010, 0x00685f10, 0x00c39c15, 0x00cca316, 0x00b09014, 0x005e5c11, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x00636012, 0x00958014, 0x00c09d16, 0x00cba417, 0x00caa317, 0x00c6a117, 0x00bb9816, 0x00b49415, 0x00b69515, 0x00c19d17, 0x00c8a218, 0x00cca418, 0x00cba418, 0x00c19c18, 0x00978014, 0x00646213, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5c12, 0x00585912, 0x00887413, 0x00caa116, 0x00caa116, 0x00847012, 0x004f5010, 0x004c4d0f, 0x0048490f, 0x0045470e, 0x0041420e, 0x003e400c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x00292b0a, 0x0026280c, 0x0020230a, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00111812, 0x00111812, 0x00131812, 0x00131812, 0x00131812, 0x00131712, 0x00131812, 0x00131812, 0x00141813, 0x00141813, 0x00141814, 0x00141914, 0x00141a14, 0x00131914, 0x00141914, 0x00161814, 0x00171814, 0x00171711, 0x00151610, 0x0014150f, 0x0014150f, 0x0014140f, 0x0015140f, 0x0015140d, 0x0015140e, 0x0015150c, 0x0015150c, 0x0014140b, 0x0014140b, 0x0017150c, 0x0017150d, 0x0015140b, 0x0014130a, 0x0014120a, 0x00141109, 0x00141109, 0x0014130a, 0x0014130a, 0x00131209, 0x00101208, 0x00101108, 0x00101108, 0x00101008, 0x00101008, 0x00111008, 0x00121008, 0x00141109, 0x00110e07, 0x00101009, 0x00101009, 0x000f1008, 0x00101008, 0x00101008, 0x00101109, 0x0014100a, 0x0015100b, 0x0015100b, 0x0016100c, 0x0014120c, 0x0014120c, 0x0015120c, 0x0015120d, 0x0016120c, 0x001c1009, 0x001c1107, 0x001d1206, 0x001f1408, 0x00201408, 0x0020160b, 0x0023160b, 0x0024180b, 0x0026180a, 0x0027180a, 0x0029190b, 0x002b1b0c, 0x002c1c0c, 0x002c1c0f, 0x002d1d0e, 0x002e1d0d, 0x002d1e0b, 0x002d1c08, 0x002d1c08, 0x002d1e09, 0x002c1d08, 0x002b1c08, 0x00291a08, 0x00271805, 0x00251804, 0x00241704, 0x00201400, 0x001e1300, 0x001e1300, 0x001c1406, 0x001b1508, 0x00181507, 0x00161506, 0x00141505, 0x00151404, 0x00171304, 0x001c1404, 0x00201607, 0x00211708, 0x00211708, 0x00201605, 0x00201706, 0x00241908, 0x00281b0b, 0x00281a09, 0x002a1c08, 0x00281c06, 0x00281d05, 0x002c1f05, 0x00302008, 0x00332307, 0x00382506, 0x003b2704, 0x00402a04, 0x00442d06, 0x00482f08, 0x0050350c, 0x00583b0b, 0x0062420c, 0x00795510, 0x00b4902c, 0x00ccb228, 0x00ccb717, 0x00ccb610, 0x00ccb70c, 0x00c9b908, 0x00cab810, 0x00ae910d, 0x00725100, 0x00563a00, 0x00452d00, 0x00382802, 0x002d1e00, 0x00342509, 0x00362a10, 0x0030250c, 0x0029210a, 0x00211c09, 0x001e1909, 0x00181709, 0x00101207, 0x000e1105, 0x000e1208, 0x000f1308, 0x000e1007, 0x000b0e04, 0x000a0d03, 0x000a0d03, 0x000b0c02, 0x000b0c02, 0x000c0d04, 0x000e0f05, 0x00140f08, 0x00140e08, 0x00140e08, 0x00161009, 0x00181109, 0x00181006, 0x00171006, 0x00181006, 0x00181107, 0x001a1108, 0x001a1108, 0x00191007, 0x001a1007, 0x001b1007, 0x001b1007, 0x001c1108, 0x001b1108, 0x001b1108, 0x001b1108, 0x001a1108, 0x00191007, 0x00181107, 0x00181105, 0x00191306, 0x00191306, 0x00181108, 0x00181009, 0x00161008, 0x00151008, 0x00141008, 0x00120e07, 0x00110e06, 0x00100d05, 0x000f0d05, 0x000f0d05, 0x00100f05, 0x00101005, 0x00121108, 0x00131108, 0x00161108, 0x0019120c, 0x001a130b, 0x001f1508, 0x00241808, 0x00281a06, 0x00301c05, 0x00362004, 0x00402707, 0x004b2f09, 0x00523309, 0x005b3806, 0x00633c04, 0x00684005, 0x006b3f04, 0x006c4002, 0x00683c00, 0x00613b01, 0x00583502, 0x00543204, 0x004e3108, 0x00482d07, 0x00452c09, 0x0041290a, 0x003c2509, 0x00392209, 0x00382309, 0x00372108, 0x00341f07, 0x00321e05, 0x00301c05, 0x00301c05, 0x002d1c04, 0x002d1b05, 0x002c1b05, 0x002d1c08, 0x002e1d0c, 0x002e1d0d, 0x002e1d0d, 0x002b1d0d, 0x00271b0a, 0x00241807, 0x00231706, 0x00211407, 0x00211504, 0x00201401, 0x00221403, 0x00241504, 0x00281808, 0x002a1807, 0x002e1c08, 0x002e1c06, 0x00311d07, 0x00372008, 0x003c230c, 0x003e250a, 0x0040270b, 0x0042280d, 0x0042280d, 0x0042280f, 0x0042280e, 0x0040280d, 0x0040270b, 0x003d280c, 0x003c270e, 0x0038260f, 0x0033230a, 0x00302006, 0x00301e04, 0x00311c05, 0x002d1c08, 0x00281a08, 0x00271809, 0x0026180a, 0x00241608, 0x00211406, 0x001e1205, 0x001d1206, 0x001b1208, 0x00181309, 0x00161409, 0x0013140a, 0x00121108, 0x0013120a, 0x0013120b, 0x0012110a, 0x0012110a, 0x0012110a, 0x0012110a, 0x0012110a, 0x0012110a, 0x0013100a, 0x0013100a, 0x0013100a, 0x00121009, 0x00111009, 0x00101009, 0x00101009, 0x00111009, 0x00121009, 0x00131008, 0x00121008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00141109, 0x00161008, 0x00151108, 0x00151208, 0x00141308, 0x0016130b, 0x0016140b, 0x0016150c, 0x0016160d, 0x0017160f, 0x00181710, 0x0017160f, 0x0016160f, 0x00181710, 0x001c1910, 0x001c1910, 0x001a1811, 0x001a1710, 0x00191811, 0x001a1913, 0x001c1d18, 0x001b1e18, 0x00181d16, 0x00171d16, 0x00161c15, 0x00161c15, 0x00151c15, 0x00151c15, 0x00151c15, 0x00141b14, 0x00131a14, 0x00121a14, 0x00131b14, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202309, 0x0024250c, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x00515110, 0x00947c13, 0x00caa216, 0x00caa216, 0x00917c13, 0x00585912, 0x005b5b12, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5d11, 0x006b6412, 0x00957f14, 0x00b59516, 0x00c7a117, 0x00cba418, 0x00cca418, 0x00cba418, 0x00cba418, 0x00c39e18, 0x00b19316, 0x00947f15, 0x006b6513, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5c12, 0x005b5b12, 0x00666011, 0x00bc9815, 0x00cca316, 0x00b08f14, 0x00565410, 0x004d4e10, 0x00494a0f, 0x0047480e, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0024250b, 0x00202309, 0x001d2008, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x00060c07, 0x00131914, 0x00131914, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00141a14, 0x00141a14, 0x00131914, 0x00141914, 0x00171813, 0x00171812, 0x00161510, 0x0014130d, 0x0014130c, 0x0014110b, 0x0014110b, 0x0014110b, 0x0014110b, 0x0014110b, 0x00141109, 0x00141109, 0x00121108, 0x00121108, 0x0014140b, 0x0015140c, 0x0013120a, 0x00101008, 0x00111008, 0x00121009, 0x00121009, 0x00121009, 0x00101009, 0x00101008, 0x00101108, 0x000f1007, 0x000f1007, 0x00101009, 0x00101009, 0x00100f08, 0x000f0e07, 0x0012110a, 0x000f1008, 0x000d1008, 0x000d1008, 0x000f1008, 0x00101008, 0x00121008, 0x00131008, 0x00141109, 0x0017100b, 0x00171009, 0x00181009, 0x0018110a, 0x0018110a, 0x0018130a, 0x0019140a, 0x001a130a, 0x001f1308, 0x001f1307, 0x00241808, 0x0028190a, 0x0028190a, 0x0029190b, 0x002a1a0c, 0x002c1b0b, 0x002c1b0b, 0x002d1c0c, 0x002e1d0b, 0x00301e0c, 0x00301f0d, 0x00301f0d, 0x0031200e, 0x0032200e, 0x00311f0a, 0x00301d06, 0x002f1c05, 0x002f1e08, 0x002d1d07, 0x002c1c06, 0x002b1a06, 0x00281805, 0x00281806, 0x00281808, 0x00241705, 0x00241506, 0x00221405, 0x00201404, 0x001f1506, 0x001d1606, 0x001d1807, 0x001c1805, 0x001f1906, 0x00231b08, 0x00271b08, 0x002b1c09, 0x002c1d0a, 0x002c1d0a, 0x002c1c08, 0x002c1c08, 0x002c1c08, 0x002c1c08, 0x002d1b06, 0x00301d04, 0x00302006, 0x00302104, 0x00342205, 0x00362508, 0x003b2a0d, 0x003e2d0d, 0x0041300c, 0x0046330c, 0x0048340d, 0x004a3610, 0x00503910, 0x00563c0c, 0x0061410e, 0x00784e10, 0x00a3791f, 0x00c8a126, 0x00c9a714, 0x00ccaa11, 0x00cbac0d, 0x00cbaf10, 0x00ccb018, 0x00ad8c14, 0x00704e00, 0x00553701, 0x00422800, 0x00362402, 0x002a1b00, 0x00312307, 0x0033270d, 0x002f240c, 0x0028200a, 0x00201b08, 0x001d1909, 0x00171608, 0x00121207, 0x00101106, 0x00101106, 0x00101106, 0x00101108, 0x000d0f05, 0x000e0f05, 0x000f0f06, 0x000f0d04, 0x000f0d04, 0x000e0d04, 0x00100f05, 0x00121008, 0x00140f08, 0x00120e06, 0x00140f08, 0x00141008, 0x00141007, 0x00141008, 0x00151108, 0x00151108, 0x00151108, 0x00151108, 0x00141007, 0x00141007, 0x00151007, 0x00151007, 0x00171008, 0x00171008, 0x00161008, 0x00151109, 0x00151009, 0x00141008, 0x00171108, 0x00181108, 0x00181209, 0x00181309, 0x00171109, 0x00171009, 0x00151008, 0x00141008, 0x00140f08, 0x00140f08, 0x00140f08, 0x00121008, 0x00121008, 0x00140f08, 0x00131008, 0x00131006, 0x00131107, 0x00151208, 0x00181108, 0x001c140c, 0x001c130c, 0x001e1508, 0x00241804, 0x002c1b05, 0x00352008, 0x0040280b, 0x004c310e, 0x004e3008, 0x00543407, 0x00593605, 0x005c3804, 0x005e3905, 0x005f3804, 0x00603804, 0x00603804, 0x005e3804, 0x00583504, 0x00543204, 0x00523206, 0x004d2e04, 0x00482c05, 0x00462d08, 0x00422a0c, 0x003f280b, 0x003f280c, 0x003d260c, 0x003c240b, 0x003a2309, 0x00392108, 0x00382108, 0x00372007, 0x00372007, 0x00342005, 0x00341f05, 0x00341e08, 0x00341d0a, 0x00341f0b, 0x00341f0a, 0x0032200a, 0x0030200b, 0x002f200c, 0x002d1c08, 0x002d1c07, 0x002c1b05, 0x002c1c06, 0x002c1904, 0x002f1c06, 0x002d1b04, 0x00301c04, 0x00331f05, 0x00372106, 0x00382306, 0x003b2408, 0x003d2707, 0x00402808, 0x00412b0a, 0x00412b0a, 0x00422c0c, 0x00432c0d, 0x00452c0c, 0x00462a0b, 0x0045290c, 0x0044290e, 0x0040290f, 0x00402b10, 0x003e290d, 0x003b250a, 0x00382409, 0x0033210a, 0x002e1d09, 0x002c1b0a, 0x002c190b, 0x00291809, 0x00261607, 0x00211404, 0x001f1304, 0x001d1306, 0x001a1208, 0x00191408, 0x0018140a, 0x00141308, 0x00141109, 0x00141109, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x00121009, 0x00121009, 0x00111009, 0x00101009, 0x00101009, 0x00101009, 0x00111009, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00131008, 0x00140f08, 0x00140f08, 0x00131008, 0x00121108, 0x00141109, 0x00141109, 0x00141109, 0x0014120a, 0x0016110b, 0x0017120c, 0x0018130d, 0x001a140f, 0x001b140f, 0x001c140e, 0x001d150f, 0x001b1410, 0x0017100b, 0x0014130c, 0x00191812, 0x001b1c17, 0x001b1d17, 0x00181d16, 0x00181e17, 0x00171d16, 0x00171d16, 0x00151c16, 0x00151c15, 0x00151c15, 0x00151c15, 0x00131b14, 0x00121a14, 0x00131b14, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003e400c, 0x0041420e, 0x0045470e, 0x0048490f, 0x004b4c0f, 0x004d4e10, 0x00595510, 0x00b79414, 0x00cca316, 0x00c39c15, 0x00786b12, 0x00595a12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005c5d11, 0x00636011, 0x00706713, 0x00847413, 0x008d7a14, 0x00887714, 0x00786e13, 0x006c6514, 0x00626013, 0x005d5e13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5c11, 0x005b5b12, 0x005b5a11, 0x00a48714, 0x00cca316, 0x00c49d15, 0x00706410, 0x004f5010, 0x004b4c0f, 0x0048490f, 0x0045470e, 0x0041420e, 0x003e400c, 0x003b3c0d, 0x0036370c, 0x0034350c, 0x0030310c, 0x002c2d0a, 0x0026280b, 0x0020230a, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00141914, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00151a14, 0x00191c16, 0x00181712, 0x0013110b, 0x00110f08, 0x00141209, 0x00131008, 0x00151109, 0x00151109, 0x00151009, 0x00140f08, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00111008, 0x00101007, 0x00101008, 0x00110f08, 0x00110f08, 0x00121009, 0x00101009, 0x00101008, 0x00101108, 0x00101108, 0x00101108, 0x00101008, 0x00101008, 0x00100f08, 0x0012110a, 0x00121009, 0x00101009, 0x0010120a, 0x000f120a, 0x00131109, 0x00151109, 0x0018110a, 0x0018110a, 0x0018120a, 0x0018130a, 0x001b130a, 0x001c1309, 0x001e140b, 0x001e140b, 0x001f150b, 0x0023180d, 0x00241a0e, 0x00291c10, 0x002a1c0d, 0x002b1c0b, 0x002c1c08, 0x002d1c08, 0x002d1c08, 0x00301c0a, 0x00301c0a, 0x002f1c08, 0x00301c0a, 0x00301d09, 0x00301e09, 0x00301e09, 0x00301e09, 0x00301e07, 0x00301f07, 0x00321e06, 0x00321e04, 0x00321e04, 0x00322005, 0x00301f04, 0x00301e03, 0x002f1d02, 0x002f1e05, 0x002e1e06, 0x002e1e07, 0x002d1e08, 0x002c1d08, 0x002b1c08, 0x002a1b08, 0x00291c08, 0x00271c08, 0x00281e09, 0x002a210b, 0x002c210c, 0x002d2009, 0x002f1f09, 0x00301e08, 0x00342009, 0x0035210b, 0x0036230a, 0x0036220c, 0x0038240d, 0x0038230c, 0x0039230b, 0x003c2509, 0x003c2809, 0x003c2808, 0x003c2808, 0x00402a0c, 0x00422c0f, 0x00452f11, 0x00493110, 0x004a330f, 0x004d3610, 0x0050390f, 0x00543c0e, 0x0059400c, 0x0065440d, 0x00754809, 0x00885706, 0x00a06d07, 0x00a87803, 0x00af7c02, 0x00b18304, 0x00b28809, 0x00b38914, 0x00946e0e, 0x00664000, 0x00543404, 0x00422800, 0x003a2806, 0x002d1e01, 0x00302206, 0x002d2008, 0x002b2007, 0x00241c07, 0x001e1907, 0x001c1809, 0x00181509, 0x0015150b, 0x00141408, 0x00141409, 0x00141409, 0x0014130a, 0x0014130a, 0x00131209, 0x00131209, 0x00141109, 0x00141109, 0x0014130a, 0x00141109, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00111008, 0x00101008, 0x00101008, 0x00101008, 0x00101008, 0x00101007, 0x00101007, 0x000f0f05, 0x000f0f05, 0x00100e05, 0x00110f07, 0x00121008, 0x00111008, 0x00101009, 0x00101009, 0x00101009, 0x00101009, 0x00140f08, 0x00140e08, 0x00151008, 0x00151008, 0x00151008, 0x00151008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00141109, 0x00151109, 0x00181108, 0x00181309, 0x00171408, 0x001a160b, 0x001a160a, 0x001e150a, 0x0020170c, 0x00241910, 0x00281d0c, 0x002a1d07, 0x002e1c04, 0x00412b10, 0x005b3d19, 0x00654519, 0x006a4816, 0x006c4711, 0x006f450e, 0x00724510, 0x00714610, 0x006c4410, 0x0068420d, 0x0064400b, 0x00603c08, 0x005c3704, 0x005b3704, 0x00583504, 0x00543204, 0x004f3004, 0x004c3007, 0x004b3008, 0x00472e07, 0x00462d08, 0x00462d08, 0x00462c09, 0x00432b0b, 0x00432b0b, 0x00452b0c, 0x00452b0c, 0x00462a0c, 0x00442809, 0x00422609, 0x0041250b, 0x0041240d, 0x0041250c, 0x003e240a, 0x003a2208, 0x00392409, 0x00382409, 0x00392308, 0x003a2308, 0x003a2308, 0x003b2409, 0x003c240a, 0x003d240c, 0x003c250b, 0x003c2609, 0x003f2708, 0x003f2707, 0x00412805, 0x00452c07, 0x004b3008, 0x0050340b, 0x0053360c, 0x0054360d, 0x0054360d, 0x0053350c, 0x00513109, 0x00513008, 0x004d2d06, 0x004c2d09, 0x00492d0c, 0x0045290d, 0x0043280d, 0x0041290d, 0x003d280b, 0x003a270c, 0x0038240e, 0x0034200d, 0x00301c0d, 0x002f1c0b, 0x002e1b09, 0x002a1908, 0x00251808, 0x0024180a, 0x0021160b, 0x001b1206, 0x00191208, 0x00181308, 0x00171209, 0x00161208, 0x0016120a, 0x0016120a, 0x00161209, 0x00151009, 0x00141008, 0x00141008, 0x0013100a, 0x0013100a, 0x0013100a, 0x0013100a, 0x0012110a, 0x0012110a, 0x0011110a, 0x00101009, 0x00111009, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00140f09, 0x00121009, 0x00101009, 0x00101009, 0x00101008, 0x00121008, 0x00141008, 0x00151109, 0x00161009, 0x0018110a, 0x0018110a, 0x001a120c, 0x001c140d, 0x001c130d, 0x001c120c, 0x0018100b, 0x00130c07, 0x0014120c, 0x001b1b14, 0x00191b14, 0x001b1e18, 0x001a2018, 0x00181f17, 0x00171d16, 0x00171d16, 0x00181e18, 0x00171d18, 0x00161c17, 0x00161c17, 0x00141c15, 0x00141c15, 0x00141c15, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x00141810, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2008, 0x00202309, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x0040400d, 0x0043440e, 0x0047480e, 0x00494a0f, 0x004c4d0f, 0x004f5010, 0x00726511, 0x00c39c15, 0x00cca316, 0x00b99615, 0x006a6312, 0x00595a12, 0x005b5b12, 0x005b5b11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005d5e12, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005e5f13, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5c11, 0x005c5c12, 0x005b5b12, 0x00585811, 0x008f7913, 0x00c9a116, 0x00c9a116, 0x00907812, 0x00505010, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0034350c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x000f130b, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00151a13, 0x00151a13, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a14, 0x00141a14, 0x00141a14, 0x00141a14, 0x00161a13, 0x00191b14, 0x0013120b, 0x000f0e07, 0x00100e05, 0x00100e05, 0x00131008, 0x00151109, 0x00151109, 0x00151009, 0x00140f08, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00110f07, 0x00100e05, 0x00100f05, 0x000f0f05, 0x00100f07, 0x00110f08, 0x00121009, 0x00121009, 0x00101009, 0x00101008, 0x00101108, 0x00101108, 0x00101008, 0x00101006, 0x00111006, 0x00131008, 0x00110f07, 0x00140d07, 0x00140f08, 0x0015120a, 0x0015130c, 0x0018120b, 0x001a120c, 0x001c130d, 0x001c130c, 0x001d140c, 0x001e140b, 0x0020160b, 0x0024180e, 0x0024190e, 0x00241a0d, 0x00251b0e, 0x00281a0c, 0x00291b0d, 0x00291b0d, 0x002a1b0c, 0x002b1909, 0x002c1906, 0x002c1a05, 0x002e1c06, 0x00301c06, 0x00321c06, 0x00301c05, 0x00311c06, 0x00331d08, 0x00352008, 0x00372108, 0x00382308, 0x00392408, 0x003a2608, 0x003b2608, 0x003b2608, 0x003c2708, 0x003c2809, 0x003c2807, 0x003b2706, 0x003a2605, 0x00382604, 0x00392605, 0x00382807, 0x00382709, 0x0036270a, 0x0035250b, 0x0035240a, 0x0036240c, 0x0032220a, 0x0032240c, 0x0033240c, 0x00322309, 0x00342209, 0x00352208, 0x00372108, 0x00392208, 0x003a2308, 0x003c2509, 0x003d280c, 0x003f280e, 0x00412910, 0x00432a0f, 0x00442c0d, 0x00452f0c, 0x00452f0b, 0x00462f0a, 0x004a300c, 0x004c330d, 0x0051350c, 0x0054380c, 0x0058390b, 0x005a3c0c, 0x005c3f0c, 0x0062430c, 0x0068480c, 0x00744f0f, 0x0082530c, 0x008a5504, 0x00975f04, 0x009a6401, 0x009d6201, 0x00945c00, 0x008d5800, 0x00865400, 0x00724800, 0x00603c08, 0x00503104, 0x00442c04, 0x003d2b0b, 0x00312005, 0x002f2006, 0x002b1d06, 0x002a1e08, 0x00241c08, 0x001f1808, 0x001d1809, 0x001a1609, 0x0018140b, 0x00171309, 0x0019160c, 0x0019150c, 0x0016120a, 0x0016120a, 0x00151109, 0x00151109, 0x00141008, 0x00141008, 0x00151109, 0x00141008, 0x00121008, 0x00121008, 0x00131008, 0x00131008, 0x00111008, 0x00101008, 0x00101008, 0x00101008, 0x00101108, 0x000f1008, 0x000f1008, 0x000c1007, 0x000d0f05, 0x000d0f05, 0x000f1007, 0x00101008, 0x00101108, 0x00101009, 0x00101009, 0x00101009, 0x00101009, 0x00110f08, 0x00120e08, 0x00140f09, 0x00140f09, 0x00141008, 0x00141008, 0x00141008, 0x00141008, 0x00131008, 0x00131008, 0x00141008, 0x00151109, 0x00161108, 0x00181309, 0x0019140b, 0x00191408, 0x001c150a, 0x001e1708, 0x00211608, 0x00241809, 0x00271b0d, 0x00291d0b, 0x002e1e07, 0x00342006, 0x00543b1c, 0x006d491e, 0x00724813, 0x00805418, 0x00845613, 0x0088550f, 0x008e5712, 0x008e5816, 0x008b5818, 0x00835518, 0x007a5314, 0x00765012, 0x00754c10, 0x006e450b, 0x00684008, 0x00623d08, 0x005a3805, 0x00583908, 0x00593908, 0x00573807, 0x00543504, 0x00543606, 0x0051350b, 0x004f340c, 0x004c310b, 0x004c300a, 0x004c300a, 0x004c300a, 0x004a2d08, 0x00482b0a, 0x0047290a, 0x0044270a, 0x0045280c, 0x0044280c, 0x0042280b, 0x0042280c, 0x0041280b, 0x00402609, 0x00412709, 0x00412709, 0x0043280c, 0x00452a0d, 0x00482c10, 0x004a2e0e, 0x004c2f0e, 0x0050310e, 0x00553511, 0x005e3c13, 0x00664312, 0x006c4715, 0x00744c18, 0x00784e1a, 0x00784e18, 0x00784e1a, 0x00784c18, 0x00744914, 0x006f4610, 0x006a430f, 0x00613d0d, 0x00553407, 0x004b2907, 0x00452705, 0x00402606, 0x003c2507, 0x00382306, 0x00372209, 0x0038230f, 0x0034200d, 0x00331f0a, 0x0033200b, 0x002e1d0b, 0x002a1b0a, 0x00291b0c, 0x0027190d, 0x00211509, 0x00201609, 0x0020170b, 0x001c140c, 0x001b130b, 0x001b130b, 0x001b130b, 0x0019130a, 0x00181209, 0x00151008, 0x00151008, 0x00141008, 0x00141008, 0x0014100a, 0x0013100a, 0x0013100a, 0x00101009, 0x00111109, 0x00101009, 0x00121009, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00131008, 0x00121009, 0x00101009, 0x00100f08, 0x00100f08, 0x00101008, 0x00101008, 0x00141008, 0x00151009, 0x00151108, 0x00161208, 0x0016130a, 0x0017120a, 0x0018130b, 0x0018120b, 0x0017120b, 0x00120d07, 0x000e0904, 0x00100f08, 0x00161810, 0x00191c15, 0x001b1f18, 0x00192018, 0x00181f17, 0x00181f17, 0x00181f17, 0x00181f18, 0x00171d18, 0x00161c17, 0x00161c17, 0x00151c16, 0x00151c15, 0x00151c15, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180c, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0041420d, 0x0044450e, 0x0048490f, 0x004b4c10, 0x004d4e0f, 0x004f4f10, 0x008b7512, 0x00c8a015, 0x00cca316, 0x00b39115, 0x00656011, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e12, 0x005e5f13, 0x005d5e12, 0x005e5f13, 0x005d5e12, 0x005d5e12, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5c12, 0x005b5b12, 0x00585811, 0x00867413, 0x00c59f15, 0x00cba216, 0x00a48614, 0x00535210, 0x004d4e0f, 0x004b4c10, 0x0048490f, 0x0044450e, 0x0041420e, 0x003e400c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x0024250c, 0x00202309, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a13, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00181a14, 0x00191a14, 0x0011120c, 0x000e0f07, 0x000c1007, 0x000c0f06, 0x000e1006, 0x00141109, 0x00151109, 0x00141008, 0x00141008, 0x00121006, 0x00121006, 0x00121006, 0x00121006, 0x00111007, 0x00110f06, 0x00110f07, 0x00130f08, 0x00121008, 0x00131008, 0x00131008, 0x00141209, 0x00121008, 0x00131107, 0x00131107, 0x00131208, 0x00131207, 0x00151307, 0x00141005, 0x00161006, 0x00191007, 0x00191007, 0x001a1108, 0x001e150c, 0x0020160f, 0x001e140d, 0x0021150e, 0x00231710, 0x00241610, 0x0024180e, 0x0025190d, 0x00261a0d, 0x0023160a, 0x0021180a, 0x00201708, 0x001f1607, 0x00211507, 0x00221608, 0x00211405, 0x00241405, 0x00271604, 0x002b1907, 0x00291a06, 0x002c1d08, 0x00301d08, 0x00342006, 0x00372206, 0x003b2609, 0x003e260c, 0x0043280e, 0x00462b0c, 0x00462c0a, 0x0048310a, 0x004a3308, 0x004b3308, 0x004b3308, 0x004c340a, 0x004c340c, 0x004c340b, 0x004d340b, 0x004d340c, 0x004e340c, 0x004b310b, 0x0049320d, 0x0044300c, 0x0041300c, 0x0040300c, 0x00402d0c, 0x0040290c, 0x003e270c, 0x003e260d, 0x003d240c, 0x003d250b, 0x003f250c, 0x0040250a, 0x00402609, 0x003f2708, 0x003f2708, 0x00422a09, 0x00442c0b, 0x00442c0c, 0x00482e11, 0x00452b0c, 0x004a300c, 0x004f340d, 0x004f350c, 0x0051370b, 0x00573b0c, 0x005c3c0c, 0x005e3b07, 0x00654009, 0x006c440a, 0x006e450a, 0x0074490c, 0x00794f0c, 0x007e540c, 0x008b5f11, 0x009b6912, 0x00a57416, 0x00af8017, 0x00bc8c1f, 0x00c08823, 0x00996109, 0x00824e04, 0x00784e04, 0x00633e00, 0x00553709, 0x00483205, 0x00403008, 0x003b2808, 0x00342207, 0x002e1e08, 0x00281b09, 0x0026190a, 0x00221809, 0x001f170a, 0x001d170a, 0x001a1509, 0x00191408, 0x00181309, 0x0018110a, 0x0018110a, 0x0018110a, 0x0018110a, 0x0017100b, 0x0017100b, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x0014100a, 0x0013100a, 0x00121009, 0x00121009, 0x00110f08, 0x00110e0a, 0x00110e0a, 0x00110e0a, 0x00110e0a, 0x00110d0a, 0x00100e0a, 0x000d0d08, 0x000c0d08, 0x000e0d06, 0x000f0e07, 0x00110f08, 0x00110f08, 0x00110f08, 0x00100f08, 0x00140f09, 0x00140f09, 0x00120f0b, 0x00120f0b, 0x0013100c, 0x0013100a, 0x00121109, 0x00121108, 0x00121108, 0x0013120a, 0x0014120b, 0x0014110b, 0x0014110a, 0x00141208, 0x00161208, 0x00181308, 0x00181308, 0x00191207, 0x001c1608, 0x00201608, 0x00221606, 0x00251706, 0x00291a08, 0x002c1d0c, 0x00311f0a, 0x003d2407, 0x00604016, 0x00744c17, 0x00845617, 0x00a77829, 0x00b38224, 0x00af7d1b, 0x00ac7716, 0x00a87314, 0x00a16c10, 0x009f6810, 0x0099630f, 0x00945d0d, 0x00905a11, 0x0088530c, 0x0085540c, 0x007c4e08, 0x00754908, 0x00714608, 0x006f440a, 0x006c410a, 0x0067400a, 0x0065400c, 0x00613f0d, 0x005b390a, 0x0058360a, 0x0058360c, 0x0057350a, 0x00543307, 0x00513306, 0x00503208, 0x00503208, 0x004b3108, 0x004a310b, 0x00462f0b, 0x00442c0a, 0x00472c0b, 0x00482c0c, 0x00492c0c, 0x00492d0f, 0x00492e10, 0x00492f0e, 0x004d300e, 0x00523410, 0x0054370c, 0x005b3d0c, 0x00694814, 0x006e4a14, 0x00785013, 0x00835412, 0x008a5915, 0x00935f19, 0x0099651b, 0x00986616, 0x00946413, 0x00936212, 0x00905f0f, 0x008e5a0c, 0x0088560e, 0x00815211, 0x00794c12, 0x006e400f, 0x005d3608, 0x004c2c05, 0x00402804, 0x003c2404, 0x00382208, 0x00341e08, 0x00301c05, 0x00301c04, 0x002e1c04, 0x002c1c07, 0x002b1c08, 0x002b1c0c, 0x00291c0e, 0x0025180c, 0x0024180e, 0x0024180e, 0x0022180e, 0x0021150c, 0x0021150c, 0x0020140c, 0x001e140b, 0x001c1409, 0x001b1309, 0x001a1208, 0x00181108, 0x00181108, 0x00181209, 0x00171009, 0x00141008, 0x00141008, 0x00140f08, 0x0014100a, 0x0014100a, 0x00140f09, 0x00140f09, 0x0014100a, 0x00141008, 0x00140f08, 0x00141006, 0x00141007, 0x00141007, 0x00121008, 0x00121008, 0x00121008, 0x00121008, 0x00130f09, 0x00140f09, 0x0014100b, 0x0015110a, 0x0017130a, 0x00171309, 0x0017140a, 0x0018140c, 0x0018140c, 0x00140f08, 0x000f0c04, 0x000c0c04, 0x000b0c04, 0x000c0e06, 0x0013150d, 0x00171c15, 0x00182017, 0x00192018, 0x00182018, 0x00192018, 0x00181f17, 0x00181f15, 0x00181f15, 0x00181f15, 0x00181f15, 0x00181e15, 0x00191e15, 0x00191e15, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0043440e, 0x0045470e, 0x0048490f, 0x004c4d0f, 0x004d4e10, 0x00515110, 0x00967d12, 0x00c9a116, 0x00cca316, 0x00b29115, 0x006a6211, 0x00585912, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005d5e11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5c11, 0x005c5c12, 0x00595a12, 0x00585911, 0x00887513, 0x00c49e16, 0x00cca316, 0x00ac8b14, 0x00595510, 0x004d4e10, 0x004c4d0f, 0x0048490f, 0x0045470e, 0x0043440e, 0x0040400d, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002d2f0b, 0x00292b0b, 0x0026280c, 0x0020230a, 0x00202308, 0x00191c08, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00151a11, 0x00151a11, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a13, 0x00151a14, 0x00151a14, 0x00151a14, 0x00151a13, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00181a14, 0x00191a14, 0x0011120c, 0x000d0f07, 0x000c1007, 0x000c0f06, 0x000c0f06, 0x0011110a, 0x0014110b, 0x00131008, 0x00121008, 0x00121008, 0x00121008, 0x00141006, 0x00141006, 0x00120f05, 0x00120f05, 0x00141006, 0x00161008, 0x00161007, 0x00151007, 0x00151007, 0x00151007, 0x00140f04, 0x00151005, 0x00151005, 0x00181206, 0x00181306, 0x00191408, 0x001e170b, 0x0021160a, 0x0022170b, 0x0020180b, 0x0020190c, 0x00221b0f, 0x0020190d, 0x0020190d, 0x0020180c, 0x001d150b, 0x001d140a, 0x001e1509, 0x001d1408, 0x001c1204, 0x001b1104, 0x001a1104, 0x00181202, 0x001a1203, 0x001c1203, 0x001e1204, 0x00231404, 0x00271804, 0x002b1906, 0x002f1c07, 0x00302008, 0x00332408, 0x003b280c, 0x003f2b0c, 0x00442f0c, 0x004a320e, 0x004e330f, 0x00533510, 0x00593810, 0x005c3c11, 0x00603f13, 0x00604010, 0x0061420d, 0x0061430b, 0x0062430b, 0x0060420a, 0x0060420b, 0x0061400c, 0x00613f0d, 0x005f3c0d, 0x005a390c, 0x0056370d, 0x0050340d, 0x004c340e, 0x004c340f, 0x004a330e, 0x0048300c, 0x00462c0c, 0x00452c0f, 0x00442a0e, 0x00442a0c, 0x00442a0c, 0x00442a0c, 0x00452c0b, 0x00452c09, 0x00452c08, 0x00482e0a, 0x004b300c, 0x004a300b, 0x004f330d, 0x0054340e, 0x00573810, 0x00593b13, 0x005a3c11, 0x00603f13, 0x00654212, 0x00704711, 0x0072470b, 0x007b4f0d, 0x0081540e, 0x0087590d, 0x00926414, 0x009c6f19, 0x00a6791f, 0x00b58c26, 0x00c39b25, 0x00c8a227, 0x00caa421, 0x00ccaa23, 0x00caa120, 0x009e7007, 0x007c4d00, 0x006c4600, 0x005f3f02, 0x00503407, 0x00443004, 0x003e2c07, 0x00372406, 0x00332108, 0x002e1c08, 0x00291b09, 0x00241809, 0x00211609, 0x001d1508, 0x001b1508, 0x001a1508, 0x00191409, 0x00181309, 0x0018110a, 0x0018110a, 0x0018110a, 0x0018110a, 0x0017100b, 0x0017100b, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x0014100a, 0x0013100a, 0x00121009, 0x00121009, 0x00110e0b, 0x00110e0c, 0x00110e0c, 0x00110e0c, 0x00110e0b, 0x00120d0a, 0x00110e0a, 0x000e0d08, 0x000c0d08, 0x000e0d06, 0x000f0e07, 0x00110f08, 0x00110f08, 0x00110f08, 0x00110f08, 0x00140f09, 0x00140f09, 0x00120f0b, 0x00120f0b, 0x0013100a, 0x00131009, 0x00121108, 0x00121108, 0x00121108, 0x0013120a, 0x0013110b, 0x0013100a, 0x00141109, 0x00141208, 0x00161307, 0x00181308, 0x00181308, 0x00191206, 0x001d1608, 0x00211609, 0x00241708, 0x00281808, 0x002c1c09, 0x002d1c0c, 0x0034200b, 0x00412709, 0x00644418, 0x00774f13, 0x008c6214, 0x00b8902d, 0x00cba32c, 0x00caa422, 0x00c99f1c, 0x00c89b1c, 0x00c5971b, 0x00c3921b, 0x00bd8c19, 0x00b88418, 0x00b07b16, 0x00a87312, 0x009d6a0b, 0x00976408, 0x00925f0a, 0x008e5c0c, 0x008b5a10, 0x00885710, 0x00855411, 0x00835414, 0x00805416, 0x007b5014, 0x00744b12, 0x00744912, 0x00714711, 0x006b430c, 0x00664008, 0x00603a04, 0x005b3803, 0x00543401, 0x00543604, 0x00523507, 0x00503308, 0x0050300b, 0x0051300c, 0x0052300d, 0x00502f0c, 0x0051320d, 0x0052330c, 0x005a3810, 0x005f3c10, 0x0068430c, 0x00734c0c, 0x00805911, 0x008c6416, 0x009c7118, 0x00aa7e1b, 0x00b48721, 0x00bb8d25, 0x00c29528, 0x00c19927, 0x00bd9724, 0x00bd9724, 0x00bc9423, 0x00b8841b, 0x00ad7a16, 0x009e6a10, 0x00915f0d, 0x0086560d, 0x00784d0d, 0x00674109, 0x00583707, 0x004b2c07, 0x00422509, 0x003a200a, 0x00301c05, 0x002c1a01, 0x002a1901, 0x00281804, 0x00261804, 0x00241706, 0x00231708, 0x0021180b, 0x0020180c, 0x0020180e, 0x0020180e, 0x00221a10, 0x00221a10, 0x0021180e, 0x0020160c, 0x0020150c, 0x0021180f, 0x0020170d, 0x001f150c, 0x001f150c, 0x001f160c, 0x001d140b, 0x001a1308, 0x001a1208, 0x00181208, 0x00181209, 0x00181209, 0x00181008, 0x00150f07, 0x00151008, 0x00161008, 0x00171008, 0x00171008, 0x00161007, 0x00151007, 0x00131008, 0x00121008, 0x00121008, 0x00121008, 0x00140f08, 0x00140f08, 0x0016120a, 0x0017130a, 0x00161208, 0x00181408, 0x001a160c, 0x00161209, 0x00120e06, 0x000f0d04, 0x000c0c03, 0x000b0c04, 0x00090c04, 0x000b0e05, 0x000e1109, 0x00171d16, 0x00182018, 0x00181e17, 0x001a2018, 0x001a2119, 0x00181f17, 0x00181f15, 0x00181f15, 0x00181f15, 0x00181f15, 0x00181e15, 0x00191e15, 0x00191e15, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280b, 0x002c2d0b, 0x002d2f0b, 0x0032330c, 0x0036370c, 0x00393b0d, 0x003c3e0d, 0x0040400d, 0x0043440e, 0x0045470e, 0x00494a10, 0x004c4d0f, 0x004d4e10, 0x00525110, 0x00987e12, 0x00c8a016, 0x00cca316, 0x00b99615, 0x00786b12, 0x00585810, 0x00595a12, 0x005b5b12, 0x005b5b12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5d11, 0x005c5c11, 0x005c5d12, 0x005c5c12, 0x005b5b12, 0x00585912, 0x005e5c11, 0x00988013, 0x00c7a015, 0x00cba216, 0x00ac8b14, 0x005c5810, 0x004d4e10, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0043440e, 0x0040400d, 0x003c3e0d, 0x00393b0c, 0x0036370c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x0024250c, 0x00202308, 0x001d2008, 0x00191c09, 0x0014180a, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00181b12, 0x00181b12, 0x00181a14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161b14, 0x00171c14, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00161711, 0x0011130b, 0x000f1008, 0x000d1008, 0x000b0e05, 0x000a0e05, 0x000d0e06, 0x00101009, 0x00141109, 0x00131107, 0x00131008, 0x00131008, 0x00131107, 0x00151308, 0x00181308, 0x00181208, 0x00191208, 0x001a1208, 0x001a1208, 0x001a1208, 0x001b1208, 0x001d140a, 0x001d140a, 0x001e1409, 0x001f1509, 0x001f170b, 0x0020190d, 0x00201a0c, 0x00201a0d, 0x0022180c, 0x00201509, 0x001c1508, 0x001c1608, 0x00191507, 0x00181406, 0x00171305, 0x00161104, 0x00141104, 0x00141104, 0x00151003, 0x00171002, 0x00181003, 0x001c1507, 0x00191404, 0x001b1605, 0x00201708, 0x0023180a, 0x00241808, 0x002a1c09, 0x00301e0a, 0x0034200a, 0x00382309, 0x003d280b, 0x00452f0e, 0x004a320d, 0x0050340f, 0x0057390c, 0x005d3c0c, 0x0064400c, 0x006b440c, 0x0072480d, 0x007a4e11, 0x00805415, 0x00835814, 0x00855a13, 0x00865c0f, 0x00865c0f, 0x00865c0f, 0x0083590c, 0x007f5708, 0x007b5308, 0x0079500a, 0x00714806, 0x006b430c, 0x00623c09, 0x005e3a0c, 0x0058370c, 0x0053360b, 0x004f340a, 0x004c320b, 0x004c320c, 0x004a300d, 0x00482f0d, 0x00482f0c, 0x004b300c, 0x004d330d, 0x004d330c, 0x004e330a, 0x0050340b, 0x0052360a, 0x00563709, 0x005c390c, 0x005f3b0c, 0x00643c0e, 0x00653f10, 0x00694310, 0x0070480e, 0x0078500f, 0x00845613, 0x008c5d13, 0x00986815, 0x00a4761a, 0x00b1851f, 0x00bb9121, 0x00c39b25, 0x00c9a429, 0x00ccaa24, 0x00ccad1b, 0x00ccb018, 0x00ccb215, 0x00ccb313, 0x00caac16, 0x00a17c04, 0x007d5300, 0x006e4803, 0x00593c00, 0x004c3305, 0x00442f04, 0x003d2804, 0x00362204, 0x00311f08, 0x002d1c08, 0x002a1908, 0x0027180b, 0x00211608, 0x001c1408, 0x001b1408, 0x00191407, 0x00181308, 0x00181108, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x0017100b, 0x0017100b, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x0015100b, 0x0015100b, 0x0014100a, 0x0014100a, 0x0014100c, 0x00120f0c, 0x00120f0c, 0x00120f0c, 0x00130f0c, 0x00140f0b, 0x00120f0b, 0x000f0e09, 0x000b0c06, 0x00100f08, 0x00100f08, 0x00121009, 0x00121009, 0x00140f0b, 0x00140f0b, 0x00140f0b, 0x00140f0b, 0x00110e0a, 0x00110f08, 0x00110f08, 0x00131108, 0x00131108, 0x00121108, 0x00111008, 0x00101008, 0x00111009, 0x00131008, 0x00131008, 0x00131107, 0x00171408, 0x00181107, 0x00181107, 0x001a1306, 0x001c1408, 0x00201408, 0x00241708, 0x00281808, 0x002c1c09, 0x002d1e0c, 0x00342009, 0x00422708, 0x00644418, 0x00795010, 0x00926710, 0x00bf9a26, 0x00ccad1f, 0x00ccb316, 0x00ccb011, 0x00ccae13, 0x00ccac14, 0x00ccaa16, 0x00cca819, 0x00cca61b, 0x00cba31e, 0x00c59c1c, 0x00c3991c, 0x00be9319, 0x00bb8c1a, 0x00b38216, 0x00ab7a14, 0x00a47311, 0x009f6c0e, 0x00a06a10, 0x009b6610, 0x0094600e, 0x00915d0f, 0x00905b10, 0x008d5810, 0x0088540e, 0x0083500a, 0x00804f0a, 0x007a4c0a, 0x0072490a, 0x006e470a, 0x00674107, 0x00623d06, 0x0060380c, 0x0060370c, 0x005e350b, 0x005c350a, 0x005c3708, 0x0064400e, 0x006d4512, 0x00744913, 0x0080530d, 0x00916410, 0x00a77d19, 0x00ba9322, 0x00c59f22, 0x00caa620, 0x00cca920, 0x00ccaa1e, 0x00ccac1d, 0x00ccaf1c, 0x00ccb01d, 0x00ccb01c, 0x00ccaf1c, 0x00cca81a, 0x00c9a019, 0x00c69a1d, 0x00b88a15, 0x00a67611, 0x00926309, 0x00885a0e, 0x00784c09, 0x00643c0a, 0x00532e09, 0x0046290a, 0x003b2407, 0x00332004, 0x002c1a02, 0x00281802, 0x00241602, 0x001f1201, 0x001b1102, 0x001a1104, 0x00161004, 0x00141005, 0x00141105, 0x00141206, 0x00171408, 0x0018160a, 0x001b140a, 0x001c140a, 0x001f160c, 0x0020180e, 0x0021180d, 0x0022180c, 0x0021180c, 0x0023180d, 0x0022180c, 0x0021160a, 0x00201509, 0x001e150a, 0x001c1308, 0x001c1308, 0x00191106, 0x00181206, 0x00181206, 0x00181008, 0x00181008, 0x00181107, 0x00171006, 0x00141007, 0x00141007, 0x00141007, 0x00141007, 0x00141008, 0x00141008, 0x0016120a, 0x00171309, 0x00181409, 0x00181408, 0x00171308, 0x00130f05, 0x000f0c04, 0x000d0c05, 0x000c0d05, 0x000b0e05, 0x000b0d07, 0x000b0d07, 0x000c0e08, 0x00161b14, 0x00161d15, 0x00181f17, 0x001a2018, 0x001a2119, 0x00181f17, 0x00171e14, 0x00182016, 0x00182016, 0x00182016, 0x00191f15, 0x00191e15, 0x00191e15, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0034350c, 0x0036370c, 0x00393b0c, 0x003c3e0c, 0x0040400d, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x004d4e10, 0x00505010, 0x008f7812, 0x00c49e15, 0x00cca316, 0x00c49e16, 0x00947c14, 0x00605c10, 0x00585911, 0x00595a12, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x005b5b12, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5c11, 0x005c5d11, 0x005c5c11, 0x005c5c11, 0x005b5b12, 0x005b5b12, 0x00595a12, 0x00595911, 0x00756911, 0x00b09015, 0x00cba216, 0x00c9a116, 0x00a48614, 0x00585510, 0x004d4e10, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450e, 0x0041420d, 0x003e400c, 0x00393b0d, 0x0036370c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0020230a, 0x001d2008, 0x001d2009, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181b12, 0x00181b12, 0x00181a14, 0x00161b14, 0x00161b14, 0x00161b14, 0x00161b15, 0x00161b15, 0x00161b14, 0x00161b14, 0x00161c14, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181b14, 0x00141510, 0x00101009, 0x000f1008, 0x000d1008, 0x000c0e08, 0x000a0d07, 0x000b0c04, 0x00100f08, 0x0017140c, 0x00151309, 0x00151308, 0x00151308, 0x00151308, 0x00181609, 0x001c1509, 0x001d1408, 0x0020150b, 0x0022170c, 0x0022170c, 0x0022170c, 0x0022170c, 0x0024180d, 0x0024180d, 0x0024180f, 0x0024180e, 0x0020140c, 0x001f150c, 0x001a170b, 0x001a170b, 0x00181309, 0x00181108, 0x00140e04, 0x00130f04, 0x00110f03, 0x00121004, 0x00141405, 0x00131304, 0x00141404, 0x00141504, 0x00151504, 0x00191404, 0x00191505, 0x001f1a09, 0x00201a09, 0x00211c09, 0x00241c0a, 0x002b200f, 0x002c200f, 0x0033230e, 0x0034220c, 0x003c280f, 0x00412910, 0x00492d0c, 0x0052340e, 0x005c3a11, 0x00643c11, 0x006b410a, 0x00754a0a, 0x00845811, 0x00906417, 0x009c6f16, 0x00aa7c19, 0x00b78924, 0x00bc9127, 0x00c09428, 0x00c09525, 0x00c09625, 0x00c09725, 0x00bc9421, 0x00b89020, 0x00b68c23, 0x00a67c1b, 0x0094690e, 0x00895f10, 0x007a500a, 0x0070470b, 0x00673f09, 0x005c3c0a, 0x0056390a, 0x0053370a, 0x0052370c, 0x0050350c, 0x004e340c, 0x004e340c, 0x0050340c, 0x0054370c, 0x0054380b, 0x0055380a, 0x005a3c0c, 0x005d3d0c, 0x00623f08, 0x00684009, 0x0070460c, 0x0073490e, 0x00784f0e, 0x00845912, 0x008c610e, 0x00996f13, 0x00a77c18, 0x00b48a1f, 0x00be951f, 0x00c8a220, 0x00ccaa20, 0x00ccac1e, 0x00ccb01c, 0x00ccb318, 0x00ccb314, 0x00ccb410, 0x00ccb50f, 0x00cbb60c, 0x00cbb70d, 0x00cab316, 0x00a38104, 0x007c5400, 0x006d4804, 0x00563900, 0x00493004, 0x00422c04, 0x003c2403, 0x00352005, 0x00301d06, 0x002b1908, 0x00281807, 0x00241608, 0x00201407, 0x001b1306, 0x001a1407, 0x00191407, 0x00181308, 0x00181108, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x0017100b, 0x0017100b, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x0017100b, 0x0017100b, 0x00150f0a, 0x00150f0a, 0x0014100a, 0x00130f0a, 0x00120e09, 0x00130f0a, 0x00130f0a, 0x00140f0b, 0x0012100b, 0x0011100b, 0x000c0d08, 0x0013120b, 0x0012110a, 0x00121009, 0x00121009, 0x00140f0b, 0x00140f0b, 0x00140f0b, 0x00140f0b, 0x00120f08, 0x00110e08, 0x00131007, 0x00131006, 0x00121008, 0x00121008, 0x00121008, 0x00111008, 0x00121008, 0x00131008, 0x00131008, 0x00131107, 0x00161307, 0x00181107, 0x00181107, 0x001a1306, 0x001c1408, 0x00201408, 0x00241608, 0x00291909, 0x002d1c0a, 0x002e1c0a, 0x00362009, 0x00432808, 0x00654518, 0x00805013, 0x00996810, 0x00c29a22, 0x00cbae16, 0x00ccb40c, 0x00cab30a, 0x00c9b20c, 0x00c9b20e, 0x00cab20f, 0x00cab110, 0x00cab114, 0x00cbb018, 0x00c9b01a, 0x00cab019, 0x00cbae1b, 0x00cca91d, 0x00c8a51d, 0x00c9a420, 0x00c79d1d, 0x00c4981b, 0x00c09018, 0x00be8a19, 0x00b98419, 0x00b37c15, 0x00af7714, 0x00aa7115, 0x00a36b15, 0x009c6510, 0x0098600e, 0x00935e0e, 0x00895c10, 0x00865810, 0x00825510, 0x007c5211, 0x00784b17, 0x00774a18, 0x00734615, 0x00704613, 0x006d440e, 0x006f450d, 0x00754a0f, 0x00885a1b, 0x00a07420, 0x00bd922b, 0x00c9a42c, 0x00ccad21, 0x00ccb116, 0x00ccb50f, 0x00cbb60d, 0x00cbb80d, 0x00c9b80d, 0x00cab710, 0x00cbb510, 0x00cbb511, 0x00cab510, 0x00cab40c, 0x00ccb411, 0x00ccb018, 0x00ccac1c, 0x00c89c1f, 0x00b98c1b, 0x00a07110, 0x008b5c09, 0x00805210, 0x0068400b, 0x0054340a, 0x00442c06, 0x003a2505, 0x00332208, 0x002e1f07, 0x00271a04, 0x00241705, 0x001e1404, 0x001c1405, 0x00181104, 0x00141105, 0x00101003, 0x000c0d00, 0x000d0f01, 0x000d0f02, 0x00101003, 0x00101003, 0x00101103, 0x00141407, 0x001c1408, 0x001f1309, 0x00201409, 0x0021170a, 0x0024180b, 0x0026180b, 0x0025190b, 0x0024190b, 0x00211709, 0x00211609, 0x001f1408, 0x001f1409, 0x001f150a, 0x001c1308, 0x001a1106, 0x00191006, 0x00191007, 0x00181106, 0x00181206, 0x00181106, 0x00171107, 0x00161208, 0x00161208, 0x00181309, 0x0018140a, 0x00191409, 0x00181408, 0x00161308, 0x00130f06, 0x000e0d04, 0x000c0d05, 0x000b0e05, 0x000b0e05, 0x000a0d07, 0x000c0e08, 0x000c0f08, 0x00161b14, 0x00151d15, 0x00181f17, 0x00182018, 0x00192018, 0x00181f17, 0x00171e14, 0x00182016, 0x00182016, 0x00182016, 0x00191e15, 0x00191e15, 0x00191e15, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180b, 0x0014180b, 0x00191c09, 0x001d2009, 0x001d2008, 0x0024250b, 0x0026280b, 0x00292b0a, 0x002d2f0b, 0x0030310c, 0x0034350c, 0x0036370c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004c4d0f, 0x004d4e0f, 0x004d4e10, 0x00786911, 0x00bb9614, 0x00cba216, 0x00cba216, 0x00b49215, 0x007d6e12, 0x005c5a10, 0x00585810, 0x00585911, 0x00595a12, 0x00595a12, 0x00595a12, 0x005b5b12, 0x005c5c12, 0x005c5c12, 0x005c5c12, 0x005c5c12, 0x005c5c12, 0x005b5b12, 0x00595a12, 0x00595a12, 0x00585912, 0x005c5b11, 0x00726811, 0x00a48713, 0x00c6a015, 0x00cca316, 0x00c49c15, 0x008f7812, 0x00535210, 0x004d4e10, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450e, 0x0041420e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0030310c, 0x002d2f0b, 0x002c2d0b, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c09, 0x0014180a, 0x0014180b, 0x0014180e, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c16, 0x00181b17, 0x00191b17, 0x00191916, 0x00141510, 0x0010100b, 0x000f100a, 0x000d100a, 0x000a0f08, 0x000a0e07, 0x000c0c07, 0x000c0d05, 0x00141408, 0x0019170b, 0x0021180f, 0x0023180e, 0x0020180d, 0x001f180b, 0x0024170c, 0x0028160c, 0x0028180c, 0x0029180d, 0x0029180e, 0x0024170d, 0x0020160b, 0x001c170a, 0x00181408, 0x00181209, 0x0018130a, 0x00161108, 0x00120f04, 0x00100f04, 0x00100e04, 0x000f0e03, 0x00111006, 0x00151106, 0x00151005, 0x00141205, 0x00161408, 0x00181708, 0x00191709, 0x00191808, 0x001a1908, 0x001e1908, 0x00231807, 0x00241807, 0x00281c0a, 0x002b1f0c, 0x002b200b, 0x002b1f0a, 0x002d200a, 0x0034240b, 0x003f240c, 0x0042270d, 0x00442b0b, 0x00482f0b, 0x0050370b, 0x005f410f, 0x006c460c, 0x00805210, 0x00946314, 0x00a8781c, 0x00b48922, 0x00c19a28, 0x00c6a425, 0x00cbaa23, 0x00ccad22, 0x00ccaf20, 0x00ccb01e, 0x00ccb01c, 0x00ccb11a, 0x00ccb41a, 0x00ccb419, 0x00ccb419, 0x00ccb221, 0x00cbab26, 0x00c5a326, 0x00bc961f, 0x00a67f14, 0x00946810, 0x007d4d06, 0x006e4309, 0x00623c0b, 0x005a3a0c, 0x00583a0e, 0x0058390b, 0x00583809, 0x005b3a0b, 0x005f3f0c, 0x0060410b, 0x00614209, 0x0068450a, 0x00704a0e, 0x00754c0e, 0x007c4c09, 0x0084540d, 0x008c5c10, 0x00996a18, 0x00a5781b, 0x00b48823, 0x00be9424, 0x00c89f27, 0x00c6a423, 0x00c9ac24, 0x00ccb020, 0x00ccb11a, 0x00ccb315, 0x00ccb413, 0x00ccb413, 0x00ccb612, 0x00ccb70f, 0x00cab808, 0x00cab808, 0x00c9b808, 0x00ccb80c, 0x00ccb315, 0x00ab880b, 0x007d5600, 0x00694401, 0x00553804, 0x00462d05, 0x00402b08, 0x003a2404, 0x00342004, 0x002f1d07, 0x00291907, 0x00261706, 0x00221508, 0x001f1307, 0x001b1308, 0x00191207, 0x00181307, 0x00171309, 0x00171309, 0x00151108, 0x00151108, 0x0017100b, 0x0017100b, 0x00150f0a, 0x00150f0a, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x00160f08, 0x00170f08, 0x00151008, 0x00151008, 0x00141009, 0x0014100a, 0x0013100a, 0x0014140c, 0x000e1008, 0x00101109, 0x0012110a, 0x0013100a, 0x0014100a, 0x0014100a, 0x0014100a, 0x00150f0a, 0x00150f0a, 0x00151009, 0x00151008, 0x00151008, 0x00171009, 0x00151008, 0x00161108, 0x00161108, 0x00161108, 0x00161109, 0x00151109, 0x00151108, 0x00151108, 0x00161208, 0x00181207, 0x00191208, 0x001c1208, 0x001d1409, 0x00201408, 0x00241508, 0x00281808, 0x002d1c09, 0x002f1b09, 0x0037200a, 0x0044280a, 0x00674418, 0x007f5014, 0x009b6915, 0x00c59c26, 0x00cbac15, 0x00cbb10a, 0x00c8b209, 0x00c8b209, 0x00c9b30b, 0x00c9b30c, 0x00cab40f, 0x00cbb410, 0x00ccb410, 0x00ccb411, 0x00ccb40f, 0x00ccb40f, 0x00ccb310, 0x00ccb311, 0x00ccb211, 0x00ccb113, 0x00ccb012, 0x00ccaf13, 0x00ccac16, 0x00ccaa1a, 0x00caa61d, 0x00caa321, 0x00c9a023, 0x00c39820, 0x00be921c, 0x00b98c19, 0x00b48417, 0x00af7c18, 0x00a77211, 0x00a06c0f, 0x009a660b, 0x009a6412, 0x00925c14, 0x00895414, 0x00885414, 0x00845310, 0x00815010, 0x008b5a15, 0x00a87925, 0x00c4a02b, 0x00caad24, 0x00ccb11d, 0x00cab314, 0x00cab40f, 0x00c9b70c, 0x00c9b80b, 0x00c8b80c, 0x00c8b80c, 0x00c8b80c, 0x00c8b70c, 0x00c8b60c, 0x00c8b50c, 0x00cbb50c, 0x00cbb40d, 0x00c9b510, 0x00c9b412, 0x00ccb018, 0x00c9ac18, 0x00bf9d18, 0x00a87e0c, 0x00905f02, 0x00804f08, 0x00683c08, 0x004c3003, 0x00402a04, 0x003c2808, 0x00342307, 0x002e2008, 0x002b1d09, 0x00281a08, 0x00241606, 0x00201407, 0x001b1207, 0x00161207, 0x00121004, 0x00100f04, 0x000c0e02, 0x00090d01, 0x00080d01, 0x00060e01, 0x00081003, 0x000e1004, 0x00101005, 0x00101004, 0x00131405, 0x001b1408, 0x0021180b, 0x0023190c, 0x0024190d, 0x0024190c, 0x00261a0c, 0x00291c10, 0x0026180e, 0x0023160c, 0x0021180a, 0x0020180b, 0x001e140a, 0x001c1108, 0x001c1206, 0x001a1306, 0x00181406, 0x00181407, 0x00181508, 0x00181408, 0x001b1408, 0x001d1408, 0x001c1409, 0x00181308, 0x00140f07, 0x00100c04, 0x000d0c04, 0x000b0c03, 0x000a0d05, 0x000c0e08, 0x000c0e08, 0x000c1009, 0x000c0f08, 0x00121710, 0x001c2019, 0x00191e17, 0x001a1f18, 0x001b2018, 0x001a1f18, 0x00182018, 0x00182018, 0x001b2018, 0x001b2018, 0x001d211a, 0x001c1f18, 0x001c1e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180e, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250c, 0x0026280b, 0x002c2d0a, 0x002d2f0b, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0047480e, 0x00494a10, 0x004b4c10, 0x004c4d0f, 0x004f5010, 0x005d5810, 0x00a08413, 0x00c79f15, 0x00cca316, 0x00c9a116, 0x00b19015, 0x00887512, 0x00635e10, 0x005b5910, 0x00585810, 0x00595a11, 0x00585911, 0x00595a11, 0x00585911, 0x00585911, 0x00585911, 0x00595a11, 0x00595a11, 0x005c5a11, 0x00656010, 0x008a7613, 0x00ae8e14, 0x00c8a015, 0x00cca316, 0x00c9a116, 0x00b08f14, 0x00706410, 0x004f4f10, 0x004d4e10, 0x004c4d0f, 0x00494a10, 0x0047480e, 0x0044450e, 0x0041420e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x002d2f0b, 0x002c2d0a, 0x0026280b, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00171c15, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c16, 0x00181b17, 0x00191b18, 0x00191a16, 0x0014150e, 0x00101009, 0x000f100a, 0x000d100a, 0x000a0f08, 0x00090e07, 0x000b0d07, 0x000b0c04, 0x000e0d02, 0x001c190d, 0x00281b12, 0x00271810, 0x0023160c, 0x0021160c, 0x0020140a, 0x00201409, 0x00201409, 0x00201409, 0x001e1408, 0x001a1305, 0x00151203, 0x00121201, 0x000d0f00, 0x000c0d02, 0x000e0d03, 0x000e0e01, 0x000f0f02, 0x00141105, 0x00131104, 0x00141205, 0x00181608, 0x001e180b, 0x001f180a, 0x00201809, 0x00221a0b, 0x00241c0d, 0x00241c0d, 0x00241d0c, 0x00271e0b, 0x002b1d0a, 0x00301c08, 0x00301c08, 0x00311e0a, 0x00331f0b, 0x0033200b, 0x00342209, 0x0037250a, 0x003c290c, 0x00492a10, 0x004e2f10, 0x0053320e, 0x005c3c11, 0x00664410, 0x007a5413, 0x00936917, 0x00b08422, 0x00c09728, 0x00c7a328, 0x00ccac24, 0x00ccaf1c, 0x00ccb216, 0x00ccb412, 0x00ccb512, 0x00ccb611, 0x00ccb811, 0x00ccb810, 0x00ccb80e, 0x00cbba0c, 0x00cbba0b, 0x00cbb90c, 0x00ccb911, 0x00ccb816, 0x00ccb619, 0x00ccb31c, 0x00cbae22, 0x00be9a21, 0x00a47a10, 0x00805703, 0x00704808, 0x00653f0a, 0x00613e0b, 0x00603d08, 0x00673f09, 0x006d440c, 0x0071480c, 0x00754c0a, 0x007e540d, 0x0084560e, 0x008d5f13, 0x00976717, 0x00a07115, 0x00ac801c, 0x00bc9026, 0x00c39929, 0x00cba427, 0x00cca824, 0x00ccac1e, 0x00ccad18, 0x00c9ae14, 0x00cbb314, 0x00ccb511, 0x00cbb50c, 0x00ccb60b, 0x00ccb60a, 0x00ccb70b, 0x00ccb80b, 0x00ccb80a, 0x00cab808, 0x00cab908, 0x00cab908, 0x00ccb80d, 0x00ccb718, 0x00af8c0d, 0x00825800, 0x00674000, 0x00563705, 0x00462d06, 0x003c2806, 0x00382201, 0x00332005, 0x002d1d07, 0x00291907, 0x00251707, 0x00221408, 0x001f1307, 0x001b1307, 0x00191207, 0x00181308, 0x00171309, 0x00171309, 0x00161208, 0x00151108, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00151008, 0x00151008, 0x00161008, 0x00160f08, 0x00151008, 0x00151008, 0x00151009, 0x0014100a, 0x0012100a, 0x0014140c, 0x000e1008, 0x00101109, 0x0012110a, 0x0013100a, 0x0014100a, 0x0014100a, 0x0014100a, 0x0017100b, 0x0017100b, 0x00151008, 0x00151008, 0x00171009, 0x00171009, 0x00171008, 0x00171008, 0x00181209, 0x00181309, 0x00171209, 0x0016120a, 0x00151109, 0x00151108, 0x00151108, 0x00181207, 0x00191208, 0x001c1208, 0x001d1409, 0x00201408, 0x00231406, 0x00281808, 0x002e1b09, 0x00301a09, 0x0038200a, 0x0045290a, 0x00684619, 0x007f5014, 0x009a6916, 0x00c69d27, 0x00ccad18, 0x00c9b109, 0x00c8b308, 0x00c8b308, 0x00c9b408, 0x00c9b408, 0x00cab408, 0x00cbb509, 0x00cbb608, 0x00cbb708, 0x00cab707, 0x00c9b706, 0x00cab606, 0x00cab607, 0x00cab407, 0x00cab408, 0x00cbb408, 0x00cbb408, 0x00ccb40b, 0x00ccb20e, 0x00ccb011, 0x00ccaf13, 0x00cbad14, 0x00caac14, 0x00caab18, 0x00caab1b, 0x00cba81d, 0x00cca01c, 0x00c99d1c, 0x00c4981b, 0x00bf9217, 0x00b58716, 0x00b07f19, 0x00a36e15, 0x0096600d, 0x008d5b0c, 0x00905e13, 0x00aa7c27, 0x00c79f34, 0x00ccb025, 0x00ccb418, 0x00ccb512, 0x00ccb60c, 0x00ccb708, 0x00cbb708, 0x00cab509, 0x00cbb30b, 0x00cbb30a, 0x00cbb30a, 0x00ccb50c, 0x00ccb50c, 0x00ccb50b, 0x00ccb409, 0x00cbb509, 0x00c9b708, 0x00c9b707, 0x00ccb50e, 0x00cbb410, 0x00ccb318, 0x00c4a219, 0x00ae7f0d, 0x00935e02, 0x007c4c07, 0x00613a04, 0x004d3004, 0x00432906, 0x00392506, 0x00342408, 0x00312008, 0x00301e08, 0x002d1c09, 0x00291909, 0x0024170a, 0x0020170c, 0x001d150b, 0x001a1409, 0x00151006, 0x00101007, 0x000e0f06, 0x000c1006, 0x000a0f05, 0x000a0f04, 0x000b0f04, 0x000a0e04, 0x000a0e03, 0x000e0d03, 0x00140d03, 0x00161006, 0x00180f05, 0x00181004, 0x001b1207, 0x001e1409, 0x0020150a, 0x0022180c, 0x0024180e, 0x0024180d, 0x0024170c, 0x0022150b, 0x0022140b, 0x0021150b, 0x00201609, 0x001f1709, 0x001d1508, 0x001d1508, 0x001f1508, 0x00201508, 0x001c1408, 0x00141005, 0x00100c04, 0x000e0c04, 0x000c0c04, 0x00090d03, 0x00090c04, 0x000b0d07, 0x000c0f08, 0x000c1009, 0x000d100a, 0x000d120c, 0x001a1f18, 0x00191e17, 0x00191e17, 0x001a1f18, 0x001a1f18, 0x00182018, 0x00182018, 0x001b2018, 0x001b2018, 0x001d201a, 0x001c1f18, 0x001c1e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x0014180c, 0x0014180b, 0x00191c0a, 0x001d2009, 0x001d2008, 0x00202309, 0x0024250b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0041420e, 0x0044450e, 0x0045470e, 0x0048490f, 0x004b4c10, 0x004c4d0f, 0x004d4e0f, 0x00515010, 0x00726511, 0x00aa8a14, 0x00c8a015, 0x00cca216, 0x00c9a116, 0x00c49d15, 0x00af8f14, 0x009c8214, 0x008c7713, 0x007e6e12, 0x00786a12, 0x00726811, 0x00796c12, 0x00837212, 0x00907a13, 0x00a08514, 0x00b39114, 0x00c59e15, 0x00caa116, 0x00cca316, 0x00caa116, 0x00b89514, 0x00877312, 0x00565410, 0x004f5010, 0x004c4d0f, 0x004b4c10, 0x0048490f, 0x0047480e, 0x0044450e, 0x0041420e, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0020230a, 0x001d2008, 0x001d2009, 0x00191c09, 0x0014180b, 0x0014180b, 0x00141810, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a1b15, 0x001a1b15, 0x001a1b15, 0x00181c15, 0x00181c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00191c16, 0x00191c16, 0x00181c15, 0x00181c16, 0x00191b17, 0x001b1c18, 0x00171813, 0x0013140c, 0x000f1008, 0x000f1008, 0x000d1008, 0x000b0f06, 0x000a0f06, 0x000c0e08, 0x000c1006, 0x000c0c01, 0x00181509, 0x0021150e, 0x001e0f09, 0x00190e07, 0x00180f07, 0x00161007, 0x00120f05, 0x00110f03, 0x00110e03, 0x00100e02, 0x000f0f01, 0x000d0f00, 0x000f1001, 0x000e1000, 0x00101204, 0x00141407, 0x00141405, 0x00141405, 0x001a1306, 0x001d1608, 0x00201708, 0x00241c0c, 0x00261c0c, 0x00271c09, 0x00261907, 0x00281b08, 0x002c1d09, 0x002d1e0a, 0x002e1e0a, 0x0030200a, 0x00332008, 0x00362008, 0x00372109, 0x00382209, 0x003c240c, 0x003c270d, 0x003c270b, 0x00402a0c, 0x00442d0c, 0x0050310f, 0x0055340c, 0x00603b08, 0x00724a11, 0x00875d14, 0x00a87f21, 0x00bf9924, 0x00c9a820, 0x00cbaf1c, 0x00cbb118, 0x00ccb413, 0x00ccb50f, 0x00ccb410, 0x00ccb10d, 0x00ccae0d, 0x00cbac0c, 0x00cbad0f, 0x00caae0f, 0x00c9af0d, 0x00cab10c, 0x00ccb50d, 0x00ccb50c, 0x00cbb70a, 0x00ccb809, 0x00ccbc09, 0x00ccba0e, 0x00ccb814, 0x00ccb41d, 0x00c4a718, 0x00a17d0b, 0x00785000, 0x00724704, 0x0072460a, 0x00764b0b, 0x0081540f, 0x008b5e12, 0x00926614, 0x009b6f13, 0x00a47814, 0x00af821d, 0x00bc9028, 0x00c49c2d, 0x00c6a023, 0x00cba824, 0x00cba81f, 0x00ccac1c, 0x00ccb014, 0x00ccb210, 0x00ccb40d, 0x00ccb409, 0x00cab608, 0x00c9b608, 0x00c9b707, 0x00c9b706, 0x00cab806, 0x00cab808, 0x00cbb808, 0x00ccb808, 0x00ccb808, 0x00ccb808, 0x00cab908, 0x00cbba0a, 0x00ccb80d, 0x00ccb518, 0x00b18e10, 0x00835a00, 0x00673f00, 0x00543403, 0x00452d06, 0x003c2805, 0x00362100, 0x00331f04, 0x002c1c08, 0x00281808, 0x00251607, 0x00221408, 0x001e1307, 0x001a1207, 0x00191207, 0x00181308, 0x00171309, 0x00171309, 0x00161208, 0x00161208, 0x0018110a, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00151109, 0x00171109, 0x0018110a, 0x0017110b, 0x0016110c, 0x0014120c, 0x0014140c, 0x000c0e06, 0x0012110a, 0x0013120b, 0x0014110b, 0x0015100b, 0x0017100b, 0x0017100b, 0x0017100b, 0x0017100b, 0x0018110a, 0x0018110a, 0x00171009, 0x00171009, 0x00181108, 0x00181108, 0x00181208, 0x00181208, 0x00171108, 0x00161208, 0x00151108, 0x00151108, 0x00161208, 0x00181207, 0x00191208, 0x001c1309, 0x001f140a, 0x00201408, 0x00231406, 0x00281707, 0x002c1a08, 0x00301b08, 0x00371f08, 0x00442707, 0x006a4819, 0x00805014, 0x009c6b18, 0x00c59c26, 0x00ccaf1a, 0x00cab30a, 0x00c9b407, 0x00c9b405, 0x00c9b405, 0x00c9b405, 0x00cab506, 0x00cab504, 0x00cbb605, 0x00c9b705, 0x00c9b707, 0x00c8b807, 0x00c9b707, 0x00c9b707, 0x00cbb607, 0x00cbb608, 0x00ccb508, 0x00ccb508, 0x00ccb507, 0x00ccb508, 0x00cbb408, 0x00cbb409, 0x00cab509, 0x00cbb50b, 0x00cbb40c, 0x00ccb410, 0x00ccb311, 0x00ccb212, 0x00ccb013, 0x00ccad14, 0x00ccac16, 0x00cba718, 0x00cba01d, 0x00c1901c, 0x00a06c06, 0x0099620a, 0x00a07017, 0x00c2982d, 0x00ccac27, 0x00cbb315, 0x00ccb60e, 0x00ccb70a, 0x00ccb805, 0x00cab504, 0x00ccb20c, 0x00cbaa0d, 0x00caa411, 0x00c8a010, 0x00c49d0c, 0x00c29c0a, 0x00c49f0c, 0x00c5a20d, 0x00c8a80e, 0x00ccb011, 0x00ccb410, 0x00ccb60c, 0x00ccb60d, 0x00ccb908, 0x00cbb707, 0x00ccb214, 0x00c8a218, 0x00ac7e08, 0x008e5c00, 0x00774903, 0x005e3805, 0x004e2f07, 0x00432804, 0x003c2608, 0x00382408, 0x00362006, 0x00331e07, 0x00301d08, 0x002c1c0a, 0x002a190e, 0x0028180d, 0x0026180e, 0x0024190e, 0x001e160b, 0x00181207, 0x00171409, 0x00131207, 0x00101105, 0x000c1003, 0x000c0f03, 0x000c0f03, 0x000d0c03, 0x00100c04, 0x00100c03, 0x00100c03, 0x000f0c02, 0x00100b01, 0x00120d02, 0x00151005, 0x001a1308, 0x001e1409, 0x001f1509, 0x0025180c, 0x0025190d, 0x0024180b, 0x0026190d, 0x0025170a, 0x00251609, 0x00241608, 0x00231608, 0x00231708, 0x001f1407, 0x00161002, 0x00100d02, 0x000e0c03, 0x000d0c04, 0x000a0d03, 0x00080e03, 0x00080d04, 0x00090e07, 0x000a0f09, 0x000d100a, 0x0010120c, 0x000e110b, 0x00151812, 0x00181d16, 0x00181d16, 0x00191e17, 0x00191e17, 0x00192018, 0x00192018, 0x001b2018, 0x001b2018, 0x001c2019, 0x001c1f18, 0x001c1e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180b, 0x0014180a, 0x00191c09, 0x001d2009, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0038380c, 0x003b3c0d, 0x003e400c, 0x0040400d, 0x0043440e, 0x0045470e, 0x0047480f, 0x00494a10, 0x004b4c0f, 0x004c4d0f, 0x004d4e10, 0x00525010, 0x00706311, 0x00a08413, 0x00be9815, 0x00cba116, 0x00cca216, 0x00cca216, 0x00caa116, 0x00c8a015, 0x00c7a015, 0x00c7a015, 0x00c8a015, 0x00c8a016, 0x00caa216, 0x00cca316, 0x00cca316, 0x00cca216, 0x00c8a015, 0x00af8e14, 0x00867111, 0x00595510, 0x004f5010, 0x004d4e0f, 0x004b4c0f, 0x00494a10, 0x0048490f, 0x0045470e, 0x0043440e, 0x0041420d, 0x003e400c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x00202308, 0x001d2009, 0x00191c09, 0x00141809, 0x0014180b, 0x0014180e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c15, 0x00181c15, 0x001a1b15, 0x00181c15, 0x00181c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00191c16, 0x00191c16, 0x00181c15, 0x00181c16, 0x00191b17, 0x001c1c18, 0x00171812, 0x0013140c, 0x000f1007, 0x000f1007, 0x000d1007, 0x000c0f04, 0x00091006, 0x000a0f06, 0x000d1007, 0x00101005, 0x00151309, 0x001a120c, 0x00140d07, 0x00100b04, 0x000e0c04, 0x000c0d04, 0x000c0d04, 0x000e0f04, 0x00101005, 0x00101005, 0x00121205, 0x00131204, 0x00151405, 0x00161405, 0x001c180b, 0x00201a0c, 0x00201a0d, 0x00211a0c, 0x00241c09, 0x00281d0b, 0x00281f0c, 0x002b1f0c, 0x002c1e0b, 0x002d1e0a, 0x002f1e0a, 0x0030200a, 0x0033220a, 0x00342209, 0x00342209, 0x0037230a, 0x00382509, 0x003a270a, 0x003c280b, 0x003f290e, 0x00402a0f, 0x00412b0e, 0x00442c0c, 0x00482e0c, 0x004c320c, 0x0058380b, 0x00634009, 0x0078500d, 0x009c7224, 0x00b9902a, 0x00cba62e, 0x00caac1f, 0x00ccb313, 0x00cbb50c, 0x00cbb40a, 0x00ccb10c, 0x00cbac0a, 0x00caa30d, 0x00c49810, 0x00bd8f0a, 0x00b58906, 0x00b08405, 0x00b08406, 0x00af8604, 0x00b48c08, 0x00bc960d, 0x00c5a311, 0x00cbae14, 0x00cab50c, 0x00c9b806, 0x00cabb09, 0x00cbbb0e, 0x00c9b710, 0x00ccb616, 0x00c0a015, 0x008c6600, 0x00805104, 0x0081530c, 0x00966919, 0x00ad8328, 0x00b38b27, 0x00bb9527, 0x00c7a129, 0x00cba826, 0x00ccac28, 0x00ccae25, 0x00ccb122, 0x00cab01c, 0x00cbb418, 0x00ccb614, 0x00ccb710, 0x00cab70c, 0x00c9b608, 0x00cab607, 0x00c9b705, 0x00c8b807, 0x00c8b708, 0x00c9b608, 0x00c9b609, 0x00c9b709, 0x00c9b809, 0x00cbb80a, 0x00ccb80a, 0x00cab908, 0x00cab908, 0x00c8ba08, 0x00cabb0a, 0x00cbb90c, 0x00ccb618, 0x00b18e10, 0x00845b00, 0x00664000, 0x00543403, 0x00442d06, 0x00382603, 0x00331f00, 0x00311e04, 0x002c1c08, 0x00281708, 0x00241508, 0x00201307, 0x001c1206, 0x00191307, 0x00181307, 0x00171408, 0x00171309, 0x00171309, 0x00161208, 0x00161208, 0x00171008, 0x00171008, 0x00171008, 0x00171008, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00171009, 0x00141109, 0x00141109, 0x0015110a, 0x0017120a, 0x0017110b, 0x0016110c, 0x0014120c, 0x0014140c, 0x000c0e06, 0x0012110b, 0x0013120b, 0x0014110b, 0x0015100b, 0x0017100b, 0x0017100b, 0x0018110c, 0x0018110c, 0x0018110a, 0x0018110a, 0x00171009, 0x00171009, 0x00181108, 0x00181108, 0x00171008, 0x00171008, 0x00161008, 0x00151108, 0x00151108, 0x00151108, 0x00161208, 0x00181207, 0x00191208, 0x001c1409, 0x001f140b, 0x00201408, 0x00231407, 0x00261706, 0x002c1908, 0x00301b08, 0x00381e08, 0x00442606, 0x006b491c, 0x00825417, 0x00a06e1b, 0x00c69c27, 0x00ccb01a, 0x00cab30a, 0x00c9b404, 0x00c9b404, 0x00c9b405, 0x00c9b405, 0x00cab506, 0x00cab506, 0x00ccb508, 0x00cbb508, 0x00cbb509, 0x00cbb50a, 0x00cbb50c, 0x00ccb40d, 0x00ccb40d, 0x00ccb40d, 0x00ccb40f, 0x00cbb40f, 0x00cbb40d, 0x00cab60c, 0x00c8b50a, 0x00c8b508, 0x00c9b508, 0x00cbb607, 0x00cbb609, 0x00cbb50c, 0x00cbb50c, 0x00cbb50c, 0x00cab40b, 0x00c9b30d, 0x00cbb210, 0x00ccad0d, 0x00cca710, 0x00c2910f, 0x00a46b00, 0x009c6504, 0x00b48720, 0x00cba82c, 0x00cbb217, 0x00cbb60c, 0x00ccb80c, 0x00ccb708, 0x00ccb805, 0x00cab109, 0x00c6a30e, 0x00b88c07, 0x00ae7902, 0x00a87002, 0x00a06d00, 0x00a06c00, 0x00a37000, 0x00a67402, 0x00b38308, 0x00bd900d, 0x00c79f14, 0x00ccaa18, 0x00cbb412, 0x00c8bb03, 0x00c9b900, 0x00ccb40b, 0x00ccb115, 0x00c4a014, 0x00a47804, 0x00815300, 0x00683f06, 0x00543306, 0x00482c04, 0x00422a07, 0x003f2707, 0x003b2305, 0x00372004, 0x00341f07, 0x00331e09, 0x00311c0c, 0x00301b0b, 0x002f1a0b, 0x002d1b0c, 0x00291a0d, 0x0026180c, 0x0024190c, 0x001f170b, 0x001b1709, 0x00181406, 0x00171306, 0x00141004, 0x00111004, 0x00101005, 0x000f0f04, 0x000c0c01, 0x000c0c01, 0x000e0c02, 0x000f0d03, 0x000d0c01, 0x00100d02, 0x00130f03, 0x00141002, 0x00191507, 0x001d1808, 0x001e1708, 0x00231809, 0x00281a0c, 0x0029190b, 0x0029180a, 0x0028180a, 0x00231707, 0x001c1101, 0x00130e00, 0x000e0c01, 0x000d0d03, 0x000c0d04, 0x000a0e04, 0x00070e03, 0x00080e04, 0x00090e07, 0x00090e07, 0x000c100a, 0x000f140c, 0x000e110b, 0x00151812, 0x00171c15, 0x00181d16, 0x00181d16, 0x00191e17, 0x00192018, 0x00192018, 0x001b2018, 0x001b2018, 0x001c2019, 0x001c1f18, 0x001c1e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180c, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0038380c, 0x00393b0d, 0x003c3e0d, 0x0040400d, 0x0041420e, 0x0044450e, 0x0045470e, 0x0048490f, 0x00494a10, 0x004b4c0f, 0x004c4d0f, 0x004d4e0f, 0x004f5010, 0x005e5810, 0x007a6a11, 0x009c8013, 0x00b18f14, 0x00bc9815, 0x00c49c15, 0x00c8a015, 0x00c9a116, 0x00c8a015, 0x00c49d16, 0x00c09915, 0x00b69314, 0x00a98914, 0x008c7512, 0x006b6011, 0x00535110, 0x004d4e10, 0x004d4e0f, 0x004c4d0f, 0x004b4c10, 0x0048490f, 0x0047480e, 0x0044450e, 0x0043440e, 0x0040400d, 0x003c3e0c, 0x003b3c0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180c, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1b15, 0x00151710, 0x00101208, 0x000f1006, 0x000f1007, 0x000d0f05, 0x000c0f04, 0x000c0f06, 0x000c1007, 0x000e0f08, 0x0015130c, 0x0014120c, 0x00141109, 0x000f0e07, 0x000e0d06, 0x000c0e06, 0x000c0e05, 0x000e1008, 0x00111108, 0x00151308, 0x00181408, 0x001d1809, 0x0021190b, 0x00241a0d, 0x0026190c, 0x002b1d0d, 0x002c1e0d, 0x002c1d0d, 0x002e1e0e, 0x002d1d0d, 0x002d1e0c, 0x00301f0c, 0x0033220d, 0x0034220c, 0x0035210c, 0x00352209, 0x0038240a, 0x0038270c, 0x003b290e, 0x003e2c11, 0x003f2d12, 0x00402e10, 0x00402f0f, 0x0040300c, 0x0044310d, 0x00473410, 0x00483310, 0x004b3410, 0x004f3610, 0x00543810, 0x0068400f, 0x00784f0f, 0x00a37823, 0x00c19530, 0x00c8ab26, 0x00ccb31d, 0x00ccb414, 0x00cab40f, 0x00ccb20f, 0x00c8a811, 0x00c29c13, 0x00b38708, 0x00a47300, 0x00976300, 0x00905a00, 0x00895400, 0x00885300, 0x00875100, 0x00855300, 0x00895700, 0x00906001, 0x009a6f07, 0x00af860e, 0x00c5a416, 0x00cbb416, 0x00cab60f, 0x00c8b80e, 0x00c8b80e, 0x00ccb80e, 0x00cbb017, 0x00a37c08, 0x00885902, 0x00916210, 0x00bb9030, 0x00cba732, 0x00c8ac26, 0x00cbb120, 0x00ccb319, 0x00ccb518, 0x00ccb618, 0x00cab715, 0x00cab813, 0x00c8b710, 0x00c8b80e, 0x00c9b80c, 0x00c9b80b, 0x00c9b809, 0x00c9b809, 0x00c9b809, 0x00c9b809, 0x00c9b80b, 0x00c9b80c, 0x00c9b80c, 0x00c9b70e, 0x00c9b70e, 0x00c9b80c, 0x00c9b80a, 0x00c8ba08, 0x00c8b908, 0x00c8b808, 0x00c8b809, 0x00cab90a, 0x00ccb90a, 0x00ccb713, 0x00b3900c, 0x00835c00, 0x00694500, 0x00543602, 0x00422c04, 0x00382504, 0x00321f00, 0x00301e08, 0x002c1a0b, 0x00251608, 0x00221406, 0x001f1406, 0x001c1205, 0x00181307, 0x00181307, 0x00171408, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x0018110a, 0x00171009, 0x00171009, 0x00171009, 0x00141208, 0x00141208, 0x00141108, 0x00161108, 0x00171109, 0x0016120a, 0x0016120a, 0x0016140b, 0x00131008, 0x00121108, 0x00141209, 0x00141109, 0x00141109, 0x00171009, 0x00171009, 0x0018100a, 0x0018100a, 0x00181108, 0x00161208, 0x00161208, 0x00161208, 0x00151108, 0x00151108, 0x00151108, 0x00151108, 0x00161108, 0x00171008, 0x00171008, 0x00171008, 0x00171309, 0x00171309, 0x00181309, 0x001c130c, 0x001d140b, 0x00201408, 0x00231407, 0x00261706, 0x002c1908, 0x00301b08, 0x00381f08, 0x00442608, 0x0069481e, 0x0085551a, 0x00a36f1c, 0x00c99e2c, 0x00ccaf1d, 0x00c8b20e, 0x00c8b408, 0x00c8b408, 0x00c8b40a, 0x00c8b40a, 0x00c8b509, 0x00cab409, 0x00cbb50b, 0x00cbb50c, 0x00cbb50c, 0x00cbb50c, 0x00cbb50c, 0x00cbb50c, 0x00ccb40d, 0x00ccb40d, 0x00ccb40c, 0x00ccb40c, 0x00cbb50a, 0x00cbb50a, 0x00cbb50a, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00cbb408, 0x00cbb408, 0x00cbb408, 0x00cbb409, 0x00ccb309, 0x00ccb008, 0x00cca80e, 0x00b78504, 0x00a16500, 0x00a1690e, 0x00c49a2c, 0x00ccb020, 0x00ccb90c, 0x00ccb90b, 0x00ccb80f, 0x00ccb810, 0x00cbb410, 0x00bc9c09, 0x00a97d03, 0x00976501, 0x00945e02, 0x008d5700, 0x008c5404, 0x008a5203, 0x008c5505, 0x008d5503, 0x00925d01, 0x009c6904, 0x00ab780a, 0x00c19018, 0x00cca619, 0x00ccb30d, 0x00cab804, 0x00ccb70a, 0x00ccb411, 0x00ccb014, 0x00c09a15, 0x00906001, 0x00744804, 0x005d3d04, 0x00503204, 0x00482e06, 0x00442b07, 0x00412909, 0x003d2507, 0x00382307, 0x00362008, 0x00341e08, 0x00321c08, 0x00321d09, 0x00301e0b, 0x002f1c0a, 0x002e1d0a, 0x002c1d09, 0x002a1d0a, 0x00251b0c, 0x0020180a, 0x00201709, 0x001d1409, 0x00191004, 0x00151004, 0x00141004, 0x00100f03, 0x00100e04, 0x00100f05, 0x000d0c04, 0x000d0c04, 0x000c0c02, 0x000c0c01, 0x000c0e00, 0x000d1002, 0x00101405, 0x00131405, 0x00171304, 0x001f1508, 0x0027190d, 0x00281c10, 0x0024190f, 0x001d1408, 0x00150f04, 0x000f0c01, 0x000e0e03, 0x000d0d04, 0x000c0c04, 0x000a0e04, 0x00080f05, 0x00080f05, 0x00080d04, 0x00080d06, 0x00090d05, 0x000a0d05, 0x000e1109, 0x0013160e, 0x00171c15, 0x00171c15, 0x00181d16, 0x00181d16, 0x00192018, 0x00192018, 0x00192018, 0x00192018, 0x001b2019, 0x001b201a, 0x001b201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x00393b0d, 0x003c3e0d, 0x003e400c, 0x0041420e, 0x0043440e, 0x0045470e, 0x0047480e, 0x0048490f, 0x00494a0f, 0x004b4c10, 0x004c4d0f, 0x004d4e0f, 0x004c4d0f, 0x004b4c10, 0x00515010, 0x00605810, 0x00685d11, 0x006d6011, 0x006f6110, 0x006c6010, 0x006a5f10, 0x00635b10, 0x00585410, 0x004c4d10, 0x004c4d10, 0x004d4e0f, 0x004c4d0f, 0x004b4c0f, 0x00494a0f, 0x0048490f, 0x0047480e, 0x0045470e, 0x0044450e, 0x0041420e, 0x0040400d, 0x003c3e0d, 0x00393b0d, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0a, 0x00292b0b, 0x0026280b, 0x0024250b, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1c16, 0x00181812, 0x0012140c, 0x000f1007, 0x000f1005, 0x000d0f05, 0x000c0e04, 0x000c0f04, 0x000c0e04, 0x000d0f07, 0x00101009, 0x0016130c, 0x0017120c, 0x00121209, 0x000d1007, 0x000d1007, 0x000e1108, 0x00111208, 0x0015150c, 0x0019160b, 0x001d180a, 0x0021190a, 0x00281b0b, 0x002c1c0d, 0x002f1d10, 0x00301d0e, 0x00311f0c, 0x0032200b, 0x0033200b, 0x0034210c, 0x0035220e, 0x0035230f, 0x0035240c, 0x0039270e, 0x003b280e, 0x003b280c, 0x003d2a0d, 0x00402c0d, 0x00412f0d, 0x00453010, 0x00473311, 0x00463211, 0x00473311, 0x00473310, 0x00483510, 0x004c3910, 0x004e3c10, 0x00503b0d, 0x00523b0c, 0x00583c0d, 0x0060420f, 0x00744e0b, 0x009c7621, 0x00be9a2b, 0x00ccac28, 0x00ccb41a, 0x00ccb710, 0x00ccb611, 0x00c9ac0e, 0x00c29e10, 0x00ad8208, 0x00996902, 0x008a5800, 0x00815000, 0x007a4900, 0x00764500, 0x00724100, 0x00724201, 0x00744403, 0x00744401, 0x00774802, 0x007f5007, 0x00825504, 0x008f6001, 0x00ac840f, 0x00cbac1f, 0x00cbb511, 0x00c8b80b, 0x00c8bb08, 0x00cbb908, 0x00cbb514, 0x00a88204, 0x00906001, 0x00996a0d, 0x00c19926, 0x00ccb024, 0x00cab414, 0x00cbb60f, 0x00ccb70a, 0x00cab80c, 0x00cab80c, 0x00ccb80d, 0x00ccb80d, 0x00cab70c, 0x00cab70c, 0x00cbb70c, 0x00cbb70c, 0x00cab70c, 0x00cab70b, 0x00cab70b, 0x00cab809, 0x00cab809, 0x00cab70b, 0x00c9b80b, 0x00c9b80b, 0x00c9b80a, 0x00c9b809, 0x00c9b808, 0x00cab907, 0x00caba06, 0x00ccba08, 0x00ccb90a, 0x00ccb80a, 0x00ccb80d, 0x00ccb616, 0x00b38f0e, 0x00845d00, 0x006e4c03, 0x00513400, 0x003f2903, 0x00362606, 0x00321e04, 0x002f1c08, 0x00281809, 0x00241506, 0x00201305, 0x001d1204, 0x001a1305, 0x00181307, 0x00171407, 0x00161408, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x00161208, 0x0016120a, 0x0016120a, 0x0016120a, 0x0016120a, 0x00141208, 0x00141106, 0x00161106, 0x00171006, 0x00181008, 0x00181108, 0x00181108, 0x00181309, 0x00141008, 0x00121107, 0x00141208, 0x00151108, 0x00151108, 0x00161208, 0x00171108, 0x00181108, 0x00181108, 0x00161307, 0x00161307, 0x00161307, 0x00161307, 0x00151208, 0x00151108, 0x00151108, 0x00151108, 0x00161108, 0x00181108, 0x00171008, 0x00181309, 0x00171309, 0x00171309, 0x00181309, 0x001c140c, 0x001d140b, 0x00201408, 0x00231406, 0x00261706, 0x002b1908, 0x00301c08, 0x00361f09, 0x00402408, 0x0065451d, 0x007c5013, 0x009a6712, 0x00c79927, 0x00cca91b, 0x00caaf0c, 0x00cab309, 0x00cab309, 0x00cab308, 0x00cab308, 0x00cbb408, 0x00cab408, 0x00cbb608, 0x00c9b608, 0x00c9b708, 0x00c9b708, 0x00c9b708, 0x00c9b707, 0x00cab608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00cbb408, 0x00cab307, 0x00cbb408, 0x00ccb408, 0x00ccb409, 0x00ccb20f, 0x00caa510, 0x00b07d02, 0x00a06301, 0x00ac7415, 0x00c7a02a, 0x00ccb31c, 0x00ccbb0a, 0x00ccbb0c, 0x00ccb810, 0x00ccb712, 0x00c4a60d, 0x00a88000, 0x00946500, 0x00885802, 0x00855405, 0x00815103, 0x0081500a, 0x00805008, 0x00804f08, 0x007f5007, 0x00835404, 0x00885802, 0x00916002, 0x00a06d08, 0x00b88c14, 0x00caa819, 0x00cbb212, 0x00ccb511, 0x00ccb510, 0x00ccb410, 0x00cbaa19, 0x00aa7c0f, 0x007d5300, 0x00664402, 0x00573804, 0x004d3306, 0x00482e07, 0x00462c09, 0x00442c0a, 0x003e2808, 0x00392306, 0x00392208, 0x00382108, 0x00362008, 0x00331f08, 0x00321e08, 0x00301e08, 0x002f1f08, 0x002f1f08, 0x002e1f0c, 0x002d1c0e, 0x002c1b0c, 0x002b190b, 0x0026180a, 0x0025180b, 0x00221809, 0x001e1707, 0x001b1408, 0x00161008, 0x00141007, 0x00121107, 0x00101006, 0x000f0f04, 0x000b0c01, 0x00090e00, 0x00081000, 0x00081000, 0x000b0f00, 0x00101001, 0x00171104, 0x001c140a, 0x001e170c, 0x0018140b, 0x00121006, 0x000f0d03, 0x000f0d03, 0x000e0d04, 0x000e0d04, 0x000c0e04, 0x00080f05, 0x00080f05, 0x00080d04, 0x00080d04, 0x00090c04, 0x00090c04, 0x000d1008, 0x0013160d, 0x00171c15, 0x00171c15, 0x00181d16, 0x00181d16, 0x00192018, 0x00192018, 0x00192018, 0x00192018, 0x001a2019, 0x001b201a, 0x001b201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280b, 0x00292b0b, 0x002c2d0a, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x00393b0c, 0x003b3c0d, 0x003c3e0c, 0x0040400d, 0x0041420d, 0x0043440e, 0x0044450d, 0x0045470e, 0x0047480e, 0x0048490f, 0x00494a10, 0x00494a0f, 0x004b4c0f, 0x004c4d0f, 0x004c4d10, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004d4e0f, 0x004c4d10, 0x004c4d0f, 0x004c4d0f, 0x004b4c10, 0x0048490f, 0x0048490f, 0x0047480e, 0x0045470e, 0x0044450e, 0x0041420e, 0x0040400d, 0x003e400c, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x00292b0b, 0x0026280b, 0x0024250c, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c09, 0x0014180b, 0x0014180b, 0x0014180e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00191b15, 0x001a1b15, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181c15, 0x00141710, 0x000d1008, 0x000d1008, 0x000d1007, 0x000c1005, 0x000c0e04, 0x000d1004, 0x000d0f05, 0x00101007, 0x0014120a, 0x0019130c, 0x0018110a, 0x00120e04, 0x00121007, 0x00141308, 0x0017140b, 0x001c180c, 0x00201c0e, 0x00261c0c, 0x00281d0c, 0x002c1f0c, 0x0030200c, 0x0032200c, 0x0036200d, 0x0038200c, 0x0039220c, 0x003c240c, 0x003c250b, 0x003d260b, 0x003c260b, 0x003c260b, 0x003c280b, 0x00402c0c, 0x00442e0e, 0x00442f0c, 0x0048310c, 0x0048330b, 0x004b340a, 0x0050380d, 0x0050380e, 0x00543810, 0x00543a0f, 0x00553b0e, 0x0059400f, 0x005b410f, 0x005d430b, 0x00604308, 0x005d4002, 0x00654404, 0x00704e0a, 0x008d6816, 0x00be9b32, 0x00caad27, 0x00cbb416, 0x00cab80c, 0x00ccb80c, 0x00cbb113, 0x00bc980c, 0x00a67603, 0x008f5b00, 0x00815003, 0x00784904, 0x00704402, 0x006a4202, 0x00684002, 0x00673e04, 0x00683f07, 0x00684008, 0x00684107, 0x006f4709, 0x00744c0b, 0x00794f08, 0x00855708, 0x009e710c, 0x00c3a01f, 0x00cbb414, 0x00c8b908, 0x00c8bc04, 0x00ccb907, 0x00cbb414, 0x00ab8304, 0x00926000, 0x00a06e0a, 0x00c49c1f, 0x00ccb219, 0x00cab40c, 0x00cab707, 0x00cbb704, 0x00c9b808, 0x00c9b808, 0x00ccb80a, 0x00ccb80a, 0x00ccb80c, 0x00ccb80c, 0x00ccb80c, 0x00ccb80c, 0x00ccb80c, 0x00ccb80c, 0x00ccb80a, 0x00ccb80a, 0x00ccb80a, 0x00ccb80a, 0x00ccb80a, 0x00cbb80a, 0x00ccb809, 0x00ccb808, 0x00ccb90b, 0x00ccb809, 0x00cbb408, 0x00cbb40b, 0x00ccb611, 0x00ccb312, 0x00ccb016, 0x00caac20, 0x00a98312, 0x00875f08, 0x00785512, 0x00513404, 0x003c2704, 0x00342307, 0x00301c05, 0x002c1906, 0x00271708, 0x00231407, 0x00201407, 0x001d1104, 0x001a1305, 0x00181307, 0x00161406, 0x00151308, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00181309, 0x00181309, 0x00161409, 0x00161409, 0x00161409, 0x00161409, 0x00161308, 0x00171205, 0x00181105, 0x00191105, 0x00191107, 0x00191208, 0x00191208, 0x001a1308, 0x00151106, 0x00141106, 0x00161307, 0x00161307, 0x00161307, 0x00161307, 0x00161307, 0x00171308, 0x00171308, 0x00171408, 0x00171408, 0x00171408, 0x00171408, 0x00161208, 0x00161208, 0x00161208, 0x00171309, 0x00171208, 0x00181108, 0x00181309, 0x00181309, 0x00171309, 0x00171309, 0x00181309, 0x001b130b, 0x001c140a, 0x00201408, 0x00211406, 0x00261607, 0x002a1a09, 0x002e1c0c, 0x00321d0a, 0x003a2008, 0x0060421c, 0x00724c11, 0x008d5f0e, 0x00ba8a21, 0x00c49a18, 0x00c8a313, 0x00caa711, 0x00ccaa10, 0x00cbab0c, 0x00cbac0c, 0x00ccb00e, 0x00ccb00e, 0x00ccb10d, 0x00cbb10c, 0x00c8b208, 0x00cab40b, 0x00cbb60a, 0x00cbb509, 0x00cbb509, 0x00ccb40a, 0x00ccb40a, 0x00cbb409, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00ccb508, 0x00cbb408, 0x00cbb408, 0x00ccb307, 0x00ccb308, 0x00ccb210, 0x00c9a410, 0x00ad7a02, 0x00a06402, 0x00b47c18, 0x00cba727, 0x00ccb418, 0x00cbb90d, 0x00cbbc0c, 0x00ccb80c, 0x00ccb310, 0x00ba9507, 0x009d6e00, 0x008c5b01, 0x00835107, 0x007f5008, 0x007a5006, 0x007a500c, 0x00794f0b, 0x00794f0b, 0x007b500d, 0x007c510c, 0x0080540a, 0x00875809, 0x008f600b, 0x009f6e0e, 0x00b98f19, 0x00caa81c, 0x00ccb61c, 0x00cab70e, 0x00ccb60b, 0x00ccb015, 0x00bc9612, 0x008b6200, 0x00704900, 0x00603c00, 0x00563506, 0x004f3005, 0x004c3007, 0x00482e08, 0x00452c08, 0x00402705, 0x00402506, 0x003e2508, 0x003c2509, 0x003a2409, 0x00362007, 0x00352007, 0x00342008, 0x00331f07, 0x00331e0a, 0x00341d0a, 0x00341c0b, 0x00341c0c, 0x00311a0a, 0x002f1b0a, 0x002c1c0c, 0x002b1c0c, 0x00281c0c, 0x00211809, 0x001d1508, 0x001b1408, 0x00161305, 0x00131004, 0x00100e02, 0x000c0e00, 0x00080e00, 0x00090f02, 0x000a1002, 0x000b0e02, 0x000d0e02, 0x00121004, 0x00181508, 0x0017150b, 0x00121006, 0x00100d02, 0x00100d01, 0x000f0e04, 0x000f0f05, 0x000c0f05, 0x00090f06, 0x00090f06, 0x00090e05, 0x00090e05, 0x000b0e05, 0x000b0e05, 0x000c1007, 0x0010130a, 0x00141810, 0x00191e17, 0x00171c15, 0x00171c17, 0x00182018, 0x00182018, 0x00192018, 0x00192018, 0x001b201a, 0x001c201b, 0x001c201b, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x0014180b, 0x00191c09, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0a, 0x002d2f0a, 0x0030310c, 0x0032330c, 0x0036370c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x003e400c, 0x0040400d, 0x0041420d, 0x0043440e, 0x0044450e, 0x0045470e, 0x0045470e, 0x0047480e, 0x0048490f, 0x0048490f, 0x00494a0f, 0x00494a0f, 0x004b4c10, 0x00494a0f, 0x00494a0f, 0x004b4c10, 0x00494a0f, 0x00494a0f, 0x0048490f, 0x0047480e, 0x0047480e, 0x0045470e, 0x0044450e, 0x0043440e, 0x0041420e, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x00393b0d, 0x0038380c, 0x0036370c, 0x0032330c, 0x0030310c, 0x0030310b, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x00202309, 0x001d2008, 0x00191c09, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00171c15, 0x00171c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x00181c15, 0x001a1b15, 0x001a1b15, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x0013160f, 0x000c1008, 0x000d1008, 0x000d1007, 0x000c1005, 0x000d0f05, 0x000d1004, 0x000e0f04, 0x00141308, 0x0018130a, 0x001b1309, 0x00191007, 0x00180f04, 0x001c1207, 0x001f150a, 0x0022180d, 0x00241a0c, 0x00271d0c, 0x002c200d, 0x002e200b, 0x0030220a, 0x0033240a, 0x0034230a, 0x0038240c, 0x0039240b, 0x003c2509, 0x0040290c, 0x00422c0c, 0x00442d0d, 0x00442f0d, 0x00442f0c, 0x0046300a, 0x0049330c, 0x004d360f, 0x004e360e, 0x0051380d, 0x0052390a, 0x00543a0a, 0x0059400c, 0x005c400d, 0x005f420f, 0x00654610, 0x006b4b10, 0x006e4d0f, 0x0070500f, 0x0076540f, 0x007c5811, 0x00765006, 0x00714900, 0x007e5505, 0x00ac8629, 0x00cbaa34, 0x00ccb51e, 0x00caba09, 0x00c8bb04, 0x00ccb70b, 0x00c7a512, 0x00a67802, 0x008f5900, 0x00804c00, 0x00754804, 0x006a4602, 0x00664204, 0x00644008, 0x00643f08, 0x00643e07, 0x00653e08, 0x00653e08, 0x00664009, 0x006c460c, 0x00714b0d, 0x00784e0c, 0x00845510, 0x009d6f13, 0x00c39c22, 0x00cbb419, 0x00c8b909, 0x00c8bb05, 0x00ccb80c, 0x00cbb017, 0x00aa7d04, 0x00945e00, 0x00a87410, 0x00caa022, 0x00ccb118, 0x00cab40d, 0x00cab50c, 0x00cbb608, 0x00c9b80a, 0x00c9b80a, 0x00cbb80b, 0x00cbb909, 0x00cbb909, 0x00cbb909, 0x00cbb80a, 0x00cbb80b, 0x00cbb80b, 0x00cbb90a, 0x00ccb80a, 0x00ccb80b, 0x00ccb80c, 0x00ccb70d, 0x00ccb70d, 0x00ccb60c, 0x00cbb60a, 0x00cab50c, 0x00ccb50d, 0x00ccb20f, 0x00cbae10, 0x00c9aa12, 0x00c5a413, 0x00c09c12, 0x00b4900f, 0x009e7a09, 0x008c6004, 0x00825810, 0x006d4910, 0x004c2f04, 0x003b2604, 0x00332106, 0x002e1c04, 0x00281704, 0x00241406, 0x00231407, 0x001f1205, 0x001d1104, 0x001a1305, 0x00181306, 0x00151306, 0x00151308, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00171309, 0x00181309, 0x00181309, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x00181407, 0x001a1405, 0x001a1305, 0x001a1204, 0x001b1206, 0x001a1206, 0x00191307, 0x001b1407, 0x00181105, 0x00161104, 0x00181306, 0x00181205, 0x00181205, 0x00171406, 0x00171406, 0x00171406, 0x00171406, 0x00171408, 0x00171408, 0x00171408, 0x00171408, 0x00161308, 0x00161208, 0x00171309, 0x00171309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00171309, 0x00171309, 0x00181309, 0x001b130b, 0x001c140a, 0x001f1308, 0x00211406, 0x00251507, 0x00291909, 0x002d1c0d, 0x00301c0c, 0x00351e08, 0x00513613, 0x006a4715, 0x007a4e0e, 0x00905e09, 0x00a06c04, 0x00a87403, 0x00ac7c08, 0x00b5860c, 0x00bb8d0d, 0x00c0940e, 0x00c49a10, 0x00c89f14, 0x00c9a115, 0x00cca717, 0x00caac12, 0x00ccb013, 0x00cbb012, 0x00cbb010, 0x00cbb010, 0x00ccb110, 0x00cab110, 0x00cbb30e, 0x00cbb50b, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00cbb608, 0x00ccb508, 0x00ccb508, 0x00cbb408, 0x00cbb408, 0x00ccb307, 0x00ccb307, 0x00ccb10c, 0x00c9a50c, 0x00ad7c00, 0x00a16600, 0x00b47e13, 0x00cca821, 0x00ccb614, 0x00cab80e, 0x00cbbb0e, 0x00ccb80c, 0x00ccad0c, 0x00ad8000, 0x00976300, 0x00885503, 0x007f5009, 0x007b5008, 0x00784f05, 0x007a4e0c, 0x007a4d0c, 0x007a4d0c, 0x007c5010, 0x007c5010, 0x007f5111, 0x00825210, 0x0085540f, 0x008d5b09, 0x009e6d09, 0x00c29a1b, 0x00ccb119, 0x00c9b709, 0x00cab806, 0x00ccb40f, 0x00c8a812, 0x009e7803, 0x007e5200, 0x006b4202, 0x00623d0a, 0x005a3809, 0x00533408, 0x00503208, 0x004c3008, 0x004a2e09, 0x00492c09, 0x00482d0b, 0x00452b0a, 0x0042280a, 0x0040270c, 0x003f270d, 0x003c250b, 0x00382108, 0x00382008, 0x00382008, 0x00381f09, 0x00371d09, 0x00361d09, 0x00311c08, 0x002e1c08, 0x002d1c0a, 0x002c1d0b, 0x002a1c0b, 0x00271c0a, 0x00251a0a, 0x00211808, 0x0021150b, 0x001d1409, 0x00160f03, 0x00100d01, 0x000e1003, 0x000c0f03, 0x000c0e04, 0x000c0f03, 0x000a0d00, 0x00131408, 0x0018150c, 0x00151208, 0x00130f04, 0x00131004, 0x00100f06, 0x000f0f05, 0x000c0f05, 0x000a0f06, 0x000a0f06, 0x00090e05, 0x00090e05, 0x000b0e05, 0x000b0e05, 0x000c1007, 0x000e1109, 0x0010160c, 0x00171b14, 0x00161b14, 0x00161b15, 0x00181f17, 0x00181f17, 0x00192018, 0x00192018, 0x001b201a, 0x001c201b, 0x001c201b, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0b, 0x00191c09, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0026280c, 0x00292b0b, 0x002c2d0b, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x00393b0c, 0x00393b0d, 0x003b3c0d, 0x003c3e0c, 0x003e400c, 0x0041420d, 0x0041420e, 0x0043440e, 0x0044450e, 0x0044450e, 0x0044450d, 0x0045470e, 0x0047480e, 0x0047480e, 0x0045470e, 0x0045470e, 0x0047480e, 0x0045470e, 0x0045470e, 0x0045470e, 0x0044450e, 0x0043440e, 0x0043440e, 0x0041420d, 0x0040400d, 0x003e400c, 0x003c3e0d, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0030310c, 0x002d2f0b, 0x002c2d0a, 0x00292b0b, 0x0026280c, 0x0024250b, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c16, 0x00181c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00181b14, 0x0012150f, 0x000d1009, 0x000d1008, 0x000c1007, 0x000c1005, 0x000e1005, 0x000f1004, 0x00101105, 0x0017140a, 0x0018140b, 0x001b1308, 0x001b1106, 0x00231508, 0x00251508, 0x00281809, 0x002b1c0b, 0x002c1e0c, 0x002f200c, 0x0033220c, 0x0034230a, 0x0035250a, 0x0037280b, 0x00382909, 0x003d2c0c, 0x003e2c0c, 0x00402c0c, 0x00442e0b, 0x0048300c, 0x004a300a, 0x004c320b, 0x004f340c, 0x004f3409, 0x0053370b, 0x00583c0f, 0x00583b0c, 0x005c400c, 0x005d440b, 0x0063450b, 0x006b490d, 0x00745011, 0x007a5412, 0x00815910, 0x008c6411, 0x00957016, 0x00a17e20, 0x00ac8a26, 0x00b5922b, 0x00966d0c, 0x007c4f00, 0x008b5f09, 0x00bc952e, 0x00cbaf28, 0x00ccb715, 0x00cab909, 0x00cbbb04, 0x00ccb60c, 0x00b79406, 0x00946600, 0x00834f00, 0x00764800, 0x006c4502, 0x00674502, 0x00644307, 0x0064400b, 0x00643f07, 0x00623d03, 0x00633e03, 0x00654006, 0x00684209, 0x006c440c, 0x00744b10, 0x0079500c, 0x0087590e, 0x00a77a1a, 0x00c9a428, 0x00ccb41a, 0x00c9b80d, 0x00c8b909, 0x00ccb70e, 0x00cba717, 0x00a47203, 0x00945f00, 0x00b4821b, 0x00cca523, 0x00ccb115, 0x00c9b40c, 0x00c8b608, 0x00c8b705, 0x00c8b70b, 0x00c9b80c, 0x00cbb80b, 0x00ccb90c, 0x00cbb809, 0x00cbb809, 0x00ccb809, 0x00ccb808, 0x00ccb806, 0x00ccb806, 0x00cbb809, 0x00cbb70c, 0x00ccb60d, 0x00ccb40d, 0x00ccb310, 0x00ccb010, 0x00ccae10, 0x00ccab11, 0x00cca817, 0x00c69f15, 0x00b9900f, 0x00ab8007, 0x00a07403, 0x00936801, 0x00855b00, 0x00775000, 0x006c4501, 0x0067430c, 0x00523305, 0x003f2500, 0x00362201, 0x00312004, 0x002c1c02, 0x00251804, 0x00241707, 0x00201406, 0x001d1307, 0x001b1205, 0x00191107, 0x00181207, 0x00171307, 0x00171308, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x0018140a, 0x0018140a, 0x00181309, 0x00181308, 0x001a1308, 0x001a1407, 0x001a1407, 0x001b1307, 0x001a1407, 0x001b1407, 0x001b1406, 0x001a1305, 0x001a1306, 0x001b1307, 0x001a1407, 0x001a1306, 0x00181004, 0x00161105, 0x00171307, 0x00171307, 0x00181307, 0x00181307, 0x00191207, 0x00191207, 0x00181307, 0x00181306, 0x00181307, 0x00181307, 0x00181307, 0x00181306, 0x00181208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191307, 0x001c1308, 0x001c1408, 0x001f1408, 0x00211407, 0x00241406, 0x00281809, 0x002c1c0d, 0x002e1c0c, 0x00321d08, 0x00392106, 0x0052320c, 0x0068400e, 0x0078490c, 0x00814f07, 0x00895406, 0x008c5607, 0x008f5904, 0x00925d00, 0x00986401, 0x009f6b01, 0x00a67004, 0x00ae7809, 0x00b47f0c, 0x00b8880b, 0x00ba8c0c, 0x00c39814, 0x00c89d17, 0x00cba016, 0x00cca415, 0x00cba612, 0x00ccab14, 0x00ccae0f, 0x00ccb00d, 0x00ccb10b, 0x00cab20a, 0x00c9b70b, 0x00c8b609, 0x00c8b409, 0x00cbb40b, 0x00c8b307, 0x00c8b406, 0x00cab406, 0x00ccb307, 0x00ccb208, 0x00ccb20c, 0x00c8a50c, 0x00af7f00, 0x00a16700, 0x00b78015, 0x00cca820, 0x00ccb513, 0x00cab80a, 0x00cabb0c, 0x00ccb80c, 0x00c9a80d, 0x00ad7c01, 0x00955d01, 0x00865405, 0x007a5008, 0x00765007, 0x00744e04, 0x00774c0b, 0x00794c0c, 0x007a4d0c, 0x007c500f, 0x007c500d, 0x007d5110, 0x00805110, 0x0080510f, 0x0084560c, 0x0093600c, 0x00ac7f11, 0x00c9a91b, 0x00c8b60b, 0x00c8b906, 0x00cbb60c, 0x00ccb114, 0x00b38c0c, 0x00885b00, 0x00784a06, 0x0073470e, 0x00684006, 0x00633e05, 0x005e3b09, 0x0057360a, 0x0055340c, 0x00513008, 0x004f2e08, 0x004d2e0b, 0x004a2c0c, 0x00492a0e, 0x00462a0e, 0x0042290c, 0x003f280b, 0x003d2608, 0x003d2407, 0x003c240a, 0x003a220a, 0x00382108, 0x00362108, 0x00332008, 0x002f1d07, 0x002e1c08, 0x002d1d08, 0x002d1c09, 0x002c1c0a, 0x002b1b09, 0x002b1a0c, 0x002a190c, 0x0024150a, 0x001c1005, 0x00151004, 0x00111005, 0x000f1106, 0x00091003, 0x00080e01, 0x00111407, 0x0018160c, 0x001a140a, 0x00181108, 0x00151006, 0x00121004, 0x00100f06, 0x000e1007, 0x000c1007, 0x000c1006, 0x000b0f06, 0x000a0f06, 0x000a0f04, 0x000c0f04, 0x000c1006, 0x000d1008, 0x0010150c, 0x00151a12, 0x00161b14, 0x00161b15, 0x00181d18, 0x00181e18, 0x00181f18, 0x00192019, 0x001b201a, 0x001b211a, 0x001b2019, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x00191c0b, 0x00191c09, 0x00191c09, 0x001d2008, 0x00202308, 0x0024250b, 0x0024250b, 0x0026280b, 0x00292b0a, 0x002c2d0a, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x003c3e0d, 0x003c3e0c, 0x0040400d, 0x0040400d, 0x0040400d, 0x0041420e, 0x0041420e, 0x0043440e, 0x0043440e, 0x0044450e, 0x0044450e, 0x0043440e, 0x0043440e, 0x0041420e, 0x0041420d, 0x0040400d, 0x0040400d, 0x003e400c, 0x003c3e0c, 0x003c3e0d, 0x003b3c0d, 0x00393b0c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0030310c, 0x002c2d0a, 0x002c2d0b, 0x0026280b, 0x0026280c, 0x0024250b, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x00191c16, 0x00171a14, 0x0011140d, 0x000d100a, 0x000c1008, 0x000c1007, 0x000d1008, 0x000f1005, 0x00101005, 0x00151408, 0x0018150a, 0x00181409, 0x001a1307, 0x00211609, 0x0029190b, 0x002c190a, 0x002d1c09, 0x00301f09, 0x0032220b, 0x0035240e, 0x003a270f, 0x003c280d, 0x003d2c0c, 0x003f2d0c, 0x0040300a, 0x0048330c, 0x0048340f, 0x00483410, 0x004c3410, 0x0050380f, 0x0050380b, 0x00533a0b, 0x00583d0c, 0x005c3d0b, 0x0061400d, 0x0065400a, 0x006a4409, 0x00704b0a, 0x0077530c, 0x00805910, 0x008c6416, 0x00987019, 0x00a77c20, 0x00b48b22, 0x00bf9824, 0x00c8a729, 0x00caad26, 0x00ccb529, 0x00cbb128, 0x00ae8810, 0x008b5f00, 0x0091670c, 0x00c29c29, 0x00caaf1c, 0x00ccb70f, 0x00ccb80d, 0x00ccb90a, 0x00ccb510, 0x00ba980d, 0x00946a00, 0x00815300, 0x00784b04, 0x00704708, 0x006c4609, 0x0068450d, 0x00674410, 0x0065420c, 0x00634008, 0x00624007, 0x0066450c, 0x0069470f, 0x006d4810, 0x00784f15, 0x007f540f, 0x00906712, 0x00b99224, 0x00ccad24, 0x00ccb711, 0x00cab909, 0x00ccb90c, 0x00ccb20d, 0x00bf920f, 0x00986400, 0x009c6806, 0x00c29424, 0x00cca920, 0x00ccb012, 0x00ccb10c, 0x00cbb404, 0x00c9b604, 0x00cab60b, 0x00cbb60c, 0x00ccb50c, 0x00ccb60c, 0x00cbb40c, 0x00cbb40c, 0x00cab40c, 0x00cbb40a, 0x00ccb509, 0x00ccb509, 0x00ccb30e, 0x00caae0e, 0x00ccac12, 0x00c8a40f, 0x00c49f10, 0x00c0980e, 0x00ba900b, 0x00b18407, 0x00a87804, 0x00986801, 0x008d5c00, 0x00825300, 0x007d5000, 0x00744901, 0x00704404, 0x00603900, 0x00533100, 0x004c2f03, 0x003f2700, 0x00382200, 0x00342103, 0x002e1f03, 0x002a1c02, 0x00241804, 0x00221807, 0x001e1508, 0x001c1407, 0x001a1107, 0x00191107, 0x00181107, 0x00171207, 0x00171308, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x0019140b, 0x0019140b, 0x00181309, 0x00181308, 0x001b1308, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001a1407, 0x001a1407, 0x001b1407, 0x001b1407, 0x00191306, 0x00181004, 0x00151106, 0x00161307, 0x00171408, 0x00181308, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00181306, 0x00181404, 0x00181404, 0x00181404, 0x00191305, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001b1206, 0x001b1206, 0x001c1305, 0x001c1407, 0x001f1408, 0x00221507, 0x00241406, 0x00281808, 0x002c1c0c, 0x002d1c0a, 0x00301b08, 0x00321c07, 0x00371c00, 0x00442402, 0x00532e06, 0x005d3405, 0x00683906, 0x006e3f06, 0x00724305, 0x00774804, 0x007d4d05, 0x00855206, 0x008c5506, 0x00925803, 0x00975d02, 0x009a6000, 0x009e6401, 0x00a46b04, 0x00a86f04, 0x00ad7405, 0x00b27904, 0x00b88508, 0x00be8e0c, 0x00c4940d, 0x00c89d11, 0x00cca515, 0x00cca814, 0x00cbab10, 0x00c8ad0c, 0x00caaf0e, 0x00ccb10f, 0x00ccb30c, 0x00ccb40c, 0x00ccb40a, 0x00cbb308, 0x00cbb309, 0x00ccb20f, 0x00c8a50e, 0x00b28204, 0x009f6500, 0x00b27c12, 0x00cba623, 0x00ccb414, 0x00c9b808, 0x00c9ba0a, 0x00ccb70f, 0x00caaa0f, 0x00ae8000, 0x00945f00, 0x00875406, 0x007c5108, 0x00755109, 0x00744f07, 0x00784e0b, 0x00784e0b, 0x00784f0c, 0x0079500c, 0x007b500a, 0x007c500b, 0x007c500b, 0x007d510c, 0x007d5409, 0x0089590c, 0x009f700e, 0x00c4a01c, 0x00c8b410, 0x00c8b809, 0x00cab60d, 0x00ccb312, 0x00c09b13, 0x00936400, 0x00804f04, 0x0080500e, 0x007c4d08, 0x00764804, 0x00724608, 0x006e430d, 0x00684010, 0x00633c0c, 0x005d3709, 0x0058330a, 0x0054300c, 0x0051300c, 0x004c2f0a, 0x00482e08, 0x00462e09, 0x00462e0a, 0x00452b09, 0x0043280a, 0x00402709, 0x003f2508, 0x003d260a, 0x003c250b, 0x0039230b, 0x00362008, 0x00352008, 0x00342009, 0x00321d0a, 0x00311b08, 0x00301c08, 0x00301c0a, 0x002c1909, 0x0028180a, 0x00201609, 0x00181306, 0x00141407, 0x000c1104, 0x000c1104, 0x00111206, 0x0019150b, 0x001e150c, 0x001c1409, 0x00161006, 0x00131005, 0x00100f08, 0x000f0f08, 0x000c1007, 0x000c1007, 0x000c0f06, 0x000a0f06, 0x000a1004, 0x000c0f04, 0x000c1005, 0x000c1006, 0x0010140c, 0x00141910, 0x00161b15, 0x00161b15, 0x00181e18, 0x00181e18, 0x00181e18, 0x0019201a, 0x001a2019, 0x001b2119, 0x001a2018, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2008, 0x00202308, 0x00202309, 0x0024250c, 0x0026280b, 0x00292b0b, 0x002c2d0b, 0x002c2d0a, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0034350c, 0x0036370c, 0x0038380c, 0x0038380c, 0x003b3c0d, 0x003b3c0d, 0x003b3c0d, 0x003c3e0d, 0x003c3e0c, 0x003e400c, 0x003e400c, 0x0040400c, 0x003e400c, 0x003e400c, 0x0040400c, 0x003e400c, 0x003e400c, 0x003c3e0c, 0x003c3e0d, 0x003b3c0d, 0x003b3c0d, 0x00393b0c, 0x0038380c, 0x0038380c, 0x0034350c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002d2f0b, 0x002c2d0a, 0x00292b0b, 0x0026280b, 0x0024250c, 0x0020230a, 0x00202308, 0x001d2008, 0x00191c09, 0x00191c09, 0x00191c0b, 0x0014180b, 0x0014180c, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x00161913, 0x0010140d, 0x000d110a, 0x000c1008, 0x000d1009, 0x000d1008, 0x000f1006, 0x00141307, 0x00181708, 0x00191509, 0x001a1509, 0x001e1507, 0x00261b0b, 0x002c1d0a, 0x002f1e0b, 0x00302009, 0x0033230b, 0x0037270c, 0x003c290d, 0x00412c10, 0x00452e0f, 0x0046310c, 0x0048340b, 0x004c340a, 0x0050380c, 0x0052390e, 0x0051380f, 0x00553b10, 0x005c3f10, 0x005d410e, 0x005e440d, 0x0064460c, 0x006c480b, 0x00744c0c, 0x007b500b, 0x0086590f, 0x00946512, 0x00a37319, 0x00ac821f, 0x00b89325, 0x00c29e27, 0x00c8a628, 0x00ccad25, 0x00ccb11e, 0x00ccb518, 0x00ccb812, 0x00ccbc12, 0x00cbb91c, 0x00b4950c, 0x008f6500, 0x008c6201, 0x00c09c24, 0x00caae18, 0x00ccb60c, 0x00ccb80d, 0x00ccb80d, 0x00ccb511, 0x00c8a918, 0x00a78209, 0x008e6200, 0x00845606, 0x00794f08, 0x00744b09, 0x00714a0d, 0x006f4812, 0x006c440e, 0x0069430c, 0x0068440c, 0x006b480f, 0x006d490e, 0x00744c10, 0x007c5312, 0x008d6313, 0x00ab8523, 0x00c7a828, 0x00ccb518, 0x00ccb90b, 0x00cab806, 0x00cbb30c, 0x00c8a30d, 0x00ab7b07, 0x00905d00, 0x00ac7c13, 0x00c89e24, 0x00cba81b, 0x00ccac12, 0x00ccb00f, 0x00ccb20a, 0x00cab309, 0x00cbb40c, 0x00ccb40c, 0x00cbb40c, 0x00cbb40c, 0x00cbb20e, 0x00ccb010, 0x00ccad11, 0x00c9a90f, 0x00c7a510, 0x00c4a00e, 0x00c09c10, 0x00b8900b, 0x00af8409, 0x00a67a05, 0x009c6d01, 0x00936400, 0x008d5c00, 0x00885901, 0x00845501, 0x007a4c00, 0x00704400, 0x00694004, 0x00643d05, 0x005b3704, 0x00543204, 0x004e3001, 0x00472a01, 0x00402703, 0x00382202, 0x00342004, 0x002f1e05, 0x002c1e08, 0x00281c06, 0x00231905, 0x00201705, 0x001d1407, 0x001b1406, 0x001a1107, 0x00191107, 0x00181208, 0x00171207, 0x00171308, 0x00181209, 0x00181209, 0x00181309, 0x00181309, 0x00181209, 0x00181209, 0x00181309, 0x00181309, 0x0019140b, 0x0019140b, 0x00181309, 0x00181308, 0x001b1308, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001a1306, 0x00181105, 0x00161207, 0x00181408, 0x00171408, 0x00181408, 0x001a1208, 0x001a1208, 0x001a1208, 0x001a1208, 0x00181306, 0x00181404, 0x00181404, 0x00181404, 0x00191305, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001b1206, 0x001b1206, 0x001c1305, 0x001c1406, 0x001f1408, 0x00231608, 0x00251508, 0x00271708, 0x002c1c0b, 0x002d1c0a, 0x00301b09, 0x00311c08, 0x00321d08, 0x00331d05, 0x00391d04, 0x00432206, 0x00492603, 0x004d2900, 0x00502d00, 0x00553101, 0x005c3704, 0x00653b05, 0x006b3d04, 0x00744406, 0x007c4905, 0x00834f04, 0x00875207, 0x008a5607, 0x008c5606, 0x008f5704, 0x00925a04, 0x00955d02, 0x009b6301, 0x009f6700, 0x00a66e02, 0x00ab7306, 0x00b27b0b, 0x00b9840c, 0x00be8d0a, 0x00c1940d, 0x00c59910, 0x00c9a111, 0x00caa50e, 0x00ccaa0f, 0x00ccad0e, 0x00ccb111, 0x00ccab14, 0x00caa316, 0x00b6850c, 0x009c6400, 0x00a97210, 0x00c8a124, 0x00cbb318, 0x00c9b70c, 0x00c9b80c, 0x00ccb70f, 0x00cbaf10, 0x00af8802, 0x00946300, 0x00885401, 0x007e5005, 0x00795009, 0x00755009, 0x00784e0a, 0x00784e0a, 0x00784f0b, 0x0079500b, 0x007b4f09, 0x007b500a, 0x007b500a, 0x007c510b, 0x007c5208, 0x0087560a, 0x00976709, 0x00bc9619, 0x00c9b114, 0x00c8b70c, 0x00cab70c, 0x00ccb411, 0x00c6a316, 0x009e7001, 0x008b5804, 0x009a6719, 0x00a16f1b, 0x0096650f, 0x00895806, 0x00865308, 0x0081510c, 0x007b4b0b, 0x00744609, 0x006e410a, 0x00683c08, 0x005f3807, 0x00593606, 0x00543407, 0x00503408, 0x00503409, 0x004c3107, 0x004c2f08, 0x004a2c08, 0x00452907, 0x00442807, 0x0044270a, 0x00412609, 0x003e2408, 0x003c2408, 0x003b240a, 0x003b230b, 0x00382008, 0x00362008, 0x00341f07, 0x00311d08, 0x002f1b09, 0x002c1a0c, 0x00261a0c, 0x001d1608, 0x00141205, 0x00141105, 0x00141004, 0x00191208, 0x0020160b, 0x001e150b, 0x00181206, 0x00151006, 0x00120f08, 0x000f0f08, 0x000e0e07, 0x000c0f07, 0x000c1006, 0x000a1006, 0x000a1004, 0x000c0f04, 0x000c1005, 0x000c0f04, 0x000d1309, 0x0012170f, 0x00151a14, 0x00161a16, 0x00171d18, 0x00181e18, 0x00181e18, 0x00181f19, 0x001a2019, 0x001b2119, 0x001a2018, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x0014180b, 0x00191c0a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x0024250b, 0x0024250b, 0x0026280b, 0x00292b0b, 0x002c2d0a, 0x002d2f0a, 0x002d2f0b, 0x0030310c, 0x0032330c, 0x0032330c, 0x0036370c, 0x0036370c, 0x0036370b, 0x0038380c, 0x0038380c, 0x00393b0c, 0x003b3c0d, 0x00393b0d, 0x00393b0d, 0x00393b0d, 0x00393b0d, 0x00393b0d, 0x003b3c0d, 0x00393b0d, 0x00393b0c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0034350c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0030310c, 0x002d2f0a, 0x002c2d0a, 0x002c2d0b, 0x0026280b, 0x0026280c, 0x0024250b, 0x00202309, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x001b1d17, 0x001a1c16, 0x00131610, 0x000d120b, 0x000d120b, 0x000c100a, 0x000d120b, 0x000e1108, 0x00121207, 0x00151407, 0x001a1809, 0x001b1608, 0x001d1507, 0x00241909, 0x002b1e0c, 0x0030200c, 0x0034240d, 0x0035250c, 0x0038280c, 0x003f2c0e, 0x00432f0f, 0x0048310f, 0x004c340f, 0x0050370e, 0x00533b0c, 0x00573d0c, 0x005c400c, 0x0061430f, 0x00654310, 0x006b4710, 0x00704b11, 0x00754f0f, 0x0078520c, 0x0080580c, 0x008f6611, 0x009a7015, 0x00a77c20, 0x00b68b28, 0x00c09826, 0x00c8a126, 0x00caa920, 0x00caae1b, 0x00cab219, 0x00cbb618, 0x00cbb817, 0x00ccb812, 0x00cbbb10, 0x00c9bd0d, 0x00cabd0e, 0x00cab814, 0x00b99a0c, 0x00956800, 0x00906001, 0x00b08816, 0x00cbae1a, 0x00cbb40c, 0x00cbb80d, 0x00cab80c, 0x00ccb80d, 0x00ccb417, 0x00c6a81b, 0x00ac880f, 0x009a7008, 0x00885f04, 0x00825704, 0x007e5208, 0x00794d09, 0x00764c09, 0x00764b0b, 0x00744b0a, 0x00754d08, 0x00785006, 0x00825708, 0x00916611, 0x00ae8724, 0x00c6a430, 0x00ccb424, 0x00c9b910, 0x00ccba0c, 0x00cbb50f, 0x00cbae1a, 0x00b6870c, 0x00945d00, 0x009b6408, 0x00bd8c24, 0x00c79921, 0x00c49914, 0x00c59b10, 0x00c8a011, 0x00cba513, 0x00cca913, 0x00ccaa14, 0x00cca912, 0x00cba811, 0x00cba711, 0x00c8a211, 0x00c49b10, 0x00bd930f, 0x00b08406, 0x00a47704, 0x009e6f04, 0x00946400, 0x008c5c00, 0x00895800, 0x00815200, 0x007c4c00, 0x007a4801, 0x00754403, 0x006f4104, 0x00694004, 0x00603c02, 0x00583801, 0x00533506, 0x00503307, 0x00492e07, 0x00432b04, 0x00402807, 0x003e2708, 0x003a2309, 0x00372008, 0x00301e08, 0x002c1e08, 0x00291c09, 0x00231908, 0x00221805, 0x00201604, 0x001c1407, 0x001a1306, 0x001a1107, 0x00191108, 0x001a1308, 0x00171207, 0x00161207, 0x00171008, 0x00181108, 0x00181309, 0x00181309, 0x00181108, 0x00181108, 0x00181309, 0x00181309, 0x0019140b, 0x0019140b, 0x00191209, 0x00191208, 0x001b1308, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1408, 0x00181206, 0x00171408, 0x0018150a, 0x00181408, 0x00181408, 0x001b1308, 0x001b1308, 0x001b1308, 0x001b1308, 0x00181306, 0x00181404, 0x00181404, 0x00181404, 0x00191305, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001c1307, 0x001c1307, 0x001c1305, 0x001c1305, 0x001f1408, 0x0023170a, 0x00251709, 0x0027170a, 0x0029190b, 0x002b1908, 0x002e1a09, 0x00301c0a, 0x002e1d09, 0x00301e0a, 0x00351e09, 0x003d210b, 0x00432408, 0x00462806, 0x00482908, 0x00482908, 0x00492c08, 0x004a2b07, 0x004d2b03, 0x00543003, 0x00593101, 0x005e3401, 0x00633804, 0x00663c04, 0x00683f04, 0x0074480d, 0x00794c0d, 0x007e4e0c, 0x0084510a, 0x008b5409, 0x008f5609, 0x00905607, 0x00955908, 0x00975c05, 0x00996002, 0x009d6604, 0x00a36c04, 0x00a87204, 0x00b07c08, 0x00b8840a, 0x00c08d0f, 0x00c59412, 0x00c79a17, 0x00c89c1d, 0x00c08c1d, 0x00a06708, 0x009a6404, 0x00b8911a, 0x00cab01c, 0x00c9b613, 0x00cbb80f, 0x00ccb80f, 0x00ccb411, 0x00bc9a0c, 0x009a6e00, 0x008e5a00, 0x00845004, 0x007e520b, 0x0079540d, 0x007a500c, 0x00784f0b, 0x0078500b, 0x0079500c, 0x007b500c, 0x007c510c, 0x007d520d, 0x0080540e, 0x007c5308, 0x0087560c, 0x0095650b, 0x00bc941e, 0x00cab11a, 0x00c9b70f, 0x00cab70c, 0x00ccb50f, 0x00c9a814, 0x00a77801, 0x00976202, 0x00b67f24, 0x00c7962f, 0x00c09222, 0x00b7881b, 0x00ab7910, 0x00a06c0a, 0x00935e07, 0x008b5705, 0x00875407, 0x00815006, 0x007a4b08, 0x00754809, 0x006f440c, 0x00623c05, 0x005c3c09, 0x00583908, 0x0055380a, 0x00523409, 0x004e3108, 0x004c3008, 0x004b2f0b, 0x00482d0c, 0x00462c0a, 0x00442b0a, 0x00432a0b, 0x0041250a, 0x00402408, 0x003e2408, 0x003b2306, 0x00382108, 0x00351f09, 0x00361c0e, 0x00311c0e, 0x0027170a, 0x00201608, 0x001e150b, 0x001e140b, 0x001c1208, 0x001f160b, 0x0020180c, 0x001c1408, 0x00181108, 0x0015110a, 0x0013100a, 0x00101008, 0x000f0e06, 0x000d0f06, 0x000b1006, 0x000a1004, 0x000c0f04, 0x000c0f04, 0x000c0f04, 0x000c1106, 0x0010140c, 0x00141914, 0x00151916, 0x00151b15, 0x00171d18, 0x00181e18, 0x00181f19, 0x001a2019, 0x001b2119, 0x00192018, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180d, 0x0014180b, 0x0014180b, 0x00141809, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x00202309, 0x0024250b, 0x0024250b, 0x00292b0b, 0x00292b0b, 0x00292b0a, 0x002c2d0a, 0x002d2f0a, 0x002d2f0b, 0x0032330c, 0x0030310c, 0x0034350c, 0x0032330c, 0x0036370c, 0x0034350c, 0x0036370c, 0x0036370c, 0x0038380c, 0x0038380c, 0x0038380c, 0x0036370c, 0x0036370c, 0x0034350c, 0x0036370c, 0x0034350c, 0x0032330c, 0x0032330c, 0x0032330c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x00292b0a, 0x00292b0a, 0x0026280b, 0x0026280c, 0x0024250c, 0x0020230a, 0x00202308, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x001b1e18, 0x00181c15, 0x0010140c, 0x000d120b, 0x000d120b, 0x000c110a, 0x000e1109, 0x00101208, 0x00141307, 0x00181407, 0x001c1809, 0x001a1405, 0x001f1606, 0x00281c09, 0x002f200b, 0x0035250c, 0x003a2a0f, 0x003e2c0e, 0x0042300e, 0x00483410, 0x004c3610, 0x00533811, 0x00583a10, 0x005f3f12, 0x00654611, 0x00694a0f, 0x006f4f0f, 0x0074500f, 0x007f520f, 0x0084570f, 0x00906214, 0x00986b15, 0x00a67a16, 0x00b08518, 0x00ba901c, 0x00c59d21, 0x00c8a527, 0x00c9aa24, 0x00ccb223, 0x00ccb418, 0x00ccb510, 0x00cbb80c, 0x00c9b90d, 0x00c8ba10, 0x00c9bb0f, 0x00cbbb0f, 0x00cabb10, 0x00c8bb10, 0x00c7ba10, 0x00c9b712, 0x00c1a010, 0x00a37402, 0x008c5800, 0x00966c06, 0x00bf9c19, 0x00ccb316, 0x00cbb80f, 0x00c8ba08, 0x00caba09, 0x00cbb90f, 0x00ccb514, 0x00cbae1c, 0x00c4a31f, 0x00b6911b, 0x00a67f11, 0x0099710c, 0x0092690c, 0x008c6208, 0x008a5f08, 0x008a6008, 0x0090650b, 0x00996e10, 0x00aa7e19, 0x00be9428, 0x00c6a42b, 0x00c9af24, 0x00cab818, 0x00c8bc0d, 0x00ccb90f, 0x00ccb218, 0x00b79014, 0x00996203, 0x008a4d00, 0x00955809, 0x00ab711b, 0x00a46c0d, 0x00a06704, 0x00a16803, 0x00a46d04, 0x00ab7608, 0x00b17d0c, 0x00b37e0c, 0x00b27d0b, 0x00ad7805, 0x00ad7807, 0x00a36e02, 0x00986400, 0x00905c00, 0x00895700, 0x00825100, 0x007c4c00, 0x00784901, 0x00734701, 0x006e4300, 0x00673d00, 0x00643b00, 0x00613802, 0x00603605, 0x005a3505, 0x00553404, 0x00513406, 0x004c3407, 0x00493307, 0x00473108, 0x00422e04, 0x003d2a04, 0x003b270c, 0x003b250d, 0x0036200a, 0x00331d0a, 0x002e1c0a, 0x00291a08, 0x00261a09, 0x00201807, 0x00201607, 0x001f1406, 0x001c1306, 0x001a1306, 0x00191107, 0x001a1208, 0x00191308, 0x00171307, 0x00161207, 0x00161008, 0x00171008, 0x00181208, 0x00181209, 0x00181208, 0x00181108, 0x00181209, 0x00181209, 0x0019140a, 0x0019140a, 0x00191208, 0x00191208, 0x001b1308, 0x001b1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001b1407, 0x001b1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001a1306, 0x00181207, 0x001a1409, 0x001a1408, 0x001a1408, 0x001c1308, 0x001c1208, 0x001c1208, 0x001c1308, 0x001a1304, 0x001a1304, 0x001a1304, 0x001a1304, 0x001a1305, 0x001a1207, 0x001a1307, 0x001a1307, 0x001a1307, 0x001a1306, 0x001a1306, 0x001a1306, 0x001b1206, 0x001c1308, 0x001c1308, 0x001c1306, 0x001d1306, 0x00201408, 0x0023160a, 0x00241608, 0x00251608, 0x00281608, 0x00281608, 0x002c1708, 0x002e1b08, 0x00301c06, 0x00301d06, 0x00341d05, 0x00381f04, 0x003d2106, 0x003f2408, 0x0043270b, 0x0044280c, 0x0044280c, 0x00452b0c, 0x00472c09, 0x004a2c07, 0x00492b03, 0x004b2b03, 0x004e2e06, 0x004f2f05, 0x004f3105, 0x004f3004, 0x00513003, 0x00583404, 0x005d3803, 0x00663c03, 0x006b3d04, 0x00744308, 0x0079470b, 0x007c4c0e, 0x007f500f, 0x00835310, 0x0085550c, 0x0089560a, 0x00905505, 0x00985b08, 0x009c5c03, 0x00a06302, 0x00a26c02, 0x00a8730a, 0x00a06a0c, 0x008e5600, 0x00915c04, 0x00a97d11, 0x00c8a71f, 0x00ccb418, 0x00ccb70f, 0x00ccb80b, 0x00ccb80c, 0x00c5aa11, 0x00a98207, 0x00966100, 0x00895402, 0x0084540b, 0x00805510, 0x007d5410, 0x007a510e, 0x0078500e, 0x0078500f, 0x007d5411, 0x007f530f, 0x0080540f, 0x0081560f, 0x007e5309, 0x0088570d, 0x0096640d, 0x00bf9421, 0x00cbb11c, 0x00c9b711, 0x00cab70c, 0x00ccb60c, 0x00ccac14, 0x00ae7d03, 0x009e6703, 0x00ba8320, 0x00ca9d26, 0x00cba61e, 0x00cca51c, 0x00caa01c, 0x00c59818, 0x00bd8c18, 0x00b07f10, 0x00a4730b, 0x00996805, 0x00925e05, 0x008c5805, 0x008a570d, 0x0081500c, 0x00754b0d, 0x006f480d, 0x0068440c, 0x00623f0c, 0x005c3a0b, 0x0058380b, 0x0054360c, 0x0050340c, 0x004d320b, 0x004c300b, 0x004c300c, 0x00482c0b, 0x00452908, 0x0044280a, 0x00422709, 0x003f2509, 0x003c2309, 0x003c210c, 0x0039200e, 0x00301a0a, 0x002a190a, 0x00281a0c, 0x0026190d, 0x0022170b, 0x001f1308, 0x0023180c, 0x0020160a, 0x001b1308, 0x0018130a, 0x0014120a, 0x00121008, 0x00101007, 0x000e1006, 0x000c1005, 0x000b1005, 0x000c0f04, 0x000c0f04, 0x000c0f03, 0x000a1004, 0x000e130a, 0x00141914, 0x00141815, 0x00141a15, 0x00161c17, 0x00181d18, 0x00181e19, 0x001a201b, 0x001a2019, 0x00192019, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x0024250b, 0x0024250c, 0x0024250b, 0x0026280b, 0x00292b0b, 0x00292b0a, 0x00292b0a, 0x002d2f0a, 0x002c2d0a, 0x0030310c, 0x0030310c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0030310c, 0x0030310c, 0x0030310c, 0x0030310c, 0x0030310c, 0x0032330c, 0x0030310c, 0x0030310c, 0x002d2f0b, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x0026280a, 0x0026280b, 0x0026280c, 0x0024250c, 0x0020230a, 0x00202308, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c09, 0x00141809, 0x0014180b, 0x0014180b, 0x0014180d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x00191c16, 0x00191c16, 0x00191c16, 0x00171a14, 0x0010130c, 0x000f120a, 0x000f120a, 0x000e1109, 0x00101009, 0x00121107, 0x00171408, 0x001d170a, 0x00201809, 0x001c1304, 0x00281c0c, 0x002f210b, 0x0035260d, 0x003b2a0c, 0x00402e0c, 0x00443108, 0x004c350b, 0x00523a0c, 0x005c400f, 0x00644310, 0x006e4812, 0x00764d12, 0x007f5612, 0x00855d12, 0x008d6713, 0x009a7318, 0x00a8781b, 0x00b18420, 0x00ba9023, 0x00c09822, 0x00c7a21b, 0x00cba81a, 0x00ccac17, 0x00ccb018, 0x00ccb418, 0x00ccb817, 0x00ccb811, 0x00ccb80c, 0x00cab90a, 0x00cab90a, 0x00cbb90c, 0x00ccba0d, 0x00ccbb0e, 0x00cbbc0c, 0x00cbbc0c, 0x00cbbb0d, 0x00c9bc0d, 0x00c8ba0c, 0x00cbb317, 0x00b48d10, 0x00926100, 0x008a5a00, 0x009c7507, 0x00c1a11b, 0x00c9b116, 0x00cab80d, 0x00c8ba09, 0x00cabb08, 0x00cbbb07, 0x00ccb712, 0x00ccb51b, 0x00ccb31e, 0x00c9af21, 0x00c3a621, 0x00bc9f21, 0x00b8981c, 0x00b8961f, 0x00b89420, 0x00bb9621, 0x00c49e25, 0x00c9a425, 0x00ccaa24, 0x00ccb21b, 0x00ccb813, 0x00cab90b, 0x00c8ba0a, 0x00ccb410, 0x00bb9910, 0x00996a06, 0x00834b00, 0x00723e00, 0x00714000, 0x00754500, 0x00744200, 0x00713f00, 0x00743f02, 0x00754100, 0x007c4800, 0x00804b00, 0x00824c00, 0x00834c00, 0x00834c00, 0x00824b00, 0x00784400, 0x00724000, 0x00724202, 0x006c4003, 0x00663c00, 0x00633d03, 0x00603c04, 0x005a3a02, 0x00533600, 0x00513601, 0x00503404, 0x00503407, 0x00503407, 0x004c3006, 0x004b3008, 0x00472f09, 0x00422e0a, 0x00402c08, 0x003d2a06, 0x003c2905, 0x00382503, 0x00362106, 0x00342007, 0x00331d08, 0x002f1908, 0x002c1909, 0x00281908, 0x00221707, 0x00201806, 0x00201508, 0x001e1308, 0x001c1206, 0x001a1306, 0x00191207, 0x00181308, 0x00181308, 0x00151307, 0x00161207, 0x00171008, 0x00151007, 0x00151007, 0x00181108, 0x00181309, 0x00171008, 0x00181108, 0x00181108, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x001b1308, 0x001b1308, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1307, 0x00181105, 0x001c1509, 0x001c1408, 0x001c1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001c1104, 0x001c1104, 0x001c1107, 0x001b1108, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x00201408, 0x00211408, 0x00221407, 0x00241508, 0x00241409, 0x00271308, 0x00291607, 0x002d1807, 0x002f1b07, 0x002f1b05, 0x00311b03, 0x00331c01, 0x00341d04, 0x00372006, 0x003a2108, 0x003c230a, 0x0040240c, 0x00402508, 0x00402505, 0x00402504, 0x00412703, 0x00412804, 0x00422a07, 0x00442907, 0x00442908, 0x00472908, 0x004a2d0a, 0x004c2e09, 0x004e2e05, 0x00503003, 0x00533104, 0x00553004, 0x00573105, 0x00583205, 0x005d3508, 0x00613a09, 0x00643c0b, 0x006b3f0b, 0x00734005, 0x00784405, 0x00804a07, 0x00844f06, 0x00885306, 0x00885305, 0x00855004, 0x00814d02, 0x00885706, 0x009b680c, 0x00c29620, 0x00ccad1c, 0x00ccb510, 0x00ccb907, 0x00ccb907, 0x00cbb411, 0x00c09d14, 0x00a47503, 0x008f5e00, 0x00885704, 0x0084540c, 0x0080540e, 0x007c5210, 0x0079500f, 0x007a5112, 0x007d5211, 0x007f530f, 0x0080540d, 0x0083580e, 0x00835609, 0x008c5a0e, 0x009c6c11, 0x00c29a23, 0x00ccb21b, 0x00c9b611, 0x00cbb60c, 0x00ccb60b, 0x00ccac13, 0x00ae7c03, 0x009f6502, 0x00b98319, 0x00cca422, 0x00ccad14, 0x00cab010, 0x00ccb014, 0x00ccac14, 0x00cca814, 0x00c8a215, 0x00c69d19, 0x00c09418, 0x00bc8b19, 0x00b07b13, 0x00a97113, 0x009c650f, 0x00935c0d, 0x008b580d, 0x00865510, 0x00805110, 0x007c4c0f, 0x0076480f, 0x006f4410, 0x00674110, 0x00613d0e, 0x005b390a, 0x00553508, 0x00513208, 0x004c3008, 0x004c2e09, 0x004a2c0a, 0x00472a0c, 0x0044280b, 0x00422608, 0x0040240a, 0x00371e08, 0x00311c09, 0x002e1e0a, 0x002c1d0b, 0x00271a09, 0x00201404, 0x00211507, 0x0023180a, 0x001d1408, 0x001a1308, 0x00171209, 0x00131008, 0x00110f07, 0x00101006, 0x000c1005, 0x000c1007, 0x000c0f04, 0x000b0e02, 0x000b0e02, 0x000a1004, 0x000e130b, 0x00141813, 0x00141814, 0x00141815, 0x00161a17, 0x00181c19, 0x00191d1a, 0x00191f1a, 0x0019201a, 0x0019201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180b, 0x00141809, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x00202309, 0x0024250b, 0x0024250b, 0x0026280c, 0x0026280b, 0x00292b0b, 0x00292b0b, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002c2d0a, 0x002d2f0a, 0x002c2d0a, 0x002c2d0a, 0x00292b0a, 0x00292b0b, 0x00292b0b, 0x0026280b, 0x0024250b, 0x0024250c, 0x0020230a, 0x00202308, 0x001d2008, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130d, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x001a1d17, 0x00191c16, 0x00191c16, 0x00181c15, 0x00141710, 0x000f110b, 0x0010120a, 0x0010120a, 0x00101009, 0x00101008, 0x00141208, 0x001a140a, 0x0020180b, 0x00221808, 0x00241809, 0x002d200e, 0x0035260e, 0x003a2a0c, 0x00402e0c, 0x0048350c, 0x00543c0c, 0x005c3f0b, 0x00644408, 0x00714e0b, 0x007c560d, 0x00886011, 0x00986d14, 0x00a77c1b, 0x00b38821, 0x00bc9324, 0x00c49d28, 0x00c8a426, 0x00cba926, 0x00caab21, 0x00caad1c, 0x00cab011, 0x00ccb611, 0x00ccb810, 0x00ccb90f, 0x00ccba10, 0x00ccba0f, 0x00cbba0c, 0x00cab908, 0x00cab909, 0x00cab90a, 0x00cbba0b, 0x00cbba0b, 0x00cbba0b, 0x00cbbb0a, 0x00ccbb08, 0x00cbba08, 0x00cbbb06, 0x00cbbc08, 0x00ccb614, 0x00bf9e19, 0x00966a03, 0x007f4f00, 0x00835400, 0x009d7407, 0x00bc9a18, 0x00caad18, 0x00ccb416, 0x00ccb70e, 0x00cbba0a, 0x00ccbc0c, 0x00ccbc10, 0x00ccbc14, 0x00ccbc18, 0x00ccbb1b, 0x00ccb91c, 0x00cab61c, 0x00ccb41f, 0x00c9b21e, 0x00cab11d, 0x00ccb41d, 0x00ccb318, 0x00ccb414, 0x00ccb80a, 0x00ccb809, 0x00ccb60e, 0x00cab114, 0x00bc980f, 0x009c7002, 0x00805200, 0x00724100, 0x00603700, 0x005c3700, 0x005b3700, 0x005a3504, 0x005c340a, 0x005d3408, 0x005c3402, 0x005e3502, 0x00603802, 0x00633901, 0x00643a00, 0x00663b01, 0x00663c01, 0x00603800, 0x005b3500, 0x00593503, 0x00543403, 0x00533303, 0x00523404, 0x00513509, 0x004d3408, 0x00493407, 0x00483306, 0x00483207, 0x00483009, 0x0048300b, 0x00442d0a, 0x00412c0c, 0x003e2c0c, 0x003b290d, 0x003a280d, 0x0038250b, 0x0037240a, 0x00332005, 0x00321f06, 0x00321f08, 0x00301c08, 0x002c1808, 0x0029180b, 0x00251508, 0x00241508, 0x00201608, 0x00201508, 0x001e1308, 0x001c1206, 0x001a1306, 0x00191207, 0x00181308, 0x00181308, 0x00151307, 0x00161207, 0x00171008, 0x00171008, 0x00161008, 0x00181108, 0x00181209, 0x00171008, 0x00181108, 0x00181108, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x001b1308, 0x001b1308, 0x001b1407, 0x001b1407, 0x001c1307, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001b1407, 0x001e170b, 0x001d160a, 0x001e150a, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001c1104, 0x001c1104, 0x001c1108, 0x001b1108, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x00201408, 0x00211408, 0x00211507, 0x00221608, 0x00241409, 0x00261408, 0x00261504, 0x00291807, 0x002b1909, 0x002b190a, 0x002c1a08, 0x002d1b06, 0x002e1c06, 0x002f1c09, 0x00321d0b, 0x00341e0a, 0x0038200b, 0x00382108, 0x00392107, 0x003a2305, 0x003b2404, 0x003a2404, 0x003d2506, 0x00402607, 0x00422809, 0x00432809, 0x00442909, 0x00472a08, 0x00482b07, 0x00482c04, 0x00482c05, 0x00482c04, 0x004b2b05, 0x004c2c04, 0x004d2c03, 0x004d2c00, 0x004e2d00, 0x00502f00, 0x00542f01, 0x00583303, 0x005e3603, 0x00643803, 0x00653801, 0x006f4207, 0x0072460a, 0x00754a0b, 0x0080530c, 0x008d5e0f, 0x00ac7f1a, 0x00c5a422, 0x00cab218, 0x00ccb80d, 0x00ccb808, 0x00cbb40f, 0x00cbb11b, 0x00ba960f, 0x00a27703, 0x00946400, 0x008b5904, 0x00845408, 0x00805208, 0x007c5109, 0x007d510d, 0x0080520e, 0x0081530d, 0x0083540b, 0x0086580c, 0x00885908, 0x00915f0c, 0x00ab7d1a, 0x00c9a425, 0x00ccb417, 0x00cab70d, 0x00ccb60b, 0x00cbb70c, 0x00ccac13, 0x00b07b03, 0x009f6502, 0x00b9841b, 0x00cca520, 0x00cab30d, 0x00c8b708, 0x00c9b70e, 0x00ccb30e, 0x00ccb210, 0x00ccb114, 0x00ccae17, 0x00cbab18, 0x00cba117, 0x00c99e19, 0x00c8991c, 0x00c08f18, 0x00b78418, 0x00ac7814, 0x00a26e10, 0x009a640c, 0x00975f0c, 0x0091590d, 0x008c550e, 0x0084510e, 0x007d500c, 0x00774c0b, 0x006c4407, 0x00684009, 0x00613b07, 0x005c3705, 0x00583405, 0x00543108, 0x00502e0a, 0x004b2c07, 0x00472908, 0x003d2306, 0x00382108, 0x00362209, 0x0034210b, 0x002f1e09, 0x00281604, 0x00231403, 0x00241708, 0x00211708, 0x001c1408, 0x00181308, 0x00141007, 0x00110f05, 0x00101005, 0x000d0f05, 0x000c1005, 0x000c0f04, 0x000b0e02, 0x000c1001, 0x000a1004, 0x000e130b, 0x00131712, 0x00141814, 0x00141815, 0x00161a17, 0x00181c18, 0x00181d1a, 0x00191f1a, 0x0019201a, 0x0019201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202308, 0x00202309, 0x0024250a, 0x0024250b, 0x0024250c, 0x0026280c, 0x0026280b, 0x0026280b, 0x00292b0b, 0x0026280a, 0x00292b0b, 0x0026280a, 0x0026280a, 0x00292b0b, 0x00292b0b, 0x0026280a, 0x0026280a, 0x00292b0b, 0x00292b0b, 0x00292b0b, 0x0026280b, 0x0026280b, 0x0024250b, 0x0024250b, 0x0024250b, 0x00202309, 0x00202309, 0x001d2008, 0x001d2008, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180e, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x00191e17, 0x00191d18, 0x00191d18, 0x001a1d18, 0x001a1d17, 0x001a1c16, 0x0013140e, 0x0010110b, 0x0012110a, 0x0012110a, 0x00121108, 0x00131008, 0x00181309, 0x001d160c, 0x0022180c, 0x00231808, 0x002c1e0e, 0x0034240f, 0x003b280f, 0x00402d0e, 0x0048340e, 0x00543d10, 0x00644510, 0x00745012, 0x00855d11, 0x00936b14, 0x00a17c18, 0x00b79124, 0x00c39e24, 0x00c9a823, 0x00ccac24, 0x00ccae20, 0x00ccb11e, 0x00ccb318, 0x00ccb516, 0x00ccb514, 0x00ccb610, 0x00ccb70c, 0x00ccb80b, 0x00ccb90c, 0x00cbba0c, 0x00ccb90c, 0x00ccb90c, 0x00ccb90c, 0x00ccb90c, 0x00cbba0c, 0x00cbba0c, 0x00cbba0c, 0x00cbba0c, 0x00cbba0b, 0x00cab908, 0x00cab908, 0x00c9b808, 0x00cab709, 0x00ccb30d, 0x00c6a814, 0x00b58d14, 0x008e6204, 0x00784a04, 0x007b4c07, 0x007f5200, 0x00946904, 0x00b48c13, 0x00c6a31c, 0x00cbaf18, 0x00ccb510, 0x00cbb90d, 0x00ccba0c, 0x00cbba0c, 0x00ccba0c, 0x00cbba0c, 0x00cbbb0c, 0x00cbba0f, 0x00ccba11, 0x00ccb911, 0x00ccb911, 0x00ccb810, 0x00ccb70d, 0x00ccb70b, 0x00ccb508, 0x00ccb10d, 0x00c8a614, 0x00b58e10, 0x009e6d05, 0x00805300, 0x00694101, 0x00583700, 0x00543305, 0x00533205, 0x00523104, 0x00503007, 0x00502f0a, 0x00522f07, 0x00523001, 0x00523004, 0x00523008, 0x00533003, 0x00533002, 0x00533003, 0x00543003, 0x00543104, 0x00533204, 0x00503205, 0x004c3004, 0x004a2e05, 0x00492e08, 0x00482e0b, 0x00462f0c, 0x00442e09, 0x00422b07, 0x00422a09, 0x00422a0a, 0x00422a0a, 0x003e2808, 0x003a2509, 0x0038250c, 0x0036260c, 0x0034240c, 0x00322009, 0x00312008, 0x00301d06, 0x002e1e07, 0x002d1c08, 0x002a1908, 0x00271508, 0x0028150b, 0x0026150b, 0x0024150c, 0x0020160b, 0x001f1409, 0x001d1207, 0x001c1206, 0x001a1306, 0x00191207, 0x00181308, 0x00181308, 0x00151307, 0x00171208, 0x00181108, 0x00181108, 0x00181309, 0x00171008, 0x00151007, 0x00181108, 0x00181309, 0x00181309, 0x00181308, 0x00181308, 0x00181308, 0x00181308, 0x00191208, 0x00191208, 0x00191306, 0x00191306, 0x001b1307, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1307, 0x001c1307, 0x001e1409, 0x001c1408, 0x001b1408, 0x001e170b, 0x001d160a, 0x001d1409, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001c1104, 0x001c1104, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x00201408, 0x00201408, 0x00221407, 0x00221407, 0x00241409, 0x00241608, 0x00251607, 0x00271706, 0x00271706, 0x00281808, 0x00291807, 0x002c1906, 0x002c1a07, 0x002d1a07, 0x002e1b08, 0x00301b08, 0x00311c0a, 0x00331c09, 0x00331d08, 0x00351e06, 0x00351e05, 0x00351e05, 0x00351e05, 0x00382007, 0x003c230a, 0x003e230b, 0x0040240a, 0x00402409, 0x00402607, 0x003f2707, 0x003c2404, 0x003d2505, 0x00412909, 0x00442909, 0x00422806, 0x00442804, 0x00442802, 0x00422a00, 0x00442c03, 0x00482d07, 0x004b2c05, 0x00502f08, 0x00543008, 0x00553005, 0x00543302, 0x00593802, 0x00694305, 0x007f5214, 0x00946412, 0x00b48e1a, 0x00c7ac1d, 0x00c9b412, 0x00ccb80b, 0x00ccb70d, 0x00cab611, 0x00cab315, 0x00bf9b11, 0x00ab7a06, 0x00986401, 0x00905b08, 0x00885606, 0x00835305, 0x00815207, 0x0085540d, 0x0085540c, 0x0087570c, 0x008c5b0d, 0x00925f05, 0x00a37014, 0x00bd9426, 0x00ccac21, 0x00ccb510, 0x00cab808, 0x00ccb708, 0x00cab60b, 0x00c8a70f, 0x00ac7800, 0x00a46907, 0x00bc881e, 0x00cca61d, 0x00c8b40a, 0x00c6b804, 0x00c6b609, 0x00c9b60a, 0x00ccb60b, 0x00cbb60c, 0x00ccb40e, 0x00ccb30f, 0x00ccb00d, 0x00ccb00e, 0x00ccaf11, 0x00ccac13, 0x00cba819, 0x00c79e18, 0x00c29518, 0x00bd8c14, 0x00b88414, 0x00b17a12, 0x00a8700f, 0x00a0680c, 0x00976008, 0x00905c06, 0x00895808, 0x0085540c, 0x007d4e0a, 0x00764a08, 0x006f4408, 0x00683e0b, 0x00603709, 0x00553105, 0x004e2d04, 0x00472804, 0x00422706, 0x003f2508, 0x003b2108, 0x00392109, 0x00331d07, 0x00281502, 0x00241603, 0x00241807, 0x00201608, 0x001b1408, 0x00161008, 0x00141006, 0x00121006, 0x00101007, 0x000d1007, 0x000c1005, 0x000c0f03, 0x000c1001, 0x000b1004, 0x000c1109, 0x00101510, 0x00141814, 0x00141814, 0x00151916, 0x00161a17, 0x00171c18, 0x00181d18, 0x00181e18, 0x00181f19, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x001d200a, 0x001d2009, 0x001d2008, 0x001d2008, 0x00202308, 0x00202309, 0x00202309, 0x0024250b, 0x0024250b, 0x0024250b, 0x0024250c, 0x0024250c, 0x0026280c, 0x0026280c, 0x0026280c, 0x0026280c, 0x0026280c, 0x0026280c, 0x0024250c, 0x0024250c, 0x0024250b, 0x0024250b, 0x0020230a, 0x00202309, 0x00202309, 0x00202308, 0x001d2008, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x00191c16, 0x00191c16, 0x001a1d17, 0x00191e17, 0x00191d18, 0x00191d18, 0x001a1d18, 0x001a1d17, 0x00191c16, 0x0011140d, 0x0012120c, 0x0014110b, 0x0013120a, 0x00121108, 0x00131008, 0x001b140b, 0x0020170c, 0x0024180a, 0x00251808, 0x00312310, 0x0038280e, 0x00402c0e, 0x0044300c, 0x00503910, 0x005f4211, 0x0079571a, 0x0090691f, 0x00a98220, 0x00bb9826, 0x00c6a82a, 0x00caae27, 0x00cbb41f, 0x00cab414, 0x00cbb613, 0x00ccb712, 0x00ccb910, 0x00cbb90d, 0x00ccbb0d, 0x00cbb90d, 0x00cbb90d, 0x00ccb80e, 0x00ccb80f, 0x00ccb810, 0x00ccb810, 0x00ccb80d, 0x00ccb80d, 0x00cbb90d, 0x00cbb90d, 0x00cbb90d, 0x00cbb90d, 0x00ccb80d, 0x00ccb80d, 0x00ccb80c, 0x00ccb80c, 0x00ccb70d, 0x00ccb510, 0x00cbb014, 0x00bf9810, 0x00a17802, 0x00895b00, 0x00764700, 0x00694005, 0x006c410a, 0x00704608, 0x007c5204, 0x008f6103, 0x00a07408, 0x00b79212, 0x00c6a717, 0x00cbaf13, 0x00cbb010, 0x00cbb10d, 0x00ccb40c, 0x00ccb60a, 0x00ccb509, 0x00ccb60b, 0x00ccb60c, 0x00ccb60d, 0x00ccb50d, 0x00ccb40e, 0x00ccb30e, 0x00ccb012, 0x00c7a412, 0x00be9812, 0x00aa7e0c, 0x008c5c00, 0x00804f01, 0x00704604, 0x00553802, 0x004b3607, 0x0048310e, 0x004a300f, 0x004a2f0a, 0x00492e0a, 0x00492d0c, 0x00492e08, 0x004a2e04, 0x004a2d09, 0x004a2c0d, 0x00492e0b, 0x00492e0b, 0x00492e0b, 0x00482d0a, 0x00472c08, 0x00472d08, 0x00462c07, 0x00452c06, 0x00442c06, 0x00442a08, 0x0043290a, 0x0042290c, 0x003f270a, 0x003e2509, 0x003e250b, 0x003e250b, 0x003e250a, 0x003c2307, 0x00382007, 0x00352008, 0x00342108, 0x00302007, 0x002d1d05, 0x002e1e06, 0x002d1d07, 0x002c1d08, 0x002b1c0a, 0x0028180a, 0x00251509, 0x0027140b, 0x0026150c, 0x0024150d, 0x0020150c, 0x001e1208, 0x001e1107, 0x001c1106, 0x001b1206, 0x00191207, 0x00181308, 0x00181308, 0x00161408, 0x00151308, 0x00181108, 0x00181209, 0x00181309, 0x00171008, 0x00151007, 0x00181108, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181309, 0x00181308, 0x00191208, 0x00191208, 0x00191306, 0x00191306, 0x001b1307, 0x001c1307, 0x001c1408, 0x001c1407, 0x001c1407, 0x001c1307, 0x001c1307, 0x001e1409, 0x001e1409, 0x001b1407, 0x001c1509, 0x001b1407, 0x001d1409, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001c1104, 0x001c1104, 0x001c1206, 0x001c1208, 0x001c1208, 0x001c1208, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x00201408, 0x00201408, 0x00211507, 0x00211507, 0x00241409, 0x00241608, 0x00241607, 0x00271706, 0x00271706, 0x00281707, 0x002a1807, 0x002c1906, 0x002c1a05, 0x002e1a05, 0x002f1b06, 0x002f1b06, 0x002f1a08, 0x00301b08, 0x00301b08, 0x00311c08, 0x00311c06, 0x00311c06, 0x00311c06, 0x00341d08, 0x00351d08, 0x00371e09, 0x00381f08, 0x00392008, 0x00392207, 0x00382206, 0x00352105, 0x00362107, 0x00382309, 0x003a2408, 0x003b2408, 0x003b2407, 0x003c2404, 0x003c2404, 0x003e2606, 0x0042280b, 0x0044280b, 0x00492a0e, 0x004b2d0c, 0x004b2e08, 0x004f3408, 0x004e3202, 0x005a3704, 0x00704713, 0x00845610, 0x00946c09, 0x00b49415, 0x00c7ac18, 0x00ccb610, 0x00ccb80c, 0x00c8ba0b, 0x00c8b90c, 0x00ccb218, 0x00c9a01a, 0x00ba8813, 0x00a5700e, 0x00945f02, 0x00945f06, 0x00905c07, 0x00905c10, 0x00915c0f, 0x00935f0e, 0x0098630f, 0x00a6720f, 0x00b98a20, 0x00caa529, 0x00cbb11d, 0x00cab60c, 0x00cab805, 0x00ccb808, 0x00c8b107, 0x00c39e0a, 0x00a97200, 0x00a46c0a, 0x00bf8c20, 0x00cca91f, 0x00c9b408, 0x00c8b606, 0x00c8b40b, 0x00cbb50a, 0x00cbb50a, 0x00cbb50a, 0x00ccb40c, 0x00cbb50a, 0x00c9b608, 0x00c9b608, 0x00c8b508, 0x00cab50b, 0x00ccb50f, 0x00ccb413, 0x00ccae15, 0x00cba915, 0x00cba418, 0x00ca9e1c, 0x00c6981c, 0x00bf8d18, 0x00b98715, 0x00b27e14, 0x00a87410, 0x00a16c13, 0x00996611, 0x00925e0c, 0x008a560e, 0x00885619, 0x007c4c17, 0x00643c08, 0x00583706, 0x004d2f04, 0x00492c05, 0x00452808, 0x00432608, 0x003e2006, 0x00381f05, 0x002e1b04, 0x00231500, 0x00241806, 0x00221808, 0x001d1609, 0x00181208, 0x00141007, 0x00131008, 0x00101009, 0x000f1007, 0x000c1005, 0x000c0f04, 0x000c1004, 0x000c1004, 0x000d1008, 0x0011150f, 0x00141814, 0x00141814, 0x00151916, 0x00161a17, 0x00171c18, 0x00181d18, 0x00181e18, 0x00181f19, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130d, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2008, 0x00202309, 0x001d2008, 0x00202308, 0x00202308, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202309, 0x00202308, 0x001d2008, 0x001d2008, 0x00202309, 0x001d2009, 0x001d2009, 0x00191c09, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180c, 0x0014180e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x001a1d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x001a1d18, 0x001a1d17, 0x00171a14, 0x0011140d, 0x0011130d, 0x0011120c, 0x00121309, 0x00131209, 0x0016120a, 0x001d140d, 0x0023170c, 0x00281a0a, 0x002c1d0c, 0x0035240e, 0x003a280c, 0x0044300d, 0x004c360c, 0x005c4010, 0x0076521f, 0x00956e28, 0x00b69530, 0x00c8ac26, 0x00ccb41e, 0x00cbb51c, 0x00cbb819, 0x00cbb914, 0x00cbbb0d, 0x00ccbb0d, 0x00ccbb0d, 0x00ccbc0a, 0x00cbbb07, 0x00cbba0a, 0x00cbba0c, 0x00cbb90d, 0x00cbb90f, 0x00cbb90f, 0x00cbb90d, 0x00ccb80d, 0x00ccb80c, 0x00ccb80c, 0x00cbba0c, 0x00cbba0c, 0x00ccb90b, 0x00ccb80c, 0x00ccb70e, 0x00ccb60f, 0x00cbb40c, 0x00cab00c, 0x00ccac13, 0x00c39d0f, 0x00b08609, 0x00956805, 0x007c5000, 0x006c4300, 0x00603902, 0x0059350a, 0x00583607, 0x005c3b06, 0x00614005, 0x00754b08, 0x007c5002, 0x00895c00, 0x009c7003, 0x00ad840b, 0x00b6900e, 0x00bf9911, 0x00c39e10, 0x00c6a10c, 0x00c7a20c, 0x00c7a20c, 0x00c7a10d, 0x00c7a00d, 0x00c49c0c, 0x00c1990e, 0x00b78e07, 0x00ad8104, 0x009d6c04, 0x008d5b00, 0x007a4c00, 0x006c4100, 0x00613b07, 0x00543204, 0x004c3007, 0x00452e09, 0x00442b0a, 0x0044290a, 0x0044280a, 0x0045270c, 0x0044260c, 0x0044260c, 0x0045270c, 0x0047270b, 0x0046280c, 0x0044290c, 0x0044290c, 0x00422a0c, 0x00412b0c, 0x00402a0b, 0x00402a0b, 0x0040290a, 0x003e2708, 0x003c2708, 0x003c2808, 0x003c280a, 0x003a2409, 0x0038220a, 0x0038220a, 0x0038200b, 0x00341e08, 0x0038200b, 0x00341e08, 0x00331c08, 0x00331d09, 0x00321d09, 0x00301d08, 0x002c1b07, 0x002c1b0a, 0x002c1c0c, 0x00281c0c, 0x00271a0a, 0x00241707, 0x00241607, 0x0026150a, 0x00241409, 0x00211308, 0x00201408, 0x00211308, 0x00201207, 0x001d1004, 0x001c1104, 0x001a1207, 0x00181308, 0x00181308, 0x00161408, 0x00151408, 0x0018140c, 0x0019130c, 0x0019110b, 0x0019110b, 0x00181108, 0x00181108, 0x00181108, 0x00181109, 0x0018110b, 0x0018110a, 0x0019130c, 0x0019140b, 0x00191208, 0x00191208, 0x00191306, 0x00191304, 0x001a1308, 0x001b1309, 0x001c1408, 0x001c1408, 0x001d1408, 0x001e1308, 0x001e1308, 0x001f1408, 0x001c1407, 0x00191407, 0x001c1509, 0x001e1409, 0x001e1409, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001e1407, 0x001c1407, 0x001c1406, 0x001c1407, 0x001d1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1408, 0x001f1409, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001e1308, 0x001e1308, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001f1206, 0x00201307, 0x00221509, 0x00231509, 0x00211407, 0x00241407, 0x00251709, 0x00261709, 0x00271809, 0x00291808, 0x00291808, 0x002c1909, 0x002c1a0a, 0x002c1a08, 0x002c1a08, 0x002c1a08, 0x002c1a08, 0x002c1b07, 0x002c1a07, 0x002f1a08, 0x00321c09, 0x00331c0a, 0x00311b06, 0x00331c09, 0x00331c09, 0x00321e08, 0x00321e06, 0x00341e07, 0x00341e07, 0x00341e07, 0x00351e07, 0x00361e07, 0x00381f08, 0x00381f06, 0x003c2105, 0x003e2408, 0x00402409, 0x0041270a, 0x00422808, 0x00422805, 0x00482e08, 0x00482e06, 0x00513007, 0x005e3807, 0x0074490e, 0x00835610, 0x009a6d0b, 0x00bf981c, 0x00cbad1c, 0x00ccb70f, 0x00c7ba06, 0x00c8b906, 0x00ccb80e, 0x00ccb414, 0x00cbad18, 0x00c69d18, 0x00bb8c0f, 0x00b9810e, 0x00b07509, 0x00ad7210, 0x00ac7310, 0x00b07710, 0x00b88117, 0x00c4981c, 0x00caa721, 0x00ccaf1c, 0x00c9b414, 0x00c9b80a, 0x00ccb806, 0x00ccb307, 0x00ccaf0c, 0x00bc8f06, 0x00a36a00, 0x00a87010, 0x00c39924, 0x00c8ad15, 0x00cbb407, 0x00cab40b, 0x00cbb50a, 0x00cbb608, 0x00ccb508, 0x00ccb508, 0x00ccb409, 0x00ccb40a, 0x00cbb50a, 0x00cbb50a, 0x00cbb50a, 0x00cbb50a, 0x00cab60a, 0x00c9b60b, 0x00c9b60b, 0x00c9b50b, 0x00cbb10a, 0x00ccad0f, 0x00ccac14, 0x00cca917, 0x00caa618, 0x00c9a319, 0x00c59c18, 0x00c0951a, 0x00be901b, 0x00ba8113, 0x00af7112, 0x00ac6f20, 0x00a06721, 0x0081500e, 0x00653f02, 0x00523600, 0x004c3306, 0x004a2e09, 0x00482908, 0x00432507, 0x003c2307, 0x00342008, 0x002a1a05, 0x00261704, 0x00251808, 0x0022180b, 0x001c140a, 0x00171008, 0x00141008, 0x00131009, 0x00101007, 0x00100f08, 0x000c0e08, 0x000e1008, 0x00101008, 0x00101006, 0x00111309, 0x00131610, 0x00141914, 0x00141914, 0x00151a14, 0x00161b15, 0x00161c17, 0x00181e18, 0x0019201a, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180a, 0x0014180a, 0x00191c0a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x00191c09, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x00202309, 0x001d2008, 0x001d2008, 0x001d2008, 0x001d2008, 0x00202309, 0x001d2009, 0x001d2009, 0x001d2009, 0x001d2009, 0x00191c09, 0x001d200a, 0x00191c09, 0x00191c0a, 0x00191c0a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180c, 0x0014180e, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c16, 0x00191c16, 0x001a1d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00191d18, 0x001a1d18, 0x001a1d17, 0x00181914, 0x0011120c, 0x0012130d, 0x0013120c, 0x00131209, 0x0014130a, 0x00161208, 0x00211810, 0x00261a0e, 0x00281a09, 0x002e1e09, 0x0038250e, 0x003e2b0d, 0x0048320c, 0x00533c0e, 0x006a4b12, 0x00886420, 0x00ad892e, 0x00caad34, 0x00cbb81f, 0x00ccb914, 0x00cbb810, 0x00cbba0e, 0x00cbbb0b, 0x00ccbc09, 0x00cbbb07, 0x00ccbc08, 0x00ccbc06, 0x00cbbb06, 0x00cbba0a, 0x00cbba0c, 0x00cbba0b, 0x00cbba09, 0x00cbba08, 0x00cbba0b, 0x00cbba0a, 0x00ccb90a, 0x00ccb90a, 0x00ccb90c, 0x00cbb80b, 0x00ccb609, 0x00ccb30c, 0x00ccb011, 0x00c8aa12, 0x00c6a313, 0x00c09611, 0x00b2840f, 0x009f6e08, 0x00885700, 0x00744600, 0x00684001, 0x005c3703, 0x00553408, 0x0051340a, 0x00503408, 0x00503403, 0x00523401, 0x005a3807, 0x00643e09, 0x006e4606, 0x00754b03, 0x00784d00, 0x00815602, 0x00875b03, 0x008c5f04, 0x00906502, 0x00926701, 0x00936701, 0x00946601, 0x00946501, 0x00905f01, 0x008c5b00, 0x00855300, 0x007b4a00, 0x00744500, 0x00683c00, 0x00603700, 0x00573202, 0x00503005, 0x004b2c04, 0x00462c07, 0x00442c09, 0x00422808, 0x00412708, 0x00402608, 0x0041260a, 0x0040250b, 0x0040240b, 0x0040240a, 0x00402309, 0x00402308, 0x003f2308, 0x003d2408, 0x003c2409, 0x003a2509, 0x00392408, 0x00392409, 0x0039240a, 0x00382306, 0x00352206, 0x00352206, 0x00342006, 0x00332008, 0x00331f08, 0x00331e09, 0x00321d09, 0x002f1b06, 0x00321d09, 0x002f1b08, 0x00301b08, 0x00311e0b, 0x00301d0a, 0x002c1b07, 0x002a1907, 0x002b190b, 0x002a190c, 0x0027190c, 0x0024180a, 0x00241809, 0x00241809, 0x00241409, 0x00221408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x001d1104, 0x001c1204, 0x001a1207, 0x00181308, 0x00181308, 0x00161408, 0x00141308, 0x00151308, 0x00171208, 0x00181309, 0x00191209, 0x0018100a, 0x0018100a, 0x0018100a, 0x0018100a, 0x0018110a, 0x0018110a, 0x0019140b, 0x00191409, 0x00191208, 0x00191208, 0x00191306, 0x00191304, 0x001a1308, 0x001b1309, 0x001c1408, 0x001c1408, 0x001d1408, 0x001e1308, 0x001e1308, 0x001f1408, 0x001c1407, 0x00191407, 0x001c1509, 0x001e1409, 0x001f1409, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001e1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001d1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1408, 0x001f1409, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001e1308, 0x001e1308, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001e1205, 0x001e1205, 0x00201408, 0x00201408, 0x00201408, 0x00221509, 0x0023160a, 0x0023160a, 0x00241608, 0x00241506, 0x00251506, 0x00261708, 0x0028180a, 0x00281908, 0x00281908, 0x00281908, 0x00281908, 0x00291908, 0x002a1807, 0x002c1808, 0x002e1908, 0x00311c0b, 0x002f1a08, 0x002f1a08, 0x002f1a08, 0x00301b06, 0x00301a04, 0x00311b05, 0x00331b05, 0x00331b05, 0x00331b05, 0x00341b06, 0x00341b07, 0x00341c05, 0x00381c04, 0x00391e06, 0x003b2007, 0x003d2209, 0x003e230a, 0x003e2408, 0x00442b0c, 0x00452a09, 0x00492c08, 0x00523005, 0x00603704, 0x0075480e, 0x00815404, 0x009c700b, 0x00ba9318, 0x00cbac1a, 0x00cbb412, 0x00cab50c, 0x00ccb80e, 0x00ccb60d, 0x00cbb210, 0x00cbb018, 0x00cbaa17, 0x00cca618, 0x00caa31c, 0x00c89c18, 0x00c89c17, 0x00c9a017, 0x00cba519, 0x00ccac19, 0x00ccb116, 0x00cbb410, 0x00c9b70c, 0x00c8b908, 0x00cbb809, 0x00ccb30d, 0x00c4a40e, 0x00ae7f01, 0x00a06601, 0x00af7813, 0x00c89f23, 0x00c8b013, 0x00cab507, 0x00cab40b, 0x00cbb50a, 0x00cbb605, 0x00cbb503, 0x00cbb405, 0x00ccb507, 0x00ccb508, 0x00cbb608, 0x00cbb608, 0x00cbb50a, 0x00cbb50a, 0x00c9b60a, 0x00c9b60a, 0x00cbb50a, 0x00cbb609, 0x00cbb408, 0x00cbb208, 0x00ccb20c, 0x00ccb412, 0x00ccb313, 0x00ccb213, 0x00ccb116, 0x00c9ad16, 0x00c8a815, 0x00caa016, 0x00c38e13, 0x00c3871c, 0x00b47818, 0x009e6210, 0x00804d04, 0x00643c01, 0x00583704, 0x00503108, 0x004c2e0a, 0x00472b0b, 0x0040270a, 0x0039240c, 0x00301d08, 0x00281803, 0x00261806, 0x00251b0b, 0x001c1609, 0x00181308, 0x00161209, 0x00141109, 0x00101007, 0x00100f08, 0x000f100a, 0x000e1008, 0x000f0f05, 0x000f0f04, 0x00111309, 0x00131610, 0x00131712, 0x00131712, 0x00141813, 0x00141914, 0x00141a14, 0x00161c17, 0x00181e18, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180b, 0x00191c0b, 0x0014180a, 0x00191c0a, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x001d2009, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c09, 0x00191c0a, 0x0014180a, 0x0014180a, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191c18, 0x00191c18, 0x001a1d18, 0x00191d18, 0x00191d18, 0x00181e18, 0x00191d18, 0x00191d18, 0x00181c18, 0x00191d18, 0x00121510, 0x0010130c, 0x0013110c, 0x0014100b, 0x00141008, 0x00171208, 0x001d180c, 0x00241a0e, 0x00261a0c, 0x002c1c09, 0x0034240c, 0x003c280e, 0x00442d0e, 0x004d350d, 0x005c4313, 0x00775714, 0x009a771f, 0x00c2a42e, 0x00cbb721, 0x00ccc018, 0x00cbc010, 0x00cabc0b, 0x00cbbc07, 0x00cabc06, 0x00cbba07, 0x00cbba07, 0x00cbba07, 0x00cbbb05, 0x00cbbb06, 0x00cbba0a, 0x00cbba0c, 0x00cab908, 0x00caba06, 0x00cab907, 0x00ccb90c, 0x00cab70c, 0x00cbb50e, 0x00cbb20f, 0x00cab014, 0x00c9aa12, 0x00c6a50c, 0x00c09a07, 0x00b89008, 0x00ad8406, 0x00a07405, 0x00926403, 0x00875604, 0x00784703, 0x006c3c02, 0x00603a02, 0x00563400, 0x00513404, 0x004c3305, 0x00483008, 0x00473007, 0x00483106, 0x00483005, 0x004a3004, 0x004c2f03, 0x00543504, 0x005a3803, 0x005f3a04, 0x00613b03, 0x00643c03, 0x00643c01, 0x00653d00, 0x00673f00, 0x00684000, 0x00684000, 0x00684101, 0x00674002, 0x00623c01, 0x005d3701, 0x00593400, 0x00553200, 0x00502e00, 0x004e2b01, 0x00492a04, 0x00452908, 0x00432908, 0x00412808, 0x003f2708, 0x003e2407, 0x003c2306, 0x003c2107, 0x003d2209, 0x003c220a, 0x003c220a, 0x003b2109, 0x003a2009, 0x003a2009, 0x003b2009, 0x00392008, 0x00371f08, 0x00362008, 0x00341f09, 0x00341f09, 0x00341f08, 0x00341f08, 0x00331f07, 0x00331f07, 0x00321e09, 0x00311c09, 0x00301c08, 0x00301b08, 0x002e1b08, 0x002d1b08, 0x002d1b08, 0x002c1908, 0x002c1908, 0x002b1908, 0x002b1908, 0x00281806, 0x00261607, 0x00261608, 0x00251609, 0x0024170a, 0x00221509, 0x00221509, 0x00221509, 0x00241409, 0x00211408, 0x001f1407, 0x001d1407, 0x001d1205, 0x001e1205, 0x001d1205, 0x001c1305, 0x001b1308, 0x001a1408, 0x00181408, 0x00151307, 0x00141207, 0x00141308, 0x00151308, 0x00181309, 0x00181309, 0x00191209, 0x00181108, 0x00181108, 0x00191209, 0x0018120a, 0x00181309, 0x00191409, 0x00181307, 0x00191208, 0x00191208, 0x00191306, 0x00191304, 0x00191207, 0x00191208, 0x001a1307, 0x001b1407, 0x001c1207, 0x001c1106, 0x001c1106, 0x001e1407, 0x001f1508, 0x00181306, 0x001c1408, 0x001c1408, 0x001d1308, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1407, 0x001c1407, 0x001d1305, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201409, 0x00201409, 0x00201309, 0x00201308, 0x00201308, 0x00221407, 0x00221407, 0x00241508, 0x00241608, 0x00241707, 0x00241707, 0x00241707, 0x00241707, 0x00251706, 0x00261605, 0x00281707, 0x002b1808, 0x002c1a09, 0x002a1807, 0x002a1808, 0x002d1c09, 0x002c1a07, 0x002e1a05, 0x002e1a05, 0x002f1a05, 0x002f1a05, 0x002f1a05, 0x002f1a06, 0x00301b06, 0x00311a04, 0x00321b04, 0x00321b04, 0x00341c06, 0x00351e09, 0x00371f0a, 0x00372008, 0x003d260d, 0x003d260b, 0x00422809, 0x00492c08, 0x00502e04, 0x005d3507, 0x00704509, 0x007f5406, 0x00946807, 0x00b48915, 0x00c9a51d, 0x00ccb018, 0x00ccb214, 0x00ccb60d, 0x00ccb80c, 0x00cab710, 0x00cab610, 0x00cab410, 0x00cbb411, 0x00cbb311, 0x00cbb310, 0x00ccb40e, 0x00ccb40d, 0x00ccb60d, 0x00ccb70b, 0x00cab707, 0x00c9b804, 0x00c9b807, 0x00ccb80e, 0x00caac14, 0x00b48c08, 0x009f6c00, 0x00a06503, 0x00bd881c, 0x00cca823, 0x00cab210, 0x00cab507, 0x00cbb50c, 0x00cbb50a, 0x00cbb605, 0x00ccb604, 0x00ccb506, 0x00ccb508, 0x00ccb508, 0x00cbb608, 0x00cbb608, 0x00cbb50a, 0x00cbb50a, 0x00c9b60a, 0x00c9b60a, 0x00cbb50a, 0x00cbb609, 0x00cbb508, 0x00cbb406, 0x00cbb408, 0x00ccb509, 0x00ccb509, 0x00cbb50b, 0x00cbb50b, 0x00cab50c, 0x00ccb40f, 0x00ccaa0f, 0x00cc9d0e, 0x00cb9412, 0x00c48b12, 0x00bc8213, 0x00a66e0e, 0x00875408, 0x006d4306, 0x005d3b0a, 0x004f3308, 0x0048300c, 0x0043290c, 0x0040260e, 0x0038220b, 0x002e1b06, 0x00281704, 0x00261a09, 0x001c1708, 0x00161104, 0x00171208, 0x00141308, 0x00121208, 0x00101008, 0x000d0f08, 0x000c0f07, 0x00101007, 0x00101005, 0x00101108, 0x0011140e, 0x00101510, 0x00101510, 0x00131712, 0x00141813, 0x00141a14, 0x00151c16, 0x00151c16, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130c, 0x000f130b, 0x0014180c, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x0014180a, 0x00191c0b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x0014180f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181c18, 0x00181c18, 0x00191d18, 0x00191d18, 0x00191d18, 0x00181e18, 0x00191d18, 0x001a1f19, 0x00191e17, 0x00191e17, 0x0011150f, 0x0010120c, 0x0013100c, 0x0016100b, 0x00171009, 0x00181308, 0x001d170b, 0x00241a0c, 0x00271909, 0x002f200c, 0x0038260e, 0x00402c0e, 0x0048300c, 0x00563b10, 0x00654916, 0x00846214, 0x00b09027, 0x00cab025, 0x00cabc14, 0x00cbc210, 0x00cbc210, 0x00cabe0c, 0x00cbbc08, 0x00cbba07, 0x00cab909, 0x00cab90b, 0x00cbba0c, 0x00cbba08, 0x00cbbb06, 0x00cbbb09, 0x00ccb90c, 0x00cbb80b, 0x00cbb908, 0x00cbb70b, 0x00cab511, 0x00c8b014, 0x00c8a815, 0x00c39c11, 0x00b98f0e, 0x00ab7d04, 0x009e6f00, 0x00946400, 0x008e5d00, 0x00895700, 0x007d4e00, 0x00704700, 0x00674000, 0x005e3800, 0x005a3706, 0x0055350b, 0x004e3208, 0x00483207, 0x00453106, 0x00432f06, 0x00422e08, 0x00422d08, 0x00422d09, 0x00422d09, 0x00442e08, 0x00432a03, 0x00482e06, 0x004a2e04, 0x004c2e02, 0x004c2f03, 0x004c3003, 0x004c3002, 0x004d3203, 0x004d3403, 0x004d3403, 0x004f3403, 0x004e3401, 0x004c3101, 0x004c3105, 0x00492f04, 0x00482c04, 0x00472c05, 0x00462b0b, 0x0044290d, 0x0040260c, 0x003d260a, 0x003c2308, 0x003a2207, 0x00392106, 0x00381f05, 0x00361d05, 0x00361d07, 0x00351e08, 0x00341e08, 0x00341d08, 0x00331c08, 0x00341c07, 0x00341c07, 0x00341c08, 0x00341d09, 0x00321d09, 0x00311c0a, 0x00321d0b, 0x00301d0a, 0x00311d08, 0x00301d08, 0x00301d08, 0x00301c0a, 0x00301c0c, 0x002c1a08, 0x002c1a08, 0x002c1908, 0x002a1807, 0x002a1808, 0x00291809, 0x00281808, 0x00271708, 0x00261808, 0x00241606, 0x00241607, 0x00241608, 0x0024160a, 0x0023160c, 0x0021140a, 0x0021140a, 0x0021140a, 0x0022150b, 0x0020140a, 0x001d1408, 0x001c1408, 0x001c1305, 0x001d1205, 0x001c1205, 0x001c1305, 0x001b1407, 0x001a1308, 0x00181408, 0x00151207, 0x00141206, 0x00131306, 0x00141206, 0x00161307, 0x00181308, 0x00191307, 0x00191207, 0x00191307, 0x00191307, 0x00181308, 0x00181308, 0x00181307, 0x00181306, 0x00191307, 0x00191208, 0x00191306, 0x00191304, 0x00191207, 0x00191208, 0x001a1308, 0x001b1407, 0x001c1207, 0x001c1106, 0x001c1106, 0x001e1407, 0x001f1508, 0x00181306, 0x001c1408, 0x001c1408, 0x001d1408, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1407, 0x001c1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201208, 0x00201208, 0x00201208, 0x001e1208, 0x001d1208, 0x001d1207, 0x001c1106, 0x001f1207, 0x00201207, 0x00211308, 0x00221408, 0x00231509, 0x00221608, 0x00221708, 0x00221708, 0x00221708, 0x00241508, 0x00251508, 0x00261508, 0x00281408, 0x00281808, 0x00261606, 0x00261707, 0x00281908, 0x00281805, 0x00291806, 0x00291805, 0x00291805, 0x00291805, 0x00291805, 0x002a1806, 0x002a1806, 0x002b1905, 0x00301c08, 0x002f1c08, 0x002f1c08, 0x00301c08, 0x00301c0c, 0x00311e0b, 0x00341f0a, 0x00352008, 0x003c270c, 0x00442a0b, 0x00492b09, 0x004f2d08, 0x00583505, 0x00654104, 0x00795002, 0x008f6203, 0x00a87d0c, 0x00bf9918, 0x00cbab1b, 0x00ccb111, 0x00ccb50c, 0x00cab60c, 0x00cab70c, 0x00cab80c, 0x00cbb90d, 0x00cab90d, 0x00c8ba0b, 0x00c8b908, 0x00c8ba08, 0x00c9b908, 0x00c9b808, 0x00c9b806, 0x00cbb804, 0x00cab205, 0x00ccaf0f, 0x00bc9205, 0x00a57300, 0x009c6200, 0x00a16504, 0x00bf8b1b, 0x00caa41b, 0x00c9af0e, 0x00cbb40a, 0x00ccb40e, 0x00ccb50c, 0x00ccb508, 0x00ccb40a, 0x00ccb50a, 0x00ccb40a, 0x00ccb40a, 0x00cbb50a, 0x00c9b60a, 0x00c9b60a, 0x00c9b60a, 0x00c8b70a, 0x00c8b709, 0x00c9b609, 0x00c9b60a, 0x00cab509, 0x00cab408, 0x00cab509, 0x00cbb509, 0x00cbb50a, 0x00cbb50c, 0x00cbb50c, 0x00cbb50b, 0x00ccb40c, 0x00ccab0d, 0x00cba00c, 0x00c8980e, 0x00c99a14, 0x00cba315, 0x00bd8d12, 0x00a36f0e, 0x00855408, 0x00684108, 0x0057390a, 0x004a320a, 0x00472c0e, 0x0042280d, 0x003c260c, 0x00322007, 0x00291802, 0x00261b08, 0x00201908, 0x00191404, 0x00181206, 0x00141307, 0x00121108, 0x00100f08, 0x000d0f08, 0x000d0f07, 0x00101007, 0x00101005, 0x000f1108, 0x0012140e, 0x0010140f, 0x0010140f, 0x00111611, 0x00121712, 0x00131914, 0x00141a14, 0x00141a14, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x0014180f, 0x000f130b, 0x0014180d, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180b, 0x0014180c, 0x000f130b, 0x000f130b, 0x000f130c, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00191d18, 0x00191d18, 0x00191d1a, 0x00181e18, 0x00181e18, 0x00181f17, 0x00171d18, 0x0019201a, 0x001b211a, 0x00141a13, 0x000f120c, 0x0010110c, 0x0011110b, 0x0014110a, 0x00161208, 0x001c170c, 0x0020190c, 0x00231809, 0x00281b0a, 0x0032230f, 0x0038260f, 0x00422e0c, 0x004c350c, 0x005b3f0c, 0x00724f14, 0x00906c17, 0x00c0a129, 0x00cbb41a, 0x00c9bc0e, 0x00cac110, 0x00cbc113, 0x00cbbf11, 0x00cbbc09, 0x00cbbb06, 0x00cabc09, 0x00c9bb09, 0x00c9bb07, 0x00cabb04, 0x00cbba04, 0x00ccb907, 0x00ccb80c, 0x00ccb40d, 0x00ccb110, 0x00caa910, 0x00c49f12, 0x00b8900c, 0x00a97a03, 0x009c6a00, 0x00925f00, 0x00855200, 0x007c4a00, 0x00774800, 0x00704400, 0x006b4000, 0x00643e02, 0x00593803, 0x00533502, 0x00503706, 0x004d3609, 0x0048330e, 0x0044300c, 0x00412f0a, 0x0040300a, 0x003e2c08, 0x003c2a05, 0x003d2808, 0x003d2808, 0x003d2808, 0x003e2909, 0x0040280a, 0x0041290b, 0x00402b0a, 0x00412b09, 0x00422b08, 0x00432a08, 0x00422a08, 0x00422a08, 0x00442b08, 0x00442b08, 0x00472c0a, 0x00482b0a, 0x00482b0c, 0x00482a0c, 0x00482a0c, 0x00472a09, 0x00452808, 0x00432509, 0x0040250c, 0x003c230b, 0x003a230a, 0x00382008, 0x00351e05, 0x00341d05, 0x00341d07, 0x00331c08, 0x00311c08, 0x00311c08, 0x00301c08, 0x00301c08, 0x00301c09, 0x00311c08, 0x00301b07, 0x00301a06, 0x00311b07, 0x00321d09, 0x00301c09, 0x002e1c08, 0x002c1c07, 0x002b1a06, 0x002c1b07, 0x002d1a07, 0x002d1a07, 0x002c1b07, 0x002a1906, 0x002a1907, 0x00281808, 0x00281809, 0x0028180b, 0x0027180a, 0x00241709, 0x00241608, 0x00231708, 0x00231708, 0x00231708, 0x00221608, 0x00221508, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1409, 0x001f1409, 0x001f1409, 0x001f1409, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001a1508, 0x001a1508, 0x00191408, 0x00181205, 0x00151204, 0x00151405, 0x00171305, 0x00181306, 0x00181306, 0x001b1407, 0x001b1407, 0x00191306, 0x00191306, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x001b1206, 0x001b1205, 0x001b1204, 0x001b1204, 0x001a1207, 0x00191208, 0x00191307, 0x00191306, 0x001c1206, 0x001d1207, 0x001d1207, 0x001d1205, 0x00201508, 0x001a1105, 0x001c1307, 0x001c1408, 0x001c1408, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1207, 0x001d1207, 0x001e1308, 0x001e1308, 0x001f140a, 0x001e130a, 0x001d1208, 0x001d1208, 0x001d130a, 0x001c140a, 0x001c1309, 0x001c1309, 0x001d1309, 0x001f1208, 0x001f1208, 0x00201409, 0x0020140a, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00221408, 0x00221408, 0x00231409, 0x0022160a, 0x0024150b, 0x00241509, 0x00251709, 0x00251708, 0x00261707, 0x00261607, 0x00271708, 0x00281708, 0x00281708, 0x00281708, 0x00281808, 0x00281809, 0x00281808, 0x002a1908, 0x002c1b09, 0x002f1c0a, 0x002f1c0a, 0x002d1c0a, 0x002f1c0b, 0x00321d09, 0x00341e08, 0x00372007, 0x003f250c, 0x0042270b, 0x00472a0b, 0x004a310a, 0x00503403, 0x005e3b00, 0x00754b06, 0x00845805, 0x00966a08, 0x00b08514, 0x00c49a14, 0x00cba814, 0x00cbb212, 0x00ccb411, 0x00ccb60e, 0x00ccb70c, 0x00ccb80b, 0x00cbb80b, 0x00cab80b, 0x00cab80b, 0x00cbb80a, 0x00cab409, 0x00cbb40b, 0x00ccb30c, 0x00cca810, 0x00bd8d08, 0x00aa7401, 0x009d6000, 0x00a16104, 0x00a16202, 0x00b47810, 0x00bc8910, 0x00c49511, 0x00c89f11, 0x00cca615, 0x00cca912, 0x00ccae13, 0x00ccb014, 0x00caaf0e, 0x00cab30c, 0x00cbb50a, 0x00cbb608, 0x00cbb608, 0x00cab608, 0x00c8b708, 0x00c8b708, 0x00c8b806, 0x00c9b707, 0x00c9b608, 0x00cbb509, 0x00cbb50a, 0x00cbb50c, 0x00cbb50c, 0x00cab50c, 0x00c9b50d, 0x00c9b60c, 0x00c9b60a, 0x00cbb508, 0x00ccac08, 0x00c8a108, 0x00c49c07, 0x00c8a80d, 0x00ccb416, 0x00caab18, 0x00be9318, 0x00a36e0c, 0x00875107, 0x006d4207, 0x00583809, 0x004c3007, 0x00432b08, 0x003f2a0b, 0x0038250b, 0x002f1d06, 0x00281805, 0x0027190a, 0x00201708, 0x00181305, 0x00161306, 0x00141008, 0x0014130c, 0x0010100b, 0x000e0e07, 0x00111008, 0x00101006, 0x0013120a, 0x0012140e, 0x000f140e, 0x00101610, 0x00101711, 0x000f1812, 0x00111914, 0x00121a15, 0x00131b16, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130e, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e1a, 0x00181e18, 0x00181e18, 0x00181f17, 0x00181f17, 0x001a2018, 0x001b2119, 0x00141a13, 0x0010110c, 0x0010100b, 0x0011110b, 0x0015130a, 0x00181209, 0x001e180c, 0x0021180a, 0x00241907, 0x002d200c, 0x00352710, 0x003c2911, 0x0046320d, 0x0053390d, 0x006a4812, 0x007f5a17, 0x00a58423, 0x00c9ad2c, 0x00ccb718, 0x00cbbd0e, 0x00cbc110, 0x00cbc111, 0x00ccc011, 0x00cbbd0b, 0x00cabc06, 0x00c9bc06, 0x00c8bb06, 0x00c8b805, 0x00c9b705, 0x00cab607, 0x00cbb40c, 0x00c8ab0c, 0x00c4a00a, 0x00bb8b07, 0x00ae7d04, 0x009c6d01, 0x008c5d00, 0x00835400, 0x00784c00, 0x006e4400, 0x00643d01, 0x00613c01, 0x005d3a01, 0x00583800, 0x00543400, 0x004f3303, 0x004f3309, 0x004c320a, 0x0049310c, 0x0046300e, 0x00412c0c, 0x003c2a09, 0x003b2807, 0x003a2807, 0x003a2707, 0x00382606, 0x00372405, 0x00362305, 0x00382307, 0x00382408, 0x00392409, 0x00392508, 0x00392709, 0x00392708, 0x00382606, 0x00372404, 0x00382406, 0x00382408, 0x003b2409, 0x003b240a, 0x00402509, 0x00412609, 0x0043270b, 0x0043260c, 0x0042250a, 0x00402406, 0x003f2306, 0x003c2108, 0x003a2108, 0x00371f08, 0x00351f08, 0x00331d06, 0x00321c05, 0x00301c05, 0x00301c06, 0x002f1a08, 0x002f1a09, 0x002e1a0a, 0x002e1b0a, 0x002e1b0a, 0x002e1b0a, 0x002e1b09, 0x002f1a08, 0x002e1908, 0x002e1907, 0x002f1b08, 0x002e1b0a, 0x002c1c0a, 0x00281a08, 0x00271908, 0x00281808, 0x00291808, 0x00291808, 0x00281807, 0x00281807, 0x00271808, 0x00251808, 0x00251709, 0x0024180a, 0x0024180b, 0x0024170b, 0x0023160a, 0x0023160a, 0x00231708, 0x00231708, 0x00221608, 0x00221608, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1409, 0x001f1409, 0x001f1409, 0x001f1409, 0x001e1407, 0x001e1407, 0x001d1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001b1407, 0x00181306, 0x00171305, 0x00181205, 0x00191306, 0x001a1306, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x001b1205, 0x001b1204, 0x001b1204, 0x001b1204, 0x001a1207, 0x00191208, 0x00191307, 0x00191306, 0x001c1206, 0x001d1207, 0x001d1207, 0x001d1205, 0x00201508, 0x001a1105, 0x001c1307, 0x001c1408, 0x001c1408, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1409, 0x001e1308, 0x001d1207, 0x001d1207, 0x001c1408, 0x001c1408, 0x001e1409, 0x001e1409, 0x001e1409, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201508, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201508, 0x00201408, 0x00211408, 0x00221608, 0x00221608, 0x00241508, 0x00241409, 0x0024150a, 0x0024160a, 0x0024160a, 0x0024160a, 0x0024160a, 0x0025170a, 0x00261608, 0x00281806, 0x00281807, 0x002b1908, 0x002c1b09, 0x002c1b09, 0x002d1c08, 0x00301c08, 0x00331d08, 0x00351d05, 0x00381f06, 0x003d2208, 0x0043290c, 0x00442e0c, 0x0048320a, 0x00503404, 0x005c3801, 0x006d4404, 0x007b4f01, 0x00895c00, 0x009d6d03, 0x00b0840c, 0x00bc9411, 0x00c7a015, 0x00cba814, 0x00ccad13, 0x00ccb00c, 0x00ccb00b, 0x00ccb00c, 0x00ccb10c, 0x00ccb00f, 0x00ccad0f, 0x00caa811, 0x00c49c0c, 0x00b78405, 0x00a87001, 0x009e6200, 0x00a96a0a, 0x00b57514, 0x00b0700c, 0x00ac6f05, 0x00a96d00, 0x00ac7200, 0x00b27a03, 0x00b98208, 0x00be890a, 0x00c59410, 0x00c39c10, 0x00c9a514, 0x00ccac14, 0x00ccb013, 0x00ccb40c, 0x00ccb40a, 0x00cbb508, 0x00cab608, 0x00cab707, 0x00cbb606, 0x00cbb607, 0x00cbb608, 0x00ccb409, 0x00ccb40b, 0x00ccb40c, 0x00cbb40d, 0x00cbb40d, 0x00cbb40d, 0x00cbb50c, 0x00c9b60a, 0x00cab508, 0x00ccae08, 0x00c8a309, 0x00c7a009, 0x00caac0f, 0x00cbb812, 0x00ccb514, 0x00cbad1d, 0x00bc8f14, 0x009c6a0c, 0x007f5208, 0x00644006, 0x00513303, 0x004a3008, 0x00402b0b, 0x003c280c, 0x00332108, 0x002a1a05, 0x00281908, 0x00241b09, 0x00191404, 0x00161304, 0x00151208, 0x00121109, 0x0011130b, 0x00101009, 0x00110f07, 0x00101006, 0x00101008, 0x0010120c, 0x000f140e, 0x00101610, 0x000f1811, 0x000f1912, 0x00101914, 0x00121a15, 0x00131b16, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e1a, 0x00181e1a, 0x00181e1a, 0x00181e18, 0x00181e18, 0x00182018, 0x00181f17, 0x001a2018, 0x001a1f18, 0x00141811, 0x0012140e, 0x0011110c, 0x0013100c, 0x00151209, 0x0019140a, 0x001e170b, 0x00221909, 0x00261a08, 0x0031220d, 0x00382710, 0x003e2b11, 0x004a330e, 0x00583c0d, 0x006f4c0e, 0x008a6417, 0x00b69628, 0x00c9b024, 0x00ccb814, 0x00cabc0d, 0x00c8be0d, 0x00c8c00c, 0x00cbc00e, 0x00ccc010, 0x00c8b60a, 0x00c8b309, 0x00c8af09, 0x00ccad0e, 0x00ccac11, 0x00caa815, 0x00c09c12, 0x00b08809, 0x00a17400, 0x00946000, 0x00885500, 0x00794c00, 0x00714800, 0x006a4403, 0x00603c02, 0x00583804, 0x00543708, 0x00513509, 0x004e3307, 0x004c3309, 0x004a330b, 0x0046320c, 0x0046300e, 0x00442c0d, 0x0042290e, 0x00402a0e, 0x003e290c, 0x003a2809, 0x00392608, 0x00372407, 0x00372407, 0x00362407, 0x00342107, 0x00342108, 0x00342007, 0x00342007, 0x00342107, 0x00342208, 0x00342208, 0x00322306, 0x00332206, 0x00342304, 0x00342204, 0x00342204, 0x00352204, 0x00372205, 0x00392307, 0x003c2308, 0x003c2408, 0x003c220b, 0x003c230a, 0x003b2307, 0x00382005, 0x00382008, 0x00372009, 0x00331d08, 0x00311d08, 0x00301c08, 0x002f1b06, 0x002d1c06, 0x002d1b08, 0x002c1a08, 0x002c180a, 0x002c180b, 0x002c180b, 0x002c180b, 0x002c180b, 0x002c180a, 0x002c1909, 0x002c1909, 0x002a1808, 0x002b1809, 0x00271708, 0x00261808, 0x00261a0a, 0x00271a0b, 0x0027180a, 0x0028180a, 0x00281809, 0x00271809, 0x00251808, 0x00251808, 0x00231709, 0x0023160a, 0x0023160c, 0x0023160c, 0x0023160c, 0x0023160b, 0x0023160a, 0x00221509, 0x00221608, 0x00211507, 0x00211507, 0x00221509, 0x00201408, 0x00201307, 0x00201307, 0x001f1409, 0x001f1409, 0x001f1409, 0x001f1409, 0x00201307, 0x00201307, 0x001e1407, 0x001d1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x00191306, 0x00181306, 0x00191306, 0x001c1307, 0x001c1307, 0x001d1207, 0x001d1207, 0x001e1308, 0x001c1206, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001b1204, 0x001b1204, 0x001b1204, 0x001b1204, 0x001b1308, 0x001b1309, 0x001a1308, 0x00191306, 0x001c1206, 0x001d1207, 0x001d1207, 0x001d1205, 0x00201508, 0x001b1206, 0x001c1307, 0x001e1409, 0x001e1409, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1409, 0x001e1308, 0x001d1207, 0x001d1207, 0x001c140a, 0x001c140a, 0x001c1309, 0x001c1208, 0x001c1209, 0x001e130a, 0x001e130a, 0x001e130a, 0x001e130a, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x00201409, 0x001f1409, 0x001e1409, 0x001d1409, 0x001e1407, 0x001e1407, 0x00201508, 0x00201508, 0x00211507, 0x00211506, 0x00211506, 0x00211506, 0x00211507, 0x00221607, 0x00221607, 0x00221607, 0x00241607, 0x00241607, 0x00251608, 0x00281709, 0x0028180a, 0x0028180a, 0x00291809, 0x002f1b0b, 0x00321d0b, 0x00341e0a, 0x00351d08, 0x00392009, 0x003e250c, 0x00402a0d, 0x00442c0d, 0x004a300a, 0x00503306, 0x005b3705, 0x00693f06, 0x007c4e08, 0x00885404, 0x00956004, 0x00a46e04, 0x00ad7807, 0x00b48008, 0x00bb8b08, 0x00c09206, 0x00c59a0c, 0x00c69a0c, 0x00c59b0c, 0x00c1980c, 0x00bb8f08, 0x00b58506, 0x00a77200, 0x00a16800, 0x00a66a06, 0x00b07510, 0x00c0891b, 0x00cb9b21, 0x00ca981b, 0x00c59114, 0x00bd880c, 0x00b57e05, 0x00af7501, 0x00ac7001, 0x00a96b00, 0x00a46800, 0x00a46f02, 0x00ae7c07, 0x00b6880d, 0x00c59b18, 0x00caa714, 0x00ccab14, 0x00cbac10, 0x00cbb00f, 0x00cbb10c, 0x00ccb30b, 0x00ccb30a, 0x00ccb40b, 0x00ccb40c, 0x00ccb40d, 0x00ccb40d, 0x00cbb40d, 0x00cbb40d, 0x00cbb40d, 0x00cab40b, 0x00c8b509, 0x00cab408, 0x00ccac08, 0x00c8a308, 0x00c9a30c, 0x00ccaf11, 0x00cab911, 0x00cbb90f, 0x00ccb814, 0x00c8aa13, 0x00a88007, 0x00895e00, 0x00734a04, 0x005c3a02, 0x004f3107, 0x00452c09, 0x0040290a, 0x003a250c, 0x002e1c05, 0x00261704, 0x00261b08, 0x001f1808, 0x00181404, 0x00161208, 0x00100e07, 0x0010120a, 0x00121108, 0x00101008, 0x00101006, 0x00101008, 0x0010110c, 0x000f140e, 0x00101510, 0x000f1611, 0x000e1813, 0x00101815, 0x00111816, 0x00121917, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e1a, 0x00181e1a, 0x00181e1a, 0x00181e18, 0x00181e18, 0x00182018, 0x00182018, 0x001a2018, 0x00191e17, 0x0010140d, 0x0010110c, 0x0012110c, 0x0013100b, 0x00161109, 0x0019140a, 0x0020180c, 0x00221808, 0x00271a07, 0x0031220a, 0x0039270f, 0x00402c10, 0x004d340e, 0x005c3d0d, 0x00704c08, 0x00986f1c, 0x00c4a72e, 0x00cab41e, 0x00ccba10, 0x00cabd0c, 0x00c8bd0d, 0x00c8bf09, 0x00cbbf0a, 0x00ccbc10, 0x00c5ac0d, 0x00bf9d08, 0x00bb9305, 0x00bc8c08, 0x00b88408, 0x00b37e0d, 0x00a07008, 0x008a5c00, 0x007c5000, 0x006f4500, 0x00684200, 0x005f3c00, 0x00593a00, 0x00573801, 0x00543605, 0x00513407, 0x004f3108, 0x004e3109, 0x004b300a, 0x00482f0c, 0x00442e0c, 0x00402c09, 0x003e2a09, 0x003e2708, 0x003d2409, 0x003c240a, 0x00392409, 0x00362407, 0x00342107, 0x00321e04, 0x00321e04, 0x00311d04, 0x002f1d05, 0x002f1c05, 0x00301d06, 0x00301d06, 0x00301d06, 0x00301d06, 0x00301d06, 0x00311d04, 0x00311d04, 0x00321c04, 0x00311d04, 0x00301e05, 0x00301e06, 0x00321e06, 0x00331e06, 0x00321e04, 0x00321d06, 0x00341d08, 0x00341e08, 0x00352006, 0x00341f05, 0x00341e08, 0x00331d09, 0x002f1b08, 0x002d1b08, 0x002c1c08, 0x002c1c08, 0x002c1b08, 0x002a1b0a, 0x00291809, 0x0028170a, 0x0028170b, 0x0028170b, 0x0028170b, 0x0028170b, 0x0028170a, 0x00281709, 0x00281709, 0x00281809, 0x0029190b, 0x00251709, 0x00241809, 0x00231809, 0x00231809, 0x00231708, 0x00241608, 0x00251709, 0x00241608, 0x00231708, 0x0023160a, 0x0020150a, 0x0020150a, 0x0020140b, 0x0021140c, 0x0021140c, 0x0021140c, 0x0021140a, 0x00221608, 0x00221608, 0x00211507, 0x00211507, 0x00221509, 0x00201408, 0x00201307, 0x00201307, 0x001f1409, 0x001f1409, 0x001f1409, 0x001f1409, 0x00201307, 0x00201307, 0x001e1407, 0x001d1407, 0x001d1308, 0x001e1308, 0x001e1308, 0x001d1308, 0x001a1206, 0x00181306, 0x001a1306, 0x001c1307, 0x001c1307, 0x001d1207, 0x001d1207, 0x001e1308, 0x001c1106, 0x001a1204, 0x00191304, 0x00191304, 0x00191304, 0x001b1204, 0x001b1204, 0x001b1204, 0x001b1204, 0x001b1308, 0x001b1309, 0x001a1307, 0x00191306, 0x001c1206, 0x001d1207, 0x001d1207, 0x001d1205, 0x00201508, 0x001b1206, 0x001c1307, 0x001e1409, 0x001e1409, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1304, 0x001d1304, 0x001e1405, 0x001e1406, 0x001f1408, 0x001d1205, 0x001d1205, 0x001d1205, 0x001c1409, 0x001c140a, 0x001c1309, 0x001c1208, 0x001c1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1508, 0x001d1508, 0x001c1508, 0x001c1405, 0x001c1405, 0x001f1608, 0x001f150a, 0x00201508, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00221608, 0x00221608, 0x00241608, 0x00241608, 0x00251709, 0x00251709, 0x00261808, 0x002b1809, 0x00301c0a, 0x00321c09, 0x00331c08, 0x00381f09, 0x003d240c, 0x0040280c, 0x00442a0d, 0x004c300d, 0x0052340c, 0x0059380c, 0x00613a08, 0x0073460c, 0x0084500d, 0x00a36a1b, 0x00b47817, 0x00ae730c, 0x00a86e04, 0x00a86e00, 0x00a66c00, 0x00a86d00, 0x00aa7000, 0x00a97000, 0x00a56e00, 0x00a46c00, 0x00a66c00, 0x00aa6c00, 0x00ac730c, 0x00bc871f, 0x00c69722, 0x00cca51d, 0x00ccae16, 0x00ccb013, 0x00ccb015, 0x00ccac15, 0x00cca515, 0x00c99c14, 0x00c38f16, 0x00ad730b, 0x009a5b00, 0x00975704, 0x00945600, 0x00975d00, 0x00a06c05, 0x00ad7e09, 0x00bb8e13, 0x00c09816, 0x00c7a318, 0x00caac13, 0x00ccb014, 0x00ccb113, 0x00ccb212, 0x00ccb211, 0x00ccb310, 0x00ccb40e, 0x00cbb40d, 0x00cbb40d, 0x00cbb40d, 0x00cab40b, 0x00c8b408, 0x00c9b407, 0x00cbac07, 0x00c8a208, 0x00c9a30c, 0x00cbb012, 0x00cab913, 0x00c9bb0e, 0x00cbb90d, 0x00c9b50f, 0x00b9980c, 0x00986e00, 0x00805403, 0x00684103, 0x00543407, 0x004a2f09, 0x00432a0a, 0x003d270c, 0x00321f07, 0x00281804, 0x00251906, 0x00231b0a, 0x001a1506, 0x00181408, 0x00111009, 0x00101208, 0x00121108, 0x0011110a, 0x00101007, 0x00101008, 0x0010110c, 0x0010130e, 0x00101510, 0x00101511, 0x000e1813, 0x00101816, 0x00121918, 0x00121918, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x000f130f, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e18, 0x00182019, 0x00182019, 0x0019201a, 0x001b2018, 0x001c1f18, 0x00181a14, 0x0011130c, 0x0012110b, 0x0013120b, 0x0014110a, 0x00161108, 0x001b1309, 0x0020170b, 0x00231808, 0x002c1e0a, 0x0034240a, 0x003a280c, 0x00412c0c, 0x004e360e, 0x005c3e0e, 0x00744d0f, 0x00a27b21, 0x00c9ad2c, 0x00cbb818, 0x00ccbc0c, 0x00cabd0b, 0x00cabd0d, 0x00c9bc0a, 0x00cbbc0c, 0x00cab411, 0x00b8940c, 0x00a47503, 0x009f6b01, 0x00945d00, 0x008f5800, 0x00855600, 0x00795000, 0x006c4700, 0x00603f01, 0x005b3a05, 0x00583907, 0x00543806, 0x004e3405, 0x004d3507, 0x004b3407, 0x004c340b, 0x0048300b, 0x00442b08, 0x00442a0a, 0x0040270b, 0x003c2508, 0x003a2407, 0x00382408, 0x00382308, 0x00372008, 0x00351e08, 0x00331f08, 0x00331f08, 0x00331f08, 0x00311c06, 0x00311c08, 0x00301d08, 0x002d1c07, 0x002b1b06, 0x002c1b07, 0x002c1c08, 0x002c1c08, 0x002c1c08, 0x002e1b08, 0x002e1b08, 0x002d1b06, 0x002c1a05, 0x002c1a05, 0x002c1906, 0x002b1804, 0x002e1c06, 0x002f1c07, 0x00301d08, 0x00301d08, 0x00301c07, 0x00301c05, 0x002f1c04, 0x002e1904, 0x00301c08, 0x002f1c08, 0x002d1a09, 0x002c190a, 0x002c190a, 0x002b180a, 0x0028180c, 0x0028180c, 0x00261609, 0x0025150a, 0x0027150a, 0x0028150b, 0x0028150b, 0x0027160b, 0x0025170a, 0x00241608, 0x00241608, 0x00241608, 0x00241608, 0x0026180c, 0x0026180c, 0x0024170a, 0x00231409, 0x00221509, 0x00221509, 0x00221509, 0x0023160a, 0x0023160a, 0x0023160a, 0x00211408, 0x00201409, 0x00201409, 0x0020150a, 0x0020150a, 0x0020150a, 0x00201508, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00211408, 0x00201408, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201307, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001e1306, 0x001f1408, 0x001c1205, 0x001c1305, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1409, 0x001c1106, 0x001b1005, 0x001c1106, 0x001d1208, 0x001e1308, 0x001e1308, 0x001c1408, 0x001d1408, 0x001f1307, 0x001e1407, 0x001e1407, 0x001e1508, 0x001b1206, 0x001c1307, 0x0020150a, 0x001e1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001d1205, 0x001c1204, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1306, 0x001c1307, 0x001c1408, 0x001e1308, 0x001e1308, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001c1305, 0x001c1305, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1306, 0x001e1407, 0x001f1407, 0x00221509, 0x0024170b, 0x0024160a, 0x0024160a, 0x0024160a, 0x00241608, 0x00281809, 0x002b1b08, 0x002e1b08, 0x00311c08, 0x00341c08, 0x003a2108, 0x003f2608, 0x0040280b, 0x00462b0b, 0x004c3008, 0x00543505, 0x00643f0b, 0x00754a10, 0x008a5910, 0x00b88729, 0x00cb9e2a, 0x00cb9e20, 0x00c89918, 0x00c29117, 0x00b58211, 0x00b37f0a, 0x00b17c08, 0x00b17b0b, 0x00b17c0c, 0x00b27c0b, 0x00b7820d, 0x00c6921b, 0x00c89f1e, 0x00c9a81f, 0x00ccac1b, 0x00ccb014, 0x00ccb30e, 0x00ccb409, 0x00ccb409, 0x00cab40b, 0x00cbb410, 0x00ccb214, 0x00cca91a, 0x00b88913, 0x00945b00, 0x008b5107, 0x007f4800, 0x007d4902, 0x00804f01, 0x00875703, 0x00905f02, 0x009c6c05, 0x00a8780b, 0x00b4870c, 0x00c19515, 0x00c89e18, 0x00caa418, 0x00cba714, 0x00ccac13, 0x00ccaf10, 0x00ccb30f, 0x00ccb60f, 0x00cbb40c, 0x00cab40b, 0x00cab409, 0x00cab308, 0x00caab0c, 0x00c9a00b, 0x00c8a30f, 0x00cbb114, 0x00c9ba12, 0x00c8bb0b, 0x00c8bb07, 0x00c8ba0a, 0x00c9ad15, 0x00a67c04, 0x008a5c04, 0x00754c08, 0x005c3b03, 0x00503305, 0x00462c08, 0x003e270a, 0x00362309, 0x002b1c04, 0x00251804, 0x00221a09, 0x001a1506, 0x00181407, 0x00141407, 0x00121108, 0x00101108, 0x00101009, 0x000f1008, 0x0010120a, 0x0011120c, 0x0010130e, 0x00101411, 0x000f1411, 0x000d1712, 0x000f1816, 0x00101818, 0x00121918, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e18, 0x00182019, 0x00182019, 0x0019201a, 0x001c1f18, 0x001d1e18, 0x00181a14, 0x0010120c, 0x0012120c, 0x0014120c, 0x0014110b, 0x00181108, 0x001d160c, 0x0020160b, 0x00231707, 0x002e200a, 0x0037260a, 0x003c290d, 0x00442e0a, 0x0051390e, 0x00604010, 0x007e5817, 0x00af8828, 0x00cbb028, 0x00ccb918, 0x00ccbc0c, 0x00cbbe0b, 0x00cbbc0c, 0x00ccbb0c, 0x00ccb710, 0x00ba9b06, 0x009c7400, 0x00885802, 0x00835200, 0x007f4c04, 0x00784802, 0x006c4400, 0x00603e00, 0x005b3c02, 0x00543804, 0x00533607, 0x00503408, 0x004c3408, 0x00483006, 0x00452f06, 0x00412c04, 0x00432e08, 0x00402906, 0x003c2706, 0x003c2608, 0x003b2408, 0x00382108, 0x00342006, 0x00341f06, 0x00331f08, 0x00331d08, 0x00321d09, 0x00301d08, 0x00301d08, 0x002e1c06, 0x002c1904, 0x002c1906, 0x002c1a06, 0x002a1a06, 0x00281905, 0x00291808, 0x002b1909, 0x002b1909, 0x002b1909, 0x002c1808, 0x002c1808, 0x002a1807, 0x00291807, 0x00291806, 0x00281804, 0x00281603, 0x002a1806, 0x002c1a08, 0x002c1a08, 0x002c1a08, 0x002e1b08, 0x002f1c07, 0x002e1c04, 0x002c1904, 0x002c1a07, 0x002c1a08, 0x002c1808, 0x002c1809, 0x002c190c, 0x002b170c, 0x0028150b, 0x0027160b, 0x0025150a, 0x0025150a, 0x0027150b, 0x0028150b, 0x0027160b, 0x0025170b, 0x0024180a, 0x00231708, 0x00231708, 0x00231708, 0x00231708, 0x0024160a, 0x0024160a, 0x0025170b, 0x00231409, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00211408, 0x00211408, 0x00201508, 0x001f1608, 0x001f1608, 0x001f1608, 0x00201508, 0x00201408, 0x00211408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001e1407, 0x001d1407, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1308, 0x001d1207, 0x001d1207, 0x001d1207, 0x001f1208, 0x001f1308, 0x001e1308, 0x001d1308, 0x001f1308, 0x00201307, 0x001e1407, 0x001e1407, 0x001e1508, 0x001b1206, 0x001c1307, 0x001f1409, 0x0020150a, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1406, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1306, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x00201408, 0x00221509, 0x0024160a, 0x0024160a, 0x0024160a, 0x00241608, 0x00261708, 0x002a1a09, 0x002c1906, 0x00311c08, 0x00341c07, 0x00381f08, 0x003b2307, 0x003f2609, 0x00452a0c, 0x004b3008, 0x00533303, 0x00603c08, 0x0072480e, 0x00906314, 0x00c49b2e, 0x00ccaf22, 0x00ccb015, 0x00ccb011, 0x00ccac18, 0x00cba91e, 0x00caa718, 0x00caa517, 0x00caa419, 0x00cba51c, 0x00cba619, 0x00cba818, 0x00ccaa1a, 0x00ccad17, 0x00cbb016, 0x00cbb211, 0x00cbb30d, 0x00cbb40c, 0x00cbb50a, 0x00c8b706, 0x00c7b607, 0x00c8b70b, 0x00cbb40e, 0x00cbab14, 0x00b3840a, 0x00915b00, 0x007c4b02, 0x00704000, 0x006c3e01, 0x006f4302, 0x00714501, 0x007a4d03, 0x00845504, 0x00895800, 0x00905c00, 0x00986402, 0x009d6901, 0x00ac780a, 0x00b7840e, 0x00c08f12, 0x00c69614, 0x00cba017, 0x00cba615, 0x00cba910, 0x00ccab10, 0x00ccac0e, 0x00ccac0c, 0x00c9a60a, 0x00c89c07, 0x00c9a30a, 0x00cab310, 0x00cab911, 0x00cabb09, 0x00c8bb05, 0x00c8bb09, 0x00cbb314, 0x00b48e0c, 0x00906201, 0x0081560b, 0x00644004, 0x00533402, 0x00482d05, 0x0040290a, 0x0038240b, 0x002c1d05, 0x00241602, 0x00221808, 0x00211a0c, 0x00171404, 0x00151405, 0x00121106, 0x00101108, 0x00101009, 0x000f1008, 0x00101009, 0x0010100a, 0x000f120d, 0x00101410, 0x000f1410, 0x000e1613, 0x000f1816, 0x00101818, 0x00121918, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e18, 0x00181f19, 0x0019201a, 0x001b211b, 0x001c2019, 0x001c1d17, 0x00161711, 0x0014140e, 0x0014120c, 0x0014120c, 0x0015120b, 0x001b140c, 0x0020160c, 0x0021160b, 0x00271b0b, 0x0031230b, 0x00372708, 0x003f2b0c, 0x0048330c, 0x00543c10, 0x0062440f, 0x00866118, 0x00b9942a, 0x00ccb222, 0x00cbb916, 0x00ccbc0f, 0x00ccbc0c, 0x00ccbb0c, 0x00cbb70e, 0x00c7a911, 0x00a27d00, 0x00885f00, 0x00784e00, 0x00724b01, 0x00694402, 0x00603d00, 0x00573b00, 0x00513801, 0x004f3707, 0x004c3408, 0x004c3208, 0x004c320a, 0x0048310b, 0x00432e08, 0x003f2c07, 0x003c2805, 0x003c2808, 0x003a2507, 0x00382305, 0x00382206, 0x00372108, 0x00342008, 0x00321d07, 0x00301d06, 0x00301d08, 0x002f1c08, 0x002d1b08, 0x002e1b08, 0x002e1b08, 0x002c1a07, 0x002b1805, 0x00291807, 0x00281807, 0x00281907, 0x00281a07, 0x00281808, 0x00281809, 0x0028180a, 0x0028180a, 0x00291808, 0x00291808, 0x00281707, 0x00271706, 0x00271706, 0x00241504, 0x00241403, 0x00251605, 0x00281809, 0x0029190b, 0x002b1909, 0x002b1908, 0x002c1a07, 0x002d1c06, 0x002b1a06, 0x002c1a08, 0x002a1808, 0x00291808, 0x00291808, 0x002b180b, 0x0028170b, 0x0025150a, 0x0024160a, 0x00241509, 0x00241409, 0x0025150a, 0x0025150a, 0x0024160a, 0x0023160a, 0x0023160a, 0x00231708, 0x00231708, 0x00231708, 0x00231708, 0x00241409, 0x00241409, 0x00231408, 0x00221408, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00201408, 0x00201408, 0x001f1608, 0x001f1608, 0x001f1608, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001d1306, 0x001e1407, 0x00201508, 0x00201508, 0x00201508, 0x001e1407, 0x001d1306, 0x001f1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001d1207, 0x001d1207, 0x001d1207, 0x001f1208, 0x001f1308, 0x001e1308, 0x001d1308, 0x001f1308, 0x00201307, 0x001e1407, 0x001e1407, 0x001e1508, 0x001b1206, 0x001c1307, 0x0020140a, 0x0020160b, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1306, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1306, 0x001b1407, 0x001c1308, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x00201307, 0x00221509, 0x00241409, 0x00241409, 0x0024160a, 0x00241608, 0x00271709, 0x00281808, 0x002c1808, 0x00301b08, 0x00341c08, 0x00381f08, 0x003b2208, 0x003e240a, 0x0044290d, 0x00492e0a, 0x00533307, 0x005f3809, 0x006d4409, 0x00916414, 0x00c7a02c, 0x00c9b418, 0x00cab70c, 0x00cab808, 0x00cab60f, 0x00cbb412, 0x00cbb40e, 0x00ccb50f, 0x00ccb412, 0x00ccb514, 0x00ccb512, 0x00ccb50e, 0x00cbb40c, 0x00cbb40e, 0x00cab40e, 0x00cab40d, 0x00c9b50c, 0x00c8b60c, 0x00c8b708, 0x00c7b704, 0x00c8b708, 0x00cbb50c, 0x00ccb413, 0x00caa614, 0x00a87804, 0x00885200, 0x00734600, 0x00643700, 0x00603601, 0x005c3500, 0x005c3801, 0x00613c04, 0x00694204, 0x00714707, 0x00784b08, 0x0082510c, 0x0088540a, 0x008d5708, 0x00935a06, 0x00986008, 0x00a2690c, 0x00a9720d, 0x00af7c0c, 0x00b98b0c, 0x00c29510, 0x00c89c12, 0x00cba010, 0x00c5980d, 0x00c7940c, 0x00c8a00c, 0x00ccb512, 0x00cbb910, 0x00cbba09, 0x00cabc06, 0x00c8bb0a, 0x00ccb412, 0x00c19e12, 0x009c7003, 0x00875908, 0x006e4808, 0x00563501, 0x00482d02, 0x00402908, 0x00392508, 0x00301f08, 0x00271703, 0x00211507, 0x00241b0d, 0x00181505, 0x00141405, 0x00131107, 0x00121108, 0x00101008, 0x00101108, 0x00101108, 0x00101009, 0x0010110c, 0x00111310, 0x000f1412, 0x000e1514, 0x000e1716, 0x00101817, 0x00101818, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181e18, 0x00181f19, 0x0019201a, 0x001b211a, 0x001f241c, 0x00181a14, 0x0014130c, 0x0014120c, 0x0014120c, 0x0014130a, 0x0018140c, 0x001d170d, 0x001f160b, 0x0020160b, 0x002b1d0d, 0x00322409, 0x00392808, 0x00422f0d, 0x004c380f, 0x00563d0e, 0x00684b11, 0x008d6919, 0x00c19e2b, 0x00cbb31c, 0x00cbba14, 0x00cabc0f, 0x00cbbc0b, 0x00cab90c, 0x00ccb410, 0x00b8970c, 0x00926600, 0x007f5304, 0x006e4a04, 0x00624201, 0x00583e03, 0x00503800, 0x004c3804, 0x00483504, 0x00483408, 0x00473008, 0x00482f0a, 0x00452c09, 0x00402b0a, 0x003c2808, 0x00382605, 0x00342304, 0x00342307, 0x00322006, 0x00301f05, 0x00301f04, 0x00311d08, 0x00301c08, 0x002e1c08, 0x002e1c08, 0x002c1c09, 0x002a1b0a, 0x002a1808, 0x002c1908, 0x002c1908, 0x00281805, 0x00281604, 0x00261605, 0x00251605, 0x00251705, 0x00241705, 0x00241604, 0x00241605, 0x00251706, 0x00261807, 0x00281809, 0x00281809, 0x00271708, 0x00251709, 0x00261709, 0x00231407, 0x00221406, 0x00221308, 0x00231408, 0x0025160a, 0x0028180b, 0x002b180b, 0x002b1909, 0x002a1b08, 0x00281806, 0x00281808, 0x00271708, 0x00281808, 0x00281809, 0x00261608, 0x0027160a, 0x0024160a, 0x0023160a, 0x00231509, 0x00221509, 0x0024150a, 0x0024160a, 0x0023160a, 0x0023160a, 0x0022170a, 0x00231708, 0x00231708, 0x00231708, 0x00231708, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00221509, 0x00201408, 0x001f1407, 0x001c1407, 0x001e1508, 0x001c1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1408, 0x001e1407, 0x001f1408, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001d1207, 0x001c1106, 0x001d1207, 0x001f1208, 0x001f1308, 0x001e1308, 0x001d1308, 0x001f1308, 0x00201307, 0x001e1407, 0x001e1407, 0x001e1508, 0x001b1206, 0x001c1307, 0x0020150a, 0x0020150a, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001c1306, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1306, 0x001b1407, 0x001c1307, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x00211409, 0x00221509, 0x00241409, 0x00241409, 0x0024160a, 0x00241608, 0x0028180b, 0x00291808, 0x002c1a08, 0x00301b08, 0x00321c08, 0x00361e08, 0x003b220a, 0x003f250e, 0x00442810, 0x00482c0b, 0x00523209, 0x005e380c, 0x0070460c, 0x00986c19, 0x00cba530, 0x00c9b417, 0x00cab70b, 0x00cab808, 0x00cab70d, 0x00c8b60c, 0x00c8b709, 0x00c9b80a, 0x00c9b80c, 0x00cab80d, 0x00cab80c, 0x00c9b809, 0x00c8b807, 0x00c8b708, 0x00c9b608, 0x00c9b608, 0x00c8b708, 0x00c8b806, 0x00c8b704, 0x00c9b404, 0x00cbb10b, 0x00cbad0f, 0x00cba80f, 0x00c0950e, 0x009d6902, 0x00854f04, 0x006c4401, 0x005b3400, 0x00583306, 0x00523004, 0x004c3006, 0x004e3307, 0x00503205, 0x00543304, 0x00593705, 0x005d3a04, 0x00673d04, 0x0074460a, 0x007b4a09, 0x00814e0b, 0x0088530c, 0x008d5608, 0x008f5806, 0x00925c03, 0x00986300, 0x009c6900, 0x00a87402, 0x00b07708, 0x00b57b07, 0x00c49812, 0x00ccb319, 0x00cbb811, 0x00cbba09, 0x00cabc06, 0x00c9bc0b, 0x00ccb810, 0x00caaa14, 0x00a87d05, 0x00885800, 0x00714a08, 0x00593a02, 0x004b3003, 0x00432c09, 0x003c280b, 0x0036230b, 0x002c1b06, 0x00221405, 0x0021180b, 0x001c1908, 0x00141405, 0x00141207, 0x00121107, 0x00101008, 0x00101108, 0x00101108, 0x00101009, 0x0010110c, 0x0011140f, 0x00101412, 0x000e1514, 0x000e1716, 0x000f1817, 0x00101818, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00181d18, 0x00182018, 0x00182018, 0x001a2018, 0x001d2119, 0x00161710, 0x0012120b, 0x0013120a, 0x0014120a, 0x0014130a, 0x0018150c, 0x001c170b, 0x001c1407, 0x00211907, 0x002c210b, 0x00322508, 0x003a2a06, 0x0043310d, 0x004c3a0e, 0x00583d0c, 0x00714f11, 0x0099731c, 0x00c8a62a, 0x00ccb518, 0x00caba11, 0x00c9bc0e, 0x00cbbc0b, 0x00ccb80b, 0x00c7ac0f, 0x00a78204, 0x00875b02, 0x00734b05, 0x00614204, 0x00573c03, 0x004f3907, 0x00483606, 0x00443408, 0x00423207, 0x00443008, 0x00432d08, 0x00422b08, 0x003f2808, 0x003a2507, 0x00362306, 0x00322104, 0x00312004, 0x002f1f03, 0x002e1e03, 0x002f1d06, 0x00301c09, 0x002e1c0a, 0x002c1b0a, 0x002b1a09, 0x00291908, 0x00281808, 0x00271808, 0x00271708, 0x00261605, 0x00261605, 0x00251504, 0x00241604, 0x00241507, 0x00241508, 0x00241508, 0x00241608, 0x00241608, 0x00241608, 0x00241608, 0x00251708, 0x00251608, 0x00261608, 0x0027160b, 0x0026160a, 0x00241609, 0x0023140a, 0x00201308, 0x001c1008, 0x0020140c, 0x0023140c, 0x0026150c, 0x0028180c, 0x0029180b, 0x00281708, 0x00281608, 0x00281709, 0x00251407, 0x00261608, 0x00261608, 0x00241408, 0x00251509, 0x00241509, 0x00241509, 0x00231409, 0x00231409, 0x00241409, 0x00231509, 0x00221609, 0x00211609, 0x00211609, 0x00201608, 0x00201608, 0x00211609, 0x00211609, 0x00211408, 0x00221408, 0x00211408, 0x00231509, 0x00211408, 0x00201408, 0x00211408, 0x00211408, 0x00201508, 0x00201508, 0x00201508, 0x00201408, 0x001e1306, 0x001d1306, 0x001d1306, 0x001d1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001d1205, 0x00201408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1307, 0x001e1306, 0x001e1306, 0x001d1205, 0x001e1306, 0x001e1306, 0x001e1306, 0x001e1306, 0x001d1306, 0x001d1306, 0x001f1406, 0x001f1407, 0x001d1304, 0x001d1304, 0x001d1208, 0x001e1308, 0x001d1208, 0x001d1208, 0x001f1208, 0x001f1308, 0x001e1308, 0x001e1409, 0x001e1408, 0x001e1406, 0x001e1406, 0x001d1407, 0x001c1407, 0x001c1306, 0x001c1307, 0x001f1409, 0x001f1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201407, 0x00201407, 0x001f1406, 0x001d1406, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1406, 0x001c1407, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1408, 0x001d1306, 0x001e1306, 0x001f1408, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001f1306, 0x001f1306, 0x00201307, 0x00201307, 0x001f1406, 0x001f1406, 0x001f1406, 0x001f1406, 0x001f1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00231409, 0x00231409, 0x00241409, 0x00241409, 0x0025150b, 0x0026160a, 0x0028180a, 0x00281809, 0x002b1908, 0x002f1b08, 0x00311b08, 0x00341c07, 0x0039210a, 0x003d250e, 0x00432810, 0x00482c0c, 0x0051320b, 0x005e390f, 0x006f470d, 0x009a6f1b, 0x00cba42f, 0x00cbb11b, 0x00ccb50e, 0x00ccb609, 0x00ccb50e, 0x00cbb50d, 0x00cbb608, 0x00cbb807, 0x00cbb709, 0x00cbb60c, 0x00cbb70b, 0x00cbb709, 0x00cab608, 0x00cab608, 0x00cbb708, 0x00cbb60a, 0x00cbb409, 0x00cbb208, 0x00ccaf08, 0x00cba80b, 0x00c6a00d, 0x00c0950f, 0x00b6860a, 0x00a57003, 0x008c5500, 0x007b4604, 0x00694004, 0x00593400, 0x00563206, 0x00503007, 0x004a3008, 0x004b3009, 0x004c3009, 0x004c2f0a, 0x004b2f06, 0x004b3003, 0x004f3000, 0x00523200, 0x00573500, 0x00603c03, 0x00664104, 0x006c4606, 0x0074480b, 0x00804c0f, 0x0083500c, 0x00845308, 0x00875604, 0x00915a02, 0x00a16607, 0x00bd8f18, 0x00cbb01c, 0x00ccb811, 0x00ccbb0a, 0x00cbbc08, 0x00cabc0b, 0x00ccb911, 0x00ccb016, 0x00b2880b, 0x008c5c00, 0x00744c04, 0x005c3c00, 0x004d3204, 0x00442f0b, 0x003d290c, 0x0038240b, 0x002e1e07, 0x00251806, 0x00201507, 0x001f1808, 0x00181306, 0x00141307, 0x00121207, 0x00111108, 0x00111108, 0x00101108, 0x000f1108, 0x000f110a, 0x000f110d, 0x000e120f, 0x000e1513, 0x000c1413, 0x000e1614, 0x00101815, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181e18, 0x00191d18, 0x00192018, 0x00192018, 0x001a2018, 0x001d2119, 0x0016170e, 0x00121209, 0x00131209, 0x00141309, 0x00151309, 0x0018160b, 0x001c160b, 0x001c1404, 0x00261e09, 0x00291f05, 0x00342608, 0x003c2c08, 0x0044320d, 0x004e3a0c, 0x005c400c, 0x00775111, 0x00a88026, 0x00ccae2c, 0x00ccb714, 0x00c8bb0e, 0x00c9bc0c, 0x00ccbc09, 0x00ccb70c, 0x00c0a10c, 0x009a7301, 0x00805503, 0x00694604, 0x00583c01, 0x004f3602, 0x00493406, 0x0046340a, 0x0041310a, 0x003f2e08, 0x003f2a07, 0x003d2605, 0x003c2404, 0x00392304, 0x00352004, 0x00332005, 0x00301f05, 0x00301e06, 0x002f1d05, 0x002d1c04, 0x002c1b07, 0x002c1b08, 0x002c1a09, 0x00291908, 0x00281808, 0x00261706, 0x00261706, 0x00241406, 0x00251607, 0x00241706, 0x00231605, 0x00211404, 0x00211404, 0x00211407, 0x00211408, 0x00231508, 0x00231508, 0x00231509, 0x00231509, 0x00231509, 0x0024160a, 0x00241609, 0x00241609, 0x0025150b, 0x0024140a, 0x0023140a, 0x0023150b, 0x0020140a, 0x001a1007, 0x001d140b, 0x0020140b, 0x0024140b, 0x0025150a, 0x00261508, 0x00271609, 0x00261508, 0x00261508, 0x00261508, 0x00251508, 0x00241608, 0x00241608, 0x00241608, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00231409, 0x00211509, 0x00201609, 0x00201709, 0x00201508, 0x00201508, 0x00201609, 0x00201609, 0x00201508, 0x00201508, 0x00201508, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1306, 0x001d1306, 0x001e1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1104, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1306, 0x001e1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001f1406, 0x001f1406, 0x001d1304, 0x001d1304, 0x001d1207, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1208, 0x001f1308, 0x001f1409, 0x001f1409, 0x001e1408, 0x001e1405, 0x001e1405, 0x001c1407, 0x001c1407, 0x001c1305, 0x001c1407, 0x001f1409, 0x001f1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201406, 0x00201406, 0x001f1406, 0x001e1506, 0x001d1507, 0x001c1508, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001d1205, 0x001d1306, 0x00201508, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x001f1406, 0x001f1406, 0x001f1406, 0x001f1406, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x00201508, 0x00221509, 0x00211408, 0x00201408, 0x00201408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x0025140c, 0x0027160b, 0x00271609, 0x0028180a, 0x002a1908, 0x002e1b08, 0x00311c0c, 0x00331c0b, 0x00361f08, 0x003c240c, 0x0042280f, 0x00482d0c, 0x0050330b, 0x005d3b0f, 0x0070490f, 0x009d741d, 0x00cba72f, 0x00cbb019, 0x00ccb60c, 0x00ccb707, 0x00ccb60b, 0x00cbb60c, 0x00ccb707, 0x00ccb804, 0x00ccb707, 0x00ccb508, 0x00ccb506, 0x00cbb406, 0x00cbb306, 0x00ccb10c, 0x00ccac0c, 0x00ccab10, 0x00caa40f, 0x00c4990c, 0x00bc8c08, 0x00b28004, 0x00a67300, 0x009c6500, 0x009c6000, 0x00945800, 0x00885204, 0x00784908, 0x00603801, 0x00583401, 0x00533104, 0x004d2e04, 0x00482c04, 0x00462c05, 0x00462a07, 0x00472c0a, 0x00482b09, 0x00482b05, 0x00482b03, 0x00482b01, 0x00482c00, 0x004c3003, 0x004f3302, 0x00523603, 0x00583806, 0x00613909, 0x00643c07, 0x00694108, 0x00704806, 0x007d4f03, 0x00925d08, 0x00be9220, 0x00ccb320, 0x00ccb811, 0x00ccbb0a, 0x00cbbc08, 0x00ccbc0c, 0x00ccbc11, 0x00ccb414, 0x00bc960f, 0x00936200, 0x007a4f05, 0x005f3e02, 0x00503404, 0x00442f09, 0x003e2b0b, 0x00392508, 0x002f1f06, 0x00251804, 0x001f1504, 0x00201808, 0x001b1408, 0x00151407, 0x00121207, 0x00121109, 0x00121109, 0x00101008, 0x000e1108, 0x000e1109, 0x000e110b, 0x000d110e, 0x000e1612, 0x000a1410, 0x000d1512, 0x000f1714, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181f19, 0x001a1e19, 0x001a2018, 0x001a2018, 0x001b2118, 0x001b1f14, 0x0013150c, 0x00111109, 0x00121109, 0x00131208, 0x00151308, 0x001a170c, 0x001c150a, 0x00201606, 0x00281f08, 0x002d2208, 0x0035270a, 0x003d2d09, 0x0046330c, 0x00503b0c, 0x0064450c, 0x007e5812, 0x00b48f2d, 0x00ccaf25, 0x00ccb813, 0x00c8bb0d, 0x00c9bc0c, 0x00ccbc09, 0x00ccb411, 0x00b9960d, 0x00916801, 0x00774e01, 0x00614301, 0x004f3800, 0x00483300, 0x00443104, 0x00433008, 0x003f2d08, 0x003c2a06, 0x003c2605, 0x003b2304, 0x00392004, 0x00351f04, 0x00341e08, 0x00311d08, 0x00301d08, 0x002e1c08, 0x002d1c08, 0x002c1a08, 0x002a1906, 0x00281806, 0x00281806, 0x00281808, 0x00281807, 0x00251708, 0x00251608, 0x00241507, 0x00241608, 0x00221708, 0x00211607, 0x00201506, 0x00201406, 0x00211509, 0x00201509, 0x00201509, 0x0021160a, 0x00201409, 0x00201409, 0x00201409, 0x00211509, 0x0023150a, 0x0024160b, 0x0024150b, 0x00211309, 0x00201309, 0x0021140c, 0x0020150b, 0x00191208, 0x00191208, 0x001c1308, 0x001e1408, 0x00201408, 0x00221306, 0x00241408, 0x00231408, 0x00241408, 0x00251509, 0x00241509, 0x00241509, 0x00241509, 0x00241509, 0x00241409, 0x00241409, 0x00231409, 0x00231409, 0x00231409, 0x00221409, 0x00211508, 0x00201508, 0x001f1608, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x00201408, 0x00201408, 0x00201408, 0x00201308, 0x00201408, 0x001f1408, 0x001f1408, 0x001e1408, 0x001e1407, 0x001e1407, 0x001e1306, 0x001e1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001d1306, 0x001e1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001f1306, 0x001e1306, 0x001d1306, 0x001d1305, 0x001d1305, 0x001d1306, 0x001d1306, 0x001e1306, 0x001d1306, 0x001f1406, 0x001f1406, 0x001d1304, 0x001d1304, 0x001d1207, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1208, 0x001f1308, 0x001f1409, 0x001f1409, 0x001e1408, 0x001e1405, 0x001e1405, 0x001c1407, 0x001c1407, 0x001c1305, 0x001c1407, 0x001f1409, 0x001f1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201406, 0x00201406, 0x001f1406, 0x001d1405, 0x001c1406, 0x001c1406, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1306, 0x001e1306, 0x001f1408, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201308, 0x00211408, 0x00211408, 0x00201507, 0x00201506, 0x00201506, 0x00201506, 0x00201508, 0x00201508, 0x00211609, 0x0022170a, 0x0023170a, 0x0023160a, 0x00221509, 0x00211408, 0x00211408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x0025140c, 0x0027160b, 0x0027160a, 0x0028180a, 0x002a1908, 0x002e1b09, 0x00311c0c, 0x00331c0b, 0x00341e08, 0x0039210b, 0x0042280e, 0x00482d0a, 0x0050340b, 0x005e3c0e, 0x00714b0d, 0x00a37a20, 0x00caa82b, 0x00cbb114, 0x00c9b608, 0x00c9b804, 0x00c9b80b, 0x00c9b80c, 0x00cab607, 0x00ccb508, 0x00ccb20a, 0x00ccb008, 0x00ccaf07, 0x00cbab08, 0x00c8a707, 0x00c49e0a, 0x00bf9208, 0x00b98404, 0x00b37800, 0x00a86b00, 0x00a16600, 0x009c6400, 0x009c6603, 0x00a56c0b, 0x00ae710d, 0x009e6405, 0x00845202, 0x00774d0c, 0x005c3802, 0x00523001, 0x004f2f05, 0x004a2c05, 0x00452a04, 0x00442906, 0x00422707, 0x00432709, 0x00432708, 0x00432607, 0x00432607, 0x00432607, 0x00432608, 0x00452907, 0x00482c07, 0x004b3009, 0x004e310b, 0x0050320a, 0x00533508, 0x00573a08, 0x005f4006, 0x006e4804, 0x00855509, 0x00bc9327, 0x00ccb525, 0x00ccb813, 0x00ccba0a, 0x00ccbc08, 0x00ccbc0c, 0x00ccbc0e, 0x00ccb80e, 0x00c2a20f, 0x00976b00, 0x007c5003, 0x00623f00, 0x00513402, 0x00453008, 0x003e2c09, 0x003a2506, 0x00302004, 0x00271902, 0x00201402, 0x00201607, 0x001c1609, 0x00171408, 0x00131108, 0x00111009, 0x00101009, 0x000f1008, 0x000d1008, 0x000d1008, 0x000e100b, 0x000e110e, 0x000e1512, 0x000a1410, 0x000d1512, 0x000f1714, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181f19, 0x001a1f19, 0x001b2018, 0x001b2018, 0x001c2118, 0x00181c11, 0x0010140a, 0x00101109, 0x00101009, 0x00121009, 0x00151308, 0x001b140c, 0x001b1107, 0x00241809, 0x002c1f09, 0x00302208, 0x003a280c, 0x00422e0b, 0x0049340e, 0x00543c0c, 0x006a480c, 0x00876014, 0x00bf9c34, 0x00cbb121, 0x00cbb812, 0x00c9bb0d, 0x00cabc0b, 0x00ccbb0a, 0x00ccb014, 0x00ac8408, 0x00895d03, 0x006e4800, 0x00583f00, 0x00473800, 0x00423200, 0x00402e02, 0x003c2b04, 0x00382804, 0x00352503, 0x00362202, 0x00372004, 0x00351d04, 0x00321c06, 0x00301c08, 0x002c1908, 0x002b1908, 0x002b1a0a, 0x002a1908, 0x00281806, 0x00281806, 0x00261805, 0x00261804, 0x00261804, 0x00241605, 0x00231508, 0x00231508, 0x00231508, 0x00221608, 0x00201608, 0x001f1407, 0x00201508, 0x00201508, 0x001f1409, 0x0020150a, 0x001f1409, 0x0020160b, 0x001f1409, 0x0020140a, 0x0020150a, 0x0020150a, 0x00201409, 0x0021140a, 0x0022150b, 0x00201409, 0x001f1108, 0x001f1208, 0x001c1409, 0x00191307, 0x00151205, 0x00181307, 0x001b1407, 0x001e1407, 0x00201305, 0x00221408, 0x00221408, 0x00211408, 0x00211408, 0x00221509, 0x00211509, 0x00211509, 0x00211509, 0x00241409, 0x00241409, 0x00231408, 0x00221408, 0x00221408, 0x00221408, 0x00201408, 0x00201508, 0x001f1508, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201408, 0x00201307, 0x00201307, 0x001f1307, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1306, 0x001e1306, 0x001e1306, 0x001e1407, 0x001e1407, 0x001f1406, 0x001f1406, 0x001d1304, 0x001d1304, 0x001d1207, 0x001d1207, 0x001e1308, 0x001e1308, 0x001f1208, 0x001f1308, 0x001f1409, 0x001f1409, 0x001e1408, 0x001e1405, 0x001e1405, 0x001c1407, 0x001c1407, 0x001c1305, 0x001c1407, 0x001f1409, 0x001f1409, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201406, 0x00201406, 0x001e1405, 0x001c1405, 0x001c1405, 0x001b1405, 0x001c1406, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x00201208, 0x00201208, 0x00201208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00201507, 0x00201507, 0x00201507, 0x00201507, 0x00201508, 0x00201508, 0x00201609, 0x0021170a, 0x0022160a, 0x00221509, 0x00211408, 0x00211408, 0x00211408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x0025140c, 0x0027160b, 0x0027160b, 0x0028180b, 0x002a180a, 0x002e1b09, 0x00311c0c, 0x00331c0b, 0x00341d08, 0x0039210b, 0x0041270e, 0x00482c0a, 0x00523409, 0x005e3c0c, 0x00734c0c, 0x00a88022, 0x00cba828, 0x00cbb113, 0x00cbb509, 0x00ccb70b, 0x00ccb712, 0x00cab410, 0x00cab10a, 0x00cbac0c, 0x00c9a40c, 0x00c89c0a, 0x00c49407, 0x00bb8b04, 0x00ae7d00, 0x00a87200, 0x00a56b00, 0x00a66800, 0x00a86802, 0x00ac6d0a, 0x00b17614, 0x00b38017, 0x00be8f20, 0x00c69824, 0x00ca9a26, 0x00b4801a, 0x00855402, 0x00744a0b, 0x00583603, 0x004d2e00, 0x004a2c04, 0x00442905, 0x00412805, 0x00402707, 0x003f2408, 0x003f2408, 0x003d2306, 0x003f2507, 0x00402609, 0x0040260c, 0x0040250c, 0x003f2508, 0x00412808, 0x00452c09, 0x00482f0c, 0x004a300c, 0x004a3108, 0x00503709, 0x00573c08, 0x0064440b, 0x007c520d, 0x00aa841f, 0x00c9b024, 0x00ccb611, 0x00ccb909, 0x00ccbc08, 0x00cbbc09, 0x00cabc0a, 0x00ccbb04, 0x00caae0e, 0x00a47c06, 0x007f5303, 0x00684201, 0x00553803, 0x00483308, 0x00412d08, 0x003c2604, 0x00332002, 0x002d1d04, 0x00231602, 0x001e1506, 0x001e170a, 0x00181409, 0x00141108, 0x0013100a, 0x0011100a, 0x000f1008, 0x000c1007, 0x000d1008, 0x000d100a, 0x000e120f, 0x000d1411, 0x000a1410, 0x000c1512, 0x000e1613, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181f19, 0x00191f19, 0x001b2019, 0x001b2019, 0x001c2118, 0x00171b11, 0x0010140a, 0x00101009, 0x00101009, 0x00121009, 0x00161309, 0x0019140a, 0x001d1108, 0x00271a0b, 0x002c1f0a, 0x00312108, 0x003c280c, 0x0043300c, 0x0049330c, 0x00573c0c, 0x006c480c, 0x008f6816, 0x00c2a332, 0x00cab420, 0x00cab912, 0x00c9bc0c, 0x00ccbd0a, 0x00ccba0c, 0x00c6a611, 0x00a07403, 0x00825602, 0x00684400, 0x00523c00, 0x00443600, 0x003f3000, 0x003c2c00, 0x00382804, 0x00362505, 0x00332303, 0x00332002, 0x00321e03, 0x00321c08, 0x00301c08, 0x002c1a08, 0x00281808, 0x00271809, 0x00271809, 0x00271808, 0x00261707, 0x00261807, 0x00241706, 0x00241605, 0x00241706, 0x00231606, 0x00221508, 0x00211407, 0x00211508, 0x00211508, 0x00201407, 0x00201407, 0x00201508, 0x00201508, 0x001c1206, 0x001f1408, 0x001e1308, 0x00201509, 0x001e1308, 0x00201509, 0x00201509, 0x001f1408, 0x001f1308, 0x00201408, 0x00201408, 0x00201408, 0x001f1208, 0x001e1207, 0x001c1408, 0x00181407, 0x00141104, 0x00161306, 0x00191407, 0x001c1407, 0x001e1307, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201609, 0x00201609, 0x00201609, 0x00201609, 0x00241409, 0x00241409, 0x00231409, 0x00221408, 0x00221408, 0x00221408, 0x00221409, 0x0022160a, 0x00221609, 0x00221409, 0x00211509, 0x00221609, 0x00211609, 0x00201508, 0x00201508, 0x00201609, 0x00201608, 0x00201408, 0x00201408, 0x001f1306, 0x001f1307, 0x001f1408, 0x001f1408, 0x001e1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201408, 0x00201408, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001f1408, 0x001e1306, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201408, 0x00201307, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1406, 0x001f1406, 0x001d1304, 0x001d1305, 0x001d1205, 0x001d1206, 0x001e1308, 0x001f1308, 0x00201208, 0x00201308, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1406, 0x001f1406, 0x001d1407, 0x001d1407, 0x001c1305, 0x001c1306, 0x00201409, 0x001e1408, 0x001f1408, 0x00201508, 0x00211408, 0x00201408, 0x001f1305, 0x001f1305, 0x001e1406, 0x001d1405, 0x001c1306, 0x001c1306, 0x001c1307, 0x001d1408, 0x001d1408, 0x001d1408, 0x001f1308, 0x001f1308, 0x00201208, 0x00201208, 0x00201208, 0x00201208, 0x001f1208, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1306, 0x001e1306, 0x001e1306, 0x001e1306, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001e1306, 0x001f1407, 0x001f1407, 0x001f1407, 0x001f1407, 0x001f1306, 0x001f1306, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00221508, 0x00221508, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221409, 0x00231509, 0x00221408, 0x00231408, 0x00241408, 0x00241408, 0x00241509, 0x0024150b, 0x0026160a, 0x0027160b, 0x0027180c, 0x0029180a, 0x002d1a0b, 0x00301c0c, 0x00321c0c, 0x00331d08, 0x0038210a, 0x0040270d, 0x00482c0a, 0x0051320a, 0x005e3c0c, 0x00734c0a, 0x00ac8423, 0x00cca92b, 0x00ccac14, 0x00ccac0d, 0x00ccaa0c, 0x00c8a40f, 0x00c69f0f, 0x00c3980b, 0x00bb8804, 0x00b37c01, 0x00b07301, 0x00a96a00, 0x00a46600, 0x00a56800, 0x00a86a02, 0x00ac7008, 0x00b37a10, 0x00be8919, 0x00c4941e, 0x00c99d20, 0x00cba61f, 0x00cbab1b, 0x00cbac1c, 0x00cca71f, 0x00b18213, 0x00885503, 0x00744408, 0x00533200, 0x004d2f02, 0x00452b04, 0x00412805, 0x00402508, 0x003f2409, 0x003c240b, 0x003c220c, 0x003c2309, 0x003b2108, 0x003b2309, 0x003d240c, 0x003e250c, 0x003e250b, 0x003f2608, 0x00402708, 0x00442a0a, 0x00452c0a, 0x00452d06, 0x004b3208, 0x00513809, 0x005e400c, 0x00744f0d, 0x00977414, 0x00c3a725, 0x00cbb415, 0x00ccb90c, 0x00ccbb08, 0x00cbbc08, 0x00cbbc08, 0x00ccbb05, 0x00cab00c, 0x00ae8909, 0x00845a01, 0x006c4404, 0x00583a04, 0x004c3607, 0x00423006, 0x003c2805, 0x00342203, 0x002f2006, 0x00261904, 0x001d1405, 0x001e170a, 0x00181409, 0x00141208, 0x0014110a, 0x0014130b, 0x00101008, 0x000c1007, 0x000d1008, 0x000d100a, 0x000e120c, 0x000c1410, 0x000a1410, 0x000c1512, 0x000d1512, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181e18, 0x00181f19, 0x00181f19, 0x00192018, 0x00192018, 0x001a2118, 0x00141910, 0x000e130c, 0x000f100a, 0x0011110a, 0x0014110a, 0x0017130a, 0x001a1409, 0x001e1308, 0x00281c0b, 0x002c1f0a, 0x00322208, 0x003d280d, 0x0042300b, 0x0049340c, 0x005b3f0e, 0x00714c0f, 0x009a741c, 0x00c8a930, 0x00cab51d, 0x00c8ba11, 0x00c8bc0a, 0x00cbbd09, 0x00cbb80d, 0x00be9c0d, 0x00946700, 0x007b5000, 0x00624100, 0x004c3701, 0x00413101, 0x003b2b00, 0x00382902, 0x00352604, 0x00342404, 0x00312204, 0x00311e04, 0x002d1b02, 0x002c1c07, 0x002b1a08, 0x00281807, 0x00261808, 0x00261909, 0x00241808, 0x00241607, 0x00241607, 0x00241507, 0x00231506, 0x00241607, 0x00241507, 0x00211407, 0x00221509, 0x001f1206, 0x00201408, 0x00211408, 0x00201407, 0x00201406, 0x00201406, 0x00211507, 0x001f1408, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x001f1208, 0x001c1408, 0x00191508, 0x00131003, 0x00141206, 0x00181306, 0x001b1408, 0x001c1208, 0x00201409, 0x00201409, 0x00211408, 0x00221608, 0x00201609, 0x00201609, 0x00201609, 0x00201609, 0x00241409, 0x00241409, 0x00241409, 0x00211308, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00201508, 0x00201408, 0x00201307, 0x00201508, 0x00201709, 0x00201508, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001e1205, 0x00201408, 0x00211408, 0x00201307, 0x00201307, 0x00201307, 0x001d1205, 0x001f1408, 0x00201508, 0x001f1408, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201307, 0x001e1407, 0x001c1205, 0x001c1205, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001e1306, 0x001d1306, 0x001e1407, 0x001e1306, 0x001d1206, 0x001d1207, 0x001e1308, 0x001e1308, 0x001f1308, 0x00201208, 0x00201208, 0x00201208, 0x00201208, 0x00211308, 0x00201105, 0x00201105, 0x001f1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001c1104, 0x001e1205, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001d1306, 0x001e1306, 0x001f1408, 0x00201508, 0x00201508, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241509, 0x00241409, 0x00221407, 0x00241508, 0x00241508, 0x00241608, 0x0023160a, 0x00231708, 0x0024180c, 0x0025180c, 0x0028170c, 0x002b180c, 0x002f1c0c, 0x00301b0a, 0x00321d08, 0x0037210b, 0x0040270c, 0x00482c09, 0x0052320c, 0x00633c10, 0x00744c0a, 0x00a2781c, 0x00c49824, 0x00c09410, 0x00b88908, 0x00b38000, 0x00af7700, 0x00ac7000, 0x00a76900, 0x00a66700, 0x00a46400, 0x00a66801, 0x00ad7106, 0x00b47c0d, 0x00ba8412, 0x00c38f19, 0x00c7981e, 0x00c9a220, 0x00ccaa20, 0x00ccaf1c, 0x00cbb214, 0x00cab40c, 0x00c8b608, 0x00c8b40c, 0x00cbab17, 0x00a97d08, 0x00885400, 0x00714002, 0x00523000, 0x004a2d02, 0x00422802, 0x003d2504, 0x003c2208, 0x003a1f08, 0x00361f0a, 0x00351f0d, 0x00351e0c, 0x00341c0c, 0x00341c08, 0x00351f08, 0x00392109, 0x003c240c, 0x003e250b, 0x003e260a, 0x0041290c, 0x00432c0b, 0x00432c08, 0x0048310c, 0x004e370c, 0x005e4010, 0x00705010, 0x008a670f, 0x00b5921f, 0x00ccb21d, 0x00ccb812, 0x00cbba0a, 0x00cabb08, 0x00cbba08, 0x00ccb80a, 0x00ccb412, 0x00b9980f, 0x008c6400, 0x006e4803, 0x00593b04, 0x004c3704, 0x00423004, 0x003c2805, 0x00372404, 0x00301f06, 0x00261803, 0x001c1404, 0x001d1609, 0x00181409, 0x00141208, 0x00141109, 0x00131209, 0x00101208, 0x000d1007, 0x000d1007, 0x000e1109, 0x000d110c, 0x000c140f, 0x000b1410, 0x000b1411, 0x000c1512, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181f19, 0x0019201a, 0x0019201a, 0x001b2119, 0x00192018, 0x00192017, 0x00131810, 0x000e130c, 0x000f1009, 0x0011100a, 0x0015120b, 0x0017130a, 0x00191309, 0x0020140a, 0x00281c0c, 0x002d200b, 0x00342409, 0x003e290e, 0x0044320d, 0x004b380e, 0x005d4110, 0x0074500f, 0x00a37f21, 0x00caac2d, 0x00cbb818, 0x00c8ba10, 0x00c8bc0a, 0x00cbba08, 0x00cab310, 0x00b18e0b, 0x008a5e00, 0x00764c03, 0x005d3f02, 0x00493402, 0x003f2f01, 0x00392800, 0x00352502, 0x00322402, 0x00312206, 0x00302005, 0x002c1c02, 0x00291900, 0x002b1a07, 0x00281807, 0x00241606, 0x00231707, 0x00241808, 0x00221606, 0x00211505, 0x00211505, 0x001f1305, 0x00211407, 0x00221608, 0x00211507, 0x00201408, 0x00221509, 0x001e1206, 0x00211408, 0x00221509, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x001f1308, 0x001c1408, 0x00191508, 0x00131003, 0x00131105, 0x00181308, 0x001b1308, 0x001c1208, 0x00201409, 0x00201409, 0x00221509, 0x00221608, 0x00201609, 0x00201609, 0x00201609, 0x00201609, 0x00241409, 0x00241409, 0x00241409, 0x00211308, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00201508, 0x00201408, 0x00201307, 0x00201508, 0x00201709, 0x00201508, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001e1205, 0x00201408, 0x00211408, 0x00201307, 0x00201307, 0x00201307, 0x001d1205, 0x001f1408, 0x00201508, 0x00201508, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001f1408, 0x001d1305, 0x001e1407, 0x001e1407, 0x00201307, 0x001e1205, 0x00201307, 0x00201307, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201307, 0x001e1407, 0x001c1205, 0x001c1204, 0x001e1306, 0x00201609, 0x001f1408, 0x001d1205, 0x001d1205, 0x001f1408, 0x00201508, 0x00201508, 0x00201609, 0x00201508, 0x001d1307, 0x001d1207, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x00201408, 0x001e1205, 0x001e1205, 0x001e1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1306, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201508, 0x00201508, 0x00201508, 0x00201508, 0x00201508, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241509, 0x0024160a, 0x00241409, 0x00221407, 0x00241508, 0x00241508, 0x00241608, 0x0023160a, 0x00231708, 0x0023170a, 0x0025180c, 0x0028170c, 0x002b180c, 0x002f1c0c, 0x00301b0a, 0x00321c07, 0x0037210b, 0x003f250b, 0x00472a07, 0x0055340a, 0x00673f0e, 0x0073460b, 0x00855408, 0x009c680b, 0x009a6200, 0x009a6100, 0x009c6300, 0x009c6300, 0x00a46902, 0x00aa7007, 0x00b2780a, 0x00ba8410, 0x00c39517, 0x00c79e1a, 0x00c8a31a, 0x00cca91c, 0x00ccac18, 0x00ccae14, 0x00ccb113, 0x00cab210, 0x00c8b30e, 0x00c6b40b, 0x00c6b706, 0x00c7b805, 0x00c9b60c, 0x00caa813, 0x00a47701, 0x00845300, 0x006d3e00, 0x00502d00, 0x00472a01, 0x003f2502, 0x003a2304, 0x00392007, 0x00371c07, 0x00341c09, 0x00321c0c, 0x00321c0c, 0x00331c0c, 0x00321c08, 0x00321c06, 0x00321d05, 0x00361f08, 0x00392209, 0x003a2308, 0x003c2609, 0x003f2809, 0x003f2907, 0x00422d0a, 0x0048340b, 0x00563e0f, 0x006b4c13, 0x00815d0e, 0x00a58018, 0x00caaf24, 0x00ccb718, 0x00ccb90d, 0x00cabb0a, 0x00cbba0a, 0x00ccb90a, 0x00ccb711, 0x00c0a212, 0x00936d01, 0x00734c03, 0x005c3d04, 0x004d3805, 0x00433005, 0x003d2a07, 0x00382404, 0x00312005, 0x00281904, 0x001c1404, 0x001b1406, 0x001a150a, 0x00141308, 0x00141109, 0x00131209, 0x00111309, 0x000e1107, 0x000d1007, 0x000e1109, 0x000d110c, 0x000c130e, 0x000b1410, 0x000b1411, 0x000b1411, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00181f19, 0x0019201a, 0x0019201a, 0x001b2119, 0x00192018, 0x00171e14, 0x000f140b, 0x000e130b, 0x000d1009, 0x0011100b, 0x0015140c, 0x00171308, 0x00181208, 0x0020150b, 0x00281c0c, 0x002f200a, 0x0037250b, 0x003f2a0d, 0x00483611, 0x004e390f, 0x005f4310, 0x007c5810, 0x00ae8925, 0x00cbae2a, 0x00cbb814, 0x00c8bb0e, 0x00c8ba08, 0x00cab80c, 0x00c8af10, 0x00a07c03, 0x00825702, 0x00704807, 0x00573903, 0x00483404, 0x003e2d03, 0x003a2902, 0x00322201, 0x002e1f01, 0x002c1c03, 0x002a1c04, 0x00281a04, 0x00261802, 0x00261704, 0x00241505, 0x00211506, 0x00211508, 0x00201608, 0x001f1406, 0x001f1406, 0x001f1406, 0x00201408, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x0021140a, 0x00201208, 0x0021140a, 0x0021140a, 0x00201409, 0x00201409, 0x00201208, 0x00201208, 0x001d1205, 0x001d1205, 0x001c1104, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001f1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00211309, 0x001f1409, 0x00181407, 0x00141305, 0x00141005, 0x00181308, 0x001b1308, 0x001c1208, 0x00201309, 0x00201409, 0x00211408, 0x00221608, 0x00201609, 0x00201609, 0x00201508, 0x00201508, 0x00231409, 0x00241409, 0x00231408, 0x00221408, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00201508, 0x00211408, 0x00201307, 0x00201508, 0x001f1608, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001e1205, 0x00201408, 0x00201408, 0x001f1206, 0x001e1205, 0x001e1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x001e1205, 0x00201307, 0x00201307, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201307, 0x001e1407, 0x001c1205, 0x001c1204, 0x001f1408, 0x00201508, 0x001d1205, 0x001d1205, 0x001d1306, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201508, 0x001e1407, 0x001d1206, 0x001d1207, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201408, 0x001e1205, 0x001e1205, 0x001e1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x00201508, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1306, 0x001e1205, 0x001f1205, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x00201508, 0x00211408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00211406, 0x00221407, 0x00221407, 0x00241508, 0x0023160a, 0x00231708, 0x0023160a, 0x0024180c, 0x0027160c, 0x0028170b, 0x002c190a, 0x00301b0a, 0x00331c09, 0x0038210c, 0x0040270d, 0x004a2c08, 0x00593608, 0x006c410c, 0x00774609, 0x00804c01, 0x008e5500, 0x00985e01, 0x00a06803, 0x00ab760c, 0x00b68416, 0x00c19220, 0x00c89a22, 0x00caa01c, 0x00cca51a, 0x00ccab14, 0x00ccb013, 0x00cbb213, 0x00cab310, 0x00c9b30b, 0x00ccb509, 0x00cbb608, 0x00cab408, 0x00c8b60a, 0x00c8b708, 0x00c8b705, 0x00c8b605, 0x00cbb30e, 0x00c9a214, 0x009f7001, 0x00815000, 0x00693d03, 0x004f2c01, 0x00452803, 0x003d2404, 0x00392206, 0x00392008, 0x00361c08, 0x00341c0b, 0x00321c0e, 0x00301c0d, 0x00301c0c, 0x00301c0a, 0x00301b08, 0x00301c08, 0x00311d07, 0x00341f08, 0x00372108, 0x00382308, 0x003b2608, 0x003d2908, 0x003e2b07, 0x00422f08, 0x004d380c, 0x00614511, 0x0079540f, 0x009a6f14, 0x00c0a020, 0x00ccb41f, 0x00ccb912, 0x00cbbc0c, 0x00c9bc0c, 0x00cbbc0a, 0x00ccb80e, 0x00c3aa11, 0x009a7603, 0x00774f02, 0x00604006, 0x00503906, 0x00443006, 0x003e2a07, 0x00382405, 0x00342006, 0x002c1d07, 0x001d1405, 0x00191304, 0x001c170b, 0x0016140a, 0x00131008, 0x00121108, 0x00101208, 0x000e1208, 0x000d1007, 0x000d1008, 0x000d120b, 0x000a120e, 0x000a1410, 0x000b1310, 0x000b1411, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001b211b, 0x001b211b, 0x001b211b, 0x001c221b, 0x001b2119, 0x00141a10, 0x000c1108, 0x000b1008, 0x000d0f08, 0x0012110b, 0x0016140c, 0x00161408, 0x00191308, 0x0020180c, 0x00281c0c, 0x00302109, 0x0038270a, 0x003f2c0c, 0x00473710, 0x00513c11, 0x00634811, 0x00856114, 0x00b8952a, 0x00cab024, 0x00cbb910, 0x00cabb0c, 0x00c8ba07, 0x00c8b408, 0x00c4a811, 0x00967100, 0x00795003, 0x00664104, 0x00513603, 0x00423004, 0x003d2c05, 0x00372703, 0x00302001, 0x002c1c03, 0x002a1c05, 0x002a1c05, 0x00271a05, 0x00241704, 0x00241605, 0x00211506, 0x001f1305, 0x001e1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001e1407, 0x001e1308, 0x001d1308, 0x001f1409, 0x0020150a, 0x0021140c, 0x0020120a, 0x0021140c, 0x0021140c, 0x00201409, 0x00201409, 0x00201208, 0x00201208, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001f1408, 0x00201408, 0x00201409, 0x001f1409, 0x00191407, 0x00161305, 0x00141005, 0x00181308, 0x001b1308, 0x001c1208, 0x001f1208, 0x00201409, 0x00201408, 0x00221608, 0x00221509, 0x00221509, 0x00201408, 0x00201408, 0x00211308, 0x00211308, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00211408, 0x00201508, 0x00211408, 0x00201307, 0x00201508, 0x001f1608, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001e1205, 0x00201408, 0x00201408, 0x001f1206, 0x001e1205, 0x001e1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x001e1205, 0x00201307, 0x00201307, 0x00201308, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211308, 0x00201408, 0x00201307, 0x001e1407, 0x001c1205, 0x001c1105, 0x00201508, 0x001e1306, 0x001d1205, 0x001d1205, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1206, 0x001d1207, 0x001d1308, 0x001e1308, 0x001c1408, 0x001c1405, 0x001c1405, 0x001c1405, 0x001c1405, 0x001f1408, 0x001d1305, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x00201609, 0x00201508, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1306, 0x001e1205, 0x001f1206, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x00211408, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00231409, 0x00211406, 0x00221407, 0x00221407, 0x00221407, 0x0023160a, 0x00231609, 0x0023160a, 0x0024170a, 0x0028180d, 0x00281608, 0x002b1808, 0x00301b0a, 0x00331d08, 0x0038220c, 0x00432810, 0x004c2e0e, 0x005c370a, 0x0070440c, 0x00845410, 0x00a26f1a, 0x00b17e18, 0x00bf8f1a, 0x00c89e23, 0x00caa11e, 0x00cba81f, 0x00ccac1f, 0x00ccaf1b, 0x00ccb015, 0x00cbb011, 0x00cab20d, 0x00cab50c, 0x00cab80a, 0x00cbba0a, 0x00ccb808, 0x00ccb709, 0x00ccb508, 0x00cbb409, 0x00cbb40a, 0x00cbb40a, 0x00ccb109, 0x00ccae0b, 0x00cca913, 0x00c09312, 0x00956100, 0x007e4d03, 0x00643804, 0x004c2b03, 0x00442502, 0x003b2204, 0x00382006, 0x00371d07, 0x00341a06, 0x00311908, 0x002f1a0b, 0x002c190a, 0x002c1a0a, 0x002c1908, 0x002c1808, 0x002d1a07, 0x002f1c08, 0x00301d06, 0x00331f08, 0x00352209, 0x00372407, 0x00382807, 0x003b2b06, 0x003c2c04, 0x0046360b, 0x00553b0b, 0x00714c0d, 0x008b600e, 0x00b28e19, 0x00ccb024, 0x00ccb715, 0x00cbbc0c, 0x00c8bc0b, 0x00cabc07, 0x00ccb908, 0x00c6b010, 0x009f7d04, 0x007b5200, 0x00644205, 0x00533b06, 0x00463206, 0x00402c09, 0x00392506, 0x00352206, 0x002d1d05, 0x001e1504, 0x00191304, 0x001a1709, 0x0018140a, 0x00131008, 0x00131008, 0x00111108, 0x000f1108, 0x000e1208, 0x000d1007, 0x000d120b, 0x000b130c, 0x000b140e, 0x000c1310, 0x000b1411, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001b211b, 0x001c221c, 0x001c211c, 0x001c211b, 0x001d221b, 0x0013170f, 0x000d1008, 0x000e1008, 0x00101109, 0x0013130c, 0x0016140c, 0x00151307, 0x00181408, 0x0020180c, 0x00291e0c, 0x00302209, 0x00392809, 0x003f2c09, 0x0046370d, 0x00523c11, 0x00684a10, 0x008a6610, 0x00c2a22c, 0x00ccb41d, 0x00ccba0d, 0x00c8bb0b, 0x00cbbc02, 0x00ccb80b, 0x00b8980c, 0x008c6500, 0x00754f04, 0x005f3f01, 0x004b3301, 0x00412f07, 0x003c2c09, 0x00352507, 0x002e1e04, 0x002a1c05, 0x00281a07, 0x00271a08, 0x00261808, 0x00231507, 0x00201408, 0x001e1407, 0x001c1406, 0x001c1305, 0x001d1207, 0x001c1307, 0x001c1408, 0x001c1408, 0x001c1409, 0x001c140a, 0x001c140a, 0x001c140a, 0x001d1409, 0x001e1409, 0x00201409, 0x00201409, 0x00201409, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1205, 0x001e1407, 0x00201508, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x001f1307, 0x001d1408, 0x001c1408, 0x001b1408, 0x00161003, 0x00141003, 0x00191208, 0x00191208, 0x001c1307, 0x001d1409, 0x001e1508, 0x00201607, 0x00231509, 0x00241409, 0x00201207, 0x00201207, 0x00211308, 0x00241409, 0x00241509, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00221509, 0x00201609, 0x00211408, 0x00211408, 0x001f1408, 0x001e1508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001f1408, 0x001f1408, 0x001d1205, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201406, 0x001f1204, 0x001e1204, 0x001e1204, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1205, 0x001e1205, 0x00201407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1608, 0x001d1408, 0x001c1407, 0x001c1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201207, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x00201709, 0x001d1207, 0x001b1005, 0x0020150a, 0x001f1409, 0x001d1207, 0x001d1207, 0x001e1308, 0x001e1308, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1306, 0x001b1204, 0x001b1205, 0x001c1407, 0x001c1407, 0x001c1405, 0x001c1405, 0x001c1405, 0x001c1405, 0x001e1407, 0x001e1407, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x00201609, 0x00201609, 0x001f1408, 0x00201408, 0x00241409, 0x00241409, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00211409, 0x00221509, 0x00221509, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x0021140a, 0x0024160a, 0x00271608, 0x00291808, 0x002c1a08, 0x00311b08, 0x00351e07, 0x0039210b, 0x00442811, 0x004a2c10, 0x005c360f, 0x0075480e, 0x00a17024, 0x00c89b32, 0x00cba624, 0x00cbad18, 0x00cbaf14, 0x00ccb110, 0x00ccb30e, 0x00cab40c, 0x00cab70d, 0x00c8b80b, 0x00c8b80a, 0x00c8b60a, 0x00c9b60a, 0x00c8b809, 0x00c8ba07, 0x00ccb808, 0x00ccb408, 0x00ccb108, 0x00ccb20a, 0x00cbaf09, 0x00caa90c, 0x00c8a311, 0x00c0940e, 0x00b6850b, 0x00a36c02, 0x008a5300, 0x00774604, 0x005e3501, 0x00482800, 0x00402401, 0x003a2104, 0x00361f06, 0x00361c08, 0x00331907, 0x002e1808, 0x002d1809, 0x002a1808, 0x00291808, 0x00281808, 0x00281808, 0x002b1908, 0x002c1a08, 0x002c1b07, 0x002d1c08, 0x002f1e09, 0x0034230a, 0x00342506, 0x00372805, 0x00392c03, 0x00423108, 0x00503808, 0x0068480c, 0x007d580a, 0x009c7610, 0x00c4a524, 0x00ccb519, 0x00cbba0f, 0x00c8bc06, 0x00c8bb03, 0x00c9b805, 0x00c9b40d, 0x00ae8d0a, 0x00805800, 0x006a4303, 0x00573904, 0x00483307, 0x00402c09, 0x003a2606, 0x00352304, 0x002e1e05, 0x00241908, 0x001a1102, 0x00191306, 0x0019150a, 0x0017130b, 0x00141109, 0x00121108, 0x00101108, 0x00101106, 0x000f1007, 0x000e1208, 0x000d1208, 0x000d120c, 0x000d130f, 0x000b1412, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001c221c, 0x001c221c, 0x001c211c, 0x001c201a, 0x00191e17, 0x0010140c, 0x000d1008, 0x00100f08, 0x00101109, 0x0014150c, 0x00141309, 0x00141306, 0x00191508, 0x00231b0c, 0x002c1f0c, 0x00332409, 0x003a2909, 0x003f2c09, 0x0048360c, 0x00574010, 0x006d4e0e, 0x00957217, 0x00c7a72c, 0x00ccb51e, 0x00cbba0d, 0x00c8bb0c, 0x00cbbb04, 0x00cab30b, 0x00ae8c08, 0x00825c00, 0x006e4a04, 0x00573a00, 0x00463000, 0x003d2c06, 0x00382807, 0x00322304, 0x002c1c03, 0x00281903, 0x00251606, 0x00241808, 0x00251809, 0x00231508, 0x00201409, 0x001c1408, 0x001c1408, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1508, 0x001c1408, 0x001c1408, 0x001c1308, 0x001c1307, 0x001c1408, 0x001e1508, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1305, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x001f1307, 0x001d1408, 0x001c1408, 0x001c1408, 0x00181004, 0x00140e01, 0x00181007, 0x00191208, 0x001c1307, 0x001c1408, 0x001e1508, 0x001f1507, 0x00231509, 0x00241409, 0x00201207, 0x00201207, 0x00211308, 0x00241409, 0x00241509, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00221408, 0x00221509, 0x00201609, 0x00211408, 0x00211408, 0x001f1408, 0x001e1508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001d1205, 0x001f1408, 0x001f1408, 0x001e1407, 0x001f1408, 0x001f1408, 0x001d1205, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201406, 0x001f1204, 0x001e1204, 0x001e1204, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1205, 0x001e1205, 0x00201407, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x00201508, 0x001f1608, 0x001d1408, 0x001c1407, 0x001c1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201207, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001e1407, 0x00201709, 0x001d1207, 0x001b1005, 0x0020150a, 0x001f1409, 0x001d1207, 0x001d1207, 0x001e1308, 0x001e1308, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1307, 0x001b1206, 0x001b1207, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001e1407, 0x001e1407, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00211308, 0x00211308, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211408, 0x00211409, 0x00221509, 0x00211408, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x0021140a, 0x0024170a, 0x00261708, 0x00291808, 0x002c1a08, 0x00311b08, 0x00351e07, 0x0039210b, 0x00442811, 0x004a2c0f, 0x005f380e, 0x00784b0f, 0x00ad8027, 0x00cca82d, 0x00cbaf18, 0x00ccb20d, 0x00ccb30a, 0x00ccb407, 0x00cbb408, 0x00c8b60b, 0x00c8b90d, 0x00c8ba10, 0x00caba0e, 0x00cbb809, 0x00cbb609, 0x00c8b408, 0x00c9b409, 0x00ccb10e, 0x00ccad0f, 0x00c8a60d, 0x00c09d09, 0x00ba9008, 0x00b27f04, 0x00a46f01, 0x009b6300, 0x00935a00, 0x008c5204, 0x00824807, 0x00704008, 0x00583102, 0x00482803, 0x00402303, 0x00382004, 0x00341e07, 0x00341c08, 0x00321a07, 0x002d1808, 0x002b170a, 0x00281809, 0x0028180b, 0x0028180b, 0x00281809, 0x00291909, 0x002c1a09, 0x002c1a08, 0x002c1a08, 0x002b1c08, 0x002e1f0a, 0x00322408, 0x00332605, 0x00372904, 0x003e2d07, 0x004b3408, 0x0060440c, 0x0075510a, 0x008f660b, 0x00b8941e, 0x00ccb41d, 0x00cbb911, 0x00c9bc0c, 0x00cabc06, 0x00ccb909, 0x00cab40c, 0x00b8980e, 0x00885f00, 0x006c4500, 0x00593c04, 0x00493405, 0x00412e09, 0x003b2707, 0x00362404, 0x002e1e04, 0x00241906, 0x001a1201, 0x001a1406, 0x001b180c, 0x0018140c, 0x00141109, 0x00131008, 0x00101108, 0x00101106, 0x000f1005, 0x000e1208, 0x000d1208, 0x000e130b, 0x000d130e, 0x000b1412, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001c221c, 0x001c221c, 0x001b211b, 0x001b2018, 0x00161b14, 0x000f120a, 0x000f0f08, 0x00100f08, 0x00111008, 0x0014150c, 0x00121108, 0x00141205, 0x00191608, 0x00231b0c, 0x002c1f0b, 0x00342408, 0x003c2809, 0x00442e0d, 0x004a340c, 0x005b400e, 0x0070500a, 0x00a07c1a, 0x00caac2c, 0x00ccb61c, 0x00ccbb0d, 0x00caba0d, 0x00ccb90a, 0x00c8ad0d, 0x00a17d01, 0x007d5704, 0x00674408, 0x00523704, 0x00412f01, 0x003c2c07, 0x00392808, 0x00332306, 0x002c1d04, 0x00251804, 0x00221608, 0x00211708, 0x00201409, 0x001f1409, 0x001c140a, 0x001c140a, 0x001c1409, 0x001a1408, 0x001b1407, 0x001b1407, 0x001a1407, 0x00181408, 0x001a1406, 0x001b1406, 0x001a1405, 0x00191304, 0x001a1304, 0x001c1305, 0x001e1206, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1308, 0x001c1106, 0x001c1206, 0x001c1106, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x00201508, 0x001e1407, 0x001e1407, 0x001f1407, 0x001f1307, 0x001d1408, 0x001c1408, 0x001c1408, 0x001b1206, 0x00160d01, 0x00181006, 0x001c1208, 0x001c1307, 0x001c1307, 0x001c1406, 0x001e1506, 0x00211408, 0x00221408, 0x00221408, 0x00211308, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00231409, 0x00211308, 0x00211308, 0x00211408, 0x00201508, 0x00211408, 0x00211408, 0x001f1408, 0x00201709, 0x00201508, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201406, 0x00201305, 0x00201305, 0x00201305, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x001f1206, 0x001f1206, 0x00201307, 0x00201407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x00201508, 0x001d1408, 0x001c1407, 0x001c1407, 0x001c1407, 0x001e1205, 0x001e1205, 0x001e1205, 0x001e1205, 0x001f1105, 0x001f1205, 0x001f1306, 0x001f1307, 0x001f1407, 0x00201307, 0x00201307, 0x001e1407, 0x001c1407, 0x001c1005, 0x001c1207, 0x001f1409, 0x001e1308, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001a1306, 0x00191306, 0x001a1407, 0x001b1407, 0x001a1307, 0x00191208, 0x00191208, 0x00191208, 0x00191208, 0x00191306, 0x00191306, 0x001c1408, 0x001c1408, 0x001d1407, 0x001e1407, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001e1407, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001f1408, 0x0020150a, 0x0023170a, 0x0027180b, 0x00281808, 0x002e1908, 0x00321a08, 0x00371d07, 0x003a210b, 0x0042280e, 0x004c2d0a, 0x0060380a, 0x007c4f10, 0x00b08728, 0x00ccab27, 0x00ccb412, 0x00ccb508, 0x00ccb506, 0x00ccb605, 0x00cbb607, 0x00c9b50c, 0x00c8b60f, 0x00c9b510, 0x00cbb410, 0x00ccb10e, 0x00ccac0d, 0x00c9a710, 0x00c59e0e, 0x00be910c, 0x00b48406, 0x00a67501, 0x00a37000, 0x00a06700, 0x00a06100, 0x009f6100, 0x00a06504, 0x009e640b, 0x00885202, 0x00794402, 0x006c3e08, 0x00522d00, 0x00472804, 0x003e2204, 0x00382007, 0x00331d08, 0x00321c08, 0x002f1a08, 0x002b1909, 0x00271609, 0x0024180b, 0x0024180c, 0x0024180b, 0x0024180a, 0x00241708, 0x00261806, 0x00281908, 0x00291b0a, 0x002a1b0c, 0x002d1e0c, 0x0030220b, 0x00302408, 0x00342605, 0x003e2c08, 0x00463009, 0x00543b08, 0x006a4c0c, 0x00835809, 0x00a88218, 0x00cab023, 0x00cab715, 0x00c9bb10, 0x00cbbc0c, 0x00ccb80a, 0x00cab50c, 0x00bc9c0c, 0x008e6600, 0x006c4700, 0x005b3e02, 0x00493505, 0x00422f0a, 0x003c2506, 0x00362404, 0x002e2004, 0x00261a06, 0x001c1402, 0x00171102, 0x00191609, 0x0019150c, 0x00140f08, 0x00131008, 0x00111108, 0x00101106, 0x000f1005, 0x000e1208, 0x000d1208, 0x000e130b, 0x000d130e, 0x000c1312, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001c221c, 0x001c221c, 0x001b211b, 0x001c2019, 0x00161b14, 0x000f120a, 0x00100f08, 0x00110f08, 0x00121108, 0x0014140b, 0x00101005, 0x00141205, 0x001c1709, 0x00251c0c, 0x002e200c, 0x0036250a, 0x003e2a0c, 0x00493111, 0x00503710, 0x0060430f, 0x00755408, 0x00a8881e, 0x00ccb12c, 0x00ccb719, 0x00ccbb0d, 0x00c9b90c, 0x00ccb80b, 0x00c2a70d, 0x00946f00, 0x00744e04, 0x005d3d05, 0x004c3403, 0x00402e03, 0x003c2c08, 0x00392808, 0x00322305, 0x002a1b03, 0x00221601, 0x001e1405, 0x001d1407, 0x001c1409, 0x001c140b, 0x001c130c, 0x001c140c, 0x001b140c, 0x0019140a, 0x001b1407, 0x001b1407, 0x00191407, 0x00181407, 0x00181405, 0x00181404, 0x00181404, 0x00181404, 0x001a1404, 0x001c1404, 0x001e1304, 0x00201305, 0x001f1405, 0x00201507, 0x001f1406, 0x001e1405, 0x001e1406, 0x001c1107, 0x001e130a, 0x001f140b, 0x001d1208, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x00201508, 0x001e1407, 0x001e1407, 0x001e1306, 0x001f1307, 0x001e1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x00181004, 0x00191006, 0x001b1108, 0x001c1307, 0x001c1307, 0x001c1305, 0x001c1404, 0x00211408, 0x00221408, 0x00221408, 0x00211308, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00231409, 0x00211308, 0x00211308, 0x00211408, 0x00201508, 0x00211408, 0x00211408, 0x001f1408, 0x00201709, 0x00201508, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001d1205, 0x001e1205, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201406, 0x00201406, 0x00201305, 0x00201305, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1407, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x001f1206, 0x001f1206, 0x00201307, 0x00201407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001e1205, 0x001e1205, 0x001e1205, 0x001e1205, 0x001f1105, 0x001f1205, 0x001f1306, 0x001f1307, 0x001f1407, 0x00201307, 0x00201307, 0x001e1407, 0x001d1407, 0x001c1005, 0x001c1207, 0x001f1409, 0x001d1408, 0x001c1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001a1306, 0x00191306, 0x001a1407, 0x001b1407, 0x001a1307, 0x00191208, 0x00191208, 0x00191208, 0x00191308, 0x00191306, 0x00191306, 0x001b1508, 0x001c1408, 0x001d1407, 0x001e1407, 0x001c1104, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001e1407, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001f1408, 0x0020150a, 0x0023170a, 0x0027180a, 0x00291808, 0x002e1908, 0x00331a08, 0x00371d07, 0x003a2209, 0x00442a0c, 0x004c2f08, 0x00603807, 0x00805310, 0x00b88e2f, 0x00caab28, 0x00cbb414, 0x00ccb506, 0x00ccb506, 0x00ccb408, 0x00ccb308, 0x00cab00c, 0x00caaf10, 0x00c9a910, 0x00c6a00b, 0x00c09406, 0x00b88802, 0x00b07902, 0x00ab7101, 0x00a66800, 0x00a46600, 0x00a36400, 0x00a96c04, 0x00ac6e04, 0x00b6790d, 0x00bd8614, 0x00c4901a, 0x00c4941e, 0x009c6c05, 0x00804e00, 0x006c4004, 0x00502c00, 0x00442606, 0x003c2006, 0x00382008, 0x00331e09, 0x00301b08, 0x002c1a08, 0x00291909, 0x00241608, 0x0023160a, 0x0023160c, 0x0022170c, 0x0022170c, 0x00221608, 0x00221606, 0x00231607, 0x00261808, 0x0028190b, 0x002c1b0e, 0x002f200d, 0x00302009, 0x00332405, 0x003a2806, 0x0045300a, 0x004f380a, 0x00634910, 0x007d530e, 0x00987211, 0x00c5a825, 0x00c9b617, 0x00c9bb13, 0x00cbbb0f, 0x00cbb90d, 0x00ccb60c, 0x00c4a610, 0x00946d00, 0x006f4800, 0x005c3f01, 0x00483604, 0x00432f09, 0x003c2607, 0x00382505, 0x00302206, 0x00261b06, 0x001f1604, 0x00161001, 0x00171407, 0x001c180f, 0x0016110a, 0x00131008, 0x00111208, 0x00101106, 0x000f1005, 0x000e1208, 0x000e1208, 0x000e120c, 0x000d130e, 0x000c1311, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a221e, 0x001a221e, 0x001c211d, 0x001a211a, 0x00141810, 0x000e1108, 0x00101006, 0x00111006, 0x00131209, 0x00131409, 0x00101105, 0x00151307, 0x0021180c, 0x002a1b0d, 0x002f200c, 0x0036240a, 0x003e2a0b, 0x004a3210, 0x00543810, 0x00654512, 0x007c5a0d, 0x00b29224, 0x00ccb327, 0x00ccb716, 0x00cbb90d, 0x00c8b809, 0x00cab70c, 0x00b8990b, 0x00896100, 0x006d4802, 0x00583c04, 0x00483404, 0x003e2d04, 0x003c2a08, 0x00382608, 0x00312106, 0x00291c04, 0x00221703, 0x001c1405, 0x001c1407, 0x001b1309, 0x001b130c, 0x00191208, 0x00191208, 0x001a1108, 0x001b1007, 0x001b1206, 0x00191306, 0x00181306, 0x00181306, 0x00171406, 0x00171406, 0x00191608, 0x00181408, 0x001a1406, 0x001c1407, 0x001c1407, 0x001d1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001d1205, 0x001d1205, 0x00201307, 0x00201307, 0x001f1206, 0x00201408, 0x001d1205, 0x001e1306, 0x001f1408, 0x001f1408, 0x001e1508, 0x001d1409, 0x001c1408, 0x00191004, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1305, 0x001d1406, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00201307, 0x00201408, 0x001f1408, 0x00201609, 0x001f1408, 0x00201508, 0x00201508, 0x00201406, 0x00201406, 0x00201305, 0x00201305, 0x001e1407, 0x001e1407, 0x001d1205, 0x001f1408, 0x00211609, 0x001f1408, 0x001c1104, 0x001d1205, 0x001d1205, 0x001e1205, 0x001e1205, 0x001f1206, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201307, 0x00201408, 0x00201408, 0x001f1408, 0x001f1508, 0x001d1407, 0x001d1407, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1305, 0x00201508, 0x001c1104, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1107, 0x001e1107, 0x001e1107, 0x001e1107, 0x001e1206, 0x001e1205, 0x001f1306, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001e1205, 0x00201508, 0x001b1106, 0x001a1105, 0x001c1509, 0x001c1609, 0x001d1509, 0x001c1408, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1106, 0x001c1106, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1207, 0x001e1308, 0x001d1207, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1407, 0x001e1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00221509, 0x00221509, 0x00211408, 0x00211408, 0x00211408, 0x00221408, 0x00221408, 0x00211308, 0x00211308, 0x001f1408, 0x001f1408, 0x0020140a, 0x0023170a, 0x00261809, 0x002a1808, 0x002e1908, 0x00331a08, 0x00371d07, 0x003a2208, 0x00432a0b, 0x004d2e08, 0x00603908, 0x007c4f0a, 0x00bb912f, 0x00c9a827, 0x00ccb017, 0x00ccaf0b, 0x00ccab0b, 0x00caa50b, 0x00c59f09, 0x00be940c, 0x00b88a08, 0x00b07e02, 0x00ab7400, 0x00ad6b00, 0x00ab6800, 0x00a76700, 0x00aa6b04, 0x00ad710b, 0x00b37a10, 0x00bc8618, 0x00c59320, 0x00c89a20, 0x00cca520, 0x00ccab1c, 0x00ccac1c, 0x00c9a620, 0x00a47405, 0x00835101, 0x006a4002, 0x004f2b00, 0x00442509, 0x003c2008, 0x00371e08, 0x00321c08, 0x002f1b08, 0x002c1a08, 0x00281809, 0x00241609, 0x0023160a, 0x0023160a, 0x00211609, 0x00201608, 0x00201507, 0x00201606, 0x00211606, 0x00241808, 0x00251808, 0x00281a09, 0x002c1e09, 0x002c1d07, 0x00302005, 0x00382706, 0x0042300b, 0x004b360c, 0x00584010, 0x006f4d0c, 0x008a6411, 0x00bb9c26, 0x00cab61c, 0x00cbbb10, 0x00ccba0e, 0x00ccba0e, 0x00ccb80e, 0x00caad14, 0x009c7501, 0x00744d00, 0x005c4002, 0x00473704, 0x00433008, 0x003e2808, 0x00382606, 0x00312306, 0x00291c08, 0x00201705, 0x00181003, 0x00141005, 0x001c1910, 0x00161208, 0x00131107, 0x00101206, 0x000f1007, 0x000d0f05, 0x00101008, 0x00101109, 0x0010110c, 0x000e120f, 0x000b1210, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a221e, 0x001a221e, 0x001c221f, 0x00171d18, 0x000f140b, 0x000d1007, 0x00101006, 0x00131107, 0x0016140b, 0x00121208, 0x00101004, 0x00161408, 0x0023180d, 0x002d1c0f, 0x0030200c, 0x0038270c, 0x00402c0b, 0x004c330f, 0x00543810, 0x00664612, 0x00836111, 0x00b89928, 0x00ccb324, 0x00ccb813, 0x00cbba0c, 0x00c9b80b, 0x00cbb510, 0x00ad8d06, 0x00835a00, 0x006a4401, 0x00543804, 0x00443002, 0x003d2c04, 0x00392606, 0x00352305, 0x00301f04, 0x002a1c05, 0x00221703, 0x001c1404, 0x001c1407, 0x001b130a, 0x001b120c, 0x00181308, 0x00181308, 0x00191108, 0x001a1007, 0x001b1206, 0x00191306, 0x00181306, 0x00181306, 0x00171406, 0x00171406, 0x00191608, 0x00181408, 0x001a1406, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001d1205, 0x001d1205, 0x00201307, 0x00201307, 0x001f1206, 0x00201408, 0x001d1104, 0x001e1306, 0x00201508, 0x001f1408, 0x001f1608, 0x001f150a, 0x001e1409, 0x00180f04, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1306, 0x001f1507, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00201307, 0x00201408, 0x001f1408, 0x00201609, 0x001f1408, 0x00201508, 0x00201508, 0x00201406, 0x00201406, 0x00201305, 0x00201305, 0x001e1407, 0x001e1407, 0x001d1305, 0x001f1408, 0x0021170a, 0x001f1408, 0x001c1104, 0x001d1205, 0x001d1205, 0x001e1205, 0x001e1205, 0x00201408, 0x00221509, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201307, 0x00201408, 0x00201408, 0x001f1408, 0x001e1508, 0x001c1407, 0x001c1407, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1306, 0x00201508, 0x001c1104, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1206, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x00201508, 0x001a1106, 0x001b1105, 0x001c1509, 0x001b1609, 0x001c1509, 0x001c1408, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1106, 0x001c1106, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1207, 0x001c1106, 0x001d1208, 0x001d1408, 0x001c1407, 0x001e1508, 0x00201709, 0x00201608, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x00201508, 0x00201508, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x001f1206, 0x001f1206, 0x001f1206, 0x001f1306, 0x00201307, 0x00201408, 0x00201308, 0x00211308, 0x00211308, 0x00211308, 0x00211308, 0x00201408, 0x00201408, 0x0021140a, 0x0024170a, 0x00261809, 0x002b1909, 0x002e1908, 0x00331a08, 0x00371e06, 0x003b2308, 0x00442b0d, 0x004e300b, 0x00603908, 0x00784a08, 0x00b5882d, 0x00c19824, 0x00c09816, 0x00bd8a0f, 0x00b58008, 0x00af7803, 0x00a77000, 0x00a26800, 0x00a36900, 0x00a46800, 0x00a56a01, 0x00a76c03, 0x00ab7408, 0x00b88416, 0x00c08f20, 0x00c59820, 0x00c9a221, 0x00cca820, 0x00ccac1c, 0x00cbad19, 0x00cab215, 0x00c8b313, 0x00c8b014, 0x00c8a61b, 0x009f7002, 0x00845104, 0x006b3f04, 0x004e2a00, 0x00442409, 0x003c2008, 0x00371e08, 0x00331c08, 0x002f1b08, 0x002b1908, 0x00281809, 0x00221509, 0x00221509, 0x00221509, 0x00201508, 0x001f1508, 0x001e1507, 0x001d1406, 0x001f1407, 0x00221809, 0x00241809, 0x00261a08, 0x00281c07, 0x00291c05, 0x002c1f03, 0x00352605, 0x003f2f09, 0x0048340b, 0x00533d0e, 0x006a4c0e, 0x007e5b0e, 0x00ae8d1e, 0x00c9b41c, 0x00cbb90d, 0x00cbba0c, 0x00cbb90d, 0x00ccb910, 0x00ccb217, 0x00a17c02, 0x007a5200, 0x005f4204, 0x004b3a05, 0x0047340b, 0x00422c0c, 0x003a2808, 0x00332407, 0x002b1d08, 0x00231807, 0x00181003, 0x00141005, 0x0018170d, 0x0018140b, 0x00121006, 0x000f1005, 0x00101108, 0x000f1007, 0x00101109, 0x0010120a, 0x0010110c, 0x000e120d, 0x000b120e, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a221e, 0x001a221e, 0x001d231f, 0x00151a14, 0x000f120a, 0x000f1007, 0x00121107, 0x0017140a, 0x00151308, 0x00101006, 0x00101104, 0x0019160a, 0x00251a0f, 0x002c1c0e, 0x0033210d, 0x0039260a, 0x00422e0b, 0x004b340c, 0x00543a0f, 0x00684710, 0x00896814, 0x00bfa12c, 0x00ccb31f, 0x00ccb810, 0x00cbba09, 0x00cab60c, 0x00cab116, 0x00a68205, 0x007e5500, 0x00654000, 0x00523504, 0x00443004, 0x003b2804, 0x00372204, 0x00321f02, 0x002f1d04, 0x002a1c06, 0x00221804, 0x001c1402, 0x001a1405, 0x00191208, 0x0019110b, 0x00171208, 0x00181207, 0x00181107, 0x00181006, 0x001b1206, 0x00191306, 0x00181306, 0x00181306, 0x00171406, 0x00171406, 0x00181408, 0x00181508, 0x00191306, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001d1205, 0x001e1306, 0x00201508, 0x001f1408, 0x001f1408, 0x001f1409, 0x001f1409, 0x001b1005, 0x001c1005, 0x001c1307, 0x001c1307, 0x001c1306, 0x001f1607, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00201307, 0x00201408, 0x001f1408, 0x00201508, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201406, 0x00201406, 0x00201406, 0x00201406, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x00201609, 0x001f1408, 0x001d1306, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201408, 0x00211409, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1306, 0x00201408, 0x00201408, 0x00201508, 0x001f1608, 0x001c1407, 0x001c1407, 0x001d1306, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001f1409, 0x001f1409, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1206, 0x001d1205, 0x001e1306, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001b1206, 0x001b1206, 0x001c1408, 0x001a1508, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1005, 0x001e1308, 0x001f1508, 0x001c1406, 0x001c1306, 0x001c1407, 0x001d1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00211308, 0x00211308, 0x00211308, 0x00211308, 0x00201408, 0x00201408, 0x0021140a, 0x0024160a, 0x00281709, 0x002b1909, 0x002f1a09, 0x00341b0a, 0x00381e06, 0x003c2409, 0x00462c10, 0x0053320e, 0x005f380c, 0x00703e08, 0x0088540b, 0x00925f02, 0x00945d00, 0x009c5a00, 0x009c5c00, 0x009b5c00, 0x009c6002, 0x00a56c03, 0x00aa7309, 0x00b37c11, 0x00be8c1c, 0x00c2951c, 0x00c8a020, 0x00caa720, 0x00ccac21, 0x00ccb01b, 0x00ccb116, 0x00cbb413, 0x00cbb60f, 0x00c9b70c, 0x00c8b808, 0x00c5b609, 0x00cab414, 0x00c4a014, 0x009e6e04, 0x00835006, 0x00663a03, 0x004d2802, 0x00422509, 0x003b2008, 0x00361d08, 0x00311b08, 0x002f1c0a, 0x00291808, 0x00271709, 0x00221509, 0x00211408, 0x001e1205, 0x001d1205, 0x001d1508, 0x001c1407, 0x001c1408, 0x001c1408, 0x001e1409, 0x00201609, 0x00231808, 0x00251b07, 0x00281d05, 0x002a1f04, 0x00322404, 0x003a2c05, 0x00433108, 0x004e3b0c, 0x0060440c, 0x0075520c, 0x00a07e16, 0x00c9af1f, 0x00ccba10, 0x00ccbb0c, 0x00cbb90d, 0x00ccba0e, 0x00ccb214, 0x00ac880b, 0x007c5400, 0x00604001, 0x004f3b05, 0x00463309, 0x00432b0b, 0x003c280a, 0x00322305, 0x002c1c08, 0x00241805, 0x00191104, 0x00130e04, 0x0017140b, 0x001a150c, 0x00141006, 0x000f1007, 0x000f1007, 0x000f1007, 0x00101009, 0x00101009, 0x000e1008, 0x0010140d, 0x000b120c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231c, 0x001a231c, 0x001d241e, 0x00151a13, 0x000f120a, 0x000f1007, 0x00111006, 0x00141108, 0x00141109, 0x00101007, 0x00111206, 0x001c190e, 0x00281c11, 0x002e1d0f, 0x0033220d, 0x003b280c, 0x00422f0c, 0x004b360d, 0x00573c0f, 0x006c4b10, 0x008c6c16, 0x00c5a830, 0x00cab41d, 0x00ccb90e, 0x00cbbb06, 0x00cbb60c, 0x00c7ac16, 0x009c7702, 0x00785000, 0x00623d02, 0x00503404, 0x00442f07, 0x003a2807, 0x00372205, 0x00331e03, 0x002d1d04, 0x00291d08, 0x00221805, 0x001c1404, 0x00191306, 0x00191208, 0x0019110b, 0x00171208, 0x00171307, 0x00181207, 0x00171106, 0x001b1206, 0x00191306, 0x00181306, 0x00181306, 0x00181406, 0x00171406, 0x00181408, 0x00181508, 0x00191306, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1407, 0x001c1407, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x001d1205, 0x001e1306, 0x00201508, 0x001f1408, 0x001f1408, 0x001f1409, 0x001f1409, 0x001e1308, 0x001b1005, 0x001c1307, 0x001c1307, 0x001c1306, 0x001f1507, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00201307, 0x00201408, 0x001f1408, 0x00201508, 0x001e1407, 0x001f1408, 0x001f1408, 0x00201406, 0x00201406, 0x00201406, 0x00201406, 0x001e1407, 0x001e1407, 0x001d1205, 0x001e1407, 0x00201609, 0x001f1408, 0x001d1306, 0x001e1407, 0x001f1407, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x00201408, 0x001f1306, 0x00201307, 0x00201307, 0x001f1408, 0x001c1407, 0x001c1407, 0x001c1407, 0x001d1306, 0x001d1205, 0x001d1306, 0x001e1407, 0x001e1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1306, 0x001c1305, 0x001c1406, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001b1206, 0x001b1206, 0x001c1408, 0x001a1508, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001c1106, 0x001e1308, 0x001d1207, 0x001c1205, 0x001c1407, 0x001d1408, 0x001c1407, 0x001d1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201307, 0x00201207, 0x00201207, 0x00211308, 0x00211308, 0x00201408, 0x00201408, 0x0021140a, 0x0024160a, 0x00281709, 0x002b1909, 0x00301b0a, 0x00341c0b, 0x00391f09, 0x003e260c, 0x00492f10, 0x00563612, 0x00643d0d, 0x00754408, 0x00865004, 0x00905800, 0x00985f01, 0x00a36608, 0x00aa710e, 0x00b17c14, 0x00ba891a, 0x00bd9218, 0x00c49c1c, 0x00cca925, 0x00ccac24, 0x00ccac1a, 0x00ccaf14, 0x00ccb10f, 0x00ccb50c, 0x00ccb507, 0x00ccb507, 0x00cab709, 0x00c9b80b, 0x00c8b807, 0x00c8b804, 0x00c8b708, 0x00ccb014, 0x00be9710, 0x00986500, 0x00804c04, 0x00623700, 0x004a2501, 0x0042240b, 0x003a2008, 0x00341e08, 0x00301b08, 0x002f1c0b, 0x00281808, 0x00261609, 0x00221509, 0x00201508, 0x001d1306, 0x001c1307, 0x001c1408, 0x00191408, 0x00191407, 0x001b1408, 0x001b1308, 0x001c1408, 0x00201806, 0x00231905, 0x00261d05, 0x00281f02, 0x00312404, 0x00382b05, 0x003e2f04, 0x00493809, 0x005a420c, 0x0070500e, 0x00967311, 0x00c6a81f, 0x00ccb811, 0x00ccbb0c, 0x00cbb90d, 0x00ccb90f, 0x00ccb414, 0x00af8c0c, 0x00805800, 0x00644200, 0x00513c07, 0x00463309, 0x00422a0a, 0x003c280a, 0x00332305, 0x002f1e09, 0x00271a08, 0x001c1507, 0x00140f04, 0x00141206, 0x001b150c, 0x00141006, 0x000f1007, 0x000f1007, 0x000f1007, 0x00101009, 0x00101009, 0x000e1008, 0x0010140c, 0x000b130c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231c, 0x001c221c, 0x001d211c, 0x00141710, 0x0010120a, 0x00101007, 0x00121108, 0x00131008, 0x000e0c03, 0x00131007, 0x00181409, 0x00201a0e, 0x00281c0e, 0x002f1d0c, 0x0034220c, 0x003b280c, 0x0041300d, 0x0049370f, 0x00583c0e, 0x00704c10, 0x00957417, 0x00c9ad2c, 0x00ccb617, 0x00cab909, 0x00ccb905, 0x00ccb80d, 0x00c2a312, 0x00946d00, 0x00744d00, 0x005d3c00, 0x004c3404, 0x00422e07, 0x003a2804, 0x00342302, 0x002e1f04, 0x002b1d06, 0x00281c08, 0x00201706, 0x00191304, 0x00181305, 0x00181207, 0x00161008, 0x00181207, 0x00181207, 0x00181207, 0x00171106, 0x00171106, 0x00171106, 0x00181308, 0x00191208, 0x00181207, 0x00181207, 0x00181308, 0x00191408, 0x001a1408, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001c1407, 0x001c1407, 0x00181304, 0x001b1405, 0x001c1508, 0x001b1204, 0x001d1205, 0x001e1407, 0x001f1307, 0x00211408, 0x00211408, 0x00201307, 0x001f1307, 0x001e1407, 0x001d1306, 0x001e1407, 0x001e1408, 0x001f1409, 0x0020150a, 0x001c1408, 0x00170e02, 0x001c140a, 0x001c140a, 0x001c1408, 0x001d1508, 0x00201408, 0x00211308, 0x00221408, 0x00221408, 0x00221408, 0x00231409, 0x00241409, 0x00241409, 0x00241409, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00211408, 0x00211408, 0x00201508, 0x0022170a, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001d1207, 0x001e1308, 0x001d1307, 0x001f1508, 0x001f1608, 0x001c1406, 0x001c1104, 0x001d1205, 0x001d1205, 0x001f1408, 0x00201609, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1409, 0x001d1207, 0x001c1106, 0x001d1207, 0x001f1408, 0x00201508, 0x00201408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001c1104, 0x001a1003, 0x001b1105, 0x001c1308, 0x001b1206, 0x001b1206, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001d1408, 0x001e1308, 0x001d1208, 0x001c1005, 0x001c1106, 0x001a1105, 0x001a1105, 0x001b1407, 0x00191407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001f1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x00201307, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201507, 0x00211508, 0x00231409, 0x0025170b, 0x0028180a, 0x002c1a0a, 0x00301b0a, 0x00341c0b, 0x003b1f09, 0x0042240e, 0x004b2c10, 0x005c3b11, 0x006c4610, 0x008c5c18, 0x00a4711c, 0x00b4821b, 0x00b98d19, 0x00c49c1d, 0x00cba31f, 0x00cba61b, 0x00ccab19, 0x00ccae16, 0x00ccb014, 0x00ccb112, 0x00cbb310, 0x00cab410, 0x00c9b40d, 0x00ccb40b, 0x00ccb408, 0x00c8b807, 0x00c8b708, 0x00c8b40a, 0x00cab50d, 0x00ccb80e, 0x00ccb508, 0x00cab00c, 0x00ccac1b, 0x00b88910, 0x00915c00, 0x007f4d05, 0x005d3400, 0x00492603, 0x003e2308, 0x00371d06, 0x00341c09, 0x002f1b0a, 0x002c1c09, 0x00251808, 0x00211708, 0x001f1608, 0x001e140b, 0x001c140a, 0x001b1309, 0x00191209, 0x00181207, 0x00181308, 0x00181308, 0x00191408, 0x00191408, 0x001c1608, 0x00211908, 0x00231907, 0x00291e07, 0x00302306, 0x00372a07, 0x003b2d05, 0x0047380c, 0x00553e0d, 0x006c4d10, 0x008a6711, 0x00c2a122, 0x00ccb717, 0x00cbb90d, 0x00cbba0c, 0x00ccb90f, 0x00ccb413, 0x00b7930f, 0x00875e00, 0x00684401, 0x00543c06, 0x00473309, 0x00422b0b, 0x003c2709, 0x00342304, 0x002f1f05, 0x00271a04, 0x001e1604, 0x00151101, 0x00101002, 0x0017160a, 0x00151309, 0x00110f07, 0x000f1007, 0x000f1007, 0x000e1008, 0x000d1008, 0x000e110c, 0x000d130d, 0x000b130c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231b, 0x001c221b, 0x00181d16, 0x0010140b, 0x0010120a, 0x00101007, 0x00121108, 0x00111008, 0x000d0c02, 0x00141006, 0x001c1509, 0x00231b0e, 0x00281c0b, 0x002f1e0a, 0x0034220a, 0x003b2a0c, 0x0041310c, 0x004b3810, 0x005b3e0e, 0x00745111, 0x00a17f1d, 0x00ccb029, 0x00cbb813, 0x00cab908, 0x00ccb905, 0x00ccb40c, 0x00ba9b0f, 0x00886200, 0x006e4900, 0x00563800, 0x00483202, 0x003c2c04, 0x00352402, 0x00322001, 0x002d1e04, 0x00291c08, 0x00271c0a, 0x00201708, 0x00191306, 0x00181305, 0x00181207, 0x00161007, 0x00151108, 0x00151108, 0x00151107, 0x00141007, 0x00141005, 0x00141005, 0x00151106, 0x00181308, 0x00181207, 0x00181207, 0x00181308, 0x00181308, 0x00191308, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001a1507, 0x001a1507, 0x00191405, 0x001a1507, 0x001c1407, 0x001e1508, 0x00201609, 0x001e1407, 0x001d1104, 0x001f1306, 0x00201408, 0x00201307, 0x001f1407, 0x001e1306, 0x001d1306, 0x001e1407, 0x001e1408, 0x001f1409, 0x0020150a, 0x001f150a, 0x00180f03, 0x001b1108, 0x001c1208, 0x001b1407, 0x001c1407, 0x00201408, 0x00211308, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00211308, 0x00211308, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00221408, 0x00211408, 0x00211408, 0x00201508, 0x0022170a, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1207, 0x001c1307, 0x001f1608, 0x001f1608, 0x001c1406, 0x001c1204, 0x001d1205, 0x001d1205, 0x001e1407, 0x00201508, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001f1408, 0x001f1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001e1308, 0x001e1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001c1004, 0x001a1105, 0x001c1308, 0x001b1206, 0x001b1206, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001b1206, 0x001c1307, 0x001a1105, 0x001a1105, 0x001b1407, 0x00191407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001c1408, 0x001c1408, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1207, 0x001d1308, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1305, 0x001c1305, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201307, 0x00201307, 0x00201408, 0x00201408, 0x00201507, 0x00211507, 0x0024150a, 0x0026180b, 0x0028180a, 0x002c190a, 0x00311c0c, 0x00351c0c, 0x003b1f0b, 0x00442610, 0x00502d0f, 0x005c3a0c, 0x00704609, 0x00ad7e2d, 0x00cb9e34, 0x00cca529, 0x00cba820, 0x00ccae18, 0x00ccaf14, 0x00ccb00f, 0x00ccb10c, 0x00ccb209, 0x00ccb309, 0x00ccb408, 0x00ccb608, 0x00c9b808, 0x00cab808, 0x00cbb605, 0x00cab604, 0x00c9b804, 0x00c9b707, 0x00cab409, 0x00cab00a, 0x00cbae10, 0x00caa913, 0x00c59f12, 0x00b78a0e, 0x00a06d04, 0x008b5300, 0x007c4c08, 0x00583000, 0x004a2805, 0x003e2308, 0x00361d06, 0x00311c0a, 0x002d1a0b, 0x00281a08, 0x00231705, 0x00201608, 0x001c1509, 0x001c140c, 0x001c140c, 0x001b130b, 0x00181108, 0x00181008, 0x00181309, 0x0018130a, 0x0019140b, 0x0019140b, 0x001c150b, 0x0021180b, 0x00231809, 0x002a1d0a, 0x00312208, 0x00372a08, 0x00392c05, 0x00423409, 0x00523b0c, 0x00684b12, 0x00846113, 0x00bb9820, 0x00ccb419, 0x00cbb90f, 0x00cbba0c, 0x00ccba0d, 0x00ccb613, 0x00ba970f, 0x008c6000, 0x006b4400, 0x00553a05, 0x00483408, 0x00432b0a, 0x003c2809, 0x00352404, 0x00302007, 0x00281c04, 0x00201604, 0x00161102, 0x00100f01, 0x00141408, 0x0018160e, 0x00121008, 0x00101007, 0x00101108, 0x000d1008, 0x000c1108, 0x000d110c, 0x000d130e, 0x000c130c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231b, 0x001c221b, 0x00131810, 0x00101009, 0x0011110a, 0x00110f07, 0x00121008, 0x00100f06, 0x000e0b02, 0x00141004, 0x001c1608, 0x00231a0c, 0x00291c0a, 0x002f1e06, 0x00352408, 0x003b2b09, 0x0041320b, 0x004c390d, 0x005d3f0d, 0x00795411, 0x00a98822, 0x00caaf22, 0x00cab910, 0x00c8ba08, 0x00cab805, 0x00cbb00c, 0x00b18e0b, 0x00835c00, 0x00694700, 0x00543901, 0x00443003, 0x00382805, 0x00312102, 0x002f1f01, 0x002c1c05, 0x00281b08, 0x00251909, 0x00201709, 0x001b1407, 0x00161205, 0x00151106, 0x00171008, 0x00141008, 0x00121008, 0x00121008, 0x00121008, 0x00141006, 0x00121006, 0x00131006, 0x00151108, 0x00161307, 0x00161307, 0x00181308, 0x00181308, 0x00191308, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x00191306, 0x00191306, 0x00191405, 0x00191405, 0x00191405, 0x001a1507, 0x001c1508, 0x001e1508, 0x001f1408, 0x001f1408, 0x00211408, 0x00211408, 0x00211408, 0x001f1306, 0x001d1105, 0x001e1407, 0x001e1407, 0x00201609, 0x0023180c, 0x0021160c, 0x0020150a, 0x001f160a, 0x00191004, 0x00191006, 0x001a1208, 0x001c1408, 0x001c1407, 0x00201408, 0x00211308, 0x00221408, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00241409, 0x00221509, 0x00201408, 0x00201609, 0x00211609, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1207, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1307, 0x001c1407, 0x001c1407, 0x001c1305, 0x001c1306, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1307, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x001b1406, 0x001b1405, 0x001c1406, 0x001c1407, 0x001c1407, 0x001c1307, 0x001c1307, 0x001a1105, 0x001c1408, 0x001b1206, 0x001b1206, 0x001b1407, 0x00191407, 0x001b1407, 0x001b1405, 0x001b1405, 0x001b1405, 0x001e1409, 0x001c1408, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1207, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001a1306, 0x001a1306, 0x001a1306, 0x001a1306, 0x001b1204, 0x001b1204, 0x001c1305, 0x001c1305, 0x001c1307, 0x001c1307, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00211408, 0x00211408, 0x00201609, 0x00221608, 0x0024150a, 0x0028180b, 0x002c1a0b, 0x002c1a08, 0x00311c0c, 0x0036200d, 0x003b220a, 0x0044270d, 0x00543110, 0x00603b0c, 0x00784d0c, 0x00b88b2b, 0x00cca828, 0x00ccae1b, 0x00cab214, 0x00ccb40c, 0x00ccb40b, 0x00cbb408, 0x00cbb406, 0x00cbb406, 0x00cbb406, 0x00cab405, 0x00cab406, 0x00c9b407, 0x00cab307, 0x00ccb308, 0x00ccb006, 0x00caad08, 0x00cbab0b, 0x00caa70f, 0x00c09807, 0x00b78907, 0x00ac7a04, 0x00a47000, 0x00986100, 0x008f5600, 0x00844e04, 0x0077480b, 0x00512b00, 0x00442402, 0x003c2107, 0x00361d08, 0x00321c0a, 0x002f1d0d, 0x002a1b0a, 0x00231707, 0x00201508, 0x001c1409, 0x001c140a, 0x001b130b, 0x00191209, 0x00191209, 0x0018120a, 0x0018120b, 0x0018120b, 0x0018130c, 0x0019130c, 0x001a140c, 0x001e1409, 0x0022170a, 0x00291c0b, 0x00302108, 0x00342808, 0x00382b06, 0x00403008, 0x0051390c, 0x00644810, 0x00825d13, 0x00b28e1d, 0x00ccb31c, 0x00cab810, 0x00ccbb0b, 0x00ccbb0b, 0x00ccb70e, 0x00bf9d11, 0x00906400, 0x006d4400, 0x00583b04, 0x00493407, 0x00432c08, 0x003e2807, 0x00372403, 0x00322007, 0x002a1c04, 0x00241a08, 0x00171102, 0x000f0e00, 0x00121207, 0x0018160e, 0x0013100a, 0x00101007, 0x00101108, 0x000d1008, 0x000c1108, 0x000c100a, 0x000d110d, 0x000c120c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001a231b, 0x001c221b, 0x0010140d, 0x00101009, 0x00101009, 0x00121008, 0x00121008, 0x000f0d03, 0x00100d02, 0x00171206, 0x001f1808, 0x00241b0a, 0x00291c08, 0x002f1e04, 0x00352406, 0x003c2c09, 0x0042330a, 0x004c390c, 0x005f410d, 0x007e5811, 0x00b49127, 0x00ccb31f, 0x00c9b80b, 0x00c6b906, 0x00cab808, 0x00cbb010, 0x00ac880a, 0x007f5600, 0x00674402, 0x00523a04, 0x00403004, 0x00362907, 0x002f2204, 0x002d1f04, 0x002c1b07, 0x00271908, 0x0024180a, 0x001f160a, 0x001a1307, 0x00151104, 0x00141005, 0x00151007, 0x0015130a, 0x00131008, 0x00121008, 0x00111008, 0x00121008, 0x00121008, 0x00121008, 0x00131008, 0x00151106, 0x00161307, 0x00181308, 0x00181308, 0x00191308, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x00191306, 0x00191306, 0x00191405, 0x00191405, 0x00191405, 0x00191406, 0x001c1407, 0x001c1407, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00211408, 0x001f1206, 0x001e1206, 0x001e1407, 0x001d1205, 0x001f1408, 0x00201609, 0x001f1409, 0x001e1308, 0x0020170c, 0x001c1308, 0x00191006, 0x001b1309, 0x001c1408, 0x001c1407, 0x00201408, 0x00211308, 0x00221408, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00231408, 0x00241409, 0x00241409, 0x00241409, 0x00221509, 0x00201408, 0x00201609, 0x00211609, 0x001d1306, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1207, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1307, 0x001c1407, 0x001c1406, 0x001c1305, 0x001c1306, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x001f1408, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001e1407, 0x001e1407, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001d1307, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1205, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00191405, 0x00191405, 0x001a1406, 0x001a1507, 0x001c1407, 0x001b1407, 0x001b1307, 0x00181105, 0x001c1408, 0x001b1205, 0x001a1105, 0x001c1408, 0x00191407, 0x001b1407, 0x001b1405, 0x001b1405, 0x001b1405, 0x001c1408, 0x001c1307, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1408, 0x001c1308, 0x001c1307, 0x001a1306, 0x00191306, 0x00191306, 0x00191306, 0x00191306, 0x00181306, 0x00181306, 0x00191306, 0x00191306, 0x00191304, 0x00191304, 0x001b1204, 0x001b1204, 0x001c1307, 0x001c1307, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001c1408, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x001f1408, 0x00201408, 0x00201408, 0x00201408, 0x00211408, 0x00201609, 0x00221608, 0x0025170b, 0x0028180b, 0x002c1a0a, 0x002c1a08, 0x00311c0c, 0x0037200e, 0x003d260c, 0x00472c0d, 0x00583411, 0x00694011, 0x00845915, 0x00bf952e, 0x00ccac20, 0x00cab310, 0x00c7b50c, 0x00c9b708, 0x00c9b707, 0x00c8b606, 0x00cab507, 0x00cab408, 0x00cab408, 0x00cab20a, 0x00ccb10d, 0x00ccb00f, 0x00ccaa0d, 0x00caa50c, 0x00c69c08, 0x00c09007, 0x00b48001, 0x00ad7500, 0x00a56900, 0x00a46401, 0x00a26101, 0x009f6001, 0x00985804, 0x008a4c01, 0x00824c0a, 0x006f400b, 0x004d2800, 0x00462605, 0x003c2008, 0x00361d08, 0x00301a08, 0x002d1b0b, 0x00281908, 0x00221606, 0x00201508, 0x001c140a, 0x001b1308, 0x00191209, 0x00181109, 0x0018100a, 0x00181009, 0x0018110a, 0x0018110b, 0x0018120c, 0x0019130e, 0x001a130c, 0x001c140a, 0x0022170c, 0x0027190a, 0x002f2009, 0x00332508, 0x00382a08, 0x00403009, 0x004f380b, 0x00614410, 0x007d5813, 0x00ac881d, 0x00cbb120, 0x00cab812, 0x00ccbb0c, 0x00ccbc09, 0x00ccb90e, 0x00c1a312, 0x00936801, 0x006f4400, 0x00583b02, 0x004b3507, 0x00442d06, 0x003f2906, 0x00382403, 0x00342008, 0x002c1c05, 0x00251a08, 0x00181103, 0x00111004, 0x000f1004, 0x0017140c, 0x0015130c, 0x000f0f05, 0x000d0f05, 0x000d1008, 0x000c1108, 0x000b100a, 0x000d110d, 0x000c120c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00192219, 0x001a2018, 0x000f120c, 0x00101009, 0x00111009, 0x00141109, 0x00141109, 0x00100e04, 0x00120f04, 0x00181406, 0x00201808, 0x00241c07, 0x00291e06, 0x002e1d04, 0x00342305, 0x003c2c06, 0x00423408, 0x004e3b0b, 0x00654710, 0x00805910, 0x00ba992b, 0x00ccb41c, 0x00cab90a, 0x00c8bb09, 0x00cab80a, 0x00cab112, 0x00a48008, 0x007a5101, 0x00623f04, 0x00503806, 0x00413006, 0x00362708, 0x002d2104, 0x002b1f05, 0x002b1a08, 0x0027190a, 0x0024180b, 0x001f150a, 0x00181308, 0x00141005, 0x00141107, 0x00131008, 0x0017140d, 0x0014110a, 0x00100d06, 0x000f0e06, 0x00121008, 0x00131008, 0x00131007, 0x00131108, 0x00141208, 0x00151208, 0x00171208, 0x00181207, 0x00191207, 0x001a1306, 0x001a1306, 0x001b1407, 0x001b1407, 0x001c1307, 0x001c1307, 0x001b1307, 0x001b1307, 0x001b1406, 0x001a1406, 0x001a1406, 0x001a1406, 0x001b1405, 0x001c1305, 0x001e1407, 0x001e1407, 0x001d1104, 0x00201408, 0x00201408, 0x00201408, 0x001f1407, 0x001f1408, 0x001e1407, 0x001d1205, 0x001e1408, 0x001d1206, 0x001d1206, 0x0020160a, 0x001d1308, 0x001a1005, 0x001a1308, 0x001b1408, 0x001c1407, 0x00201509, 0x00221408, 0x00221408, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00211408, 0x00221408, 0x00231509, 0x00231509, 0x00231509, 0x00221509, 0x001f1306, 0x00201408, 0x001f1408, 0x001f1407, 0x001c1104, 0x001c1104, 0x001d1205, 0x001d1205, 0x001d1205, 0x001d1205, 0x001c1307, 0x001c1307, 0x001c1206, 0x001b1106, 0x001c1206, 0x001b1407, 0x001c1407, 0x001c1306, 0x001c1307, 0x001d1407, 0x001d1407, 0x001d1306, 0x001d1306, 0x001e1407, 0x001d1305, 0x001e1407, 0x001e1407, 0x001d1205, 0x001d1205, 0x001d1306, 0x001d1306, 0x001d1207, 0x001d1208, 0x001d1207, 0x001d1207, 0x001c1106, 0x001b1005, 0x001c1005, 0x001c1106, 0x001c1106, 0x001d1206, 0x001d1206, 0x001d1206, 0x001d1307, 0x001e1308, 0x001e1308, 0x001c1105, 0x001c1105, 0x001a1105, 0x001a1105, 0x001a1105, 0x001a1105, 0x00191105, 0x00191105, 0x00191105, 0x001a1206, 0x001b1306, 0x001b1407, 0x001b1407, 0x001b1407, 0x001a1406, 0x00191306, 0x00191306, 0x00181004, 0x00191306, 0x00191105, 0x00181105, 0x001c1408, 0x001a1405, 0x001b1406, 0x001c1406, 0x001c1406, 0x001c1406, 0x001c1408, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1308, 0x001c1307, 0x001c1307, 0x001a1306, 0x00191306, 0x00191306, 0x001a1306, 0x001a1306, 0x00191407, 0x001b1408, 0x001b1408, 0x001b1408, 0x001c1408, 0x001c1408, 0x001c1308, 0x001c1308, 0x001c1408, 0x001c1408, 0x001e1409, 0x001c1408, 0x001c1408, 0x001c1307, 0x001c1307, 0x001c1307, 0x001d1207, 0x001d1207, 0x001d1208, 0x001d1208, 0x001e1308, 0x001e1408, 0x001f1408, 0x001f1409, 0x001f1408, 0x001f1407, 0x001f1407, 0x001f1408, 0x00201509, 0x0021170a, 0x00231609, 0x0028190c, 0x002b1b0c, 0x002e1c0d, 0x00301c0b, 0x00331c0b, 0x0038200d, 0x003e270c, 0x00482d0e, 0x005a3513, 0x006d4414, 0x008c6214, 0x00c49c28, 0x00ccae18, 0x00cbb209, 0x00cab408, 0x00cbb608, 0x00cbb70b, 0x00cbb408, 0x00ccb208, 0x00ccb00e, 0x00ccac10, 0x00cca814, 0x00c7a010, 0x00c0940c, 0x00b58604, 0x00b17c01, 0x00ac7200, 0x00a66800, 0x00a66700, 0x00a66601, 0x00a76805, 0x00ab6d09, 0x00b57a11, 0x00be8418, 0x00b47918, 0x00915707, 0x00824d0b, 0x00683a06, 0x004c2700, 0x00422404, 0x003a2008, 0x00351c07, 0x002e1b08, 0x002b1809, 0x00281808, 0x00241707, 0x001e1405, 0x001b1206, 0x00191208, 0x00181208, 0x00181009, 0x0018100a, 0x0017100a, 0x00161009, 0x00171009, 0x0018110b, 0x0018120c, 0x0018120b, 0x001a1208, 0x001e1408, 0x00271b0c, 0x002e2008, 0x00322408, 0x00382808, 0x003f2f08, 0x004d360b, 0x005e400f, 0x007a5412, 0x00a5801b, 0x00caaf24, 0x00cbb615, 0x00ccbb0c, 0x00ccbb0a, 0x00ccba0f, 0x00c4a614, 0x00996e04, 0x00704400, 0x00593901, 0x004b3606, 0x00442e06, 0x003f2906, 0x00382404, 0x00342106, 0x002e1c05, 0x00281b0a, 0x001a1404, 0x00111005, 0x000d0c03, 0x0014140c, 0x0014130a, 0x00101007, 0x000e0f05, 0x000d1008, 0x000d1009, 0x000c0f09, 0x000c100c, 0x000c110c, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x001c251c, 0x00151c14, 0x000f110b, 0x00101009, 0x0013110b, 0x00141109, 0x00121008, 0x000f0c04, 0x00141007, 0x001b1708, 0x00211a07, 0x00251d05, 0x002a1f06, 0x00312008, 0x00372608, 0x003c2d06, 0x00433408, 0x004c3808, 0x0064440c, 0x00856013, 0x00c09f2e, 0x00ccb41c, 0x00cbba0c, 0x00c9bc0b, 0x00cbb80d, 0x00c8b011, 0x00a07c03, 0x00784f02, 0x00603e07, 0x004e3808, 0x00402f06, 0x00382608, 0x002e2105, 0x00291d06, 0x002a1909, 0x0026180b, 0x0022160a, 0x001d1409, 0x00181308, 0x00141004, 0x00101006, 0x000f1007, 0x00100f08, 0x00110e08, 0x0013100a, 0x0011100a, 0x00121007, 0x00110f07, 0x00131107, 0x00131107, 0x00131107, 0x00141107, 0x00171208, 0x00181107, 0x00181207, 0x00191306, 0x001a1306, 0x001b1407, 0x001b1407, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1407, 0x001b1405, 0x001c1305, 0x001e1407, 0x001e1407, 0x001e1205, 0x0023160a, 0x00201408, 0x00201408, 0x00201408, 0x001f1408, 0x001f1408, 0x001e1407, 0x001e1407, 0x00201508, 0x00201508, 0x0020150a, 0x001f1409, 0x00170e03, 0x00171004, 0x001b1508, 0x001d1407, 0x00201307, 0x00211308, 0x00211308, 0x00211408, 0x00221408, 0x00221408, 0x00221408, 0x00221408, 0x00211408, 0x00211408, 0x00211408, 0x00221509, 0x00211408, 0x00211408, 0x00201408, 0x00221509, 0x00221509, 0x00201609, 0x00201508, 0x001d1305, 0x001d1305, 0x001d1306, 0x001e1306, 0x001d1306, 0x001d1306, 0x001c1308, 0x001c1308, 0x001b1206, 0x001b1206, 0x001a1306, 0x001b1407, 0x001c1408, 0x001c1308, 0x001c1408, 0x001d1407, 0x001d1407, 0x001d1306, 0x001d1306, 0x001d1306, 0x001d1306, 0x001e1407, 0x001e1407, 0x001d1306, 0x001d1306, 0x001d1306, 0x001d1306, 0x001d1208, 0x001d1208, 0x001d1207, 0x001d1207, 0x001d1208, 0x001e1308, 0x001f1409, 0x001f1409, 0x001f1409, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001c1106, 0x001c1106, 0x001c1106, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001a1306, 0x001b1407, 0x001b1408, 0x001c1408, 0x001c1408, 0x001b1408, 0x001a1306, 0x00191206, 0x001b1408, 0x00181105, 0x00181004, 0x001c1509, 0x001a1304, 0x001c1406, 0x001c1407, 0x001c1407, 0x001c1407, 0x001c1408, 0x001c1408, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001b1206, 0x001c1307, 0x001c1307, 0x001c1307, 0x001c1307, 0x001b1206, 0x001b1206, 0x001a1306, 0x00191306, 0x00191306, 0x00191306, 0x00191206, 0x00181105, 0x00181105, 0x00181105, 0x00181105, 0x001b1206, 0x001b1206, 0x001a1105, 0x001a1105, 0x001a1105, 0x001a1105, 0x001b1206, 0x001c1307, 0x001c1307, 0x001e1409, 0x001e1409, 0x001f150a, 0x001f1409, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001e1308, 0x001d1207, 0x001c1106, 0x001d1207, 0x001d1205, 0x001e1407, 0x001e1407, 0x00201609, 0x0022170a, 0x00221509, 0x00241608, 0x00281809, 0x002e1a0b, 0x002f1a09, 0x00331c0b, 0x0039200d, 0x003f270c, 0x00492c0e, 0x005c3814, 0x00714617, 0x00936618, 0x00c7a02b, 0x00ccac19, 0x00ccae0e, 0x00cbad0f, 0x00caa912, 0x00c8a70f, 0x00c8a20c, 0x00c39b08, 0x00ba8f07, 0x00b18303, 0x00ac7801, 0x00a67100, 0x00a36c00, 0x00a36a01, 0x00a36702, 0x00a76804, 0x00ab6d08, 0x00b0770f, 0x00b98417, 0x00c2901d, 0x00c89c24, 0x00cca324, 0x00cca421, 0x00bd8c17, 0x00925e04, 0x00804c08, 0x00643804, 0x004a2700, 0x00402202, 0x00371d04, 0x00301a04, 0x00301c08, 0x002a1909, 0x00261704, 0x00231504, 0x001f1305, 0x001b1106, 0x00191208, 0x00181308, 0x0017110a, 0x0017100b, 0x0017100b, 0x0017110a, 0x0017110a, 0x0017110a, 0x0018120c, 0x0017130b, 0x001a1308, 0x001c1408, 0x00291d0d, 0x002e2008, 0x00312407, 0x00382807, 0x003f2f08, 0x004e360c, 0x005c3f0e, 0x00785213, 0x00a27c1a, 0x00c9ad26, 0x00ccb717, 0x00ccbb0d, 0x00ccbb0d, 0x00cbba10, 0x00c4a813, 0x009d7005, 0x00744800, 0x00593c03, 0x004b3508, 0x00442e06, 0x003f2906, 0x00382405, 0x00342006, 0x00301c05, 0x002a1c0c, 0x001f1809, 0x00101005, 0x000d0c04, 0x0014130c, 0x0014130a, 0x00101007, 0x00101007, 0x000f1008, 0x000e110a, 0x000e100c, 0x000e110d, 0x000e130e, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00222922, 0x001b2018, 0x00151811, 0x00171610, 0x001a1812, 0x001c1810, 0x0017140c, 0x0016130b, 0x001e1910, 0x00231d10, 0x0027200d, 0x002c210b, 0x0030250c, 0x00382810, 0x003d2c0f, 0x0044350f, 0x004c3c10, 0x00554011, 0x006b4c13, 0x00906b1c, 0x00c5a534, 0x00ccb41e, 0x00cbbb0d, 0x00c9bb0c, 0x00cbb80f, 0x00c8ae11, 0x009e7901, 0x007b5004, 0x00624008, 0x00513c0d, 0x0045330b, 0x00402c0e, 0x0035280d, 0x0030240c, 0x002d1c0d, 0x00281b0e, 0x0025180d, 0x0020180c, 0x001e180d, 0x0019160b, 0x0016150b, 0x0014160c, 0x0016150e, 0x001b1812, 0x0017140e, 0x0015140e, 0x0018160d, 0x0018160e, 0x0018160c, 0x0019170d, 0x0018180d, 0x001a170d, 0x001d180e, 0x001f180e, 0x0020180d, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0021180c, 0x0021180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020180c, 0x0020190b, 0x00221a0c, 0x00241a0e, 0x00241a0e, 0x0025190d, 0x002a1e12, 0x00281b0f, 0x0025180c, 0x0024180c, 0x0024190d, 0x0024190c, 0x0024180c, 0x0024190c, 0x00271c10, 0x00281d10, 0x00281d12, 0x00281d12, 0x0020170c, 0x0020190c, 0x0020190d, 0x00231a0c, 0x00251a0d, 0x00281a0f, 0x0027190d, 0x0026190d, 0x0026180c, 0x0027180c, 0x0027180c, 0x0027180d, 0x0026190d, 0x00261a0e, 0x00281b0f, 0x00281b10, 0x00271a0e, 0x00281b0f, 0x00281b10, 0x00271a0e, 0x0025190d, 0x0024180c, 0x0024180c, 0x00251a0d, 0x0024190c, 0x0024190c, 0x0023180c, 0x0024190c, 0x0024190c, 0x00231a0e, 0x00231a0e, 0x0022190d, 0x0022190d, 0x0021190d, 0x0020190d, 0x0021190e, 0x0022190e, 0x0022190d, 0x00231a0d, 0x00241a0d, 0x0024190c, 0x0024190c, 0x0024190c, 0x0024190c, 0x00251b0e, 0x00251b0f, 0x00251b0e, 0x00261c0f, 0x00251b0e, 0x00251b0e, 0x00251a10, 0x00251a10, 0x0024190f, 0x0024190f, 0x0024190f, 0x0024180e, 0x0024190f, 0x0024190f, 0x0024190f, 0x0024190f, 0x0024190e, 0x0024190e, 0x0024190e, 0x0024190e, 0x0024190e, 0x0022180c, 0x0022180c, 0x0021180d, 0x0021180d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0021180d, 0x0022190d, 0x00221a0e, 0x00221b0f, 0x00211a0e, 0x0020190e, 0x00211a0e, 0x00211a0e, 0x00211a0e, 0x00211a0f, 0x00231c10, 0x0020190d, 0x00201a0e, 0x00241c11, 0x00231c0f, 0x00221b0d, 0x0020190a, 0x00211a0c, 0x00221b0c, 0x00231a0e, 0x00231a0e, 0x00221a0e, 0x0022190e, 0x0022190e, 0x0022190e, 0x0022190e, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190d, 0x0022190e, 0x0022190e, 0x0022190e, 0x0022190e, 0x0021180d, 0x0021180d, 0x0020190d, 0x0020190d, 0x0020190d, 0x0020190d, 0x0020190d, 0x0020190d, 0x00201a0e, 0x00201a0e, 0x00211a0e, 0x00231a0f, 0x00231a0f, 0x0022190e, 0x0022190e, 0x0022190e, 0x0022190e, 0x00231a0f, 0x00231a0e, 0x00231a10, 0x00231a0f, 0x00221a0f, 0x00221a0f, 0x0024190f, 0x0024190f, 0x0024190f, 0x0024190e, 0x0024190e, 0x0024180e, 0x0024180e, 0x0024190e, 0x0024190e, 0x00251c0f, 0x00251c0f, 0x00241a0d, 0x00261c10, 0x00271c10, 0x00281b10, 0x002c1e10, 0x00302010, 0x00342112, 0x0036210f, 0x00382110, 0x003d2512, 0x00442c12, 0x004e3113, 0x00623d1b, 0x00744819, 0x0092641b, 0x00c4982e, 0x00c39c17, 0x00bf9a0b, 0x00b89208, 0x00b08506, 0x00aa7d02, 0x00a47400, 0x009f6c00, 0x009c6800, 0x009c6601, 0x00a16704, 0x00a46709, 0x00ac6c14, 0x00b3741b, 0x00ba7c21, 0x00c48928, 0x00c6942a, 0x00c89d2b, 0x00cca42a, 0x00cca827, 0x00ccac22, 0x00cbad1c, 0x00ccad1b, 0x00b99210, 0x008f6000, 0x007f4e08, 0x00623804, 0x004c2c04, 0x00432606, 0x003e240c, 0x0038220c, 0x0034210f, 0x00301e0f, 0x002c1d0b, 0x00291c0c, 0x0024180b, 0x0021180c, 0x0020180d, 0x001f190e, 0x001f1811, 0x001f1812, 0x001e1811, 0x001d1810, 0x001e1811, 0x001f1811, 0x001f1812, 0x001e1911, 0x0020180f, 0x0022180d, 0x002e2313, 0x0032240d, 0x0034280b, 0x003c2c0b, 0x0044320c, 0x00513a11, 0x00604212, 0x00785212, 0x00a37c1b, 0x00c8ac25, 0x00ccb719, 0x00ccbb0f, 0x00ccbb0e, 0x00cbba10, 0x00c6a814, 0x00a27508, 0x007b4e04, 0x005f400b, 0x00503b0e, 0x0049330c, 0x00442e0d, 0x003f2a0c, 0x003b270d, 0x0036220c, 0x00302111, 0x00261e10, 0x0017160c, 0x0014130c, 0x00191811, 0x001b1b11, 0x00191810, 0x0017170e, 0x0014160e, 0x00141610, 0x00141510, 0x00131611, 0x00141813, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07, 0x00060c07}; \ No newline at end of file diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index d55125a..2c0bbba 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -9,7 +9,7 @@ #include "../core/include/utils/pid.h" #include "../core/include/utils/feedback_base.h" #include "../core/include/robot_specs.h" -#include "../core/src/utils/pure_pursuit.cpp" +#include "../core/include/utils/pure_pursuit.h" #include @@ -47,7 +47,7 @@ class TankDrive * @param power modifies the input velocities left^power, right^power * @param isdriver default false. if true uses motor percentage. if false uses plain percentage of maximum voltage */ - void drive_tank(double left, double right, int power=1, bool isdriver=false); + void drive_tank(double left, double right, int power=1); /** * Drive the robot using arcade style controls. forward_back controls the linear motion, @@ -165,18 +165,8 @@ class TankDrive */ static double modify_inputs(double input, int power=2); - /** - * Follow a hermite curve using the pure pursuit algorithm. - * - * @param path The hermite curve for the robot to take. Must have 2 or more points. - * @param dir Whether the robot should move forward or backwards - * @param radius How the pure pursuit radius, in inches, for finding the lookahead point - * @param res The number of points to use along the path; the hermite curve is split up into "res" individual points. - * @param feedback The feedback controller to use - * @param max_speed Robot's maximum speed throughout the path, between 0 and 1.0 - * @return true when we reach the end of the path - */ - bool pure_pursuit(std::vector path, directionType dir, double radius, double res, Feedback &feedback, double max_speed=1); + + bool pure_pursuit(std::vector path, directionType dir, double radius, Feedback &feedback, double max_speed=1); private: motor_group &left_motors; ///< left drive motors diff --git a/include/utils/geometry.h b/include/utils/geometry.h index 5730e6d..b653031 100644 --- a/include/utils/geometry.h +++ b/include/utils/geometry.h @@ -44,6 +44,11 @@ struct point_t .y = this->y - other.y}; return p; } + + bool operator==(const point_t& rhs) + { + return x==rhs.x && y==rhs.y; + } }; @@ -55,4 +60,9 @@ typedef struct double x; ///< x position in the world double y; ///< y position in the world double rot; ///< rotation in the world + + point_t get_point() + { + return point_t{.x=x, .y=y}; + } } pose_t; \ No newline at end of file diff --git a/include/utils/math_util.h b/include/utils/math_util.h index 71fbe30..4ec27c9 100644 --- a/include/utils/math_util.h +++ b/include/utils/math_util.h @@ -1,7 +1,9 @@ #pragma once +#include #include "math.h" #include "vex.h" -#include +#include "../core/include/utils/geometry.h" + /** * Constrain the input between a minimum and a maximum value @@ -54,3 +56,4 @@ Calculates the slope and y intercept of the line of best fit for the data */ std::pair calculate_linear_regression(std::vector> const &points); +double estimate_path_length(std::vector points); \ No newline at end of file diff --git a/include/utils/moving_average.h b/include/utils/moving_average.h index 07acc79..39bb9a0 100644 --- a/include/utils/moving_average.h +++ b/include/utils/moving_average.h @@ -1,3 +1,4 @@ +#pragma once #include /** diff --git a/include/utils/pure_pursuit.h b/include/utils/pure_pursuit.h index f3f427c..66cd15a 100644 --- a/include/utils/pure_pursuit.h +++ b/include/utils/pure_pursuit.h @@ -44,16 +44,16 @@ namespace PurePursuit { * Returns points of the intersections of a line segment and a circle. The line * segment is defined by two points, and the circle is defined by a center and radius. */ - static std::vector line_circle_intersections(point_t center, double r, point_t point1, point_t point2); + extern std::vector line_circle_intersections(point_t center, double r, point_t point1, point_t point2); /** * Selects a look ahead from all the intersections in the path. */ - static point_t get_lookahead(std::vector path, point_t robot_loc, double radius); + extern point_t get_lookahead(std::vector path, pose_t robot_loc, double radius); /** * Injects points in a path without changing the curvature with a certain spacing. */ - static std::vector inject_path(std::vector path, double spacing); + extern std::vector inject_path(std::vector path, double spacing); /** * Returns a smoothed path maintaining the start and end of the path. @@ -66,9 +66,9 @@ namespace PurePursuit { * https://medium.com/@jaems33/understanding-robot-motion-path-smoothing-5970c8363bc4 */ - static std::vector smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance); + extern std::vector smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance); - static std::vector smooth_path_cubic(std::vector path, double res); + extern std::vector smooth_path_cubic(std::vector path, double res); /** * Interpolates a smooth path given a list of waypoints using hermite splines. @@ -78,5 +78,18 @@ namespace PurePursuit { * @param steps The number of points interpolated between points. * @return The smoothed path. */ - static std::vector smooth_path_hermite(std::vector path, double step); + extern std::vector smooth_path_hermite(std::vector path, double step); + + /** + * Estimates the remaining distance from the robot's position to the end, + * by "searching" for the robot along the path and running a "connect the dots" + * distance algoritm + * + * @param path The pure pursuit path the robot is following + * @param robot_pose The robot's current position + * @param radius Pure pursuit "radius", used to search for the robot along the path + * @return A rough estimate of the remaining distance + */ + extern double estimate_remaining_dist(std::vector path, pose_t robot_pose, double radius); + } \ No newline at end of file diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index fad0728..15a650a 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -22,6 +22,7 @@ OdometryBase::OdometryBase(bool is_async) : current_pos(zero_pos) int OdometryBase::background_task(void* ptr) { OdometryBase &obj = *((OdometryBase*) ptr); + vexDelay(1000); while(!obj.end_task) { obj.mut.lock(); diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 92c613b..4fd7fc6 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -1,6 +1,7 @@ #include "../core/include/utils/geometry.h" #include "../core/include/subsystems/tank_drive.h" #include "../core/include/utils/math_util.h" +#include "../core/include/utils/pidff.h" TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom) : left_motors(left_motors), right_motors(right_motors), correction_pid(config.correction_pid), odometry(odom), config(config) @@ -32,20 +33,13 @@ void TankDrive::stop() * * left_motors and right_motors are in "percent": -1.0 -> 1.0 */ -void TankDrive::drive_tank(double left, double right, int power, bool isdriver) +void TankDrive::drive_tank(double left, double right, int power) { left = modify_inputs(left, power); right = modify_inputs(right, power); - if(isdriver == false) - { - left_motors.spin(directionType::fwd, left * 12, voltageUnits::volt); - right_motors.spin(directionType::fwd, right * 12, voltageUnits::volt); - }else - { - left_motors.spin(directionType::fwd, left * 100.0, percentUnits::pct); - right_motors.spin(directionType::fwd, right * 100.0, percentUnits::pct); - } + left_motors.spin(directionType::fwd, left * 12, voltageUnits::volt); + right_motors.spin(directionType::fwd, right * 12, voltageUnits::volt); } /** @@ -409,23 +403,69 @@ double TankDrive::modify_inputs(double input, int power) return sign(input)* pow(std::abs(input), power); } -bool TankDrive::pure_pursuit(std::vector path, directionType dir, double radius, double res, Feedback &feedback, double max_speed) +// TODO forwards & backwards +bool TankDrive::pure_pursuit(std::vector path, directionType dir, double radius, Feedback &feedback, double max_speed) { - is_pure_pursuit = true; - std::vector smoothed_path = PurePursuit::smooth_path_hermite(path, res); + pose_t robot_pose = odometry->get_position(); + static pose_t start_pos; + // static PID::pid_config_t pid_cfg = { + // .p=.1 + // }; + // static FeedForward::ff_config_t ff_cfg = { + + // }; + // static PIDFF pid(pid_cfg, ff_cfg); + + if(!func_initialized) + { + feedback.init(-estimate_path_length(path), 0); + start_pos = robot_pose; + func_initialized = true; + } + + point_t lookahead = PurePursuit::get_lookahead(path, odometry->get_position(), radius); + point_t localized = lookahead - robot_pose.get_point(); + + point_t last_point = path[path.size()-1]; + bool is_last_point = (lookahead == last_point); + + double correction = 0; + double dist_remaining = PurePursuit::estimate_remaining_dist(path, robot_pose, radius); + double angle_diff = OdometryBase::smallest_angle(robot_pose.rot, rad2deg(atan2(localized.y, localized.x))); + + // Correct the robot's heading until the last cut-off + if(!(is_last_point && robot_pose.get_point().dist(last_point) < config.drive_correction_cutoff)) + { + correction_pid.update(angle_diff); + correction = correction_pid.get(); + } else // Inside cut-off radius, ignore horizontal diffs + { + dist_remaining *= cos(angle_diff * (PI / 180.0)); + } + + feedback.update(-dist_remaining); - point_t lookahead = PurePursuit::get_lookahead(smoothed_path, {odometry->get_position().x, odometry->get_position().y}, radius); - //printf("%f\t%f\n", odometry->get_position().x, odometry->get_position().y); - //printf("%f\t%f\n", lookahead.x, lookahead.y); - bool is_last_point = (path.back().x == lookahead.x) && (path.back().y == lookahead.y); + max_speed = fabs(max_speed); - if(is_last_point) - is_pure_pursuit = false; + double left = clamp(feedback.get(), -max_speed, max_speed); + double right = clamp(feedback.get(), -max_speed, max_speed); - bool retval = drive_to_point(lookahead.x, lookahead.y, dir, feedback, max_speed); + left += correction; + right -= correction; + + // left = clamp(left + correction, -max_speed, max_speed); + // right = clamp(right - correction, -max_speed, max_speed); + + // printf("x:%f, y:%f, rot:%f, d:%f, c:%f l:%f, r:%f\n", robot_pose.x, robot_pose.y, robot_pose.rot, dist_remaining, correction, left, right); - if(is_last_point) - return retval; + drive_tank(left, right); + // When the robot has reached the end point and feedback reports on target, end pure pursuit + if(is_last_point && feedback.is_on_target()) + { + func_initialized = false; + stop(); + return true; + } return false; } diff --git a/src/utils/math_util.cpp b/src/utils/math_util.cpp index 4ab2406..494f9d4 100644 --- a/src/utils/math_util.cpp +++ b/src/utils/math_util.cpp @@ -117,3 +117,23 @@ std::pair calculate_linear_regression(std::vector(slope, y_intercept); } + + +double estimate_path_length(std::vector points) +{ + double dist = 0; + + for(point_t p : points) + { + static point_t last_p = p; + + // Ignore the first point + if(p == last_p) + continue; + + dist += p.dist(last_p); + last_p = p; + } + + return dist; +} \ No newline at end of file diff --git a/src/utils/pidff.cpp b/src/utils/pidff.cpp index 7d1df2a..616caec 100644 --- a/src/utils/pidff.cpp +++ b/src/utils/pidff.cpp @@ -35,7 +35,9 @@ double PIDFF::update(double val) { double pid_out = pid.update(val); double ff_out = ff_cfg.kS * sign(pid_out); - out = clamp(pid_out + ff_out, lower_lim, upper_lim); + out = pid_out + ff_out; + if (lower_lim != upper_lim) + out = clamp(out, lower_lim, upper_lim); return out; } @@ -53,7 +55,9 @@ double PIDFF::update(double val, double vel_setpt, double a_setpt) double pid_out = pid.update(val); double ff_out = ff.calculate(vel_setpt, a_setpt); - out = clamp(ff_out + pid_out, lower_lim, upper_lim); + out = pid_out + ff_out; + if (lower_lim != upper_lim) + out = clamp(out, lower_lim, upper_lim); return out; } diff --git a/src/utils/pure_pursuit.cpp b/src/utils/pure_pursuit.cpp index 78e1740..dfdbc9c 100644 --- a/src/utils/pure_pursuit.cpp +++ b/src/utils/pure_pursuit.cpp @@ -52,13 +52,13 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub /** * Selects a look ahead from all the intersections in the path. */ -[[maybe_unused]] point_t PurePursuit::get_lookahead(std::vector path, point_t robot_loc, double radius) +[[maybe_unused]] point_t PurePursuit::get_lookahead(std::vector path, pose_t robot_loc, double radius) { //Default: the end of the path point_t target = path.back(); - - if(target.dist(robot_loc) <= radius) + + if(target.dist(robot_loc.get_point()) <= radius) { return target; } @@ -69,7 +69,7 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub point_t start = path[i]; point_t end = path[i+1]; - std::vector intersections = line_circle_intersections(robot_loc, radius, start, end); + std::vector intersections = line_circle_intersections(robot_loc.get_point(), radius, start, end); //Choose the intersection that is closest to the end of the line segment //This prioritizes the closest intersection to the end of the path for(point_t intersection: intersections) @@ -234,3 +234,45 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub return new_path; } + +/** + * Estimates the remaining distance from the robot's position to the end, + * by "searching" for the robot along the path and running a "connect the dots" + * distance algoritm + * + * @param path The pure pursuit path the robot is following + * @param robot_pose The robot's current position + * @param radius Pure pursuit "radius", used to search for the robot along the path + * @return A rough estimate of the remaining distance +*/ +double PurePursuit::estimate_remaining_dist(std::vector path, pose_t robot_pose, double radius) +{ + point_t lookahead_pt = get_lookahead(path, robot_pose, radius); + + if (lookahead_pt == path[path.size() - 1]) + return robot_pose.get_point().dist(lookahead_pt); + + double dist = 0; + + // Run through the path backwards, adding distances + for(int i = path.size()-1; i >= 0; i--) + { + // Test if the robot is between the two points + auto pts = line_circle_intersections(robot_pose.get_point(), radius, path[i-1], path[i]); + + // There is an intersection? Robot is between the points so add the distance + // from the bot to the next point and end. + if(!pts.empty()) + { + dist += robot_pose.get_point().dist(path[i]); + return dist; + } + + // No intersections? Add the distance between the two points and move backwards + // in the path until we find the robot, or run out of points. + dist += path[i-1].dist(path[i]); + } + + return dist; +} + From f0f89dfddba7c07ab088beb884f52b02842fed24 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 24 Sep 2023 17:26:54 -0400 Subject: [PATCH 222/243] Now supports backwards driving --- src/subsystems/tank_drive.cpp | 26 ++++++++++++++++---------- 1 file changed, 16 insertions(+), 10 deletions(-) diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 4fd7fc6..431e457 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -408,17 +408,14 @@ bool TankDrive::pure_pursuit(std::vector path, directionType dir, doubl { pose_t robot_pose = odometry->get_position(); static pose_t start_pos; - // static PID::pid_config_t pid_cfg = { - // .p=.1 - // }; - // static FeedForward::ff_config_t ff_cfg = { - - // }; - // static PIDFF pid(pid_cfg, ff_cfg); if(!func_initialized) { - feedback.init(-estimate_path_length(path), 0); + if(dir != directionType::rev) + feedback.init(-estimate_path_length(path), 0); + else + feedback.init(estimate_path_length(path), 0); + start_pos = robot_pose; func_initialized = true; } @@ -431,8 +428,14 @@ bool TankDrive::pure_pursuit(std::vector path, directionType dir, doubl double correction = 0; double dist_remaining = PurePursuit::estimate_remaining_dist(path, robot_pose, radius); - double angle_diff = OdometryBase::smallest_angle(robot_pose.rot, rad2deg(atan2(localized.y, localized.x))); + double angle_diff = 0; + // Robot is facing forwards / backwards, change the bot's angle by 180 + if(dir != directionType::rev) + angle_diff = OdometryBase::smallest_angle(robot_pose.rot, rad2deg(atan2(localized.y, localized.x))); + else + angle_diff = OdometryBase::smallest_angle(robot_pose.rot + 180, rad2deg(atan2(localized.y, localized.x))); + // Correct the robot's heading until the last cut-off if(!(is_last_point && robot_pose.get_point().dist(last_point) < config.drive_correction_cutoff)) { @@ -443,7 +446,10 @@ bool TankDrive::pure_pursuit(std::vector path, directionType dir, doubl dist_remaining *= cos(angle_diff * (PI / 180.0)); } - feedback.update(-dist_remaining); + if(dir != directionType::rev) + feedback.update(-dist_remaining); + else + feedback.update(dist_remaining); max_speed = fabs(max_speed); From 3d97a86a49fc93d9799ee1974d09d1d4f399c162 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 1 Oct 2023 12:33:42 -0400 Subject: [PATCH 223/243] Added AutoCommand functionality --- include/subsystems/tank_drive.h | 28 +++++++++- .../utils/command_structure/drive_commands.h | 55 +++++++++++++++++-- src/subsystems/tank_drive.cpp | 39 ++++++++++--- .../command_structure/drive_commands.cpp | 29 ++++++++++ 4 files changed, 136 insertions(+), 15 deletions(-) diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 2c0bbba..e92ab25 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -165,9 +165,35 @@ class TankDrive */ static double modify_inputs(double input, int power=2); - + /** + * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of + * waypoints - the robot will attempt to follow the points while cutting corners (radius) + * to save time (compared to stop / turn / start) + * + * @param path The list of coordinates to follow, in order + * @param dir Run the bot forwards or backwards + * @param radius How big the corner cutting should be - small values follow the path more closely + * @param feedback The feedback controller determining speed + * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) + * @return True when the path is complete + */ bool pure_pursuit(std::vector path, directionType dir, double radius, Feedback &feedback, double max_speed=1); + /** + * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of + * waypoints - the robot will attempt to follow the points while cutting corners (radius) + * to save time (compared to stop / turn / start) + * + * Use the default drive feedback + * + * @param path The list of coordinates to follow, in order + * @param dir Run the bot forwards or backwards + * @param radius How big the corner cutting should be - small values follow the path more closely + * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) + * @return True when the path is complete + */ + bool pure_pursuit(std::vector path, directionType dir, double radius, double max_speed=1); + private: motor_group &left_motors; ///< left drive motors motor_group &right_motors; ///< right drive motors diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index 97a08d7..b7636ff 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -33,7 +33,8 @@ using namespace vex; * TankDrive class * */ -class DriveForwardCommand: public AutoCommand { +class DriveForwardCommand: public AutoCommand +{ public: DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed=1); @@ -65,7 +66,8 @@ class DriveForwardCommand: public AutoCommand { * AutoCommand wrapper class for the turn_degrees function in the * TankDrive class */ -class TurnDegreesCommand: public AutoCommand { +class TurnDegreesCommand: public AutoCommand +{ public: TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed = 1); @@ -97,7 +99,8 @@ class TurnDegreesCommand: public AutoCommand { * AutoCommand wrapper class for the drive_to_point function in the * TankDrive class */ -class DriveToPointCommand: public AutoCommand { +class DriveToPointCommand: public AutoCommand +{ public: DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed = 1); DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, point_t point, directionType dir, double max_speed=1); @@ -135,7 +138,8 @@ class DriveToPointCommand: public AutoCommand { * TankDrive class * */ -class TurnToHeadingCommand: public AutoCommand { +class TurnToHeadingCommand: public AutoCommand +{ public: TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed = 1); @@ -163,11 +167,49 @@ class TurnToHeadingCommand: public AutoCommand { double max_speed; }; +/** + * Autocommand wrapper class for pure pursuit function in the TankDrive class +*/ +class PurePursuitCommand: public AutoCommand +{ + public: + /** + * Construct a Pure Pursuit AutoCommand + * + * @param path The list of coordinates to follow, in order + * @param dir Run the bot forwards or backwards + * @param radius How big the corner cutting should be - small values follow the path more closely + * @param feedback The feedback controller determining speed + * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) + */ + PurePursuitCommand(TankDrive &drive_sys, Feedback &feedback, std::vector path, directionType dir, double radius, double max_speed=1); + + /** + * Direct call to TankDrive::pure_pursuit + */ + bool run() override; + + /** + * Reset the drive system when it times out + */ + void on_timeout() override; + + private: + TankDrive &drive_sys; + std::vector path; + directionType dir; + double radius; + Feedback &feedback; + double max_speed; + +}; + /** * AutoCommand wrapper class for the stop() function in the * TankDrive class */ -class DriveStopCommand: public AutoCommand { +class DriveStopCommand: public AutoCommand +{ public: DriveStopCommand(TankDrive &drive_sys); @@ -191,7 +233,8 @@ class DriveStopCommand: public AutoCommand { * AutoCommand wrapper class for the set_position function in the * Odometry class */ -class OdomSetPosition: public AutoCommand { +class OdomSetPosition: public AutoCommand +{ public: /** * constructs a new OdomSetPosition command diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 431e457..d2d6586 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -403,12 +403,23 @@ double TankDrive::modify_inputs(double input, int power) return sign(input)* pow(std::abs(input), power); } -// TODO forwards & backwards +/** + * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of + * waypoints - the robot will attempt to follow the points while cutting corners (radius) + * to save time (compared to stop / turn / start) + * + * @param path The list of coordinates to follow, in order + * @param dir Run the bot forwards or backwards + * @param radius How big the corner cutting should be - small values follow the path more closely + * @param feedback The feedback controller determining speed + * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) + * @return True when the path is complete +*/ bool TankDrive::pure_pursuit(std::vector path, directionType dir, double radius, Feedback &feedback, double max_speed) { pose_t robot_pose = odometry->get_position(); - static pose_t start_pos; + // On function initialization, send the path-length estimate to the feedback controller if(!func_initialized) { if(dir != directionType::rev) @@ -416,7 +427,6 @@ bool TankDrive::pure_pursuit(std::vector path, directionType dir, doubl else feedback.init(estimate_path_length(path), 0); - start_pos = robot_pose; func_initialized = true; } @@ -459,11 +469,6 @@ bool TankDrive::pure_pursuit(std::vector path, directionType dir, doubl left += correction; right -= correction; - // left = clamp(left + correction, -max_speed, max_speed); - // right = clamp(right - correction, -max_speed, max_speed); - - // printf("x:%f, y:%f, rot:%f, d:%f, c:%f l:%f, r:%f\n", robot_pose.x, robot_pose.y, robot_pose.rot, dist_remaining, correction, left, right); - drive_tank(left, right); // When the robot has reached the end point and feedback reports on target, end pure pursuit @@ -475,3 +480,21 @@ bool TankDrive::pure_pursuit(std::vector path, directionType dir, doubl } return false; } + +/** + * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of + * waypoints - the robot will attempt to follow the points while cutting corners (radius) + * to save time (compared to stop / turn / start) + * + * Use the default drive feedback + * + * @param path The list of coordinates to follow, in order + * @param dir Run the bot forwards or backwards + * @param radius How big the corner cutting should be - small values follow the path more closely + * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) + * @return True when the path is complete +*/ +bool TankDrive::pure_pursuit(std::vector path, directionType dir, double radius, double max_speed) +{ + return pure_pursuit(path, dir, radius, *config.drive_feedback, max_speed); +} \ No newline at end of file diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index dbb5d3d..633fa4f 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -143,6 +143,35 @@ void TurnToHeadingCommand::on_timeout(){ drive_sys.stop(); } +/** + * Construct a Pure Pursuit AutoCommand + * + * @param path The list of coordinates to follow, in order + * @param dir Run the bot forwards or backwards + * @param radius How big the corner cutting should be - small values follow the path more closely + * @param feedback The feedback controller determining speed + * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) +*/ +PurePursuitCommand::PurePursuitCommand(TankDrive &drive_sys, Feedback &feedback, std::vector path, directionType dir, double radius, double max_speed) +: drive_sys(drive_sys), path(path), dir(dir), radius(radius), feedback(feedback), max_speed(max_speed) +{} + +/** + * Direct call to TankDrive::pure_pursuit +*/ +bool PurePursuitCommand::run() +{ + return drive_sys.pure_pursuit(path, dir, radius, feedback, max_speed); +} + +/** + * Reset the drive system when it times out +*/ +void PurePursuitCommand::on_timeout() +{ + drive_sys.reset_auto(); + drive_sys.stop(); +} /** * Construct a DriveStop Command From b1a8d1e2f935e04c34ab83d3079d375f45050448 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 1 Oct 2023 13:32:18 -0400 Subject: [PATCH 224/243] Merge remote-tracking branch 'origin/main' into pure_pursuit --- include/subsystems/flywheel.h | 213 ++++++++-------- include/subsystems/tank_drive.h | 83 +++--- .../utils/command_structure/auto_command.h | 200 +++++++++++++-- .../command_structure/command_controller.h | 18 +- include/utils/generic_auto.h | 4 + src/subsystems/tank_drive.cpp | 182 +++++++------ src/utils/command_structure/auto_command.cpp | 239 ++++++++++++++++++ .../command_structure/command_controller.cpp | 12 +- 8 files changed, 713 insertions(+), 238 deletions(-) create mode 100644 src/utils/command_structure/auto_command.cpp diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index 199cf3e..31b8e94 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -1,20 +1,21 @@ #pragma once /********************************************************* -* -* File: Flywheel.h -* Purpose: Generalized flywheel class for Core. -* Author: Chris Nokes -* -********************************************************** -* EDIT HISTORY -********************************************************** -* 09/23/2022 Reorganized, added documentation. -* 09/23/2022 Added functions elaborated on in .cpp. -*********************************************************/ + * + * File: Flywheel.h + * Purpose: Generalized flywheel class for Core. + * Author: Chris Nokes + * + ********************************************************** + * EDIT HISTORY + ********************************************************** + * 09/23/2022 Reorganized, added documentation. + * 09/23/2022 Added functions elaborated on in .cpp. + *********************************************************/ #include "../core/include/utils/feedforward.h" #include "vex.h" #include "../core/include/robot_specs.h" #include "../core/include/utils/pid.h" +#include "../core/include/utils/command_structure/auto_command.h" #include using namespace vex; @@ -22,162 +23,176 @@ using namespace vex; /** * a Flywheel class that handles all control of a high inertia spinning disk * It gives multiple options for what control system to use in order to control wheel velocity and functions alerting the user when the flywheel is up to speed. - * Flywheel is a set and forget class. + * Flywheel is a set and forget class. * Once you create it you can call spinRPM or stop on it at any time and it will take all necessary steps to accomplish this - * -*/ -class Flywheel{ - enum FlywheelControlStyle{ + * + */ +class Flywheel +{ + enum FlywheelControlStyle + { PID_Feedforward, Feedforward, Take_Back_Half, Bang_Bang, }; - public: +public: // CONSTRUCTORS, GETTERS, AND SETTERS /** - * Create the Flywheel object using PID + feedforward for control. - * @param motors pointer to the motors on the fly wheel - * @param pid_config pointer the pid config to use - * @param ff_config the feedforward config to use - * @param ratio ratio of the whatever just multiplies the velocity - */ + * Create the Flywheel object using PID + feedforward for control. + * @param motors pointer to the motors on the fly wheel + * @param pid_config pointer the pid config to use + * @param ff_config the feedforward config to use + * @param ratio ratio of the whatever just multiplies the velocity + */ Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio); /** - * Create the Flywheel object using only feedforward for control - * @param motors the motors on the fly wheel - * @param ff_config the feedforward config to use - * @param ratio ratio of the whatever just multiplies the velocity - */ + * Create the Flywheel object using only feedforward for control + * @param motors the motors on the fly wheel + * @param ff_config the feedforward config to use + * @param ratio ratio of the whatever just multiplies the velocity + */ Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio); /** - * Create the Flywheel object using Take Back Half for control - * @param motors the motors on the fly wheel - * @param tbh_gain the TBH control paramater - * @param ratio ratio of the whatever just multiplies the velocity - */ + * Create the Flywheel object using Take Back Half for control + * @param motors the motors on the fly wheel + * @param tbh_gain the TBH control paramater + * @param ratio ratio of the whatever just multiplies the velocity + */ Flywheel(motor_group &motors, double tbh_gain, const double ratio); /** - * Create the Flywheel object using Bang Bang for control - * @param motors the motors on the fly wheel - * @param ratio ratio of the whatever just multiplies the velocity - */ + * Create the Flywheel object using Bang Bang for control + * @param motors the motors on the fly wheel + * @param ratio ratio of the whatever just multiplies the velocity + */ Flywheel(motor_group &motors, const double ratio); /** - * Return the RPM that the flywheel is currently trying to achieve - * @return RPM the target rpm - */ + * Return the RPM that the flywheel is currently trying to achieve + * @return RPM the target rpm + */ double getDesiredRPM(); /** - * Checks if the background RPM controlling task is running - * @return true if the task is running - */ + * Checks if the background RPM controlling task is running + * @return true if the task is running + */ bool isTaskRunning(); /** - * Returns a POINTER to the motors - */ - motor_group* getMotors(); + * Returns a POINTER to the motors + */ + motor_group *getMotors(); /** - * make a measurement of the current RPM of the flywheel motor and return a smoothed version - */ + * make a measurement of the current RPM of the flywheel motor and return a smoothed version + */ double measureRPM(); /** - * return the current smoothed velocity of the flywheel motors, in RPM - */ + * return the current smoothed velocity of the flywheel motors, in RPM + */ double getRPM(); /** - * Returns a POINTER to the PID. - */ - PID* getPID(); + * Returns a POINTER to the PID. + */ + PID *getPID(); /** - * returns the current OUT value of the PID - the value that the PID would set the motors to - */ + * returns the current OUT value of the PID - the value that the PID would set the motors to + */ double getPIDValue(); /** - * returns the current OUT value of the PID - the value that the PID would set the motors to - */ + * returns the current OUT value of the PID - the value that the PID would set the motors to + */ double getFeedforwardValue(); - + /** - * get the gain used for TBH control - */ + * get the gain used for TBH control + */ double getTBHGain(); - + /** - * Sets the value of the PID target - * @param value - desired value of the PID - */ + * Sets the value of the PID target + * @param value - desired value of the PID + */ void setPIDTarget(double value); -/** -* updates the value of the PID -* @param value - value to update the PID with -*/ + /** + * updates the value of the PID + * @param value - value to update the PID with + */ void updatePID(double value); // SPINNERS AND STOPPERS - /** - * Spin motors using voltage; defaults forward at 12 volts - * FOR USE BY TASKS ONLY - * @param speed - speed (between -1 and 1) to set the motor - * @param dir - direction that the motor moves in; defaults to forward - */ - void spin_raw(double speed, directionType dir=fwd); - - /** - * Spin motors using voltage; defaults forward at 12 volts - * FOR USE BY OPCONTROL AND AUTONOMOUS - this only applies if the RPM thread is not running - * @param speed - speed (between -1 and 1) to set the motor - * @param dir - direction that the motor moves in; defaults to forward - */ - void spin_manual(double speed, directionType dir=fwd); - - /** - * starts or sets the RPM thread at new value - * what control scheme is dependent on control_style - * @param rpm - the RPM we want to spin at - */ + /** + * Spin motors using voltage; defaults forward at 12 volts + * FOR USE BY TASKS ONLY + * @param speed - speed (between -1 and 1) to set the motor + * @param dir - direction that the motor moves in; defaults to forward + */ + void spin_raw(double speed, directionType dir = fwd); + + /** + * Spin motors using voltage; defaults forward at 12 volts + * FOR USE BY OPCONTROL AND AUTONOMOUS - this only applies if the RPM thread is not running + * @param speed - speed (between -1 and 1) to set the motor + * @param dir - direction that the motor moves in; defaults to forward + */ + void spin_manual(double speed, directionType dir = fwd); + + /** + * starts or sets the RPM thread at new value + * what control scheme is dependent on control_style + * @param rpm - the RPM we want to spin at + */ void spinRPM(int rpm); /** - * stop the RPM thread and the wheel - */ + * stop the RPM thread and the wheel + */ void stop(); - /** - * stop only the motors; exclusively for BANG BANG use - */ + * stop only the motors; exclusively for BANG BANG use + */ void stopMotors(); /** - * Stop the motors if the task isn't running - stop manual control - */ + * Stop the motors if the task isn't running - stop manual control + */ void stopNonTasks(); - private: + AutoCommand *SpinRpmCmd(int rpm) + { + + return new FunctionCommand([this]() + {spinRPM(1000); return true; }); + } + + AutoCommand *WaitUntilUpToSpeedCmd() + { + return new WaitUntilCondition( + new FunctionCondition([this]() + { return RPM == smoothedRPM; })); + } +private: motor_group &motors; // motors that make up the flywheel bool taskRunning = false; // is the task (thread but not) currently running? PID pid; // PID on the flywheel FeedForward ff; // FF constants for the flywheel double TBH_gain; // TBH gain parameter for the flywheel double ratio; // multiplies the velocity by this value - std::atomic RPM; // Desired RPM of the flywheel. + std::atomic RPM; // Desired RPM of the flywheel. task rpmTask; // task (thread but not) that handles spinning the wheel at a given RPM FlywheelControlStyle control_style; // how the flywheel should be controlled double smoothedRPM; MovingAverage RPM_avger; - }; \ No newline at end of file +}; \ No newline at end of file diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index e92ab25..3b3887d 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -10,27 +10,38 @@ #include "../core/include/utils/feedback_base.h" #include "../core/include/robot_specs.h" #include "../core/include/utils/pure_pursuit.h" +#include "../core/include/utils/command_structure/auto_command.h" #include - using namespace vex; /** * TankDrive is a class to run a tank drive system. * A tank drive system, sometimes called differential drive, has a motor (or group of synchronized motors) on the left and right side -*/ + */ class TankDrive { public: - /** - * Create the TankDrive object + * Create the TankDrive object * @param left_motors left side drive motors * @param right_motors right side drive motors * @param config the configuration specification defining physical dimensions about the robot. See robot_specs_t for more info * @param odom an odometry system to track position and rotation. this is necessary to execute autonomous paths */ - TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom=NULL); + TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom = NULL); + + AutoCommand *DriveToPointCmd(point_t pt, vex::directionType dir = vex::forward, double max_speed = 1.0); + AutoCommand *DriveToPointCmd(Feedback &fb, point_t pt, vex::directionType dir = vex::forward, double max_speed = 1.0); + + AutoCommand *DriveForwardCmd(double dist, vex::directionType dir = vex::forward, double max_speed = 1.0); + AutoCommand *DriveForwardCmd(Feedback &fb, double dist, vex::directionType dir = vex::forward, double max_speed = 1.0); + + AutoCommand *TurnToHeadingCmd(double heading, double max_speed = 1.0); + AutoCommand *TurnToHeadingCmd(Feedback &fb, double heading, double max_speed = 1.0); + + AutoCommand *TurnDegreesCmd(double degrees, double max_speed = 1.0); + AutoCommand *TurnDegreesCmd(Feedback &fb, double degrees, double max_speed = 1.0); /** * Stops rotation of all the motors using their "brake mode" @@ -40,7 +51,7 @@ class TankDrive /** * Drive the robot using differential style controls. left_motors controls the left motors, * right_motors controls the right motors. - * + * * left_motors and right_motors are in "percent": -1.0 -> 1.0 * @param left the percent to run the left motors * @param right the percent to run the right motors @@ -52,14 +63,14 @@ class TankDrive /** * Drive the robot using arcade style controls. forward_back controls the linear motion, * left_right controls the turning. - * + * * forward_back and left_right are in "percent": -1.0 -> 1.0 - * + * * @param forward_back the percent to move forward or backward * @param left_right the percent to turn left or right * @param power modifies the input velocities left^power, right^power */ - void drive_arcade(double forward_back, double left_right, int power=1); + void drive_arcade(double forward_back, double left_right, int power = 1); /** * Use odometry to drive forward a certain distance using a custom feedback controller @@ -71,40 +82,40 @@ class TankDrive * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power * @return true when we have reached our target distance */ - bool drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed=1); + bool drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed = 1); /** * Autonomously drive the robot forward a certain distance - * - * + * + * * @param inches degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw * @param dir the direction we want to travel forward and backward * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ - bool drive_forward(double inches, directionType dir, double max_speed=1); + bool drive_forward(double inches, directionType dir, double max_speed = 1); /** * Autonomously turn the robot X degrees counterclockwise (negative for clockwise), with a maximum motor speed * of percent_speed (-1.0 -> 1.0) - * + * * Uses PID + Feedforward for it's control. - * + * * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ - bool turn_degrees(double degrees, Feedback &feedback, double max_speed=1); + bool turn_degrees(double degrees, Feedback &feedback, double max_speed = 1); /** * Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed * of percent_speed (-1.0 -> 1.0) - * + * * Uses the defualt turning feedback of the drive system. - * + * * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - */ - bool turn_degrees(double degrees, double max_speed=1); + */ + bool turn_degrees(double degrees, double max_speed = 1); /** * Use odometry to automatically drive the robot to a point on the field. @@ -117,8 +128,8 @@ class TankDrive * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ - bool drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed=1); - + bool drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed = 1); + /** * Use odometry to automatically drive the robot to a point on the field. * X and Y is the final point we want the robot. @@ -130,25 +141,25 @@ class TankDrive * @param dir the direction we want to travel forward and backward * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ - bool drive_to_point(double x, double y, vex::directionType dir, double max_speed=1); + bool drive_to_point(double x, double y, vex::directionType dir, double max_speed = 1); /** * Turn the robot in place to an exact heading relative to the field. * 0 is forward. - * - * @param heading_deg the heading to which we will turn + * + * @param heading_deg the heading to which we will turn * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ - bool turn_to_heading(double heading_deg, Feedback &feedback, double max_speed=1); + bool turn_to_heading(double heading_deg, Feedback &feedback, double max_speed = 1); /** * Turn the robot in place to an exact heading relative to the field. - * 0 is forward. Uses the defualt turn feedback of the drive system - * - * @param heading_deg the heading to which we will turn + * 0 is forward. Uses the defualt turn feedback of the drive system + * + * @param heading_deg the heading to which we will turn * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ - bool turn_to_heading(double heading_deg, double max_speed=1); + bool turn_to_heading(double heading_deg, double max_speed = 1); /** * Reset the initialization for autonomous drive functions @@ -158,12 +169,12 @@ class TankDrive /** * Create a curve for the inputs, so that drivers have more control at lower speeds. * Curves are exponential, with the default being squaring the inputs. - * + * * @param input the input before modification * @param power the power to raise input to * @return input ^ power (accounts for negative inputs and odd numbered powers) */ - static double modify_inputs(double input, int power=2); + static double modify_inputs(double input, int power = 2); /** * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of @@ -195,17 +206,17 @@ class TankDrive bool pure_pursuit(std::vector path, directionType dir, double radius, double max_speed=1); private: - motor_group &left_motors; ///< left drive motors + motor_group &left_motors; ///< left drive motors motor_group &right_motors; ///< right drive motors - PID correction_pid; ///< PID controller used to drive in as straight a line as possible + PID correction_pid; ///< PID controller used to drive in as straight a line as possible Feedback *drive_default_feedback = NULL; ///< feedback to use to drive if none is specified - Feedback *turn_default_feedback = NULL; ///< feedback to use to turn if none is specified + Feedback *turn_default_feedback = NULL; ///< feedback to use to turn if none is specified OdometryBase *odometry; ///< odometry system to track position and rotation. necessary for autonomous driving robot_specs_t &config; ///< configuration holding physical dimensions of the robot. see robot_specs_t for more information bool func_initialized = false; ///< used to control initialization of autonomous driving. (you only wan't to set the target once, not every iteration that you're driving) - bool is_pure_pursuit = false; ///< true if we are driving with a pure pursuit system + bool is_pure_pursuit = false; ///< true if we are driving with a pure pursuit system }; diff --git a/include/utils/command_structure/auto_command.h b/include/utils/command_structure/auto_command.h index e19a356..066cb20 100644 --- a/include/utils/command_structure/auto_command.h +++ b/include/utils/command_structure/auto_command.h @@ -7,33 +7,179 @@ #pragma once #include "vex.h" +#include +#include +#include +#include -class AutoCommand { - public: - static constexpr double default_timeout = 10.0; - /** - * Executes the command - * Overridden by child classes - * @returns true when the command is finished, false otherwise - */ - virtual bool run() { return true; } - /** - * What to do if we timeout instead of finishing. timeout is specified by the timeout seconds in the constructor - */ - virtual void on_timeout(){} - AutoCommand* withTimeout(double t_seconds){ - this->timeout_seconds = t_seconds; +class AutoCommand +{ +public: + static constexpr double default_timeout = 10.0; + /** + * Executes the command + * Overridden by child classes + * @returns true when the command is finished, false otherwise + */ + virtual bool run() { return true; } + /** + * What to do if we timeout instead of finishing. timeout is specified by the timeout seconds in the constructor + */ + virtual void on_timeout() {} + AutoCommand *withTimeout(double t_seconds) + { + if (this->timeout_seconds < 0) + { + // should never be timed out return this; } - /** - * How long to run until we cancel this command. - * If the command is cancelled, on_timeout() is called to allow any cleanup from the function. - * If the timeout_seconds <= 0, no timeout will be applied and this command will run forever - * A timeout can come in handy for some commands that can not reach the end due to some physical limitation such as - * - a drive command hitting a wall and not being able to reach its target - * - a command that waits until something is up to speed that never gets up to speed because of battery voltage - * - something else... - */ - double timeout_seconds = default_timeout; - -}; \ No newline at end of file + this->timeout_seconds = t_seconds; + return this; + } + /** + * How long to run until we cancel this command. + * If the command is cancelled, on_timeout() is called to allow any cleanup from the function. + * If the timeout_seconds <= 0, no timeout will be applied and this command will run forever + * A timeout can come in handy for some commands that can not reach the end due to some physical limitation such as + * - a drive command hitting a wall and not being able to reach its target + * - a command that waits until something is up to speed that never gets up to speed because of battery voltage + * - something else... + */ + double timeout_seconds = default_timeout; +}; + +/** + * FunctionCommand is fun and good way to do simple things + * Printing, launching nukes, and other quick and dirty one time things + */ +class FunctionCommand : public AutoCommand +{ +public: + FunctionCommand(std::function f) : f(f) {} + bool run() + { + return f(); + } + +private: + std::function f; +}; + +/** + * A Condition is a function that returns true or false + * is_even is a predicate that would return true if a number is even + * For our purposes, a Condition is a choice to be made at runtime + * drive_sys.reached_point(10, 30) is a predicate + * time.has_elapsed(10, vex::seconds) is a predicate + * extend this class for different choices you wish to make + + */ +class Condition +{ +public: + virtual bool test() = 0; +}; + +/// @brief FunctionCondition is a quick and dirty Condition to wrap some expression that should be evaluated at runtime +class FunctionCondition : public Condition +{ +public: + FunctionCondition( + std::function cond, std::function timeout = []() {}) : cond(cond), timeout(timeout) + { + } + bool test() override; + +private: + std::function cond; + std::function timeout; +}; + +/// @brief IfTimePassed tests based on time since the command controller was constructed. Returns true if elapsed time > time_s +class IfTimePassed : public Condition +{ +public: + IfTimePassed(double time_s); + bool test() override; + +private: + double time_s; + vex::timer tmr; +}; + +/// @brief Waits until the condition is true +class WaitUntilCondition : public AutoCommand +{ +public: + WaitUntilCondition(Condition *cond) : cond(cond) {} + bool run() override + { + return cond->test(); + } + +private: + Condition *cond; +}; + +/// @brief InOrder runs its commands sequentially then continues. +/// How to handle timeout in this case. Automatically set it to sum of commands timouts? +class InOrder : public AutoCommand +{ +public: + InOrder(std::queue cmds); + InOrder(std::initializer_list cmds); + bool run() override; + void on_timeout() override; + +private: + AutoCommand *current_command = nullptr; + std::queue cmds; + vex::timer tmr; +}; + +/// @brief Parallel runs multiple commands in parallel and waits for all to finish before continuing. +/// if none finish before this command's timeout, it will call on_timeout on all children continue +class Parallel : public AutoCommand +{ +public: + Parallel(std::initializer_list cmds); + bool run() override; + void on_timeout() override; + +private: + std::vector cmds; + std::vector runners; +}; + +/// @brief Branch chooses from multiple options at runtime. the function decider returns an index into the choices vector +/// If you wish to make no choice and skip this section, return NO_CHOICE; +/// any choice that is out of bounds set to NO_CHOICE +class Branch : public AutoCommand +{ +public: + Branch(Condition *cond, AutoCommand *false_choice, AutoCommand *true_choice); + ~Branch(); + bool run() override; + void on_timeout() override; + +private: + AutoCommand *false_choice; + AutoCommand *true_choice; + Condition *cond; + bool choice = false; + bool chosen = false; + vex::timer tmr; +}; + +/// @brief Async runs a command asynchronously +/// will simply let it go and never look back +/// THIS HAS A VERY NICHE USE CASE. THINK ABOUT IF YOU REALLY NEED IT +class Async : public AutoCommand +{ +public: + Async(AutoCommand *cmd) : cmd(cmd) {} + bool run() override; + +private: + AutoCommand *cmd = nullptr; +}; diff --git a/include/utils/command_structure/command_controller.h b/include/utils/command_structure/command_controller.h index 2757f1a..3bae711 100644 --- a/include/utils/command_structure/command_controller.h +++ b/include/utils/command_structure/command_controller.h @@ -15,25 +15,32 @@ class CommandController { public: + /// @brief Create an empty CommandController. Add Command with CommandController::add() + [[deprecated("Use list constructor instead.")]] CommandController() : command_queue({}) {} + + /// @brief Create a CommandController with commands pre added. More can be added with CommandController::add() + /// @param cmds + CommandController(std::initializer_list cmds) : command_queue(cmds) {} /** * Adds a command to the queue * @param cmd the AutoCommand we want to add to our list * @param timeout_seconds the number of seconds we will let the command run for. If it exceeds this, we cancel it and run on_timeout. if it is <= 0 no time out will be applied */ + [[deprecated("Use list constructor instead. If you need to make a decision before adding new commands, use Branch")]] void add(std::vector cmds); void add(AutoCommand *cmd, double timeout_seconds = 10.0); /** * Add multiple commands to the queue. No timeout here. * @param cmds the AutoCommands we want to add to our list */ - void add(std::vector cmds); /** * Add multiple commands to the queue. No timeout here. * @param cmds the AutoCommands we want to add to our list * @param timeout_sec timeout in seconds to apply to all commands if they are still the default */ - void add(std::vector cmds, double timeout_sec); + [[deprecated("Use list constructor instead. If you need to make a decision before adding new commands, use Branch")]] void + add(std::vector cmds, double timeout_sec); /** * Adds a command that will delay progression * of the queue @@ -42,11 +49,16 @@ class CommandController */ void add_delay(int ms); + /// @brief add_cancel_func specifies that when this func evaluates to true, to cancel the command controller + /// @param true_if_cancel a function that returns true when we want to cancel the command controller + void add_cancel_func(std::function true_if_cancel); + /** * Begin execution of the queue * Execute and remove commands in FIFO order */ void run(); + /** * last_command_timed_out tells how the last command ended * Use this if you want to make decisions based on the end of the last command @@ -57,4 +69,6 @@ class CommandController private: std::queue command_queue; bool command_timed_out = false; + std::function should_cancel = []() + { return false; }; }; \ No newline at end of file diff --git a/include/utils/generic_auto.h b/include/utils/generic_auto.h index d344847..f03fd76 100644 --- a/include/utils/generic_auto.h +++ b/include/utils/generic_auto.h @@ -28,24 +28,28 @@ class GenericAuto * @returns * true after all states have finished. */ + [[deprecated("Use CommandController instead.")]] bool run(bool blocking); /** * Add a new state to the autonomous via function point of type "bool (ptr*)()" * @param new_state the function to run */ + [[deprecated("Use CommandController instead.")]] void add(state_ptr new_state); /** * Add a new state to the autonomous via function point of type "bool (ptr*)()" that will run asynchronously * @param async_state the function to run */ + [[deprecated("Use CommandController instead.")]] void add_async(state_ptr async_state); /** * add_delay adds a period where the auto system will simply wait for the specified time * @param ms how long to wait in milliseconds */ + [[deprecated("Use CommandController instead.")]] void add_delay(int ms); private: diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index d2d6586..2afb3f9 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -2,6 +2,7 @@ #include "../core/include/subsystems/tank_drive.h" #include "../core/include/utils/math_util.h" #include "../core/include/utils/pidff.h" +#include "../core/include/utils/command_structure/drive_commands.h" TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom) : left_motors(left_motors), right_motors(right_motors), correction_pid(config.correction_pid), odometry(odom), config(config) @@ -10,6 +11,44 @@ TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, robot_ turn_default_feedback = config.turn_feedback; } +AutoCommand *TankDrive::DriveToPointCmd(Feedback &fb, point_t pt, vex::directionType dir, double max_speed) +{ + return new DriveToPointCommand(*this, fb, pt, dir, max_speed); +} + +AutoCommand *TankDrive::DriveToPointCmd(point_t pt, vex::directionType dir, double max_speed) +{ + return new DriveToPointCommand(*this, *drive_default_feedback, pt, dir, max_speed); +} + +AutoCommand *TankDrive::DriveForwardCmd(double dist, vex::directionType dir, double max_speed) +{ + return new DriveForwardCommand(*this, *drive_default_feedback, dist, dir, max_speed); +} + +AutoCommand *TankDrive::DriveForwardCmd(Feedback &fb, double dist, vex::directionType dir, double max_speed) +{ + return new DriveForwardCommand(*this, fb, dist, dir, max_speed); +} + +AutoCommand *TankDrive::TurnToHeadingCmd(double heading, double max_speed) +{ + return new TurnToHeadingCommand(*this, *turn_default_feedback, heading, max_speed); +} +AutoCommand *TankDrive::TurnToHeadingCmd(Feedback &fb, double heading, double max_speed) +{ + return new TurnToHeadingCommand(*this, fb, heading, max_speed); +} + +AutoCommand *TankDrive::TurnDegreesCmd(double degrees, double max_speed) +{ + return new TurnDegreesCommand(*this, *turn_default_feedback, degrees, max_speed); +} +AutoCommand *TankDrive::TurnDegreesCmd(Feedback &fb, double degrees, double max_speed) +{ + return new TurnDegreesCommand(*this, fb, degrees, max_speed); +} + /** * Reset the initialization for autonomous drive functions */ @@ -30,7 +69,7 @@ void TankDrive::stop() /** * Drive the robot using differential style controls. left_motors controls the left motors, * right_motors controls the right motors. - * + * * left_motors and right_motors are in "percent": -1.0 -> 1.0 */ void TankDrive::drive_tank(double left, double right, int power) @@ -45,7 +84,7 @@ void TankDrive::drive_tank(double left, double right, int power) /** * Drive the robot using arcade style controls. forward_back controls the linear motion, * left_right controls the turning. - * + * * left_motors and right_motors are in "percent": -1.0 -> 1.0 */ void TankDrive::drive_arcade(double forward_back, double left_right, int power) @@ -74,7 +113,7 @@ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedba static pose_t pos_setpt; // We can't run the auto drive function without odometry - if(odometry == NULL) + if (odometry == NULL) { fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); fflush(stderr); @@ -93,13 +132,12 @@ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedba inches = fabs(inches); // Use vector math to get an X and Y - Vector2D cur_pos_vec({.x=cur_pos.x , .y=cur_pos.y}); + Vector2D cur_pos_vec({.x = cur_pos.x, .y = cur_pos.y}); Vector2D delta_pos_vec(deg2rad(cur_pos.rot), inches); Vector2D setpt_vec = cur_pos_vec + delta_pos_vec; // Save the new X and Y values - pos_setpt = {.x=setpt_vec.get_x(), .y=setpt_vec.get_y()}; - + pos_setpt = {.x = setpt_vec.get_x(), .y = setpt_vec.get_y()}; } // Call the drive_to_point with updated point values @@ -107,8 +145,8 @@ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedba } /** * Autonomously drive the robot forward a certain distance - * - * + * + * * @param inches degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw * @param dir the direction we want to travel forward and backward * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power @@ -116,7 +154,7 @@ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedba */ bool TankDrive::drive_forward(double inches, directionType dir, double max_speed) { - if(drive_default_feedback != NULL) + if (drive_default_feedback != NULL) return drive_forward(inches, dir, *drive_default_feedback, max_speed); printf("tank_drive.cpp: Cannot run drive_forward without a feedback controller!\n"); @@ -127,9 +165,9 @@ bool TankDrive::drive_forward(double inches, directionType dir, double max_speed /** * Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed * of percent_speed (-1.0 -> 1.0) - * + * * Uses the specified feedback for it's control. - * + * * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power @@ -138,7 +176,7 @@ bool TankDrive::drive_forward(double inches, directionType dir, double max_speed bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_speed) { // We can't run the auto drive function without odometry - if(odometry == NULL) + if (odometry == NULL) { fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); fflush(stderr); @@ -152,58 +190,57 @@ bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_spee { double start_heading = odometry->get_position().rot; target_heading = start_heading + degrees; - } - return turn_to_heading(target_heading); + return turn_to_heading(target_heading, feedback, max_speed); } /** * Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed * of percent_speed (-1.0 -> 1.0) - * + * * Uses the defualt turning feedback of the drive system. - * + * * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power * @return true if we turned te target number of degrees */ bool TankDrive::turn_degrees(double degrees, double max_speed) { - if(turn_default_feedback != NULL) + if (turn_default_feedback != NULL) return turn_degrees(degrees, *turn_default_feedback, max_speed); - + printf("tank_drive.cpp: Cannot run turn_degrees without a feedback controller!\n"); fflush(stdout); return true; } /** - * Use odometry to automatically drive the robot to a point on the field. - * X and Y is the final point we want the robot. - * - * Returns whether or not the robot has reached it's destination. - * @param x the x position of the target - * @param y the y position of the target - * @param dir the direction we want to travel forward and backward - * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @return true if we have reached our target point - */ + * Use odometry to automatically drive the robot to a point on the field. + * X and Y is the final point we want the robot. + * + * Returns whether or not the robot has reached it's destination. + * @param x the x position of the target + * @param y the y position of the target + * @param dir the direction we want to travel forward and backward + * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @return true if we have reached our target point + */ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed) { // We can't run the auto drive function without odometry - if(odometry == NULL) + if (odometry == NULL) { fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); fflush(stderr); return true; } - - if(!func_initialized) + + if (!func_initialized) { - - double initial_dist = OdometryBase::pos_diff(odometry->get_position(), {.x=x, .y=y}); + + double initial_dist = OdometryBase::pos_diff(odometry->get_position(), {.x = x, .y = y}); // Reset the control loops correction_pid.init(0, 0); @@ -217,20 +254,19 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb // Store the initial position of the robot pose_t current_pos = odometry->get_position(); - pose_t end_pos = {.x=x, .y=y}; + pose_t end_pos = {.x = x, .y = y}; // Create a point (and vector) to get the direction - point_t pos_diff_pt = - { - .x = x - current_pos.x, - .y = y - current_pos.y - }; + point_t pos_diff_pt = + { + .x = x - current_pos.x, + .y = y - current_pos.y}; Vector2D point_vec(pos_diff_pt); // Get the distance between 2 points double dist_left = OdometryBase::pos_diff(current_pos, end_pos); - + int sign = 1; // Make an imaginary perpendicualar line to that between the bot and the point. If the point is behind that line, @@ -240,16 +276,18 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb double angle = fmod(current_pos.rot - angle_to_point, 360.0); // Normalize the angle between 0 and 360 - if (angle > 360) angle -= 360; - if (angle < 0) angle += 360; + if (angle > 360) + angle -= 360; + if (angle < 0) + angle += 360; // If the angle is behind the robot, report negative. if (dir == directionType::fwd && angle > 90 && angle < 270) sign = -1; - else if(dir == directionType::rev && (angle < 90 || angle > 270)) + else if (dir == directionType::rev && (angle < 90 || angle > 270)) sign = -1; - if (fabs(dist_left) < config.drive_correction_cutoff) + if (fabs(dist_left) < config.drive_correction_cutoff) { // When inside the robot's cutoff radius, report the distance to the point along the robot's forward axis, // so we always "reach" the point without having to do a lateral translation @@ -273,12 +311,12 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb // Disable correction when we're close enough to the point double correction = 0; - if(is_pure_pursuit || fabs(dist_left) > config.drive_correction_cutoff) + if (is_pure_pursuit || fabs(dist_left) > config.drive_correction_cutoff) correction = correction_pid.get(); // Reverse the drive_pid output if we're going backwards double drive_pid_rval; - if(dir == directionType::rev) + if (dir == directionType::rev) drive_pid_rval = feedback.get() * -1; else drive_pid_rval = feedback.get(); @@ -288,13 +326,13 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb double rside = drive_pid_rval - correction; // limit the outputs between -1 and +1 - lside = clamp(lside, -1, 1); - rside = clamp(rside, -1, 1); + lside = clamp(lside, -max_speed, max_speed); + rside = clamp(rside, -max_speed, max_speed); drive_tank(lside, rside); // Check if the robot has reached it's destination - if(feedback.is_on_target()) + if (feedback.is_on_target()) { stop(); func_initialized = false; @@ -306,20 +344,20 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb } /** - * Use odometry to automatically drive the robot to a point on the field. - * X and Y is the final point we want the robot. - * Here we use the default feedback controller from the drive_sys - * - * Returns whether or not the robot has reached it's destination. - * @param x the x position of the target - * @param y the y position of the target - * @param dir the direction we want to travel forward and backward - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @return true if we have reached our target point - */ + * Use odometry to automatically drive the robot to a point on the field. + * X and Y is the final point we want the robot. + * Here we use the default feedback controller from the drive_sys + * + * Returns whether or not the robot has reached it's destination. + * @param x the x position of the target + * @param y the y position of the target + * @param dir the direction we want to travel forward and backward + * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @return true if we have reached our target point + */ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, double max_speed) { - if(drive_default_feedback != NULL) + if (drive_default_feedback != NULL) return this->drive_to_point(x, y, dir, *drive_default_feedback, max_speed); printf("tank_drive.cpp: Cannot run drive_to_point without a feedback controller!\n"); @@ -330,8 +368,8 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, doubl /** * Turn the robot in place to an exact heading relative to the field. * 0 is forward. - * - * @param heading_deg the heading to which we will turn + * + * @param heading_deg the heading to which we will turn * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power * @return true if we have reached our target heading @@ -339,14 +377,14 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, doubl bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double max_speed) { // We can't run the auto drive function without odometry - if(odometry == NULL) + if (odometry == NULL) { fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); fflush(stderr); return true; } - if(!func_initialized) + if (!func_initialized) { double initial_delta = OdometryBase::smallest_angle(odometry->get_position().rot, heading_deg); feedback.init(-initial_delta, 0); @@ -364,7 +402,7 @@ bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double m drive_tank(-feedback.get(), feedback.get()); // When the robot has reached it's angle, return true. - if(feedback.is_on_target()) + if (feedback.is_on_target()) { func_initialized = false; stop(); @@ -375,15 +413,15 @@ bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double m } /** * Turn the robot in place to an exact heading relative to the field. - * 0 is forward. Uses the defualt turn feedback of the drive system - * - * @param heading_deg the heading to which we will turn + * 0 is forward. Uses the defualt turn feedback of the drive system + * + * @param heading_deg the heading to which we will turn * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power * @return true if we have reached our target heading */ bool TankDrive::turn_to_heading(double heading_deg, double max_speed) { - if(turn_default_feedback != NULL) + if (turn_default_feedback != NULL) return turn_to_heading(heading_deg, *turn_default_feedback, max_speed); printf("tank_drive.cpp: Cannot run turn_to_heading without a feedback controller!\n"); @@ -400,7 +438,7 @@ bool TankDrive::turn_to_heading(double heading_deg, double max_speed) */ double TankDrive::modify_inputs(double input, int power) { - return sign(input)* pow(std::abs(input), power); + return sign(input) * pow(std::abs(input), power); } /** diff --git a/src/utils/command_structure/auto_command.cpp b/src/utils/command_structure/auto_command.cpp new file mode 100644 index 0000000..d9b0461 --- /dev/null +++ b/src/utils/command_structure/auto_command.cpp @@ -0,0 +1,239 @@ +#include "../core/include/utils/command_structure/auto_command.h" + +bool FunctionCondition::test() +{ + return cond(); +} +IfTimePassed::IfTimePassed(double time_s) : time_s(time_s), tmr() {} +bool IfTimePassed::test() +{ + return (static_cast(tmr.time()) / 1000.0) > time_s; +} + +InOrder::InOrder(std::queue cmds) : cmds(cmds) +{ + timeout_seconds = -1.0; // never timeout unless with_timeout is explicitly called +} +InOrder::InOrder(std::initializer_list cmds) : cmds(cmds) +{ + timeout_seconds = -1.0; +} + +bool InOrder::run() +{ + // outer loop finished + if (cmds.size() == 0) + { + return true; + } + // retrieve and remove command at the front of the queue + if (current_command == nullptr) + { + current_command = cmds.front(); + cmds.pop(); + tmr.reset(); + } + + // run command + bool cmd_finished = current_command->run(); + if (cmd_finished) + { + current_command = nullptr; + return false; // continue omn next command + } + + double seconds = static_cast(tmr.time()) / 1000.0; + + bool should_timeout = current_command->timeout_seconds > 0.0; + bool command_timed_out = seconds > current_command->timeout_seconds; + + // timeout + if (should_timeout && command_timed_out) + { + current_command->on_timeout(); + current_command = nullptr; + return false; + } + return false; +} + +void InOrder::on_timeout() +{ + if (current_command != nullptr) + { + current_command->on_timeout(); + } +} + +struct parallel_runner_info +{ + int index; + std::vector *runners; + AutoCommand *cmd; +}; +static int parallel_runner(void *arg) +{ + parallel_runner_info *ri = (parallel_runner_info *)arg; + vex::timer tmr; + while (1) + { + bool finished = ri->cmd->run(); + if (finished) + { + break; + } + double t = (double)(tmr.time()) / 1000.0; + bool timed_out = t > ri->cmd->timeout_seconds; + bool should_timeout = ri->cmd->timeout_seconds > 0; + + if (timed_out && should_timeout) + { + ri->cmd->on_timeout(); + } + vexDelay(20); + } + + if ((*ri->runners)[ri->index] != nullptr) + { + delete (*ri->runners)[ri->index]; + (*ri->runners)[ri->index] = nullptr; + } + return 0; +} + +// wait for all to finish +Parallel::Parallel(std::initializer_list cmds) : cmds(cmds), runners(0) {} + +bool Parallel::run() +{ + if (runners.size() == 0) + { + // not initialized yet + for (int i = 0; i < cmds.size(); i++) + { + parallel_runner_info *ri = new parallel_runner_info{ + .index = i, + .runners = &runners, + .cmd = cmds[i], + }; + runners.push_back(new vex::task(parallel_runner, ri)); + } + } + + bool all_finished = true; + + for (int i = 0; i < cmds.size(); i++) + { + if (runners[i] != nullptr) + { + all_finished = false; + } + } + return all_finished; +} +void Parallel::on_timeout() +{ + for (int i = 0; i < runners.size(); i++) + { + + if (runners[i] != nullptr) + { + runners[i]->stop(); + if (cmds[i] != nullptr) + { + cmds[i]->on_timeout(); + } + delete runners[i]; + runners[i] = nullptr; + if (cmds[i] != nullptr) + { + delete cmds[i]; + cmds[i] = nullptr; + } + } + } +} + +Branch::Branch(Condition *cond, AutoCommand *false_choice, AutoCommand *true_choice) : false_choice(false_choice), true_choice(true_choice), cond(cond), choice(false), chosen(false), tmr() {} + +Branch::~Branch() +{ + delete false_choice; + delete true_choice; +}; +bool Branch::run() +{ + if (!chosen) + { + choice = cond->test(); + chosen = true; + } + + double seconds = static_cast(tmr.time()) / 1000.0; + if (choice == false) + { + if (seconds > false_choice->timeout_seconds && false_choice->timeout_seconds != -1) + { + false_choice->on_timeout(); + } + return false_choice->run(); + } + else + { + if (seconds > true_choice->timeout_seconds && true_choice->timeout_seconds != -1) + { + true_choice->on_timeout(); + } + return true_choice->run(); + } +} +void Branch::on_timeout() +{ + if (!chosen) + { + // dont need to do anything + return; + } + + if (choice == false) + { + false_choice->on_timeout(); + } + else + { + true_choice->on_timeout(); + } +} + +static int async_runner(void *arg) +{ + AutoCommand *cmd = (AutoCommand *)arg; + vex::timer tmr; + while (1) + { + bool finished = cmd->run(); + if (finished) + { + break; + } + double t = (double)(tmr.time()) / 1000.0; + bool timed_out = t > cmd->timeout_seconds; + bool should_timeout = cmd->timeout_seconds > 0; + if (timed_out && should_timeout) + { + cmd->on_timeout(); + break; + } + vexDelay(20); + } + delete cmd; + + return 0; +} +bool Async::run() +{ + vex::task *t = new vex::task(async_runner, (void *)cmd); + (void)t; + // lmao get memory leaked + return true; +} diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index 782ca0a..37bfa84 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -62,6 +62,11 @@ void CommandController::add_delay(int ms) command_queue.push(delay); } + +void CommandController::add_cancel_func(std::function true_if_cancel){ + should_cancel = true_if_cancel; +} + /** * Begin execution of the queue * Execute and remove commands in FIFO order @@ -75,7 +80,7 @@ void CommandController::run() vex::timer tmr; tmr.reset(); - while (!command_queue.empty()) + while (!command_queue.empty() ) { // retrieve and remove command at the front of the queue next_cmd = command_queue.front(); @@ -101,13 +106,16 @@ void CommandController::run() // If we do want to check for timeout, check and end the command if we should double cmd_elapsed_sec = ((double)timeout_timer.time()) / 1000.0; - if (cmd_elapsed_sec > next_cmd->timeout_seconds) + if (cmd_elapsed_sec > next_cmd->timeout_seconds || should_cancel()) { next_cmd->on_timeout(); command_timed_out = true; break; } } + if (should_cancel()){ + break; + } printf("Finished Command %d. Timed out: %s\n", command_count, command_timed_out ? "true" : "false"); fflush(stdout); From 7dd16360d284c99efa01a616917e43e932e402c6 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 1 Oct 2023 14:11:36 -0400 Subject: [PATCH 225/243] Added pure pursuit commands in tank_drive --- include/subsystems/tank_drive.h | 3 +++ src/subsystems/tank_drive.cpp | 8 ++++++++ 2 files changed, 11 insertions(+) diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 3b3887d..02edee4 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -43,6 +43,9 @@ class TankDrive AutoCommand *TurnDegreesCmd(double degrees, double max_speed = 1.0); AutoCommand *TurnDegreesCmd(Feedback &fb, double degrees, double max_speed = 1.0); + AutoCommand *PurePursuitCmd(std::vector path, directionType dir, double radius, double max_speed=1); + AutoCommand *PurePursuitCmd(Feedback &feedback, std::vector path, directionType dir, double radius, double max_speed=1); + /** * Stops rotation of all the motors using their "brake mode" */ diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 2afb3f9..095cf80 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -48,6 +48,14 @@ AutoCommand *TankDrive::TurnDegreesCmd(Feedback &fb, double degrees, double max_ { return new TurnDegreesCommand(*this, fb, degrees, max_speed); } +AutoCommand *TankDrive::PurePursuitCmd(std::vector path, directionType dir, double radius, double max_speed) +{ + return new PurePursuitCommand(*this, *drive_default_feedback, path, dir, radius, max_speed); +} +AutoCommand *TankDrive::PurePursuitCmd(Feedback &feedback, std::vector path, directionType dir, double radius, double max_speed) +{ + return new PurePursuitCommand(*this, feedback, path, dir, radius, max_speed); +} /** * Reset the initialization for autonomous drive functions From 1e7a752a254a10f34a4b4b1098e568984c8168f8 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 1 Oct 2023 17:41:24 -0400 Subject: [PATCH 226/243] Updated const parameters --- include/utils/geometry.h | 2 +- include/utils/math_util.h | 2 +- include/utils/pure_pursuit.h | 16 ++++++++-------- src/utils/math_util.cpp | 2 +- src/utils/pure_pursuit.cpp | 12 ++++++------ 5 files changed, 17 insertions(+), 17 deletions(-) diff --git a/include/utils/geometry.h b/include/utils/geometry.h index b653031..1226e49 100644 --- a/include/utils/geometry.h +++ b/include/utils/geometry.h @@ -14,7 +14,7 @@ struct point_t * @param other the point to measure the distance from * @return the euclidian distance between this and other */ - double dist(const point_t other) + double dist(const point_t other) const { return std::sqrt(std::pow(this->x - other.x, 2) + pow(this->y - other.y, 2)); } diff --git a/include/utils/math_util.h b/include/utils/math_util.h index 4ec27c9..8cfc91c 100644 --- a/include/utils/math_util.h +++ b/include/utils/math_util.h @@ -56,4 +56,4 @@ Calculates the slope and y intercept of the line of best fit for the data */ std::pair calculate_linear_regression(std::vector> const &points); -double estimate_path_length(std::vector points); \ No newline at end of file +double estimate_path_length(const std::vector &points); \ No newline at end of file diff --git a/include/utils/pure_pursuit.h b/include/utils/pure_pursuit.h index 66cd15a..9d3b17c 100644 --- a/include/utils/pure_pursuit.h +++ b/include/utils/pure_pursuit.h @@ -31,11 +31,11 @@ namespace PurePursuit { double dir; double mag; - point_t getPoint() { + point_t getPoint() const { return {x, y}; } - Vector2D getTangent() { + Vector2D getTangent() const { return Vector2D(dir, mag); } }; @@ -48,12 +48,12 @@ namespace PurePursuit { /** * Selects a look ahead from all the intersections in the path. */ - extern point_t get_lookahead(std::vector path, pose_t robot_loc, double radius); + extern point_t get_lookahead(const std::vector &path, pose_t robot_loc, double radius); /** * Injects points in a path without changing the curvature with a certain spacing. */ - extern std::vector inject_path(std::vector path, double spacing); + extern std::vector inject_path(const std::vector &path, double spacing); /** * Returns a smoothed path maintaining the start and end of the path. @@ -66,9 +66,9 @@ namespace PurePursuit { * https://medium.com/@jaems33/understanding-robot-motion-path-smoothing-5970c8363bc4 */ - extern std::vector smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance); + extern std::vector smooth_path(const std::vector &path, double weight_data, double weight_smooth, double tolerance); - extern std::vector smooth_path_cubic(std::vector path, double res); + extern std::vector smooth_path_cubic(const std::vector &path, double res); /** * Interpolates a smooth path given a list of waypoints using hermite splines. @@ -78,7 +78,7 @@ namespace PurePursuit { * @param steps The number of points interpolated between points. * @return The smoothed path. */ - extern std::vector smooth_path_hermite(std::vector path, double step); + extern std::vector smooth_path_hermite(const std::vector &path, double step); /** * Estimates the remaining distance from the robot's position to the end, @@ -90,6 +90,6 @@ namespace PurePursuit { * @param radius Pure pursuit "radius", used to search for the robot along the path * @return A rough estimate of the remaining distance */ - extern double estimate_remaining_dist(std::vector path, pose_t robot_pose, double radius); + extern double estimate_remaining_dist(const std::vector &path, pose_t robot_pose, double radius); } \ No newline at end of file diff --git a/src/utils/math_util.cpp b/src/utils/math_util.cpp index 494f9d4..6d28630 100644 --- a/src/utils/math_util.cpp +++ b/src/utils/math_util.cpp @@ -119,7 +119,7 @@ std::pair calculate_linear_regression(std::vector points) +double estimate_path_length(const std::vector &points) { double dist = 0; diff --git a/src/utils/pure_pursuit.cpp b/src/utils/pure_pursuit.cpp index dfdbc9c..34db5a6 100644 --- a/src/utils/pure_pursuit.cpp +++ b/src/utils/pure_pursuit.cpp @@ -52,7 +52,7 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub /** * Selects a look ahead from all the intersections in the path. */ -[[maybe_unused]] point_t PurePursuit::get_lookahead(std::vector path, pose_t robot_loc, double radius) +[[maybe_unused]] point_t PurePursuit::get_lookahead(const std::vector &path, pose_t robot_loc, double radius) { //Default: the end of the path point_t target = path.back(); @@ -85,7 +85,7 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub /** Injects points in a path without changing the curvature with a certain spacing. */ -[[maybe_unused]] std::vector PurePursuit::inject_path(std::vector path, double spacing) +[[maybe_unused]] std::vector PurePursuit::inject_path(const std::vector &path, double spacing) { std::vector new_path; @@ -125,7 +125,7 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub * Honestly have no idea if/how this works. * https://medium.com/@jaems33/understanding-robot-motion-path-smoothing-5970c8363bc4 */ -[[maybe_unused]] std::vector PurePursuit::smooth_path(std::vector path, double weight_data, double weight_smooth, double tolerance) +[[maybe_unused]] std::vector PurePursuit::smooth_path(const std::vector &path, double weight_data, double weight_smooth, double tolerance) { std::vector new_path = path; double change = tolerance; @@ -159,7 +159,7 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub * @param steps The number of points interpolated between points. * @return The smoothed path. */ -[[maybe_unused]] std::vector PurePursuit::smooth_path_hermite(std::vector path, double steps) { +[[maybe_unused]] std::vector PurePursuit::smooth_path_hermite(const std::vector &path, double steps) { std::vector new_path; for(int i = 0; i < path.size() - 1; i++) { for(int t = 0; t < steps; t++) { @@ -191,7 +191,7 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub return new_path; } -[[maybe_unused]] std::vector PurePursuit::smooth_path_cubic(std::vector path, double res) { +[[maybe_unused]] std::vector PurePursuit::smooth_path_cubic(const std::vector &path, double res) { std::vector new_path; std::vector splines; @@ -245,7 +245,7 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub * @param radius Pure pursuit "radius", used to search for the robot along the path * @return A rough estimate of the remaining distance */ -double PurePursuit::estimate_remaining_dist(std::vector path, pose_t robot_pose, double radius) +double PurePursuit::estimate_remaining_dist(const std::vector &path, pose_t robot_pose, double radius) { point_t lookahead_pt = get_lookahead(path, robot_pose, radius); From ff8dc3d3ce617174d35510989df7a32503fb4778 Mon Sep 17 00:00:00 2001 From: cowsed Date: Thu, 5 Oct 2023 21:50:57 -0400 Subject: [PATCH 227/243] fixed warnings --- include/utils/command_structure/command_controller.h | 4 ++-- src/utils/serializer.cpp | 10 +++++----- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/include/utils/command_structure/command_controller.h b/include/utils/command_structure/command_controller.h index 3bae711..4f8cf14 100644 --- a/include/utils/command_structure/command_controller.h +++ b/include/utils/command_structure/command_controller.h @@ -26,7 +26,7 @@ class CommandController * @param cmd the AutoCommand we want to add to our list * @param timeout_seconds the number of seconds we will let the command run for. If it exceeds this, we cancel it and run on_timeout. if it is <= 0 no time out will be applied */ - [[deprecated("Use list constructor instead. If you need to make a decision before adding new commands, use Branch")]] void add(std::vector cmds); + [[deprecated("Use list constructor instead. If you need to make a decision before adding new commands, use Branch (https://github.com/RIT-VEX-U/Core/wiki/3-%7C-Utilites#commandcontroller)")]] void add(std::vector cmds); void add(AutoCommand *cmd, double timeout_seconds = 10.0); /** @@ -39,7 +39,7 @@ class CommandController * @param cmds the AutoCommands we want to add to our list * @param timeout_sec timeout in seconds to apply to all commands if they are still the default */ - [[deprecated("Use list constructor instead. If you need to make a decision before adding new commands, use Branch")]] void + [[deprecated("Use list constructor instead. If you need to make a decision before adding new commands, use Branch (https://github.com/RIT-VEX-U/Core/wiki/3-%7C-Utilites#commandcontroller)")]] void add(std::vector cmds, double timeout_sec); /** * Adds a command that will delay progression diff --git a/src/utils/serializer.cpp b/src/utils/serializer.cpp index c93d1ad..9e611f1 100644 --- a/src/utils/serializer.cpp +++ b/src/utils/serializer.cpp @@ -32,7 +32,7 @@ std::vector to_bytes(std::string str) /// @brief Convert bytes to a type /// @param gets data from arbitrary bytes. Overload this for non integer types template -T from_bytes(const std::vector &data, std::vector::const_iterator &position) +T from_bytes(std::vector::const_iterator &position) { T value; std::copy(position, position + sizeof(T), static_cast(static_cast(&value))); @@ -41,7 +41,7 @@ T from_bytes(const std::vector &data, std::vector::const_iterator &p } template <> -std::string from_bytes(const std::vector &data, std::vector::const_iterator &position) +std::string from_bytes(std::vector::const_iterator &position) { auto pos = position; while (*pos != 0x0) @@ -110,10 +110,10 @@ static std::vector::const_iterator read_data(const std::vector &data { auto name_start = pos; // read name - std::string name = from_bytes(data, name_start); + std::string name = from_bytes(name_start); pos += name.size() + 1; // read value - value_type value = from_bytes(data, pos); + value_type value = from_bytes(pos); printf("Read Name: %s\n", name.c_str()); map.insert({name, value}); } @@ -247,7 +247,7 @@ bool Serializer::read_from_disk() auto doubles_start = read_data(data, bool_start, bools); auto strings_start = read_data(data, doubles_start, doubles); auto file_end = read_data(data, strings_start, strings); - + (void)file_end; return true; } From db61c54f2809f20a8eb8576d9335101ad7ee346b Mon Sep 17 00:00:00 2001 From: cowsed Date: Tue, 10 Oct 2023 19:02:46 -0400 Subject: [PATCH 228/243] started, breaking --- include/subsystems/screen.h | 74 +++++++++++++--- src/subsystems/screen.cpp | 169 ++++++++++++++++++++++++++++++------ 2 files changed, 204 insertions(+), 39 deletions(-) diff --git a/include/subsystems/screen.h b/include/subsystems/screen.h index 60a49ef..5ba4770 100644 --- a/include/subsystems/screen.h +++ b/include/subsystems/screen.h @@ -1,24 +1,72 @@ #pragma once #include "vex.h" #include +#include -/// @brief the type of function that the screen controller expects -/// @param screen a reference to the screen to draw on -/// @param x the x position this widget has been told to start at -/// @param y the y position this widget has been told to start at +namespace screen +{ + /** + * @brief Start the screen background task. Once you start this, no need to draw to the screen manually elsewhere + * @param screen reference to the vex screen + * @param pages drawing pages + * @param first_page optional, which page to start the program at. by default 0 + */ + void start_screen(vex::brain::lcd &screen, std::vector pages, int first_page = 0); -typedef void (*screenFunc)(vex::brain::lcd &screen, int x, int y, int width, int height, bool first_run); + void stop_screen(); + /// @brief Page describes one part of the screen slideshow + class Page + { + public: + /** + * @brief collect data, respond to screen input, do fast things (runs at + * 50hz even if you're not focused on this Page (only drawn page gets + * touch updates)) + * @param was_pressed true if the screen has been pressed + * @param x x position of screen press (if the screen was pressed) + * @param y y position of screen press (if the screen was pressed) + */ + virtual void update(bool was_pressed, int x, int y); + /** + * @brief draw stored data to the screen (runs at 10 hz and only runs if + * this page is in front) + * @param first_draw true if we just switched to this page + * @param frame_number frame of drawing we are on (basically an animation + * tick) + */ + virtual void draw(vex::brain::lcd &screen, bool first_draw, + unsigned int frame_number); + }; -void draw_mot_header(vex::brain::lcd &screen, int x, int y, int width); -// name should be no longer than 15 characters -void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char *name, vex::motor &motor, int animation_tick); -void draw_dev_stats(vex::brain::lcd &screen, int x, int y, int width, const char *name, vex::device &dev, int animation_tick); + /// @brief type of function needed for update + using update_func_t = std::function; -void draw_battery_stats(vex::brain::lcd &screen, int x, int y, double voltage, double percentage); + /// @brief type of function needed for draw + using draw_func_t = std::function; + class MotorPage : public Page + { + public: + MotorPage(std::map motors) : motors(motors) {} + void update(bool was_pressed, int x, int y) override; + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; + private: + std::map motors; + }; -void draw_lr_arrows(vex::brain::lcd &screen, int bar_width, int width, int height); + /// @brief Simple page that stores no internal data. the draw and update functions use only global data rather than storing anything + class FunctionPage : public Page + { + public: + FunctionPage(update_func_t update_f, draw_func_t draw_t); -int handle_screen_thread(vex::brain::lcd &screen, std::vector pages, int first_page); -void StartScreen(vex::brain::lcd &screen, std::vector pages, int first_page = 0); \ No newline at end of file + void update(bool was_pressed, int x, int y) override; + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; + + private: + update_func_t update_f; + draw_func_t draw_f; + }; + +} diff --git a/src/subsystems/screen.cpp b/src/subsystems/screen.cpp index 13af0c8..6f5acd7 100644 --- a/src/subsystems/screen.cpp +++ b/src/subsystems/screen.cpp @@ -1,6 +1,117 @@ #include "../core/include/subsystems/screen.h" -void draw_battery_stats(vex::brain::lcd &screen, int x, int y, double voltage, double percentage) +namespace screen +{ + /// @brief start_screen begins a screen. only call this once per program (a + /// good place is vexcodeInit) + /// This is a set and forget type function. You don't have to wait on it or + /// start it in a new thread + /// @param screen the brain screen + /// @param pages the list of pages in your UI slideshow + /// @param first_page the page to start on (by default 0) + void start_screen(vex::brain::lcd &screen, std::vector pages, + int first_page) + { + if (running) + { + printf("THERE IS ALREADY A SCREEN THREAD RUNNING\n"); + return; + } + ScreenData *data = new ScreenData{pages, first_page, &screen}; + + screen_thread = new vex::thread(screen_thread_func, static_cast(data)); + } + + void stop_screen() { running = false; } + /** + * @brief The ScreenData class holds the data that will be passed to the + * screen thread + * you probably shouldnt have to use it + */ + struct ScreenData + { + ScreenData(const std::vector &m_pages, int m_page, vex::brain::lcd *m_screen) + : pages(m_pages), page(m_page), screen(m_screen) {} + std::vector pages; + int page = 0; + vex::brain::lcd *screen = nullptr; + }; + + static vex::thread *screen_thread = nullptr; + static bool running = false; + + /** + * @brief runs the screen thread + * This should only be called by start_screen + * If you are calling this, maybe don't + */ + int screen_thread_func(void *screen_data_v) + { + ScreenData screen_data = *static_cast(screen_data_v); + running = true; + unsigned int frame = 0; + + bool was_pressed = false; + int x_press = 0; + int y_press = 0; + + while (running) + { + Page *front_page = screen_data.pages[screen_data.page]; + + // Update all pages + for (auto page : screen_data.pages) + { + if (page == front_page) + { + page->update(was_pressed, x_press, y_press); + } + else + { + page->update(false, 0, 0); + } + } + + // Draw First Page + if (frame % 5 == 0) + { + front_page->draw(*screen_data.screen, false, frame); + } + + vexDelay(20); + } + + return 0; + } + /** + * @brief FunctionPage + * @param update_f drawing function + * @param draw_f drawing function + */ + FunctionPage::FunctionPage(update_func_t update_f, draw_func_t draw_f) + : update_f(update_f), draw_f(draw_f) + { + } + + /// @brief update uses the supplied update function to update this page + void FunctionPage::update(bool was_pressed, int x, int y) + { + update_f(was_pressed, x, y); + } + /// @brief draw uses the supplied draw function to draw to the screen + void FunctionPage::draw(vex::brain::lcd &screen, bool first_draw, + unsigned int frame_number) + { + draw_f(screen, first_draw, frame_number); + } + + MotorPage::MotorPage(std::map motors) + +} // namespace screen + +/* +void draw_battery_stats(vex::brain::lcd &screen, int x, int y, double +voltage, double percentage) { double low_pct = 70.0; double med_pct = 85.0; @@ -9,8 +120,6 @@ void draw_battery_stats(vex::brain::lcd &screen, int x, int y, double voltage, d vex::color med_col = vex::color(140, 100, 0); vex::color high_col = vex::black; - - vex::color bg_col = vex::black; vex::color border_col = vex::white; @@ -32,9 +141,9 @@ void draw_battery_stats(vex::brain::lcd &screen, int x, int y, double voltage, d screen.setPenColor(border_col); screen.setFont(vex::mono15); - - screen.drawRectangle(x+3, y, 200-3, 20); - screen.printAt(x + 5, y + 15, "battery: %.1fv %d%%", voltage, (int)percentage); + screen.drawRectangle(x + 3, y, 200 - 3, 20); + screen.printAt(x + 5, y + 15, "battery: %.1fv %d%%", voltage, +(int)percentage); } void draw_mot_header(vex::brain::lcd &screen, int x, int y, int width) @@ -46,7 +155,7 @@ void draw_mot_header(vex::brain::lcd &screen, int x, int y, int width) screen.setPenColor(border_col); screen.setFont(vex::mono15); - screen.drawRectangle(x+3, y, width-3, 20); + screen.drawRectangle(x + 3, y, width - 3, 20); screen.printAt(x + 5, y + 15, "motor name"); int name_width = 110; @@ -59,7 +168,8 @@ void draw_mot_header(vex::brain::lcd &screen, int x, int y, int width) screen.printAt(x + name_width + 55, y + 15, "port"); } -void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char *name, vex::motor &motor, int animation_tick) +void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const +char *name, vex::motor &motor, int animation_tick) { double tempC = motor.temperature(vex::celsius); bool pluggedin = motor.installed(); @@ -101,7 +211,7 @@ void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char screen.setPenColor(border_col); screen.setFont(vex::mono15); - screen.drawRectangle(x+3, y, width-3, 20); + screen.drawRectangle(x + 3, y, width - 3, 20); // name screen.printAt(x + 7, y + 15, name); @@ -122,7 +232,8 @@ void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const char } // -void draw_dev_stats(vex::brain::lcd &screen, int x, int y, int width, const char *name, vex::device &dev, int animation_tick) +void draw_dev_stats(vex::brain::lcd &screen, int x, int y, int width, const +char *name, vex::device &dev, int animation_tick) { bool pluggedin = dev.installed(); int port = dev.index() + 1; @@ -145,7 +256,7 @@ void draw_dev_stats(vex::brain::lcd &screen, int x, int y, int width, const char screen.setPenColor(border_col); screen.setFont(vex::mono15); - screen.drawRectangle(x+3, y, width-3, 20); + screen.drawRectangle(x + 3, y, width - 3, 20); // name screen.printAt(x + 5, y + 15, name); @@ -165,7 +276,8 @@ void draw_dev_stats(vex::brain::lcd &screen, int x, int y, int width, const char screen.printAt(x + name_width + 60, y + 15, "%d%s", port, warning); } -void draw_lr_arrows(vex::brain::lcd &screen, int bar_width, int width, int height) +void draw_lr_arrows(vex::brain::lcd &screen, int bar_width, int width, int +height) { auto bar_col = vex::color(40, 40, 40); auto arrow_col = vex::color(255, 255, 255); @@ -178,14 +290,17 @@ void draw_lr_arrows(vex::brain::lcd &screen, int bar_width, int width, int heigh // draw arrows screen.setPenColor(arrow_col); - screen.drawLine(bar_width / 3, height / 2, 2 * bar_width / 3, height / 2 - 20); - screen.drawLine(bar_width / 3, height / 2, 2 * bar_width / 3, height / 2 + 20); + screen.drawLine(bar_width / 3, height / 2, 2 * bar_width / 3, height / 2 +- 20); screen.drawLine(bar_width / 3, height / 2, 2 * bar_width / 3, height +/ 2 + 20); - screen.drawLine(width - bar_width / 3, height / 2, width - 2 * bar_width / 3, height / 2 - 20); - screen.drawLine(width - bar_width / 3, height / 2, width - 2 * bar_width / 3, height / 2 + 20); + screen.drawLine(width - bar_width / 3, height / 2, width - 2 * bar_width +/ 3, height / 2 - 20); screen.drawLine(width - bar_width / 3, height / 2, +width - 2 * bar_width / 3, height / 2 + 20); } -int handle_screen_thread(vex::brain::lcd &screen, std::vector pages, int first_page) +int handle_screen_thread(vex::brain::lcd &screen, std::vector +pages, int first_page) { unsigned int num_pages = pages.size(); unsigned int current_page = first_page; @@ -199,7 +314,8 @@ int handle_screen_thread(vex::brain::lcd &screen, std::vector pages, bool first_draw = true; while (true) { - pages[current_page](screen, bar_width, 0, width - bar_width * 2, height, first_draw); + pages[current_page](screen, bar_width, 0, width - bar_width * 2, +height, first_draw); first_draw = false; // handle presses @@ -235,12 +351,13 @@ int handle_screen_thread(vex::brain::lcd &screen, std::vector pages, return 0; } -void StartScreen(vex::brain::lcd &screen, std::vector pages, int first_page) +void StartScreen(vex::brain::lcd &screen, std::vector pages, int +first_page) { - // hold onto arguments here so we don't lose them and can use then in the lambda down there. capture semantics are not fun - static std::vector my_pages = pages; - static vex::brain::lcd my_screen = screen; - static int my_first_page = first_page; - vex::task screenTask([]() - { return handle_screen_thread(my_screen, my_pages, my_first_page); }); -} \ No newline at end of file + // hold onto arguments here so we don't lose them and can use then in +the lambda down there. capture semantics are not fun static +std::vector my_pages = pages; static vex::brain::lcd my_screen = +screen; static int my_first_page = first_page; vex::task screenTask([]() { +return handle_screen_thread(my_screen, my_pages, my_first_page); }); +} +*/ From 86fe9f05228a8b31fc2c61e62482e532019f5ec7 Mon Sep 17 00:00:00 2001 From: cowsed Date: Tue, 10 Oct 2023 19:05:48 -0400 Subject: [PATCH 229/243] more --- include/subsystems/screen.h | 22 +++++++++++++--------- 1 file changed, 13 insertions(+), 9 deletions(-) diff --git a/include/subsystems/screen.h b/include/subsystems/screen.h index 5ba4770..589fefc 100644 --- a/include/subsystems/screen.h +++ b/include/subsystems/screen.h @@ -5,15 +5,6 @@ namespace screen { - /** - * @brief Start the screen background task. Once you start this, no need to draw to the screen manually elsewhere - * @param screen reference to the vex screen - * @param pages drawing pages - * @param first_page optional, which page to start the program at. by default 0 - */ - void start_screen(vex::brain::lcd &screen, std::vector pages, int first_page = 0); - - void stop_screen(); /// @brief Page describes one part of the screen slideshow class Page { @@ -38,6 +29,19 @@ namespace screen unsigned int frame_number); }; + + /** + * @brief Start the screen background task. Once you start this, no need to draw to the screen manually elsewhere + * @param screen reference to the vex screen + * @param pages drawing pages + * @param first_page optional, which page to start the program at. by default 0 + */ + void start_screen(vex::brain::lcd &screen, std::vector pages, int first_page = 0); + + void stop_screen(); + + + /// @brief type of function needed for update using update_func_t = std::function; From 36fa87e8cb4cce7dc6829b3410f5f81b976eb376 Mon Sep 17 00:00:00 2001 From: cowsed Date: Tue, 10 Oct 2023 22:35:43 -0400 Subject: [PATCH 230/243] odometry map --- include/subsystems/screen.h | 33 +++++- include/utils/geometry.h | 46 +++++++- src/subsystems/screen.cpp | 213 ++++++++++++++++++++++++++++++++---- 3 files changed, 262 insertions(+), 30 deletions(-) diff --git a/include/subsystems/screen.h b/include/subsystems/screen.h index 589fefc..861f529 100644 --- a/include/subsystems/screen.h +++ b/include/subsystems/screen.h @@ -2,6 +2,8 @@ #include "vex.h" #include #include +#include +#include "../core/include/subsystems/odometry/odometry_base.h" namespace screen { @@ -29,7 +31,6 @@ namespace screen unsigned int frame_number); }; - /** * @brief Start the screen background task. Once you start this, no need to draw to the screen manually elsewhere * @param screen reference to the vex screen @@ -40,23 +41,43 @@ namespace screen void stop_screen(); - - /// @brief type of function needed for update using update_func_t = std::function; /// @brief type of function needed for draw using draw_func_t = std::function; - class MotorPage : public Page + class StatsPage : public Page + { + public: + StatsPage(std::map motors); + void update(bool was_pressed, int x, int y) override; + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; + + private: + void draw_motor_stats(const std::string &name, vex::motor &mot, unsigned int frame, int x, int y, vex::brain::lcd &scr); + + std::map motors; + static const int y_start = 0; + static const int per_column = 4; + static const int row_height = 20; + static const int row_width = 200; + }; + + class OdometryPage : public Page { public: - MotorPage(std::map motors) : motors(motors) {} + OdometryPage(OdometryBase &odom, double width, double height); void update(bool was_pressed, int x, int y) override; void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; private: - std::map motors; + OdometryBase &odom; + double width; + double height; + uint8_t *buf = nullptr; + int buf_size = 0; + static constexpr char const *field_filename = "vex_field_240p.png"; }; /// @brief Simple page that stores no internal data. the draw and update functions use only global data rather than storing anything diff --git a/include/utils/geometry.h b/include/utils/geometry.h index 1226e49..c01c186 100644 --- a/include/utils/geometry.h +++ b/include/utils/geometry.h @@ -45,12 +45,27 @@ struct point_t return p; } - bool operator==(const point_t& rhs) + point_t operator*(double s) const { - return x==rhs.x && y==rhs.y; + return {x * s, y * s}; + } + point_t operator/(double s) const + { + return {x / s, y / s}; } -}; + point_t operator-() const{ + return {-x, -y}; + } + point_t operator+() const{ + return {x, y}; + } + + bool operator==(const point_t &rhs) + { + return x == rhs.x && y == rhs.y; + } +}; /** * Describes a single position and rotation @@ -63,6 +78,27 @@ typedef struct point_t get_point() { - return point_t{.x=x, .y=y}; + return point_t{.x = x, .y = y}; + } + +} pose_t; + +struct Mat2 +{ + double X11, X12; + double X21, X22; + point_t operator*(const point_t p) const + { + double outx = p.x * X11 + p.y * X12; + double outy = p.x * X21 + p.y * X22; + return {outx, outy}; + } + + static Mat2 FromRotationDegrees(double degrees) + { + double rad = degrees * (M_PI / 180.0); + double c = cos(rad); + double s = sin(rad); + return {c, -s, s, c}; } -} pose_t; \ No newline at end of file +}; \ No newline at end of file diff --git a/src/subsystems/screen.cpp b/src/subsystems/screen.cpp index 6f5acd7..a0d52f6 100644 --- a/src/subsystems/screen.cpp +++ b/src/subsystems/screen.cpp @@ -2,6 +2,24 @@ namespace screen { + /** + * @brief The ScreenData class holds the data that will be passed to the + * screen thread + * you probably shouldnt have to use it + */ + struct ScreenData + { + ScreenData(const std::vector &m_pages, int m_page, vex::brain::lcd &m_screen) + : pages(m_pages), page(m_page), screen(m_screen) {} + std::vector pages; + int page = 0; + vex::brain::lcd screen; + }; + + static vex::thread *screen_thread = nullptr; + static bool running = false; + static int screen_thread_func(void *screen_data_v); + /// @brief start_screen begins a screen. only call this once per program (a /// good place is vexcodeInit) /// This is a set and forget type function. You don't have to wait on it or @@ -17,28 +35,12 @@ namespace screen printf("THERE IS ALREADY A SCREEN THREAD RUNNING\n"); return; } - ScreenData *data = new ScreenData{pages, first_page, &screen}; + ScreenData *data = new ScreenData{pages, first_page, screen}; screen_thread = new vex::thread(screen_thread_func, static_cast(data)); } void stop_screen() { running = false; } - /** - * @brief The ScreenData class holds the data that will be passed to the - * screen thread - * you probably shouldnt have to use it - */ - struct ScreenData - { - ScreenData(const std::vector &m_pages, int m_page, vex::brain::lcd *m_screen) - : pages(m_pages), page(m_page), screen(m_screen) {} - std::vector pages; - int page = 0; - vex::brain::lcd *screen = nullptr; - }; - - static vex::thread *screen_thread = nullptr; - static bool running = false; /** * @brief runs the screen thread @@ -58,6 +60,29 @@ namespace screen while (running) { Page *front_page = screen_data.pages[screen_data.page]; + bool pressing = screen_data.screen.pressing(); + + if (pressing) + { + pressing = true; + x_press = screen_data.screen.xPosition(); + y_press = screen_data.screen.yPosition(); + } + bool just_pressed = pressing && !was_pressed; + + if (just_pressed && x_press < 40) + { + screen_data.page--; + if (screen_data.page < 0) + { + screen_data.page += screen_data.pages.size(); + } + } + if (just_pressed && x_press > 440) + { + screen_data.page++; + screen_data.page %= screen_data.pages.size(); + } // Update all pages for (auto page : screen_data.pages) @@ -75,9 +100,28 @@ namespace screen // Draw First Page if (frame % 5 == 0) { - front_page->draw(*screen_data.screen, false, frame); + screen_data.screen.clearScreen(vex::color::black); + screen_data.screen.setPenColor("#FFFFFF"); + screen_data.screen.setFillColor("#000000"); + front_page->draw(screen_data.screen, false, frame / 5); + + // Draw side boxes + screen_data.screen.setPenColor("#202020"); + screen_data.screen.setFillColor("#202020"); + screen_data.screen.drawRectangle(0, 0, 40, 240); + screen_data.screen.drawRectangle(440, 0, 40, 240); + screen_data.screen.setPenColor("#FFFFFF"); + // left arrow + screen_data.screen.drawLine(30, 100, 15, 120); + screen_data.screen.drawLine(30, 140, 15, 120); + // right arrow + screen_data.screen.drawLine(450, 100, 465, 120); + screen_data.screen.drawLine(450, 140, 465, 120); } + screen_data.screen.render(); + frame++; + was_pressed = pressing; vexDelay(20); } @@ -105,8 +149,139 @@ namespace screen draw_f(screen, first_draw, frame_number); } - MotorPage::MotorPage(std::map motors) + StatsPage::StatsPage(std::map motors) : motors(motors) {} + void StatsPage::update(bool was_pressed, int x, int y) + { + (void)x; + (void)y; + (void)was_pressed; + } + void StatsPage::draw_motor_stats(const std::string &name, vex::motor &mot, unsigned int frame, int x, int y, vex::brain::lcd &scr) + { + const vex::color hot_col = vex::color(120, 0, 0); + const vex::color med_col = vex::color(140, 100, 0); + const vex::color ok_col = vex::black; + const vex::color not_plugged_in_col = vex::color(255, 0, 0); + bool installed = mot.installed(); + double temp = 0; + int port = mot.index() + 1; + vex::color col = ok_col; + if (installed) + { + temp = mot.temperature(vex::temperatureUnits::celsius); + } + if (temp > 40) + { + col = med_col; + } + else if (temp > 50) + { + col = hot_col; + } + if (!installed && frame % 2 == 0) + { + col = not_plugged_in_col; + } + + scr.drawRectangle(x, y, row_width, row_height, col); + scr.printAt(x + 2, y + 16, false, " %2d %2.0fC %.7s", port, temp, name.c_str()); + } + void StatsPage::draw(vex::brain::lcd &scr, bool first_draw, unsigned int frame_number) + { + int num = 0; + int x = 40; + int y = y_start + row_height; + scr.drawRectangle(x, y_start, row_width, row_height); + scr.printAt(x, y_start + 16, false, " port temp name"); + for (auto &kv : motors) + { + if (num > per_column) + { + scr.drawRectangle(x + row_width, y_start, row_width, row_height); + scr.printAt(x + row_width, y_start + 16, false, " port temp name"); + + y = y_start + row_height; + x += row_width; + num = 0; + } + + draw_motor_stats(kv.first, kv.second, frame_number, x, y, scr); + y += row_height; + num++; + } + vex::brain b; + scr.printAt(50, 220, "Battery: %2.1fv %2.0fC %d%%", b.Battery.voltage(), b.Battery.temperature(vex::temperatureUnits::celsius), b.Battery.capacity()); + } + + OdometryPage::OdometryPage(OdometryBase &odom, double width, double height) : odom(odom), width(width), height(height) + { + vex::brain b; + + buf_size = b.SDcard.size(field_filename); + buf = (uint8_t *)malloc(buf_size); + b.SDcard.loadfile(field_filename, buf, buf_size); + } + + int in_to_px(double in) + { + double p = in / (6.0 * 24.0); + return (int)(p * 240); + } + + void OdometryPage::draw(vex::brain::lcd &scr, bool first_draw, unsigned int frame_number) + { + auto to_px = [](const point_t p) -> point_t + { + return {(double)in_to_px(p.x) + 200, (double)in_to_px(-p.y) + 240}; + }; + + auto draw_line = [to_px, &scr](const point_t from, const point_t to) + { + scr.drawLine((int)to_px(from).x, (int)to_px(from).y, (int)to_px(to).x, (int)to_px(to).y); + }; + + pose_t pose = odom.get_position(); + point_t pos = pose.get_point(); + fflush(stdout); + scr.printAt(45, 30, "(%.2f, %.2f)", pose.x, pose.y); + scr.printAt(45, 50, "%.2f deg", pose.rot); + + if (buf == nullptr) + { + scr.printAt(320, 110, "Field Image Not Found"); + return; + } + + scr.drawImageFromBuffer(buf, 200, 0, buf_size); + + point_t pos_px = to_px(pos); + scr.drawCircle((int)pos_px.x, (int)pos_px.y, 3, vex::color::white); + + Mat2 mat = Mat2::FromRotationDegrees(pose.rot - 90); + const point_t to_left = point_t{-width / 2.0, 0}; + const point_t to_front = point_t{0.0, height / 2.0}; + + const point_t fl = pos + mat * (+to_left + to_front); + const point_t fr = pos + mat * (-to_left + to_front); + const point_t bl = pos + mat * (+to_left - to_front); + const point_t br = pos + mat * (-to_left - to_front); + const point_t front = pos + mat * (to_front * 2.0); + + + draw_line(fl, fr); + draw_line(fr, br); + draw_line(br, bl); + draw_line(bl, fl); + + draw_line(pos, front); + } + void OdometryPage::update(bool was_pressed, int x, int y) + { + (void)x; + (void)y; + (void)was_pressed; + } } // namespace screen /* From 89c81b7d34e630b52384a320e225af2c4e6b141e Mon Sep 17 00:00:00 2001 From: cowsed Date: Tue, 10 Oct 2023 22:52:53 -0400 Subject: [PATCH 231/243] odometry map with trail --- include/subsystems/screen.h | 12 +++++++++-- include/utils/geometry.h | 6 ++++-- src/subsystems/screen.cpp | 43 ++++++++++++++++++++++++++++++------- 3 files changed, 49 insertions(+), 12 deletions(-) diff --git a/include/subsystems/screen.h b/include/subsystems/screen.h index 861f529..b096bda 100644 --- a/include/subsystems/screen.h +++ b/include/subsystems/screen.h @@ -64,20 +64,28 @@ namespace screen static const int row_width = 200; }; + /** + * @brief a page that shows odometry position and rotation and a map (if an sd card with the file is on) + */ class OdometryPage : public Page { public: - OdometryPage(OdometryBase &odom, double width, double height); + OdometryPage(OdometryBase &odom, double width, double height, bool do_trail); void update(bool was_pressed, int x, int y) override; void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; private: + static const int path_len = 40; + static constexpr char const *field_filename = "vex_field_240p.png"; + OdometryBase &odom; double width; double height; uint8_t *buf = nullptr; int buf_size = 0; - static constexpr char const *field_filename = "vex_field_240p.png"; + pose_t path[path_len]; + int path_index = 0; + bool do_trail; }; /// @brief Simple page that stores no internal data. the draw and update functions use only global data rather than storing anything diff --git a/include/utils/geometry.h b/include/utils/geometry.h index c01c186..52b34b8 100644 --- a/include/utils/geometry.h +++ b/include/utils/geometry.h @@ -54,10 +54,12 @@ struct point_t return {x / s, y / s}; } - point_t operator-() const{ + point_t operator-() const + { return {-x, -y}; } - point_t operator+() const{ + point_t operator+() const + { return {x, y}; } diff --git a/src/subsystems/screen.cpp b/src/subsystems/screen.cpp index a0d52f6..40e11dc 100644 --- a/src/subsystems/screen.cpp +++ b/src/subsystems/screen.cpp @@ -214,13 +214,20 @@ namespace screen scr.printAt(50, 220, "Battery: %2.1fv %2.0fC %d%%", b.Battery.voltage(), b.Battery.temperature(vex::temperatureUnits::celsius), b.Battery.capacity()); } - OdometryPage::OdometryPage(OdometryBase &odom, double width, double height) : odom(odom), width(width), height(height) + OdometryPage::OdometryPage(OdometryBase &odom, double width, double height, bool do_trail) : odom(odom), width(width), height(height), do_trail(do_trail) { vex::brain b; - - buf_size = b.SDcard.size(field_filename); - buf = (uint8_t *)malloc(buf_size); - b.SDcard.loadfile(field_filename, buf, buf_size); + if (b.SDcard.exists(field_filename)) + { + buf_size = b.SDcard.size(field_filename); + buf = (uint8_t *)malloc(buf_size); + b.SDcard.loadfile(field_filename, buf, buf_size); + } + pose_t pos = odom.get_position(); + for (int i = 0; i < path_len; i++) + { + path[i] = pos; + } } int in_to_px(double in) @@ -231,6 +238,13 @@ namespace screen void OdometryPage::draw(vex::brain::lcd &scr, bool first_draw, unsigned int frame_number) { + if (do_trail) + { + path_index++; + path_index %= path_len; + path[path_index] = odom.get_position(); + } + auto to_px = [](const point_t p) -> point_t { return {(double)in_to_px(p.x) + 200, (double)in_to_px(-p.y) + 240}; @@ -241,7 +255,7 @@ namespace screen scr.drawLine((int)to_px(from).x, (int)to_px(from).y, (int)to_px(to).x, (int)to_px(to).y); }; - pose_t pose = odom.get_position(); + pose_t pose = path[path_index]; point_t pos = pose.get_point(); fflush(stdout); scr.printAt(45, 30, "(%.2f, %.2f)", pose.x, pose.y); @@ -249,7 +263,7 @@ namespace screen if (buf == nullptr) { - scr.printAt(320, 110, "Field Image Not Found"); + scr.printAt(180, 110, "Field Image Not Found"); return; } @@ -258,6 +272,20 @@ namespace screen point_t pos_px = to_px(pos); scr.drawCircle((int)pos_px.x, (int)pos_px.y, 3, vex::color::white); + if (do_trail) + { + pose_t last_pos = path[(path_index + 1) % path_len]; + for (int i = path_index + 2; i < path_index + path_len; i++) + { + int j = i % path_len; + pose_t pose = path[j]; + scr.setPenColor(vex::color(80, 80, 80)); + draw_line(pose.get_point(), last_pos.get_point()); + last_pos = pose; + } + } + scr.setPenColor(vex::color::white); + Mat2 mat = Mat2::FromRotationDegrees(pose.rot - 90); const point_t to_left = point_t{-width / 2.0, 0}; const point_t to_front = point_t{0.0, height / 2.0}; @@ -268,7 +296,6 @@ namespace screen const point_t br = pos + mat * (-to_left - to_front); const point_t front = pos + mat * (to_front * 2.0); - draw_line(fl, fr); draw_line(fr, br); draw_line(br, bl); From 4e2530202cd907dbc996358cadcdf18f41193681 Mon Sep 17 00:00:00 2001 From: Richard Sommers <44383226+cowsed@users.noreply.github.com> Date: Sun, 15 Oct 2023 13:59:14 -0400 Subject: [PATCH 232/243] Update main.yml --- .github/workflows/main.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index e93b7f8..9b1d5b7 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -6,7 +6,7 @@ name: Doxygen Action # events but only for the master branch on: push: - branches: [ master ] + branches: [ main ] From d3cf9b7e913760a5046eeec3d0f296c301176b54 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Tue, 31 Oct 2023 13:49:17 -0400 Subject: [PATCH 233/243] Update README.md --- README.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/README.md b/README.md index 6e1e6b0..09e0eb1 100644 --- a/README.md +++ b/README.md @@ -4,6 +4,9 @@ This is the host repository for the custom VEX libraries used by the RIT VEXU te Automatically updated documentation is available at [here](https://rit-vex-u.github.io/Core/). There is also a downloadable [reference manual](https://rit-vex-u.github.io/Core/refman.pdf). +![core_logo](https://github.com/RIT-VEX-U/Core/assets/12285261/e91c680b-5bf4-431c-b164-6631bef2a853) + + ## Getting Started In order to simply use this repo, you can either clone it into your VEXcode project folder, or download the .zip and place it into a core/ subfolder. Then follow the instructions for setting up compilation at [Wiki/BuildSystem](https://github.com/RIT-VEX-U/Core/wiki/1-%7C-Project-Setup#build-system) From b95c030fcee38eeae2b6b76a579f778841fef88e Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 5 Nov 2023 13:35:17 -0500 Subject: [PATCH 234/243] git subrepo pull (merge) core subrepo: subdir: "core" merged: "09f265d" upstream: origin: "git@github.com:RIT-VEX-U/Core.git" branch: "main" commit: "d3cf9b7" git-subrepo: version: "0.4.6" origin: "???" commit: "???" --- include/robot_specs.h | 4 +- include/subsystems/flywheel.h | 207 ++++----- include/subsystems/lift.h | 2 +- include/subsystems/mecanum_drive.h | 2 +- include/subsystems/screen.h | 132 +++++- include/subsystems/tank_drive.h | 57 +-- include/utils/auto_chooser.h | 54 +-- .../utils/command_structure/auto_command.h | 80 +++- .../utils/command_structure/basic_command.h | 118 +++++ .../utils/command_structure/drive_commands.h | 21 +- .../command_structure/flywheel_commands.h | 4 +- include/utils/controls/bang_bang.h | 50 +++ include/utils/{ => controls}/feedback_base.h | 16 +- include/utils/{ => controls}/feedforward.h | 0 .../utils/{ => controls}/motion_controller.h | 13 +- include/utils/{ => controls}/pid.h | 16 +- include/utils/{ => controls}/pidff.h | 10 +- include/utils/controls/take_back_half.h | 59 +++ include/utils/controls/trapezoid_profile.h | 162 +++++++ include/utils/geometry.h | 37 +- include/utils/graph_drawer.h | 38 +- include/utils/logger.h | 2 +- include/utils/math_util.h | 7 + include/utils/moving_average.h | 116 +++-- include/utils/pure_pursuit.h | 33 ++ include/utils/serializer.h | 9 +- include/utils/trapezoid_profile.h | 87 ---- src/subsystems/flywheel.cpp | 402 ++++++------------ src/subsystems/screen.cpp | 351 +++++---------- src/subsystems/tank_drive.cpp | 170 ++++---- src/utils/auto_chooser.cpp | 118 +++-- src/utils/command_structure/auto_command.cpp | 112 ++++- src/utils/command_structure/basic_command.cpp | 89 ++++ .../command_structure/command_controller.cpp | 17 +- .../command_structure/drive_commands.cpp | 45 +- .../command_structure/flywheel_commands.cpp | 8 +- src/utils/controls/bang_bang.cpp | 43 ++ src/utils/{ => controls}/feedforward.cpp | 6 +- .../{ => controls}/motion_controller.cpp | 19 +- src/utils/{ => controls}/pid.cpp | 33 +- src/utils/{ => controls}/pidff.cpp | 6 +- src/utils/controls/take_back_half.cpp | 120 ++++++ src/utils/graph_drawer.cpp | 163 ++++--- src/utils/math_util.cpp | 145 ++++--- src/utils/moving_average.cpp | 123 ++++-- src/utils/pure_pursuit.cpp | 101 +++-- src/utils/serializer.cpp | 36 +- src/utils/trapezoid_profile.cpp | 324 +++++++++++--- 48 files changed, 2401 insertions(+), 1366 deletions(-) create mode 100644 include/utils/command_structure/basic_command.h create mode 100644 include/utils/controls/bang_bang.h rename include/utils/{ => controls}/feedback_base.h (80%) rename include/utils/{ => controls}/feedforward.h (100%) rename include/utils/{ => controls}/motion_controller.h (92%) rename include/utils/{ => controls}/pid.h (90%) rename include/utils/{ => controls}/pidff.h (80%) create mode 100644 include/utils/controls/take_back_half.h create mode 100644 include/utils/controls/trapezoid_profile.h delete mode 100644 include/utils/trapezoid_profile.h create mode 100644 src/utils/command_structure/basic_command.cpp create mode 100644 src/utils/controls/bang_bang.cpp rename src/utils/{ => controls}/feedforward.cpp (95%) rename src/utils/{ => controls}/motion_controller.cpp (90%) rename src/utils/{ => controls}/pid.cpp (83%) rename src/utils/{ => controls}/pidff.cpp (91%) create mode 100644 src/utils/controls/take_back_half.cpp diff --git a/include/robot_specs.h b/include/robot_specs.h index baf9877..9a5fa0c 100644 --- a/include/robot_specs.h +++ b/include/robot_specs.h @@ -1,6 +1,6 @@ #pragma once -#include "../core/include/utils/pid.h" -#include "../core/include/utils/feedback_base.h" +#include "../core/include/utils/controls/pid.h" +#include "../core/include/utils/controls/feedback_base.h" /** * Main robot characterization struct. diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index 31b8e94..c8c42b3 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -1,198 +1,139 @@ #pragma once -/********************************************************* - * - * File: Flywheel.h - * Purpose: Generalized flywheel class for Core. - * Author: Chris Nokes - * - ********************************************************** - * EDIT HISTORY - ********************************************************** - * 09/23/2022 Reorganized, added documentation. - * 09/23/2022 Added functions elaborated on in .cpp. - *********************************************************/ -#include "../core/include/utils/feedforward.h" + +#include "../core/include/utils/controls/feedforward.h" #include "vex.h" #include "../core/include/robot_specs.h" -#include "../core/include/utils/pid.h" +#include "../core/include/utils/controls/pid.h" #include "../core/include/utils/command_structure/auto_command.h" +#include "../core/include/subsystems/screen.h" #include -using namespace vex; - /** * a Flywheel class that handles all control of a high inertia spinning disk * It gives multiple options for what control system to use in order to control wheel velocity and functions alerting the user when the flywheel is up to speed. * Flywheel is a set and forget class. - * Once you create it you can call spinRPM or stop on it at any time and it will take all necessary steps to accomplish this + * Once you create it you can call spin_rpm or stop on it at any time and it will take all necessary steps to accomplish this * */ class Flywheel { - enum FlywheelControlStyle - { - PID_Feedforward, - Feedforward, - Take_Back_Half, - Bang_Bang, - }; public: // CONSTRUCTORS, GETTERS, AND SETTERS /** * Create the Flywheel object using PID + feedforward for control. * @param motors pointer to the motors on the fly wheel - * @param pid_config pointer the pid config to use - * @param ff_config the feedforward config to use - * @param ratio ratio of the whatever just multiplies the velocity - */ - Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio); - - /** - * Create the Flywheel object using only feedforward for control - * @param motors the motors on the fly wheel - * @param ff_config the feedforward config to use - * @param ratio ratio of the whatever just multiplies the velocity - */ - Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio); - - /** - * Create the Flywheel object using Take Back Half for control - * @param motors the motors on the fly wheel - * @param tbh_gain the TBH control paramater - * @param ratio ratio of the whatever just multiplies the velocity - */ - Flywheel(motor_group &motors, double tbh_gain, const double ratio); - - /** - * Create the Flywheel object using Bang Bang for control - * @param motors the motors on the fly wheel - * @param ratio ratio of the whatever just multiplies the velocity - */ - Flywheel(motor_group &motors, const double ratio); - - /** - * Return the RPM that the flywheel is currently trying to achieve - * @return RPM the target rpm + * @param feedback a feedback controleller + * @param helper a feedforward config (only kV is used) to help the feedback controller along + * @param ratio ratio of the gears from the motor to the flywheel just multiplies the velocity + * @param filter the filter to use to smooth noisy motor readings */ - double getDesiredRPM(); + Flywheel(vex::motor_group &motors, Feedback &feedback, FeedForward &helper, const double ratio, Filter &filt); /** - * Checks if the background RPM controlling task is running - * @return true if the task is running + * Return the target_rpm that the flywheel is currently trying to achieve + * @return target_rpm the target rpm */ - bool isTaskRunning(); + double get_target() const; /** - * Returns a POINTER to the motors + * return the velocity of the flywheel */ - motor_group *getMotors(); + double getRPM() const; /** - * make a measurement of the current RPM of the flywheel motor and return a smoothed version + * Returns the motors */ - double measureRPM(); - - /** - * return the current smoothed velocity of the flywheel motors, in RPM - */ - double getRPM(); - /** - * Returns a POINTER to the PID. - */ - PID *getPID(); - - /** - * returns the current OUT value of the PID - the value that the PID would set the motors to - */ - double getPIDValue(); - - /** - * returns the current OUT value of the PID - the value that the PID would set the motors to - */ - double getFeedforwardValue(); - - /** - * get the gain used for TBH control - */ - double getTBHGain(); - - /** - * Sets the value of the PID target - * @param value - desired value of the PID - */ - void setPIDTarget(double value); - - /** - * updates the value of the PID - * @param value - value to update the PID with - */ - void updatePID(double value); - - // SPINNERS AND STOPPERS - - /** - * Spin motors using voltage; defaults forward at 12 volts - * FOR USE BY TASKS ONLY - * @param speed - speed (between -1 and 1) to set the motor - * @param dir - direction that the motor moves in; defaults to forward - */ - void spin_raw(double speed, directionType dir = fwd); + vex::motor_group &get_motors() const; /** * Spin motors using voltage; defaults forward at 12 volts - * FOR USE BY OPCONTROL AND AUTONOMOUS - this only applies if the RPM thread is not running + * FOR USE BY OPCONTROL AND AUTONOMOUS - this only applies if the target_rpm thread is not running * @param speed - speed (between -1 and 1) to set the motor * @param dir - direction that the motor moves in; defaults to forward */ void spin_manual(double speed, directionType dir = fwd); /** - * starts or sets the RPM thread at new value + * starts or sets the target_rpm thread at new value * what control scheme is dependent on control_style - * @param rpm - the RPM we want to spin at + * @param rpm - the target_rpm we want to spin at */ - void spinRPM(int rpm); + void spin_rpm(double rpm); /** - * stop the RPM thread and the wheel + * Stops the motors. If manually spinning, this will do nothing just call spin_mainual(0.0) to send 0 volts */ void stop(); /** - * stop only the motors; exclusively for BANG BANG use + * @brief check if the feedback controller thinks the flywheel is on target + * @return true if on target */ - void stopMotors(); + bool is_on_target() + { + return fb.is_on_target(); + } /** - * Stop the motors if the task isn't running - stop manual control + * @brief Creates a page displaying info about the flywheel + * @return the page should be used for `screen::start_screen(screen, {fw.Page()}); */ - void stopNonTasks(); + screen::Page *Page() const; + /** + * @brief Creates a new auto command to spin the flywheel at the desired velocity + * @param rpm the rpm to spin at + * @return an auto command to add to a command controller + */ AutoCommand *SpinRpmCmd(int rpm) { - return new FunctionCommand([this]() - {spinRPM(1000); return true; }); + return new FunctionCommand([this, rpm]() + {spin_rpm(rpm); return true; }); } + /** + * @brief Creates a new auto command that will hold until the flywheel has its target as defined by its feedback controller + * @return an auto command to add to a command controller + */ AutoCommand *WaitUntilUpToSpeedCmd() { return new WaitUntilCondition( new FunctionCondition([this]() - { return RPM == smoothedRPM; })); + { return is_on_target(); })); } private: - motor_group &motors; // motors that make up the flywheel - bool taskRunning = false; // is the task (thread but not) currently running? - PID pid; // PID on the flywheel - FeedForward ff; // FF constants for the flywheel - double TBH_gain; // TBH gain parameter for the flywheel - double ratio; // multiplies the velocity by this value - std::atomic RPM; // Desired RPM of the flywheel. - task rpmTask; // task (thread but not) that handles spinning the wheel at a given RPM - FlywheelControlStyle control_style; // how the flywheel should be controlled - double smoothedRPM; - MovingAverage RPM_avger; + friend class FlywheelPage; + friend int spinRPMTask(void *wheelPointer); + + vex::motor_group &motors; ///< motors that make up the flywheel + bool task_running = false; ///< is the task currently running? + Feedback &fb; ///< Main Feeback controller + FeedForward &ff; ///< Helper Feedforward Controller + vex::mutex fb_mut; ///< guard for talking to the runner thread + double ratio; ///< ratio between motor and flywheel. For accurate RPM calcualation + std::atomic target_rpm; ///< Desired RPM of the flywheel. + task rpm_task; ///< task that handles spinning the wheel at a given target_rpm + Filter &avger; ///< Moving average to smooth out noise from + + // Functions for internal use only + /** + * Sets the target rpm of the flywheel + * @param value - desired RPM + */ + void set_target(double value); + /** + * make a measurement of the current target_rpm of the flywheel motor and return a smoothed version + */ + double measure_RPM(); + + /** + * Spin motors using voltage; defaults forward at 12 volts + * FOR USE BY TASKS ONLY + * @param speed - speed (between -1 and 1) to set the motor + * @param dir - direction that the motor moves in; defaults to forward + */ + void spin_raw(double speed, directionType dir = fwd); }; \ No newline at end of file diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index d04ddc4..2b45fa7 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -1,7 +1,7 @@ #pragma once #include "vex.h" -#include "../core/include/utils/pid.h" +#include "../core/include/utils/controls/pid.h" #include #include #include diff --git a/include/subsystems/mecanum_drive.h b/include/subsystems/mecanum_drive.h index fdc4777..97f3cdb 100644 --- a/include/subsystems/mecanum_drive.h +++ b/include/subsystems/mecanum_drive.h @@ -1,7 +1,7 @@ #pragma once #include "vex.h" -#include "../core/include/utils/pid.h" +#include "../core/include/utils/controls/pid.h" #ifndef PI #define PI 3.141592654 diff --git a/include/subsystems/screen.h b/include/subsystems/screen.h index b096bda..d5ebcea 100644 --- a/include/subsystems/screen.h +++ b/include/subsystems/screen.h @@ -3,7 +3,11 @@ #include #include #include +#include #include "../core/include/subsystems/odometry/odometry_base.h" +#include "../core/include/utils/graph_drawer.h" +#include "../core/include/utils/controls/pid.h" +#include "../core/include/utils/controls/pidff.h" namespace screen { @@ -31,6 +35,68 @@ namespace screen unsigned int frame_number); }; + /// @brief Widget that updates a double value. Updates by reference so watch out for race conditions cuz the screen stuff lives on another thread + class SliderWidget + { + public: + /// @brief Creates a slider widget + /// @param val reference to the value to modify + /// @param low minimum value to go to + /// @param high maximum value to go to + /// @param rect rect to draw it + /// @param name name of the value + SliderWidget(double &val, double low, double high, Rect rect, std::string name) : value(val), low(low), high(high), rect(rect), name(name) {} + + /// @brief responds to user input + /// @param was_pressed if the screen is pressed + /// @param x x position if the screen was pressed + /// @param y y position if the screen was pressed + /// @return true if the value updated + bool update(bool was_pressed, int x, int y); + /// @brief @ref Page::draws the slide to the screen + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number); + + private: + double &value; + + double low; + double high; + + Rect rect; + std::string name = ""; + }; + + /// @brief Widget that does something when you tap it. The function is only called once when you first tap it + class ButtonWidget + { + public: + /// @brief Create a Button widget + /// @param onpress the function to be called when the button is tapped + /// @param rect the area the button should take up on the screen + /// @param name the label put on the button + ButtonWidget(std::function onpress, Rect rect, std::string name) : onpress(onpress), rect(rect), name(name) {} + /// @brief Create a Button widget + /// @param onpress the function to be called when the button is tapped + /// @param rect the area the button should take up on the screen + /// @param name the label put on the button + ButtonWidget(void (*onpress)(), Rect rect, std::string name) : onpress(onpress), rect(rect), name(name) {} + + /// @brief responds to user input + /// @param was_pressed if the screen is pressed + /// @param x x position if the screen was pressed + /// @param y y position if the screen was pressed + /// @return true if the button was pressed + bool update(bool was_pressed, int x, int y); + /// @brief draws the button to the screen + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number); + + private: + std::function onpress; + Rect rect; + std::string name = ""; + bool was_pressed_last = false; + }; + /** * @brief Start the screen background task. Once you start this, no need to draw to the screen manually elsewhere * @param screen reference to the vex screen @@ -39,6 +105,7 @@ namespace screen */ void start_screen(vex::brain::lcd &screen, std::vector pages, int first_page = 0); + /// @brief stops the screen. If you have a drive team that hates fun call this at the start of opcontrol void stop_screen(); /// @brief type of function needed for update @@ -47,11 +114,17 @@ namespace screen /// @brief type of function needed for draw using draw_func_t = std::function; + + /// @brief Draws motor stats and battery stats to the screen class StatsPage : public Page { public: + /// @brief Creates a stats page + /// @param motors a map of string to motor that we want to draw on this page StatsPage(std::map motors); + /// @brief @see Page#update void update(bool was_pressed, int x, int y) override; + /// @brief @see Page#draw void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; private: @@ -66,12 +139,19 @@ namespace screen /** * @brief a page that shows odometry position and rotation and a map (if an sd card with the file is on) - */ + */ class OdometryPage : public Page { public: - OdometryPage(OdometryBase &odom, double width, double height, bool do_trail); + /// @brief Create an odometry trail. Make sure odometry is initilized before now + /// @param odom the odometry system to monitor + /// @param robot_width the width (side to side) of the robot in inches. Used for visualization + /// @param robot_height the robot_height (front to back) of the robot in inches. Used for visualization + /// @param do_trail whether or not to calculate and draw the trail. Drawing and storing takes a very *slight* extra amount of processing power + OdometryPage(OdometryBase &odom, double robot_width, double robot_height, bool do_trail); + /// @brief @see Page#update void update(bool was_pressed, int x, int y) override; + /// @brief @see Page#draw void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; private: @@ -79,22 +159,26 @@ namespace screen static constexpr char const *field_filename = "vex_field_240p.png"; OdometryBase &odom; - double width; - double height; + double robot_width; + double robot_height; uint8_t *buf = nullptr; int buf_size = 0; pose_t path[path_len]; int path_index = 0; - bool do_trail; + bool do_trail; }; /// @brief Simple page that stores no internal data. the draw and update functions use only global data rather than storing anything class FunctionPage : public Page { public: + /// @brief Creates a function page + /// @param update_f the function called every tick to respond to user input or do data collection + /// @param draw_t the function called to draw to the screen FunctionPage(update_func_t update_f, draw_func_t draw_t); - + /// @brief @see Page#update void update(bool was_pressed, int x, int y) override; + /// @brief @see Page#draw void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; private: @@ -102,4 +186,40 @@ namespace screen draw_func_t draw_f; }; + /// @brief PIDPage provides a way to tune a pid controller on the screen + class PIDPage : public Page + { + public: + /// @brief Create a PIDPage + /// @param pid the pid controller we're changing + /// @param name a name to recognize this pid controller if we've got multiple pid screens + /// @param onchange a function that is called when a tuning parameter is changed. If you need to update stuff on that change register a handler here + PIDPage(PID &pid, std::string name, std::function onchange = [](){}); + PIDPage(PIDFF &pidff, std::string name, std::function onchange = [](){}); + + /// @brief @see Page#update + void update(bool was_pressed, int x, int y) override; + /// @brief @see Page#draw + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; + + private: + /// @brief reset d + void zero_d_f() { cfg.d = 0; } + /// @brief reset i + void zero_i_f() { cfg.i = 0; } + + PID::pid_config_t &cfg; + PID &pid; + const std::string name; + std::function onchange; + + SliderWidget p_slider; + SliderWidget i_slider; + SliderWidget d_slider; + ButtonWidget zero_i; + ButtonWidget zero_d; + + GraphDrawer graph; + }; + } diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 02edee4..c2826de 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -6,8 +6,8 @@ #include "vex.h" #include "../core/include/subsystems/odometry/odometry_tank.h" -#include "../core/include/utils/pid.h" -#include "../core/include/utils/feedback_base.h" +#include "../core/include/utils/controls/pid.h" +#include "../core/include/utils/controls/feedback_base.h" #include "../core/include/robot_specs.h" #include "../core/include/utils/pure_pursuit.h" #include "../core/include/utils/command_structure/auto_command.h" @@ -31,20 +31,20 @@ class TankDrive */ TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom = NULL); - AutoCommand *DriveToPointCmd(point_t pt, vex::directionType dir = vex::forward, double max_speed = 1.0); - AutoCommand *DriveToPointCmd(Feedback &fb, point_t pt, vex::directionType dir = vex::forward, double max_speed = 1.0); + AutoCommand *DriveToPointCmd(point_t pt, vex::directionType dir = vex::forward, double max_speed = 1.0, double end_speed = 0.0); + AutoCommand *DriveToPointCmd(Feedback &fb, point_t pt, vex::directionType dir = vex::forward, double max_speed = 1.0, double end_speed = 0.0); - AutoCommand *DriveForwardCmd(double dist, vex::directionType dir = vex::forward, double max_speed = 1.0); - AutoCommand *DriveForwardCmd(Feedback &fb, double dist, vex::directionType dir = vex::forward, double max_speed = 1.0); + AutoCommand *DriveForwardCmd(double dist, vex::directionType dir = vex::forward, double max_speed = 1.0, double end_speed = 0.0); + AutoCommand *DriveForwardCmd(Feedback &fb, double dist, vex::directionType dir = vex::forward, double max_speed = 1.0, double end_speed = 0.0); - AutoCommand *TurnToHeadingCmd(double heading, double max_speed = 1.0); - AutoCommand *TurnToHeadingCmd(Feedback &fb, double heading, double max_speed = 1.0); + AutoCommand *TurnToHeadingCmd(double heading, double max_speed = 1.0, double end_speed = 0.0); + AutoCommand *TurnToHeadingCmd(Feedback &fb, double heading, double max_speed = 1.0, double end_speed = 0.0); - AutoCommand *TurnDegreesCmd(double degrees, double max_speed = 1.0); - AutoCommand *TurnDegreesCmd(Feedback &fb, double degrees, double max_speed = 1.0); + AutoCommand *TurnDegreesCmd(double degrees, double max_speed = 1.0, double start_speed = 0.0); + AutoCommand *TurnDegreesCmd(Feedback &fb, double degrees, double max_speed = 1.0, double end_speed = 0.0); - AutoCommand *PurePursuitCmd(std::vector path, directionType dir, double radius, double max_speed=1); - AutoCommand *PurePursuitCmd(Feedback &feedback, std::vector path, directionType dir, double radius, double max_speed=1); + AutoCommand *PurePursuitCmd(PurePursuit::Path path, directionType dir, double max_speed=1, double end_speed=0); + AutoCommand *PurePursuitCmd(Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed=1, double end_speed=0); /** * Stops rotation of all the motors using their "brake mode" @@ -83,9 +83,10 @@ class TankDrive * @param dir the direction we want to travel forward and backward * @param feedback the custom feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return true when we have reached our target distance */ - bool drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed = 1); + bool drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed = 1, double end_speed = 0); /** * Autonomously drive the robot forward a certain distance @@ -94,8 +95,9 @@ class TankDrive * @param inches degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw * @param dir the direction we want to travel forward and backward * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by its completion */ - bool drive_forward(double inches, directionType dir, double max_speed = 1); + bool drive_forward(double inches, directionType dir, double max_speed = 1, double end_speed = 0); /** * Autonomously turn the robot X degrees counterclockwise (negative for clockwise), with a maximum motor speed @@ -107,7 +109,7 @@ class TankDrive * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ - bool turn_degrees(double degrees, Feedback &feedback, double max_speed = 1); + bool turn_degrees(double degrees, Feedback &feedback, double max_speed = 1, double end_speed = 0); /** * Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed @@ -117,8 +119,9 @@ class TankDrive * * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - */ - bool turn_degrees(double degrees, double max_speed = 1); + * @param end_speed the movement profile will attempt to reach this velocity by its completion + */ + bool turn_degrees(double degrees, double max_speed = 1, double end_speed = 0); /** * Use odometry to automatically drive the robot to a point on the field. @@ -130,8 +133,9 @@ class TankDrive * @param dir the direction we want to travel forward and backward * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by its completion */ - bool drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed = 1); + bool drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed = 1, double end_speed = 0); /** * Use odometry to automatically drive the robot to a point on the field. @@ -143,8 +147,9 @@ class TankDrive * @param y the y position of the target * @param dir the direction we want to travel forward and backward * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by its completion */ - bool drive_to_point(double x, double y, vex::directionType dir, double max_speed = 1); + bool drive_to_point(double x, double y, vex::directionType dir, double max_speed = 1, double end_speed = 0); /** * Turn the robot in place to an exact heading relative to the field. @@ -153,16 +158,18 @@ class TankDrive * @param heading_deg the heading to which we will turn * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by its completion */ - bool turn_to_heading(double heading_deg, Feedback &feedback, double max_speed = 1); + bool turn_to_heading(double heading_deg, Feedback &feedback, double max_speed = 1, double end_speed = 0); /** * Turn the robot in place to an exact heading relative to the field. * 0 is forward. Uses the defualt turn feedback of the drive system * * @param heading_deg the heading to which we will turn * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by its completion */ - bool turn_to_heading(double heading_deg, double max_speed = 1); + bool turn_to_heading(double heading_deg, double max_speed = 1, double end_speed = 0); /** * Reset the initialization for autonomous drive functions @@ -186,12 +193,12 @@ class TankDrive * * @param path The list of coordinates to follow, in order * @param dir Run the bot forwards or backwards - * @param radius How big the corner cutting should be - small values follow the path more closely * @param feedback The feedback controller determining speed * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) + * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return True when the path is complete */ - bool pure_pursuit(std::vector path, directionType dir, double radius, Feedback &feedback, double max_speed=1); + bool pure_pursuit(PurePursuit::Path path, directionType dir, Feedback &feedback, double max_speed=1, double end_speed=0); /** * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of @@ -202,11 +209,11 @@ class TankDrive * * @param path The list of coordinates to follow, in order * @param dir Run the bot forwards or backwards - * @param radius How big the corner cutting should be - small values follow the path more closely * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) + * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return True when the path is complete */ - bool pure_pursuit(std::vector path, directionType dir, double radius, double max_speed=1); + bool pure_pursuit(PurePursuit::Path path, directionType dir, double max_speed=1, double end_speed=0); private: motor_group &left_motors; ///< left drive motors diff --git a/include/utils/auto_chooser.h b/include/utils/auto_chooser.h index e42f1d4..59562b6 100644 --- a/include/utils/auto_chooser.h +++ b/include/utils/auto_chooser.h @@ -2,57 +2,49 @@ #include "vex.h" #include #include - +#include "../core/include/subsystems/screen.h" +#include "../core/include/utils/geometry.h" /** * Autochooser is a utility to make selecting robot autonomous programs easier * source: RIT VexU Wiki - * During a season, we usually code between 4 and 6 autonomous programs. + * During a season, we usually code between 4 and 6 autonomous programs. * Most teams will change their entire robot program as a way of choosing autonomi - * but this may cause issues if you have an emergency patch to upload during a competition. + * but this may cause issues if you have an emergency patch to upload during a competition. * This class was built as a way of using the robot screen to list autonomous programs, and the touchscreen to select them. */ -class AutoChooser +class AutoChooser : public screen::Page { - public: -/** - * Initialize the auto-chooser. This class places a choice menu on the brain screen, - * so the driver can choose which autonomous to run. - * @param brain the brain on which to draw the selection boxes - */ - AutoChooser(vex::brain &brain); - +public: /** - * Add an auto path to the chooser - * @param name The name of the path. This should be used as an human readable identifier to the auto path - */ - void add(std::string name); + * Initialize the auto-chooser. This class places a choice menu on the brain screen, + * so the driver can choose which autonomous to run. + * @param brain the brain on which to draw the selection boxes + */ + AutoChooser(std::vector paths, size_t def = 0); + + void update(bool was_pressed, int x, int y); + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number); /** * Get the currently selected auto choice * @return the identifier to the auto path - */ - std::string get_choice(); - - protected: + */ + size_t get_choice(); +protected: /** * entry_t is a datatype used to store information that the chooser knows about an auto selection button - */ + */ struct entry_t { - int x; /**< screen x position of the block*/ - int y; /**< screen y position of the block*/ - int width; /**< width of the block*/ - int height; /**< height of the block*/ - std::string name; /**< name of the auto repretsented by the block*/ + Rect rect; + std::string name; /**< name of the auto repretsented by the block*/ }; - void render(entry_t *selected); + static const size_t width = 380; + static const size_t height = 220; - std::string choice; /**< the current choice of auto*/ + size_t choice; /**< the current choice of auto*/ std::vector list /**< a list of all possible auto choices*/; - vex::brain &brain; /**< the brain to show the choices on*/ - - }; \ No newline at end of file diff --git a/include/utils/command_structure/auto_command.h b/include/utils/command_structure/auto_command.h index 066cb20..fa8528e 100644 --- a/include/utils/command_structure/auto_command.h +++ b/include/utils/command_structure/auto_command.h @@ -12,6 +12,25 @@ #include #include + +/** + * A Condition is a function that returns true or false + * is_even is a predicate that would return true if a number is even + * For our purposes, a Condition is a choice to be made at runtime + * drive_sys.reached_point(10, 30) is a predicate + * time.has_elapsed(10, vex::seconds) is a predicate + * extend this class for different choices you wish to make + + */ +class Condition +{ +public: + Condition *Or(Condition *b); + Condition *And(Condition *b); + virtual bool test() = 0; +}; + + class AutoCommand { public: @@ -36,6 +55,10 @@ class AutoCommand this->timeout_seconds = t_seconds; return this; } + AutoCommand *withCancelCondition(Condition *true_to_end){ + this->true_to_end = true_to_end; + return this; + } /** * How long to run until we cancel this command. * If the command is cancelled, on_timeout() is called to allow any cleanup from the function. @@ -46,6 +69,7 @@ class AutoCommand * - something else... */ double timeout_seconds = default_timeout; + Condition *true_to_end = nullptr; }; /** @@ -65,19 +89,29 @@ class FunctionCommand : public AutoCommand std::function f; }; -/** - * A Condition is a function that returns true or false - * is_even is a predicate that would return true if a number is even - * For our purposes, a Condition is a choice to be made at runtime - * drive_sys.reached_point(10, 30) is a predicate - * time.has_elapsed(10, vex::seconds) is a predicate - * extend this class for different choices you wish to make - - */ -class Condition +// Times tested 3 +// Test 1 -> false +// Test 2 -> false +// Test 3 -> true +// Returns false until the Nth time that it is called +// This is pretty much only good for implementing RepeatUntil +class TimesTestedCondition : public Condition { public: - virtual bool test() = 0; + TimesTestedCondition(size_t N) : max(N) {} + bool test() override + { + count++; + if (count >= max) + { + return true; + } + return false; + } + +private: + size_t count = 0; + size_t max; }; /// @brief FunctionCondition is a quick and dirty Condition to wrap some expression that should be evaluated at runtime @@ -121,11 +155,15 @@ class WaitUntilCondition : public AutoCommand Condition *cond; }; +/// @brief InOrder runs its commands sequentially then continues. +/// How to handle timeout in this case. Automatically set it to sum of commands timouts? + /// @brief InOrder runs its commands sequentially then continues. /// How to handle timeout in this case. Automatically set it to sum of commands timouts? class InOrder : public AutoCommand { public: + InOrder(const InOrder &other) = default; InOrder(std::queue cmds); InOrder(std::initializer_list cmds); bool run() override; @@ -183,3 +221,23 @@ class Async : public AutoCommand private: AutoCommand *cmd = nullptr; }; + +class RepeatUntil : public AutoCommand +{ +public: + /// @brief RepeatUntil that runs a fixed number of times + /// @param cmds the cmds to repeat + /// @param repeats the number of repeats to do + RepeatUntil(InOrder cmds, size_t repeats); + /// @brief RepeatUntil the condition + /// @param cmds the cmds to run + /// @param true_to_end we will repeat until true_or_end.test() returns true + RepeatUntil(InOrder cmds, Condition *true_to_end); + bool run() override; + void on_timeout() override; + +private: + const InOrder cmds; + InOrder *working_cmds; + Condition *cond; +}; diff --git a/include/utils/command_structure/basic_command.h b/include/utils/command_structure/basic_command.h new file mode 100644 index 0000000..6df7306 --- /dev/null +++ b/include/utils/command_structure/basic_command.h @@ -0,0 +1,118 @@ +/** + * @file basic_commands.h + * @author Ethan Kishimori GITHUB(LilacEthan) + * + * @brief Basic Commands for Motors and Solenoids able to throw into the Command Controller + * Commands Included + * - BasicSpinCommand + * - BasicStopCommand + * - BasicSolenoidSet + * + * @version 0.1 + * + */ +#pragma once + +#include "../core/include/utils/command_structure/auto_command.h" + +//Basic Motor Classes----------------------------------------------- + +/** + * AutoCommand wrapper class for BasicSpinCommand + * using the vex hardware functions + */ +class BasicSpinCommand : public AutoCommand { + public: + + //Enumurator for the type of power setting in the motor + enum type {percent,voltage,veocity}; + + /** + * @brief Construct a new BasicSpinCommand + * + * @param motor Motor to spin + * @param direc Direction of motor spin + * @param setting Power setting in volts,percentage,velocity + * @param power Value of desired power + */ + BasicSpinCommand(vex::motor &motor, vex::directionType dir, BasicSpinCommand::type setting, double power); + + /** + * @brief Runs the BasicSpinCommand + * Overrides run from Auto Command + * + * @return True Async running command + */ + bool run() override; + + private: + + vex::motor &motor; + + type setting; + + vex::directionType dir; + + double power; +}; +/** + * AutoCommand wrapper class for BasicStopCommand + * Using the Vex hardware functions + */ +class BasicStopCommand : public AutoCommand{ + public: + + /** + * @brief Construct a new BasicMotorStop Command + * + * @param motor The motor to stop + * @param setting The brake setting for the motor + */ + BasicStopCommand(vex::motor &motor, vex::brakeType setting); + + /** + * @brief Runs the BasicMotorStop Command + * Overrides run command from AutoCommand + * + * @return True Command runs once + */ + bool run() override; + + private: + + vex::motor &motor; + + vex::brakeType setting; +}; + +//Basic Solenoid Commands---------------------------------- + +/** + * AutoCommand wrapper class for BasicSolenoidSet + * Using the Vex hardware functions + */ +class BasicSolenoidSet : public AutoCommand{ + public: + + /** + * @brief Construct a new BasicSolenoidSet Command + * + * @param solenoid Solenoid being set + * @param setting Setting of the solenoid in boolean (true,false) + */ + BasicSolenoidSet(vex::pneumatics &solenoid, bool setting); + + /** + * @brief Runs the BasicSolenoidSet + * Overrides run command from AutoCommand + * + * @return True Command runs once + */ + bool run() override; + + private: + + vex::pneumatics &solenoid; + + bool setting; +}; \ No newline at end of file diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index b7636ff..ee590fb 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -36,7 +36,7 @@ using namespace vex; class DriveForwardCommand: public AutoCommand { public: - DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed=1); + DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed=1, double end_speed=0); /** * Run drive_forward @@ -60,6 +60,7 @@ class DriveForwardCommand: public AutoCommand double inches; directionType dir; double max_speed; + double end_speed; }; /** @@ -69,7 +70,7 @@ class DriveForwardCommand: public AutoCommand class TurnDegreesCommand: public AutoCommand { public: - TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed = 1); + TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed = 1, double end_speed = 0); /** * Run turn_degrees @@ -93,6 +94,7 @@ class TurnDegreesCommand: public AutoCommand // parameters for turn_degrees double degrees; double max_speed; + double end_speed; }; /** @@ -102,8 +104,8 @@ class TurnDegreesCommand: public AutoCommand class DriveToPointCommand: public AutoCommand { public: - DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed = 1); - DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, point_t point, directionType dir, double max_speed=1); + DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed = 1, double end_speed = 0); + DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, point_t point, directionType dir, double max_speed=1, double end_speed = 0); /** * Run drive_to_point @@ -130,6 +132,7 @@ class DriveToPointCommand: public AutoCommand double y; directionType dir; double max_speed; + double end_speed; }; @@ -141,7 +144,7 @@ class DriveToPointCommand: public AutoCommand class TurnToHeadingCommand: public AutoCommand { public: - TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed = 1); + TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed = 1, double end_speed = 0); /** * Run turn_to_heading @@ -165,6 +168,7 @@ class TurnToHeadingCommand: public AutoCommand // parameters for turn_to_heading double heading_deg; double max_speed; + double end_speed; }; /** @@ -178,11 +182,10 @@ class PurePursuitCommand: public AutoCommand * * @param path The list of coordinates to follow, in order * @param dir Run the bot forwards or backwards - * @param radius How big the corner cutting should be - small values follow the path more closely * @param feedback The feedback controller determining speed * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) */ - PurePursuitCommand(TankDrive &drive_sys, Feedback &feedback, std::vector path, directionType dir, double radius, double max_speed=1); + PurePursuitCommand(TankDrive &drive_sys, Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed=1, double end_speed=0); /** * Direct call to TankDrive::pure_pursuit @@ -196,11 +199,11 @@ class PurePursuitCommand: public AutoCommand private: TankDrive &drive_sys; - std::vector path; + PurePursuit::Path path; directionType dir; - double radius; Feedback &feedback; double max_speed; + double end_speed; }; diff --git a/include/utils/command_structure/flywheel_commands.h b/include/utils/command_structure/flywheel_commands.h index 133c210..04bf8f5 100644 --- a/include/utils/command_structure/flywheel_commands.h +++ b/include/utils/command_structure/flywheel_commands.h @@ -10,7 +10,7 @@ #include "../core/include/utils/command_structure/auto_command.h" /** - * AutoCommand wrapper class for the spinRPM function + * AutoCommand wrapper class for the spin_rpm function * in the Flywheel class * */ @@ -34,7 +34,7 @@ class SpinRPMCommand: public AutoCommand { // Flywheel instance to run the function on Flywheel &flywheel; - // parameters for spinRPM + // parameters for spin_rpm int rpm; }; diff --git a/include/utils/controls/bang_bang.h b/include/utils/controls/bang_bang.h new file mode 100644 index 0000000..aeba17d --- /dev/null +++ b/include/utils/controls/bang_bang.h @@ -0,0 +1,50 @@ +#include "../core/include/utils/controls/feedback_base.h" + +class BangBang : public Feedback +{ + +public: + BangBang(double thresshold, double low, double high); + /** + * Initialize the feedback controller for a movement + * + * @param start_pt the current sensor value + * @param set_pt where the sensor value should be + * @param start_vel Movement starting velocity + * @param end_vel Movement ending velocity + */ + void init(double start_pt, double set_pt, double start_vel [[maybe_unused]] = 0.0, double end_vel [[maybe_unused]] = 0.0) override; + + /** + * Iterate the feedback loop once with an updated sensor value + * + * @param val value from the sensor + * @return feedback loop result + */ + double update(double val) override; + + /** + * @return the last saved result from the feedback controller + */ + double get() override; + + /** + * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * + * @param lower Upper limit + * @param upper Lower limit + */ + void set_limits(double lower, double upper) override; + + /** + * @return true if the feedback controller has reached it's setpoint + */ + bool is_on_target() override; + +private: + double setpt; + double sensor_val; + double lower_bound, upper_bound; + double last_output; + double threshhold; +}; diff --git a/include/utils/feedback_base.h b/include/utils/controls/feedback_base.h similarity index 80% rename from include/utils/feedback_base.h rename to include/utils/controls/feedback_base.h index 19d45a9..9b9c625 100644 --- a/include/utils/feedback_base.h +++ b/include/utils/controls/feedback_base.h @@ -10,20 +10,15 @@ class Feedback { public: - enum FeedbackType - { - PIDType, - FeedforwardType, - OtherType, - }; - /** * Initialize the feedback controller for a movement * * @param start_pt the current sensor value * @param set_pt where the sensor value should be + * @param start_vel Movement starting velocity + * @param end_vel Movement ending velocity */ - virtual void init(double start_pt, double set_pt) = 0; + virtual void init(double start_pt, double set_pt, double start_vel = 0.0, double end_vel = 0.0) = 0; /** * Iterate the feedback loop once with an updated sensor value @@ -51,8 +46,5 @@ class Feedback */ virtual bool is_on_target() = 0; - virtual Feedback::FeedbackType get_type() - { - return FeedbackType::OtherType; - } + }; \ No newline at end of file diff --git a/include/utils/feedforward.h b/include/utils/controls/feedforward.h similarity index 100% rename from include/utils/feedforward.h rename to include/utils/controls/feedforward.h diff --git a/include/utils/motion_controller.h b/include/utils/controls/motion_controller.h similarity index 92% rename from include/utils/motion_controller.h rename to include/utils/controls/motion_controller.h index 6683934..03bbce6 100644 --- a/include/utils/motion_controller.h +++ b/include/utils/controls/motion_controller.h @@ -1,8 +1,8 @@ #pragma once -#include "../core/include/utils/pid.h" -#include "../core/include/utils/feedforward.h" -#include "../core/include/utils/trapezoid_profile.h" -#include "../core/include/utils/feedback_base.h" +#include "../core/include/utils/controls/pid.h" +#include "../core/include/utils/controls/feedforward.h" +#include "../core/include/utils/controls/trapezoid_profile.h" +#include "../core/include/utils/controls/feedback_base.h" #include "../core/include/subsystems/tank_drive.h" #include "vex.h" @@ -54,7 +54,7 @@ class MotionController : public Feedback * @brief Initialize the motion profile for a new movement * This will also reset the PID and profile timers. */ - void init(double start_pt, double end_pt) override; + void init(double start_pt, double end_pt, double start_vel, double end_vel) override; /** * @brief Update the motion profile with a new sensor value @@ -117,6 +117,9 @@ class MotionController : public Feedback FeedForward ff; TrapezoidProfile profile; + double current_pos; + double end_pt; + double lower_limit = 0, upper_limit = 0; double out = 0; motion_t cur_motion; diff --git a/include/utils/pid.h b/include/utils/controls/pid.h similarity index 90% rename from include/utils/pid.h rename to include/utils/controls/pid.h index 4ff41e3..a2b3557 100644 --- a/include/utils/pid.h +++ b/include/utils/controls/pid.h @@ -2,7 +2,7 @@ #include #include "vex.h" -#include "../core/include/utils/feedback_base.h" +#include "../core/include/utils/controls/feedback_base.h" using namespace vex; @@ -63,8 +63,10 @@ class PID : public Feedback * start_pt can be safely ignored in this feedback controller * @param start_pt commpletely ignored for PID. necessary to satisfy Feedback base * @param set_pt sets the target of the PID controller + * @param start_vel completely ignored for PID. necessary to satisfy Feedback base + * @param end_vel sets the target end velocity of the PID controller */ - void init(double start_pt, double set_pt) override; + void init(double start_pt, double set_pt, double start_vel = 0, double end_vel = 0) override; /** * Update the PID loop by taking the time difference from last update, @@ -74,6 +76,14 @@ class PID : public Feedback */ double update(double sensor_val) override; + + /** + * @brief gets the sensor value that we were last updated with + * @return sensor_val + */ + double get_sensor_val(); + + /** * Gets the current PID out value, from when update() was last run * @return the Out value of the controller (voltage, RPM, whatever the PID controller is controlling) @@ -117,7 +127,6 @@ class PID : public Feedback */ void set_target(double target); - Feedback::FeedbackType get_type() override; pid_config_t &config; ///< configuration struct for this controller. see pid_config_t for information about what this contains @@ -134,6 +143,7 @@ class PID : public Feedback double upper_limit = 0; ///< the PID controller will never set a target to go higher than this double target = 0; ///< the target position of the PID controller (lower_limit <= target <= upper_limit) + double target_vel = 0; ///< the target velocity of the PID controller (if != 0, controller will not wait for stop) double sensor_val = 0; ///< the last recorded value of the sensor we use to feed the PID controller double out = 0; ///< the last calculated output value. we save it here so that we don't have to recalculate if we ask for it more than once between update() calls diff --git a/include/utils/pidff.h b/include/utils/controls/pidff.h similarity index 80% rename from include/utils/pidff.h rename to include/utils/controls/pidff.h index a09c6d3..f2c8219 100644 --- a/include/utils/pidff.h +++ b/include/utils/controls/pidff.h @@ -1,7 +1,7 @@ #pragma once -#include "../core/include/utils/feedback_base.h" -#include "../core/include/utils/pid.h" -#include "../core/include/utils/feedforward.h" +#include "../core/include/utils/controls/feedback_base.h" +#include "../core/include/utils/controls/pid.h" +#include "../core/include/utils/controls/feedforward.h" class PIDFF : public Feedback { @@ -14,8 +14,10 @@ class PIDFF : public Feedback * * @param start_pt the current sensor value * @param set_pt where the sensor value should be + * @param start_vel the current rate of change of the sensor value + * @param end_vel the desired ending rate of change of the sensor value */ - void init(double start_pt, double set_pt) override; + void init(double start_pt, double set_pt, double start_vel, double end_vel) override; /** * Set the target of the PID loop diff --git a/include/utils/controls/take_back_half.h b/include/utils/controls/take_back_half.h new file mode 100644 index 0000000..692660f --- /dev/null +++ b/include/utils/controls/take_back_half.h @@ -0,0 +1,59 @@ +#pragma once +#include "../core/include/utils/controls/feedback_base.h" + +/// @brief A velocity controller +/// @warning If you try to use this as a position controller, it will fail. +class TakeBackHalf : public Feedback +{ + +public: + TakeBackHalf(double TBH_gain, double first_cross_split, double on_target_threshold); + /** + * Initialize the feedback controller for a movement + * + * @param start_pt the current sensor value + * @param set_pt where the sensor value should be + * @param start_vel Movement starting velocity (IGNORED) + * @param end_vel Movement ending velocity (IGNORED) + */ + void init(double start_pt, double set_pt, double, double); + /** + * Iterate the feedback loop once with an updated sensor value + * + * @param val value from the sensor + * @return feedback loop result + */ + double update(double val) override; + + /** + * @return the last saved result from the feedback controller + */ + double get() override; + + /** + * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * + * @param lower Upper limit + * @param upper Lower limit + */ + void set_limits(double lower, double upper) override; + + /** + * @return true if the feedback controller has reached it's setpoint + */ + bool is_on_target() override; + + double TBH_gain; ///< tuned parameter + double first_cross_split; +private: + double on_target_threshhold; ///< tuned parameter + + double target = 0.0; + + bool first_cross = true; + double tbh = 0.0; + double prev_error = 0.0; + + double output = 0.0; + double lower = 0.0, upper = 0.0; ///< output limits +}; \ No newline at end of file diff --git a/include/utils/controls/trapezoid_profile.h b/include/utils/controls/trapezoid_profile.h new file mode 100644 index 0000000..0f2756c --- /dev/null +++ b/include/utils/controls/trapezoid_profile.h @@ -0,0 +1,162 @@ +#pragma once + +const int MAX_TRAPEZOID_PROFILE_SEGMENTS = 4; + +/** + * motion_t is a description of 1 dimensional motion at a point in time. +*/ +typedef struct +{ + double pos; ///< 1d position at this point in time + double vel; ///< 1d velocity at this point in time + double accel; ///< 1d acceleration at this point in time + +} motion_t; + +/** + * trapezoid_profile_segment_t is a description of one constant acceleration segment of a trapezoid motion profile + */ +typedef struct +{ + double pos_after; ///< 1d position after this segment concludes + double vel_after; ///< 1d velocity after this segment concludes + double accel; ///< 1d acceleration during the segment + double duration; ///< duration of the segment +} trapezoid_profile_segment_t; + +/** + * Trapezoid Profile + * + * This is a motion profile defined by: + * - maximum acceleration + * - maximum velocity + * - start position and velocity + * - end position and velocity + * + * Using this information, a parametric function is generated, with a period of acceleration, constant + * velocity, and deceleration. The velocity graph usually looks like a trapezoid, giving it its name. + * + * If the maximum velocity is set high enough, this will become a S-curve profile, with only acceleration and deceleration. + * + * If the initial velocity is in the wrong direction, the profile will first come to a stop, then continue a normal + * trapezoid profile. + * + * If the initial velocity is higher than the maximum velocity, the profile will first try to achieve the maximum velocity. + * + * If the end velocity is not achievable, the profile will try to get as close as possible. The end velocity must + * be in the direction of the end point. + * + * This class is designed for use in properly modelling the motion of the robots to create a feedfoward + * and target for PID. Acceleration and Maximum velocity should be measured on the robot and tuned down + * slightly to account for battery drop. + * + * Here are the equations graphed for ease of understanding: + * https://www.desmos.com/calculator/rkm3ivu1yk + * + * @author Ryan McGee + * @date 7/12/2022 + * + */ +class TrapezoidProfile +{ + public: + + /** + * @brief Construct a new Trapezoid Profile object + * + * @param max_v Maximum velocity the robot can run at + * @param accel Maximum acceleration of the robot + */ + TrapezoidProfile(double max_v, double accel); + + /** + * @brief Run the trapezoidal profile based on the time and distance that's elapsed + * + * @param time_s Time since start of movement + * @param pos_s The current position + * @return motion_t Position, velocity and acceleration + */ + motion_t calculate(double time_s, double pos_s); + + /** + * @brief Run the trapezoidal profile based on the time that's elapsed + * + * @param time_s Time since start of movement + * @return motion_t Position, velocity and acceleration + */ + motion_t calculate_time_based(double time_s); + + /** + * @brief set_endpts defines a start and end position + * + * @param start the starting position of the path + * @param end the ending position of the path + */ + void set_endpts(double start, double end); + + /** + * @brief set start and end velocities + * + * @param start the starting velocity of the path + * @param end the ending velocity of the path + */ + void set_vel_endpts(double start, double end); + + /** + * @brief set_accel sets the acceleration this profile will use (the left and right legs of the trapezoid) + * + * @param accel the acceleration amount to use + */ + void set_accel(double accel); + + /** + * @brief sets the maximum velocity for the profile (the height of the top of the trapezoid) + * + * @param max_v the maximum velocity the robot can travel at + */ + void set_max_v(double max_v); + + /** + * @brief uses the kinematic equations to and specified accel and max_v to figure out how long moving along the profile would take + * + * @return the time the path will take to travel + */ + double get_movement_time(); + + private: + double si, sf; ///< the initial and final position of the profile + double vi, vf; ///< the initial and final velocity of the profile + double max_v; ///< the maximum velocity to travel at for this profile + double accel; ///< the rate of acceleration to use for this profile. + + trapezoid_profile_segment_t segments[MAX_TRAPEZOID_PROFILE_SEGMENTS]; + int num_acceleration_phases; + + bool precalculated; ///< whether or not the segment array is up to date + + /** + * Attempt to generate the motion profile for the given parameters + * + * @return False if there was a problem with the parameters + */ + bool precalculate(); + + /** + * Calculate a trapezoid segment given a target velocity that accelerates to the given velocity + * + * @param si segment initial position + * @param vi segment initial velocity + * @param v_target target velocity + * @return a trapezoid_profile_segment_t that represents constant acceleration to the target velocity + */ + trapezoid_profile_segment_t calculate_kinetic_motion(double si, double vi, double v_target); + + /** + * Calculate the next segment of the trapezoid motion profile + * + * @param s segment starting position + * @param v segment starting velocity + * @return the next segment of the trapezoid motion profile + */ + trapezoid_profile_segment_t calculate_next_segment(double s, double v); +}; \ No newline at end of file diff --git a/include/utils/geometry.h b/include/utils/geometry.h index 52b34b8..c6e18a9 100644 --- a/include/utils/geometry.h +++ b/include/utils/geometry.h @@ -24,7 +24,7 @@ struct point_t * @param other the point to add on to this * @return this + other (this.x + other.x, this.y + other.y) */ - point_t operator+(const point_t &other) + point_t operator+(const point_t &other) const { point_t p{ .x = this->x + other.x, @@ -37,7 +37,7 @@ struct point_t * @param other the point_t to subtract from this * @return this - other (this.x - other.x, this.y - other.y) */ - point_t operator-(const point_t &other) + point_t operator-(const point_t &other) const { point_t p{ .x = this->x - other.x, @@ -72,7 +72,7 @@ struct point_t /** * Describes a single position and rotation */ -typedef struct +struct pose_t { double x; ///< x position in the world double y; ///< y position in the world @@ -83,7 +83,36 @@ typedef struct return point_t{.x = x, .y = y}; } -} pose_t; +} ; + +struct Rect +{ + point_t min; + point_t max; + static Rect from_min_and_size(point_t min, point_t size){ + return {min, min+size}; + } + point_t dimensions() const + { + return max - min; + } + point_t center() const{ + return (min + max)/2; + } + double width() const{ + return max.x - min.x; + } + double height() const{ + return max.y - min.y; + } + bool contains(point_t p) const + { + bool xin = p.x > min.x && p.x < max.x; + bool yin = p.y > min.y && p.y < max.y; + return xin && yin; + } + +}; struct Mat2 { diff --git a/include/utils/graph_drawer.h b/include/utils/graph_drawer.h index 09cce09..9273389 100644 --- a/include/utils/graph_drawer.h +++ b/include/utils/graph_drawer.h @@ -11,23 +11,25 @@ class GraphDrawer { public: + /// @brief Creates a graph drawer with the specified number of series (each series is a separate line) + /// @param num_samples the number of samples to graph at a time (40 will graph the last 40 data points) + /// @param lower_bound the bottom of the window when displaying (if upper_bound = lower_bound, auto calculate bounds) + /// @param upper_bound the top of the window when displaying (if upper_bound = lower_bound, auto calculate bounds) + /// @param colors the colors of the series. must be of size num_series + /// @param num_series the number of series to graph + GraphDrawer(int num_samples, double lower_bound, double upper_bound, std::vector colors, size_t num_series = 1); /** - * Construct a GraphDrawer - * @brief a helper class to graph values on the brain screen - * @param screen a reference to Brain.screen we can save for later - * @param num_samples the graph works on a fixed window and will plot the last `num_samples` before the history is forgotten. Larger values give more context but may slow down if you have many graphs or an exceptionally high - * @param x_label the name of the x axis (currently unused) - * @param y_label the name of the y axis (currently unused) - * @param draw_border whether to draw the border around the graph. can be turned off if there are multiple graphs in the same space ie. a graph of error and output - * @param lower_bound the bottom of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints - * @param upper_bound the top of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints + * add_samples adds a point to the graph, removing one from the back + * @param sample an x, y coordinate of the next point to graph */ - GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound); + void add_samples(std::vector sample); + /** - * add_sample adds a point to the graph, removing one from the back - * @param sample an x, y coordinate of the next point to graph + * add_samples adds a point to the graph, removing one from the back + * @param sample a y coordinate of the next point to graph, the x coordinate is gotten from vex::timer::system(); (time in ms) */ - void add_sample(point_t sample); + void add_samples(std::vector sample); + /** * draws the graph to the screen in the constructor * @param x x position of the top left of the graphed region @@ -35,17 +37,15 @@ class GraphDrawer * @param width the width of the graphed region * @param height the height of the graphed region */ - void draw(int x, int y, int width, int height); + void draw(vex::brain::lcd &screen, int x, int y, int width, int height); private: - vex::brain::lcd &Screen; - std::vector samples; + std::vector> series; int sample_index = 0; - std::string xlabel; - std::string ylabel; - vex::color col = vex::red; + std::vector cols; vex::color bgcol = vex::transparent; bool border; double upper; double lower; + bool auto_fit = false; }; diff --git a/include/utils/logger.h b/include/utils/logger.h index 3194841..159baa6 100644 --- a/include/utils/logger.h +++ b/include/utils/logger.h @@ -26,7 +26,7 @@ class Logger public: /// @brief maximum size for a string to be before it's written - const int MAX_FORMAT_LEN = 512; + static constexpr int MAX_FORMAT_LEN = 512; /// @brief Create a logger that will save to a file /// @param filename the file to save to explicit Logger(const std::string &filename); diff --git a/include/utils/math_util.h b/include/utils/math_util.h index 8cfc91c..d419a6e 100644 --- a/include/utils/math_util.h +++ b/include/utils/math_util.h @@ -14,6 +14,13 @@ **/ double clamp(double value, double low, double high); +/** + * @brief Linearly intERPolate between values + * @param a at t = 0, output = a + * @param b at t = 1, output = b + * @return a linear mixing of a and b according to t +*/ +double lerp(double a, double b, double t); /** * Returns the sign of a number * @param x diff --git a/include/utils/moving_average.h b/include/utils/moving_average.h index 39bb9a0..099b5db 100644 --- a/include/utils/moving_average.h +++ b/include/utils/moving_average.h @@ -1,20 +1,32 @@ #pragma once #include +/** + * Interface for filters + * Use add_entry to supply data and get_value to retrieve the filtered value + */ +class Filter +{ +public: + virtual void add_entry(double n) = 0; + virtual double get_value() const = 0; +}; + /** * MovingAverage * - * A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. + * A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. * This means that if you collect enough samples those that are too high are cancelled out by the samples that are too low leaving the real value. * - * The MovingAverage class provides a simple interface to do this smoothing from our noisy sensor values. + * The MovingAverage class provides a simple interface to do this smoothing from our noisy sensor values. * - * WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' behind the actual value that the sensor is reading. - * Using a MovingAverage is thus a tradeoff between accuracy and lag time (more samples) vs. less accuracy and faster updating (less samples). + * WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' behind the actual value that the sensor is reading. + * Using a MovingAverage is thus a tradeoff between accuracy and lag time (more samples) vs. less accuracy and faster updating (less samples). * */ -class MovingAverage { - public: +class MovingAverage : public Filter +{ +public: /* * Create a moving average calculator with 0 as the default value * @@ -29,33 +41,89 @@ class MovingAverage { MovingAverage(int buffer_size, double starting_value); /* - * Add a reading to the buffer - * Before: - * [ 1 1 2 2 3 3] => 2 - * ^ - * After: - * [ 2 1 2 2 3 3] => 2.16 - * ^ - * @param n the sample that will be added to the moving average. - */ + * Add a reading to the buffer + * Before: + * [ 1 1 2 2 3 3] => 2 + * ^ + * After: + * [ 2 1 2 2 3 3] => 2.16 + * ^ + * @param n the sample that will be added to the moving average. + */ void add_entry(double n); /** * Returns the average based off of all the samples collected so far * @return the calculated average. sum(samples)/numsamples */ - double get_average(); + double get_value() const; /** - * How many samples the average is made from - * @return the number of samples used to calculate this average - */ - int get_size(); + * How many samples the average is made from + * @return the number of samples used to calculate this average + */ + int get_size() const; + +private: + int buffer_index; // index of the next value to be overridden + std::vector buffer; // all current data readings we've taken + double current_avg; // the current value of the data +}; + +/** + * ExponentialMovingAverage + * + * An exponential moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. + * This means that if you collect enough samples those that are too high are cancelled out by the samples that are too low leaving the real value. + * + * A simple mobing average lags significantly with time as it has to counteract old samples. An exponential moving average keeps more up to date by + * weighting newer readings higher than older readings so it is more up to date while also still smoothed. + * + * The ExponentialMovingAverage class provides an simple interface to do this smoothing from our noisy sensor values. + * + */ +class ExponentialMovingAverage : public Filter +{ +public: + /* + * Create a moving average calculator with 0 as the default value + * + * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading + */ + ExponentialMovingAverage(int buffer_size); + /* + * Create a moving average calculator with a specified default value + * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading + * @param starting_value The value that the average will be before any data is added + */ + ExponentialMovingAverage(int buffer_size, double starting_value); + + /* + * Add a reading to the buffer + * Before: + * [ 1 1 2 2 3 3] => 2 + * ^ + * After: + * [ 2 1 2 2 3 3] => 2.16 + * ^ + * @param n the sample that will be added to the moving average. + */ + void add_entry(double n); + /** + * Returns the average based off of all the samples collected so far + * @return the calculated average. sum(samples)/numsamples + */ + double get_value(); - private: - int buffer_index; //index of the next value to be overridden - std::vector buffer; //all current data readings we've taken - double current_avg; //the current value of the data + /** + * How many samples the average is made from + * @return the number of samples used to calculate this average + */ + int get_size(); +private: + int buffer_index; // index of the next value to be overridden + std::vector buffer; // all current data readings we've taken + double current_avg; // the current value of the data }; \ No newline at end of file diff --git a/include/utils/pure_pursuit.h b/include/utils/pure_pursuit.h index 9d3b17c..3fd8edb 100644 --- a/include/utils/pure_pursuit.h +++ b/include/utils/pure_pursuit.h @@ -8,6 +8,39 @@ using namespace vex; namespace PurePursuit { + /** + * Wrapper for a vector of points, checking if any of the points are too close for pure pursuit + */ + class Path + { + public: + /** + * Create a Path + * @param points the points that make up the path + * @param radius the lookahead radius for pure pursuit + */ + Path(std::vector points, double radius); + + /** + * Get the points associated with this Path + */ + std::vector get_points(); + + /** + * Get the radius associated with this Path + */ + double get_radius(); + + /** + * Get whether this path will behave as expected + */ + bool is_valid(); + + private: + std::vector points; + double radius; + bool valid; + }; /** * Represents a piece of a cubic spline with s(x) = a(x-xi)^3 + b(x-xi)^2 + c(x-xi) + d * The x_start and x_end shows where the equation is valid. diff --git a/include/utils/serializer.h b/include/utils/serializer.h index bf29138..327b653 100644 --- a/include/utils/serializer.h +++ b/include/utils/serializer.h @@ -4,11 +4,12 @@ #include #include #include +#include /// @brief character that will be used to seperate values const char serialization_separator = '$'; /// @brief max file size that the system can deal with -const std::size_t MAX_FILE_SIZE = 4096; +const std::size_t MAX_FILE_SIZE = 4096; /// @brief Serializes Arbitrary data to a file on the SD Card class Serializer @@ -36,7 +37,11 @@ class Serializer /// @brief create a Serializer /// @param filename the file to read from. If filename does not exist we will create that file /// @param flush_always If true, after every write flush to a file. If false, you are responsible for calling save_to_disk - explicit Serializer(const std::string &filename, bool flush_always = true) : flush_always(flush_always), filename(filename), ints({}), bools({}), doubles({}), strings({}) { read_from_disk(); } + explicit Serializer(const std::string &filename, bool flush_always = true) : flush_always(flush_always), filename(filename), ints({}), bools({}), doubles({}), strings({}) + + { + read_from_disk(); + } /// @brief saves current Serializer state to disk void save_to_disk() const; diff --git a/include/utils/trapezoid_profile.h b/include/utils/trapezoid_profile.h deleted file mode 100644 index 865d342..0000000 --- a/include/utils/trapezoid_profile.h +++ /dev/null @@ -1,87 +0,0 @@ -#pragma once - -/** - * motion_t is a description of 1 dimensional motion at a point in time. -*/ -typedef struct -{ - double pos; ///< 1d position at this point in time - double vel; ///< 1d velocity at this point in time - double accel; ///< 1d acceleration at this point in time - -} motion_t; - -/** - * Trapezoid Profile - * - * This is a motion profile defined by an acceleration, maximum velocity, start point and end point. - * Using this information, a parametric function is generated, with a period of acceleration, constant - * velocity, and deceleration. The velocity graph looks like a trapezoid, giving it it's name. - * - * If the maximum velocity is set high enough, this will become a S-curve profile, with only acceleration and deceleration. - * - * This class is designed for use in properly modelling the motion of the robots to create a feedfoward - * and target for PID. Acceleration and Maximum velocity should be measured on the robot and tuned down - * slightly to account for battery drop. - * - * Here are the equations graphed for ease of understanding: - * https://www.desmos.com/calculator/rkm3ivu1yk - * - * @author Ryan McGee - * @date 7/12/2022 - * - */ -class TrapezoidProfile -{ - public: - - /** - * @brief Construct a new Trapezoid Profile object - * - * @param max_v Maximum velocity the robot can run at - * @param accel Maximum acceleration of the robot - */ - TrapezoidProfile(double max_v, double accel); - - /** - * @brief Run the trapezoidal profile based on the time that's ellapsed - * - * @param time_s Time since start of movement - * @return motion_t Position, velocity and acceleration - */ - motion_t calculate(double time_s); - - /** - * set_endpts defines a start and end position - * @param start the starting position of the path - * @param end the ending position of the path - */ - void set_endpts(double start, double end); - - /** - * set_accel sets the acceleration this profile will use (the left and right legs of the trapezoid) - * @param accel the acceleration amount to use - */ - void set_accel(double accel); - - /** - * sets the maximum velocity for the profile - * (the height of the top of the trapezoid) - * @param max_v the maximum velocity the robot can travel at - */ - void set_max_v(double max_v); - - /** - * uses the kinematic equations to and specified accel and max_v to figure out how long moving along the profile would take - * @return the time the path will take to travel - */ - double get_movement_time(); - - private: - double start, end; ///< the start and ending position of the profile - double max_v; ///< the maximum velocity to travel at for this profile - double accel; ///< the rate of acceleration to use for this profile. - double time; ///< the current point in time along the path - - -}; \ No newline at end of file diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index 01a2c2a..b740c58 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -1,307 +1,185 @@ -/********************************************************* -* -* File: Flywheel.cpp -* Purpose: Generalized flywheel class for Core. -* Author: Chris Nokes, Richie Sommers -* -********************************************************** -* EDIT HISTORY -********************************************************** -* 09/16/2022 Created file, added constructor, spins, RPM setting, stop. -* 09/18/2022 Added async functionality. -* 09/22/2022 Documentation improvements, fixed error if RPM is set but motor is stopped. -* 09/23/2022 Neatened up program, added getters and setters, fixed documentation and bang bang. -* 09/29/2022 Bug fixes, RPM handling. Multiplied the motor by 18. -*********************************************************/ - #include "../core/include/subsystems/flywheel.h" -#include "../core/include/utils/feedforward.h" -#include "../core/include/utils/pid.h" +#include "../core/include/utils/controls/feedforward.h" +#include "../core/include/utils/controls/pid.h" #include "../core/include/utils/math_util.h" +#include "../core/include/subsystems/screen.h" +#include "../core/include/utils/graph_drawer.h" #include "vex.h" using namespace vex; -const int FlywheelWindowSize = 20; - /********************************************************* -* CONSTRUCTOR, GETTERS, SETTERS -*********************************************************/ -//used when using bang bang or TBH control -PID::pid_config_t empty_pid = PID::pid_config_t{}; -FeedForward::ff_config_t empty_ff = FeedForward::ff_config_t{}; - -/** -* Create the Flywheel object using PID + feedforward for control. -*/ -Flywheel::Flywheel(motor_group &motors, PID::pid_config_t &pid_config, FeedForward::ff_config_t &ff_config, const double ratio) - :motors(motors), pid(pid_config), ff(ff_config), ratio(ratio), control_style(PID_Feedforward), smoothedRPM(0), RPM_avger(MovingAverage(FlywheelWindowSize)) { - } - -/** -* Create the Flywheel object using only feedforward for control -*/ -Flywheel::Flywheel(motor_group &motors, FeedForward::ff_config_t &ff_config, const double ratio) - :motors(motors), pid(empty_pid), ff(ff_config), ratio(ratio), control_style(Feedforward), smoothedRPM(0), RPM_avger(MovingAverage(FlywheelWindowSize)) {} - -/** -* Create the Flywheel object using Take Back Half for control -*/ -Flywheel::Flywheel(motor_group &motors, const double TBH_gain, const double ratio) - :motors(motors), pid(empty_pid), ff(empty_ff), TBH_gain(TBH_gain), ratio(ratio), control_style(Take_Back_Half), smoothedRPM(0), RPM_avger(MovingAverage(FlywheelWindowSize)) {} - -/** -* Create the Flywheel object using Bang Bang for control -*/ -Flywheel::Flywheel(motor_group &motors, const double ratio) - :motors(motors), pid(empty_pid), ff(empty_ff), ratio(ratio), control_style(Bang_Bang), smoothedRPM(0), RPM_avger(MovingAverage(FlywheelWindowSize)) {} - -/** -* Return the current value that the RPM should be set to -*/ -double Flywheel::getDesiredRPM() { return RPM; } - -/** -* Checks if the background RPM controlling task is running -* @return taskRunning - If the task is running -*/ -bool Flywheel::isTaskRunning() { return taskRunning; } - -/** -* Returns a POINTER TO the motors; not currently used. -* @return motorPointer -pointer to the motors -*/ -motor_group* Flywheel::getMotors() { return &motors; } // TODO -- Remove? + * CONSTRUCTOR, GETTERS, SETTERS + *********************************************************/ -/** -* return the current velocity of the flywheel motors, in RPM -* @return the measured velocity of the flywheel -*/ -double Flywheel::measureRPM() { - double rawRPM = ratio * motors.velocity(velocityUnits::rpm); - RPM_avger.add_entry(rawRPM); - smoothedRPM = RPM_avger.get_average(); - return smoothedRPM; //TODO Change back -} +Flywheel::Flywheel(motor_group &motors, Feedback &feedback, FeedForward &helper, const double ratio, Filter &filt) : motors(motors), + task_running(false), fb(feedback), ff(helper), + ratio(ratio), avger(filt) {} -double Flywheel::getRPM(){ - return smoothedRPM; -} /** -* Returns a POINTER TO the PID; not currently used. -* @return pidPointer -pointer to the PID -*/ -PID* Flywheel::getPID() { return &pid; } // TODO -- Remove? + * Return the current value that the target_rpm should be set to + */ +double Flywheel::get_target() const { return target_rpm; } /** -* returns the current OUT value of the PID - the value that the PID would set the motors to -* @return the voltage that PID wants the motors at to achieve the target RPM -*/ -double Flywheel::getPIDValue() { return pid.get(); } + * @return the motors used to run the flywheel + */ +motor_group &Flywheel::get_motors() const { return motors; } /** -* returns the current OUT value of the Feedforward - the value that the Feedforward would set the motors to -* @return the voltage that feedforward wants the motors at to achieve the target RPM -*/ -double Flywheel::getFeedforwardValue() { - double v = getDesiredRPM(); - return ff.calculate(v, 0); + * return the current velocity of the flywheel motors, in RPM + * @return the measured velocity of the flywheel + */ +double Flywheel::measure_RPM() +{ + double rawRPM = ratio * motors.velocity(velocityUnits::rpm); + avger.add_entry(rawRPM); + return avger.get_value(); } -/** -* get the gain used for TBH control -* @return the gain used in TBH control -*/ -double Flywheel::getTBHGain(){ - return TBH_gain; +double Flywheel::getRPM() const +{ + return avger.get_value(); } /** -* Sets the value of the PID target -* @param value - desired value of the PID -*/ -void Flywheel::setPIDTarget(double value) { pid.set_target(value); } - -/** -* updates the value of the PID -* @param value - value to update the PID with -*/ -void Flywheel::updatePID(double value) { pid.update(value); } - -/********************************************************* -* RPM SETTING THREADS -* ALL OF THE FOLLOWING PROGRAMS HAVE THE SAME PARAMETERS AND RESULTS: -* spin this flywheel at a given RPM, async; runs until stop(), stopThread(), or a new spinRPM() is called. -* @param wheelPointer - points to the current wheel object -*********************************************************/ - -/** -* Runs a Feedforward variant to control rpm -*/ -int spinRPMTask_BangBang(void* wheelPointer) { - Flywheel* wheel = (Flywheel*) wheelPointer; - while(true) { - // if it below the RPM, go, otherwise don't - wheel->measureRPM(); - - if(wheel->getRPM() < wheel->getDesiredRPM()) { - wheel->spin_raw(1, fwd); - } - else { wheel->stopMotors(); } - vexDelay(10); - } - return 0; -} + * Runs a thread that keeps track of updating flywheel RPM and controlling it accordingly + */ +int spinRPMTask(void *wheelPointer) +{ + Flywheel &wheel = *(Flywheel *)wheelPointer; -/** -* Runs a Feedforward variant to control rpm -*/ -int spinRPMTask_Feedforward(void* wheelPointer) { - Flywheel* wheel = (Flywheel*) wheelPointer; - // get the pid from the wheel and set its target to the RPM stored in the wheel. - while(true) { - wheel->measureRPM(); - wheel->updatePID(wheel->getRPM()); // check the current velocity and update the PID with it. - double output = wheel->getFeedforwardValue(); - wheel->spin_raw(output, fwd); // set the motors to whatever feedforward tells them to do - vexDelay(1); - } - return 0; -} -/** -* Runs a PID + Feedforward variant to control rpm -*/ -int spinRPMTask_PID_Feedforward(void* wheelPointer) { - Flywheel* wheel = (Flywheel*) wheelPointer; // get the pid from the wheel and set its target to the RPM stored in the wheel. - while(true) { - wheel->measureRPM(); - wheel->updatePID(wheel->getRPM()); // check the current velocity and update the PID with it. - double output = wheel->getPIDValue() + wheel->getFeedforwardValue(); - wheel->spin_raw(output, fwd); // set the motors to whatever PID tells them to do - vexDelay(1); - } - return 0; -} - -/** -* Runs a Take Back Half variant to control RPM -* https://www.vexwiki.org/programming/controls_algorithms/tbh -*/ -int spinRPMTask_TBH(void* wheelPointer) { - Flywheel* wheel = (Flywheel*) wheelPointer; - - double tbh = 0.0; - double output = 0.0; - double previous_error = 0.0; - - while (true){ - wheel->measureRPM(); - - //reset if set to 0, this keeps the tbh val from screwing us up when we start up again - if (wheel->getDesiredRPM()==0){ - output = 0; - tbh = 0; - } - - double error = wheel->getDesiredRPM() - wheel->getRPM(); - output += wheel->getTBHGain() * error; - wheel->spin_raw(clamp(output, 0, 1), fwd); - - if (sign(error)!=sign(previous_error)){ - output = .5 * (output + tbh); - tbh = output; - previous_error = error; + while (true) + { + double rpm = wheel.measure_RPM(); + + if (wheel.target_rpm != 0) + { + double output = wheel.ff.calculate(wheel.target_rpm, 0.0, 0.0); + { + wheel.fb_mut.lock(); + wheel.fb.update(rpm); // check the current velocity and update the PID with it. + + output += wheel.fb.get(); + wheel.fb_mut.unlock(); + } + + wheel.spin_raw(output, fwd); // set the motors to whatever feedforward tells them to do } - - vexDelay(1); + vexDelay(5); } - - return 0; + return 0; } -// Runs a 'Moving average filter with above closed loop systems' variant, whatever that means; FUNCTION STUB -int spinRPMTask_ClosedLoop(void* wheelPointer) { return 0; } - /********************************************************* -* SPINNERS AND STOPPERS -*********************************************************/ + * SPINNERS AND STOPPERS + *********************************************************/ -/** -* Spin motors using voltage; defaults forward at 12 volts -* FOR USE BY TASKS ONLY -* @param speed - speed (between -1 and 1) to set the motor -* @param dir - direction that the motor moves in; defaults to forward -*/ -void Flywheel::spin_raw(double speed, directionType dir){ +/** + * Spin motors using voltage; defaults forward at 12 volts + * FOR USE BY TASKS ONLY + * @param speed - speed (between -1 and 1) to set the motor + * @param dir - direction that the motor moves in; defaults to forward + */ +void Flywheel::spin_raw(double speed, directionType dir) +{ motors.spin(dir, speed * 12, voltageUnits::volt); } /** -* Spin motors using voltage; defaults forward at 12 volts -* FOR USE BY OPCONTROL AND AUTONOMOUS - this only applies if the RPM thread is not running -* @param speed - speed (between -1 and 1) to set the motor -* @param dir - direction that the motor moves in; defaults to forward -*/ -void Flywheel::spin_manual(double speed, directionType dir){ - if(!taskRunning) motors.spin(dir, speed * 12, voltageUnits::volt); + * Spin motors using voltage; defaults forward at 12 volts + * FOR USE BY OPCONTROL AND AUTONOMOUS - this only applies if the RPM thread is not running + * @param speed - speed (between -1 and 1) to set the motor + * @param dir - direction that the motor moves in; defaults to forward + */ +void Flywheel::spin_manual(double speed, directionType dir) +{ + if (!task_running) + motors.spin(dir, speed * 12, voltageUnits::volt); } /** -* starts or sets the RPM thread at new value -* what control scheme is dependent on control_style -* @param inputRPM - set the current RPM -*/ -void Flywheel::spinRPM(int inputRPM) { + * starts or sets the RPM thread at new value + * what control scheme is dependent on control_style + * @param input_rpm - set the current RPM + */ +void Flywheel::spin_rpm(double input_rpm) +{ // setting to 0 is equivelent to stopping - if (inputRPM==0){ + if (input_rpm == 0.0) + { stop(); } // only run if the RPM is different or it isn't already running - if(!taskRunning) { - - int (*rpm_control_task)(void *); // this just means a function that returns int and takes a void pointer as an argument aka a spinRPMTask function - // choose which version to use based on how the flywheel was constructed - switch(control_style){ - case Bang_Bang: - rpm_control_task = spinRPMTask_BangBang; - break; - case Take_Back_Half: - rpm_control_task = spinRPMTask_TBH; - break; - case Feedforward: - rpm_control_task = spinRPMTask_Feedforward; - break; - case PID_Feedforward: - rpm_control_task = spinRPMTask_PID_Feedforward; - break; - } - - - rpmTask = task(rpm_control_task, this); - taskRunning = true; + if (!task_running) + { + rpm_task = task(spinRPMTask, this); + task_running = true; } - RPM = inputRPM; - setPIDTarget(RPM); + // now that its running, set the target + set_target(input_rpm); +} +void Flywheel::set_target(double value) +{ + fb_mut.lock(); + target_rpm = (value); + fb.init(getRPM(), value); + fb_mut.unlock(); } /** -* stop the RPM thread and the wheel -*/ -void Flywheel::stop() { - rpmTask.stop(); - taskRunning = false; - RPM = 0.0; - smoothedRPM = 0.0; - motors.stop(); + * stop the RPM thread and the wheel + */ +void Flywheel::stop() +{ + if (task_running) + { + task_running = false; + rpm_task.stop(); + target_rpm = 0.0; + motors.stop(); + } } -/** -* stop only the motors; exclusively for BANG BANG use -*/ -void Flywheel::stopMotors() { motors.stop(); } +//------------------------- Screen Stuff ---------------------------- +class FlywheelPage : public screen::Page +{ +public: + static const size_t window_size = 40; + + FlywheelPage(const Flywheel &fw) : fw(fw), gd(GraphDrawer(window_size, 0.0, 0.0, {vex::color(255, 0, 0), vex::color(0, 255, 0), vex::color(0, 0, 255)}, 3)), avg_err(window_size) {} + /// @brief @see Page#update + void update(bool, int, int) override {} + /// @brief @see Page#draw + void draw(vex::brain::lcd &screen, bool, + unsigned int) override + { + + double target = fw.get_target(); + double actual = fw.getRPM(); + double err = fabs(target - actual); + + avg_err.add_entry(err); + double volts = fw.fb.get() * 12.0; + gd.add_samples({target, actual, volts / 12.0 * 1000.0}); + + gd.draw(screen, 200, 10, 220, 220); + screen.setPenColor(vex::white); + screen.printAt(50, 30, "set: %.2f", target); + screen.printAt(50, 60, "act: %.2f", actual); + screen.printAt(50, 90, "stddev: %.2f", avg_err.get_value()); + screen.printAt(50, 150, "temp: %.2fc", fw.get_motors().temperature(vex::celsius)); + screen.printAt(50, 180, "volt: %.2fv", volts); + } -/** -* Stop the motors if the task isn't running - stop manual control -*/ -void Flywheel::stopNonTasks() { if(!taskRunning) { motors.stop(); }} \ No newline at end of file +private: + const Flywheel &fw; + GraphDrawer gd; + MovingAverage avg_err; +}; + +screen::Page *Flywheel::Page() const +{ + return new FlywheelPage(*this); +} \ No newline at end of file diff --git a/src/subsystems/screen.cpp b/src/subsystems/screen.cpp index 40e11dc..43066f3 100644 --- a/src/subsystems/screen.cpp +++ b/src/subsystems/screen.cpp @@ -1,5 +1,5 @@ #include "../core/include/subsystems/screen.h" - +#include "../core/include/utils/math_util.h" namespace screen { /** @@ -30,6 +30,13 @@ namespace screen void start_screen(vex::brain::lcd &screen, std::vector pages, int first_page) { + if (pages.size() == 0) + { + printf("No pages, not starting screen"); + return; + } + first_page %= pages.size(); + if (running) { printf("THERE IS ALREADY A SCREEN THREAD RUNNING\n"); @@ -98,7 +105,7 @@ namespace screen } // Draw First Page - if (frame % 5 == 0) + if (frame % 2 == 0) { screen_data.screen.clearScreen(vex::color::black); screen_data.screen.setPenColor("#FFFFFF"); @@ -122,7 +129,7 @@ namespace screen screen_data.screen.render(); frame++; was_pressed = pressing; - vexDelay(20); + vexDelay(5); } return 0; @@ -187,11 +194,13 @@ namespace screen scr.drawRectangle(x, y, row_width, row_height, col); scr.printAt(x + 2, y + 16, false, " %2d %2.0fC %.7s", port, temp, name.c_str()); } - void StatsPage::draw(vex::brain::lcd &scr, bool first_draw, unsigned int frame_number) + void StatsPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], unsigned int frame_number [[maybe_unused]]) { int num = 0; int x = 40; int y = y_start + row_height; + scr.setPenWidth(1); + scr.drawRectangle(x, y_start, row_width, row_height); scr.printAt(x, y_start + 16, false, " port temp name"); for (auto &kv : motors) @@ -214,7 +223,7 @@ namespace screen scr.printAt(50, 220, "Battery: %2.1fv %2.0fC %d%%", b.Battery.voltage(), b.Battery.temperature(vex::temperatureUnits::celsius), b.Battery.capacity()); } - OdometryPage::OdometryPage(OdometryBase &odom, double width, double height, bool do_trail) : odom(odom), width(width), height(height), do_trail(do_trail) + OdometryPage::OdometryPage(OdometryBase &odom, double width, double height, bool do_trail) : odom(odom), robot_width(width), robot_height(height), do_trail(do_trail) { vex::brain b; if (b.SDcard.exists(field_filename)) @@ -236,13 +245,15 @@ namespace screen return (int)(p * 240); } - void OdometryPage::draw(vex::brain::lcd &scr, bool first_draw, unsigned int frame_number) + void OdometryPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], unsigned int frame_number [[maybe_unused]]) { - if (do_trail) + pose_t pose = odom.get_position(); + path[path_index] = pose; + + if (do_trail && frame_number % 5 == 0) { path_index++; path_index %= path_len; - path[path_index] = odom.get_position(); } auto to_px = [](const point_t p) -> point_t @@ -255,7 +266,6 @@ namespace screen scr.drawLine((int)to_px(from).x, (int)to_px(from).y, (int)to_px(to).x, (int)to_px(to).y); }; - pose_t pose = path[path_index]; point_t pos = pose.get_point(); fflush(stdout); scr.printAt(45, 30, "(%.2f, %.2f)", pose.x, pose.y); @@ -279,7 +289,8 @@ namespace screen { int j = i % path_len; pose_t pose = path[j]; - scr.setPenColor(vex::color(80, 80, 80)); + scr.setPenWidth(2); + scr.setPenColor(vex::color(255, 255, 80)); draw_line(pose.get_point(), last_pos.get_point()); last_pos = pose; } @@ -287,8 +298,8 @@ namespace screen scr.setPenColor(vex::color::white); Mat2 mat = Mat2::FromRotationDegrees(pose.rot - 90); - const point_t to_left = point_t{-width / 2.0, 0}; - const point_t to_front = point_t{0.0, height / 2.0}; + const point_t to_left = point_t{-robot_width / 2.0, 0}; + const point_t to_front = point_t{0.0, robot_height / 2.0}; const point_t fl = pos + mat * (+to_left + to_front); const point_t fr = pos + mat * (-to_left + to_front); @@ -309,257 +320,131 @@ namespace screen (void)y; (void)was_pressed; } -} // namespace screen - -/* -void draw_battery_stats(vex::brain::lcd &screen, int x, int y, double -voltage, double percentage) -{ - double low_pct = 70.0; - double med_pct = 85.0; - - vex::color low_col = vex::color(120, 0, 0); - vex::color med_col = vex::color(140, 100, 0); - vex::color high_col = vex::black; - vex::color bg_col = vex::black; - vex::color border_col = vex::white; - - if (percentage < low_pct) - { - bg_col = low_col; - } - else if (percentage < med_pct) + bool SliderWidget::update(bool was_pressed, int x, int y) { - bg_col = med_col; + const double margin = 10.0; + if (was_pressed) + { + double dx = x; + double dy = y; + if (rect.contains(point_t{dx, dy})) + { + double pct = (dx - rect.min.x - margin) / (rect.dimensions().x - 2 * margin); + pct = clamp(pct, 0.0, 1.0); + value = (low + pct * (high - low)); + } + return true; + } + return false; } - else + void SliderWidget::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], unsigned int frame_number [[maybe_unused]]) { - bg_col = high_col; - } - - screen.setPenWidth(3); - screen.setFillColor(bg_col); - screen.setPenColor(border_col); - screen.setFont(vex::mono15); - - screen.drawRectangle(x + 3, y, 200 - 3, 20); - screen.printAt(x + 5, y + 15, "battery: %.1fv %d%%", voltage, -(int)percentage); -} - -void draw_mot_header(vex::brain::lcd &screen, int x, int y, int width) -{ - vex::color bg_col = vex::black; - vex::color border_col = vex::white; - screen.setPenWidth(3); - screen.setFillColor(bg_col); - screen.setPenColor(border_col); - screen.setFont(vex::mono15); + if (rect.height() <= 0) + { + printf("Slider: %s has no height. Cant use it.", name.c_str()); + } + double xl = rect.min.x; + double xh = rect.max.x; + double xmid = (xl + xh) / 2.0; + double y = rect.min.y + rect.height() / 2; + const double margin = 5.0; - screen.drawRectangle(x + 3, y, width - 3, 20); - screen.printAt(x + 5, y + 15, "motor name"); - int name_width = 110; + scr.setPenColor(vex::color(50, 50, 50)); + scr.setFillColor(vex::color(50, 50, 50)); + scr.setPenWidth(1); - screen.printAt(x + name_width + 7, y + 15, "temp"); + scr.drawRectangle(rect.min.x, rect.min.y, rect.dimensions().x, rect.dimensions().y); - screen.drawLine(x + name_width, y, x + name_width, y + 20); + scr.setPenColor(vex::color(200, 200, 200)); + scr.setPenWidth(4); - screen.drawLine(x + name_width + 50, y, x + name_width + 50, y + 20); + scr.drawLine(xl + margin, y, xh - margin, y); - screen.printAt(x + name_width + 55, y + 15, "port"); -} + double pct = (value - low) / (high - low); + double vx = pct * (rect.dimensions().x - (2 * margin)) + rect.min.x + margin; + const double handle_width = 4; + const double handle_height = 4; -void draw_mot_stats(vex::brain::lcd &screen, int x, int y, int width, const -char *name, vex::motor &motor, int animation_tick) -{ - double tempC = motor.temperature(vex::celsius); - bool pluggedin = motor.installed(); - int port = motor.index() + 1; - - // used for flashing - vex::color bg_col = vex::black; - vex::color hot_col = vex::color(120, 0, 0); - vex::color med_col = vex::color(140, 100, 0); - vex::color low_col = vex::black; // color(0,100,0); - vex::color not_plugged_in_col = vex::color(255, 0, 0); - - double lowtemp = 40; - double hightemp = 50; - if (tempC < lowtemp) - { - bg_col = low_col; - } - else if (tempC >= lowtemp && tempC < hightemp) - { - bg_col = med_col; - } - else if (tempC >= hightemp) - { - bg_col = hot_col; + scr.drawRectangle(vx - (handle_width / 2), y - (handle_height / 2), handle_width, handle_height); + int text_w = scr.getStringWidth((name + " ").c_str()); + scr.printAt(xmid - text_w / 2, y - 15, false, "%s: %.5f", name.c_str(), value); } - if (!pluggedin) + bool ButtonWidget::update(bool was_pressed, int x, int y) { - if ((animation_tick / 8) % 2 == 0) + if (was_pressed && !was_pressed_last && rect.contains({(double)x, (double)y})) { - bg_col = not_plugged_in_col; + onpress(); + was_pressed_last = was_pressed; + return true; } + was_pressed_last = was_pressed; + return false; } - vex::color border_col = vex::white; - screen.setPenWidth(3); - screen.setFillColor(bg_col); - screen.setPenColor(border_col); - screen.setFont(vex::mono15); - - screen.drawRectangle(x + 3, y, width - 3, 20); - - // name - screen.printAt(x + 7, y + 15, name); - int name_width = 110; - - // temp - screen.drawLine(x + name_width, y, x + name_width, y + 20); - screen.printAt(x + name_width + 10, y + 15, "%dC", (int)tempC); - - // PORT - screen.drawLine(x + name_width + 50, y, x + name_width + 50, y + 20); - char *warning = (char *)"!"; - if (pluggedin) + void ButtonWidget::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], unsigned int frame_number [[maybe_unused]]) { - warning = (char *)""; + scr.setPenColor(vex::white); + scr.setPenWidth(1); + scr.setFillColor(vex::color(50, 50, 50)); + scr.drawRectangle(rect.min.x, rect.min.y, rect.width(), rect.height()); + int w = scr.getStringWidth(name.c_str()); + int h = scr.getStringHeight(name.c_str()); + scr.printAt(rect.center().x - w / 2, rect.center().y + h / 2, name.c_str()); } - screen.printAt(x + name_width + 60, y + 15, "%d%s", port, warning); -} -// -void draw_dev_stats(vex::brain::lcd &screen, int x, int y, int width, const -char *name, vex::device &dev, int animation_tick) -{ - bool pluggedin = dev.installed(); - int port = dev.index() + 1; + PIDPage::PIDPage( + PID &pid, std::string name, std::function onchange) + : cfg(pid.config), pid(pid), name(name), onchange(onchange), + p_slider(cfg.p, 0.0, 0.5, Rect{{60, 20}, {210, 60}}, "P"), + i_slider(cfg.i, 0.0, 0.05, Rect{{60, 80}, {180, 120}}, "I"), + d_slider(cfg.d, 0.0, 0.05, Rect{{60, 140}, {180, 180}}, "D"), + zero_i([this]() + { zero_i_f(); }, + Rect{{180, 80}, {220, 120}}, "0"), + zero_d([this]() + { zero_d_f(); }, + Rect{{180, 140}, {220, 180}}, "0"), + graph(40, 0, 0, {vex::red, vex::green}, 2) + { + } - // used for flashing - vex::color bg_col = vex::black; - vex::color not_plugged_in_col = vex::color(255, 0, 0); + PIDPage::PIDPage(PIDFF &pidff, std::string name, std::function onchange) : PIDPage((pidff.pid), name, onchange) {} - if (!pluggedin) + void PIDPage::update(bool was_pressed, int x, int y) { - if ((animation_tick / 8) % 2 == 0) + bool updated = false; + updated |= p_slider.update(was_pressed, x, y); + updated |= i_slider.update(was_pressed, x, y); + updated |= d_slider.update(was_pressed, x, y); + + updated |= zero_i.update(was_pressed, x, y); + updated |= zero_d.update(was_pressed, x, y); + if (updated) { - bg_col = not_plugged_in_col; + onchange(); } } - - vex::color border_col = vex::white; - screen.setPenWidth(3); - screen.setFillColor(bg_col); - screen.setPenColor(border_col); - screen.setFont(vex::mono15); - - screen.drawRectangle(x + 3, y, width - 3, 20); - - // name - screen.printAt(x + 5, y + 15, name); - int name_width = 110; - - // temp - // screen.drawLine(x + name_width, y, x + name_width, y + 20); - // screen.printAt(x + name_width + 10, y + 15, "%dC", (int)tempC); - - // PORT - screen.drawLine(x + name_width + 50, y, x + name_width + 50, y + 20); - char *warning = (char *)"!"; - if (pluggedin) + void PIDPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], unsigned int frame_number [[maybe_unused]]) { - warning = (char *)""; - } - screen.printAt(x + name_width + 60, y + 15, "%d%s", port, warning); -} + p_slider.draw(scr, first_draw, frame_number); + i_slider.draw(scr, first_draw, frame_number); + d_slider.draw(scr, first_draw, frame_number); + zero_i.draw(scr, first_draw, frame_number); + zero_d.draw(scr, first_draw, frame_number); -void draw_lr_arrows(vex::brain::lcd &screen, int bar_width, int width, int -height) -{ - auto bar_col = vex::color(40, 40, 40); - auto arrow_col = vex::color(255, 255, 255); - // draw touch zones - screen.setFillColor(bar_col); - screen.setPenColor(bar_col); - - screen.drawRectangle(0, 0, bar_width, height); - screen.drawRectangle(width - bar_width, 0, width, height); - - // draw arrows - screen.setPenColor(arrow_col); - screen.drawLine(bar_width / 3, height / 2, 2 * bar_width / 3, height / 2 -- 20); screen.drawLine(bar_width / 3, height / 2, 2 * bar_width / 3, height -/ 2 + 20); - - screen.drawLine(width - bar_width / 3, height / 2, width - 2 * bar_width -/ 3, height / 2 - 20); screen.drawLine(width - bar_width / 3, height / 2, -width - 2 * bar_width / 3, height / 2 + 20); -} - -int handle_screen_thread(vex::brain::lcd &screen, std::vector -pages, int first_page) -{ - unsigned int num_pages = pages.size(); - unsigned int current_page = first_page; + graph.add_samples({pid.get_target(), pid.get_sensor_val()}); - int width = 480; - int height = 240; + graph.draw(scr, 230, 20, 200, 200); - int bar_width = 40; + scr.setPenColor(vex::white); + scr.printAt(60, 215, false, "%s", name.c_str()); - bool was_pressing = false; - bool first_draw = true; - while (true) - { - pages[current_page](screen, bar_width, 0, width - bar_width * 2, -height, first_draw); - - first_draw = false; - // handle presses - if (screen.pressing() && !was_pressing) - { - - int x = screen.xPosition(); - // int y = screen.yPosition(); - - if (x < bar_width) - { - if (current_page == 0) - { - current_page = num_pages; - } - current_page--; - first_draw = true; - } - - if (x > width - bar_width) - { - current_page++; - current_page %= num_pages; - first_draw = true; - } - } - draw_lr_arrows(screen, bar_width, width, height); - was_pressing = screen.pressing(); - screen.render(); - vexDelay(40); + scr.setPenColor(vex::red); + scr.printAt(240, 20, false, "%.2f", pid.get_target()); + scr.setPenColor(vex::green); + scr.printAt(300, 20, false, "%.2f", pid.get_sensor_val()); } - return 0; -} - -void StartScreen(vex::brain::lcd &screen, std::vector pages, int -first_page) -{ - // hold onto arguments here so we don't lose them and can use then in -the lambda down there. capture semantics are not fun static -std::vector my_pages = pages; static vex::brain::lcd my_screen = -screen; static int my_first_page = first_page; vex::task screenTask([]() { -return handle_screen_thread(my_screen, my_pages, my_first_page); }); -} -*/ +} // namespace screen diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 095cf80..d86f61f 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -1,7 +1,7 @@ #include "../core/include/utils/geometry.h" #include "../core/include/subsystems/tank_drive.h" #include "../core/include/utils/math_util.h" -#include "../core/include/utils/pidff.h" +#include "../core/include/utils/controls/pidff.h" #include "../core/include/utils/command_structure/drive_commands.h" TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom) @@ -11,50 +11,50 @@ TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, robot_ turn_default_feedback = config.turn_feedback; } -AutoCommand *TankDrive::DriveToPointCmd(Feedback &fb, point_t pt, vex::directionType dir, double max_speed) +AutoCommand *TankDrive::DriveToPointCmd(Feedback &fb, point_t pt, vex::directionType dir, double max_speed, double end_speed) { - return new DriveToPointCommand(*this, fb, pt, dir, max_speed); + return new DriveToPointCommand(*this, fb, pt, dir, max_speed, end_speed); } -AutoCommand *TankDrive::DriveToPointCmd(point_t pt, vex::directionType dir, double max_speed) +AutoCommand *TankDrive::DriveToPointCmd(point_t pt, vex::directionType dir, double max_speed, double end_speed) { - return new DriveToPointCommand(*this, *drive_default_feedback, pt, dir, max_speed); + return new DriveToPointCommand(*this, *drive_default_feedback, pt, dir, max_speed, end_speed); } -AutoCommand *TankDrive::DriveForwardCmd(double dist, vex::directionType dir, double max_speed) +AutoCommand *TankDrive::DriveForwardCmd(double dist, vex::directionType dir, double max_speed, double end_speed) { - return new DriveForwardCommand(*this, *drive_default_feedback, dist, dir, max_speed); + return new DriveForwardCommand(*this, *drive_default_feedback, dist, dir, max_speed, end_speed); } -AutoCommand *TankDrive::DriveForwardCmd(Feedback &fb, double dist, vex::directionType dir, double max_speed) +AutoCommand *TankDrive::DriveForwardCmd(Feedback &fb, double dist, vex::directionType dir, double max_speed, double end_speed) { - return new DriveForwardCommand(*this, fb, dist, dir, max_speed); + return new DriveForwardCommand(*this, fb, dist, dir, max_speed, end_speed); } -AutoCommand *TankDrive::TurnToHeadingCmd(double heading, double max_speed) +AutoCommand *TankDrive::TurnToHeadingCmd(double heading, double max_speed, double end_speed) { - return new TurnToHeadingCommand(*this, *turn_default_feedback, heading, max_speed); + return new TurnToHeadingCommand(*this, *turn_default_feedback, heading, max_speed, end_speed); } -AutoCommand *TankDrive::TurnToHeadingCmd(Feedback &fb, double heading, double max_speed) +AutoCommand *TankDrive::TurnToHeadingCmd(Feedback &fb, double heading, double max_speed, double end_speed) { - return new TurnToHeadingCommand(*this, fb, heading, max_speed); + return new TurnToHeadingCommand(*this, fb, heading, max_speed, end_speed); } -AutoCommand *TankDrive::TurnDegreesCmd(double degrees, double max_speed) +AutoCommand *TankDrive::TurnDegreesCmd(double degrees, double max_speed, double end_speed) { - return new TurnDegreesCommand(*this, *turn_default_feedback, degrees, max_speed); + return new TurnDegreesCommand(*this, *turn_default_feedback, degrees, max_speed, end_speed); } -AutoCommand *TankDrive::TurnDegreesCmd(Feedback &fb, double degrees, double max_speed) +AutoCommand *TankDrive::TurnDegreesCmd(Feedback &fb, double degrees, double max_speed, double end_speed) { - return new TurnDegreesCommand(*this, fb, degrees, max_speed); + return new TurnDegreesCommand(*this, fb, degrees, max_speed, end_speed); } -AutoCommand *TankDrive::PurePursuitCmd(std::vector path, directionType dir, double radius, double max_speed) +AutoCommand *TankDrive::PurePursuitCmd(PurePursuit::Path path, directionType dir, double max_speed, double end_speed) { - return new PurePursuitCommand(*this, *drive_default_feedback, path, dir, radius, max_speed); + return new PurePursuitCommand(*this, *drive_default_feedback, path, dir, max_speed, end_speed); } -AutoCommand *TankDrive::PurePursuitCmd(Feedback &feedback, std::vector path, directionType dir, double radius, double max_speed) +AutoCommand *TankDrive::PurePursuitCmd(Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed, double end_speed) { - return new PurePursuitCommand(*this, feedback, path, dir, radius, max_speed); + return new PurePursuitCommand(*this, feedback, path, dir, max_speed, end_speed); } /** @@ -115,8 +115,9 @@ void TankDrive::drive_arcade(double forward_back, double left_right, int power) * @param dir the direction we want to travel forward and backward * @param feedback the custom feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by its completion */ -bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed) +bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed, double end_speed) { static pose_t pos_setpt; @@ -135,10 +136,15 @@ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedba // forwards is positive Y axis, backwards is negative if (dir == directionType::rev) + { + printf("going backwards\n"); inches = -fabs(inches); + } else + { + printf("going forwards\n"); inches = fabs(inches); - + } // Use vector math to get an X and Y Vector2D cur_pos_vec({.x = cur_pos.x, .y = cur_pos.y}); Vector2D delta_pos_vec(deg2rad(cur_pos.rot), inches); @@ -149,7 +155,7 @@ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedba } // Call the drive_to_point with updated point values - return drive_to_point(pos_setpt.x, pos_setpt.y, dir, feedback, max_speed); + return drive_to_point(pos_setpt.x, pos_setpt.y, dir, feedback, max_speed, end_speed); } /** * Autonomously drive the robot forward a certain distance @@ -158,12 +164,13 @@ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedba * @param inches degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw * @param dir the direction we want to travel forward and backward * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return true if we have finished driving to our point */ -bool TankDrive::drive_forward(double inches, directionType dir, double max_speed) +bool TankDrive::drive_forward(double inches, directionType dir, double max_speed, double end_speed) { if (drive_default_feedback != NULL) - return drive_forward(inches, dir, *drive_default_feedback, max_speed); + return drive_forward(inches, dir, *drive_default_feedback, max_speed, end_speed); printf("tank_drive.cpp: Cannot run drive_forward without a feedback controller!\n"); fflush(stdout); @@ -179,14 +186,15 @@ bool TankDrive::drive_forward(double inches, directionType dir, double max_speed * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return true if we have turned our target number of degrees */ -bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_speed) +bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_speed, double end_speed) { // We can't run the auto drive function without odometry if (odometry == NULL) { - fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); + fprintf(stderr, "Odometry is NULL. Unable to run turn_degrees()\n"); fflush(stderr); return true; } @@ -200,7 +208,7 @@ bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_spee target_heading = start_heading + degrees; } - return turn_to_heading(target_heading, feedback, max_speed); + return turn_to_heading(target_heading, feedback, max_speed, end_speed); } /** @@ -211,12 +219,13 @@ bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_spee * * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return true if we turned te target number of degrees */ -bool TankDrive::turn_degrees(double degrees, double max_speed) +bool TankDrive::turn_degrees(double degrees, double max_speed, double end_speed) { if (turn_default_feedback != NULL) - return turn_degrees(degrees, *turn_default_feedback, max_speed); + return turn_degrees(degrees, *turn_default_feedback, max_speed, end_speed); printf("tank_drive.cpp: Cannot run turn_degrees without a feedback controller!\n"); fflush(stdout); @@ -233,9 +242,10 @@ bool TankDrive::turn_degrees(double degrees, double max_speed) * @param dir the direction we want to travel forward and backward * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return true if we have reached our target point */ -bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed) +bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed, double end_speed) { // We can't run the auto drive function without odometry if (odometry == NULL) @@ -251,8 +261,8 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb double initial_dist = OdometryBase::pos_diff(odometry->get_position(), {.x = x, .y = y}); // Reset the control loops - correction_pid.init(0, 0); - feedback.init(-initial_dist, 0); + correction_pid.init(0, 0, 0, 0); + feedback.init(-initial_dist, 0, odometry->get_speed(), fabs(end_speed)); correction_pid.set_limits(-1, 1); feedback.set_limits(-1, 1); @@ -265,10 +275,11 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb pose_t end_pos = {.x = x, .y = y}; // Create a point (and vector) to get the direction - point_t pos_diff_pt = - { - .x = x - current_pos.x, - .y = y - current_pos.y}; + point_t pos_diff_pt = + { + .x = x - current_pos.x, + .y = y - current_pos.y + }; Vector2D point_vec(pos_diff_pt); @@ -342,9 +353,10 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb // Check if the robot has reached it's destination if (feedback.is_on_target()) { - stop(); + if (end_speed == 0) stop(); func_initialized = false; - stop(); + printf("Func unitililized\n"); + if (end_speed == 0) stop(); return true; } @@ -361,12 +373,13 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb * @param y the y position of the target * @param dir the direction we want to travel forward and backward * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return true if we have reached our target point */ -bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, double max_speed) +bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, double max_speed, double end_speed) { if (drive_default_feedback != NULL) - return this->drive_to_point(x, y, dir, *drive_default_feedback, max_speed); + return this->drive_to_point(x, y, dir, *drive_default_feedback, max_speed, end_speed); printf("tank_drive.cpp: Cannot run drive_to_point without a feedback controller!\n"); fflush(stdout); @@ -380,9 +393,10 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, doubl * @param heading_deg the heading to which we will turn * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return true if we have reached our target heading */ -bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double max_speed) +bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double max_speed, double end_speed) { // We can't run the auto drive function without odometry if (odometry == NULL) @@ -395,7 +409,7 @@ bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double m if (!func_initialized) { double initial_delta = OdometryBase::smallest_angle(odometry->get_position().rot, heading_deg); - feedback.init(-initial_delta, 0); + feedback.init(-initial_delta, 0, odometry->get_angular_speed_deg(), end_speed); feedback.set_limits(-fabs(max_speed), fabs(max_speed)); func_initialized = true; @@ -425,12 +439,13 @@ bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double m * * @param heading_deg the heading to which we will turn * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return true if we have reached our target heading */ -bool TankDrive::turn_to_heading(double heading_deg, double max_speed) +bool TankDrive::turn_to_heading(double heading_deg, double max_speed, double end_speed) { if (turn_default_feedback != NULL) - return turn_to_heading(heading_deg, *turn_default_feedback, max_speed); + return turn_to_heading(heading_deg, *turn_default_feedback, max_speed, end_speed); printf("tank_drive.cpp: Cannot run turn_to_heading without a feedback controller!\n"); fflush(stdout); @@ -450,59 +465,63 @@ double TankDrive::modify_inputs(double input, int power) } /** - * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of + * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of * waypoints - the robot will attempt to follow the points while cutting corners (radius) * to save time (compared to stop / turn / start) - * + * * @param path The list of coordinates to follow, in order * @param dir Run the bot forwards or backwards - * @param radius How big the corner cutting should be - small values follow the path more closely * @param feedback The feedback controller determining speed * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) * @return True when the path is complete -*/ -bool TankDrive::pure_pursuit(std::vector path, directionType dir, double radius, Feedback &feedback, double max_speed) + */ +bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback &feedback, double max_speed, double end_speed) { + std::vector points = path.get_points(); + if (!path.is_valid()) { + printf("WARNING: Unexpected pure pursuit path - some segments intersect or are too close\n"); + } pose_t robot_pose = odometry->get_position(); // On function initialization, send the path-length estimate to the feedback controller - if(!func_initialized) + if (!func_initialized) { - if(dir != directionType::rev) - feedback.init(-estimate_path_length(path), 0); + if (dir != directionType::rev) + feedback.init(-estimate_path_length(points), 0, odometry->get_speed(), end_speed); else - feedback.init(estimate_path_length(path), 0); - + feedback.init(estimate_path_length(points), 0, odometry->get_speed(), end_speed); + func_initialized = true; } - - point_t lookahead = PurePursuit::get_lookahead(path, odometry->get_position(), radius); + + point_t lookahead = PurePursuit::get_lookahead(points, odometry->get_position(), path.get_radius()); point_t localized = lookahead - robot_pose.get_point(); - point_t last_point = path[path.size()-1]; + point_t last_point = points[points.size() - 1]; bool is_last_point = (lookahead == last_point); - + double correction = 0; - double dist_remaining = PurePursuit::estimate_remaining_dist(path, robot_pose, radius); + double dist_remaining = PurePursuit::estimate_remaining_dist(points, robot_pose, path.get_radius()); double angle_diff = 0; - + // Robot is facing forwards / backwards, change the bot's angle by 180 - if(dir != directionType::rev) + if (dir != directionType::rev) angle_diff = OdometryBase::smallest_angle(robot_pose.rot, rad2deg(atan2(localized.y, localized.x))); else angle_diff = OdometryBase::smallest_angle(robot_pose.rot + 180, rad2deg(atan2(localized.y, localized.x))); - // Correct the robot's heading until the last cut-off - if(!(is_last_point && robot_pose.get_point().dist(last_point) < config.drive_correction_cutoff)) + // Correct the robot's heading until the last cut-off + if (!(is_last_point && robot_pose.get_point().dist(last_point) < config.drive_correction_cutoff)) { correction_pid.update(angle_diff); correction = correction_pid.get(); - } else // Inside cut-off radius, ignore horizontal diffs + } + else // Inside cut-off radius, ignore horizontal diffs { dist_remaining *= cos(angle_diff * (PI / 180.0)); } - if(dir != directionType::rev) + if (dir != directionType::rev) feedback.update(-dist_remaining); else feedback.update(dist_remaining); @@ -514,11 +533,11 @@ bool TankDrive::pure_pursuit(std::vector path, directionType dir, doubl left += correction; right -= correction; - + drive_tank(left, right); // When the robot has reached the end point and feedback reports on target, end pure pursuit - if(is_last_point && feedback.is_on_target()) + if (is_last_point && feedback.is_on_target()) { func_initialized = false; stop(); @@ -528,19 +547,18 @@ bool TankDrive::pure_pursuit(std::vector path, directionType dir, doubl } /** - * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of + * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of * waypoints - the robot will attempt to follow the points while cutting corners (radius) * to save time (compared to stop / turn / start) - * + * * Use the default drive feedback - * + * * @param path The list of coordinates to follow, in order * @param dir Run the bot forwards or backwards - * @param radius How big the corner cutting should be - small values follow the path more closely * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) * @return True when the path is complete -*/ -bool TankDrive::pure_pursuit(std::vector path, directionType dir, double radius, double max_speed) + */ +bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, double max_speed, double end_speed) { - return pure_pursuit(path, dir, radius, *config.drive_feedback, max_speed); + return pure_pursuit(path, dir, *config.drive_feedback, max_speed, end_speed); } \ No newline at end of file diff --git a/src/utils/auto_chooser.cpp b/src/utils/auto_chooser.cpp index 4edd072..9ef9b87 100644 --- a/src/utils/auto_chooser.cpp +++ b/src/utils/auto_chooser.cpp @@ -1,88 +1,72 @@ #include "../core/include/utils/auto_chooser.h" /** - * Initialize the auto-chooser. This class places a choice menu on the brain screen, - * so the driver can choose which autonomous to run. - * @param brain the brain on which to draw the selection boxes - */ -AutoChooser::AutoChooser(vex::brain &brain) : brain(brain) + * Initialize the auto-chooser. This class places a choice menu on the brain screen, + * so the driver can choose which autonomous to run. + * @param brain the brain on which to draw the selection boxes + */ +AutoChooser::AutoChooser(std::vector paths, size_t def) : choice(def) { - brain.Screen.pressed([](void *ptr){ - AutoChooser &a = *(AutoChooser*)ptr; - int x = a.brain.Screen.xPosition(); - int y = a.brain.Screen.yPosition(); + const static int per_line = 3; + const static int num_lines = 2; + const static int x_padding = 20; + const static int y_padding = 20; - entry_t *selected = NULL; - - // Check if the touchscreen press is inside each rectangle - for(int i = 0; i < a.list.size(); i++) + const int entry_height = ((height - (y_padding * (num_lines - 1))) / num_lines); + const int entry_width = ((width - (x_padding * (per_line - 1))) / per_line); + + list = std::vector(paths.size()); + int x = 50; + int y = 10; + for (size_t i = 0; i < list.size(); i++) + { + Rect r = Rect::from_min_and_size({(double)x, (double)y}, {entry_width, entry_height}); + list[i] = entry_t{r, paths[i]}; + x += entry_width + x_padding; + if ((i + 1) % per_line == 0) { - int rect_x = a.list[i].x, rect_y = a.list[i].y; - int rect_w = a.list[i].width, rect_h = a.list[i].height; - if (x > rect_x && x < rect_x + rect_w) - if (y > rect_y && y < rect_y + rect_h) - selected = &a.list[i]; + y += entry_height + y_padding; + x = 50; } - - // Re-render all the choices on each press. - a.render(selected); - - if(selected == NULL) - a.choice = ""; - else - a.choice = selected->name; - - }, this); + } } - -#define PADDING 10 -#define WIDTH 150 -#define HEIGHT 40 - -/** - * Place all the autonomous choices on the screen. - * If one is selected, change it's color - * @param selected the choice that is currently selected - */ -void AutoChooser::render(entry_t *selected) +void AutoChooser::update(bool was_pressed, int x, int y) { - for(int i = 0; i < list.size(); i++) + size_t i = 0; + for (const entry_t &e : list) { - brain.Screen.setPenColor(vex::color::black); - - if(selected != NULL && selected == &list[i]) - brain.Screen.setFillColor(vex::color::white); - else - brain.Screen.setFillColor(vex::color::orange); - - brain.Screen.drawRectangle(list[i].x, list[i].y, list[i].width, list[i].height); - brain.Screen.printAt(list[i].x + PADDING, list[i].y + list[i].height - PADDING, list[i].name.c_str()); + if (was_pressed && e.rect.contains({(double)x, (double)y})) + { + choice = i; + } + i++; } } -/** - * Add a new autonomous option. There are 3 options per row. - */ -void AutoChooser::add(std::string name) +void AutoChooser::draw(vex::brain::lcd &scr, [[maybe_unused]] bool first_draw, [[maybe_unused]] unsigned int frame_number) { - int x = (PADDING * ((list.size() % 3) + 1)) + ((list.size() % 3) * WIDTH); - int y = (PADDING * ((list.size() / 3) + 1)) + ((list.size() / 3) * HEIGHT); - entry_t entry = { - .x=x, - .y=y, - .width=WIDTH, - .height=HEIGHT, - .name=name - }; + scr.setFont(vex::fontType::mono20); + + for (size_t i = 0; i < list.size(); i++) + { + entry_t e = list[i]; + scr.setFillColor(vex::blue); - list.push_back(entry); - render(NULL); + if (choice == i) + { + scr.setFillColor(vex::green); + } + scr.drawRectangle(e.rect.min.x, e.rect.min.y, e.rect.width(), e.rect.height()); + + int width = scr.getStringWidth(e.name.c_str()); + scr.printAt(e.rect.center().x - width / 2, e.rect.center().y - 10, e.name.c_str()); + } } /** - * Return the selected autonomous - */ -std::string AutoChooser::get_choice() + * Return the selected autonomous + */ +size_t AutoChooser::get_choice() { return choice; } \ No newline at end of file diff --git a/src/utils/command_structure/auto_command.cpp b/src/utils/command_structure/auto_command.cpp index d9b0461..b1869c6 100644 --- a/src/utils/command_structure/auto_command.cpp +++ b/src/utils/command_structure/auto_command.cpp @@ -1,5 +1,47 @@ #include "../core/include/utils/command_structure/auto_command.h" +class OrCondition : public Condition +{ +public: + OrCondition(Condition *A, Condition *B) : A(A), B(B) {} + bool test() override + { + bool a = A->test(); + bool b = B->test(); + return a | b; + } + +private: + Condition *A; + Condition *B; +}; + +class AndCondition : public Condition +{ +public: + AndCondition(Condition *A, Condition *B) : A(A), B(B) {} + bool test() override + { + bool a = A->test(); + bool b = B->test(); + return a & b; + } + +private: + Condition *A; + Condition *B; +}; + +Condition *Condition::Or(Condition *b) +{ + return new OrCondition(this, b); +} + +Condition *Condition::And(Condition *b) +{ + return new AndCondition(this, b); +} + bool FunctionCondition::test() { return cond(); @@ -22,14 +64,17 @@ InOrder::InOrder(std::initializer_list cmds) : cmds(cmds) bool InOrder::run() { // outer loop finished - if (cmds.size() == 0) + if (cmds.size() == 0 && current_command == nullptr) { + printf("INORDER finished\n"); return true; } // retrieve and remove command at the front of the queue if (current_command == nullptr) { + printf("TAKING INORDER: len = %d\n", cmds.size()); current_command = cmds.front(); + printf("Current command: %p\n", (void *)current_command); cmds.pop(); tmr.reset(); } @@ -38,17 +83,23 @@ bool InOrder::run() bool cmd_finished = current_command->run(); if (cmd_finished) { + printf("InOrder Cmd finished\n"); current_command = nullptr; - return false; // continue omn next command + return false; // continue onto next command } double seconds = static_cast(tmr.time()) / 1000.0; bool should_timeout = current_command->timeout_seconds > 0.0; - bool command_timed_out = seconds > current_command->timeout_seconds; + bool doTimeout = should_timeout && seconds > current_command->timeout_seconds; + if (current_command->true_to_end != nullptr) + { + doTimeout = doTimeout || current_command->true_to_end->test(); + } + printf("."); // timeout - if (should_timeout && command_timed_out) + if (doTimeout) { current_command->on_timeout(); current_command = nullptr; @@ -84,9 +135,12 @@ static int parallel_runner(void *arg) } double t = (double)(tmr.time()) / 1000.0; bool timed_out = t > ri->cmd->timeout_seconds; - bool should_timeout = ri->cmd->timeout_seconds > 0; - - if (timed_out && should_timeout) + bool doTimeout = timed_out && (ri->cmd->timeout_seconds > 0); + if (ri->cmd->true_to_end != nullptr) + { + doTimeout = doTimeout || ri->cmd->true_to_end->test(); + } + if (doTimeout) { ri->cmd->on_timeout(); } @@ -218,8 +272,12 @@ static int async_runner(void *arg) } double t = (double)(tmr.time()) / 1000.0; bool timed_out = t > cmd->timeout_seconds; - bool should_timeout = cmd->timeout_seconds > 0; - if (timed_out && should_timeout) + bool doTimeout = timed_out && cmd->timeout_seconds > 0; + if (cmd->true_to_end != nullptr) + { + doTimeout = doTimeout || cmd->true_to_end->test(); + } + if (doTimeout) { cmd->on_timeout(); break; @@ -237,3 +295,39 @@ bool Async::run() // lmao get memory leaked return true; } + +RepeatUntil::RepeatUntil(InOrder cmds, size_t times) : RepeatUntil(cmds, new TimesTestedCondition(times)) +{ + timeout_seconds = -1.0; +} + +RepeatUntil::RepeatUntil(InOrder cmds, Condition *cond) : cmds(cmds), working_cmds(new InOrder(cmds)), cond(cond) +{ + timeout_seconds = -1.0; +} + +bool RepeatUntil::run() +{ + bool finished = working_cmds->run(); + if (!finished) + { + // return if we're not done yet + return false; + } + // this run finished + + bool res = cond->test(); + // we should finish + if (res) + { + return true; + } + working_cmds = new InOrder(cmds); + + return false; +} + +void RepeatUntil::on_timeout() +{ + working_cmds->on_timeout(); +} \ No newline at end of file diff --git a/src/utils/command_structure/basic_command.cpp b/src/utils/command_structure/basic_command.cpp new file mode 100644 index 0000000..a45b85f --- /dev/null +++ b/src/utils/command_structure/basic_command.cpp @@ -0,0 +1,89 @@ +/** + * @file basic_commands.cpp + * @author Ethan Kishimori GITHUB(LilacEthan) + * + * @brief Basic Commands for Motors and Solenoids able to throw into the Command Controller + * Commands Included + * - BasicSpinCommand + * - BasicStopCommand + * - BasicSolenoidSet + * + * @version 0.1 + * + */ +#include "../core/include/utils/command_structure/basic_command.h" + +// Basic Motor Commands-------------------------------------- +/** + * @brief a BasicMotorSpin Command + * + * @param motor Motor port to spin + * @param dir Direction for spining + * @param setting Power setting in volts,percentage,velocity + * @param power Value of desired power + */ +BasicSpinCommand::BasicSpinCommand(vex::motor &motor, vex::directionType dir, BasicSpinCommand::type setting, double power) : motor(motor), setting(setting), dir(dir), power(power) {} + +/** + * @brief Run the BasicSpinCommand + * Overrides run from Auto Command + * + * @return True Command runs once + */ +bool BasicSpinCommand::run() +{ + switch (setting) + { // Switch Statement taking the setting Enum + case voltage: // Voltage Setting + motor.spin(dir, power, vex::volt); + break; + case percent: // Percentage Setting + motor.spin(dir, power, vex::percent); + break; + case veocity: // Velocity Setting + motor.spin(dir, power, vex::velocityUnits::rpm); + break; + } + return true; // Always return True to send next on CommandController +} + +/** + * @brief Construct a BasicMotorStop Command + * + * @param motor Motor to stop + * @param setting Braketype setting brake,coast,hold + */ +BasicStopCommand::BasicStopCommand(vex::motor &motor, vex::brakeType setting) : motor(motor), setting(setting) {} + +/** + * @brief Runs the BasicMotorStop command + * Ovverides run command from AutoCommand + * + * @return True Command runs once + */ +bool BasicStopCommand::run() +{ + motor.stop(setting); + return true; +} + +// Basic Solenoid Commands----------------------------------- +/** + * @brief Construct a new BasicSolenoidSet Command + * + * @param solenoid Solenoid being set + * @param setting Setting of the solenoid in boolean (true,false) + */ +BasicSolenoidSet::BasicSolenoidSet(vex::pneumatics &solenoid, bool setting) : solenoid(solenoid), setting(setting) {} + +/** + * @brief Runs the BasicSolenoidSet + * Overrides run command from AutoCommand + * + * @return True Command runs once + */ +bool BasicSolenoidSet::run() +{ + solenoid.set(setting); + return true; +} \ No newline at end of file diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index 37bfa84..79eb29c 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -62,8 +62,8 @@ void CommandController::add_delay(int ms) command_queue.push(delay); } - -void CommandController::add_cancel_func(std::function true_if_cancel){ +void CommandController::add_cancel_func(std::function true_if_cancel) +{ should_cancel = true_if_cancel; } @@ -80,19 +80,23 @@ void CommandController::run() vex::timer tmr; tmr.reset(); - while (!command_queue.empty() ) + while (!command_queue.empty()) { // retrieve and remove command at the front of the queue next_cmd = command_queue.front(); command_queue.pop(); command_timed_out = false; - printf("Beginning Command %d : timeout = %.2f : at time = %.1f seconds\n", command_count, next_cmd->timeout_seconds, tmr.time(vex::seconds)); - fflush(stdout); + // printf("Beginning Command %d : timeout = %.2f : at time = %.1f seconds\n", command_count, next_cmd->timeout_seconds, tmr.time(vex::seconds)); + // fflush(stdout); vex::timer timeout_timer; timeout_timer.reset(); bool doTimeout = next_cmd->timeout_seconds > 0.0; + if (next_cmd->true_to_end != nullptr) + { + doTimeout = doTimeout || next_cmd->true_to_end->test(); + } // run the current command until it returns true or we timeout while (!next_cmd->run()) @@ -113,7 +117,8 @@ void CommandController::run() break; } } - if (should_cancel()){ + if (should_cancel()) + { break; } diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index 633fa4f..4984cf6 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -29,8 +29,8 @@ * @param dir the direction to drive * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at */ -DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed): - drive_sys(drive_sys), feedback(feedback), inches(inches), dir(dir), max_speed(max_speed) {} +DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed, double end_speed): + drive_sys(drive_sys), feedback(feedback), inches(inches), dir(dir), max_speed(max_speed), end_speed(end_speed) {} /** * Run drive_forward @@ -38,15 +38,15 @@ DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, Feedback &feedbac * @returns true when execution is complete, false otherwise */ bool DriveForwardCommand::run() { - return drive_sys.drive_forward(inches, dir, feedback, max_speed); + return drive_sys.drive_forward(inches, dir, feedback, max_speed, end_speed); } /** * reset the drive system if we timeout */ void DriveForwardCommand::on_timeout(){ - drive_sys.reset_auto(); drive_sys.stop(); + drive_sys.reset_auto(); } @@ -57,8 +57,8 @@ void DriveForwardCommand::on_timeout(){ * @param degrees how many degrees to rotate * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at */ -TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed): - drive_sys(drive_sys), feedback(feedback), degrees(degrees), max_speed(max_speed){} +TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed, double end_speed): + drive_sys(drive_sys), feedback(feedback), degrees(degrees), max_speed(max_speed), end_speed(end_speed) {} /** * Run turn_degrees @@ -66,14 +66,14 @@ TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, * @returns true when execution is complete, false otherwise */ bool TurnDegreesCommand::run() { - return drive_sys.turn_degrees(degrees, max_speed); + return drive_sys.turn_degrees(degrees, max_speed, end_speed); } /** * reset the drive system if we timeout */ void TurnDegreesCommand::on_timeout(){ - drive_sys.reset_auto(); drive_sys.stop(); + drive_sys.reset_auto(); } @@ -86,8 +86,8 @@ void TurnDegreesCommand::on_timeout(){ * @param dir the direction to drive * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at */ -DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed): - drive_sys(drive_sys), feedback(feedback), x(x), y(y), dir(dir), max_speed(max_speed) {} +DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed, double end_speed): + drive_sys(drive_sys), feedback(feedback), x(x), y(y), dir(dir), max_speed(max_speed), end_speed(end_speed) {} /** * Construct a DriveForward Command @@ -97,8 +97,8 @@ DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedbac * @param dir the direction to drive * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at */ -DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, point_t point, directionType dir, double max_speed): - drive_sys(drive_sys), feedback(feedback), x(point.x), y(point.y), dir(dir), max_speed(max_speed) {} +DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, point_t point, directionType dir, double max_speed, double end_speed): + drive_sys(drive_sys), feedback(feedback), x(point.x), y(point.y), dir(dir), max_speed(max_speed), end_speed(end_speed) {} /** * Run drive_to_point @@ -106,14 +106,14 @@ DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedbac * @returns true when execution is complete, false otherwise */ bool DriveToPointCommand::run() { - return drive_sys.drive_to_point(x, y, dir, feedback, max_speed); + return drive_sys.drive_to_point(x, y, dir, feedback, max_speed, end_speed); } /** * reset the drive system if we don't hit our target */ void DriveToPointCommand::on_timeout(){ - drive_sys.reset_auto(); drive_sys.stop(); + drive_sys.reset_auto(); } @@ -124,8 +124,8 @@ void DriveToPointCommand::on_timeout(){ * @param heading_deg the heading to turn to in degrees * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at */ -TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double max_speed): - drive_sys(drive_sys), feedback(feedback), heading_deg(heading_deg), max_speed(max_speed) {} +TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double max_speed, double end_speed): + drive_sys(drive_sys), feedback(feedback), heading_deg(heading_deg), max_speed(max_speed), end_speed(end_speed) {} /** * Run turn_to_heading @@ -133,14 +133,14 @@ TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedb * @returns true when execution is complete, false otherwise */ bool TurnToHeadingCommand::run() { - return drive_sys.turn_to_heading(heading_deg, feedback, max_speed); + return drive_sys.turn_to_heading(heading_deg, feedback, max_speed, end_speed); } /** * reset the drive system if we don't hit our target */ void TurnToHeadingCommand::on_timeout(){ - drive_sys.reset_auto(); drive_sys.stop(); + drive_sys.reset_auto(); } /** @@ -148,12 +148,11 @@ void TurnToHeadingCommand::on_timeout(){ * * @param path The list of coordinates to follow, in order * @param dir Run the bot forwards or backwards - * @param radius How big the corner cutting should be - small values follow the path more closely * @param feedback The feedback controller determining speed * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) */ -PurePursuitCommand::PurePursuitCommand(TankDrive &drive_sys, Feedback &feedback, std::vector path, directionType dir, double radius, double max_speed) -: drive_sys(drive_sys), path(path), dir(dir), radius(radius), feedback(feedback), max_speed(max_speed) +PurePursuitCommand::PurePursuitCommand(TankDrive &drive_sys, Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed, double end_speed) +: drive_sys(drive_sys), path(path), dir(dir), feedback(feedback), max_speed(max_speed), end_speed(end_speed) {} /** @@ -161,7 +160,7 @@ PurePursuitCommand::PurePursuitCommand(TankDrive &drive_sys, Feedback &feedback, */ bool PurePursuitCommand::run() { - return drive_sys.pure_pursuit(path, dir, radius, feedback, max_speed); + return drive_sys.pure_pursuit(path, dir, feedback, max_speed, end_speed); } /** @@ -169,8 +168,8 @@ bool PurePursuitCommand::run() */ void PurePursuitCommand::on_timeout() { - drive_sys.reset_auto(); drive_sys.stop(); + drive_sys.reset_auto(); } /** diff --git a/src/utils/command_structure/flywheel_commands.cpp b/src/utils/command_structure/flywheel_commands.cpp index a4aa4d0..bddda27 100644 --- a/src/utils/command_structure/flywheel_commands.cpp +++ b/src/utils/command_structure/flywheel_commands.cpp @@ -11,7 +11,7 @@ SpinRPMCommand::SpinRPMCommand(Flywheel &flywheel, int rpm): flywheel(flywheel), rpm(rpm) {} bool SpinRPMCommand::run() { - flywheel.spinRPM(rpm); + flywheel.spin_rpm(rpm); return true; } @@ -20,7 +20,7 @@ WaitUntilUpToSpeedCommand::WaitUntilUpToSpeedCommand(Flywheel &flywheel, int thr bool WaitUntilUpToSpeedCommand::run() { // If we're withing the specified threshold, we're ready to fire - if (fabs(flywheel.getDesiredRPM() - flywheel.getRPM()) < threshold_rpm){ + if (fabs(flywheel.get_target() - flywheel.getRPM()) < threshold_rpm){ return true; } // else, keep waiting @@ -42,7 +42,7 @@ FlywheelStopMotorsCommand::FlywheelStopMotorsCommand(Flywheel &flywheel): flywheel(flywheel) {} bool FlywheelStopMotorsCommand::run() { - flywheel.stopMotors(); + flywheel.stop(); return true; } @@ -51,6 +51,6 @@ FlywheelStopNonTasksCommand::FlywheelStopNonTasksCommand(Flywheel &flywheel): flywheel(flywheel) {} bool FlywheelStopNonTasksCommand::run() { - flywheel.stopNonTasks(); + flywheel.stop(); return true; } diff --git a/src/utils/controls/bang_bang.cpp b/src/utils/controls/bang_bang.cpp new file mode 100644 index 0000000..161a951 --- /dev/null +++ b/src/utils/controls/bang_bang.cpp @@ -0,0 +1,43 @@ +#include "../core/include/utils/controls/bang_bang.h" +#include + +BangBang::BangBang(double threshhold, double low, double high) : setpt(low), sensor_val(low), lower_bound(low), upper_bound(high), threshhold(threshhold) {} + +void BangBang::init(double start_pt, double set_pt, double, double) +{ + sensor_val = start_pt; + setpt = set_pt; +} + +void BangBang::set_limits(double lower, double upper) +{ + lower_bound = lower; + upper_bound = upper; +} +double BangBang::get() +{ + return last_output; +} + +double BangBang::update(double val) +{ + sensor_val = val; + if (fabs(val - setpt) < threshhold) + { + last_output = 0; + } + else if (val > setpt) + { + last_output = lower_bound; + } + else + { + last_output = upper_bound; + } + return upper_bound; +} + +bool BangBang::is_on_target() +{ + return fabs(sensor_val - setpt) < threshhold; +} \ No newline at end of file diff --git a/src/utils/feedforward.cpp b/src/utils/controls/feedforward.cpp similarity index 95% rename from src/utils/feedforward.cpp rename to src/utils/controls/feedforward.cpp index 1b4ff99..ef0d242 100644 --- a/src/utils/feedforward.cpp +++ b/src/utils/controls/feedforward.cpp @@ -1,4 +1,4 @@ -#include "../core/include/utils/feedforward.h" +#include "../core/include/utils/controls/feedforward.h" /** @@ -49,8 +49,8 @@ FeedForward::ff_config_t tune_feedforward(vex::motor_group &motor, double pct, d vel_ma.add_entry(motor.velocity(vex::velocityUnits::rpm)); accel_ma.add_entry(motor.velocity(vex::velocityUnits::rpm)/dt); - double speed = vel_ma.get_average(); - double accel = accel_ma.get_average(); + double speed = vel_ma.get_value(); + double accel = accel_ma.get_value(); // For kV: if(speed > max_speed) diff --git a/src/utils/motion_controller.cpp b/src/utils/controls/motion_controller.cpp similarity index 90% rename from src/utils/motion_controller.cpp rename to src/utils/controls/motion_controller.cpp index a68770a..8253f35 100644 --- a/src/utils/motion_controller.cpp +++ b/src/utils/controls/motion_controller.cpp @@ -1,4 +1,4 @@ -#include "../core/include/utils/motion_controller.h" +#include "../core/include/utils/controls/motion_controller.h" #include "../core/include/utils/math_util.h" #include @@ -20,12 +20,17 @@ MotionController::MotionController(m_profile_cfg_t &config) * This will also reset the PID and profile timers. * @param start_pt Movement starting position * @param end_pt Movement ending posiiton + * @param start_vel Movement starting velocity + * @param end_vel Movement ending velocity */ -void MotionController::init(double start_pt, double end_pt) +void MotionController::init(double start_pt, double end_pt, double start_vel, double end_vel) { profile.set_endpts(start_pt, end_pt); + profile.set_vel_endpts(start_vel, end_vel); pid.reset(); tmr.reset(); + + this->end_pt = end_pt; } /** @@ -36,10 +41,12 @@ void MotionController::init(double start_pt, double end_pt) */ double MotionController::update(double sensor_val) { - cur_motion = profile.calculate(tmr.time(timeUnits::sec)); + cur_motion = profile.calculate(tmr.time(timeUnits::sec), sensor_val); pid.set_target(cur_motion.pos); pid.update(sensor_val); + this->current_pos = sensor_val; + out = pid.get() + ff.calculate(cur_motion.vel, cur_motion.accel, pid.get()); if(lower_limit != upper_limit) @@ -74,7 +81,7 @@ void MotionController::set_limits(double lower, double upper) */ bool MotionController::is_on_target() { - return (tmr.time(timeUnits::sec) > profile.get_movement_time()) && pid.is_on_target(); + return (tmr.time(timeUnits::sec) > profile.get_movement_time()) && pid.is_on_target() && fabs(end_pt - current_pos) < pid.config.deadband; } /** @@ -142,8 +149,8 @@ FeedForward::ff_config_t MotionController::tune_feedforward(TankDrive &drive, Od vel_ma.add_entry(odometry.get_speed()); accel_ma.add_entry(odometry.get_accel()); - double speed = vel_ma.get_average(); - double accel = accel_ma.get_average(); + double speed = vel_ma.get_value(); + double accel = accel_ma.get_value(); // For kV: if(speed > max_speed) diff --git a/src/utils/pid.cpp b/src/utils/controls/pid.cpp similarity index 83% rename from src/utils/pid.cpp rename to src/utils/controls/pid.cpp index ae35cd5..21a7475 100644 --- a/src/utils/pid.cpp +++ b/src/utils/controls/pid.cpp @@ -1,4 +1,4 @@ -#include "../core/include/utils/pid.h" +#include "../core/include/utils/controls/pid.h" #include "../core/include/subsystems/odometry/odometry_base.h" /** @@ -10,9 +10,11 @@ PID::PID(pid_config_t &config) pid_timer.reset(); } -void PID::init(double start_pt, double set_pt) +void PID::init(double start_pt, double set_pt, double, double end_vel) { set_target(set_pt); + target_vel = end_vel; + sensor_val = start_pt; reset(); } @@ -31,12 +33,11 @@ double PID::update(double sensor_val) // Avoid a divide by zero error double d_term = 0; - if(time_delta != 0) + if (time_delta != 0) d_term = config.d * (get_error() - last_error) / time_delta; - else if(last_time != 0) + else if (last_time != 0) printf("(pid.cpp): Warning - running PID without a delay is just a P loop!\n"); - // P and D terms out = (config.p * get_error()) + d_term; @@ -44,9 +45,9 @@ double PID::update(double sensor_val) // Only add to the accumulated error if the output is not saturated // aka "Integral Clamping" anti-windup technique - if ( !limits_exist || (limits_exist && (out < upper_limit && out > lower_limit)) ) + if (!limits_exist || (limits_exist && (out < upper_limit && out > lower_limit))) accum_error += time_delta * get_error(); - + // I term out += config.i * accum_error; @@ -55,11 +56,17 @@ double PID::update(double sensor_val) // Enable clamping if the limit is not 0 if (limits_exist) - out = (out < lower_limit) ? lower_limit : (out > upper_limit) ? upper_limit : out; + out = (out < lower_limit) ? lower_limit : (out > upper_limit) ? upper_limit + : out; return out; } +double PID::get_sensor_val() +{ + return sensor_val; +} + /** * Reset the PID loop by resetting time since 0 and accumulated error. */ @@ -88,7 +95,8 @@ double PID::get() */ double PID::get_error() { - if (config.error_method==ERROR_TYPE::ANGULAR){ + if (config.error_method == ERROR_TYPE::ANGULAR) + { return OdometryBase::smallest_angle(target, sensor_val); } return target - sensor_val; @@ -108,7 +116,7 @@ void PID::set_target(double target) } /** - * Set the limits on the PID out. The PID out will "clip" itself to be + * Set the limits on the PID out. The PID out will "clip" itself to be * between the limits. */ void PID::set_limits(double lower, double upper) @@ -125,6 +133,7 @@ bool PID::is_on_target() { if (fabs(get_error()) < config.deadband) { + if (target_vel != 0) return true; if (is_checking_on_target == false) { on_target_last_time = pid_timer.value(); @@ -142,7 +151,3 @@ bool PID::is_on_target() return false; } - -Feedback::FeedbackType PID::get_type(){ - return Feedback::FeedbackType::PIDType; -} \ No newline at end of file diff --git a/src/utils/pidff.cpp b/src/utils/controls/pidff.cpp similarity index 91% rename from src/utils/pidff.cpp rename to src/utils/controls/pidff.cpp index 616caec..64439fe 100644 --- a/src/utils/pidff.cpp +++ b/src/utils/controls/pidff.cpp @@ -1,4 +1,4 @@ -#include "../core/include/utils/pidff.h" +#include "../core/include/utils/controls/pidff.h" #include "../core/include/utils/math_util.h" PIDFF::PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg): pid(pid_cfg), ff_cfg(ff_cfg),ff(ff_cfg) @@ -14,9 +14,9 @@ PIDFF::PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg): pid * @param start_pt the current sensor value * @param set_pt where the sensor value should be */ -void PIDFF::init(double start_pt, double set_pt) +void PIDFF::init(double start_pt, double set_pt, double start_vel, double end_vel) { - pid.init(start_pt, set_pt); + pid.init(start_pt, set_pt, start_vel, end_vel); } void PIDFF::set_target(double set_pt) diff --git a/src/utils/controls/take_back_half.cpp b/src/utils/controls/take_back_half.cpp new file mode 100644 index 0000000..7defe78 --- /dev/null +++ b/src/utils/controls/take_back_half.cpp @@ -0,0 +1,120 @@ +#include "../core/include/utils/controls/take_back_half.h" +#include "../core/include/utils/math_util.h" + +TakeBackHalf::TakeBackHalf(double gain, double first_cross_split, double thresh) : TBH_gain(gain), first_cross_split(first_cross_split), on_target_threshhold(fabs(thresh)) +{ + tbh = 0.0; + output = 0.0; + prev_error = 0.0; + lower = 0.0; + upper = 0.0; + first_cross = true; +} + +void TakeBackHalf::init(double start_pt, double set_pt, double, double) +{ + if (set_pt == target) + { + // nothing to do + return; + } + first_cross = true; + tbh = output; + target = set_pt; + output = update(start_pt); +} + +double TakeBackHalf::update(double val) +{ + + if (target == 0.0) + { + printf("no target\n"); + return 0.0; + } + + double error = target - val; + output += TBH_gain * error; + + // taking back half crossed target + if (sign(error) != sign(prev_error)) + { + if (first_cross) + { + output = lerp(tbh, output, first_cross_split); + tbh = output; + first_cross = false; + printf("First cross\n"); + } + else + { + // output = .5 * (output + tbh); + output = lerp(tbh, output, .5); + tbh = output; + } + prev_error = error; + } + + if (lower != upper) + { + output = clamp(output, lower, upper); + } + return output; +} + +double TakeBackHalf::get() +{ + return output; +} + +void TakeBackHalf::set_limits(double low, double high) +{ + + lower = low; + upper = high; + printf("Set limits: %f, %f\n", lower, upper); +} + +bool TakeBackHalf::is_on_target() +{ + return fabs(prev_error) < on_target_threshhold; +} + +// Runs a Take Back Half variant to control RPM +// https://www.vexwiki.org/programming/controls_algorithms/tbh + +// int spinRPMTask_TBH(void *wheelPointer) +// { +// // Flywheel *wheel = (Flywheel *)wheelPointer; + +// double tbh = 0.0; +// double output = 0.0; +// double previous_error = 0.0; + +// while (true) +// { +// wheel->measure_RPM(); + +// // reset if set to 0, this keeps the tbh val from screwing us up when we start up again +// if (wheel->get_target() == 0) +// { +// output = 0; +// tbh = 0; +// } + +// double error = wheel->get_target() - wheel->getRPM(); +// output += wheel->getTBHGain() * error; +// wheel->spin_raw(clamp(output, 0, 1), fwd); + +// if (sign(error) != sign(previous_error)) +// { +// output = .5 * (output + tbh); +// tbh = output; +// previous_error = error; +// } + +// vexDelay(1); +// } + +// return 0; +// } \ No newline at end of file diff --git a/src/utils/graph_drawer.cpp b/src/utils/graph_drawer.cpp index 3386620..5621d99 100644 --- a/src/utils/graph_drawer.cpp +++ b/src/utils/graph_drawer.cpp @@ -1,31 +1,73 @@ #include "../core/include/utils/graph_drawer.h" -/** - * Construct a GraphDrawer - * @brief a helper class to graph values on the brain screen - * @param screen a reference to Brain.screen we can save for later - * @param num_samples the graph works on a fixed window and will plot the last `num_samples` before the history is forgotten. Larger values give more context but may slow down if you have many graphs or an exceptionally high - * @param x_label the name of the x axis (currently unused) - * @param y_label the name of the y axis (currently unused) - * @param draw_border whether to draw the border around the graph. can be turned off if there are multiple graphs in the same space ie. a graph of error and output - * @param lower_bound the bottom of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints - * @param upper_bound the top of the window to graph. if lower_bound == upperbound, the graph will scale to it's datapoints - */ -GraphDrawer::GraphDrawer(vex::brain::lcd &screen, int num_samples, std::string x_label, std::string y_label, vex::color col, bool draw_border, double lower_bound, double upper_bound) : Screen(screen), sample_index(0), xlabel(x_label), ylabel(y_label), col(col), border(draw_border), upper(upper_bound), lower(lower_bound) +/// @brief Creates a graph drawer with the specified number of series (each series is a separate line) +/// @param num_samples the number of samples to graph at a time (40 will graph the last 40 data points) +/// @param lower_bound the bottom of the window when displaying (if upper_bound = lower_bound, auto calculate bounds) +/// @param upper_bound the top of the window when displaying (if upper_bound = lower_bound, auto calculate bounds) +/// @param colors the colors of the series. must be of size num_series +/// @param num_series the number of series to graph +GraphDrawer::GraphDrawer(int num_samples, double lower_bound, double upper_bound, std::vector colors, size_t num_series) : cols(colors), auto_fit(lower_bound == upper_bound) { - std::vector temp(num_samples, point_t{.x = 0.0, .y = 0.0}); - samples = temp; + if (colors.size() != num_series) + { + printf("The number of colors does not match the number of series in graph drawer\n"); + } + series = std::vector>(num_series); + for (size_t i = 0; i < num_series; i++) + { + series[i] = std::vector(num_samples, {0.0, 0.0}); + } + + if (auto_fit) + { + upper = -1000.0; + lower = 1000.0; + } else { + upper = upper_bound; + lower = lower_bound; + } } /** - * add_sample adds a point to the graph, removing one from the back + * add_samples adds a point to the graph, removing one from the back * @param sample an x, y coordinate of the next point to graph */ -void GraphDrawer::add_sample(point_t sample) +void GraphDrawer::add_samples(std::vector new_samples) +{ + if (series.size() != new_samples.size()) + { + printf("Mismatch between # of samples given and number of series. %s : %d\n", __FILE__, __LINE__); + } + for (size_t i = 0; i < series.size(); i++) + { + series[i][sample_index] = new_samples[i]; + if (auto_fit) + { + upper = fmax(upper, new_samples[i].y); + lower = fmin(lower, new_samples[i].y); + } + } + sample_index++; + sample_index %= series[0].size(); +} + +void GraphDrawer::add_samples(std::vector new_samples) { - samples[sample_index] = sample; + if (series.size() != new_samples.size()) + { + printf("Mismatch between # of samples given and number of series. %s : %d\n", __FILE__, __LINE__); + } + for (size_t i = 0; i < series.size(); i++) + { + series[i][sample_index] = {(double)vex::timer::system(), new_samples[i]}; + if (auto_fit) + { + upper = fmax(upper, new_samples[i]); + lower = fmin(lower, new_samples[i]); + } + } sample_index++; - sample_index %= samples.size(); + sample_index %= series[0].size(); } /** @@ -35,74 +77,61 @@ void GraphDrawer::add_sample(point_t sample) * @param width the width of the graphed region * @param height the height of the graphed region */ -void GraphDrawer::draw(int x, int y, int width, int height) +void GraphDrawer::draw(vex::brain::lcd &screen, int x, int y, int width, int height) { - if (samples.size() < 1) + if (series[0].size() < 1) { return; } - - double current_min = samples[0].y; - double current_max = samples[0].y; - double earliest_time = samples[0].x; - double latest_time = samples[0].x; - // collect data - for (int i = 0; i < samples.size(); i++) + if (cols.size() != series.size()) { - point_t p = samples[i]; - if (p.x < earliest_time) - { - earliest_time = p.x; - } - else if (p.x > latest_time) - { - latest_time = p.x; - } + printf("The number of colors does not match the number of series in graph drawer\n"); + } - if (p.y < current_min) - { - current_min = p.y; - } - else if (p.y > current_max) - { - current_max = p.y; - } + size_t newest_index = (sample_index-1); + if (sample_index<0){ + sample_index+=series[0].size(); } + + double earliest_time = series[0][sample_index].x; + double latest_time = series[0][newest_index].x; + // collect data if (std::abs(latest_time - earliest_time) < 0.001) { - Screen.printAt(width / 2, height / 2, "Not enough Data"); + screen.printAt(width / 2, height / 2, "Not enough Data"); return; } - if (upper != lower) - { - current_min = lower; - current_max = upper; - } if (border) { - Screen.setPenWidth(1); - Screen.setPenColor(vex::white); - Screen.setFillColor(bgcol); - Screen.drawRectangle(x, y, width, height); + screen.setPenWidth(1); + screen.setPenColor(vex::white); + screen.setFillColor(bgcol); + screen.drawRectangle(x, y, width, height); } double time_range = latest_time - earliest_time; - double sample_range = current_max - current_min; - double x_s = (double)x; - double y_s = (double)y + (double)height; - Screen.setPenWidth(4); - Screen.setPenColor(col); - for (int i = sample_index; i < samples.size() + sample_index - 1; i++) + double sample_range = upper - lower; + screen.setPenWidth(2); + + for (int j = 0; j < series.size(); j++) { - point_t p = samples[i % samples.size()]; - double x_pos = x_s + ((p.x - earliest_time) / time_range) * (double)width; - double y_pos = y_s + ((p.y - current_min) / sample_range) * (double)(-height); + double x_s = (double)x; + double y_s = (double)y + (double)height; + const std::vector &samples = series[j]; - point_t p2 = samples[(i + 1) % samples.size()]; - double x_pos2 = x_s + ((p2.x - earliest_time) / time_range) * (double)width; - double y_pos2 = y_s + ((p2.y - current_min) / sample_range) * (double)(-height); + screen.setPenColor(cols[j]); + for (int i = sample_index; i < samples.size() + sample_index - 1; i++) + { + point_t p = samples[i % samples.size()]; + double x_pos = x_s + ((p.x - earliest_time) / time_range) * (double)width; + double y_pos = y_s + ((p.y - lower) / sample_range) * (double)(-height); - Screen.drawLine((int)x_pos, (int)y_pos, (int)x_pos2, (int)y_pos2); + point_t p2 = samples[(i + 1) % samples.size()]; + double x_pos2 = x_s + ((p2.x - earliest_time) / time_range) * (double)width; + double y_pos2 = y_s + ((p2.y - lower) / sample_range) * (double)(-height); + + screen.drawLine((int)x_pos, (int)y_pos, (int)x_pos2, (int)y_pos2); + } } } diff --git a/src/utils/math_util.cpp b/src/utils/math_util.cpp index 6d28630..58051ae 100644 --- a/src/utils/math_util.cpp +++ b/src/utils/math_util.cpp @@ -6,38 +6,49 @@ #endif /** -* Constrain the input between a minimum and a maximum value -* -* @param val the value to be restrained -* @param low the minimum value that will be returned -* @param high the maximum value that will be returned -**/ -double clamp(double val, double low, double high){ - if (val < low){ + * Constrain the input between a minimum and a maximum value + * + * @param val the value to be restrained + * @param low the minimum value that will be returned + * @param high the maximum value that will be returned + **/ +double clamp(double val, double low, double high) +{ + if (val < low) + { return low; - } else if (val > high){ + } + else if (val > high) + { return high; } return val; } + +double lerp(double a, double b, double t) +{ + return a * (1.0 - t) + b * t; +} + /** -* Returns the sign of a number -* @param x -* -* returns the sign +/-1 of x. special case at 0 it returns +1 -**/ -double sign(double x){ - if (x<0){ + * Returns the sign of a number + * @param x + * + * returns the sign +/-1 of x. special case at 0 it returns +1 + **/ +double sign(double x) +{ + if (x < 0) + { return -1; } return 1; } - double wrap_angle_deg(double input) { double angle = fmod(input, 360); - if(angle < 0) + if (angle < 0) angle += 360; return angle; @@ -45,9 +56,9 @@ double wrap_angle_deg(double input) double wrap_angle_rad(double input) { - double angle = fmod(input, 2*PI); - if(angle < 0) - angle += 2*PI; + double angle = fmod(input, 2 * PI); + if (angle < 0) + angle += 2 * PI; return angle; } @@ -55,27 +66,30 @@ double wrap_angle_rad(double input) Calculates the average of a vector of doubles @param values the list of values for which the average is taken */ -double mean(std::vector const &values){ - double total=0; - for (int i=0; i const &values) +{ + double total = 0; + for (int i = 0; i < values.size(); i++) + { + total += values[i]; + } + return total / (double)values.size(); } - /* Calculates the variance of a set of numbers (needed for linear regression) https://en.wikipedia.org/wiki/Variance @param values the values for which the covariance is taken @param mean the average of values */ -double variance(std::vector const &values, double mean) { - double total = 0.0; - for (int i=0; i const &values, double mean) +{ + double total = 0.0; + for (int i = 0; i < values.size(); i++) + { + total += (values[i] - mean) * (values[i] - mean); + } + return total; } /* @@ -87,53 +101,56 @@ Calculates the covariance of a set of points (needed for linear regression) @param meanx the mean value of all x coordinates in points @param meany the mean value of all y coordinates in points */ -double covariance(std::vector> const &points, double meanx, double meany){ - double covar = 0.0; - for (int i=0; i> const &points, double meanx, double meany) +{ + double covar = 0.0; + for (int i = 0; i < points.size(); i++) + { + covar += (points[i].first - meanx) * (points[i].second - meany); + } + return covar; } /* -* Calculates the slope and y intercept of the line of best fit for the data -* @param points the points for the data -* @return slope, y intercept. y = m(x)+b. std::pair -*/ -std::pair calculate_linear_regression(std::vector> const &points){ - //Purely for convenience and the ability to reuse mean() and variance() - can be easily rewritten to avoid allocating these if the code is repeatedly called - std::vector xs(points.size(), 0.0); - std::vector ys(points.size(), 0.0); - for (int i =0; i(slope, y_intercept); -} + * Calculates the slope and y intercept of the line of best fit for the data + * @param points the points for the data + * @return slope, y intercept. y = m(x)+b. std::pair + */ +std::pair calculate_linear_regression(std::vector> const &points) +{ + // Purely for convenience and the ability to reuse mean() and variance() - can be easily rewritten to avoid allocating these if the code is repeatedly called + std::vector xs(points.size(), 0.0); + std::vector ys(points.size(), 0.0); + for (int i = 0; i < points.size(); i++) + { + xs[i] = points[i].first; + ys[i] = points[i].second; + } + + double meanx = mean(xs); + double meany = mean(ys); + double slope = covariance(points, meanx, meany) / variance(xs, meanx); + double y_intercept = meany - slope * meanx; + + return std::pair(slope, y_intercept); +} double estimate_path_length(const std::vector &points) { double dist = 0; - for(point_t p : points) + for (point_t p : points) { static point_t last_p = p; // Ignore the first point - if(p == last_p) + if (p == last_p) continue; dist += p.dist(last_p); last_p = p; } - + return dist; } \ No newline at end of file diff --git a/src/utils/moving_average.cpp b/src/utils/moving_average.cpp index 08cf344..d5419e1 100644 --- a/src/utils/moving_average.cpp +++ b/src/utils/moving_average.cpp @@ -1,26 +1,29 @@ #include #include "../core/include/utils/moving_average.h" +#include + /* -* MovingAverage -* -* A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. -* This means that if you collect enough samples those that are too high are cancelled out by the samples that are too low leaving the real value. -* -* The MovingAverage class provides a simple interface to do this smoothing from our noisy sensor values. -* -* WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' behind the actual value that the sensor is reading. -* Using a MovingAverage is thus a tradeoff between accuracy and lag time (more samples) vs. less accuracy and faster updating (less samples). -* -*/ + * MovingAverage + * + * A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. + * This means that if you collect enough samples those that are too high are cancelled out by the samples that are too low leaving the real value. + * + * The MovingAverage class provides a simple interface to do this smoothing from our noisy sensor values. + * + * WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' behind the actual value that the sensor is reading. + * Using a MovingAverage is thus a tradeoff between accuracy and lag time (more samples) vs. less accuracy and faster updating (less samples). + * + */ /** * Create a moving average calculator with 0 as the default value * * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading */ -MovingAverage::MovingAverage(int buffer_size) { - buffer = std::vector(buffer_size, 0.0); - buffer_index = 0; +MovingAverage::MovingAverage(int buffer_size) +{ + buffer = std::vector(buffer_size, 0.0); + buffer_index = 0; current_avg = 0; } @@ -29,13 +32,71 @@ MovingAverage::MovingAverage(int buffer_size) { * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading * @param starting_value The value that the average will be before any data is added */ -MovingAverage::MovingAverage(int buffer_size, double starting_value) { - buffer = std::vector(buffer_size, starting_value); - buffer_index = 0; +MovingAverage::MovingAverage(int buffer_size, double starting_value) +{ + buffer = std::vector(buffer_size, starting_value); + buffer_index = 0; current_avg = starting_value; } +/** + * Add a reading to the buffer + * Before: + * [ 1 1 2 2 3 3] => 2 + * ^ + * After: + * [ 2 1 2 2 3 3] => 2.16 + * ^ + * @param n the sample that will be added to the moving average. + */ +void MovingAverage::add_entry(double n) +{ + current_avg -= buffer[buffer_index] / (double)get_size(); + current_avg += n / get_size(); + buffer[buffer_index] = n; + buffer_index++; + buffer_index %= get_size(); +} + +/** + * How many samples the average is made from + * @return the number of samples used to calculate this average + */ +double MovingAverage::get_value() const +{ + return current_avg; +} + +// How many samples the average is made from +int MovingAverage::get_size() const +{ + return buffer.size(); +} + +/** + * Create a moving average calculator with 0 as the default value + * + * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading + */ +ExponentialMovingAverage::ExponentialMovingAverage(int buffer_size) +{ + buffer = std::vector(buffer_size, 0.0); + buffer_index = 0; + current_avg = 0; +} + +/** + * Create a moving average calculator with a specified default value + * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading + * @param starting_value The value that the average will be before any data is added + */ +ExponentialMovingAverage::ExponentialMovingAverage(int buffer_size, double starting_value) +{ + buffer = std::vector(buffer_size, starting_value); + buffer_index = 0; + current_avg = starting_value; +} /** * Add a reading to the buffer @@ -44,27 +105,39 @@ MovingAverage::MovingAverage(int buffer_size, double starting_value) { * ^ * After: * [ 2 1 2 2 3 3] => 2.16 - * ^ + * ^ * @param n the sample that will be added to the moving average. */ -void MovingAverage::add_entry(double n){ - current_avg -= buffer[buffer_index]/(double)get_size(); - current_avg += n/get_size(); +void ExponentialMovingAverage::add_entry(double n) +{ + int oldest_index = buffer_index; + double oldest_sample = buffer[oldest_index]; + double oldest_weight = 1.0 / pow(2, (double)(buffer.size() - 1)); + + double second_oldest_sample = buffer[(oldest_index + 1) % buffer.size()]; + + current_avg -= oldest_sample * oldest_weight; + current_avg /= 2; + current_avg += second_oldest_sample / pow(2, (double)(buffer.size())); + current_avg += n / 2; + buffer[buffer_index] = n; buffer_index++; - buffer_index%=get_size(); + buffer_index %= buffer.size(); } /** * How many samples the average is made from * @return the number of samples used to calculate this average - */ -double MovingAverage::get_average(){ + */ +double ExponentialMovingAverage::get_value() +{ return current_avg; } // How many samples the average is made from -int MovingAverage::get_size(){ +int ExponentialMovingAverage::get_size() +{ return buffer.size(); } diff --git a/src/utils/pure_pursuit.cpp b/src/utils/pure_pursuit.cpp index 34db5a6..91502c9 100644 --- a/src/utils/pure_pursuit.cpp +++ b/src/utils/pure_pursuit.cpp @@ -1,5 +1,63 @@ #include "../core/include/utils/pure_pursuit.h" +/** + * Create a Path + * @param points the points that make up the path + * @param radius the lookahead radius for pure pursuit + */ +PurePursuit::Path::Path(std::vector points, double radius) { + this->points = points; + this->radius = radius; + this->valid = true; + + for(int i = 0; i < points.size() - 1; i++) { + for(int j = i + 2; j < points.size() - 1; j++) { + // Iterate over points on the segments discretely and compare distances + double segment_i_dist = points[i].dist(points[i+1]); + if (segment_i_dist == 0) segment_i_dist = 0.1; + double segment_j_dist = points[j].dist(points[j+1]); + if (segment_j_dist == 0) segment_j_dist = 0.1; + for(double t1 = 0; t1 <= 1; t1 += radius / segment_i_dist) { + point_t p1; + p1.x = points[i].x + t1 * (points[i+1].x - points[i].x); + p1.y = points[i].y + t1 * (points[i+1].y - points[i].y); + + for(double t2 = 0; t2 <= 1; t2 += radius / segment_j_dist) { + point_t p2; + p2.x = points[j].x + t2 * (points[j+1].x - points[j].x); + p2.y = points[j].y + t2 * (points[j+1].y - points[j].y); + + if(p1.dist(p2) < radius) { + this->valid = false; + return; + } + } + } + } + } +} + +/** + * Get the points associated with this Path + */ +std::vector PurePursuit::Path::get_points() { + return this->points; +} + +/** + * Get the radius associated with this Path + */ +double PurePursuit::Path::get_radius() { + return this->radius; +} + +/** + * Get whether this path will behave as expected + */ +bool PurePursuit::Path::is_valid() { + return this->valid; +} + /** * Returns points of the intersections of a line segment and a circle. The line * segment is defined by two points, and the circle is defined by a center and radius. @@ -191,49 +249,6 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub return new_path; } -[[maybe_unused]] std::vector PurePursuit::smooth_path_cubic(const std::vector &path, double res) { - std::vector new_path; - std::vector splines; - - double delta_x[path.size() - 1]; - double slope[path.size() - 1]; - double ftt[path.size()]; - - for(int i = 0; i < path.size() - 1; i++) { - delta_x[i] = path[i+1].x - path[i].x; - slope[i] = (path[i+1].y - path[i].y) / delta_x[i]; - } - - ftt[0] = 0; - for(int i = 0; i < path.size() - 2; i++) { - ftt[i+1] = 3 * (slope[i+1] - slope[i]) / (delta_x[i+1] + delta_x[i]); - } - ftt[path.size() - 1] = 0; - - for (int i = 0; i < path.size() - 1; i++) - { - splines.push_back({ - .a = (ftt[i + 1] - ftt[i]) / (6 * delta_x[i]), - .b = ftt[i] / 2, - .c = slope[i] - delta_x[i] * (ftt[i + 1] + 2 * ftt[i]) / 6, - .d = path[i].y, - .x_start = path[i].x, - .x_end = path[i+1].x - }); - } - - for(spline spline: splines) { - printf("spline a: %f b: %f c: %f d %f start %f, %f end %f, %f\n", spline.a, spline.b, spline.c, spline.d, spline.x_start, spline.getY(spline.x_start), spline.x_end, spline.getY(spline.x_end)); - double x = spline.x_start; - while(x >= fmin(spline.x_start, spline.x_end) && x <= fmax(spline.x_start, spline.x_end)) { - new_path.push_back({x, spline.getY(x)}); - spline.x_start < spline.x_end ? x += res: x -= res; - } - } - new_path.push_back({splines.back().x_end, splines.back().getY(splines.back().x_end)}); - - return new_path; -} /** * Estimates the remaining distance from the robot's position to the end, diff --git a/src/utils/serializer.cpp b/src/utils/serializer.cpp index 9e611f1..fd756e3 100644 --- a/src/utils/serializer.cpp +++ b/src/utils/serializer.cpp @@ -100,8 +100,7 @@ static void add_data(std::vector &data, const std::map -static std::vector::const_iterator read_data(const std::vector &data, - std::vector::const_iterator begin, +static std::vector::const_iterator read_data(std::vector::const_iterator begin, std::map &map) { std::vector::const_iterator pos = begin; @@ -194,19 +193,24 @@ std::string Serializer::string_or(const std::string &name, std::string otherwise /// @brief forms data bytes then saves to filename this was openned with void Serializer::save_to_disk() const { + vex::brain::sdcard sd; + if (!sd.isInserted()) + { + printf("!! Trying to Serialize to No SD Card !!\n"); + return; + } + std::vector data = {}; add_data(data, ints); add_data(data, bools); add_data(data, doubles); add_data(data, strings); - fflush(stdout); - vex::brain::sdcard sd; int32_t written = sd.savefile(filename.c_str(), (unsigned char *)&data[0], data.size()); if (written != data.size()) { - printf("!! Error writing to `%s`!!", filename.c_str()); + printf("!! Error writing to `%s`!!\n", filename.c_str()); return; } } @@ -221,8 +225,16 @@ bool Serializer::read_from_disk() return false; } int size = sd.size(filename.c_str()); + if (size == 0) + { + ints = {}; + doubles = {}; + bools = {}; + return true; + } - if (filename == ""){ + if (filename == "") + { printf("!! Can't write to empty filename!!\n"); return false; } @@ -239,14 +251,16 @@ bool Serializer::read_from_disk() int readsize = sd.loadfile(filename.c_str(), (unsigned char *)&data[0], size); if (size != readsize) { - printf("!! Error reading from file !!");; + printf("!! Error reading from file !!"); + ; return false; } - auto bool_start = read_data(data, data.cbegin(), ints); - auto doubles_start = read_data(data, bool_start, bools); - auto strings_start = read_data(data, doubles_start, doubles); - auto file_end = read_data(data, strings_start, strings); + + auto bool_start = read_data(data.cbegin(), ints); + auto doubles_start = read_data(bool_start, bools); + auto strings_start = read_data(doubles_start, doubles); + auto file_end = read_data(strings_start, strings); (void)file_end; return true; diff --git a/src/utils/trapezoid_profile.cpp b/src/utils/trapezoid_profile.cpp index fba334f..98eac62 100644 --- a/src/utils/trapezoid_profile.cpp +++ b/src/utils/trapezoid_profile.cpp @@ -1,117 +1,305 @@ -#include "../core/include/utils/trapezoid_profile.h" +#include "../core/include/utils/controls/trapezoid_profile.h" #include "../core/include/utils/math_util.h" #include +#include +const double EPSILON = 0.000005; + + +inline double calc_pos(double t, double a, double v, double si) { + return (0.5*(a)*(t)*(t))+((v)*(t))+(si); +} + +inline double calc_vel(double t, double a, double vi) { + return ((a)*(t))+(vi); +} TrapezoidProfile::TrapezoidProfile(double max_v, double accel) -: start(0), end(0), max_v(max_v), accel(accel) {} +: si(0), sf(0), vi(0), vf(0), max_v(max_v), accel(accel), segments(), num_acceleration_phases(0), precalculated(false) {} void TrapezoidProfile::set_max_v(double max_v) { this->max_v = max_v; + + this->precalculated = false; } void TrapezoidProfile::set_accel(double accel) { this->accel = accel; + + this->precalculated = false; } void TrapezoidProfile::set_endpts(double start, double end) { - this->start = start; - this->end = end; + this->si = start; + this->sf = end; + + this->precalculated = false; } -// Kinematic equations as macros -#define CALC_POS(time_s,a,v,s) ((0.5*(a)*(time_s)*(time_s))+((v)*(time_s))+(s)) -#define CALC_VEL(time_s,a,v) (((a)*(time_s))+(v)) - -/** - * @brief Run the trapezoidal profile based on the time that's ellapsed - * - * @param time_s Time since start of movement - * @return motion_t Position, velocity and acceleration - */ -motion_t TrapezoidProfile::calculate(double time_s) +void TrapezoidProfile::set_vel_endpts(double start, double end) { - double delta_pos = end - start; + this->vi = start; + this->vf = end; - // redefine accel and max_v in this scope for negative calcs - double accel_local = this->accel; - double max_v_local = this->max_v; - if(delta_pos < 0) - { - accel_local = -this->accel; - max_v_local = -this->max_v; - } + this->precalculated = false; +} + +motion_t TrapezoidProfile::calculate_time_based(double time_s) { + if (!this->precalculated) precalculate(); + + int segment_i = 0; - // Calculate the time spent during the acceleration / maximum velocity / deceleration stages - double accel_time = max_v_local / accel_local; - double max_vel_time = (delta_pos - (accel_local * accel_time * accel_time)) / max_v_local; - this->time = (2 * accel_time) + max_vel_time; + // position, velocity, acceleration, and time at the beginning of the segment we're in + double segment_s = this->si; + double segment_v = this->vi; + double segment_a = this->segments[0].accel; + double segment_t = 0; - // If the time during the "max velocity" state is negative, use an S profile - if (max_vel_time < 0) - { - accel_time = sqrt(fabs(delta_pos / accel)); - max_vel_time = 0; - this->time = 2 * accel_time; + // skip phases based on time + while (segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS + && time_s > segment_t + this->segments[segment_i].duration) { + segment_t += this->segments[segment_i].duration; + segment_s = this->segments[segment_i].pos_after; + segment_v = this->segments[segment_i].vel_after; + segment_i++; + segment_a = this->segments[segment_i].accel; } motion_t out; - // Handle if a bad time is put in - if (time_s < 0) - { - out.pos = start; - out.vel = 0; + // if we are beyond the last phase, return the position/velocity at the last phase + if (segment_i == MAX_TRAPEZOID_PROFILE_SEGMENTS) { out.accel = 0; + out.pos = this->segments[MAX_TRAPEZOID_PROFILE_SEGMENTS - 1].pos_after; + out.vel = this->segments[MAX_TRAPEZOID_PROFILE_SEGMENTS - 1].vel_after; return out; } - // Handle after the setpoint is reached - if (time_s > 2*accel_time + max_vel_time) - { - out.pos = end; - out.vel = 0; - out.accel = 0; - return out; - } + // calculate based on time + out.accel = this->segments[segment_i].accel; + out.vel = calc_vel(time_s - segment_t, segment_a, segment_v); + out.pos = calc_pos(time_s - segment_t, segment_a, segment_v, segment_s); + return out; +} - // ======== KINEMATIC EQUATIONS ======== +motion_t TrapezoidProfile::calculate(double time_s, double pos_s) { + if (!this->precalculated) precalculate(); - // Displacement from initial acceleration - if(time_s < accel_time) - { - out.pos = start + CALC_POS(time_s, accel_local, 0, 0); - out.vel = CALC_VEL(time_s, accel_local, 0); - out.accel = accel_local; - return out; + // printf("%f %f\n", time_s, pos_s); + + int segment_i = 0; + + // position, velocity, acceleration, and time at the beginning of the segment we're in + double segment_s = this->si; + double segment_v = this->vi; + double segment_a = this->segments[0].accel; + double segment_t = 0; + + // skip acceleration phases based on time + while (segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS + && segment_i < this->num_acceleration_phases + && time_s > segment_t + this->segments[segment_i].duration) { + segment_t += this->segments[segment_i].duration; + segment_s = this->segments[segment_i].pos_after; + segment_v = this->segments[segment_i].vel_after; + segment_i++; + segment_a = this->segments[segment_i].accel; } - double s_accel = CALC_POS(accel_time, accel_local, 0, 0); + // skip other segments based on distance, if we are past the time segments + if (segment_i >= this->num_acceleration_phases) { + while (segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS && + ((this->si < this->sf && pos_s > this->segments[segment_i].pos_after) + || (this->si > this->sf && pos_s < this->segments[segment_i].pos_after))) { + segment_t += this->segments[segment_i].duration; + segment_s = this->segments[segment_i].pos_after; + segment_v = this->segments[segment_i].vel_after; + segment_i++; + segment_a = this->segments[segment_i].accel; + } + } - // Displacement during maximum velocity - if (time_s < accel_time + max_vel_time) - { - out.pos = start + CALC_POS(time_s - accel_time, 0, max_v_local, s_accel); - out.vel = sign(delta_pos) * max_v; + motion_t out; + + // if we are beyond the last phase, return the position/velocity at the last phase + if (segment_i == MAX_TRAPEZOID_PROFILE_SEGMENTS) { out.accel = 0; + out.pos = this->segments[MAX_TRAPEZOID_PROFILE_SEGMENTS - 1].pos_after; + out.vel = this->segments[MAX_TRAPEZOID_PROFILE_SEGMENTS - 1].vel_after; return out; } - double s_max_vel = CALC_POS(max_vel_time, 0, max_v_local, s_accel); + // if we are in an acceleration phase, calculate based on time + if (segment_i < this->num_acceleration_phases) { + out.accel = segment_a; + out.vel = calc_vel(time_s - segment_t, segment_a, segment_v); + out.pos = calc_pos(time_s - segment_t, segment_a, segment_v, segment_s); + return out; + } - // Displacement during deceleration - out.pos = start + CALC_POS(time_s - (2*accel_time) - max_vel_time, -accel_local, 0, s_accel + s_max_vel); - out.vel = CALC_VEL(time_s - accel_time - max_vel_time, -accel_local, max_v_local); - out.accel = -accel_local; - return out; + // otherwise calculate based on distance + out.accel = segment_a; + out.pos = pos_s; + // Calculating the final velocity in uniformly accelerated motion: + // v_f^2 = v_i^2 + 2a(x_f - x_i) + // v_f = sqrt(v_i^2 + 2a(x_f - x_i)) + out.vel = sqrt(segment_v*segment_v + 2*segment_a*(pos_s - segment_s)); + // match the sign of the starting velocity of the segment + if (segment_v < 0) out.vel *= -1; + + return out; } double TrapezoidProfile::get_movement_time() { - return time; + if (!this->precalculated) precalculate(); + + double t = 0; + for (auto &segment : this->segments) { + t += segment.duration; + } + return t; +} + +bool TrapezoidProfile::precalculate() { + for (auto &segment : this->segments) { + segment.pos_after = 0; + segment.vel_after = 0; + segment.accel = 0; + segment.duration = 0; + } + this->num_acceleration_phases = 0; + + if (this->accel < EPSILON) { + printf("WARNING: trapezoid motion profile acceleration was negative, or too small\n"); + this->accel = fmin(EPSILON, fabs(this->accel)); + } + + if (this->max_v < EPSILON) { + printf("WARNING: trapezoid motion profile maximum velocity was negative, or too small\n"); + this->max_v = fmin(EPSILON, fabs(this->max_v)); + } + + // make sure vf is within v_max + if (fabs(this->vf) > this->max_v) { + printf("WARNING: trapezoid motion profile target velocity is greater than maximum velocity\n"); + if (this->vf > this->max_v) this->vf = this->max_v; + else this->vf = -this->max_v; + } + + // if displacement is + but vf is -, or if displacement is - but vf is + + if ((this->si < this->sf && this->vf < 0) || (this->si > this->sf && this->vf > 0)) { + printf("WARNING: trapezoid motion profile target velocity is in the wrong direction\n"); + this->vf = 0; + } + + double s = this->si, v = this->vi; + + for (auto & segment : this->segments) { + segment = calculate_next_segment(s, v); + + if (fabs(segment.pos_after - this->sf) < EPSILON) return true; + + // Check if xf is between x and x_next (meaning we overshot the end position) + if ((((this->si < this->sf) && (this->sf < segment.pos_after)) || ((segment.pos_after < this->sf) && (this->sf < this->si))) + && fabs(this->sf - segment.pos_after) > EPSILON) { + // Solve for the exact time to reach self.xf using the quadratic formula + // Given: x = x0 + v0 * t + 0.5 * a * t^2 + double a_coeff = 0.5 * segment.accel; + if (fabs(a_coeff) < EPSILON) a_coeff = EPSILON; + double b_coeff = v; + double c_coeff = s - this->sf; + + double discriminant = b_coeff * b_coeff - 4.0 * a_coeff * c_coeff; + if (discriminant >= 0) { + double t1 = (-b_coeff + sqrt(discriminant)) / (2 * a_coeff); + double t2 = (-b_coeff - sqrt(discriminant)) / (2 * a_coeff); + + double t_corrected = fmin(t1, t2); + if (t_corrected < 0) { + t_corrected = fmax(t1, t2); + } + segment.duration = t_corrected; + segment.vel_after = calc_vel(segment.duration, segment.accel, v); + segment.pos_after = calc_pos(segment.duration, segment.accel, v, s); + return true; + } else { + printf("ERROR: No real solution to reach sf.\n"); + return false; + } + } + + v = segment.vel_after; + s = segment.pos_after; + } + + printf("WARNING: trapezoid motion profile did not reach end position in %d segments (the maximum)\n", MAX_TRAPEZOID_PROFILE_SEGMENTS); + return false; +} + +trapezoid_profile_segment_t TrapezoidProfile::calculate_kinetic_motion(double si, double vi, double v_target) { + trapezoid_profile_segment_t m; + + m.duration = fabs(v_target - vi) / this->accel; + m.vel_after = v_target; + if (vi < v_target) { + m.accel = this->accel; + } else { + m.accel = -this->accel; + } + + m.pos_after = calc_pos(m.duration, m.accel, vi, si); + return m; +} + +trapezoid_profile_segment_t TrapezoidProfile::calculate_next_segment(double s, double v) { + // d represents the direction of travel, + or - + int d = 1; + if (this->si > this->sf) { + d = -1; + } + + // if going the wrong way, come to a stop + if ((d == 1 && v < -EPSILON) || (d == -1 && v > EPSILON)) { + this->num_acceleration_phases += 1; + return calculate_kinetic_motion(s, v, 0); + } + + // if |v| > max_v, slow down + if (v > this->max_v || v < -this->max_v) { + this->num_acceleration_phases += 1; + return calculate_kinetic_motion(s, v, d * this->max_v); + } + + // how much distance would it take to reach vf in one segment? + trapezoid_profile_segment_t beeline_vf = calculate_kinetic_motion(s, v, this->vf); + if ((d == 1 && beeline_vf.pos_after > this->sf - EPSILON) || (d == -1 && beeline_vf.pos_after <= this->sf + EPSILON)) { + // we can't make it to vf - get as close as possible + return beeline_vf; + } + + // we can reach vf in one segment - choose the fastest speed so that that is still possible + double v_middle = d * sqrt(((v*v + this->vf*this->vf)/2.0) + this->accel*fabs(this->sf - s) + this->vf*this->vf); + // cap this at our max speed + v_middle = fmax(-this->max_v, fmin(v_middle, this->max_v)); + + // if we aren't at this speed yet, let's get there + if (fabs(v_middle - v) > EPSILON) { + this->num_acceleration_phases += 1; + return calculate_kinetic_motion(s, v, v_middle); + } + + // we are at our max speed - hold it until we have to start slowing down + trapezoid_profile_segment_t out; + out.accel = 0; + double distance = d * fabs(this->sf - beeline_vf.pos_after); + out.pos_after = s + distance; + out.duration = distance / v_middle; + out.vel_after = v_middle; + return out; } From ce579a26783f34fac0c96f1fbe4f94e28883567d Mon Sep 17 00:00:00 2001 From: Richard Sommers <44383226+cowsed@users.noreply.github.com> Date: Wed, 27 Dec 2023 17:24:05 -0500 Subject: [PATCH 235/243] Update main.yml add ability to run manually so we can run when we update the google doc --- .github/workflows/main.yml | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index 9b1d5b7..c9a9bb7 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -4,10 +4,11 @@ name: Doxygen Action # Controls when the action will run. Triggers the workflow on push or pull request # events but only for the master branch -on: +on: push: branches: [ main ] - + workflow_dispatch: + # A workflow run is made up of one or more jobs that can run sequentially or in parallel From d1921ad3e71e82903b00082c09c7a7bc006184ab Mon Sep 17 00:00:00 2001 From: cowsed Date: Tue, 16 Jan 2024 14:54:49 -0500 Subject: [PATCH 236/243] maybe gonna break things --- include/subsystems/layout.h | 11 + include/subsystems/odometry/odometry_base.h | 3 +- include/subsystems/odometry/odometry_tank.h | 3 + include/subsystems/screen.h | 185 ++-- include/subsystems/tank_drive.h | 43 +- include/utils/controls/motion_controller.h | 8 +- include/utils/controls/pid.h | 145 +-- include/utils/controls/pidff.h | 145 +-- include/utils/controls/trapezoid_profile.h | 264 +++--- include/utils/moving_average.h | 8 +- src/subsystems/custom_encoder.cpp | 10 +- src/subsystems/flywheel.cpp | 3 +- src/subsystems/mecanum_drive.cpp | 5 +- src/subsystems/odometry/odometry_base.cpp | 71 +- src/subsystems/odometry/odometry_tank.cpp | 258 +++--- src/subsystems/screen.cpp | 872 ++++++++++--------- src/subsystems/tank_drive.cpp | 139 ++- src/utils/command_structure/auto_command.cpp | 11 +- src/utils/controls/feedforward.cpp | 3 +- src/utils/controls/motion_controller.cpp | 208 +++-- src/utils/controls/pid.cpp | 89 +- src/utils/controls/pidff.cpp | 62 +- src/utils/generic_auto.cpp | 20 +- src/utils/math_util.cpp | 9 +- src/utils/moving_average.cpp | 2 +- src/utils/pure_pursuit.cpp | 12 +- src/utils/trapezoid_profile.cpp | 516 +++++------ 27 files changed, 1714 insertions(+), 1391 deletions(-) create mode 100644 include/subsystems/layout.h diff --git a/include/subsystems/layout.h b/include/subsystems/layout.h new file mode 100644 index 0000000..1715e93 --- /dev/null +++ b/include/subsystems/layout.h @@ -0,0 +1,11 @@ +#include +#include + +struct SliderCfg{ + double &val; + double min; + double max; +}; + + + diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index 304a2c4..2da4202 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -3,6 +3,7 @@ #include "vex.h" #include "../core/include/utils/geometry.h" #include "../core/include/robot_specs.h" +#include "../core/include/utils/command_structure/auto_command.h" #ifndef PI #define PI 3.141592654 @@ -44,7 +45,7 @@ class OdometryBase * @param newpos the new position that the odometry will believe it is at */ virtual void set_position(const pose_t& newpos=zero_pos); - + AutoCommand *SetPositionCmd(const pose_t& newpos=zero_pos); /** * Update the current position on the field based on the sensors * @return the location that the robot is at after the odometry does its calculations diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index c2e4e1c..7e8607f 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -4,6 +4,8 @@ #include "../core/include/subsystems/custom_encoder.h" #include "../core/include/utils/geometry.h" #include "../core/include/utils/vector2d.h" +#include "../core/include/utils/moving_average.h" + #include "../core/include/robot_specs.h" static int background_task(void* odom_obj); @@ -77,5 +79,6 @@ class OdometryTank : public OdometryBase robot_specs_t &config; double rotation_offset = 0; + ExponentialMovingAverage ema = ExponentialMovingAverage(3); }; \ No newline at end of file diff --git a/include/subsystems/screen.h b/include/subsystems/screen.h index d5ebcea..58159b2 100644 --- a/include/subsystems/screen.h +++ b/include/subsystems/screen.h @@ -11,28 +11,35 @@ namespace screen { - /// @brief Page describes one part of the screen slideshow - class Page + /// @brief Widget that does something when you tap it. The function is only called once when you first tap it + class ButtonWidget { public: - /** - * @brief collect data, respond to screen input, do fast things (runs at - * 50hz even if you're not focused on this Page (only drawn page gets - * touch updates)) - * @param was_pressed true if the screen has been pressed - * @param x x position of screen press (if the screen was pressed) - * @param y y position of screen press (if the screen was pressed) - */ - virtual void update(bool was_pressed, int x, int y); - /** - * @brief draw stored data to the screen (runs at 10 hz and only runs if - * this page is in front) - * @param first_draw true if we just switched to this page - * @param frame_number frame of drawing we are on (basically an animation - * tick) - */ - virtual void draw(vex::brain::lcd &screen, bool first_draw, - unsigned int frame_number); + /// @brief Create a Button widget + /// @param onpress the function to be called when the button is tapped + /// @param rect the area the button should take up on the screen + /// @param name the label put on the button + ButtonWidget(std::function onpress, Rect rect, std::string name) : onpress(onpress), rect(rect), name(name) {} + /// @brief Create a Button widget + /// @param onpress the function to be called when the button is tapped + /// @param rect the area the button should take up on the screen + /// @param name the label put on the button + ButtonWidget(void (*onpress)(), Rect rect, std::string name) : onpress(onpress), rect(rect), name(name) {} + + /// @brief responds to user input + /// @param was_pressed if the screen is pressed + /// @param x x position if the screen was pressed + /// @param y y position if the screen was pressed + /// @return true if the button was pressed + bool update(bool was_pressed, int x, int y); + /// @brief draws the button to the screen + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number); + + private: + std::function onpress; + Rect rect; + std::string name = ""; + bool was_pressed_last = false; }; /// @brief Widget that updates a double value. Updates by reference so watch out for race conditions cuz the screen stuff lives on another thread @@ -66,35 +73,109 @@ namespace screen std::string name = ""; }; - /// @brief Widget that does something when you tap it. The function is only called once when you first tap it - class ButtonWidget + struct WidgetConfig; + + struct SliderConfig + { + double &val; + double low; + double high; + }; + struct ButtonConfig + { + std::function onclick; + }; + struct CheckboxConfig + { + std::function onupdate; + }; + struct LabelConfig + { + std::string label; + }; + + struct TextConfig + { + std::function text; + }; + struct SizedWidget + { + int size; + WidgetConfig &widget; + }; + struct WidgetConfig + { + enum Type + { + Col, + Row, + Slider, + Button, + Checkbox, + Label, + Text, + Graph, + }; + Type type; + union + { + std::vector widgets; + SliderConfig slider; + ButtonConfig button; + CheckboxConfig checkbox; + LabelConfig label; + TextConfig text; + GraphDrawer *graph; + } config; + }; + + class Page; + /// @brief Page describes one part of the screen slideshow + class Page { public: - /// @brief Create a Button widget - /// @param onpress the function to be called when the button is tapped - /// @param rect the area the button should take up on the screen - /// @param name the label put on the button - ButtonWidget(std::function onpress, Rect rect, std::string name) : onpress(onpress), rect(rect), name(name) {} - /// @brief Create a Button widget - /// @param onpress the function to be called when the button is tapped - /// @param rect the area the button should take up on the screen - /// @param name the label put on the button - ButtonWidget(void (*onpress)(), Rect rect, std::string name) : onpress(onpress), rect(rect), name(name) {} + /** + * @brief collect data, respond to screen input, do fast things (runs at + * 50hz even if you're not focused on this Page (only drawn page gets + * touch updates)) + * @param was_pressed true if the screen has been pressed + * @param x x position of screen press (if the screen was pressed) + * @param y y position of screen press (if the screen was pressed) + */ + virtual void update(bool was_pressed, int x, int y); + /** + * @brief draw stored data to the screen (runs at 10 hz and only runs if + * this page is in front) + * @param first_draw true if we just switched to this page + * @param frame_number frame of drawing we are on (basically an animation + * tick) + */ + virtual void draw(vex::brain::lcd &screen, bool first_draw, + unsigned int frame_number); + }; - /// @brief responds to user input - /// @param was_pressed if the screen is pressed - /// @param x x position if the screen was pressed - /// @param y y position if the screen was pressed - /// @return true if the button was pressed - bool update(bool was_pressed, int x, int y); - /// @brief draws the button to the screen - void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number); + struct ScreenRect + { + uint32_t x1; + uint32_t y1; + uint32_t x2; + uint32_t y2; + }; + void draw_widget(WidgetConfig &widget, ScreenRect rect); + + class WidgetPage : public Page + { + public: + WidgetPage(WidgetConfig &cfg) : base_widget(cfg) {} + void update(bool was_pressed, int x, int y) override; + + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override + { + draw_widget(base_widget, {.x1 = 20, .y1 = 0, .x2 = 440, .y2 = 240}); + } private: - std::function onpress; - Rect rect; - std::string name = ""; - bool was_pressed_last = false; + WidgetConfig &base_widget; }; /** @@ -105,6 +186,10 @@ namespace screen */ void start_screen(vex::brain::lcd &screen, std::vector pages, int first_page = 0); + + void next_page(); + void prev_page(); + /// @brief stops the screen. If you have a drive team that hates fun call this at the start of opcontrol void stop_screen(); @@ -114,8 +199,7 @@ namespace screen /// @brief type of function needed for draw using draw_func_t = std::function; - - /// @brief Draws motor stats and battery stats to the screen + /// @brief Draws motor stats and battery stats to the screen class StatsPage : public Page { public: @@ -147,7 +231,7 @@ namespace screen /// @param odom the odometry system to monitor /// @param robot_width the width (side to side) of the robot in inches. Used for visualization /// @param robot_height the robot_height (front to back) of the robot in inches. Used for visualization - /// @param do_trail whether or not to calculate and draw the trail. Drawing and storing takes a very *slight* extra amount of processing power + /// @param do_trail whether or not to calculate and draw the trail. Drawing and storing takes a very *slight* extra amount of processing power OdometryPage(OdometryBase &odom, double robot_width, double robot_height, bool do_trail); /// @brief @see Page#update void update(bool was_pressed, int x, int y) override; @@ -166,6 +250,7 @@ namespace screen pose_t path[path_len]; int path_index = 0; bool do_trail; + GraphDrawer velocity_graph; }; /// @brief Simple page that stores no internal data. the draw and update functions use only global data rather than storing anything @@ -194,8 +279,10 @@ namespace screen /// @param pid the pid controller we're changing /// @param name a name to recognize this pid controller if we've got multiple pid screens /// @param onchange a function that is called when a tuning parameter is changed. If you need to update stuff on that change register a handler here - PIDPage(PID &pid, std::string name, std::function onchange = [](){}); - PIDPage(PIDFF &pidff, std::string name, std::function onchange = [](){}); + PIDPage( + PID &pid, std::string name, std::function onchange = []() {}); + PIDPage( + PIDFF &pidff, std::string name, std::function onchange = []() {}); /// @brief @see Page#update void update(bool was_pressed, int x, int y) override; diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index c2826de..2e63002 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -22,6 +22,12 @@ using namespace vex; class TankDrive { public: + enum class BrakeType + { + None, ///< just send 0 volts to the motors + ZeroVelocity, ///< try to bring the robot to rest. But don't try to hold position + Smart, ///< bring the robot to rest and once it's stopped, try to hold that position + }; /** * Create the TankDrive object * @param left_motors left side drive motors @@ -43,8 +49,8 @@ class TankDrive AutoCommand *TurnDegreesCmd(double degrees, double max_speed = 1.0, double start_speed = 0.0); AutoCommand *TurnDegreesCmd(Feedback &fb, double degrees, double max_speed = 1.0, double end_speed = 0.0); - AutoCommand *PurePursuitCmd(PurePursuit::Path path, directionType dir, double max_speed=1, double end_speed=0); - AutoCommand *PurePursuitCmd(Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed=1, double end_speed=0); + AutoCommand *PurePursuitCmd(PurePursuit::Path path, directionType dir, double max_speed = 1, double end_speed = 0); + AutoCommand *PurePursuitCmd(Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed = 1, double end_speed = 0); /** * Stops rotation of all the motors using their "brake mode" @@ -59,9 +65,15 @@ class TankDrive * @param left the percent to run the left motors * @param right the percent to run the right motors * @param power modifies the input velocities left^power, right^power - * @param isdriver default false. if true uses motor percentage. if false uses plain percentage of maximum voltage + * @param bt breaktype. What to do if the driver lets go of the sticks */ - void drive_tank(double left, double right, int power=1); + void drive_tank(double left, double right, int power = 1, BrakeType bt = BrakeType::None); + /** + * Drive the robot raw-ly + * @param left the percent to run the left motors (-1, 1) + * @param right the percent to run the right motors (-1, 1) + */ + void drive_tank_raw(double left, double right); /** * Drive the robot using arcade style controls. forward_back controls the linear motion, @@ -72,8 +84,9 @@ class TankDrive * @param forward_back the percent to move forward or backward * @param left_right the percent to turn left or right * @param power modifies the input velocities left^power, right^power + * @param bt breaktype. What to do if the driver lets go of the sticks */ - void drive_arcade(double forward_back, double left_right, int power = 1); + void drive_arcade(double forward_back, double left_right, int power = 1, BrakeType bt = BrakeType::None); /** * Use odometry to drive forward a certain distance using a custom feedback controller @@ -120,7 +133,7 @@ class TankDrive * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power * @param end_speed the movement profile will attempt to reach this velocity by its completion - */ + */ bool turn_degrees(double degrees, double max_speed = 1, double end_speed = 0); /** @@ -187,33 +200,33 @@ class TankDrive static double modify_inputs(double input, int power = 2); /** - * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of + * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of * waypoints - the robot will attempt to follow the points while cutting corners (radius) * to save time (compared to stop / turn / start) - * + * * @param path The list of coordinates to follow, in order * @param dir Run the bot forwards or backwards * @param feedback The feedback controller determining speed * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return True when the path is complete - */ - bool pure_pursuit(PurePursuit::Path path, directionType dir, Feedback &feedback, double max_speed=1, double end_speed=0); + */ + bool pure_pursuit(PurePursuit::Path path, directionType dir, Feedback &feedback, double max_speed = 1, double end_speed = 0); /** - * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of + * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of * waypoints - the robot will attempt to follow the points while cutting corners (radius) * to save time (compared to stop / turn / start) - * + * * Use the default drive feedback - * + * * @param path The list of coordinates to follow, in order * @param dir Run the bot forwards or backwards * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return True when the path is complete - */ - bool pure_pursuit(PurePursuit::Path path, directionType dir, double max_speed=1, double end_speed=0); + */ + bool pure_pursuit(PurePursuit::Path path, directionType dir, double max_speed = 1, double end_speed = 0); private: motor_group &left_motors; ///< left drive motors diff --git a/include/utils/controls/motion_controller.h b/include/utils/controls/motion_controller.h index 03bbce6..86b3cde 100644 --- a/include/utils/controls/motion_controller.h +++ b/include/utils/controls/motion_controller.h @@ -4,6 +4,8 @@ #include "../core/include/utils/controls/trapezoid_profile.h" #include "../core/include/utils/controls/feedback_base.h" #include "../core/include/subsystems/tank_drive.h" +#include "../core/include/subsystems/screen.h" + #include "vex.h" /** @@ -87,7 +89,10 @@ class MotionController : public Feedback /** * @return The current postion, velocity and acceleration setpoints */ - motion_t get_motion(); + motion_t get_motion() const; + + + screen::Page *Page(); /** * This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. @@ -125,5 +130,6 @@ class MotionController : public Feedback motion_t cur_motion; vex::timer tmr; + friend class MotionControllerPage; }; \ No newline at end of file diff --git a/include/utils/controls/pid.h b/include/utils/controls/pid.h index a2b3557..102bc8a 100644 --- a/include/utils/controls/pid.h +++ b/include/utils/controls/pid.h @@ -1,105 +1,111 @@ #pragma once -#include -#include "vex.h" #include "../core/include/utils/controls/feedback_base.h" +#include "vex.h" +#include using namespace vex; /** * PID Class - * - * Defines a standard feedback loop using the constants kP, kI, kD, deadband, and on_target_time. - * The formula is: - * + * + * Defines a standard feedback loop using the constants kP, kI, kD, deadband, + * and on_target_time. The formula is: + * * out = kP*error + kI*integral(d Error) + kD*(dError/dt) - * - * The PID object will determine it is "on target" when the error is within the deadband, for - * a duration of on_target_time - * + * + * The PID object will determine it is "on target" when the error is within the + * deadband, for a duration of on_target_time + * * @author Ryan McGee * @date 4/3/2020 */ -class PID : public Feedback -{ +class PID : public Feedback { public: /** - * An enum to distinguish between a linear and angular caluclation of PID error. + * An enum to distinguish between a linear and angular caluclation of PID + * error. */ - enum ERROR_TYPE{ + enum ERROR_TYPE { LINEAR, ANGULAR // assumes degrees }; /** * pid_config_t holds the configuration parameters for a pid controller - * In addtion to the constant of proportional, integral and derivative, these parameters include: - * - deadband - + * In addtion to the constant of proportional, integral and derivative, these + * parameters include: + * - deadband - * - on_target_time - for how long do we have to be at the target to stop - * As well, pid_config_t holds an error type which determines whether errors should be calculated as if the sensor position is a measure of distance or an angle - */ - struct pid_config_t - { - double p; ///< proportional coeffecient p * error() - double i; ///< integral coeffecient i * integral(error) - double d; ///< derivitave coeffecient d * derivative(error) + * As well, pid_config_t holds an error type which determines whether errors + * should be calculated as if the sensor position is a measure of distance or + * an angle + */ + struct pid_config_t { + double p; ///< proportional coeffecient p * error() + double i; ///< integral coeffecient i * integral(error) + double d; ///< derivitave coeffecient d * derivative(error) double deadband; ///< at what threshold are we close enough to be finished - double on_target_time; ///< the time in seconds that we have to be on target for to say we are officially at the target - ERROR_TYPE error_method; ///< Linear or angular. wheter to do error as a simple subtraction or to wrap + double on_target_time; ///< the time in seconds that we have to be on target + ///< for to say we are officially at the target + ERROR_TYPE error_method; ///< Linear or angular. wheter to do error as a + ///< simple subtraction or to wrap }; - - /** * Create the PID object * @param config the configuration data for this controller */ PID(pid_config_t &config); - /** * Inherited from Feedback for interoperability. * Update the setpoint and reset integral accumulation - * + * * start_pt can be safely ignored in this feedback controller - * @param start_pt commpletely ignored for PID. necessary to satisfy Feedback base + * @param start_pt commpletely ignored for PID. necessary to satisfy Feedback + * base * @param set_pt sets the target of the PID controller - * @param start_vel completely ignored for PID. necessary to satisfy Feedback base + * @param start_vel completely ignored for PID. necessary to satisfy Feedback + * base * @param end_vel sets the target end velocity of the PID controller */ - void init(double start_pt, double set_pt, double start_vel = 0, double end_vel = 0) override; + void init(double start_pt, double set_pt, double start_vel = 0, + double end_vel = 0) override; /** * Update the PID loop by taking the time difference from last update, * and running the PID formula with the new sensor data - * @param sensor_val the distance, angle, encoder position or whatever it is we are measuring + * @param sensor_val the distance, angle, encoder position or whatever it is + * we are measuring * @return the new output. What would be returned by PID::get() */ double update(double sensor_val) override; - /** * @brief gets the sensor value that we were last updated with * @return sensor_val - */ - double get_sensor_val(); - + */ + double get_sensor_val() const; /** * Gets the current PID out value, from when update() was last run - * @return the Out value of the controller (voltage, RPM, whatever the PID controller is controlling) + * @return the Out value of the controller (voltage, RPM, whatever the PID + * controller is controlling) */ double get() override; /** - * Set the limits on the PID out. The PID out will "clip" itself to be + * Set the limits on the PID out. The PID out will "clip" itself to be * between the limits. - * @param lower the lower limit. the PID controller will never command the output go below `lower` - * @param upper the upper limit. the PID controller will never command the output go higher than `upper` + * @param lower the lower limit. the PID controller will never command the + * output go below `lower` + * @param upper the upper limit. the PID controller will never command the + * output go higher than `upper` */ void set_limits(double lower, double upper) override; /** - * Checks if the PID controller is on target. + * Checks if the PID controller is on target. * @return true if the loop is within [deadband] for [on_target_time] seconds */ bool is_on_target() override; @@ -111,7 +117,8 @@ class PID : public Feedback /** * Get the delta between the current sensor data and the target - * @return the error calculated. how it is calculated depends on error_method specified in pid_config_t + * @return the error calculated. how it is calculated depends on error_method + * specified in pid_config_t */ double get_error(); @@ -119,7 +126,7 @@ class PID : public Feedback * Get the PID's target * @return the target the PID controller is trying to achieve */ - double get_target(); + double get_target() const; /** * Set the target for the PID loop, where the robot is trying to end up @@ -127,27 +134,39 @@ class PID : public Feedback */ void set_target(double target); - - pid_config_t &config; ///< configuration struct for this controller. see pid_config_t for information about what this contains + pid_config_t + &config; ///< configuration struct for this controller. see pid_config_t + ///< for information about what this contains private: + double last_error = + 0; ///< the error measured on the last iteration of update() + double accum_error = + 0; ///< the integral of error over time since we called init() - - double last_error = 0; ///< the error measured on the last iteration of update() - double accum_error = 0; ///< the integral of error over time since we called init() - double last_time = 0; ///< the time measured the last time update() was called - double on_target_last_time = 0; ///< the time at which we started being on target - - double lower_limit = 0; ///< the PID controller will never set a target to go lower than this - double upper_limit = 0; ///< the PID controller will never set a target to go higher than this - - double target = 0; ///< the target position of the PID controller (lower_limit <= target <= upper_limit) - double target_vel = 0; ///< the target velocity of the PID controller (if != 0, controller will not wait for stop) - double sensor_val = 0; ///< the last recorded value of the sensor we use to feed the PID controller - double out = 0; ///< the last calculated output value. we save it here so that we don't have to recalculate if we ask for it more than once between update() calls - - bool is_checking_on_target = false; ///< true if the sensor reading is within target +/- deadband - - timer pid_timer; ///< used for calculating integrals and derivatives in line with the real world times and checking the time we are on target + double on_target_last_time = + 0; ///< the time at which we started being on target + + double lower_limit = + 0; ///< the PID controller will never set a target to go lower than this + double upper_limit = + 0; ///< the PID controller will never set a target to go higher than this + + double target = 0; ///< the target position of the PID controller (lower_limit + ///< <= target <= upper_limit) + double target_vel = 0; ///< the target velocity of the PID controller (if != + ///< 0, controller will not wait for stop) + double sensor_val = 0; ///< the last recorded value of the sensor we use to + ///< feed the PID controller + double out = 0; ///< the last calculated output value. we save it here so that + ///< we don't have to recalculate if we ask for it more than + ///< once between update() calls + + bool is_checking_on_target = + false; ///< true if the sensor reading is within target +/- deadband + + timer pid_timer; ///< used for calculating integrals and derivatives in line + ///< with the real world times and checking the time we are + ///< on target }; diff --git a/include/utils/controls/pidff.h b/include/utils/controls/pidff.h index f2c8219..243f81b 100644 --- a/include/utils/controls/pidff.h +++ b/include/utils/controls/pidff.h @@ -1,77 +1,78 @@ #pragma once #include "../core/include/utils/controls/feedback_base.h" -#include "../core/include/utils/controls/pid.h" #include "../core/include/utils/controls/feedforward.h" +#include "../core/include/utils/controls/pid.h" -class PIDFF : public Feedback -{ - public: - - PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg); - - /** - * Initialize the feedback controller for a movement - * - * @param start_pt the current sensor value - * @param set_pt where the sensor value should be - * @param start_vel the current rate of change of the sensor value - * @param end_vel the desired ending rate of change of the sensor value - */ - void init(double start_pt, double set_pt, double start_vel, double end_vel) override; - - /** - * Set the target of the PID loop - * @param set_pt Setpoint / target value - */ - void set_target(double set_pt); - - /** - * Iterate the feedback loop once with an updated sensor value. - * Only kS for feedfoward will be applied. - * - * @param val value from the sensor - * @return feedback loop result - */ - double update(double val) override; - - /** - * Iterate the feedback loop once with an updated sensor value - * - * @param val value from the sensor - * @param vel_setpt Velocity for feedforward - * @param a_setpt Acceleration for feedfoward - * @return feedback loop result - */ - double update(double val, double vel_setpt, double a_setpt=0); - - /** - * @return the last saved result from the feedback controller - */ - double get() override; - - /** - * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. - * - * @param lower Upper limit - * @param upper Lower limit - */ - void set_limits(double lower, double upper) override; - - /** - * @return true if the feedback controller has reached it's setpoint - */ - bool is_on_target() override; - - PID pid; - - - private: - - FeedForward::ff_config_t &ff_cfg; - - FeedForward ff; - - double out; - double lower_lim, upper_lim; - +class PIDFF : public Feedback { +public: + PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg); + + /** + * Initialize the feedback controller for a movement + * + * @param start_pt the current sensor value + * @param set_pt where the sensor value should be + * @param start_vel the current rate of change of the sensor value + * @param end_vel the desired ending rate of change of the sensor value + */ + void init(double start_pt, double set_pt, double start_vel, + double end_vel) override; + + /** + * Set the target of the PID loop + * @param set_pt Setpoint / target value + */ + void set_target(double set_pt); + + double get_target() const; + double get_sensor_val() const; + /** + * Iterate the feedback loop once with an updated sensor value. + * Only kS for feedfoward will be applied. + * + * @param val value from the sensor + * @return feedback loop result + */ + double update(double val) override; + + /** + * Iterate the feedback loop once with an updated sensor value + * + * @param val value from the sensor + * @param vel_setpt Velocity for feedforward + * @param a_setpt Acceleration for feedfoward + * @return feedback loop result + */ + double update(double val, double vel_setpt, double a_setpt = 0); + + /** + * @return the last saved result from the feedback controller + */ + double get() override; + + /** + * Clamp the upper and lower limits of the output. If both are 0, no limits + * should be applied. + * + * @param lower Upper limit + * @param upper Lower limit + */ + void set_limits(double lower, double upper) override; + + /** + * @return true if the feedback controller has reached it's setpoint + */ + bool is_on_target() override; + + void reset(); + + PID pid; + +private: + FeedForward::ff_config_t &ff_cfg; + + FeedForward ff; + + double out; + double lower_lim, upper_lim; }; \ No newline at end of file diff --git a/include/utils/controls/trapezoid_profile.h b/include/utils/controls/trapezoid_profile.h index 0f2756c..6cd9cc2 100644 --- a/include/utils/controls/trapezoid_profile.h +++ b/include/utils/controls/trapezoid_profile.h @@ -4,24 +4,23 @@ const int MAX_TRAPEZOID_PROFILE_SEGMENTS = 4; /** * motion_t is a description of 1 dimensional motion at a point in time. -*/ -typedef struct -{ - double pos; ///< 1d position at this point in time - double vel; ///< 1d velocity at this point in time - double accel; ///< 1d acceleration at this point in time + */ +typedef struct { + double pos; ///< 1d position at this point in time + double vel; ///< 1d velocity at this point in time + double accel; ///< 1d acceleration at this point in time } motion_t; /** - * trapezoid_profile_segment_t is a description of one constant acceleration segment of a trapezoid motion profile + * trapezoid_profile_segment_t is a description of one constant acceleration + * segment of a trapezoid motion profile */ -typedef struct -{ - double pos_after; ///< 1d position after this segment concludes - double vel_after; ///< 1d velocity after this segment concludes - double accel; ///< 1d acceleration during the segment - double duration; ///< duration of the segment +typedef struct { + double pos_after; ///< 1d position after this segment concludes + double vel_after; ///< 1d velocity after this segment concludes + double accel; ///< 1d acceleration during the segment + double duration; ///< duration of the segment } trapezoid_profile_segment_t; /** @@ -33,22 +32,26 @@ typedef struct * - start position and velocity * - end position and velocity * - * Using this information, a parametric function is generated, with a period of acceleration, constant - * velocity, and deceleration. The velocity graph usually looks like a trapezoid, giving it its name. + * Using this information, a parametric function is generated, with a period of + * acceleration, constant velocity, and deceleration. The velocity graph usually + * looks like a trapezoid, giving it its name. * - * If the maximum velocity is set high enough, this will become a S-curve profile, with only acceleration and deceleration. + * If the maximum velocity is set high enough, this will become a S-curve + * profile, with only acceleration and deceleration. * - * If the initial velocity is in the wrong direction, the profile will first come to a stop, then continue a normal - * trapezoid profile. + * If the initial velocity is in the wrong direction, the profile will first + * come to a stop, then continue a normal trapezoid profile. * - * If the initial velocity is higher than the maximum velocity, the profile will first try to achieve the maximum velocity. + * If the initial velocity is higher than the maximum velocity, the profile will + * first try to achieve the maximum velocity. * - * If the end velocity is not achievable, the profile will try to get as close as possible. The end velocity must - * be in the direction of the end point. + * If the end velocity is not achievable, the profile will try to get as close + * as possible. The end velocity must be in the direction of the end point. * - * This class is designed for use in properly modelling the motion of the robots to create a feedfoward - * and target for PID. Acceleration and Maximum velocity should be measured on the robot and tuned down - * slightly to account for battery drop. + * This class is designed for use in properly modelling the motion of the robots + * to create a feedfoward and target for PID. Acceleration and Maximum velocity + * should be measured on the robot and tuned down slightly to account for + * battery drop. * * Here are the equations graphed for ease of understanding: * https://www.desmos.com/calculator/rkm3ivu1yk @@ -57,106 +60,115 @@ typedef struct * @date 7/12/2022 * */ -class TrapezoidProfile -{ - public: - - /** - * @brief Construct a new Trapezoid Profile object - * - * @param max_v Maximum velocity the robot can run at - * @param accel Maximum acceleration of the robot - */ - TrapezoidProfile(double max_v, double accel); - - /** - * @brief Run the trapezoidal profile based on the time and distance that's elapsed - * - * @param time_s Time since start of movement - * @param pos_s The current position - * @return motion_t Position, velocity and acceleration - */ - motion_t calculate(double time_s, double pos_s); - - /** - * @brief Run the trapezoidal profile based on the time that's elapsed - * - * @param time_s Time since start of movement - * @return motion_t Position, velocity and acceleration - */ - motion_t calculate_time_based(double time_s); - - /** - * @brief set_endpts defines a start and end position - * - * @param start the starting position of the path - * @param end the ending position of the path - */ - void set_endpts(double start, double end); - - /** - * @brief set start and end velocities - * - * @param start the starting velocity of the path - * @param end the ending velocity of the path - */ - void set_vel_endpts(double start, double end); - - /** - * @brief set_accel sets the acceleration this profile will use (the left and right legs of the trapezoid) - * - * @param accel the acceleration amount to use - */ - void set_accel(double accel); - - /** - * @brief sets the maximum velocity for the profile (the height of the top of the trapezoid) - * - * @param max_v the maximum velocity the robot can travel at - */ - void set_max_v(double max_v); - - /** - * @brief uses the kinematic equations to and specified accel and max_v to figure out how long moving along the profile would take - * - * @return the time the path will take to travel - */ - double get_movement_time(); - - private: - double si, sf; ///< the initial and final position of the profile - double vi, vf; ///< the initial and final velocity of the profile - double max_v; ///< the maximum velocity to travel at for this profile - double accel; ///< the rate of acceleration to use for this profile. - - trapezoid_profile_segment_t segments[MAX_TRAPEZOID_PROFILE_SEGMENTS]; - int num_acceleration_phases; - - bool precalculated; ///< whether or not the segment array is up to date - - /** - * Attempt to generate the motion profile for the given parameters - * - * @return False if there was a problem with the parameters - */ - bool precalculate(); - - /** - * Calculate a trapezoid segment given a target velocity that accelerates to the given velocity - * - * @param si segment initial position - * @param vi segment initial velocity - * @param v_target target velocity - * @return a trapezoid_profile_segment_t that represents constant acceleration to the target velocity - */ - trapezoid_profile_segment_t calculate_kinetic_motion(double si, double vi, double v_target); - - /** - * Calculate the next segment of the trapezoid motion profile - * - * @param s segment starting position - * @param v segment starting velocity - * @return the next segment of the trapezoid motion profile - */ - trapezoid_profile_segment_t calculate_next_segment(double s, double v); +class TrapezoidProfile { +public: + /** + * @brief Construct a new Trapezoid Profile object + * + * @param max_v Maximum velocity the robot can run at + * @param accel Maximum acceleration of the robot + */ + TrapezoidProfile(double max_v, double accel); + + /** + * @brief Run the trapezoidal profile based on the time and distance that's + * elapsed + * + * @param time_s Time since start of movement + * @param pos_s The current position + * @return motion_t Position, velocity and acceleration + */ + motion_t calculate(double time_s, double pos_s); + + /** + * @brief Run the trapezoidal profile based on the time that's elapsed + * + * @param time_s Time since start of movement + * @return motion_t Position, velocity and acceleration + */ + motion_t calculate_time_based(double time_s); + + /** + * @brief set_endpts defines a start and end position + * + * @param start the starting position of the path + * @param end the ending position of the path + */ + void set_endpts(double start, double end); + + /** + * @brief set start and end velocities + * + * @param start the starting velocity of the path + * @param end the ending velocity of the path + */ + void set_vel_endpts(double start, double end); + + /** + * @brief set_accel sets the acceleration this profile will use (the left and + * right legs of the trapezoid) + * + * @param accel the acceleration amount to use + */ + void set_accel(double accel); + + /** + * @brief sets the maximum velocity for the profile (the height of the top of + * the trapezoid) + * + * @param max_v the maximum velocity the robot can travel at + */ + void set_max_v(double max_v); + + /** + * @brief uses the kinematic equations to and specified accel and max_v to + * figure out how long moving along the profile would take + * + * @return the time the path will take to travel + */ + double get_movement_time() const; + + double get_max_v() const; + double get_accel() const; + +private: + double si, sf; ///< the initial and final position of the profile + double vi, vf; ///< the initial and final velocity of the profile + double max_v; ///< the maximum velocity to travel at for this profile + double accel; ///< the rate of acceleration to use for this profile. + double duration; + + trapezoid_profile_segment_t segments[MAX_TRAPEZOID_PROFILE_SEGMENTS]; + int num_acceleration_phases; + + bool precalculated; ///< whether or not the segment array is up to date + + /** + * Attempt to generate the motion profile for the given parameters + * + * @return False if there was a problem with the parameters + */ + bool precalculate(); + + /** + * Calculate a trapezoid segment given a target velocity that accelerates to + * the given velocity + * + * @param si segment initial position + * @param vi segment initial velocity + * @param v_target target velocity + * @return a trapezoid_profile_segment_t that represents constant acceleration + * to the target velocity + */ + trapezoid_profile_segment_t calculate_kinetic_motion(double si, double vi, + double v_target); + + /** + * Calculate the next segment of the trapezoid motion profile + * + * @param s segment starting position + * @param v segment starting velocity + * @return the next segment of the trapezoid motion profile + */ + trapezoid_profile_segment_t calculate_next_segment(double s, double v); }; \ No newline at end of file diff --git a/include/utils/moving_average.h b/include/utils/moving_average.h index 099b5db..ed01819 100644 --- a/include/utils/moving_average.h +++ b/include/utils/moving_average.h @@ -50,13 +50,13 @@ class MovingAverage : public Filter * ^ * @param n the sample that will be added to the moving average. */ - void add_entry(double n); + void add_entry(double n) override; /** * Returns the average based off of all the samples collected so far * @return the calculated average. sum(samples)/numsamples */ - double get_value() const; + double get_value() const override; /** * How many samples the average is made from @@ -108,13 +108,13 @@ class ExponentialMovingAverage : public Filter * ^ * @param n the sample that will be added to the moving average. */ - void add_entry(double n); + void add_entry(double n) override; /** * Returns the average based off of all the samples collected so far * @return the calculated average. sum(samples)/numsamples */ - double get_value(); + double get_value() const override; /** * How many samples the average is made from diff --git a/src/subsystems/custom_encoder.cpp b/src/subsystems/custom_encoder.cpp index 64f3662..a8f3adc 100644 --- a/src/subsystems/custom_encoder.cpp +++ b/src/subsystems/custom_encoder.cpp @@ -19,16 +19,18 @@ void CustomEncoder::setPosition(double val, vex::rotationUnits units) double CustomEncoder::rotation(vex::rotationUnits units) { - if(units != vex::rotationUnits::raw) - return super::rotation(units) * tick_scalar; + if(units != vex::rotationUnits::raw) { + return super::rotation(units) * tick_scalar; +} return super::rotation(units); } double CustomEncoder::position(vex::rotationUnits units) { - if (units != vex::rotationUnits::raw) - return super::position(units) * tick_scalar; + if (units != vex::rotationUnits::raw) { + return super::position(units) * tick_scalar; +} return super::position(units); } diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index b740c58..eab2f74 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -95,9 +95,10 @@ void Flywheel::spin_raw(double speed, directionType dir) */ void Flywheel::spin_manual(double speed, directionType dir) { - if (!task_running) + if (!task_running) { motors.spin(dir, speed * 12, voltageUnits::volt); } +} /** * starts or sets the RPM thread at new value diff --git a/src/subsystems/mecanum_drive.cpp b/src/subsystems/mecanum_drive.cpp index 641fe57..793c1b9 100644 --- a/src/subsystems/mecanum_drive.cpp +++ b/src/subsystems/mecanum_drive.cpp @@ -127,8 +127,9 @@ bool MecanumDrive::auto_drive(double inches, double direction, double speed, boo drive_gyro_pid->set_target(0.0); } // reset only if lateral wheel exists - if(enable_wheel) - lateral_wheel->resetPosition(); + if(enable_wheel) { + lateral_wheel->resetPosition(); +} // Finish setting up the PID loop - max speed and position target drive_pid->set_limits(-fabs(speed), fabs(speed)); diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index 15a650a..2cd8328 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -3,34 +3,35 @@ /** * Construct a new Odometry Base object - * + * * @param is_async True to run constantly in the background, false to call update() manually */ OdometryBase::OdometryBase(bool is_async) : current_pos(zero_pos) { - if(is_async) - handle = new vex::task(background_task, (void*) this); + if (is_async) { + handle = new vex::task(background_task, (void *)this); +} } /** * Function that runs in the background task. This function pointer is passed - * to the vex::task constructor. - * + * to the vex::task constructor. + * * @param ptr Pointer to OdometryBase object * @return Required integer return code. Unused. */ -int OdometryBase::background_task(void* ptr) +int OdometryBase::background_task(void *ptr) { - OdometryBase &obj = *((OdometryBase*) ptr); - vexDelay(1000); - while(!obj.end_task) - { - obj.mut.lock(); - obj.update(); - obj.mut.unlock(); - } - - return 0; + OdometryBase &obj = *((OdometryBase *)ptr); + vexDelay(1000); + while (!obj.end_task) + { + obj.mut.lock(); + obj.update(); + obj.mut.unlock(); + } + + return 0; } /** @@ -44,30 +45,36 @@ void OdometryBase::end_async() } /** -* Gets the current position and rotation -*/ + * Gets the current position and rotation + */ pose_t OdometryBase::get_position(void) { - mut.lock(); + mut.lock(); - // Create a new struct to pass-by-value - pose_t out = current_pos; + // Create a new struct to pass-by-value + pose_t out = current_pos; - mut.unlock(); + mut.unlock(); - return out; + return out; } /** * Sets the current position of the robot */ -void OdometryBase::set_position(const pose_t& newpos) +void OdometryBase::set_position(const pose_t &newpos) { - mut.lock(); + mut.lock(); + + current_pos = newpos; + + mut.unlock(); +} - current_pos = newpos; +AutoCommand *OdometryBase::SetPositionCmd(const pose_t &newpos) +{ + return new FunctionCommand([&](){set_position(newpos); return true;}); - mut.unlock(); } /** @@ -80,7 +87,7 @@ double OdometryBase::pos_diff(pose_t start_pos, pose_t end_pos) { // Use the pythagorean theorem double retval = sqrt(pow(end_pos.x - start_pos.x, 2) + pow(end_pos.y - start_pos.y, 2)); - + return retval; } @@ -102,12 +109,14 @@ double OdometryBase::smallest_angle(double start_deg, double end_deg) double retval; // get the difference between 0 and 360 retval = fmod(end_deg - start_deg, 360.0); - if(retval < 0) + if (retval < 0) { retval += 360.0; +} // Get the closest angle, now between -180 (turn left) and +180 (turn right) - if(retval > 180) + if (retval > 180) { retval -= 360; +} return retval; } @@ -117,7 +126,7 @@ double OdometryBase::get_speed() mut.lock(); double retval = speed; mut.unlock(); - + return retval; } diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index 171c880..b910cff 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -1,47 +1,47 @@ #include "../core/include/subsystems/odometry/odometry_tank.h" /** -* Initialize the Odometry module, calculating position from the drive motors. -* @param left_side The left motors -* @param right_side The right motors -* @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained -* @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. -* @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). -*/ + * Initialize the Odometry module, calculating position from the drive motors. + * @param left_side The left motors + * @param right_side The right motors + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained + * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). + */ OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu, bool is_async) -: OdometryBase(is_async), left_side(&left_side), right_side(&right_side), left_custom_enc(NULL), right_custom_enc(NULL), left_vex_enc(NULL), right_vex_enc(NULL), imu(imu), config(config) + : OdometryBase(is_async), left_side(&left_side), right_side(&right_side), left_custom_enc(NULL), right_custom_enc(NULL), left_vex_enc(NULL), right_vex_enc(NULL), imu(imu), config(config) { } /** -* Initialize the Odometry module, calculating position from the drive motors. -* @param left_custom_enc The left custom encoder -* @param right_custom_enc The right custom encoder -* @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained -* @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. -* @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). -*/ + * Initialize the Odometry module, calculating position from the drive motors. + * @param left_custom_enc The left custom encoder + * @param right_custom_enc The right custom encoder + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained + * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). + */ OdometryTank::OdometryTank(CustomEncoder &left_custom_enc, CustomEncoder &right_custom_enc, robot_specs_t &config, vex::inertial *imu, bool is_async) -: OdometryBase(is_async), left_side(NULL), right_side(NULL), left_custom_enc(&left_custom_enc), right_custom_enc(&right_custom_enc), left_vex_enc(NULL), right_vex_enc(NULL), imu(imu), config(config) + : OdometryBase(is_async), left_side(NULL), right_side(NULL), left_custom_enc(&left_custom_enc), right_custom_enc(&right_custom_enc), left_vex_enc(NULL), right_vex_enc(NULL), imu(imu), config(config) { } /** -* Initialize the Odometry module, calculating position from the drive motors. -* @param left_vex_enc The left vex encoder -* @param right_vex_enc The right vex encoder -* @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained -* @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. -* @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). -*/ + * Initialize the Odometry module, calculating position from the drive motors. + * @param left_vex_enc The left vex encoder + * @param right_vex_enc The right vex encoder + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained + * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). + */ OdometryTank::OdometryTank(vex::encoder &left_vex_enc, vex::encoder &right_vex_enc, robot_specs_t &config, vex::inertial *imu, bool is_async) -: OdometryBase(is_async), left_side(NULL), right_side(NULL), left_custom_enc(NULL), right_custom_enc(NULL), left_vex_enc(&left_vex_enc), right_vex_enc(&right_vex_enc), imu(imu), config(config) + : OdometryBase(is_async), left_side(NULL), right_side(NULL), left_custom_enc(NULL), right_custom_enc(NULL), left_vex_enc(&left_vex_enc), right_vex_enc(&right_vex_enc), imu(imu), config(config) { } /** * Resets the position and rotational data to the input. - * + * */ void OdometryTank::set_position(const pose_t &newpos) { @@ -58,85 +58,87 @@ void OdometryTank::set_position(const pose_t &newpos) */ pose_t OdometryTank::update() { - double lside_revs = 0, rside_revs = 0; - - if(left_side != NULL && right_side != NULL) - { - lside_revs = left_side->position(vex::rotationUnits::rev) / config.odom_gear_ratio; - rside_revs = right_side->position(vex::rotationUnits::rev) / config.odom_gear_ratio; - }else if(left_custom_enc != NULL && right_custom_enc != NULL) - { - lside_revs = left_custom_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; - rside_revs = right_custom_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; - }else if(left_vex_enc != NULL && right_vex_enc != NULL) - { - lside_revs = left_vex_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; - rside_revs = right_vex_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; - } - - double angle = 0; - - // If the IMU data was passed in, use it for rotational data - if(imu == NULL || imu->installed() == false) - { - // Get the difference in distance driven between the two sides - // Uses the absolute position of the encoders, so resetting them will result in - // a bad angle. - // Get the arclength of the turning circle of the robot - double distance_diff = (rside_revs - lside_revs) * PI * config.odom_wheel_diam; - - - //Use the arclength formula to calculate the angle. Add 90 to make "0 degrees" to starboard - angle = ((180.0 / PI) * (distance_diff / config.dist_between_wheels)) + 90; - - // printf("angle: %f, ", (180.0 / PI) * (distance_diff / config.dist_between_wheels)); - - } else - { - // Translate "0 forward and clockwise positive" to "90 forward and CCW negative" - angle = -imu->rotation(vex::rotationUnits::deg) + 90; - } - - // Offset the angle, if we've done a set_position - angle += rotation_offset; - - //Limit the angle betwen 0 and 360. - //fmod (floating-point modulo) gets it between -359 and +359, so tack on another 360 if it's negative. - angle = fmod(angle, 360.0); - if(angle < 0) - angle += 360; - - current_pos = calculate_new_pos(config, current_pos, lside_revs, rside_revs, angle); - - - static pose_t last_pos = current_pos; - static double last_speed = 0; - static double last_ang_speed = 0; - static timer tmr; - bool update_vel_accel = tmr.time(sec) > 0.1; - - // This loop runs too fast. Only check at LEAST every 1/10th sec - if(update_vel_accel) - { - // Calculate robot velocity - speed = pos_diff(current_pos, last_pos) / tmr.time(sec); - - // Calculate robot acceleration - accel = (speed - last_speed) / tmr.time(sec); - - // Calculate robot angular velocity (deg/sec) - ang_speed_deg = smallest_angle(current_pos.rot, last_pos.rot) / tmr.time(sec); - - // Calculate robot angular acceleration (deg/sec^2) - ang_accel_deg = (ang_speed_deg - last_ang_speed) / tmr.time(sec); - - tmr.reset(); - last_pos = current_pos; - last_speed = speed; - last_ang_speed = ang_speed_deg; - } - - return current_pos; + double lside_revs = 0, rside_revs = 0; + + if (left_side != NULL && right_side != NULL) + { + lside_revs = left_side->position(vex::rotationUnits::rev) / config.odom_gear_ratio; + rside_revs = right_side->position(vex::rotationUnits::rev) / config.odom_gear_ratio; + } + else if (left_custom_enc != NULL && right_custom_enc != NULL) + { + lside_revs = left_custom_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; + rside_revs = right_custom_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; + } + else if (left_vex_enc != NULL && right_vex_enc != NULL) + { + lside_revs = left_vex_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; + rside_revs = right_vex_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; + } + + double angle = 0; + + // If the IMU data was passed in, use it for rotational data + if (imu == NULL || imu->installed() == false) + { + // Get the difference in distance driven between the two sides + // Uses the absolute position of the encoders, so resetting them will result in + // a bad angle. + // Get the arclength of the turning circle of the robot + double distance_diff = (rside_revs - lside_revs) * PI * config.odom_wheel_diam; + + // Use the arclength formula to calculate the angle. Add 90 to make "0 degrees" to starboard + angle = ((180.0 / PI) * (distance_diff / config.dist_between_wheels)) + 90; + + // printf("angle: %f, ", (180.0 / PI) * (distance_diff / config.dist_between_wheels)); + } + else + { + // Translate "0 forward and clockwise positive" to "90 forward and CCW negative" + angle = -imu->rotation(vex::rotationUnits::deg) + 90; + } + + // Offset the angle, if we've done a set_position + angle += rotation_offset; + + // Limit the angle betwen 0 and 360. + // fmod (floating-point modulo) gets it between -359 and +359, so tack on another 360 if it's negative. + angle = fmod(angle, 360.0); + if (angle < 0) { + angle += 360; +} + + current_pos = calculate_new_pos(config, current_pos, lside_revs, rside_revs, angle); + + static pose_t last_pos = current_pos; + static double last_speed = 0; + static double last_ang_speed = 0; + static timer tmr; + bool update_vel_accel = tmr.time(sec) > 0.02; + + // This loop runs too fast. Only check at LEAST every 1/10th sec + if (update_vel_accel) + { + // Calculate robot velocity + double this_speed = pos_diff(current_pos, last_pos) / tmr.time(sec); + ema.add_entry(this_speed); + speed = ema.get_value(); + // Calculate robot acceleration + accel = (speed - last_speed) / tmr.time(sec); + + // Calculate robot angular velocity (deg/sec) + ang_speed_deg = smallest_angle(current_pos.rot, last_pos.rot) / tmr.time(sec); + + // Calculate robot angular acceleration (deg/sec^2) + ang_accel_deg = (ang_speed_deg - last_ang_speed) / tmr.time(sec); + + tmr.reset(); + last_pos = current_pos; + last_speed = speed; + last_ang_speed = ang_speed_deg; + } + + return current_pos; } /** @@ -145,36 +147,36 @@ pose_t OdometryTank::update() */ pose_t OdometryTank::calculate_new_pos(robot_specs_t &config, pose_t &curr_pos, double lside_revs, double rside_revs, double angle_deg) { - pose_t new_pos; + pose_t new_pos; + + static double stored_lside_revs = lside_revs; + static double stored_rside_revs = rside_revs; - static double stored_lside_revs = lside_revs; - static double stored_rside_revs = rside_revs; + // Convert the revolutions into "change in distance", and average the values for a "distance driven" + double lside_diff = (lside_revs - stored_lside_revs) * PI * config.odom_wheel_diam; + double rside_diff = (rside_revs - stored_rside_revs) * PI * config.odom_wheel_diam; + double dist_driven = (lside_diff + rside_diff) / 2.0; - // Convert the revolutions into "change in distance", and average the values for a "distance driven" - double lside_diff = (lside_revs - stored_lside_revs) * PI * config.odom_wheel_diam; - double rside_diff = (rside_revs - stored_rside_revs) * PI * config.odom_wheel_diam; - double dist_driven = (lside_diff + rside_diff) / 2.0; + double angle = angle_deg * PI / 180.0; // Degrees to radians - double angle = angle_deg * PI / 180.0; // Degrees to radians + // Create a vector from the change in distance in the current direction of the robot + // deg2rad((smallest_angle(curr_pos.rot, angle_deg)/2 + curr_pos.rot, dist_driven) + Vector2D chg_vec(angle, dist_driven); - // Create a vector from the change in distance in the current direction of the robot - //deg2rad((smallest_angle(curr_pos.rot, angle_deg)/2 + curr_pos.rot, dist_driven) - Vector2D chg_vec(angle, dist_driven); - - // Create a vector from the current position in reference to X,Y=0,0 - point_t curr_point = {.x = curr_pos.x, .y = curr_pos.y}; - Vector2D curr_vec(curr_point); + // Create a vector from the current position in reference to X,Y=0,0 + point_t curr_point = {.x = curr_pos.x, .y = curr_pos.y}; + Vector2D curr_vec(curr_point); - // Tack on the "difference" vector to the current vector - Vector2D new_vec = curr_vec + chg_vec; + // Tack on the "difference" vector to the current vector + Vector2D new_vec = curr_vec + chg_vec; - new_pos.x = new_vec.get_x(); - new_pos.y = new_vec.get_y(); - new_pos.rot = angle_deg; + new_pos.x = new_vec.get_x(); + new_pos.y = new_vec.get_y(); + new_pos.rot = angle_deg; - // Store the left and right encoder values to find the difference in the next iteration - stored_lside_revs = lside_revs; - stored_rside_revs = rside_revs; + // Store the left and right encoder values to find the difference in the next iteration + stored_lside_revs = lside_revs; + stored_rside_revs = rside_revs; - return new_pos; + return new_pos; } \ No newline at end of file diff --git a/src/subsystems/screen.cpp b/src/subsystems/screen.cpp index 43066f3..6518bd0 100644 --- a/src/subsystems/screen.cpp +++ b/src/subsystems/screen.cpp @@ -1,450 +1,456 @@ #include "../core/include/subsystems/screen.h" #include "../core/include/utils/math_util.h" -namespace screen -{ - /** - * @brief The ScreenData class holds the data that will be passed to the - * screen thread - * you probably shouldnt have to use it - */ - struct ScreenData - { - ScreenData(const std::vector &m_pages, int m_page, vex::brain::lcd &m_screen) - : pages(m_pages), page(m_page), screen(m_screen) {} - std::vector pages; - int page = 0; - vex::brain::lcd screen; - }; - - static vex::thread *screen_thread = nullptr; - static bool running = false; - static int screen_thread_func(void *screen_data_v); - - /// @brief start_screen begins a screen. only call this once per program (a - /// good place is vexcodeInit) - /// This is a set and forget type function. You don't have to wait on it or - /// start it in a new thread - /// @param screen the brain screen - /// @param pages the list of pages in your UI slideshow - /// @param first_page the page to start on (by default 0) - void start_screen(vex::brain::lcd &screen, std::vector pages, - int first_page) - { - if (pages.size() == 0) - { - printf("No pages, not starting screen"); - return; - } - first_page %= pages.size(); - - if (running) - { - printf("THERE IS ALREADY A SCREEN THREAD RUNNING\n"); - return; - } - ScreenData *data = new ScreenData{pages, first_page, screen}; - - screen_thread = new vex::thread(screen_thread_func, static_cast(data)); +namespace screen { +void draw_label(vex::brain::lcd &scr, std::string lbl, ScreenRect rect) { + uint32_t height = scr.getStringHeight(lbl.c_str()); + scr.printAt(rect.x1 + 1, rect.y1 + height, true, "%s", lbl.c_str()); +} +void draw_widget(vex::brain::lcd &scr, WidgetConfig &widget, ScreenRect rect) { + switch (widget.type) { + case WidgetConfig::Type::Col: + case WidgetConfig::Type::Row: + case WidgetConfig::Type::Slider: + case WidgetConfig::Type::Button: + case WidgetConfig::Type::Checkbox: + case WidgetConfig::Type::Graph: + printf("unimplemented\n"); + break; + case WidgetConfig::Type::Text: + draw_label(scr, widget.config.text.text(), rect); + break; + case WidgetConfig::Type::Label: + draw_label(scr, widget.config.label.label, rect); + break; + } +} + +/** + * @brief The ScreenData class holds the data that will be passed to the + * screen thread + * you probably shouldnt have to use it + */ +struct ScreenData { + ScreenData(const std::vector &m_pages, int m_page, + vex::brain::lcd &m_screen) + : pages(m_pages), page(m_page), screen(m_screen) {} + std::vector pages; + int page = 0; + vex::brain::lcd screen; +}; + +static vex::thread *screen_thread = nullptr; +static bool running = false; +static int screen_thread_func(void *screen_data_v); +static ScreenData *screen_data_ptr; + +/// @brief start_screen begins a screen. only call this once per program (a +/// good place is vexcodeInit) +/// This is a set and forget type function. You don't have to wait on it or +/// start it in a new thread +/// @param screen the brain screen +/// @param pages the list of pages in your UI slideshow +/// @param first_page the page to start on (by default 0) +void start_screen(vex::brain::lcd &screen, std::vector pages, + int first_page) { + if (pages.size() == 0) { + printf("No pages, not starting screen"); + return; + } + first_page %= pages.size(); + + if (running) { + printf("THERE IS ALREADY A SCREEN THREAD RUNNING\n"); + return; + } + + ScreenData *data = new ScreenData{pages, first_page, screen}; + + screen_thread = + new vex::thread(screen_thread_func, static_cast(data)); +} + +void stop_screen() { running = false; } + +void prev_page() { + screen_data_ptr->page--; + if (screen_data_ptr->page < 0) { + screen_data_ptr->page += screen_data_ptr->pages.size(); + } +} +void next_page() { + screen_data_ptr->page++; + screen_data_ptr->page %= screen_data_ptr->pages.size(); +} + +/** + * @brief runs the screen thread + * This should only be called by start_screen + * If you are calling this, maybe don't + */ +int screen_thread_func(void *screen_data_v) { + ScreenData &screen_data = *static_cast(screen_data_v); + screen_data_ptr = static_cast(screen_data_v); + running = true; + unsigned int frame = 0; + + bool was_pressed = false; + int x_press = 0; + int y_press = 0; + + while (running) { + Page *front_page = screen_data.pages[screen_data.page]; + bool pressing = screen_data.screen.pressing(); + + if (pressing) { + pressing = true; + x_press = screen_data.screen.xPosition(); + y_press = screen_data.screen.yPosition(); } + bool just_pressed = pressing && !was_pressed; - void stop_screen() { running = false; } - - /** - * @brief runs the screen thread - * This should only be called by start_screen - * If you are calling this, maybe don't - */ - int screen_thread_func(void *screen_data_v) - { - ScreenData screen_data = *static_cast(screen_data_v); - running = true; - unsigned int frame = 0; - - bool was_pressed = false; - int x_press = 0; - int y_press = 0; - - while (running) - { - Page *front_page = screen_data.pages[screen_data.page]; - bool pressing = screen_data.screen.pressing(); - - if (pressing) - { - pressing = true; - x_press = screen_data.screen.xPosition(); - y_press = screen_data.screen.yPosition(); - } - bool just_pressed = pressing && !was_pressed; - - if (just_pressed && x_press < 40) - { - screen_data.page--; - if (screen_data.page < 0) - { - screen_data.page += screen_data.pages.size(); - } - } - if (just_pressed && x_press > 440) - { - screen_data.page++; - screen_data.page %= screen_data.pages.size(); - } - - // Update all pages - for (auto page : screen_data.pages) - { - if (page == front_page) - { - page->update(was_pressed, x_press, y_press); - } - else - { - page->update(false, 0, 0); - } - } - - // Draw First Page - if (frame % 2 == 0) - { - screen_data.screen.clearScreen(vex::color::black); - screen_data.screen.setPenColor("#FFFFFF"); - screen_data.screen.setFillColor("#000000"); - front_page->draw(screen_data.screen, false, frame / 5); - - // Draw side boxes - screen_data.screen.setPenColor("#202020"); - screen_data.screen.setFillColor("#202020"); - screen_data.screen.drawRectangle(0, 0, 40, 240); - screen_data.screen.drawRectangle(440, 0, 40, 240); - screen_data.screen.setPenColor("#FFFFFF"); - // left arrow - screen_data.screen.drawLine(30, 100, 15, 120); - screen_data.screen.drawLine(30, 140, 15, 120); - // right arrow - screen_data.screen.drawLine(450, 100, 465, 120); - screen_data.screen.drawLine(450, 140, 465, 120); - } - - screen_data.screen.render(); - frame++; - was_pressed = pressing; - vexDelay(5); - } - - return 0; + if (just_pressed && x_press < 40) { + screen_data.page--; + if (screen_data.page < 0) { + screen_data.page += screen_data.pages.size(); + } } - /** - * @brief FunctionPage - * @param update_f drawing function - * @param draw_f drawing function - */ - FunctionPage::FunctionPage(update_func_t update_f, draw_func_t draw_f) - : update_f(update_f), draw_f(draw_f) - { + if (just_pressed && x_press > 440) { + screen_data.page++; + screen_data.page %= screen_data.pages.size(); } - /// @brief update uses the supplied update function to update this page - void FunctionPage::update(bool was_pressed, int x, int y) - { - update_f(was_pressed, x, y); - } - /// @brief draw uses the supplied draw function to draw to the screen - void FunctionPage::draw(vex::brain::lcd &screen, bool first_draw, - unsigned int frame_number) - { - draw_f(screen, first_draw, frame_number); - } - - StatsPage::StatsPage(std::map motors) : motors(motors) {} - void StatsPage::update(bool was_pressed, int x, int y) - { - (void)x; - (void)y; - (void)was_pressed; - } - void StatsPage::draw_motor_stats(const std::string &name, vex::motor &mot, unsigned int frame, int x, int y, vex::brain::lcd &scr) - { - const vex::color hot_col = vex::color(120, 0, 0); - const vex::color med_col = vex::color(140, 100, 0); - const vex::color ok_col = vex::black; - const vex::color not_plugged_in_col = vex::color(255, 0, 0); - bool installed = mot.installed(); - double temp = 0; - int port = mot.index() + 1; - vex::color col = ok_col; - if (installed) - { - temp = mot.temperature(vex::temperatureUnits::celsius); - } - - if (temp > 40) - { - col = med_col; - } - else if (temp > 50) - { - col = hot_col; - } - if (!installed && frame % 2 == 0) - { - col = not_plugged_in_col; - } - - scr.drawRectangle(x, y, row_width, row_height, col); - scr.printAt(x + 2, y + 16, false, " %2d %2.0fC %.7s", port, temp, name.c_str()); - } - void StatsPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], unsigned int frame_number [[maybe_unused]]) - { - int num = 0; - int x = 40; - int y = y_start + row_height; - scr.setPenWidth(1); - - scr.drawRectangle(x, y_start, row_width, row_height); - scr.printAt(x, y_start + 16, false, " port temp name"); - for (auto &kv : motors) - { - if (num > per_column) - { - scr.drawRectangle(x + row_width, y_start, row_width, row_height); - scr.printAt(x + row_width, y_start + 16, false, " port temp name"); - - y = y_start + row_height; - x += row_width; - num = 0; - } - - draw_motor_stats(kv.first, kv.second, frame_number, x, y, scr); - y += row_height; - num++; - } - vex::brain b; - scr.printAt(50, 220, "Battery: %2.1fv %2.0fC %d%%", b.Battery.voltage(), b.Battery.temperature(vex::temperatureUnits::celsius), b.Battery.capacity()); + // Update all pages + for (auto page : screen_data.pages) { + if (page == front_page) { + page->update(was_pressed, x_press, y_press); + } else { + page->update(false, 0, 0); + } } - OdometryPage::OdometryPage(OdometryBase &odom, double width, double height, bool do_trail) : odom(odom), robot_width(width), robot_height(height), do_trail(do_trail) - { - vex::brain b; - if (b.SDcard.exists(field_filename)) - { - buf_size = b.SDcard.size(field_filename); - buf = (uint8_t *)malloc(buf_size); - b.SDcard.loadfile(field_filename, buf, buf_size); - } - pose_t pos = odom.get_position(); - for (int i = 0; i < path_len; i++) - { - path[i] = pos; - } + // Draw First Page + if (frame % 2 == 0) { + screen_data.screen.clearScreen(vex::color::black); + screen_data.screen.setPenColor("#FFFFFF"); + screen_data.screen.setFillColor("#000000"); + front_page->draw(screen_data.screen, false, frame / 5); + + // Draw side boxes + screen_data.screen.setPenColor("#202020"); + screen_data.screen.setFillColor("#202020"); + screen_data.screen.drawRectangle(0, 0, 40, 240); + screen_data.screen.drawRectangle(440, 0, 40, 240); + screen_data.screen.setPenColor("#FFFFFF"); + // left arrow + screen_data.screen.drawLine(30, 100, 15, 120); + screen_data.screen.drawLine(30, 140, 15, 120); + // right arrow + screen_data.screen.drawLine(450, 100, 465, 120); + screen_data.screen.drawLine(450, 140, 465, 120); } - int in_to_px(double in) - { - double p = in / (6.0 * 24.0); - return (int)(p * 240); - } - - void OdometryPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], unsigned int frame_number [[maybe_unused]]) - { - pose_t pose = odom.get_position(); - path[path_index] = pose; - - if (do_trail && frame_number % 5 == 0) - { - path_index++; - path_index %= path_len; - } - - auto to_px = [](const point_t p) -> point_t - { - return {(double)in_to_px(p.x) + 200, (double)in_to_px(-p.y) + 240}; - }; - - auto draw_line = [to_px, &scr](const point_t from, const point_t to) - { - scr.drawLine((int)to_px(from).x, (int)to_px(from).y, (int)to_px(to).x, (int)to_px(to).y); - }; - - point_t pos = pose.get_point(); - fflush(stdout); - scr.printAt(45, 30, "(%.2f, %.2f)", pose.x, pose.y); - scr.printAt(45, 50, "%.2f deg", pose.rot); - - if (buf == nullptr) - { - scr.printAt(180, 110, "Field Image Not Found"); - return; - } - - scr.drawImageFromBuffer(buf, 200, 0, buf_size); - - point_t pos_px = to_px(pos); - scr.drawCircle((int)pos_px.x, (int)pos_px.y, 3, vex::color::white); - - if (do_trail) - { - pose_t last_pos = path[(path_index + 1) % path_len]; - for (int i = path_index + 2; i < path_index + path_len; i++) - { - int j = i % path_len; - pose_t pose = path[j]; - scr.setPenWidth(2); - scr.setPenColor(vex::color(255, 255, 80)); - draw_line(pose.get_point(), last_pos.get_point()); - last_pos = pose; - } - } - scr.setPenColor(vex::color::white); - - Mat2 mat = Mat2::FromRotationDegrees(pose.rot - 90); - const point_t to_left = point_t{-robot_width / 2.0, 0}; - const point_t to_front = point_t{0.0, robot_height / 2.0}; - - const point_t fl = pos + mat * (+to_left + to_front); - const point_t fr = pos + mat * (-to_left + to_front); - const point_t bl = pos + mat * (+to_left - to_front); - const point_t br = pos + mat * (-to_left - to_front); - const point_t front = pos + mat * (to_front * 2.0); - - draw_line(fl, fr); - draw_line(fr, br); - draw_line(br, bl); - draw_line(bl, fl); - - draw_line(pos, front); - } - void OdometryPage::update(bool was_pressed, int x, int y) - { - (void)x; - (void)y; - (void)was_pressed; - } - - bool SliderWidget::update(bool was_pressed, int x, int y) - { - const double margin = 10.0; - if (was_pressed) - { - double dx = x; - double dy = y; - if (rect.contains(point_t{dx, dy})) - { - double pct = (dx - rect.min.x - margin) / (rect.dimensions().x - 2 * margin); - pct = clamp(pct, 0.0, 1.0); - value = (low + pct * (high - low)); - } - return true; - } - return false; - } - void SliderWidget::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], unsigned int frame_number [[maybe_unused]]) - { - if (rect.height() <= 0) - { - printf("Slider: %s has no height. Cant use it.", name.c_str()); - } - double xl = rect.min.x; - double xh = rect.max.x; - double xmid = (xl + xh) / 2.0; - double y = rect.min.y + rect.height() / 2; - const double margin = 5.0; - - scr.setPenColor(vex::color(50, 50, 50)); - scr.setFillColor(vex::color(50, 50, 50)); - scr.setPenWidth(1); - - scr.drawRectangle(rect.min.x, rect.min.y, rect.dimensions().x, rect.dimensions().y); - - scr.setPenColor(vex::color(200, 200, 200)); - scr.setPenWidth(4); - - scr.drawLine(xl + margin, y, xh - margin, y); - - double pct = (value - low) / (high - low); - double vx = pct * (rect.dimensions().x - (2 * margin)) + rect.min.x + margin; - const double handle_width = 4; - const double handle_height = 4; - - scr.drawRectangle(vx - (handle_width / 2), y - (handle_height / 2), handle_width, handle_height); - int text_w = scr.getStringWidth((name + " ").c_str()); - scr.printAt(xmid - text_w / 2, y - 15, false, "%s: %.5f", name.c_str(), value); + screen_data.screen.render(); + frame++; + was_pressed = pressing; + vexDelay(5); + } + + return 0; +} +/** + * @brief FunctionPage + * @param update_f drawing function + * @param draw_f drawing function + */ +FunctionPage::FunctionPage(update_func_t update_f, draw_func_t draw_f) + : update_f(update_f), draw_f(draw_f) {} + +/// @brief update uses the supplied update function to update this page +void FunctionPage::update(bool was_pressed, int x, int y) { + update_f(was_pressed, x, y); +} +/// @brief draw uses the supplied draw function to draw to the screen +void FunctionPage::draw(vex::brain::lcd &screen, bool first_draw, + unsigned int frame_number) { + draw_f(screen, first_draw, frame_number); +} + +StatsPage::StatsPage(std::map motors) + : motors(motors) {} +void StatsPage::update(bool was_pressed, int x, int y) { + (void)x; + (void)y; + (void)was_pressed; +} +void StatsPage::draw_motor_stats(const std::string &name, vex::motor &mot, + unsigned int frame, int x, int y, + vex::brain::lcd &scr) { + const vex::color hot_col = vex::color(120, 0, 0); + const vex::color med_col = vex::color(140, 100, 0); + const vex::color ok_col = vex::black; + const vex::color not_plugged_in_col = vex::color(255, 0, 0); + bool installed = mot.installed(); + double temp = 0; + int port = mot.index() + 1; + vex::color col = ok_col; + if (installed) { + temp = mot.temperature(vex::temperatureUnits::celsius); + } + + if (temp > 40) { + col = med_col; + } else if (temp > 50) { + col = hot_col; + } + if (!installed && frame % 2 == 0) { + col = not_plugged_in_col; + } + + scr.drawRectangle(x, y, row_width, row_height, col); + scr.printAt(x + 2, y + 16, false, " %2d %2.0fC %.7s", port, temp, + name.c_str()); +} +void StatsPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], + unsigned int frame_number [[maybe_unused]]) { + int num = 0; + int x = 40; + int y = y_start + row_height; + scr.setPenWidth(1); + + scr.drawRectangle(x, y_start, row_width, row_height); + scr.printAt(x, y_start + 16, false, " port temp name"); + for (auto &kv : motors) { + if (num > per_column) { + scr.drawRectangle(x + row_width, y_start, row_width, row_height); + scr.printAt(x + row_width, y_start + 16, false, " port temp name"); + + y = y_start + row_height; + x += row_width; + num = 0; } - bool ButtonWidget::update(bool was_pressed, int x, int y) - { - if (was_pressed && !was_pressed_last && rect.contains({(double)x, (double)y})) - { - onpress(); - was_pressed_last = was_pressed; - return true; - } - was_pressed_last = was_pressed; - return false; + draw_motor_stats(kv.first, kv.second, frame_number, x, y, scr); + y += row_height; + num++; + } + vex::brain b; + scr.printAt(50, 220, "Battery: %2.1fv %2.0fC %d%%", b.Battery.voltage(), + b.Battery.temperature(vex::temperatureUnits::celsius), + b.Battery.capacity()); +} + +OdometryPage::OdometryPage(OdometryBase &odom, double width, double height, + bool do_trail) + : odom(odom), robot_width(width), robot_height(height), do_trail(do_trail), + velocity_graph(30, 0.0, 0.0, {vex::green}, 1) { + vex::brain b; + if (b.SDcard.exists(field_filename)) { + buf_size = b.SDcard.size(field_filename); + buf = (uint8_t *)malloc(buf_size); + b.SDcard.loadfile(field_filename, buf, buf_size); + } + pose_t pos = odom.get_position(); + for (int i = 0; i < path_len; i++) { + path[i] = pos; + } +} + +int in_to_px(double in) { + double p = in / (6.0 * 24.0); + return (int)(p * 240); +} + +void OdometryPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], + unsigned int frame_number [[maybe_unused]]) { + pose_t pose = odom.get_position(); + path[path_index] = pose; + + if (do_trail && frame_number % 5 == 0) { + path_index++; + path_index %= path_len; + } + + auto to_px = [](const point_t p) -> point_t { + return {(double)in_to_px(p.x) + 200, (double)in_to_px(-p.y) + 240}; + }; + + auto draw_line = [to_px, &scr](const point_t from, const point_t to) { + scr.drawLine((int)to_px(from).x, (int)to_px(from).y, (int)to_px(to).x, + (int)to_px(to).y); + }; + + point_t pos = pose.get_point(); + fflush(stdout); + scr.printAt(45, 30, "(%.2f, %.2f)", pose.x, pose.y); + scr.printAt(45, 50, "%.2f deg", pose.rot); + + double speed = odom.get_speed(); + scr.printAt(45, 80, "%.2f speed", speed); + velocity_graph.add_samples({speed}); + velocity_graph.draw(scr, 30, 100, 170, 120); + + if (buf == nullptr) { + scr.printAt(180, 110, "Field Image Not Found"); + return; + } + + scr.drawImageFromBuffer(buf, 200, 0, buf_size); + + point_t pos_px = to_px(pos); + scr.drawCircle((int)pos_px.x, (int)pos_px.y, 3, vex::color::white); + + if (do_trail) { + pose_t last_pos = path[(path_index + 1) % path_len]; + for (int i = path_index + 2; i < path_index + path_len; i++) { + int j = i % path_len; + pose_t pose = path[j]; + scr.setPenWidth(2); + scr.setPenColor(vex::color(255, 255, 80)); + draw_line(pose.get_point(), last_pos.get_point()); + last_pos = pose; } - - void ButtonWidget::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], unsigned int frame_number [[maybe_unused]]) - { - scr.setPenColor(vex::white); - scr.setPenWidth(1); - scr.setFillColor(vex::color(50, 50, 50)); - scr.drawRectangle(rect.min.x, rect.min.y, rect.width(), rect.height()); - int w = scr.getStringWidth(name.c_str()); - int h = scr.getStringHeight(name.c_str()); - scr.printAt(rect.center().x - w / 2, rect.center().y + h / 2, name.c_str()); - } - - PIDPage::PIDPage( - PID &pid, std::string name, std::function onchange) - : cfg(pid.config), pid(pid), name(name), onchange(onchange), - p_slider(cfg.p, 0.0, 0.5, Rect{{60, 20}, {210, 60}}, "P"), - i_slider(cfg.i, 0.0, 0.05, Rect{{60, 80}, {180, 120}}, "I"), - d_slider(cfg.d, 0.0, 0.05, Rect{{60, 140}, {180, 180}}, "D"), - zero_i([this]() - { zero_i_f(); }, - Rect{{180, 80}, {220, 120}}, "0"), - zero_d([this]() - { zero_d_f(); }, - Rect{{180, 140}, {220, 180}}, "0"), - graph(40, 0, 0, {vex::red, vex::green}, 2) - { - } - - PIDPage::PIDPage(PIDFF &pidff, std::string name, std::function onchange) : PIDPage((pidff.pid), name, onchange) {} - - void PIDPage::update(bool was_pressed, int x, int y) - { - bool updated = false; - updated |= p_slider.update(was_pressed, x, y); - updated |= i_slider.update(was_pressed, x, y); - updated |= d_slider.update(was_pressed, x, y); - - updated |= zero_i.update(was_pressed, x, y); - updated |= zero_d.update(was_pressed, x, y); - if (updated) - { - onchange(); - } - } - void PIDPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], unsigned int frame_number [[maybe_unused]]) - { - p_slider.draw(scr, first_draw, frame_number); - i_slider.draw(scr, first_draw, frame_number); - d_slider.draw(scr, first_draw, frame_number); - zero_i.draw(scr, first_draw, frame_number); - zero_d.draw(scr, first_draw, frame_number); - - graph.add_samples({pid.get_target(), pid.get_sensor_val()}); - - graph.draw(scr, 230, 20, 200, 200); - - scr.setPenColor(vex::white); - scr.printAt(60, 215, false, "%s", name.c_str()); - - scr.setPenColor(vex::red); - scr.printAt(240, 20, false, "%.2f", pid.get_target()); - scr.setPenColor(vex::green); - scr.printAt(300, 20, false, "%.2f", pid.get_sensor_val()); + } + scr.setPenColor(vex::color::white); + + Mat2 mat = Mat2::FromRotationDegrees(pose.rot - 90); + const point_t to_left = point_t{-robot_width / 2.0, 0}; + const point_t to_front = point_t{0.0, robot_height / 2.0}; + + const point_t fl = pos + mat * (+to_left + to_front); + const point_t fr = pos + mat * (-to_left + to_front); + const point_t bl = pos + mat * (+to_left - to_front); + const point_t br = pos + mat * (-to_left - to_front); + const point_t front = pos + mat * (to_front * 2.0); + + draw_line(fl, fr); + draw_line(fr, br); + draw_line(br, bl); + draw_line(bl, fl); + + draw_line(pos, front); +} +void OdometryPage::update(bool was_pressed, int x, int y) { + (void)x; + (void)y; + (void)was_pressed; +} + +bool SliderWidget::update(bool was_pressed, int x, int y) { + const double margin = 10.0; + if (was_pressed) { + double dx = x; + double dy = y; + if (rect.contains(point_t{dx, dy})) { + double pct = + (dx - rect.min.x - margin) / (rect.dimensions().x - 2 * margin); + pct = clamp(pct, 0.0, 1.0); + value = (low + pct * (high - low)); } + return true; + } + return false; +} +void SliderWidget::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], + unsigned int frame_number [[maybe_unused]]) { + if (rect.height() <= 0) { + printf("Slider: %s has no height. Cant use it.", name.c_str()); + } + double xl = rect.min.x; + double xh = rect.max.x; + double xmid = (xl + xh) / 2.0; + double y = rect.min.y + rect.height() / 2; + const double margin = 5.0; + + scr.setPenColor(vex::color(50, 50, 50)); + scr.setFillColor(vex::color(50, 50, 50)); + scr.setPenWidth(1); + + scr.drawRectangle(rect.min.x, rect.min.y, rect.dimensions().x, + rect.dimensions().y); + + scr.setPenColor(vex::color(200, 200, 200)); + scr.setPenWidth(4); + + scr.drawLine(xl + margin, y, xh - margin, y); + + double pct = (value - low) / (high - low); + double vx = pct * (rect.dimensions().x - (2 * margin)) + rect.min.x + margin; + const double handle_width = 4; + const double handle_height = 4; + + scr.drawRectangle(vx - (handle_width / 2), y - (handle_height / 2), + handle_width, handle_height); + int text_w = scr.getStringWidth((name + " ").c_str()); + scr.printAt(xmid - text_w / 2, y - 15, false, "%s: %.5f", name.c_str(), + value); +} + +bool ButtonWidget::update(bool was_pressed, int x, int y) { + if (was_pressed && !was_pressed_last && + rect.contains({(double)x, (double)y})) { + onpress(); + was_pressed_last = was_pressed; + return true; + } + was_pressed_last = was_pressed; + return false; +} + +void ButtonWidget::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], + unsigned int frame_number [[maybe_unused]]) { + scr.setPenColor(vex::white); + scr.setPenWidth(1); + scr.setFillColor(vex::color(50, 50, 50)); + scr.drawRectangle(rect.min.x, rect.min.y, rect.width(), rect.height()); + int w = scr.getStringWidth(name.c_str()); + int h = scr.getStringHeight(name.c_str()); + scr.printAt(rect.center().x - w / 2, rect.center().y + h / 2, name.c_str()); +} + +PIDPage::PIDPage(PID &pid, std::string name, std::function onchange) + : cfg(pid.config), pid(pid), name(name), onchange(onchange), + p_slider(cfg.p, 0.0, 0.5, Rect{{60, 20}, {210, 60}}, "P"), + i_slider(cfg.i, 0.0, 0.05, Rect{{60, 80}, {180, 120}}, "I"), + d_slider(cfg.d, 0.0, 0.05, Rect{{60, 140}, {180, 180}}, "D"), + zero_i([this]() { zero_i_f(); }, Rect{{180, 80}, {220, 120}}, "0"), + zero_d([this]() { zero_d_f(); }, Rect{{180, 140}, {220, 180}}, "0"), + graph(40, 0, 0, {vex::red, vex::green}, 2) {} + +PIDPage::PIDPage(PIDFF &pidff, std::string name, + std::function onchange) + : PIDPage((pidff.pid), name, onchange) {} + +void PIDPage::update(bool was_pressed, int x, int y) { + bool updated = false; + updated |= p_slider.update(was_pressed, x, y); + updated |= i_slider.update(was_pressed, x, y); + updated |= d_slider.update(was_pressed, x, y); + + updated |= zero_i.update(was_pressed, x, y); + updated |= zero_d.update(was_pressed, x, y); + if (updated) { + onchange(); + } +} +void PIDPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], + unsigned int frame_number [[maybe_unused]]) { + p_slider.draw(scr, first_draw, frame_number); + i_slider.draw(scr, first_draw, frame_number); + d_slider.draw(scr, first_draw, frame_number); + zero_i.draw(scr, first_draw, frame_number); + zero_d.draw(scr, first_draw, frame_number); + + graph.add_samples({pid.get_target(), pid.get_sensor_val()}); + + graph.draw(scr, 230, 20, 200, 200); + + scr.setPenColor(vex::white); + scr.printAt(60, 215, false, "%s", name.c_str()); + + scr.setPenColor(vex::red); + scr.printAt(240, 20, false, "%.2f", pid.get_target()); + scr.setPenColor(vex::green); + scr.printAt(300, 20, false, "%.2f", pid.get_sensor_val()); +} } // namespace screen diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index d86f61f..ee0c64e 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -74,19 +74,78 @@ void TankDrive::stop() right_motors.stop(); } +void TankDrive::drive_tank_raw(double left_norm, double right_norm) +{ + left_motors.spin(directionType::fwd, left_norm * 12, voltageUnits::volt); + right_motors.spin(directionType::fwd, right_norm * 12, voltageUnits::volt); +} /** * Drive the robot using differential style controls. left_motors controls the left motors, * right_motors controls the right motors. * * left_motors and right_motors are in "percent": -1.0 -> 1.0 */ -void TankDrive::drive_tank(double left, double right, int power) +bool captured_position = false; +bool was_breaking = false; +void TankDrive::drive_tank(double left, double right, int power, BrakeType bt) { + left = modify_inputs(left, power); right = modify_inputs(right, power); + double brake_threshold = 0.05; + bool should_brake = (bt != BrakeType::None) && fabs(left) < brake_threshold && fabs(right) < brake_threshold; + + if (!should_brake) + { + drive_tank_raw(left, right); + was_breaking = false; + return; + } + if (should_brake && !was_breaking) + { + captured_position = false; + } + static PID::pid_config_t zero_vel_cfg = {.p = 0.005, .d = 0.0005}; + static PID zero_vel_pid = PID(zero_vel_cfg); - left_motors.spin(directionType::fwd, left * 12, voltageUnits::volt); - right_motors.spin(directionType::fwd, right * 12, voltageUnits::volt); + if (bt == BrakeType::ZeroVelocity) + { + zero_vel_pid.set_target(0); + double vel = left_motors.velocity(vex::velocityUnits::pct) + right_motors.velocity(vex::velocityUnits::pct); + double outp = zero_vel_pid.update(vel); + left_motors.spin(directionType::fwd, outp, voltageUnits::volt); + right_motors.spin(directionType::fwd, outp, voltageUnits::volt); + } + else if (bt == BrakeType::Smart) + { + static pose_t target_pose = {.x = 0.0, .y = 0.0, .rot = 0.0}; + + zero_vel_pid.set_target(0); + double vel = odometry->get_speed(); + if (fabs(vel) <= 0.01 && !captured_position) + { + target_pose = odometry->get_position(); + captured_position = true; + } + else if (captured_position) + { + double dist_to_target = odometry->pos_diff(target_pose, odometry->get_position()); + if (dist_to_target < 12.0) + { + drive_to_point(target_pose.x, target_pose.y, vex::fwd); + } else { + target_pose = odometry->get_position(); + reset_auto(); + } + } + else + { + double outp = zero_vel_pid.update(vel); + left_motors.spin(directionType::fwd, outp, voltageUnits::volt); + right_motors.spin(directionType::fwd, outp, voltageUnits::volt); + } + } + was_breaking = should_brake; } /** @@ -95,7 +154,7 @@ void TankDrive::drive_tank(double left, double right, int power) * * left_motors and right_motors are in "percent": -1.0 -> 1.0 */ -void TankDrive::drive_arcade(double forward_back, double left_right, int power) +void TankDrive::drive_arcade(double forward_back, double left_right, int power, BrakeType bt) { forward_back = modify_inputs(forward_back, power); left_right = modify_inputs(left_right, power); @@ -103,8 +162,7 @@ void TankDrive::drive_arcade(double forward_back, double left_right, int power) double left = forward_back + left_right; double right = forward_back - left_right; - left_motors.spin(directionType::fwd, left * 12, voltageUnits::volt); - right_motors.spin(directionType::fwd, right * 12, voltageUnits::volt); + drive_tank(left, right, 1, bt); } /** @@ -169,8 +227,9 @@ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedba */ bool TankDrive::drive_forward(double inches, directionType dir, double max_speed, double end_speed) { - if (drive_default_feedback != NULL) + if (drive_default_feedback != NULL) { return drive_forward(inches, dir, *drive_default_feedback, max_speed, end_speed); +} printf("tank_drive.cpp: Cannot run drive_forward without a feedback controller!\n"); fflush(stdout); @@ -224,8 +283,9 @@ bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_spee */ bool TankDrive::turn_degrees(double degrees, double max_speed, double end_speed) { - if (turn_default_feedback != NULL) + if (turn_default_feedback != NULL) { return turn_degrees(degrees, *turn_default_feedback, max_speed, end_speed); +} printf("tank_drive.cpp: Cannot run turn_degrees without a feedback controller!\n"); fflush(stdout); @@ -275,11 +335,10 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb pose_t end_pos = {.x = x, .y = y}; // Create a point (and vector) to get the direction - point_t pos_diff_pt = - { - .x = x - current_pos.x, - .y = y - current_pos.y - }; + point_t pos_diff_pt = + { + .x = x - current_pos.x, + .y = y - current_pos.y}; Vector2D point_vec(pos_diff_pt); @@ -295,16 +354,19 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb double angle = fmod(current_pos.rot - angle_to_point, 360.0); // Normalize the angle between 0 and 360 - if (angle > 360) + if (angle > 360) { angle -= 360; - if (angle < 0) +} + if (angle < 0) { angle += 360; +} // If the angle is behind the robot, report negative. - if (dir == directionType::fwd && angle > 90 && angle < 270) + if (dir == directionType::fwd && angle > 90 && angle < 270) { sign = -1; - else if (dir == directionType::rev && (angle < 90 || angle > 270)) + } else if (dir == directionType::rev && (angle < 90 || angle > 270)) { sign = -1; +} if (fabs(dist_left) < config.drive_correction_cutoff) { @@ -319,10 +381,11 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb double delta_heading = 0; // Going backwards "flips" the robot's current heading - if (dir == directionType::fwd) + if (dir == directionType::fwd) { delta_heading = OdometryBase::smallest_angle(current_pos.rot, heading); - else + } else { delta_heading = OdometryBase::smallest_angle(current_pos.rot - 180, heading); +} // Update the PID controllers with new information correction_pid.update(delta_heading); @@ -330,15 +393,17 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb // Disable correction when we're close enough to the point double correction = 0; - if (is_pure_pursuit || fabs(dist_left) > config.drive_correction_cutoff) + if (is_pure_pursuit || fabs(dist_left) > config.drive_correction_cutoff) { correction = correction_pid.get(); +} // Reverse the drive_pid output if we're going backwards double drive_pid_rval; - if (dir == directionType::rev) + if (dir == directionType::rev) { drive_pid_rval = feedback.get() * -1; - else + } else { drive_pid_rval = feedback.get(); +} // Combine the two pid outputs double lside = drive_pid_rval + correction; @@ -353,10 +418,10 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb // Check if the robot has reached it's destination if (feedback.is_on_target()) { - if (end_speed == 0) stop(); + if (end_speed == 0) { + stop(); +} func_initialized = false; - printf("Func unitililized\n"); - if (end_speed == 0) stop(); return true; } @@ -378,8 +443,9 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb */ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, double max_speed, double end_speed) { - if (drive_default_feedback != NULL) + if (drive_default_feedback != NULL) { return this->drive_to_point(x, y, dir, *drive_default_feedback, max_speed, end_speed); +} printf("tank_drive.cpp: Cannot run drive_to_point without a feedback controller!\n"); fflush(stdout); @@ -444,8 +510,9 @@ bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double m */ bool TankDrive::turn_to_heading(double heading_deg, double max_speed, double end_speed) { - if (turn_default_feedback != NULL) + if (turn_default_feedback != NULL) { return turn_to_heading(heading_deg, *turn_default_feedback, max_speed, end_speed); +} printf("tank_drive.cpp: Cannot run turn_to_heading without a feedback controller!\n"); fflush(stdout); @@ -478,7 +545,8 @@ double TankDrive::modify_inputs(double input, int power) bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback &feedback, double max_speed, double end_speed) { std::vector points = path.get_points(); - if (!path.is_valid()) { + if (!path.is_valid()) + { printf("WARNING: Unexpected pure pursuit path - some segments intersect or are too close\n"); } pose_t robot_pose = odometry->get_position(); @@ -486,10 +554,11 @@ bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback // On function initialization, send the path-length estimate to the feedback controller if (!func_initialized) { - if (dir != directionType::rev) + if (dir != directionType::rev) { feedback.init(-estimate_path_length(points), 0, odometry->get_speed(), end_speed); - else + } else { feedback.init(estimate_path_length(points), 0, odometry->get_speed(), end_speed); +} func_initialized = true; } @@ -505,10 +574,11 @@ bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback double angle_diff = 0; // Robot is facing forwards / backwards, change the bot's angle by 180 - if (dir != directionType::rev) + if (dir != directionType::rev) { angle_diff = OdometryBase::smallest_angle(robot_pose.rot, rad2deg(atan2(localized.y, localized.x))); - else + } else { angle_diff = OdometryBase::smallest_angle(robot_pose.rot + 180, rad2deg(atan2(localized.y, localized.x))); +} // Correct the robot's heading until the last cut-off if (!(is_last_point && robot_pose.get_point().dist(last_point) < config.drive_correction_cutoff)) @@ -521,10 +591,11 @@ bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback dist_remaining *= cos(angle_diff * (PI / 180.0)); } - if (dir != directionType::rev) + if (dir != directionType::rev) { feedback.update(-dist_remaining); - else + } else { feedback.update(dist_remaining); +} max_speed = fabs(max_speed); diff --git a/src/utils/command_structure/auto_command.cpp b/src/utils/command_structure/auto_command.cpp index b1869c6..86c8ac9 100644 --- a/src/utils/command_structure/auto_command.cpp +++ b/src/utils/command_structure/auto_command.cpp @@ -49,7 +49,7 @@ bool FunctionCondition::test() IfTimePassed::IfTimePassed(double time_s) : time_s(time_s), tmr() {} bool IfTimePassed::test() { - return (static_cast(tmr.time()) / 1000.0) > time_s; + return tmr.value() > time_s; } InOrder::InOrder(std::queue cmds) : cmds(cmds) @@ -66,7 +66,6 @@ bool InOrder::run() // outer loop finished if (cmds.size() == 0 && current_command == nullptr) { - printf("INORDER finished\n"); return true; } // retrieve and remove command at the front of the queue @@ -74,7 +73,6 @@ bool InOrder::run() { printf("TAKING INORDER: len = %d\n", cmds.size()); current_command = cmds.front(); - printf("Current command: %p\n", (void *)current_command); cmds.pop(); tmr.reset(); } @@ -88,7 +86,7 @@ bool InOrder::run() return false; // continue onto next command } - double seconds = static_cast(tmr.time()) / 1000.0; + double seconds = tmr.value(); bool should_timeout = current_command->timeout_seconds > 0.0; bool doTimeout = should_timeout && seconds > current_command->timeout_seconds; @@ -97,10 +95,10 @@ bool InOrder::run() doTimeout = doTimeout || current_command->true_to_end->test(); } - printf("."); // timeout if (doTimeout) { + printf("InOrder timed out\n"); current_command->on_timeout(); current_command = nullptr; return false; @@ -306,6 +304,8 @@ RepeatUntil::RepeatUntil(InOrder cmds, Condition *cond) : cmds(cmds), working_cm timeout_seconds = -1.0; } + + bool RepeatUntil::run() { bool finished = working_cmds->run(); @@ -324,6 +324,7 @@ bool RepeatUntil::run() } working_cmds = new InOrder(cmds); + return false; } diff --git a/src/utils/controls/feedforward.cpp b/src/utils/controls/feedforward.cpp index ef0d242..ba68dc2 100644 --- a/src/utils/controls/feedforward.cpp +++ b/src/utils/controls/feedforward.cpp @@ -53,8 +53,9 @@ FeedForward::ff_config_t tune_feedforward(vex::motor_group &motor, double pct, d double accel = accel_ma.get_value(); // For kV: - if(speed > max_speed) + if(speed > max_speed) { max_speed = speed; +} // For kA: // Filter out the acceleration dampening due to motor inductance diff --git a/src/utils/controls/motion_controller.cpp b/src/utils/controls/motion_controller.cpp index 8253f35..eba94cc 100644 --- a/src/utils/controls/motion_controller.cpp +++ b/src/utils/controls/motion_controller.cpp @@ -1,30 +1,31 @@ #include "../core/include/utils/controls/motion_controller.h" +#include "../core/include/subsystems/screen.h" #include "../core/include/utils/math_util.h" #include /** -* @brief Construct a new Motion Controller object -* -* @param config The definition of how the robot is able to move -* max_v Maximum velocity the movement is capable of -* accel Acceleration / deceleration of the movement -* pid_cfg Definitions of kP, kI, and kD -* ff_cfg Definitions of kS, kV, and kA -*/ + * @brief Construct a new Motion Controller object + * + * @param config The definition of how the robot is able to move + * max_v Maximum velocity the movement is capable of + * accel Acceleration / deceleration of the movement + * pid_cfg Definitions of kP, kI, and kD + * ff_cfg Definitions of kS, kV, and kA + */ MotionController::MotionController(m_profile_cfg_t &config) -: config(config), pid(config.pid_cfg), ff(config.ff_cfg), profile(config.max_v, config.accel) -{} + : config(config), pid(config.pid_cfg), ff(config.ff_cfg), + profile(config.max_v, config.accel) {} /** * @brief Initialize the motion profile for a new movement * This will also reset the PID and profile timers. * @param start_pt Movement starting position - * @param end_pt Movement ending posiiton + * @param end_pt Movement ending posiiton * @param start_vel Movement starting velocity * @param end_vel Movement ending velocity */ -void MotionController::init(double start_pt, double end_pt, double start_vel, double end_vel) -{ +void MotionController::init(double start_pt, double end_pt, double start_vel, + double end_vel) { profile.set_endpts(start_pt, end_pt); profile.set_vel_endpts(start_vel, end_vel); pid.reset(); @@ -34,93 +35,89 @@ void MotionController::init(double start_pt, double end_pt, double start_vel, do } /** -* @brief Update the motion profile with a new sensor value -* -* @param sensor_val Value from the sensor -* @return the motor input generated from the motion profile -*/ -double MotionController::update(double sensor_val) -{ + * @brief Update the motion profile with a new sensor value + * + * @param sensor_val Value from the sensor + * @return the motor input generated from the motion profile + */ +double MotionController::update(double sensor_val) { cur_motion = profile.calculate(tmr.time(timeUnits::sec), sensor_val); pid.set_target(cur_motion.pos); pid.update(sensor_val); this->current_pos = sensor_val; - out = pid.get() + ff.calculate(cur_motion.vel, cur_motion.accel, pid.get()); + out = pid.get() + ff.calculate(cur_motion.vel, cur_motion.accel, pid.get()); - if(lower_limit != upper_limit) + if (lower_limit != upper_limit) { out = clamp(out, lower_limit, upper_limit); - + } + return out; } /** * @return the last saved result from the feedback controller */ -double MotionController::get() -{ - return out; -} +double MotionController::get() { return out; } /** - * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. - * + * Clamp the upper and lower limits of the output. If both are 0, no limits + * should be applied. + * * @param lower Upper limit * @param upper Lower limit */ -void MotionController::set_limits(double lower, double upper) -{ +void MotionController::set_limits(double lower, double upper) { lower_limit = lower; upper_limit = upper; } -/** +/** * @return Whether or not the movement has finished, and the PID * confirms it is on target */ -bool MotionController::is_on_target() -{ - return (tmr.time(timeUnits::sec) > profile.get_movement_time()) && pid.is_on_target() && fabs(end_pt - current_pos) < pid.config.deadband; +bool MotionController::is_on_target() { + return (tmr.time(timeUnits::sec) > profile.get_movement_time()) && + pid.is_on_target() && + fabs(end_pt - current_pos) < pid.config.deadband; } /** * @return The current postion, velocity and acceleration setpoints -*/ -motion_t MotionController::get_motion() -{ - return cur_motion; -} + */ +motion_t MotionController::get_motion() const { return cur_motion; } /** - * This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. - * It does this by first calculating the kS (voltage to overcome static friction) by slowly increasing - * the voltage until it moves. - * - * Next is kV (voltage to sustain a certain velocity), where the robot will record it's steady-state velocity - * at 'pct' speed. - * - * Finally, kA (voltage needed to accelerate by a certain rate), where the robot will record the entire movement's - * velocity and acceleration, record a plot of [X=(pct-kV*V-kS), Y=(Acceleration)] along the movement, - * and since kA*Accel = pct-kV*V-kS, the reciprocal of the linear regression is the kA value. - * + * This method attempts to characterize the robot's drivetrain and automatically + * tune the feedforward. It does this by first calculating the kS (voltage to + * overcome static friction) by slowly increasing the voltage until it moves. + * + * Next is kV (voltage to sustain a certain velocity), where the robot will + * record it's steady-state velocity at 'pct' speed. + * + * Finally, kA (voltage needed to accelerate by a certain rate), where the robot + * will record the entire movement's velocity and acceleration, record a plot of + * [X=(pct-kV*V-kS), Y=(Acceleration)] along the movement, and since kA*Accel = + * pct-kV*V-kS, the reciprocal of the linear regression is the kA value. + * * @param drive The tankdrive to operate on * @param odometry The robot's odometry subsystem * @param pct Maximum velocity in percent (0->1.0) * @param duration Amount of time the robot should be moving for the test * @return A tuned feedforward object */ -FeedForward::ff_config_t MotionController::tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct, double duration) -{ +FeedForward::ff_config_t +MotionController::tune_feedforward(TankDrive &drive, OdometryTank &odometry, + double pct, double duration) { FeedForward::ff_config_t out = {}; - + pose_t start_pos = odometry.get_position(); // ========== kS Tuning ========= // Start at 0 and slowly increase the power until the robot starts moving double power = 0; - while(odometry.pos_diff(start_pos, odometry.get_position()) < 0.05) - { + while (odometry.pos_diff(start_pos, odometry.get_position()) < 0.05) { drive.drive_tank(power, power, 1); power += 0.001; vexDelay(100); @@ -128,22 +125,24 @@ FeedForward::ff_config_t MotionController::tune_feedforward(TankDrive &drive, Od out.kS = power; drive.stop(); - // ========== kV / kA Tuning ========= - std::vector> vel_data_points; // time, velocity + std::vector> vel_data_points; // time, velocity std::vector> accel_data_points; // time, accel double max_speed = 0; + double max_accel = 0; timer tmr; double time; MovingAverage vel_ma(3); MovingAverage accel_ma(3); - // Move the robot forward at a fixed percentage for X seconds while taking velocity and accel measurements - do - { + // Move the robot forward at a fixed percentage for X seconds while taking + // velocity and accel measurements + + drive.drive_tank(pct, pct, 1); + do { time = tmr.time(sec); vel_ma.add_entry(odometry.get_speed()); @@ -151,41 +150,100 @@ FeedForward::ff_config_t MotionController::tune_feedforward(TankDrive &drive, Od double speed = vel_ma.get_value(); double accel = accel_ma.get_value(); - // For kV: - if(speed > max_speed) + if (speed > max_speed) { max_speed = speed; + } + if (accel > max_accel) { + max_accel = accel; + } // For kA: // Filter out the acceleration dampening due to motor inductance - if(time > 0.25) - { + if (time > 0.25) { vel_data_points.push_back(std::pair(time, speed)); accel_data_points.push_back(std::pair(time, accel)); } - // Theoretical polling rate = 100hz (it won't be that much, cause, y'know, vex.) - vexDelay(10); - } while(time < duration); + // Theoretical polling rate = 100hz (it won't be that much, cause, + // y'know, vex.) + vexDelay(10); + } while (time < duration); drive.stop(); // Calculate kV (volts/12 per unit per second) out.kV = (pct - out.kS) / max_speed; + printf("Max speed achieved: %.4f\n", max_speed); + printf("Max accel achieved: %.4f\n", max_accel); + // Calculate kA (volts/12 per unit per second^2) std::vector> accel_per_pct; - for (int i = 0; i < vel_data_points.size(); i++) - { + for (int i = 0; i < vel_data_points.size(); i++) { accel_per_pct.push_back(std::pair( - pct - out.kS - (vel_data_points[i].second * out.kV), // Acceleration-causing percent (X variable) - accel_data_points[i].second // Measured acceleration (Y variable) - )); + pct - out.kS - + (vel_data_points[i].second * + out.kV), // Acceleration-causing percent (X variable) + accel_data_points[i].second // Measured acceleration (Y variable) + )); } - + // kA is the reciprocal of the slope of the linear regression double regres_slope = calculate_linear_regression(accel_per_pct).first; - out.kA = 1.0 / regres_slope; + out.kA = 1.0 / regres_slope; return out; +} + +class MotionControllerPage : public screen::Page { + public: + MotionControllerPage(const MotionController &mc) : mc(mc) {} + + void update(bool was_pressed, int x, int y) override {} + void draw(vex::brain::lcd &screen, bool first_draw, + unsigned int frame_number) { + const motion_t mot = mc.get_motion(); + + // Text - top right + screen.printAt(240, 20, "pos: %.2fin", mot.pos); + screen.printAt(240, 40, "vel: %.2fin", mot.vel); + screen.printAt(240, 60, "acc: %.2fin", mot.accel); + screen.printAt(240, 80, "%.2fs of %.2fs", mc.tmr.value(), + mc.profile.get_movement_time()); + + // Trapezoid - bottom right + const int32_t trap_width = 200; + const int32_t trap_height = 98; + const double seconds = mc.tmr.value(); + const double full_time = mc.profile.get_movement_time(); + const double x_pct = seconds / full_time; + const double y_pct = mot.vel / mc.profile.get_max_v(); + const int32_t x_pos = (int32_t)(x_pct * trap_width) + 240; + const int32_t y_pos = (int32_t)(-y_pct * trap_height) + 100; + const int32_t max_vel_y = 120; + const int32_t end_acc_x = 260; + const int32_t start_dec_x = 420; + + // trapezoid + screen.setPenColor(vex::red); + // accelerating + screen.drawLine(240, 200, end_acc_x, max_vel_y); + // staying + screen.drawLine(end_acc_x, max_vel_y, start_dec_x, max_vel_y); + // decellerating + screen.drawLine(440, 200, start_dec_x, max_vel_y); + + // dot where we are + screen.setFillColor(vex::red); + screen.setPenColor(vex::white); + screen.drawCircle(x_pos, y_pos, 3); + } + + private: + const MotionController &mc; +}; + +screen::Page *MotionController::Page() { + return new MotionControllerPage(*this); } \ No newline at end of file diff --git a/src/utils/controls/pid.cpp b/src/utils/controls/pid.cpp index 21a7475..2c46495 100644 --- a/src/utils/controls/pid.cpp +++ b/src/utils/controls/pid.cpp @@ -4,14 +4,9 @@ /** * Create the PID object */ -PID::PID(pid_config_t &config) - : config(config) -{ - pid_timer.reset(); -} +PID::PID(pid_config_t &config) : config(config) { pid_timer.reset(); } -void PID::init(double start_pt, double set_pt, double, double end_vel) -{ +void PID::init(double start_pt, double set_pt, double, double end_vel) { set_target(set_pt); target_vel = end_vel; sensor_val = start_pt; @@ -21,11 +16,11 @@ void PID::init(double start_pt, double set_pt, double, double end_vel) /** * Update the PID loop by taking the time difference from last update, * and running the PID formula with the new sensor data - * @param sensor_val the distance, angle, encoder position or whatever it is we are measuring + * @param sensor_val the distance, angle, encoder position or whatever it is we + * are measuring * @return the new output. What would be returned by PID::get() */ -double PID::update(double sensor_val) -{ +double PID::update(double sensor_val) { this->sensor_val = sensor_val; @@ -33,10 +28,12 @@ double PID::update(double sensor_val) // Avoid a divide by zero error double d_term = 0; - if (time_delta != 0) + if (time_delta != 0) { d_term = config.d * (get_error() - last_error) / time_delta; - else if (last_time != 0) - printf("(pid.cpp): Warning - running PID without a delay is just a P loop!\n"); + } else if (last_time != 0) { + printf( + "(pid.cpp): Warning - running PID without a delay is just a P loop!\n"); +} // P and D terms out = (config.p * get_error()) + d_term; @@ -45,8 +42,10 @@ double PID::update(double sensor_val) // Only add to the accumulated error if the output is not saturated // aka "Integral Clamping" anti-windup technique - if (!limits_exist || (limits_exist && (out < upper_limit && out > lower_limit))) + if (!limits_exist || + (limits_exist && (out < upper_limit && out > lower_limit))) { accum_error += time_delta * get_error(); +} // I term out += config.i * accum_error; @@ -55,23 +54,21 @@ double PID::update(double sensor_val) last_error = get_error(); // Enable clamping if the limit is not 0 - if (limits_exist) - out = (out < lower_limit) ? lower_limit : (out > upper_limit) ? upper_limit - : out; + if (limits_exist) { + out = (out < lower_limit) ? lower_limit + : (out > upper_limit) ? upper_limit + : out; +} return out; } -double PID::get_sensor_val() -{ - return sensor_val; -} +double PID::get_sensor_val() const { return sensor_val; } /** * Reset the PID loop by resetting time since 0 and accumulated error. */ -void PID::reset() -{ +void PID::reset() { pid_timer.reset(); last_error = 0; @@ -85,42 +82,30 @@ void PID::reset() /** * Gets the current PID out value, from when update() was last run */ -double PID::get() -{ - return out; -} +double PID::get() { return out; } /** * Get the delta between the current sensor data and the target */ -double PID::get_error() -{ - if (config.error_method == ERROR_TYPE::ANGULAR) - { +double PID::get_error() { + if (config.error_method == ERROR_TYPE::ANGULAR) { return OdometryBase::smallest_angle(target, sensor_val); } return target - sensor_val; } -double PID::get_target() -{ - return target; -} +double PID::get_target() const { return target; } /** * Set the target for the PID loop, where the robot is trying to end up */ -void PID::set_target(double target) -{ - this->target = target; -} +void PID::set_target(double target) { this->target = target; } /** * Set the limits on the PID out. The PID out will "clip" itself to be * between the limits. */ -void PID::set_limits(double lower, double upper) -{ +void PID::set_limits(double lower, double upper) { lower_limit = lower; upper_limit = upper; } @@ -129,23 +114,19 @@ void PID::set_limits(double lower, double upper) * Returns true if the loop is within [deadband] for [on_target_time] * seconds */ -bool PID::is_on_target() -{ - if (fabs(get_error()) < config.deadband) - { - if (target_vel != 0) return true; - if (is_checking_on_target == false) - { +bool PID::is_on_target() { + if (fabs(get_error()) < config.deadband) { + if (target_vel != 0) { + return true; +} + if (is_checking_on_target == false) { on_target_last_time = pid_timer.value(); is_checking_on_target = true; - } - else if (pid_timer.value() - on_target_last_time > config.on_target_time) - { + } else if (pid_timer.value() - on_target_last_time > + config.on_target_time) { return true; } - } - else - { + } else { is_checking_on_target = false; } diff --git a/src/utils/controls/pidff.cpp b/src/utils/controls/pidff.cpp index 64439fe..240e7a8 100644 --- a/src/utils/controls/pidff.cpp +++ b/src/utils/controls/pidff.cpp @@ -1,8 +1,8 @@ #include "../core/include/utils/controls/pidff.h" #include "../core/include/utils/math_util.h" -PIDFF::PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg): pid(pid_cfg), ff_cfg(ff_cfg),ff(ff_cfg) -{ +PIDFF::PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg) + : pid(pid_cfg), ff_cfg(ff_cfg), ff(ff_cfg) { out = 0; lower_lim = 0; upper_lim = 0; @@ -10,82 +10,78 @@ PIDFF::PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg): pid /** * Initialize the feedback controller for a movement - * + * * @param start_pt the current sensor value * @param set_pt where the sensor value should be */ -void PIDFF::init(double start_pt, double set_pt, double start_vel, double end_vel) -{ +void PIDFF::init(double start_pt, double set_pt, double start_vel, + double end_vel) { pid.init(start_pt, set_pt, start_vel, end_vel); } -void PIDFF::set_target(double set_pt) -{ - pid.set_target(set_pt); -} +void PIDFF::set_target(double set_pt) { pid.set_target(set_pt); } /** * Iterate the feedback loop once with an updated sensor value. * Only kS for feedfoward will be applied. - * + * * @param val value from the sensor * @return feedback loop result */ -double PIDFF::update(double val) -{ +double PIDFF::update(double val) { double pid_out = pid.update(val); - double ff_out = ff_cfg.kS * sign(pid_out); + double ff_out = ff_cfg.kG + (ff_cfg.kS * sign(pid_out)); out = pid_out + ff_out; - if (lower_lim != upper_lim) + if (lower_lim != upper_lim) { out = clamp(out, lower_lim, upper_lim); +} return out; } +double PIDFF::get_sensor_val() const { return pid.get_sensor_val(); } +double PIDFF::get_target() const { return pid.get_target(); } + /** * Iterate the feedback loop once with an updated sensor value - * + * * @param val value from the sensor * @param vel_setpt Velocity for feedforward * @param a_setpt Acceleration for feedfoward * @return feedback loop result -*/ -double PIDFF::update(double val, double vel_setpt, double a_setpt) -{ + */ +double PIDFF::update(double val, double vel_setpt, double a_setpt) { double pid_out = pid.update(val); double ff_out = ff.calculate(vel_setpt, a_setpt); out = pid_out + ff_out; - if (lower_lim != upper_lim) + if (lower_lim != upper_lim) { out = clamp(out, lower_lim, upper_lim); - +} + return out; } /** * @return the last saved result from the feedback controller */ -double PIDFF::get() -{ - return out; -} +double PIDFF::get() { return out; } /** - * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. - * + * Clamp the upper and lower limits of the output. If both are 0, no limits + * should be applied. + * * @param lower Upper limit * @param upper Lower limit */ -void PIDFF::set_limits(double lower, double upper) -{ +void PIDFF::set_limits(double lower, double upper) { upper_lim = upper; lower_lim = lower; } -/** +/** * @return true if the feedback controller has reached it's setpoint */ -bool PIDFF::is_on_target() -{ - return pid.is_on_target(); -} \ No newline at end of file +bool PIDFF::is_on_target() { return pid.is_on_target(); } + +void PIDFF::reset() { pid.reset(); } \ No newline at end of file diff --git a/src/utils/generic_auto.cpp b/src/utils/generic_auto.cpp index 5147af5..1ac9dcd 100644 --- a/src/utils/generic_auto.cpp +++ b/src/utils/generic_auto.cpp @@ -15,16 +15,19 @@ */ bool GenericAuto::run(bool blocking) { - if(state_list.empty()) - return true; + if(state_list.empty()) { + return true; +} do { - if( state_list.front()() ) - state_list.pop(); + if( state_list.front()() ) { + state_list.pop(); +} - if(blocking) - vexDelay(20); + if(blocking) { + vexDelay(20); +} } while(blocking && !state_list.empty()); @@ -42,8 +45,9 @@ void GenericAuto::add_async(state_ptr async_state) { state_ptr fn = [&async_state](){ vex::task t([](void* fn_ptr){ - while(! (*(state_ptr*)fn_ptr)() ) - vexDelay(20); + while(! (*(state_ptr*)fn_ptr)() ) { + vexDelay(20); +} return 0; }, &async_state); diff --git a/src/utils/math_util.cpp b/src/utils/math_util.cpp index 58051ae..6f8e0d6 100644 --- a/src/utils/math_util.cpp +++ b/src/utils/math_util.cpp @@ -48,8 +48,9 @@ double sign(double x) double wrap_angle_deg(double input) { double angle = fmod(input, 360); - if (angle < 0) + if (angle < 0) { angle += 360; +} return angle; } @@ -57,8 +58,9 @@ double wrap_angle_deg(double input) double wrap_angle_rad(double input) { double angle = fmod(input, 2 * PI); - if (angle < 0) + if (angle < 0) { angle += 2 * PI; +} return angle; } @@ -145,8 +147,9 @@ double estimate_path_length(const std::vector &points) static point_t last_p = p; // Ignore the first point - if (p == last_p) + if (p == last_p) { continue; +} dist += p.dist(last_p); last_p = p; diff --git a/src/utils/moving_average.cpp b/src/utils/moving_average.cpp index d5419e1..1073776 100644 --- a/src/utils/moving_average.cpp +++ b/src/utils/moving_average.cpp @@ -131,7 +131,7 @@ void ExponentialMovingAverage::add_entry(double n) * How many samples the average is made from * @return the number of samples used to calculate this average */ -double ExponentialMovingAverage::get_value() +double ExponentialMovingAverage::get_value() const { return current_avg; } diff --git a/src/utils/pure_pursuit.cpp b/src/utils/pure_pursuit.cpp index 91502c9..ffdd36b 100644 --- a/src/utils/pure_pursuit.cpp +++ b/src/utils/pure_pursuit.cpp @@ -14,9 +14,11 @@ PurePursuit::Path::Path(std::vector points, double radius) { for(int j = i + 2; j < points.size() - 1; j++) { // Iterate over points on the segments discretely and compare distances double segment_i_dist = points[i].dist(points[i+1]); - if (segment_i_dist == 0) segment_i_dist = 0.1; + if (segment_i_dist == 0) { segment_i_dist = 0.1; +} double segment_j_dist = points[j].dist(points[j+1]); - if (segment_j_dist == 0) segment_j_dist = 0.1; + if (segment_j_dist == 0) { segment_j_dist = 0.1; +} for(double t1 = 0; t1 <= 1; t1 += radius / segment_i_dist) { point_t p1; p1.x = points[i].x + t1 * (points[i+1].x - points[i].x); @@ -132,8 +134,9 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub //This prioritizes the closest intersection to the end of the path for(point_t intersection: intersections) { - if(intersection.dist(end) < target.dist(end)) + if(intersection.dist(end) < target.dist(end)) { target = intersection; +} } } @@ -264,8 +267,9 @@ double PurePursuit::estimate_remaining_dist(const std::vector &path, po { point_t lookahead_pt = get_lookahead(path, robot_pose, radius); - if (lookahead_pt == path[path.size() - 1]) + if (lookahead_pt == path[path.size() - 1]) { return robot_pose.get_point().dist(lookahead_pt); +} double dist = 0; diff --git a/src/utils/trapezoid_profile.cpp b/src/utils/trapezoid_profile.cpp index 98eac62..98014ba 100644 --- a/src/utils/trapezoid_profile.cpp +++ b/src/utils/trapezoid_profile.cpp @@ -5,301 +5,331 @@ const double EPSILON = 0.000005; - inline double calc_pos(double t, double a, double v, double si) { - return (0.5*(a)*(t)*(t))+((v)*(t))+(si); + return (0.5 * (a) * (t) * (t)) + ((v) * (t)) + (si); } inline double calc_vel(double t, double a, double vi) { - return ((a)*(t))+(vi); + return ((a) * (t)) + (vi); } TrapezoidProfile::TrapezoidProfile(double max_v, double accel) -: si(0), sf(0), vi(0), vf(0), max_v(max_v), accel(accel), segments(), num_acceleration_phases(0), precalculated(false) {} + : si(0), sf(0), vi(0), vf(0), max_v(max_v), accel(accel), segments(), + num_acceleration_phases(0), precalculated(false) {} -void TrapezoidProfile::set_max_v(double max_v) -{ - this->max_v = max_v; +void TrapezoidProfile::set_max_v(double max_v) { + this->max_v = max_v; - this->precalculated = false; + this->precalculated = false; } -void TrapezoidProfile::set_accel(double accel) -{ - this->accel = accel; +void TrapezoidProfile::set_accel(double accel) { + this->accel = accel; - this->precalculated = false; + this->precalculated = false; } -void TrapezoidProfile::set_endpts(double start, double end) -{ - this->si = start; - this->sf = end; +void TrapezoidProfile::set_endpts(double start, double end) { + this->si = start; + this->sf = end; - this->precalculated = false; + this->precalculated = false; } -void TrapezoidProfile::set_vel_endpts(double start, double end) -{ - this->vi = start; - this->vf = end; +void TrapezoidProfile::set_vel_endpts(double start, double end) { + this->vi = start; + this->vf = end; - this->precalculated = false; + this->precalculated = false; } motion_t TrapezoidProfile::calculate_time_based(double time_s) { - if (!this->precalculated) precalculate(); - - int segment_i = 0; - - // position, velocity, acceleration, and time at the beginning of the segment we're in - double segment_s = this->si; - double segment_v = this->vi; - double segment_a = this->segments[0].accel; - double segment_t = 0; - - // skip phases based on time - while (segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS - && time_s > segment_t + this->segments[segment_i].duration) { - segment_t += this->segments[segment_i].duration; - segment_s = this->segments[segment_i].pos_after; - segment_v = this->segments[segment_i].vel_after; - segment_i++; - segment_a = this->segments[segment_i].accel; - } - - motion_t out; - - // if we are beyond the last phase, return the position/velocity at the last phase - if (segment_i == MAX_TRAPEZOID_PROFILE_SEGMENTS) { - out.accel = 0; - out.pos = this->segments[MAX_TRAPEZOID_PROFILE_SEGMENTS - 1].pos_after; - out.vel = this->segments[MAX_TRAPEZOID_PROFILE_SEGMENTS - 1].vel_after; - return out; - } + if (!this->precalculated) { + precalculate(); +} - // calculate based on time - out.accel = this->segments[segment_i].accel; - out.vel = calc_vel(time_s - segment_t, segment_a, segment_v); - out.pos = calc_pos(time_s - segment_t, segment_a, segment_v, segment_s); + int segment_i = 0; + + // position, velocity, acceleration, and time at the beginning of the segment + // we're in + double segment_s = this->si; + double segment_v = this->vi; + double segment_a = this->segments[0].accel; + double segment_t = 0; + + // skip phases based on time + while (segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS && + time_s > segment_t + this->segments[segment_i].duration) { + segment_t += this->segments[segment_i].duration; + segment_s = this->segments[segment_i].pos_after; + segment_v = this->segments[segment_i].vel_after; + segment_i++; + segment_a = this->segments[segment_i].accel; + } + + motion_t out; + + // if we are beyond the last phase, return the position/velocity at the last + // phase + if (segment_i == MAX_TRAPEZOID_PROFILE_SEGMENTS) { + out.accel = 0; + out.pos = this->segments[MAX_TRAPEZOID_PROFILE_SEGMENTS - 1].pos_after; + out.vel = this->segments[MAX_TRAPEZOID_PROFILE_SEGMENTS - 1].vel_after; return out; + } + + // calculate based on time + out.accel = this->segments[segment_i].accel; + out.vel = calc_vel(time_s - segment_t, segment_a, segment_v); + out.pos = calc_pos(time_s - segment_t, segment_a, segment_v, segment_s); + return out; } motion_t TrapezoidProfile::calculate(double time_s, double pos_s) { - if (!this->precalculated) precalculate(); - - // printf("%f %f\n", time_s, pos_s); - - int segment_i = 0; - - // position, velocity, acceleration, and time at the beginning of the segment we're in - double segment_s = this->si; - double segment_v = this->vi; - double segment_a = this->segments[0].accel; - double segment_t = 0; - - // skip acceleration phases based on time - while (segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS - && segment_i < this->num_acceleration_phases - && time_s > segment_t + this->segments[segment_i].duration) { - segment_t += this->segments[segment_i].duration; - segment_s = this->segments[segment_i].pos_after; - segment_v = this->segments[segment_i].vel_after; - segment_i++; - segment_a = this->segments[segment_i].accel; - } + if (!this->precalculated) { + precalculate(); +} - // skip other segments based on distance, if we are past the time segments - if (segment_i >= this->num_acceleration_phases) { - while (segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS && - ((this->si < this->sf && pos_s > this->segments[segment_i].pos_after) - || (this->si > this->sf && pos_s < this->segments[segment_i].pos_after))) { - segment_t += this->segments[segment_i].duration; - segment_s = this->segments[segment_i].pos_after; - segment_v = this->segments[segment_i].vel_after; - segment_i++; - segment_a = this->segments[segment_i].accel; - } + // printf("%f %f\n", time_s, pos_s); + + int segment_i = 0; + + // position, velocity, acceleration, and time at the beginning of the segment + // we're in + double segment_s = this->si; + double segment_v = this->vi; + double segment_a = this->segments[0].accel; + double segment_t = 0; + + // skip acceleration phases based on time + while (segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS && + segment_i < this->num_acceleration_phases && + time_s > segment_t + this->segments[segment_i].duration) { + segment_t += this->segments[segment_i].duration; + segment_s = this->segments[segment_i].pos_after; + segment_v = this->segments[segment_i].vel_after; + segment_i++; + segment_a = this->segments[segment_i].accel; + } + + // skip other segments based on distance, if we are past the time segments + if (segment_i >= this->num_acceleration_phases) { + while ( + segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS && + ((this->si < this->sf && pos_s > this->segments[segment_i].pos_after) || + (this->si > this->sf && + pos_s < this->segments[segment_i].pos_after))) { + segment_t += this->segments[segment_i].duration; + segment_s = this->segments[segment_i].pos_after; + segment_v = this->segments[segment_i].vel_after; + segment_i++; + segment_a = this->segments[segment_i].accel; } + } - motion_t out; + motion_t out; - // if we are beyond the last phase, return the position/velocity at the last phase - if (segment_i == MAX_TRAPEZOID_PROFILE_SEGMENTS) { - out.accel = 0; - out.pos = this->segments[MAX_TRAPEZOID_PROFILE_SEGMENTS - 1].pos_after; - out.vel = this->segments[MAX_TRAPEZOID_PROFILE_SEGMENTS - 1].vel_after; - return out; - } - - // if we are in an acceleration phase, calculate based on time - if (segment_i < this->num_acceleration_phases) { - out.accel = segment_a; - out.vel = calc_vel(time_s - segment_t, segment_a, segment_v); - out.pos = calc_pos(time_s - segment_t, segment_a, segment_v, segment_s); - return out; - } + // if we are beyond the last phase, return the position/velocity at the last + // phase + if (segment_i == MAX_TRAPEZOID_PROFILE_SEGMENTS) { + out.accel = 0; + out.pos = this->segments[MAX_TRAPEZOID_PROFILE_SEGMENTS - 1].pos_after; + out.vel = this->segments[MAX_TRAPEZOID_PROFILE_SEGMENTS - 1].vel_after; + return out; + } - // otherwise calculate based on distance + // if we are in an acceleration phase, calculate based on time + if (segment_i < this->num_acceleration_phases) { out.accel = segment_a; - out.pos = pos_s; - // Calculating the final velocity in uniformly accelerated motion: - // v_f^2 = v_i^2 + 2a(x_f - x_i) - // v_f = sqrt(v_i^2 + 2a(x_f - x_i)) - out.vel = sqrt(segment_v*segment_v + 2*segment_a*(pos_s - segment_s)); - - // match the sign of the starting velocity of the segment - if (segment_v < 0) out.vel *= -1; - + out.vel = calc_vel(time_s - segment_t, segment_a, segment_v); + out.pos = calc_pos(time_s - segment_t, segment_a, segment_v, segment_s); return out; + } + + // otherwise calculate based on distance + out.accel = segment_a; + out.pos = pos_s; + // Calculating the final velocity in uniformly accelerated motion: + // v_f^2 = v_i^2 + 2a(x_f - x_i) + // v_f = sqrt(v_i^2 + 2a(x_f - x_i)) + out.vel = sqrt(segment_v * segment_v + 2 * segment_a * (pos_s - segment_s)); + + // match the sign of the starting velocity of the segment + if (segment_v < 0) { + out.vel *= -1; } -double TrapezoidProfile::get_movement_time() -{ - if (!this->precalculated) precalculate(); - - double t = 0; - for (auto &segment : this->segments) { - t += segment.duration; - } - return t; + return out; } -bool TrapezoidProfile::precalculate() { - for (auto &segment : this->segments) { - segment.pos_after = 0; - segment.vel_after = 0; - segment.accel = 0; - segment.duration = 0; - } - this->num_acceleration_phases = 0; +double TrapezoidProfile::get_movement_time() const { return duration; } - if (this->accel < EPSILON) { - printf("WARNING: trapezoid motion profile acceleration was negative, or too small\n"); - this->accel = fmin(EPSILON, fabs(this->accel)); - } +bool TrapezoidProfile::precalculate() { + for (auto &segment : this->segments) { + segment.pos_after = 0; + segment.vel_after = 0; + segment.accel = 0; + segment.duration = 0; + } + this->num_acceleration_phases = 0; + + if (this->accel < EPSILON) { + printf("WARNING: trapezoid motion profile acceleration was negative, or " + "too small\n"); + this->accel = fmin(EPSILON, fabs(this->accel)); + } + + if (this->max_v < EPSILON) { + printf("WARNING: trapezoid motion profile maximum velocity was negative, " + "or too small\n"); + this->max_v = fmin(EPSILON, fabs(this->max_v)); + } + + // make sure vf is within v_max + if (fabs(this->vf) > this->max_v) { + printf("WARNING: trapezoid motion profile target velocity is greater than " + "maximum velocity\n"); + if (this->vf > this->max_v) { + this->vf = this->max_v; + } else { + this->vf = -this->max_v; +} + } - if (this->max_v < EPSILON) { - printf("WARNING: trapezoid motion profile maximum velocity was negative, or too small\n"); - this->max_v = fmin(EPSILON, fabs(this->max_v)); - } + // if displacement is + but vf is -, or if displacement is - but vf is + + if ((this->si < this->sf && this->vf < 0) || + (this->si > this->sf && this->vf > 0)) { + printf("WARNING: trapezoid motion profile target velocity is in the wrong " + "direction\n"); + this->vf = 0; + } - // make sure vf is within v_max - if (fabs(this->vf) > this->max_v) { - printf("WARNING: trapezoid motion profile target velocity is greater than maximum velocity\n"); - if (this->vf > this->max_v) this->vf = this->max_v; - else this->vf = -this->max_v; - } + double s = this->si, v = this->vi; - // if displacement is + but vf is -, or if displacement is - but vf is + - if ((this->si < this->sf && this->vf < 0) || (this->si > this->sf && this->vf > 0)) { - printf("WARNING: trapezoid motion profile target velocity is in the wrong direction\n"); - this->vf = 0; - } + double total_time = 0; - double s = this->si, v = this->vi; - - for (auto & segment : this->segments) { - segment = calculate_next_segment(s, v); - - if (fabs(segment.pos_after - this->sf) < EPSILON) return true; - - // Check if xf is between x and x_next (meaning we overshot the end position) - if ((((this->si < this->sf) && (this->sf < segment.pos_after)) || ((segment.pos_after < this->sf) && (this->sf < this->si))) - && fabs(this->sf - segment.pos_after) > EPSILON) { - // Solve for the exact time to reach self.xf using the quadratic formula - // Given: x = x0 + v0 * t + 0.5 * a * t^2 - double a_coeff = 0.5 * segment.accel; - if (fabs(a_coeff) < EPSILON) a_coeff = EPSILON; - double b_coeff = v; - double c_coeff = s - this->sf; - - double discriminant = b_coeff * b_coeff - 4.0 * a_coeff * c_coeff; - if (discriminant >= 0) { - double t1 = (-b_coeff + sqrt(discriminant)) / (2 * a_coeff); - double t2 = (-b_coeff - sqrt(discriminant)) / (2 * a_coeff); - - double t_corrected = fmin(t1, t2); - if (t_corrected < 0) { - t_corrected = fmax(t1, t2); - } - segment.duration = t_corrected; - segment.vel_after = calc_vel(segment.duration, segment.accel, v); - segment.pos_after = calc_pos(segment.duration, segment.accel, v, s); - return true; - } else { - printf("ERROR: No real solution to reach sf.\n"); - return false; - } - } - - v = segment.vel_after; - s = segment.pos_after; - } + for (auto &segment : this->segments) { + segment = calculate_next_segment(s, v); + total_time += segment.duration; - printf("WARNING: trapezoid motion profile did not reach end position in %d segments (the maximum)\n", MAX_TRAPEZOID_PROFILE_SEGMENTS); - return false; + if (fabs(segment.pos_after - this->sf) < EPSILON) { + return true; } -trapezoid_profile_segment_t TrapezoidProfile::calculate_kinetic_motion(double si, double vi, double v_target) { - trapezoid_profile_segment_t m; - - m.duration = fabs(v_target - vi) / this->accel; - m.vel_after = v_target; - if (vi < v_target) { - m.accel = this->accel; - } else { - m.accel = -this->accel; - } - - m.pos_after = calc_pos(m.duration, m.accel, vi, si); - return m; + // Check if xf is between x and x_next (meaning we overshot the end + // position) + if ((((this->si < this->sf) && (this->sf < segment.pos_after)) || + ((segment.pos_after < this->sf) && (this->sf < this->si))) && + fabs(this->sf - segment.pos_after) > EPSILON) { + // Solve for the exact time to reach self.xf using the quadratic formula + // Given: x = x0 + v0 * t + 0.5 * a * t^2 + double a_coeff = 0.5 * segment.accel; + if (fabs(a_coeff) < EPSILON) { + a_coeff = EPSILON; } + double b_coeff = v; + double c_coeff = s - this->sf; -trapezoid_profile_segment_t TrapezoidProfile::calculate_next_segment(double s, double v) { - // d represents the direction of travel, + or - - int d = 1; - if (this->si > this->sf) { - d = -1; - } - - // if going the wrong way, come to a stop - if ((d == 1 && v < -EPSILON) || (d == -1 && v > EPSILON)) { - this->num_acceleration_phases += 1; - return calculate_kinetic_motion(s, v, 0); - } + double discriminant = b_coeff * b_coeff - 4.0 * a_coeff * c_coeff; + if (discriminant >= 0) { + double t1 = (-b_coeff + sqrt(discriminant)) / (2 * a_coeff); + double t2 = (-b_coeff - sqrt(discriminant)) / (2 * a_coeff); - // if |v| > max_v, slow down - if (v > this->max_v || v < -this->max_v) { - this->num_acceleration_phases += 1; - return calculate_kinetic_motion(s, v, d * this->max_v); + double t_corrected = fmin(t1, t2); + if (t_corrected < 0) { + t_corrected = fmax(t1, t2); + } + segment.duration = t_corrected; + segment.vel_after = calc_vel(segment.duration, segment.accel, v); + segment.pos_after = calc_pos(segment.duration, segment.accel, v, s); + return true; + } else { + printf("ERROR: No real solution to reach sf.\n"); + return false; + } } - // how much distance would it take to reach vf in one segment? - trapezoid_profile_segment_t beeline_vf = calculate_kinetic_motion(s, v, this->vf); - if ((d == 1 && beeline_vf.pos_after > this->sf - EPSILON) || (d == -1 && beeline_vf.pos_after <= this->sf + EPSILON)) { - // we can't make it to vf - get as close as possible - return beeline_vf; - } + v = segment.vel_after; + s = segment.pos_after; + duration = total_time; + } - // we can reach vf in one segment - choose the fastest speed so that that is still possible - double v_middle = d * sqrt(((v*v + this->vf*this->vf)/2.0) + this->accel*fabs(this->sf - s) + this->vf*this->vf); - // cap this at our max speed - v_middle = fmax(-this->max_v, fmin(v_middle, this->max_v)); + printf("WARNING: trapezoid motion profile did not reach end position in %d " + "segments (the maximum)\n", + MAX_TRAPEZOID_PROFILE_SEGMENTS); + return false; +} - // if we aren't at this speed yet, let's get there - if (fabs(v_middle - v) > EPSILON) { - this->num_acceleration_phases += 1; - return calculate_kinetic_motion(s, v, v_middle); - } +trapezoid_profile_segment_t +TrapezoidProfile::calculate_kinetic_motion(double si, double vi, + double v_target) { + trapezoid_profile_segment_t m; + + m.duration = fabs(v_target - vi) / this->accel; + m.vel_after = v_target; + if (vi < v_target) { + m.accel = this->accel; + } else { + m.accel = -this->accel; + } + + m.pos_after = calc_pos(m.duration, m.accel, vi, si); + return m; +} - // we are at our max speed - hold it until we have to start slowing down - trapezoid_profile_segment_t out; - out.accel = 0; - double distance = d * fabs(this->sf - beeline_vf.pos_after); - out.pos_after = s + distance; - out.duration = distance / v_middle; - out.vel_after = v_middle; - return out; +trapezoid_profile_segment_t TrapezoidProfile::calculate_next_segment(double s, + double v) { + // d represents the direction of travel, + or - + int d = 1; + if (this->si > this->sf) { + d = -1; + } + + // if going the wrong way, come to a stop + if ((d == 1 && v < -EPSILON) || (d == -1 && v > EPSILON)) { + this->num_acceleration_phases += 1; + return calculate_kinetic_motion(s, v, 0); + } + + // if |v| > max_v, slow down + if (v > this->max_v || v < -this->max_v) { + this->num_acceleration_phases += 1; + return calculate_kinetic_motion(s, v, d * this->max_v); + } + + // how much distance would it take to reach vf in one segment? + trapezoid_profile_segment_t beeline_vf = + calculate_kinetic_motion(s, v, this->vf); + if ((d == 1 && beeline_vf.pos_after > this->sf - EPSILON) || + (d == -1 && beeline_vf.pos_after <= this->sf + EPSILON)) { + // we can't make it to vf - get as close as possible + return beeline_vf; + } + + // we can reach vf in one segment - choose the fastest speed so that that is + // still possible + double v_middle = + d * sqrt(((v * v + this->vf * this->vf) / 2.0) + + this->accel * fabs(this->sf - s) + this->vf * this->vf); + // cap this at our max speed + v_middle = fmax(-this->max_v, fmin(v_middle, this->max_v)); + + // if we aren't at this speed yet, let's get there + if (fabs(v_middle - v) > EPSILON) { + this->num_acceleration_phases += 1; + return calculate_kinetic_motion(s, v, v_middle); + } + + // we are at our max speed - hold it until we have to start slowing down + trapezoid_profile_segment_t out; + out.accel = 0; + double distance = d * fabs(this->sf - beeline_vf.pos_after); + out.pos_after = s + distance; + out.duration = distance / v_middle; + out.vel_after = v_middle; + return out; } +double TrapezoidProfile::get_max_v() const { return max_v; }; + +double TrapezoidProfile::get_accel() const { return accel; } \ No newline at end of file From ab439a4f6232a93cf059420b109e23e521314566 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Tue, 16 Jan 2024 22:03:16 -0500 Subject: [PATCH 237/243] git subrepo commit (merge) core subrepo: subdir: "core" merged: "e2cb990" upstream: origin: "git@github.com:RIT-VEX-U/Core.git" branch: "main" commit: "d1921ad" git-subrepo: version: "0.4.6" origin: "???" commit: "???" --- src/subsystems/odometry/odometry_base.cpp | 2 +- src/subsystems/tank_drive.cpp | 2 +- src/utils/command_structure/auto_command.cpp | 4 ++-- src/utils/controls/pidff.cpp | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index 2cd8328..15981ae 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -10,7 +10,7 @@ OdometryBase::OdometryBase(bool is_async) : current_pos(zero_pos) { if (is_async) { handle = new vex::task(background_task, (void *)this); -} + } } /** diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index ee0c64e..3c33872 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -420,7 +420,7 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb { if (end_speed == 0) { stop(); -} + } func_initialized = false; return true; } diff --git a/src/utils/command_structure/auto_command.cpp b/src/utils/command_structure/auto_command.cpp index 86c8ac9..5bce832 100644 --- a/src/utils/command_structure/auto_command.cpp +++ b/src/utils/command_structure/auto_command.cpp @@ -296,12 +296,12 @@ bool Async::run() RepeatUntil::RepeatUntil(InOrder cmds, size_t times) : RepeatUntil(cmds, new TimesTestedCondition(times)) { - timeout_seconds = -1.0; + timeout_seconds = 999999; } RepeatUntil::RepeatUntil(InOrder cmds, Condition *cond) : cmds(cmds), working_cmds(new InOrder(cmds)), cond(cond) { - timeout_seconds = -1.0; + timeout_seconds = 999999; } diff --git a/src/utils/controls/pidff.cpp b/src/utils/controls/pidff.cpp index 240e7a8..f8f38c7 100644 --- a/src/utils/controls/pidff.cpp +++ b/src/utils/controls/pidff.cpp @@ -84,4 +84,4 @@ void PIDFF::set_limits(double lower, double upper) { */ bool PIDFF::is_on_target() { return pid.is_on_target(); } -void PIDFF::reset() { pid.reset(); } \ No newline at end of file +void PIDFF::reset() { pid.reset(); } From a860b526f20bffeb694928799e36c568b03b6423 Mon Sep 17 00:00:00 2001 From: Richard Sommers <44383226+cowsed@users.noreply.github.com> Date: Sat, 20 Jan 2024 10:05:09 -0500 Subject: [PATCH 238/243] Update Doxyfile to generate diagrams --- Doxyfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Doxyfile b/Doxyfile index 3807b19..3401099 100644 --- a/Doxyfile +++ b/Doxyfile @@ -2428,7 +2428,7 @@ HIDE_UNDOC_RELATIONS = YES # set to NO # The default value is: NO. -HAVE_DOT = NO +HAVE_DOT = YES # The DOT_NUM_THREADS specifies the number of dot invocations doxygen is allowed # to run in parallel. When set to 0 doxygen will base this on the number of From e2dff6d35e232c60e232af7c166ab3ee56aedc6b Mon Sep 17 00:00:00 2001 From: Richard Sommers <44383226+cowsed@users.noreply.github.com> Date: Sat, 20 Jan 2024 10:09:15 -0500 Subject: [PATCH 239/243] Update Doxyfile put generated diagrams on website --- Doxyfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Doxyfile b/Doxyfile index 3401099..60b26a6 100644 --- a/Doxyfile +++ b/Doxyfile @@ -499,7 +499,7 @@ NUM_PROC_THREADS = 1 # normally produced when WARNINGS is set to YES. # The default value is: NO. -EXTRACT_ALL = NO +EXTRACT_ALL = YES # If the EXTRACT_PRIVATE tag is set to YES, all private members of a class will # be included in the documentation. From 77882f67e3df90de8c7b8afcca2c1541946b926c Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Fri, 23 Feb 2024 10:07:03 -0500 Subject: [PATCH 240/243] Rolled back Motion Profiles, post WV --- include/utils/controls/bang_bang.h | 2 +- include/utils/controls/feedback_base.h | 2 +- include/utils/controls/motion_controller.h | 13 +- include/utils/controls/pid.h | 14 +- include/utils/controls/pidff.h | 3 +- include/utils/controls/take_back_half.h | 2 +- include/utils/controls/trapezoid_profile.h | 229 +++----- include/utils/state_machine.h | 206 ++++++++ src/subsystems/tank_drive.cpp | 10 +- src/utils/command_structure/auto_command.cpp | 487 ++++++++---------- .../command_structure/command_controller.cpp | 2 +- src/utils/controls/bang_bang.cpp | 2 +- src/utils/controls/motion_controller.cpp | 219 +++----- src/utils/controls/pid.cpp | 30 +- src/utils/controls/pidff.cpp | 5 +- src/utils/controls/take_back_half.cpp | 2 +- src/utils/controls/trapezoid_profile.cpp | 117 +++++ src/utils/math_util.cpp | 2 +- src/utils/trapezoid_profile.cpp | 335 ------------ 19 files changed, 734 insertions(+), 948 deletions(-) create mode 100644 include/utils/state_machine.h create mode 100644 src/utils/controls/trapezoid_profile.cpp delete mode 100644 src/utils/trapezoid_profile.cpp diff --git a/include/utils/controls/bang_bang.h b/include/utils/controls/bang_bang.h index aeba17d..8fbc180 100644 --- a/include/utils/controls/bang_bang.h +++ b/include/utils/controls/bang_bang.h @@ -13,7 +13,7 @@ class BangBang : public Feedback * @param start_vel Movement starting velocity * @param end_vel Movement ending velocity */ - void init(double start_pt, double set_pt, double start_vel [[maybe_unused]] = 0.0, double end_vel [[maybe_unused]] = 0.0) override; + void init(double start_pt, double set_pt) override; /** * Iterate the feedback loop once with an updated sensor value diff --git a/include/utils/controls/feedback_base.h b/include/utils/controls/feedback_base.h index 9b9c625..528af20 100644 --- a/include/utils/controls/feedback_base.h +++ b/include/utils/controls/feedback_base.h @@ -18,7 +18,7 @@ class Feedback * @param start_vel Movement starting velocity * @param end_vel Movement ending velocity */ - virtual void init(double start_pt, double set_pt, double start_vel = 0.0, double end_vel = 0.0) = 0; + virtual void init(double start_pt, double set_pt) = 0; /** * Iterate the feedback loop once with an updated sensor value diff --git a/include/utils/controls/motion_controller.h b/include/utils/controls/motion_controller.h index 86b3cde..11c07de 100644 --- a/include/utils/controls/motion_controller.h +++ b/include/utils/controls/motion_controller.h @@ -4,8 +4,6 @@ #include "../core/include/utils/controls/trapezoid_profile.h" #include "../core/include/utils/controls/feedback_base.h" #include "../core/include/subsystems/tank_drive.h" -#include "../core/include/subsystems/screen.h" - #include "vex.h" /** @@ -56,7 +54,7 @@ class MotionController : public Feedback * @brief Initialize the motion profile for a new movement * This will also reset the PID and profile timers. */ - void init(double start_pt, double end_pt, double start_vel, double end_vel) override; + void init(double start_pt, double end_pt) override; /** * @brief Update the motion profile with a new sensor value @@ -89,10 +87,7 @@ class MotionController : public Feedback /** * @return The current postion, velocity and acceleration setpoints */ - motion_t get_motion() const; - - - screen::Page *Page(); + motion_t get_motion(); /** * This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. @@ -122,14 +117,10 @@ class MotionController : public Feedback FeedForward ff; TrapezoidProfile profile; - double current_pos; - double end_pt; - double lower_limit = 0, upper_limit = 0; double out = 0; motion_t cur_motion; vex::timer tmr; - friend class MotionControllerPage; }; \ No newline at end of file diff --git a/include/utils/controls/pid.h b/include/utils/controls/pid.h index 102bc8a..0b5d4b0 100644 --- a/include/utils/controls/pid.h +++ b/include/utils/controls/pid.h @@ -69,8 +69,7 @@ class PID : public Feedback { * base * @param end_vel sets the target end velocity of the PID controller */ - void init(double start_pt, double set_pt, double start_vel = 0, - double end_vel = 0) override; + void init(double start_pt, double set_pt) override; /** * Update the PID loop by taking the time difference from last update, @@ -81,6 +80,17 @@ class PID : public Feedback { */ double update(double sensor_val) override; + /** + * Update the PID loop by taking the time difference from last update, + * and running the PID formula with the new sensor data + * @param sensor_val the distance, angle, encoder position or whatever it is we + * are measuring + * @param v_setpt Expected velocity setpoint, to subtract from the D term (for + * velocity control) + * @return the new output. What would be returned by PID::get() + */ + double update(double sensor_val, double v_setpt); + /** * @brief gets the sensor value that we were last updated with * @return sensor_val diff --git a/include/utils/controls/pidff.h b/include/utils/controls/pidff.h index 243f81b..bda22f2 100644 --- a/include/utils/controls/pidff.h +++ b/include/utils/controls/pidff.h @@ -15,8 +15,7 @@ class PIDFF : public Feedback { * @param start_vel the current rate of change of the sensor value * @param end_vel the desired ending rate of change of the sensor value */ - void init(double start_pt, double set_pt, double start_vel, - double end_vel) override; + void init(double start_pt, double set_pt) override; /** * Set the target of the PID loop diff --git a/include/utils/controls/take_back_half.h b/include/utils/controls/take_back_half.h index 692660f..68adb6a 100644 --- a/include/utils/controls/take_back_half.h +++ b/include/utils/controls/take_back_half.h @@ -16,7 +16,7 @@ class TakeBackHalf : public Feedback * @param start_vel Movement starting velocity (IGNORED) * @param end_vel Movement ending velocity (IGNORED) */ - void init(double start_pt, double set_pt, double, double); + void init(double start_pt, double set_pt); /** * Iterate the feedback loop once with an updated sensor value * diff --git a/include/utils/controls/trapezoid_profile.h b/include/utils/controls/trapezoid_profile.h index 6cd9cc2..865d342 100644 --- a/include/utils/controls/trapezoid_profile.h +++ b/include/utils/controls/trapezoid_profile.h @@ -1,174 +1,87 @@ #pragma once -const int MAX_TRAPEZOID_PROFILE_SEGMENTS = 4; - /** * motion_t is a description of 1 dimensional motion at a point in time. - */ -typedef struct { - double pos; ///< 1d position at this point in time - double vel; ///< 1d velocity at this point in time - double accel; ///< 1d acceleration at this point in time +*/ +typedef struct +{ + double pos; ///< 1d position at this point in time + double vel; ///< 1d velocity at this point in time + double accel; ///< 1d acceleration at this point in time } motion_t; -/** - * trapezoid_profile_segment_t is a description of one constant acceleration - * segment of a trapezoid motion profile - */ -typedef struct { - double pos_after; ///< 1d position after this segment concludes - double vel_after; ///< 1d velocity after this segment concludes - double accel; ///< 1d acceleration during the segment - double duration; ///< duration of the segment -} trapezoid_profile_segment_t; - /** * Trapezoid Profile - * - * This is a motion profile defined by: - * - maximum acceleration - * - maximum velocity - * - start position and velocity - * - end position and velocity - * - * Using this information, a parametric function is generated, with a period of - * acceleration, constant velocity, and deceleration. The velocity graph usually - * looks like a trapezoid, giving it its name. - * - * If the maximum velocity is set high enough, this will become a S-curve - * profile, with only acceleration and deceleration. - * - * If the initial velocity is in the wrong direction, the profile will first - * come to a stop, then continue a normal trapezoid profile. - * - * If the initial velocity is higher than the maximum velocity, the profile will - * first try to achieve the maximum velocity. - * - * If the end velocity is not achievable, the profile will try to get as close - * as possible. The end velocity must be in the direction of the end point. - * - * This class is designed for use in properly modelling the motion of the robots - * to create a feedfoward and target for PID. Acceleration and Maximum velocity - * should be measured on the robot and tuned down slightly to account for - * battery drop. - * + * + * This is a motion profile defined by an acceleration, maximum velocity, start point and end point. + * Using this information, a parametric function is generated, with a period of acceleration, constant + * velocity, and deceleration. The velocity graph looks like a trapezoid, giving it it's name. + * + * If the maximum velocity is set high enough, this will become a S-curve profile, with only acceleration and deceleration. + * + * This class is designed for use in properly modelling the motion of the robots to create a feedfoward + * and target for PID. Acceleration and Maximum velocity should be measured on the robot and tuned down + * slightly to account for battery drop. + * * Here are the equations graphed for ease of understanding: * https://www.desmos.com/calculator/rkm3ivu1yk - * + * * @author Ryan McGee * @date 7/12/2022 - * + * */ -class TrapezoidProfile { -public: - /** - * @brief Construct a new Trapezoid Profile object - * - * @param max_v Maximum velocity the robot can run at - * @param accel Maximum acceleration of the robot - */ - TrapezoidProfile(double max_v, double accel); - - /** - * @brief Run the trapezoidal profile based on the time and distance that's - * elapsed - * - * @param time_s Time since start of movement - * @param pos_s The current position - * @return motion_t Position, velocity and acceleration - */ - motion_t calculate(double time_s, double pos_s); - - /** - * @brief Run the trapezoidal profile based on the time that's elapsed - * - * @param time_s Time since start of movement - * @return motion_t Position, velocity and acceleration - */ - motion_t calculate_time_based(double time_s); - - /** - * @brief set_endpts defines a start and end position - * - * @param start the starting position of the path - * @param end the ending position of the path - */ - void set_endpts(double start, double end); - - /** - * @brief set start and end velocities - * - * @param start the starting velocity of the path - * @param end the ending velocity of the path - */ - void set_vel_endpts(double start, double end); - - /** - * @brief set_accel sets the acceleration this profile will use (the left and - * right legs of the trapezoid) - * - * @param accel the acceleration amount to use - */ - void set_accel(double accel); - - /** - * @brief sets the maximum velocity for the profile (the height of the top of - * the trapezoid) - * - * @param max_v the maximum velocity the robot can travel at - */ - void set_max_v(double max_v); - - /** - * @brief uses the kinematic equations to and specified accel and max_v to - * figure out how long moving along the profile would take - * - * @return the time the path will take to travel - */ - double get_movement_time() const; - - double get_max_v() const; - double get_accel() const; - -private: - double si, sf; ///< the initial and final position of the profile - double vi, vf; ///< the initial and final velocity of the profile - double max_v; ///< the maximum velocity to travel at for this profile - double accel; ///< the rate of acceleration to use for this profile. - double duration; - - trapezoid_profile_segment_t segments[MAX_TRAPEZOID_PROFILE_SEGMENTS]; - int num_acceleration_phases; - - bool precalculated; ///< whether or not the segment array is up to date - - /** - * Attempt to generate the motion profile for the given parameters - * - * @return False if there was a problem with the parameters - */ - bool precalculate(); - - /** - * Calculate a trapezoid segment given a target velocity that accelerates to - * the given velocity - * - * @param si segment initial position - * @param vi segment initial velocity - * @param v_target target velocity - * @return a trapezoid_profile_segment_t that represents constant acceleration - * to the target velocity - */ - trapezoid_profile_segment_t calculate_kinetic_motion(double si, double vi, - double v_target); +class TrapezoidProfile +{ + public: + + /** + * @brief Construct a new Trapezoid Profile object + * + * @param max_v Maximum velocity the robot can run at + * @param accel Maximum acceleration of the robot + */ + TrapezoidProfile(double max_v, double accel); + + /** + * @brief Run the trapezoidal profile based on the time that's ellapsed + * + * @param time_s Time since start of movement + * @return motion_t Position, velocity and acceleration + */ + motion_t calculate(double time_s); + + /** + * set_endpts defines a start and end position + * @param start the starting position of the path + * @param end the ending position of the path + */ + void set_endpts(double start, double end); + + /** + * set_accel sets the acceleration this profile will use (the left and right legs of the trapezoid) + * @param accel the acceleration amount to use + */ + void set_accel(double accel); + + /** + * sets the maximum velocity for the profile + * (the height of the top of the trapezoid) + * @param max_v the maximum velocity the robot can travel at + */ + void set_max_v(double max_v); + + /** + * uses the kinematic equations to and specified accel and max_v to figure out how long moving along the profile would take + * @return the time the path will take to travel + */ + double get_movement_time(); + + private: + double start, end; ///< the start and ending position of the profile + double max_v; ///< the maximum velocity to travel at for this profile + double accel; ///< the rate of acceleration to use for this profile. + double time; ///< the current point in time along the path + - /** - * Calculate the next segment of the trapezoid motion profile - * - * @param s segment starting position - * @param v segment starting velocity - * @return the next segment of the trapezoid motion profile - */ - trapezoid_profile_segment_t calculate_next_segment(double s, double v); }; \ No newline at end of file diff --git a/include/utils/state_machine.h b/include/utils/state_machine.h new file mode 100644 index 0000000..f821180 --- /dev/null +++ b/include/utils/state_machine.h @@ -0,0 +1,206 @@ +#pragma once +#include +#include +#include + +/** + * @brief State Machine :)))))) + * A fun fun way of controlling stateful subsystems - used in the 2023-2024 Over + * Under game for our overly complex intake-cata subsystem (see there for an + * example) + * The statemachine runs in a background thread and a user thread can interact + * with it through current_state and send_message. + * + * Designwise: + * the System class should hold onto any motors, feedback controllers, etc that + * are persistent in the system States themselves should hold any data that + * *only* that state needs. For example if a state should be exitted after a + * certain amount of time, it should hold a timer rather than the System holding + * that timer. (see Junder from 2024 for an example of this design) + * + * @tparam System The system that this is the base class of `class Thing : + * public StateMachine + * @tparam IDType The ID enum that recognizes states. Hint hint, use an `enum + * class` + * @tparam Message the message enum that a state or an outside can send and that + * states respond to + * @tparam delay_ms the delay to wait between each state processing to allow + * other threads to work + * @tparam do_log true if you want print statements describing incoming messages + * and current states. If true, it is expected that IDType and Message have a + * function called to_string that takes them as its only parameter and returns a + * std::string + */ +template +class StateMachine { + static_assert(std::is_enum::value, + "Message should be an enum (it's easier that way)"); + static_assert(std::is_enum::value, + "IDType should be an enum (it's easier that way)"); + + public: + /** + * @brief MaybeMessage + * a message of Message type or nothing + * MaybeMessage m = {}; // empty + * MaybeMessage m = Message::EnumField1 + */ + class MaybeMessage { + public: + /** + * @brief Empty message - when theres no message + */ + MaybeMessage() : exists(false) {} + /** + * @brief Create a maybemessage with a message + * @param msg the message to hold on to + */ + MaybeMessage(Message msg) : exists(true), thing(msg) {} + /** + * @brief check if the message is here + * @return true if there is a message + */ + bool has_message() { return exists; } + /** + * @brief Get the message stored. The return value is invalid unless + * has_message returned true + * @return The message if it exists. Undefined otherwise + */ + Message message() { return thing; } + + private: + bool exists; + Message thing; + }; + /** + * Abstract class that all states for this machine must inherit from + * States MUST override respond() and id() in order to function correctly + * (the compiler won't have it any other way) + */ + struct State { + // run once when we enter the state + virtual void entry(System &) {} + // run continously while in the state + virtual MaybeMessage work(System &) { return {}; } + // run once when we exit the state + virtual void exit(System &) {} + // respond to a message when one comes in + virtual State *respond(System &s, Message m) = 0; + // Identify + virtual IDType id() const = 0; + + // virtual destructor cuz c++ + virtual ~State() {} + }; + + // Data that gets passed to the runner thread. Don't worry too much about + // this + using thread_data = std::pair; + + /** + * @brief Construct a state machine and immediatly start running it + * @param initial the state that the machine will begin in + */ + StateMachine(State *initial) + : runner(thread_runner, new thread_data{initial, this}) {} + + /** + * @brief retrieve the current state of the state machine. This is safe to + * call from external threads + * @return the current state + */ + IDType current_state() const { + mut.lock(); + auto t = cur_type; + mut.unlock(); + return t; + } + /** + * @brief send a message to the state machine from outside + * @param msg the message to send + * This is safe to call from external threads + */ + void send_message(Message msg) { + mut.lock(); + incoming_msg = msg; + mut.unlock(); + } + + private: + vex::task runner; + mutable vex::mutex mut; + MaybeMessage incoming_msg; + IDType cur_type; + + /** + * @brief the thread that does the running of the state machine. + * @param vptr the thread_data that we get passed to begin. cast it back + * @return return value of thread (the thread never ends so this doesn't + * really matter) + */ + static int thread_runner(void *vptr) { + thread_data *ptr = static_cast(vptr); + State *cur_state = ptr->first; + + StateMachine &sys = *ptr->second; + System &derived = *static_cast(&sys); + + cur_state->entry(derived); + + sys.cur_type = cur_state->id(); + + auto respond_to_message = [&](Message msg) { + if (do_log) { + printf("responding to msg: %s\n", to_string(msg).c_str()); + fflush(stdout); + } + + State *next_state = cur_state->respond(derived, msg); + + if (cur_state != next_state) { + // switched states + sys.mut.lock(); + + cur_state->exit(derived); + next_state->entry(derived); + + delete cur_state; + + cur_state = next_state; + sys.cur_type = cur_state->id(); + + sys.mut.unlock(); + } + }; + + while (true) { + if (do_log) { + std::string str = to_string(cur_state->id()); + std::string str2 = to_string(sys.cur_type); + + printf("state: %s %s\n", str.c_str(), str2.c_str()); + } + + // Internal Message passed + MaybeMessage internal_msg = cur_state->work(derived); + + if (internal_msg.has_message()) { + respond_to_message(internal_msg.message()); + } + + // External Message passed + sys.mut.lock(); + MaybeMessage incoming = sys.incoming_msg; + sys.incoming_msg = {}; + sys.mut.unlock(); + + if (incoming.has_message()) { + respond_to_message(incoming.message()); + } + + vexDelay(delay_ms); + } + return 0; + } +}; diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 3c33872..b665687 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -321,8 +321,8 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb double initial_dist = OdometryBase::pos_diff(odometry->get_position(), {.x = x, .y = y}); // Reset the control loops - correction_pid.init(0, 0, 0, 0); - feedback.init(-initial_dist, 0, odometry->get_speed(), fabs(end_speed)); + correction_pid.init(0, 0); + feedback.init(-initial_dist, 0); correction_pid.set_limits(-1, 1); feedback.set_limits(-1, 1); @@ -475,7 +475,7 @@ bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double m if (!func_initialized) { double initial_delta = OdometryBase::smallest_angle(odometry->get_position().rot, heading_deg); - feedback.init(-initial_delta, 0, odometry->get_angular_speed_deg(), end_speed); + feedback.init(-initial_delta, 0); feedback.set_limits(-fabs(max_speed), fabs(max_speed)); func_initialized = true; @@ -555,9 +555,9 @@ bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback if (!func_initialized) { if (dir != directionType::rev) { - feedback.init(-estimate_path_length(points), 0, odometry->get_speed(), end_speed); + feedback.init(-estimate_path_length(points), 0); } else { - feedback.init(estimate_path_length(points), 0, odometry->get_speed(), end_speed); + feedback.init(estimate_path_length(points), 0); } func_initialized = true; diff --git a/src/utils/command_structure/auto_command.cpp b/src/utils/command_structure/auto_command.cpp index 5bce832..c6cdbbd 100644 --- a/src/utils/command_structure/auto_command.cpp +++ b/src/utils/command_structure/auto_command.cpp @@ -1,334 +1,271 @@ #include "../core/include/utils/command_structure/auto_command.h" -class OrCondition : public Condition -{ +class OrCondition : public Condition { public: - OrCondition(Condition *A, Condition *B) : A(A), B(B) {} - bool test() override - { - bool a = A->test(); - bool b = B->test(); - return a | b; - } + OrCondition(Condition *A, Condition *B) : A(A), B(B) {} + bool test() override { + bool a = A->test(); + bool b = B->test(); + return a | b; + } private: - Condition *A; - Condition *B; + Condition *A; + Condition *B; }; -class AndCondition : public Condition -{ +class AndCondition : public Condition { public: - AndCondition(Condition *A, Condition *B) : A(A), B(B) {} - bool test() override - { - bool a = A->test(); - bool b = B->test(); - return a & b; - } + AndCondition(Condition *A, Condition *B) : A(A), B(B) {} + bool test() override { + bool a = A->test(); + bool b = B->test(); + return a & b; + } private: - Condition *A; - Condition *B; + Condition *A; + Condition *B; }; -Condition *Condition::Or(Condition *b) -{ - return new OrCondition(this, b); -} +Condition *Condition::Or(Condition *b) { return new OrCondition(this, b); } -Condition *Condition::And(Condition *b) -{ - return new AndCondition(this, b); -} +Condition *Condition::And(Condition *b) { return new AndCondition(this, b); } -bool FunctionCondition::test() -{ - return cond(); -} +bool FunctionCondition::test() { return cond(); } IfTimePassed::IfTimePassed(double time_s) : time_s(time_s), tmr() {} -bool IfTimePassed::test() -{ - return tmr.value() > time_s; -} +bool IfTimePassed::test() { return tmr.value() > time_s; } -InOrder::InOrder(std::queue cmds) : cmds(cmds) -{ - timeout_seconds = -1.0; // never timeout unless with_timeout is explicitly called +InOrder::InOrder(std::queue cmds) : cmds(cmds) { + timeout_seconds = + -1.0; // never timeout unless with_timeout is explicitly called } -InOrder::InOrder(std::initializer_list cmds) : cmds(cmds) -{ - timeout_seconds = -1.0; +InOrder::InOrder(std::initializer_list cmds) : cmds(cmds) { + timeout_seconds = -1.0; } -bool InOrder::run() -{ - // outer loop finished - if (cmds.size() == 0 && current_command == nullptr) - { - return true; - } - // retrieve and remove command at the front of the queue - if (current_command == nullptr) - { - printf("TAKING INORDER: len = %d\n", cmds.size()); - current_command = cmds.front(); - cmds.pop(); - tmr.reset(); - } - - // run command - bool cmd_finished = current_command->run(); - if (cmd_finished) - { - printf("InOrder Cmd finished\n"); - current_command = nullptr; - return false; // continue onto next command - } - - double seconds = tmr.value(); - - bool should_timeout = current_command->timeout_seconds > 0.0; - bool doTimeout = should_timeout && seconds > current_command->timeout_seconds; - if (current_command->true_to_end != nullptr) - { - doTimeout = doTimeout || current_command->true_to_end->test(); - } - - // timeout - if (doTimeout) - { - printf("InOrder timed out\n"); - current_command->on_timeout(); - current_command = nullptr; - return false; - } +bool InOrder::run() { + // outer loop finished + if (cmds.size() == 0 && current_command == nullptr) { + return true; + } + // retrieve and remove command at the front of the queue + if (current_command == nullptr) { + printf("TAKING INORDER: len = %d\n", cmds.size()); + current_command = cmds.front(); + cmds.pop(); + tmr.reset(); + } + + // run command + bool cmd_finished = current_command->run(); + if (cmd_finished) { + printf("InOrder Cmd finished\n"); + current_command = nullptr; + return false; // continue onto next command + } + + double seconds = tmr.value(); + + bool should_timeout = current_command->timeout_seconds > 0.0; + bool doTimeout = should_timeout && seconds > current_command->timeout_seconds; + if (current_command->true_to_end != nullptr) { + doTimeout = doTimeout || current_command->true_to_end->test(); + } + + // timeout + if (doTimeout) { + printf("InOrder timed out\n"); + current_command->on_timeout(); + current_command = nullptr; return false; + } + return false; } -void InOrder::on_timeout() -{ - if (current_command != nullptr) - { - current_command->on_timeout(); - } +void InOrder::on_timeout() { + if (current_command != nullptr) { + current_command->on_timeout(); + } } -struct parallel_runner_info -{ - int index; - std::vector *runners; - AutoCommand *cmd; +struct parallel_runner_info { + int index; + std::vector *runners; + AutoCommand *cmd; }; -static int parallel_runner(void *arg) -{ - parallel_runner_info *ri = (parallel_runner_info *)arg; - vex::timer tmr; - while (1) - { - bool finished = ri->cmd->run(); - if (finished) - { - break; - } - double t = (double)(tmr.time()) / 1000.0; - bool timed_out = t > ri->cmd->timeout_seconds; - bool doTimeout = timed_out && (ri->cmd->timeout_seconds > 0); - if (ri->cmd->true_to_end != nullptr) - { - doTimeout = doTimeout || ri->cmd->true_to_end->test(); - } - if (doTimeout) - { - ri->cmd->on_timeout(); - } - vexDelay(20); +static int parallel_runner(void *arg) { + parallel_runner_info *ri = (parallel_runner_info *)arg; + vex::timer tmr; + while (1) { + bool finished = ri->cmd->run(); + if (finished) { + break; } - - if ((*ri->runners)[ri->index] != nullptr) - { - delete (*ri->runners)[ri->index]; - (*ri->runners)[ri->index] = nullptr; + double t = (double)(tmr.time()) / 1000.0; + bool timed_out = t > ri->cmd->timeout_seconds; + bool doTimeout = timed_out && (ri->cmd->timeout_seconds > 0); + if (ri->cmd->true_to_end != nullptr) { + doTimeout = doTimeout || ri->cmd->true_to_end->test(); + } + if (doTimeout) { + ri->cmd->on_timeout(); } - return 0; + vexDelay(20); + } + + if ((*ri->runners)[ri->index] != nullptr) { + delete (*ri->runners)[ri->index]; + (*ri->runners)[ri->index] = nullptr; + } + return 0; } // wait for all to finish -Parallel::Parallel(std::initializer_list cmds) : cmds(cmds), runners(0) {} - -bool Parallel::run() -{ - if (runners.size() == 0) - { - // not initialized yet - for (int i = 0; i < cmds.size(); i++) - { - parallel_runner_info *ri = new parallel_runner_info{ - .index = i, - .runners = &runners, - .cmd = cmds[i], - }; - runners.push_back(new vex::task(parallel_runner, ri)); - } +Parallel::Parallel(std::initializer_list cmds) + : cmds(cmds), runners(0) {} + +bool Parallel::run() { + if (runners.size() == 0) { + // not initialized yet + for (int i = 0; i < cmds.size(); i++) { + parallel_runner_info *ri = new parallel_runner_info{ + .index = i, + .runners = &runners, + .cmd = cmds[i], + }; + runners.push_back(new vex::task(parallel_runner, ri)); } + } - bool all_finished = true; + bool all_finished = true; - for (int i = 0; i < cmds.size(); i++) - { - if (runners[i] != nullptr) - { - all_finished = false; - } + for (int i = 0; i < cmds.size(); i++) { + if (runners[i] != nullptr) { + all_finished = false; } - return all_finished; + } + return all_finished; } -void Parallel::on_timeout() -{ - for (int i = 0; i < runners.size(); i++) - { - - if (runners[i] != nullptr) - { - runners[i]->stop(); - if (cmds[i] != nullptr) - { - cmds[i]->on_timeout(); - } - delete runners[i]; - runners[i] = nullptr; - if (cmds[i] != nullptr) - { - delete cmds[i]; - cmds[i] = nullptr; - } - } +void Parallel::on_timeout() { + for (int i = 0; i < runners.size(); i++) { + + if (runners[i] != nullptr) { + runners[i]->stop(); + if (cmds[i] != nullptr) { + cmds[i]->on_timeout(); + } + delete runners[i]; + runners[i] = nullptr; + if (cmds[i] != nullptr) { + delete cmds[i]; + cmds[i] = nullptr; + } } + } + runners.clear(); } -Branch::Branch(Condition *cond, AutoCommand *false_choice, AutoCommand *true_choice) : false_choice(false_choice), true_choice(true_choice), cond(cond), choice(false), chosen(false), tmr() {} +Branch::Branch(Condition *cond, AutoCommand *false_choice, + AutoCommand *true_choice) + : false_choice(false_choice), true_choice(true_choice), cond(cond), + choice(false), chosen(false), tmr() {} -Branch::~Branch() -{ - delete false_choice; - delete true_choice; +Branch::~Branch() { + delete false_choice; + delete true_choice; }; -bool Branch::run() -{ - if (!chosen) - { - choice = cond->test(); - chosen = true; +bool Branch::run() { + if (!chosen) { + choice = cond->test(); + chosen = true; + } + + double seconds = static_cast(tmr.time()) / 1000.0; + if (choice == false) { + if (seconds > false_choice->timeout_seconds && + false_choice->timeout_seconds != -1) { + false_choice->on_timeout(); } - - double seconds = static_cast(tmr.time()) / 1000.0; - if (choice == false) - { - if (seconds > false_choice->timeout_seconds && false_choice->timeout_seconds != -1) - { - false_choice->on_timeout(); - } - return false_choice->run(); - } - else - { - if (seconds > true_choice->timeout_seconds && true_choice->timeout_seconds != -1) - { - true_choice->on_timeout(); - } - return true_choice->run(); + return false_choice->run(); + } else { + if (seconds > true_choice->timeout_seconds && + true_choice->timeout_seconds != -1) { + true_choice->on_timeout(); } + return true_choice->run(); + } +} +void Branch::on_timeout() { + if (!chosen) { + // dont need to do anything + return; + } + + if (choice == false) { + false_choice->on_timeout(); + } else { + true_choice->on_timeout(); + } } -void Branch::on_timeout() -{ - if (!chosen) - { - // dont need to do anything - return; - } - if (choice == false) - { - false_choice->on_timeout(); +static int async_runner(void *arg) { + AutoCommand *cmd = (AutoCommand *)arg; + vex::timer tmr; + while (1) { + bool finished = cmd->run(); + if (finished) { + break; } - else - { - true_choice->on_timeout(); + double t = (double)(tmr.time()) / 1000.0; + bool timed_out = t > cmd->timeout_seconds; + bool doTimeout = timed_out && cmd->timeout_seconds > 0; + if (cmd->true_to_end != nullptr) { + doTimeout = doTimeout || cmd->true_to_end->test(); } -} - -static int async_runner(void *arg) -{ - AutoCommand *cmd = (AutoCommand *)arg; - vex::timer tmr; - while (1) - { - bool finished = cmd->run(); - if (finished) - { - break; - } - double t = (double)(tmr.time()) / 1000.0; - bool timed_out = t > cmd->timeout_seconds; - bool doTimeout = timed_out && cmd->timeout_seconds > 0; - if (cmd->true_to_end != nullptr) - { - doTimeout = doTimeout || cmd->true_to_end->test(); - } - if (doTimeout) - { - cmd->on_timeout(); - break; - } - vexDelay(20); + if (doTimeout) { + cmd->on_timeout(); + break; } - delete cmd; + vexDelay(20); + } + delete cmd; - return 0; + return 0; } -bool Async::run() -{ - vex::task *t = new vex::task(async_runner, (void *)cmd); - (void)t; - // lmao get memory leaked - return true; +bool Async::run() { + vex::task *t = new vex::task(async_runner, (void *)cmd); + (void)t; + // lmao get memory leaked + return true; } -RepeatUntil::RepeatUntil(InOrder cmds, size_t times) : RepeatUntil(cmds, new TimesTestedCondition(times)) -{ - timeout_seconds = 999999; +RepeatUntil::RepeatUntil(InOrder cmds, size_t times) + : RepeatUntil(cmds, new TimesTestedCondition(times)) { + timeout_seconds = 999999; } -RepeatUntil::RepeatUntil(InOrder cmds, Condition *cond) : cmds(cmds), working_cmds(new InOrder(cmds)), cond(cond) -{ - timeout_seconds = 999999; +RepeatUntil::RepeatUntil(InOrder cmds, Condition *cond) + : cmds(cmds), working_cmds(new InOrder(cmds)), cond(cond) { + timeout_seconds = 999999; } +bool RepeatUntil::run() { + bool finished = working_cmds->run(); + if (!finished) { + // return if we're not done yet + return false; + } + // this run finished + bool res = cond->test(); + // we should finish + if (res) { + return true; + } + working_cmds = new InOrder(cmds); -bool RepeatUntil::run() -{ - bool finished = working_cmds->run(); - if (!finished) - { - // return if we're not done yet - return false; - } - // this run finished - - bool res = cond->test(); - // we should finish - if (res) - { - return true; - } - working_cmds = new InOrder(cmds); - - - return false; + return false; } -void RepeatUntil::on_timeout() -{ - working_cmds->on_timeout(); -} \ No newline at end of file +void RepeatUntil::on_timeout() { working_cmds->on_timeout(); } \ No newline at end of file diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index 79eb29c..efae140 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -101,7 +101,7 @@ void CommandController::run() // run the current command until it returns true or we timeout while (!next_cmd->run()) { - vexDelay(20); + vexDelay(5); if (!doTimeout) { diff --git a/src/utils/controls/bang_bang.cpp b/src/utils/controls/bang_bang.cpp index 161a951..fcc1c70 100644 --- a/src/utils/controls/bang_bang.cpp +++ b/src/utils/controls/bang_bang.cpp @@ -3,7 +3,7 @@ BangBang::BangBang(double threshhold, double low, double high) : setpt(low), sensor_val(low), lower_bound(low), upper_bound(high), threshhold(threshhold) {} -void BangBang::init(double start_pt, double set_pt, double, double) +void BangBang::init(double start_pt, double set_pt) { sensor_val = start_pt; setpt = set_pt; diff --git a/src/utils/controls/motion_controller.cpp b/src/utils/controls/motion_controller.cpp index eba94cc..3ba4715 100644 --- a/src/utils/controls/motion_controller.cpp +++ b/src/utils/controls/motion_controller.cpp @@ -1,123 +1,119 @@ #include "../core/include/utils/controls/motion_controller.h" -#include "../core/include/subsystems/screen.h" #include "../core/include/utils/math_util.h" #include /** - * @brief Construct a new Motion Controller object - * - * @param config The definition of how the robot is able to move - * max_v Maximum velocity the movement is capable of - * accel Acceleration / deceleration of the movement - * pid_cfg Definitions of kP, kI, and kD - * ff_cfg Definitions of kS, kV, and kA - */ +* @brief Construct a new Motion Controller object +* +* @param config The definition of how the robot is able to move +* max_v Maximum velocity the movement is capable of +* accel Acceleration / deceleration of the movement +* pid_cfg Definitions of kP, kI, and kD +* ff_cfg Definitions of kS, kV, and kA +*/ MotionController::MotionController(m_profile_cfg_t &config) - : config(config), pid(config.pid_cfg), ff(config.ff_cfg), - profile(config.max_v, config.accel) {} +: config(config), pid(config.pid_cfg), ff(config.ff_cfg), profile(config.max_v, config.accel) +{} /** * @brief Initialize the motion profile for a new movement * This will also reset the PID and profile timers. * @param start_pt Movement starting position - * @param end_pt Movement ending posiiton - * @param start_vel Movement starting velocity - * @param end_vel Movement ending velocity + * @param end_pt Movement ending posiiton */ -void MotionController::init(double start_pt, double end_pt, double start_vel, - double end_vel) { +void MotionController::init(double start_pt, double end_pt) +{ profile.set_endpts(start_pt, end_pt); - profile.set_vel_endpts(start_vel, end_vel); pid.reset(); tmr.reset(); - - this->end_pt = end_pt; } /** - * @brief Update the motion profile with a new sensor value - * - * @param sensor_val Value from the sensor - * @return the motor input generated from the motion profile - */ -double MotionController::update(double sensor_val) { - cur_motion = profile.calculate(tmr.time(timeUnits::sec), sensor_val); +* @brief Update the motion profile with a new sensor value +* +* @param sensor_val Value from the sensor +* @return the motor input generated from the motion profile +*/ +double MotionController::update(double sensor_val) +{ + cur_motion = profile.calculate(tmr.time(timeUnits::sec)); pid.set_target(cur_motion.pos); - pid.update(sensor_val); + pid.update(sensor_val, cur_motion.vel); - this->current_pos = sensor_val; + out = pid.get() + ff.calculate(cur_motion.vel, cur_motion.accel, pid.get()); - out = pid.get() + ff.calculate(cur_motion.vel, cur_motion.accel, pid.get()); - - if (lower_limit != upper_limit) { + if(lower_limit != upper_limit) out = clamp(out, lower_limit, upper_limit); - } - + return out; } /** * @return the last saved result from the feedback controller */ -double MotionController::get() { return out; } +double MotionController::get() +{ + return out; +} /** - * Clamp the upper and lower limits of the output. If both are 0, no limits - * should be applied. - * + * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * * @param lower Upper limit * @param upper Lower limit */ -void MotionController::set_limits(double lower, double upper) { +void MotionController::set_limits(double lower, double upper) +{ lower_limit = lower; upper_limit = upper; } -/** +/** * @return Whether or not the movement has finished, and the PID * confirms it is on target */ -bool MotionController::is_on_target() { - return (tmr.time(timeUnits::sec) > profile.get_movement_time()) && - pid.is_on_target() && - fabs(end_pt - current_pos) < pid.config.deadband; +bool MotionController::is_on_target() +{ + return (tmr.time(timeUnits::sec) > profile.get_movement_time()) && pid.is_on_target(); } /** * @return The current postion, velocity and acceleration setpoints - */ -motion_t MotionController::get_motion() const { return cur_motion; } +*/ +motion_t MotionController::get_motion() +{ + return cur_motion; +} /** - * This method attempts to characterize the robot's drivetrain and automatically - * tune the feedforward. It does this by first calculating the kS (voltage to - * overcome static friction) by slowly increasing the voltage until it moves. - * - * Next is kV (voltage to sustain a certain velocity), where the robot will - * record it's steady-state velocity at 'pct' speed. - * - * Finally, kA (voltage needed to accelerate by a certain rate), where the robot - * will record the entire movement's velocity and acceleration, record a plot of - * [X=(pct-kV*V-kS), Y=(Acceleration)] along the movement, and since kA*Accel = - * pct-kV*V-kS, the reciprocal of the linear regression is the kA value. - * + * This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. + * It does this by first calculating the kS (voltage to overcome static friction) by slowly increasing + * the voltage until it moves. + * + * Next is kV (voltage to sustain a certain velocity), where the robot will record it's steady-state velocity + * at 'pct' speed. + * + * Finally, kA (voltage needed to accelerate by a certain rate), where the robot will record the entire movement's + * velocity and acceleration, record a plot of [X=(pct-kV*V-kS), Y=(Acceleration)] along the movement, + * and since kA*Accel = pct-kV*V-kS, the reciprocal of the linear regression is the kA value. + * * @param drive The tankdrive to operate on * @param odometry The robot's odometry subsystem * @param pct Maximum velocity in percent (0->1.0) * @param duration Amount of time the robot should be moving for the test * @return A tuned feedforward object */ -FeedForward::ff_config_t -MotionController::tune_feedforward(TankDrive &drive, OdometryTank &odometry, - double pct, double duration) { +FeedForward::ff_config_t MotionController::tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct, double duration) +{ FeedForward::ff_config_t out = {}; - + pose_t start_pos = odometry.get_position(); // ========== kS Tuning ========= // Start at 0 and slowly increase the power until the robot starts moving double power = 0; - while (odometry.pos_diff(start_pos, odometry.get_position()) < 0.05) { + while(odometry.pos_diff(start_pos, odometry.get_position()) < 0.05) + { drive.drive_tank(power, power, 1); power += 0.001; vexDelay(100); @@ -125,24 +121,22 @@ MotionController::tune_feedforward(TankDrive &drive, OdometryTank &odometry, out.kS = power; drive.stop(); + // ========== kV / kA Tuning ========= - std::vector> vel_data_points; // time, velocity + std::vector> vel_data_points; // time, velocity std::vector> accel_data_points; // time, accel double max_speed = 0; - double max_accel = 0; timer tmr; double time; MovingAverage vel_ma(3); MovingAverage accel_ma(3); - // Move the robot forward at a fixed percentage for X seconds while taking - // velocity and accel measurements - - drive.drive_tank(pct, pct, 1); - do { + // Move the robot forward at a fixed percentage for X seconds while taking velocity and accel measurements + do + { time = tmr.time(sec); vel_ma.add_entry(odometry.get_speed()); @@ -150,100 +144,41 @@ MotionController::tune_feedforward(TankDrive &drive, OdometryTank &odometry, double speed = vel_ma.get_value(); double accel = accel_ma.get_value(); + // For kV: - if (speed > max_speed) { + if(speed > max_speed) max_speed = speed; - } - if (accel > max_accel) { - max_accel = accel; - } // For kA: // Filter out the acceleration dampening due to motor inductance - if (time > 0.25) { + if(time > 0.25) + { vel_data_points.push_back(std::pair(time, speed)); accel_data_points.push_back(std::pair(time, accel)); } - // Theoretical polling rate = 100hz (it won't be that much, cause, - // y'know, vex.) - vexDelay(10); - } while (time < duration); + // Theoretical polling rate = 100hz (it won't be that much, cause, y'know, vex.) + vexDelay(10); + } while(time < duration); drive.stop(); // Calculate kV (volts/12 per unit per second) out.kV = (pct - out.kS) / max_speed; - printf("Max speed achieved: %.4f\n", max_speed); - printf("Max accel achieved: %.4f\n", max_accel); - // Calculate kA (volts/12 per unit per second^2) std::vector> accel_per_pct; - for (int i = 0; i < vel_data_points.size(); i++) { + for (int i = 0; i < vel_data_points.size(); i++) + { accel_per_pct.push_back(std::pair( - pct - out.kS - - (vel_data_points[i].second * - out.kV), // Acceleration-causing percent (X variable) - accel_data_points[i].second // Measured acceleration (Y variable) - )); + pct - out.kS - (vel_data_points[i].second * out.kV), // Acceleration-causing percent (X variable) + accel_data_points[i].second // Measured acceleration (Y variable) + )); } - + // kA is the reciprocal of the slope of the linear regression double regres_slope = calculate_linear_regression(accel_per_pct).first; - out.kA = 1.0 / regres_slope; + out.kA = 1.0 / regres_slope; return out; -} - -class MotionControllerPage : public screen::Page { - public: - MotionControllerPage(const MotionController &mc) : mc(mc) {} - - void update(bool was_pressed, int x, int y) override {} - void draw(vex::brain::lcd &screen, bool first_draw, - unsigned int frame_number) { - const motion_t mot = mc.get_motion(); - - // Text - top right - screen.printAt(240, 20, "pos: %.2fin", mot.pos); - screen.printAt(240, 40, "vel: %.2fin", mot.vel); - screen.printAt(240, 60, "acc: %.2fin", mot.accel); - screen.printAt(240, 80, "%.2fs of %.2fs", mc.tmr.value(), - mc.profile.get_movement_time()); - - // Trapezoid - bottom right - const int32_t trap_width = 200; - const int32_t trap_height = 98; - const double seconds = mc.tmr.value(); - const double full_time = mc.profile.get_movement_time(); - const double x_pct = seconds / full_time; - const double y_pct = mot.vel / mc.profile.get_max_v(); - const int32_t x_pos = (int32_t)(x_pct * trap_width) + 240; - const int32_t y_pos = (int32_t)(-y_pct * trap_height) + 100; - const int32_t max_vel_y = 120; - const int32_t end_acc_x = 260; - const int32_t start_dec_x = 420; - - // trapezoid - screen.setPenColor(vex::red); - // accelerating - screen.drawLine(240, 200, end_acc_x, max_vel_y); - // staying - screen.drawLine(end_acc_x, max_vel_y, start_dec_x, max_vel_y); - // decellerating - screen.drawLine(440, 200, start_dec_x, max_vel_y); - - // dot where we are - screen.setFillColor(vex::red); - screen.setPenColor(vex::white); - screen.drawCircle(x_pos, y_pos, 3); - } - - private: - const MotionController &mc; -}; - -screen::Page *MotionController::Page() { - return new MotionControllerPage(*this); } \ No newline at end of file diff --git a/src/utils/controls/pid.cpp b/src/utils/controls/pid.cpp index 2c46495..88696b6 100644 --- a/src/utils/controls/pid.cpp +++ b/src/utils/controls/pid.cpp @@ -6,9 +6,9 @@ */ PID::PID(pid_config_t &config) : config(config) { pid_timer.reset(); } -void PID::init(double start_pt, double set_pt, double, double end_vel) { +void PID::init(double start_pt, double set_pt) { set_target(set_pt); - target_vel = end_vel; + target_vel = 0; // TODO change back when trapezoid profiles are fixed sensor_val = start_pt; reset(); } @@ -20,17 +20,31 @@ void PID::init(double start_pt, double set_pt, double, double end_vel) { * are measuring * @return the new output. What would be returned by PID::get() */ -double PID::update(double sensor_val) { +double PID::update(double sensor_val) +{ + return update(sensor_val, 0); +} + +/** + * Update the PID loop by taking the time difference from last update, + * and running the PID formula with the new sensor data + * @param sensor_val the distance, angle, encoder position or whatever it is we + * are measuring + * @param v_setpt Expected velocity setpoint, to subtract from the D term (for + * velocity control) + * @return the new output. What would be returned by PID::get() + */ +double PID::update(double sensor_val, double v_setpt) { this->sensor_val = sensor_val; - double time_delta = pid_timer.value() - last_time; + double time_delta = (pid_timer.systemHighResolution() / 1000000.0) - last_time; // Avoid a divide by zero error double d_term = 0; - if (time_delta != 0) { - d_term = config.d * (get_error() - last_error) / time_delta; - } else if (last_time != 0) { + if (time_delta != 0.0) { + d_term = config.d * (((get_error() - last_error) / time_delta) - v_setpt); + } else if (last_time != 0.0) { printf( "(pid.cpp): Warning - running PID without a delay is just a P loop!\n"); } @@ -50,7 +64,7 @@ double PID::update(double sensor_val) { // I term out += config.i * accum_error; - last_time = pid_timer.value(); + last_time = pid_timer.systemHighResolution() / 1000000.0; last_error = get_error(); // Enable clamping if the limit is not 0 diff --git a/src/utils/controls/pidff.cpp b/src/utils/controls/pidff.cpp index f8f38c7..b98e356 100644 --- a/src/utils/controls/pidff.cpp +++ b/src/utils/controls/pidff.cpp @@ -14,9 +14,8 @@ PIDFF::PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg) * @param start_pt the current sensor value * @param set_pt where the sensor value should be */ -void PIDFF::init(double start_pt, double set_pt, double start_vel, - double end_vel) { - pid.init(start_pt, set_pt, start_vel, end_vel); +void PIDFF::init(double start_pt, double set_pt) { + pid.init(start_pt, set_pt); } void PIDFF::set_target(double set_pt) { pid.set_target(set_pt); } diff --git a/src/utils/controls/take_back_half.cpp b/src/utils/controls/take_back_half.cpp index 7defe78..72418df 100644 --- a/src/utils/controls/take_back_half.cpp +++ b/src/utils/controls/take_back_half.cpp @@ -11,7 +11,7 @@ TakeBackHalf::TakeBackHalf(double gain, double first_cross_split, double thresh) first_cross = true; } -void TakeBackHalf::init(double start_pt, double set_pt, double, double) +void TakeBackHalf::init(double start_pt, double set_pt) { if (set_pt == target) { diff --git a/src/utils/controls/trapezoid_profile.cpp b/src/utils/controls/trapezoid_profile.cpp new file mode 100644 index 0000000..c2fbfc7 --- /dev/null +++ b/src/utils/controls/trapezoid_profile.cpp @@ -0,0 +1,117 @@ +#include "../core/include/utils/controls/trapezoid_profile.h" +#include "../core/include/utils/math_util.h" +#include + + +TrapezoidProfile::TrapezoidProfile(double max_v, double accel) +: start(0), end(0), max_v(max_v), accel(accel) {} + +void TrapezoidProfile::set_max_v(double max_v) +{ + this->max_v = max_v; +} + +void TrapezoidProfile::set_accel(double accel) +{ + this->accel = accel; +} + +void TrapezoidProfile::set_endpts(double start, double end) +{ + this->start = start; + this->end = end; +} + +// Kinematic equations as macros +#define CALC_POS(time_s,a,v,s) ((0.5*(a)*(time_s)*(time_s))+((v)*(time_s))+(s)) +#define CALC_VEL(time_s,a,v) (((a)*(time_s))+(v)) + +/** + * @brief Run the trapezoidal profile based on the time that's ellapsed + * + * @param time_s Time since start of movement + * @return motion_t Position, velocity and acceleration + */ +motion_t TrapezoidProfile::calculate(double time_s) +{ + double delta_pos = end - start; + + // redefine accel and max_v in this scope for negative calcs + double accel_local = this->accel; + double max_v_local = this->max_v; + if(delta_pos < 0) + { + accel_local = -this->accel; + max_v_local = -this->max_v; + } + + // Calculate the time spent during the acceleration / maximum velocity / deceleration stages + double accel_time = max_v_local / accel_local; + double max_vel_time = (delta_pos - (accel_local * accel_time * accel_time)) / max_v_local; + this->time = (2 * accel_time) + max_vel_time; + + // If the time during the "max velocity" state is negative, use an S profile + if (max_vel_time < 0) + { + accel_time = sqrt(fabs(delta_pos / accel)); + max_vel_time = 0; + this->time = 2 * accel_time; + } + + motion_t out; + + // Handle if a bad time is put in + if (time_s < 0) + { + out.pos = start; + out.vel = 0; + out.accel = 0; + return out; + } + + // Handle after the setpoint is reached + if (time_s > 2*accel_time + max_vel_time) + { + out.pos = end; + out.vel = 0; + out.accel = 0; + return out; + } + + // ======== KINEMATIC EQUATIONS ======== + + // Displacement from initial acceleration + if(time_s < accel_time) + { + out.pos = start + CALC_POS(time_s, accel_local, 0, 0); + out.vel = CALC_VEL(time_s, accel_local, 0); + out.accel = accel_local; + return out; + } + + double s_accel = CALC_POS(accel_time, accel_local, 0, 0); + + // Displacement during maximum velocity + if (time_s < accel_time + max_vel_time) + { + out.pos = start + CALC_POS(time_s - accel_time, 0, max_v_local, s_accel); + out.vel = sign(delta_pos) * max_v; + out.accel = 0; + return out; + } + + double s_max_vel = CALC_POS(max_vel_time, 0, max_v_local, s_accel); + + // Displacement during deceleration + out.pos = start + CALC_POS(time_s - (2*accel_time) - max_vel_time, -accel_local, 0, s_accel + s_max_vel); + out.vel = CALC_VEL(time_s - accel_time - max_vel_time, -accel_local, max_v_local); + out.accel = -accel_local; + return out; + +} + +double TrapezoidProfile::get_movement_time() +{ + return time; +} + diff --git a/src/utils/math_util.cpp b/src/utils/math_util.cpp index 6f8e0d6..ba4f394 100644 --- a/src/utils/math_util.cpp +++ b/src/utils/math_util.cpp @@ -91,7 +91,7 @@ double variance(std::vector const &values, double mean) { total += (values[i] - mean) * (values[i] - mean); } - return total; + return total / (values.size() - 1); } /* diff --git a/src/utils/trapezoid_profile.cpp b/src/utils/trapezoid_profile.cpp deleted file mode 100644 index 98014ba..0000000 --- a/src/utils/trapezoid_profile.cpp +++ /dev/null @@ -1,335 +0,0 @@ -#include "../core/include/utils/controls/trapezoid_profile.h" -#include "../core/include/utils/math_util.h" -#include -#include - -const double EPSILON = 0.000005; - -inline double calc_pos(double t, double a, double v, double si) { - return (0.5 * (a) * (t) * (t)) + ((v) * (t)) + (si); -} - -inline double calc_vel(double t, double a, double vi) { - return ((a) * (t)) + (vi); -} - -TrapezoidProfile::TrapezoidProfile(double max_v, double accel) - : si(0), sf(0), vi(0), vf(0), max_v(max_v), accel(accel), segments(), - num_acceleration_phases(0), precalculated(false) {} - -void TrapezoidProfile::set_max_v(double max_v) { - this->max_v = max_v; - - this->precalculated = false; -} - -void TrapezoidProfile::set_accel(double accel) { - this->accel = accel; - - this->precalculated = false; -} - -void TrapezoidProfile::set_endpts(double start, double end) { - this->si = start; - this->sf = end; - - this->precalculated = false; -} - -void TrapezoidProfile::set_vel_endpts(double start, double end) { - this->vi = start; - this->vf = end; - - this->precalculated = false; -} - -motion_t TrapezoidProfile::calculate_time_based(double time_s) { - if (!this->precalculated) { - precalculate(); -} - - int segment_i = 0; - - // position, velocity, acceleration, and time at the beginning of the segment - // we're in - double segment_s = this->si; - double segment_v = this->vi; - double segment_a = this->segments[0].accel; - double segment_t = 0; - - // skip phases based on time - while (segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS && - time_s > segment_t + this->segments[segment_i].duration) { - segment_t += this->segments[segment_i].duration; - segment_s = this->segments[segment_i].pos_after; - segment_v = this->segments[segment_i].vel_after; - segment_i++; - segment_a = this->segments[segment_i].accel; - } - - motion_t out; - - // if we are beyond the last phase, return the position/velocity at the last - // phase - if (segment_i == MAX_TRAPEZOID_PROFILE_SEGMENTS) { - out.accel = 0; - out.pos = this->segments[MAX_TRAPEZOID_PROFILE_SEGMENTS - 1].pos_after; - out.vel = this->segments[MAX_TRAPEZOID_PROFILE_SEGMENTS - 1].vel_after; - return out; - } - - // calculate based on time - out.accel = this->segments[segment_i].accel; - out.vel = calc_vel(time_s - segment_t, segment_a, segment_v); - out.pos = calc_pos(time_s - segment_t, segment_a, segment_v, segment_s); - return out; -} - -motion_t TrapezoidProfile::calculate(double time_s, double pos_s) { - if (!this->precalculated) { - precalculate(); -} - - // printf("%f %f\n", time_s, pos_s); - - int segment_i = 0; - - // position, velocity, acceleration, and time at the beginning of the segment - // we're in - double segment_s = this->si; - double segment_v = this->vi; - double segment_a = this->segments[0].accel; - double segment_t = 0; - - // skip acceleration phases based on time - while (segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS && - segment_i < this->num_acceleration_phases && - time_s > segment_t + this->segments[segment_i].duration) { - segment_t += this->segments[segment_i].duration; - segment_s = this->segments[segment_i].pos_after; - segment_v = this->segments[segment_i].vel_after; - segment_i++; - segment_a = this->segments[segment_i].accel; - } - - // skip other segments based on distance, if we are past the time segments - if (segment_i >= this->num_acceleration_phases) { - while ( - segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS && - ((this->si < this->sf && pos_s > this->segments[segment_i].pos_after) || - (this->si > this->sf && - pos_s < this->segments[segment_i].pos_after))) { - segment_t += this->segments[segment_i].duration; - segment_s = this->segments[segment_i].pos_after; - segment_v = this->segments[segment_i].vel_after; - segment_i++; - segment_a = this->segments[segment_i].accel; - } - } - - motion_t out; - - // if we are beyond the last phase, return the position/velocity at the last - // phase - if (segment_i == MAX_TRAPEZOID_PROFILE_SEGMENTS) { - out.accel = 0; - out.pos = this->segments[MAX_TRAPEZOID_PROFILE_SEGMENTS - 1].pos_after; - out.vel = this->segments[MAX_TRAPEZOID_PROFILE_SEGMENTS - 1].vel_after; - return out; - } - - // if we are in an acceleration phase, calculate based on time - if (segment_i < this->num_acceleration_phases) { - out.accel = segment_a; - out.vel = calc_vel(time_s - segment_t, segment_a, segment_v); - out.pos = calc_pos(time_s - segment_t, segment_a, segment_v, segment_s); - return out; - } - - // otherwise calculate based on distance - out.accel = segment_a; - out.pos = pos_s; - // Calculating the final velocity in uniformly accelerated motion: - // v_f^2 = v_i^2 + 2a(x_f - x_i) - // v_f = sqrt(v_i^2 + 2a(x_f - x_i)) - out.vel = sqrt(segment_v * segment_v + 2 * segment_a * (pos_s - segment_s)); - - // match the sign of the starting velocity of the segment - if (segment_v < 0) { - out.vel *= -1; -} - - return out; -} - -double TrapezoidProfile::get_movement_time() const { return duration; } - -bool TrapezoidProfile::precalculate() { - for (auto &segment : this->segments) { - segment.pos_after = 0; - segment.vel_after = 0; - segment.accel = 0; - segment.duration = 0; - } - this->num_acceleration_phases = 0; - - if (this->accel < EPSILON) { - printf("WARNING: trapezoid motion profile acceleration was negative, or " - "too small\n"); - this->accel = fmin(EPSILON, fabs(this->accel)); - } - - if (this->max_v < EPSILON) { - printf("WARNING: trapezoid motion profile maximum velocity was negative, " - "or too small\n"); - this->max_v = fmin(EPSILON, fabs(this->max_v)); - } - - // make sure vf is within v_max - if (fabs(this->vf) > this->max_v) { - printf("WARNING: trapezoid motion profile target velocity is greater than " - "maximum velocity\n"); - if (this->vf > this->max_v) { - this->vf = this->max_v; - } else { - this->vf = -this->max_v; -} - } - - // if displacement is + but vf is -, or if displacement is - but vf is + - if ((this->si < this->sf && this->vf < 0) || - (this->si > this->sf && this->vf > 0)) { - printf("WARNING: trapezoid motion profile target velocity is in the wrong " - "direction\n"); - this->vf = 0; - } - - double s = this->si, v = this->vi; - - double total_time = 0; - - for (auto &segment : this->segments) { - segment = calculate_next_segment(s, v); - total_time += segment.duration; - - if (fabs(segment.pos_after - this->sf) < EPSILON) { - return true; -} - - // Check if xf is between x and x_next (meaning we overshot the end - // position) - if ((((this->si < this->sf) && (this->sf < segment.pos_after)) || - ((segment.pos_after < this->sf) && (this->sf < this->si))) && - fabs(this->sf - segment.pos_after) > EPSILON) { - // Solve for the exact time to reach self.xf using the quadratic formula - // Given: x = x0 + v0 * t + 0.5 * a * t^2 - double a_coeff = 0.5 * segment.accel; - if (fabs(a_coeff) < EPSILON) { - a_coeff = EPSILON; -} - double b_coeff = v; - double c_coeff = s - this->sf; - - double discriminant = b_coeff * b_coeff - 4.0 * a_coeff * c_coeff; - if (discriminant >= 0) { - double t1 = (-b_coeff + sqrt(discriminant)) / (2 * a_coeff); - double t2 = (-b_coeff - sqrt(discriminant)) / (2 * a_coeff); - - double t_corrected = fmin(t1, t2); - if (t_corrected < 0) { - t_corrected = fmax(t1, t2); - } - segment.duration = t_corrected; - segment.vel_after = calc_vel(segment.duration, segment.accel, v); - segment.pos_after = calc_pos(segment.duration, segment.accel, v, s); - return true; - } else { - printf("ERROR: No real solution to reach sf.\n"); - return false; - } - } - - v = segment.vel_after; - s = segment.pos_after; - duration = total_time; - } - - printf("WARNING: trapezoid motion profile did not reach end position in %d " - "segments (the maximum)\n", - MAX_TRAPEZOID_PROFILE_SEGMENTS); - return false; -} - -trapezoid_profile_segment_t -TrapezoidProfile::calculate_kinetic_motion(double si, double vi, - double v_target) { - trapezoid_profile_segment_t m; - - m.duration = fabs(v_target - vi) / this->accel; - m.vel_after = v_target; - if (vi < v_target) { - m.accel = this->accel; - } else { - m.accel = -this->accel; - } - - m.pos_after = calc_pos(m.duration, m.accel, vi, si); - return m; -} - -trapezoid_profile_segment_t TrapezoidProfile::calculate_next_segment(double s, - double v) { - // d represents the direction of travel, + or - - int d = 1; - if (this->si > this->sf) { - d = -1; - } - - // if going the wrong way, come to a stop - if ((d == 1 && v < -EPSILON) || (d == -1 && v > EPSILON)) { - this->num_acceleration_phases += 1; - return calculate_kinetic_motion(s, v, 0); - } - - // if |v| > max_v, slow down - if (v > this->max_v || v < -this->max_v) { - this->num_acceleration_phases += 1; - return calculate_kinetic_motion(s, v, d * this->max_v); - } - - // how much distance would it take to reach vf in one segment? - trapezoid_profile_segment_t beeline_vf = - calculate_kinetic_motion(s, v, this->vf); - if ((d == 1 && beeline_vf.pos_after > this->sf - EPSILON) || - (d == -1 && beeline_vf.pos_after <= this->sf + EPSILON)) { - // we can't make it to vf - get as close as possible - return beeline_vf; - } - - // we can reach vf in one segment - choose the fastest speed so that that is - // still possible - double v_middle = - d * sqrt(((v * v + this->vf * this->vf) / 2.0) + - this->accel * fabs(this->sf - s) + this->vf * this->vf); - // cap this at our max speed - v_middle = fmax(-this->max_v, fmin(v_middle, this->max_v)); - - // if we aren't at this speed yet, let's get there - if (fabs(v_middle - v) > EPSILON) { - this->num_acceleration_phases += 1; - return calculate_kinetic_motion(s, v, v_middle); - } - - // we are at our max speed - hold it until we have to start slowing down - trapezoid_profile_segment_t out; - out.accel = 0; - double distance = d * fabs(this->sf - beeline_vf.pos_after); - out.pos_after = s + distance; - out.duration = distance / v_middle; - out.vel_after = v_middle; - return out; -} - -double TrapezoidProfile::get_max_v() const { return max_v; }; - -double TrapezoidProfile::get_accel() const { return accel; } \ No newline at end of file From aade2e8117930b220f6edc08992bb80aaf312835 Mon Sep 17 00:00:00 2001 From: Ryan McGee Date: Sun, 25 Feb 2024 13:51:35 -0500 Subject: [PATCH 241/243] Formatted to LLVM & 120 char limit --- include/robot_specs.h | 24 +- include/subsystems/custom_encoder.h | 14 +- include/subsystems/flywheel.h | 45 +- include/subsystems/layout.h | 11 +- include/subsystems/lift.h | 291 ++++----- include/subsystems/mecanum_drive.h | 114 ++-- include/subsystems/odometry/odometry_3wheel.h | 128 ++-- include/subsystems/odometry/odometry_base.h | 257 ++++---- include/subsystems/odometry/odometry_tank.h | 123 ++-- include/subsystems/screen.h | 599 +++++++++--------- include/subsystems/tank_drive.h | 65 +- include/utils/auto_chooser.h | 13 +- .../utils/command_structure/auto_command.h | 80 +-- .../utils/command_structure/basic_command.h | 166 +++-- .../command_structure/command_controller.h | 20 +- .../utils/command_structure/delay_command.h | 40 +- .../utils/command_structure/drive_commands.h | 344 +++++----- .../command_structure/flywheel_commands.h | 150 ++--- include/utils/controls/bang_bang.h | 77 ++- include/utils/controls/feedback_base.h | 67 +- include/utils/controls/feedforward.h | 115 ++-- include/utils/controls/motion_controller.h | 191 +++--- include/utils/controls/pid.h | 55 +- include/utils/controls/take_back_half.h | 94 +-- include/utils/controls/trapezoid_profile.h | 117 ++-- include/utils/generic_auto.h | 54 +- include/utils/geometry.h | 179 ++---- include/utils/graph_drawer.h | 19 +- include/utils/logger.h | 100 ++- include/utils/math_util.h | 30 +- include/utils/moving_average.h | 29 +- include/utils/pure_pursuit.h | 212 +++---- include/utils/serializer.h | 159 ++--- include/utils/state_machine.h | 296 +++++---- include/utils/vector2d.h | 156 +++-- src/subsystems/custom_encoder.cpp | 39 +- src/subsystems/flywheel.cpp | 71 +-- src/subsystems/mecanum_drive.cpp | 188 +++--- src/subsystems/odometry/odometry_3wheel.cpp | 381 ++++++----- src/subsystems/odometry/odometry_base.cpp | 56 +- src/subsystems/odometry/odometry_tank.cpp | 75 +-- src/subsystems/screen.cpp | 65 +- src/subsystems/tank_drive.cpp | 214 +++---- src/utils/auto_chooser.cpp | 33 +- src/utils/command_structure/auto_command.cpp | 28 +- src/utils/command_structure/basic_command.cpp | 46 +- .../command_structure/command_controller.cpp | 61 +- .../command_structure/drive_commands.cpp | 99 ++- .../command_structure/flywheel_commands.cpp | 23 +- src/utils/controls/bang_bang.cpp | 53 +- src/utils/controls/feedforward.cpp | 131 ++-- src/utils/controls/motion_controller.cpp | 234 ++++--- src/utils/controls/pid.cpp | 28 +- src/utils/controls/pidff.cpp | 45 +- src/utils/controls/take_back_half.cpp | 116 ++-- src/utils/controls/trapezoid_profile.cpp | 171 +++-- src/utils/generic_auto.cpp | 79 ++- src/utils/graph_drawer.cpp | 181 +++--- src/utils/logger.cpp | 121 ++-- src/utils/math_util.cpp | 66 +- src/utils/moving_average.cpp | 50 +- src/utils/pure_pursuit.cpp | 211 +++--- src/utils/serializer.cpp | 370 +++++------ src/utils/vector2d.cpp | 94 +-- 64 files changed, 3544 insertions(+), 4219 deletions(-) diff --git a/include/robot_specs.h b/include/robot_specs.h index 9a5fa0c..d853783 100644 --- a/include/robot_specs.h +++ b/include/robot_specs.h @@ -1,25 +1,27 @@ #pragma once -#include "../core/include/utils/controls/pid.h" #include "../core/include/utils/controls/feedback_base.h" +#include "../core/include/utils/controls/pid.h" /** * Main robot characterization struct. - * This will be passed to all the major subsystems + * This will be passed to all the major subsystems * that require info about the robot. * All distance measurements are in inches. */ -typedef struct -{ - double robot_radius; ///< if you were to draw a circle with this radius, the robot would be entirely contained within it +typedef struct { + double + robot_radius; ///< if you were to draw a circle with this radius, the robot would be entirely contained within it - double odom_wheel_diam; ///< the diameter of the wheels used for - double odom_gear_ratio; ///< the ratio of the odometry wheel to the encoder reading odometry data - double dist_between_wheels; ///< the distance between centers of the central drive wheels + double odom_wheel_diam; ///< the diameter of the wheels used for + double odom_gear_ratio; ///< the ratio of the odometry wheel to the encoder reading odometry data + double dist_between_wheels; ///< the distance between centers of the central drive wheels - double drive_correction_cutoff; ///< the distance at which to stop trying to turn towards the target. If we are less than this value, we can continue driving forward to minimize our distance but will not try to spin around to point directly at the target + double drive_correction_cutoff; ///< the distance at which to stop trying to turn towards the target. If we are less + ///< than this value, we can continue driving forward to minimize our distance but + ///< will not try to spin around to point directly at the target - Feedback *drive_feedback; ///< the default feedback for autonomous driving - Feedback *turn_feedback; ///< the defualt feedback for autonomous turning + Feedback *drive_feedback; ///< the default feedback for autonomous driving + Feedback *turn_feedback; ///< the defualt feedback for autonomous turning PID::pid_config_t correction_pid; ///< the pid controller to keep the robot driving in as straight a line as possible } robot_specs_t; \ No newline at end of file diff --git a/include/subsystems/custom_encoder.h b/include/subsystems/custom_encoder.h index 2b87b86..b9d3e96 100644 --- a/include/subsystems/custom_encoder.h +++ b/include/subsystems/custom_encoder.h @@ -5,30 +5,29 @@ * A wrapper class for the vex encoder that allows the use of 3rd party * encoders with different tick-per-revolution values. */ -class CustomEncoder : public vex::encoder -{ +class CustomEncoder : public vex::encoder { typedef vex::encoder super; - public: +public: /** * Construct an encoder with a custom number of ticks * @param port the triport port on the brain the encoder is plugged into * @param ticks_per_rev the number of ticks the encoder will report for one revolution - */ + */ CustomEncoder(vex::triport::port &port, double ticks_per_rev); /** * sets the stored rotation of the encoder. Any further movements will be from this value * @param val the numerical value of the angle we are setting to * @param units the unit of val - */ + */ void setRotation(double val, vex::rotationUnits units); /** * sets the stored position of the encoder. Any further movements will be from this value * @param val the numerical value of the position we are setting to * @param units the unit of val - */ + */ void setPosition(double val, vex::rotationUnits units); /** @@ -52,7 +51,6 @@ class CustomEncoder : public vex::encoder */ double velocity(vex::velocityUnits units); - - private: +private: double tick_scalar; }; \ No newline at end of file diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index c8c42b3..2837d7a 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -1,22 +1,21 @@ #pragma once -#include "../core/include/utils/controls/feedforward.h" -#include "vex.h" #include "../core/include/robot_specs.h" -#include "../core/include/utils/controls/pid.h" -#include "../core/include/utils/command_structure/auto_command.h" #include "../core/include/subsystems/screen.h" +#include "../core/include/utils/command_structure/auto_command.h" +#include "../core/include/utils/controls/feedforward.h" +#include "../core/include/utils/controls/pid.h" +#include "vex.h" #include /** * a Flywheel class that handles all control of a high inertia spinning disk - * It gives multiple options for what control system to use in order to control wheel velocity and functions alerting the user when the flywheel is up to speed. - * Flywheel is a set and forget class. - * Once you create it you can call spin_rpm or stop on it at any time and it will take all necessary steps to accomplish this + * It gives multiple options for what control system to use in order to control wheel velocity and functions alerting + * the user when the flywheel is up to speed. Flywheel is a set and forget class. Once you create it you can call + * spin_rpm or stop on it at any time and it will take all necessary steps to accomplish this * */ -class Flywheel -{ +class Flywheel { public: // CONSTRUCTORS, GETTERS, AND SETTERS @@ -70,10 +69,7 @@ class Flywheel * @brief check if the feedback controller thinks the flywheel is on target * @return true if on target */ - bool is_on_target() - { - return fb.is_on_target(); - } + bool is_on_target() { return fb.is_on_target(); } /** * @brief Creates a page displaying info about the flywheel @@ -85,23 +81,22 @@ class Flywheel * @brief Creates a new auto command to spin the flywheel at the desired velocity * @param rpm the rpm to spin at * @return an auto command to add to a command controller - */ - AutoCommand *SpinRpmCmd(int rpm) - { + */ + AutoCommand *SpinRpmCmd(int rpm) { - return new FunctionCommand([this, rpm]() - {spin_rpm(rpm); return true; }); + return new FunctionCommand([this, rpm]() { + spin_rpm(rpm); + return true; + }); } /** - * @brief Creates a new auto command that will hold until the flywheel has its target as defined by its feedback controller + * @brief Creates a new auto command that will hold until the flywheel has its target as defined by its feedback + * controller * @return an auto command to add to a command controller */ - AutoCommand *WaitUntilUpToSpeedCmd() - { - return new WaitUntilCondition( - new FunctionCondition([this]() - { return is_on_target(); })); + AutoCommand *WaitUntilUpToSpeedCmd() { + return new WaitUntilCondition(new FunctionCondition([this]() { return is_on_target(); })); } private: @@ -116,7 +111,7 @@ class Flywheel double ratio; ///< ratio between motor and flywheel. For accurate RPM calcualation std::atomic target_rpm; ///< Desired RPM of the flywheel. task rpm_task; ///< task that handles spinning the wheel at a given target_rpm - Filter &avger; ///< Moving average to smooth out noise from + Filter &avger; ///< Moving average to smooth out noise from // Functions for internal use only /** diff --git a/include/subsystems/layout.h b/include/subsystems/layout.h index 1715e93..61531f2 100644 --- a/include/subsystems/layout.h +++ b/include/subsystems/layout.h @@ -1,11 +1,8 @@ #include #include -struct SliderCfg{ - double &val; - double min; - double max; +struct SliderCfg { + double &val; + double min; + double max; }; - - - diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index 2b45fa7..8512f47 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -1,10 +1,10 @@ #pragma once -#include "vex.h" #include "../core/include/utils/controls/pid.h" +#include "vex.h" +#include #include #include -#include #include using namespace vex; @@ -17,19 +17,15 @@ using namespace std; * * @author Ryan McGee */ -template -class Lift -{ - public: - +template class Lift { +public: /** * lift_cfg_t holds the physical parameter specifications of a lify system. * includes: * - maximum speeds for the system - * - softstops to stop the lift from hitting the hard stops too hard + * - softstops to stop the lift from hitting the hard stops too hard */ - struct lift_cfg_t - { + struct lift_cfg_t { double up_speed, down_speed; double softstop_up, softstop_down; @@ -37,73 +33,71 @@ class Lift }; /** - * Construct the Lift object and begin the background task that controls the lift. - * - * Usage example: - * /code{.cpp} - * enum Positions {UP, MID, DOWN}; - * map setpt_map { - * {DOWN, 0.0}, - * {MID, 0.5}, - * {UP, 1.0} - * }; - * Lift my_lift(motors, lift_cfg, setpt_map); - * /endcode - * - * @param lift_motors - * A set of motors, all set that positive rotation correlates with the lift going up - * @param lift_cfg - * Lift characterization information; PID tunings and movement speeds - * @param setpoint_map - * A map of enum type T, in which each enum entry corresponds to a different lift height - */ - Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map &setpoint_map, limit *homing_switch=NULL) - : lift_motors(lift_motors), cfg(lift_cfg), lift_pid(cfg.lift_pid_cfg), setpoint_map(setpoint_map), homing_switch(homing_switch) - { + * Construct the Lift object and begin the background task that controls the lift. + * + * Usage example: + * /code{.cpp} + * enum Positions {UP, MID, DOWN}; + * map setpt_map { + * {DOWN, 0.0}, + * {MID, 0.5}, + * {UP, 1.0} + * }; + * Lift my_lift(motors, lift_cfg, setpt_map); + * /endcode + * + * @param lift_motors + * A set of motors, all set that positive rotation correlates with the lift going up + * @param lift_cfg + * Lift characterization information; PID tunings and movement speeds + * @param setpoint_map + * A map of enum type T, in which each enum entry corresponds to a different lift height + */ + Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map &setpoint_map, limit *homing_switch = NULL) + : lift_motors(lift_motors), cfg(lift_cfg), lift_pid(cfg.lift_pid_cfg), setpoint_map(setpoint_map), + homing_switch(homing_switch) { is_async = true; setpoint = 0; - + // Create a background task that is constantly updating the lift PID, if requested. // Set once, and forget. - task t([](void* ptr){ - Lift &lift = *((Lift*) ptr); - - while(true) - { - if(lift.get_async()) - lift.hold(); + task t( + [](void *ptr) { + Lift &lift = *((Lift *)ptr); - vexDelay(50); - } + while (true) { + if (lift.get_async()) + lift.hold(); - return 0; - }, this); + vexDelay(50); + } + return 0; + }, + this); } /** - * Control the lift with an "up" button and a "down" button. - * Use PID to hold the lift when letting go. - * @param up_ctrl - * Button controlling the "UP" motion - * @param down_ctrl - * Button controlling the "DOWN" motion - */ - void control_continuous(bool up_ctrl, bool down_ctrl) - { + * Control the lift with an "up" button and a "down" button. + * Use PID to hold the lift when letting go. + * @param up_ctrl + * Button controlling the "UP" motion + * @param down_ctrl + * Button controlling the "DOWN" motion + */ + void control_continuous(bool up_ctrl, bool down_ctrl) { static timer tmr; - + double cur_pos = 0; // Check if there's a hook for a custom sensor. If not, use the motors. - if(get_sensor == NULL) + if (get_sensor == NULL) cur_pos = lift_motors.position(rev); else cur_pos = get_sensor(); - if(up_ctrl && cur_pos < cfg.softstop_up) - { + if (up_ctrl && cur_pos < cfg.softstop_up) { lift_motors.spin(directionType::fwd, cfg.up_speed, volt); setpoint = cur_pos + .3; @@ -111,71 +105,65 @@ class Lift // Disable the PID while going UP. is_async = false; - } else if(down_ctrl && cur_pos > cfg.softstop_down) - { + } else if (down_ctrl && cur_pos > cfg.softstop_down) { // Lower the lift slowly, at a rate defined by down_speed - if(setpoint > cfg.softstop_down) + if (setpoint > cfg.softstop_down) setpoint = setpoint - (tmr.time(sec) * cfg.down_speed); // std::cout << "DEBUG OUT: DOWN " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n"; is_async = true; - } else - { + } else { // Hold the lift at the last setpoint is_async = true; } - tmr.reset(); + tmr.reset(); } /** * Control the lift with manual controls (no holding voltage) - * + * * @param up_btn Raise the lift when true * @param down_btn Lower the lift when true * @param volt_up Motor voltage when raising the lift * @param volt_down Motor voltage when lowering the lift */ - void control_manual(bool up_btn, bool down_btn, int volt_up, int volt_down) - { + void control_manual(bool up_btn, bool down_btn, int volt_up, int volt_down) { static bool down_hold = false; static bool init = true; // Allow for setting position while still calling this function - if(init || up_btn || down_btn) - { + if (init || up_btn || down_btn) { init = false; is_async = false; } double rev = lift_motors.position(rotationUnits::rev); - if(rev < cfg.softstop_down && down_btn) + if (rev < cfg.softstop_down && down_btn) down_hold = true; - else if( !down_btn ) + else if (!down_btn) down_hold = false; - if(up_btn && rev < cfg.softstop_up) + if (up_btn && rev < cfg.softstop_up) lift_motors.spin(directionType::fwd, volt_up, voltageUnits::volt); - else if(down_btn && rev > cfg.softstop_down && !down_hold) + else if (down_btn && rev > cfg.softstop_down && !down_hold) lift_motors.spin(directionType::rev, volt_down, voltageUnits::volt); else lift_motors.spin(directionType::fwd, 0, voltageUnits::volt); - } /** - * Control the lift in "steps". When the "up" button is pressed, the lift will go to the next - * position as defined by pos_list. Order matters! - * - * @param up_step - * A button that increments the position of the lift. - * @param down_step - * A button that decrements the position of the lift. - * @param pos_list - * A list of positions for the lift to go through. The higher the index, the higher the lift should be (generally). - */ - void control_setpoints(bool up_step, bool down_step, vector pos_list) - { + * Control the lift in "steps". When the "up" button is pressed, the lift will go to the next + * position as defined by pos_list. Order matters! + * + * @param up_step + * A button that increments the position of the lift. + * @param down_step + * A button that decrements the position of the lift. + * @param pos_list + * A list of positions for the lift to go through. The higher the index, the higher the lift should be (generally). + */ + void control_setpoints(bool up_step, bool down_step, vector pos_list) { // Make sure inputs are only processed on the rising edge of the button static bool up_last = up_step, down_last = down_step; @@ -188,31 +176,29 @@ class Lift static int cur_index = 0; // Avoid an index overflow. Shouldn't happen unless the user changes pos_list between calls. - if(cur_index >= pos_list.size()) + if (cur_index >= pos_list.size()) cur_index = pos_list.size() - 1; // Increment or decrement the index of the list, bringing it up or down. - if(up_rising && cur_index < (pos_list.size() - 1)) + if (up_rising && cur_index < (pos_list.size() - 1)) cur_index++; - else if(down_rising && cur_index > 0) + else if (down_rising && cur_index > 0) cur_index--; // Set the lift to hold the position in the background with the PID loop set_position(pos_list[cur_index]); - is_async = true; - + is_async = true; } /** - * Enable the background task, and send the lift to a position, specified by the - * setpoint map from the constructor. - * - * @param pos - * A lift position enum type - * @return True if the pid has reached the setpoint - */ - bool set_position(T pos) - { + * Enable the background task, and send the lift to a position, specified by the + * setpoint map from the constructor. + * + * @param pos + * A lift position enum type + * @return True if the pid has reached the setpoint + */ + bool set_position(T pos) { this->setpoint = setpoint_map[pos]; is_async = true; @@ -220,35 +206,30 @@ class Lift } /** - * Manually set a setpoint value for the lift PID to go to. - * @param val - * Lift setpoint, in motor revolutions or sensor units defined by get_sensor. Cannot be outside the softstops. - * @return True if the pid has reached the setpoint - */ - bool set_setpoint(double val) - { + * Manually set a setpoint value for the lift PID to go to. + * @param val + * Lift setpoint, in motor revolutions or sensor units defined by get_sensor. Cannot be outside the softstops. + * @return True if the pid has reached the setpoint + */ + bool set_setpoint(double val) { this->setpoint = val; return (lift_pid.get_target() == this->setpoint) && lift_pid.is_on_target(); } - + /** - * @return The current setpoint for the lift - */ - double get_setpoint() - { - return this->setpoint; - } + * @return The current setpoint for the lift + */ + double get_setpoint() { return this->setpoint; } /** - * Target the class's setpoint. - * Calculate the PID output and set the lift motors accordingly. - */ - void hold() - { + * Target the class's setpoint. + * Calculate the PID output and set the lift motors accordingly. + */ + void hold() { lift_pid.set_target(setpoint); // std::cout << "DEBUG OUT: SETPOINT " << setpoint << "\n"; - if(get_sensor != NULL) + if (get_sensor != NULL) lift_pid.update(get_sensor()); else lift_pid.update(lift_motors.position(rev)); @@ -259,16 +240,14 @@ class Lift } /** - * A blocking function that automatically homes the lift based on a sensor or hard stop, + * A blocking function that automatically homes the lift based on a sensor or hard stop, * and sets the position to 0. A watchdog times out after 3 seconds, to avoid damage. */ - void home() - { + void home() { static timer tmr; tmr.reset(); - - while(tmr.time(sec) < 3) - { + + while (tmr.time(sec) < 3) { lift_motors.spin(directionType::rev, 6, volt); if (homing_switch == NULL && lift_motors.current(currentUnits::amp) > 1.5) @@ -277,45 +256,35 @@ class Lift break; } - if(reset_sensor != NULL) + if (reset_sensor != NULL) reset_sensor(); - + lift_motors.resetPosition(); lift_motors.stop(); - } /** - * @return whether or not the background thread is running the lift - */ - bool get_async() - { - return is_async; - } + * @return whether or not the background thread is running the lift + */ + bool get_async() { return is_async; } /** - * Enables or disables the background task. Note that running the control functions, or set_position functions - * will immediately re-enable the task for autonomous use. - * @param val Whether or not the background thread should run the lift - */ - void set_async(bool val) - { - this->is_async = val; - } + * Enables or disables the background task. Note that running the control functions, or set_position functions + * will immediately re-enable the task for autonomous use. + * @param val Whether or not the background thread should run the lift + */ + void set_async(bool val) { this->is_async = val; } /** - * Creates a custom hook for any other type of sensor to be used on the lift. Example: - * /code{.cpp} - * my_lift.set_sensor_function( [](){return my_sensor.position();} ); - * /endcode - * - * @param fn_ptr - * Pointer to custom sensor function - */ - void set_sensor_function(double (*fn_ptr) (void)) - { - this->get_sensor = fn_ptr; - } + * Creates a custom hook for any other type of sensor to be used on the lift. Example: + * /code{.cpp} + * my_lift.set_sensor_function( [](){return my_sensor.position();} ); + * /endcode + * + * @param fn_ptr + * Pointer to custom sensor function + */ + void set_sensor_function(double (*fn_ptr)(void)) { this->get_sensor = fn_ptr; } /** * Creates a custom hook to reset the sensor used in set_sensor_function(). Example: @@ -323,24 +292,18 @@ class Lift * my_lift.set_sensor_reset( my_sensor.resetPosition ); * /endcode */ - void set_sensor_reset(void (*fn_ptr) (void)) - { - this->reset_sensor = fn_ptr; - } - - private: + void set_sensor_reset(void (*fn_ptr)(void)) { this->reset_sensor = fn_ptr; } +private: motor_group &lift_motors; lift_cfg_t &cfg; PID lift_pid; map &setpoint_map; limit *homing_switch; - + atomic setpoint; atomic is_async; double (*get_sensor)(void) = NULL; void (*reset_sensor)(void) = NULL; - - }; \ No newline at end of file diff --git a/include/subsystems/mecanum_drive.h b/include/subsystems/mecanum_drive.h index 97f3cdb..b120d66 100644 --- a/include/subsystems/mecanum_drive.h +++ b/include/subsystems/mecanum_drive.h @@ -1,26 +1,23 @@ #pragma once -#include "vex.h" #include "../core/include/utils/controls/pid.h" +#include "vex.h" #ifndef PI #define PI 3.141592654 #endif /** - * A class representing the Mecanum drivetrain. - * Contains 4 motors, a possible IMU (intertial), and a possible undriven perpendicular wheel. - */ -class MecanumDrive -{ - - public: + * A class representing the Mecanum drivetrain. + * Contains 4 motors, a possible IMU (intertial), and a possible undriven perpendicular wheel. + */ +class MecanumDrive { +public: /** - * Configure the Mecanum drive PID tunings and robot configurations - */ - struct mecanumdrive_config_t - { + * Configure the Mecanum drive PID tunings and robot configurations + */ + struct mecanumdrive_config_t { // PID configurations for autonomous driving PID::pid_config_t drive_pid_conf; PID::pid_config_t drive_gyro_pid_conf; @@ -34,65 +31,63 @@ class MecanumDrive // Width between the center of the left and right wheels double wheelbase_width; - }; /** - * Create the Mecanum drivetrain object - */ - MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear, - vex::rotation *lateral_wheel=NULL, vex::inertial *imu=NULL, mecanumdrive_config_t *config=NULL); + * Create the Mecanum drivetrain object + */ + MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear, + vex::rotation *lateral_wheel = NULL, vex::inertial *imu = NULL, mecanumdrive_config_t *config = NULL); /** - * Drive the robot using vectors. This handles all the math required for mecanum control. - * - * @param direction_deg the direction to drive the robot, in degrees. 0 is forward, - * 180 is back, clockwise is positive, counterclockwise is negative. - * @param magnitude How fast the robot should drive, in percent: 0.0->1.0 - * @param rotation How fast the robot should rotate, in percent: -1.0->+1.0 - */ + * Drive the robot using vectors. This handles all the math required for mecanum control. + * + * @param direction_deg the direction to drive the robot, in degrees. 0 is forward, + * 180 is back, clockwise is positive, counterclockwise is negative. + * @param magnitude How fast the robot should drive, in percent: 0.0->1.0 + * @param rotation How fast the robot should rotate, in percent: -1.0->+1.0 + */ void drive_raw(double direction_deg, double magnitude, double rotation); /** - * Drive the robot with a mecanum-style / arcade drive. Inputs are in percent (-100.0 -> 100.0) straight from the controller. - * Controls are mixed, so the robot can drive forward / strafe / rotate all at the same time. - * - * @param left_y left joystick, Y axis (forward / backwards) - * @param left_x left joystick, X axis (strafe left / right) - * @param right_x right joystick, X axis (rotation left / right) - * @param power =2 how much of a "curve" there should be on drive controls; better for low speed maneuvers. - * Leave blank for a default curve of 2 (higher means more fidelity) - */ - void drive(double left_y, double left_x, double right_x, int power=2); + * Drive the robot with a mecanum-style / arcade drive. Inputs are in percent (-100.0 -> 100.0) straight from the + * controller. Controls are mixed, so the robot can drive forward / strafe / rotate all at the same time. + * + * @param left_y left joystick, Y axis (forward / backwards) + * @param left_x left joystick, X axis (strafe left / right) + * @param right_x right joystick, X axis (rotation left / right) + * @param power =2 how much of a "curve" there should be on drive controls; better for low speed maneuvers. + * Leave blank for a default curve of 2 (higher means more fidelity) + */ + void drive(double left_y, double left_x, double right_x, int power = 2); /** - * Drive the robot in a straight line automatically. - * If the inertial was declared in the constructor, use it to correct while driving. - * If the lateral wheel was declared in the constructor, use it for more accurate positioning while strafing. - * - * @param inches How far the robot should drive, in inches - * @param direction What direction the robot should travel in, in degrees. - * 0 is forward, +/-180 is reverse, clockwise is positive. - * @param speed The maximum speed the robot should travel, in percent: -1.0->+1.0 - * @param gyro_correction =true Whether or not to use the gyro to help correct while driving. - * Will always be false if no gyro was declared in the constructor. - */ - bool auto_drive(double inches, double direction, double speed, bool gyro_correction=true); + * Drive the robot in a straight line automatically. + * If the inertial was declared in the constructor, use it to correct while driving. + * If the lateral wheel was declared in the constructor, use it for more accurate positioning while strafing. + * + * @param inches How far the robot should drive, in inches + * @param direction What direction the robot should travel in, in degrees. + * 0 is forward, +/-180 is reverse, clockwise is positive. + * @param speed The maximum speed the robot should travel, in percent: -1.0->+1.0 + * @param gyro_correction =true Whether or not to use the gyro to help correct while driving. + * Will always be false if no gyro was declared in the constructor. + */ + bool auto_drive(double inches, double direction, double speed, bool gyro_correction = true); /** - * Autonomously turn the robot X degrees over it's center point. Uses a closed loop - * for control. - * @param degrees How many degrees to rotate the robot. Clockwise postive. - * @param speed What percentage to run the motors at: 0.0 -> 1.0 - * @param ignore_imu =false Whether or not to use the Inertial for determining angle. - * Will instead use circumference formula + robot's wheelbase + encoders to determine. - * - * @return whether or not the robot has finished the maneuver - */ - bool auto_turn(double degrees, double speed, bool ignore_imu=false); - - private: - + * Autonomously turn the robot X degrees over it's center point. Uses a closed loop + * for control. + * @param degrees How many degrees to rotate the robot. Clockwise postive. + * @param speed What percentage to run the motors at: 0.0 -> 1.0 + * @param ignore_imu =false Whether or not to use the Inertial for determining angle. + * Will instead use circumference formula + robot's wheelbase + encoders to determine. + * + * @return whether or not the robot has finished the maneuver + */ + bool auto_turn(double degrees, double speed, bool ignore_imu = false); + +private: vex::motor &left_front, &right_front, &left_rear, &right_rear; mecanumdrive_config_t *config; @@ -104,5 +99,4 @@ class MecanumDrive PID *turn_pid = NULL; bool init = true; - }; \ No newline at end of file diff --git a/include/subsystems/odometry/odometry_3wheel.h b/include/subsystems/odometry/odometry_3wheel.h index 15ce85d..bef1f85 100644 --- a/include/subsystems/odometry/odometry_3wheel.h +++ b/include/subsystems/odometry/odometry_3wheel.h @@ -1,14 +1,14 @@ #pragma once +#include "../core/include/subsystems/custom_encoder.h" #include "../core/include/subsystems/odometry/odometry_base.h" #include "../core/include/subsystems/tank_drive.h" -#include "../core/include/subsystems/custom_encoder.h" /** * Odometry3Wheel - * + * * This class handles the code for a standard 3-pod odometry setup, where there are 3 "pods" made up of undriven * (dead) wheels connected to encoders in the following configuration: - * + * * +Y --------------- * ^ | | * | | | @@ -18,80 +18,76 @@ * | --------------- * | * +-------------------> + X - * + * * Where O is the center of rotation. The robot will monitor the changes in rotation of these wheels and calculate * the robot's X, Y and rotation on the field. - * + * * This is a "set and forget" class, meaning once the object is created, the robot will immediately begin * tracking it's movement in the background. - * + * * @author Ryan McGee * @date Oct 31 2022 - * + * */ -class Odometry3Wheel : public OdometryBase -{ - public: - - /** - * odometry3wheel_cfg_t holds all the specifications for how to calculate position with 3 encoders - * See the core wiki for what exactly each of these parameters measures - */ - typedef struct - { - double wheelbase_dist; /**< distance from the center of the left wheel to the center of the right wheel*/ - double off_axis_center_dist; /**< distance from the center of the robot to the center off axis wheel*/ - double wheel_diam; /**< the diameter of the tracking wheel*/ - - } odometry3wheel_cfg_t; - - /** - * Construct a new Odometry 3 Wheel object - * - * @param lside_fwd left-side encoder reference - * @param rside_fwd right-side encoder reference - * @param off_axis off-axis (perpendicular) encoder reference - * @param cfg robot odometry configuration - * @param is_async true to constantly run in the background - */ - Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, odometry3wheel_cfg_t &cfg, bool is_async=true); - - /** - * Update the current position of the robot once, using the current state of - * the encoders and the previous known location - * - * @return the robot's updated position - */ - pose_t update() override; +class Odometry3Wheel : public OdometryBase { +public: + /** + * odometry3wheel_cfg_t holds all the specifications for how to calculate position with 3 encoders + * See the core wiki for what exactly each of these parameters measures + */ + typedef struct { + double wheelbase_dist; /**< distance from the center of the left wheel to the center of the right wheel*/ + double off_axis_center_dist; /**< distance from the center of the robot to the center off axis wheel*/ + double wheel_diam; /**< the diameter of the tracking wheel*/ - /** - * A guided tuning process to automatically find tuning parameters. - * This method is blocking, and returns when tuning has finished. Follow - * the instructions on the controller to complete the tuning process - * - * @param con Controller reference, for screen and button control - * @param drive Drivetrain reference for robot control - */ - void tune(vex::controller &con, TankDrive &drive); + } odometry3wheel_cfg_t; - private: + /** + * Construct a new Odometry 3 Wheel object + * + * @param lside_fwd left-side encoder reference + * @param rside_fwd right-side encoder reference + * @param off_axis off-axis (perpendicular) encoder reference + * @param cfg robot odometry configuration + * @param is_async true to constantly run in the background + */ + Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, odometry3wheel_cfg_t &cfg, + bool is_async = true); - /** - * Calculation method for the robot's new position using the change in encoders, the old position, and the robot's configuration. - * This uses a series of arclength formulae for finding distance driven and change in angle. - * Then vector math is used to combine it with the robot's old position data - * - * @param lside_delta_deg Left encoder change in rotation, in degrees - * @param rside_delta_deg Right encoder change in rotation, in degrees - * @param offax_delta_deg Off-axis (perpendicular) encoder change in rotation, in degrees - * @param old_pos Robot's old position, for integration - * @param cfg Data on robot's configuration (wheel diameter, wheelbase, off-axis distance from center) - * @return The robot's new position (x, y, rot) - */ - static pose_t calculate_new_pos(double lside_delta_deg, double rside_delta_deg, double offax_delta_deg, pose_t old_pos, odometry3wheel_cfg_t cfg); + /** + * Update the current position of the robot once, using the current state of + * the encoders and the previous known location + * + * @return the robot's updated position + */ + pose_t update() override; - CustomEncoder &lside_fwd, &rside_fwd, &off_axis; - odometry3wheel_cfg_t &cfg; + /** + * A guided tuning process to automatically find tuning parameters. + * This method is blocking, and returns when tuning has finished. Follow + * the instructions on the controller to complete the tuning process + * + * @param con Controller reference, for screen and button control + * @param drive Drivetrain reference for robot control + */ + void tune(vex::controller &con, TankDrive &drive); +private: + /** + * Calculation method for the robot's new position using the change in encoders, the old position, and the robot's + * configuration. This uses a series of arclength formulae for finding distance driven and change in angle. Then + * vector math is used to combine it with the robot's old position data + * + * @param lside_delta_deg Left encoder change in rotation, in degrees + * @param rside_delta_deg Right encoder change in rotation, in degrees + * @param offax_delta_deg Off-axis (perpendicular) encoder change in rotation, in degrees + * @param old_pos Robot's old position, for integration + * @param cfg Data on robot's configuration (wheel diameter, wheelbase, off-axis distance from center) + * @return The robot's new position (x, y, rot) + */ + static pose_t calculate_new_pos(double lside_delta_deg, double rside_delta_deg, double offax_delta_deg, + pose_t old_pos, odometry3wheel_cfg_t cfg); + CustomEncoder &lside_fwd, &rside_fwd, &off_axis; + odometry3wheel_cfg_t &cfg; }; \ No newline at end of file diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index 2da4202..05293f4 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -1,149 +1,146 @@ #pragma once -#include "vex.h" -#include "../core/include/utils/geometry.h" #include "../core/include/robot_specs.h" #include "../core/include/utils/command_structure/auto_command.h" +#include "../core/include/utils/geometry.h" +#include "vex.h" #ifndef PI #define PI 3.141592654 #endif - - /** * OdometryBase - * + * * This base class contains all the shared code between different implementations of odometry. - * It handles the asynchronous management, position input/output and basic math functions, and - * holds positional types specific to field orientation. - * - * All future odometry implementations should extend this file and redefine update() function. - * + * It handles the asynchronous management, position input/output and basic math functions, and + * holds positional types specific to field orientation. + * + * All future odometry implementations should extend this file and redefine update() function. + * * @author Ryan McGee * @date Aug 11 2021 */ -class OdometryBase -{ +class OdometryBase { public: - - /** - * Construct a new Odometry Base object - * - * @param is_async True to run constantly in the background, false to call update() manually - */ - OdometryBase(bool is_async); - - /** - * Gets the current position and rotation - * @return the position that the odometry believes the robot is at - */ - pose_t get_position(void); - - /** - * Sets the current position of the robot - * @param newpos the new position that the odometry will believe it is at - */ - virtual void set_position(const pose_t& newpos=zero_pos); - AutoCommand *SetPositionCmd(const pose_t& newpos=zero_pos); - /** - * Update the current position on the field based on the sensors - * @return the location that the robot is at after the odometry does its calculations - */ - virtual pose_t update() = 0; - - /** - * Function that runs in the background task. This function pointer is passed - * to the vex::task constructor. - * - * @param ptr Pointer to OdometryBase object - * @return Required integer return code. Unused. - */ - static int background_task(void* ptr); - - /** - * End the background task. Cannot be restarted. - * If the user wants to end the thread but keep the data up to date, - * they must run the update() function manually from then on. - */ - void end_async(); - - /** - * Get the distance between two points - * @param start_pos distance from this point - * @param end_pos to this point - * @return the euclidean distance between start_pos and end_pos - */ - static double pos_diff(pose_t start_pos, pose_t end_pos); - - /** - * Get the change in rotation between two points - * @param pos1 position with initial rotation - * @param pos2 position with final rotation - * @return change in rotation between pos1 and pos2 - */ - static double rot_diff(pose_t pos1, pose_t pos2); - - /** - * Get the smallest difference in angle between a start heading and end heading. - * Returns the difference between -180 degrees and +180 degrees, representing the robot - * turning left or right, respectively. - * @param start_deg intitial angle (degrees) - * @param end_deg final angle (degrees) - * @return the smallest angle from the initial to the final angle. This takes into account the wrapping of rotations around 360 degrees - */ - static double smallest_angle(double start_deg, double end_deg); - - /// @brief end_task is true if we instruct the odometry thread to shut down - bool end_task = false; - - /** - * Get the current speed - * @return the speed at which the robot is moving and grooving (inch/s) - */ - double get_speed(); - - /** - * Get the current acceleration - * @return the acceleration rate of the robot (inch/s^2) - */ - double get_accel(); - - /** - * Get the current angular speed in degrees - * @return the angular velocity at which we are turning (deg/s) - */ - double get_angular_speed_deg(); - - /** - * Get the current angular acceleration in degrees - * @return the angular acceleration at which we are turning (deg/s^2) - */ - double get_angular_accel_deg(); - - /** - * Zeroed position. X=0, Y=0, Rotation= 90 degrees - */ - inline static constexpr pose_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}; + /** + * Construct a new Odometry Base object + * + * @param is_async True to run constantly in the background, false to call update() manually + */ + OdometryBase(bool is_async); + + /** + * Gets the current position and rotation + * @return the position that the odometry believes the robot is at + */ + pose_t get_position(void); + + /** + * Sets the current position of the robot + * @param newpos the new position that the odometry will believe it is at + */ + virtual void set_position(const pose_t &newpos = zero_pos); + AutoCommand *SetPositionCmd(const pose_t &newpos = zero_pos); + /** + * Update the current position on the field based on the sensors + * @return the location that the robot is at after the odometry does its calculations + */ + virtual pose_t update() = 0; + + /** + * Function that runs in the background task. This function pointer is passed + * to the vex::task constructor. + * + * @param ptr Pointer to OdometryBase object + * @return Required integer return code. Unused. + */ + static int background_task(void *ptr); + + /** + * End the background task. Cannot be restarted. + * If the user wants to end the thread but keep the data up to date, + * they must run the update() function manually from then on. + */ + void end_async(); + + /** + * Get the distance between two points + * @param start_pos distance from this point + * @param end_pos to this point + * @return the euclidean distance between start_pos and end_pos + */ + static double pos_diff(pose_t start_pos, pose_t end_pos); + + /** + * Get the change in rotation between two points + * @param pos1 position with initial rotation + * @param pos2 position with final rotation + * @return change in rotation between pos1 and pos2 + */ + static double rot_diff(pose_t pos1, pose_t pos2); + + /** + * Get the smallest difference in angle between a start heading and end heading. + * Returns the difference between -180 degrees and +180 degrees, representing the robot + * turning left or right, respectively. + * @param start_deg intitial angle (degrees) + * @param end_deg final angle (degrees) + * @return the smallest angle from the initial to the final angle. This takes into account the wrapping of rotations + * around 360 degrees + */ + static double smallest_angle(double start_deg, double end_deg); + + /// @brief end_task is true if we instruct the odometry thread to shut down + bool end_task = false; + + /** + * Get the current speed + * @return the speed at which the robot is moving and grooving (inch/s) + */ + double get_speed(); + + /** + * Get the current acceleration + * @return the acceleration rate of the robot (inch/s^2) + */ + double get_accel(); + + /** + * Get the current angular speed in degrees + * @return the angular velocity at which we are turning (deg/s) + */ + double get_angular_speed_deg(); + + /** + * Get the current angular acceleration in degrees + * @return the angular acceleration at which we are turning (deg/s^2) + */ + double get_angular_accel_deg(); + + /** + * Zeroed position. X=0, Y=0, Rotation= 90 degrees + */ + inline static constexpr pose_t zero_pos = {.x = 0.0L, .y = 0.0L, .rot = 90.0L}; protected: - /** - * handle to the vex task that is running the odometry code - */ - vex::task *handle; - - /** - * Mutex to control multithreading - */ - vex::mutex mut; - - /** - * Current position of the robot in terms of x,y,rotation - */ - pose_t current_pos; - - double speed; /**< the speed at which we are travelling (inch/s)*/ - double accel; /**< the rate at which we are accelerating (inch/s^2)*/ - double ang_speed_deg; /**< the speed at which we are turning (deg/s)*/ - double ang_accel_deg; /**< the rate at which we are accelerating our turn (deg/s^2)*/ + /** + * handle to the vex task that is running the odometry code + */ + vex::task *handle; + + /** + * Mutex to control multithreading + */ + vex::mutex mut; + + /** + * Current position of the robot in terms of x,y,rotation + */ + pose_t current_pos; + + double speed; /**< the speed at which we are travelling (inch/s)*/ + double accel; /**< the rate at which we are accelerating (inch/s^2)*/ + double ang_speed_deg; /**< the speed at which we are turning (deg/s)*/ + double ang_accel_deg; /**< the rate at which we are accelerating our turn (deg/s^2)*/ }; \ No newline at end of file diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index 7e8607f..186ea85 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -1,84 +1,89 @@ #pragma once -#include "../core/include/subsystems/odometry/odometry_base.h" #include "../core/include/subsystems/custom_encoder.h" +#include "../core/include/subsystems/odometry/odometry_base.h" #include "../core/include/utils/geometry.h" -#include "../core/include/utils/vector2d.h" #include "../core/include/utils/moving_average.h" +#include "../core/include/utils/vector2d.h" #include "../core/include/robot_specs.h" -static int background_task(void* odom_obj); - +static int background_task(void *odom_obj); /** * OdometryTank defines an odometry system for a tank drivetrain * This requires encoders in the same orientation as the drive wheels - * Odometry is a "start and forget" subsystem, which means once it's created and configured, + * Odometry is a "start and forget" subsystem, which means once it's created and configured, * it will constantly run in the background and track the robot's X, Y and rotation coordinates. -*/ -class OdometryTank : public OdometryBase -{ + */ +class OdometryTank : public OdometryBase { public: - /** - * Initialize the Odometry module, calculating position from the drive motors. - * @param left_side The left motors - * @param right_side The right motors - * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained - * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. - * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). - */ - OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true); - - /** - * Initialize the Odometry module, calculating position from the drive motors. - * @param left_custom_enc The left custom encoder - * @param right_custom_enc The right custom encoder - * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained - * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. - * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). - */ + /** + * Initialize the Odometry module, calculating position from the drive motors. + * @param left_side The left motors + * @param right_side The right motors + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for + * what is contained + * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will + * have to manually call update(). + */ + OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, + vex::inertial *imu = NULL, bool is_async = true); - OdometryTank(CustomEncoder &left_custom_enc, CustomEncoder &right_custom_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true); + /** + * Initialize the Odometry module, calculating position from the drive motors. + * @param left_custom_enc The left custom encoder + * @param right_custom_enc The right custom encoder + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for + * what is contained + * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will + * have to manually call update(). + */ - /** - * Initialize the Odometry module, calculating position from the drive motors. - * @param left_vex_enc The left vex encoder - * @param right_vex_enc The right vex encoder - * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained - * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. - * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). - */ + OdometryTank(CustomEncoder &left_custom_enc, CustomEncoder &right_custom_enc, robot_specs_t &config, + vex::inertial *imu = NULL, bool is_async = true); - OdometryTank(vex::encoder &left_vex_enc, vex::encoder &right_vex_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true); + /** + * Initialize the Odometry module, calculating position from the drive motors. + * @param left_vex_enc The left vex encoder + * @param right_vex_enc The right vex encoder + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for + * what is contained + * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will + * have to manually call update(). + */ - /** - * Update the current position on the field based on the sensors - * @return the position that odometry has calculated itself to be at - */ - pose_t update() override; + OdometryTank(vex::encoder &left_vex_enc, vex::encoder &right_vex_enc, robot_specs_t &config, + vex::inertial *imu = NULL, bool is_async = true); - /** - * set_position tells the odometry to place itself at a position - * @param newpos the position the odometry will take - */ - void set_position(const pose_t &newpos=zero_pos) override; + /** + * Update the current position on the field based on the sensors + * @return the position that odometry has calculated itself to be at + */ + pose_t update() override; - + /** + * set_position tells the odometry to place itself at a position + * @param newpos the position the odometry will take + */ + void set_position(const pose_t &newpos = zero_pos) override; private: - /** - * Get information from the input hardware and an existing position, and calculate a new current position - */ - static pose_t calculate_new_pos(robot_specs_t &config, pose_t &stored_info, double lside_diff, double rside_diff, double angle_deg); + /** + * Get information from the input hardware and an existing position, and calculate a new current position + */ + static pose_t calculate_new_pos(robot_specs_t &config, pose_t &stored_info, double lside_diff, double rside_diff, + double angle_deg); - vex::motor_group *left_side, *right_side; - CustomEncoder *left_custom_enc, *right_custom_enc; - vex::encoder *left_vex_enc, *right_vex_enc; - vex::inertial *imu; - robot_specs_t &config; + vex::motor_group *left_side, *right_side; + CustomEncoder *left_custom_enc, *right_custom_enc; + vex::encoder *left_vex_enc, *right_vex_enc; + vex::inertial *imu; + robot_specs_t &config; - double rotation_offset = 0; - ExponentialMovingAverage ema = ExponentialMovingAverage(3); - + double rotation_offset = 0; + ExponentialMovingAverage ema = ExponentialMovingAverage(3); }; \ No newline at end of file diff --git a/include/subsystems/screen.h b/include/subsystems/screen.h index 58159b2..2c2d27e 100644 --- a/include/subsystems/screen.h +++ b/include/subsystems/screen.h @@ -1,312 +1,297 @@ #pragma once -#include "vex.h" -#include -#include -#include -#include #include "../core/include/subsystems/odometry/odometry_base.h" -#include "../core/include/utils/graph_drawer.h" #include "../core/include/utils/controls/pid.h" #include "../core/include/utils/controls/pidff.h" +#include "../core/include/utils/graph_drawer.h" +#include "vex.h" +#include +#include +#include +#include -namespace screen -{ - /// @brief Widget that does something when you tap it. The function is only called once when you first tap it - class ButtonWidget - { - public: - /// @brief Create a Button widget - /// @param onpress the function to be called when the button is tapped - /// @param rect the area the button should take up on the screen - /// @param name the label put on the button - ButtonWidget(std::function onpress, Rect rect, std::string name) : onpress(onpress), rect(rect), name(name) {} - /// @brief Create a Button widget - /// @param onpress the function to be called when the button is tapped - /// @param rect the area the button should take up on the screen - /// @param name the label put on the button - ButtonWidget(void (*onpress)(), Rect rect, std::string name) : onpress(onpress), rect(rect), name(name) {} - - /// @brief responds to user input - /// @param was_pressed if the screen is pressed - /// @param x x position if the screen was pressed - /// @param y y position if the screen was pressed - /// @return true if the button was pressed - bool update(bool was_pressed, int x, int y); - /// @brief draws the button to the screen - void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number); - - private: - std::function onpress; - Rect rect; - std::string name = ""; - bool was_pressed_last = false; - }; - - /// @brief Widget that updates a double value. Updates by reference so watch out for race conditions cuz the screen stuff lives on another thread - class SliderWidget - { - public: - /// @brief Creates a slider widget - /// @param val reference to the value to modify - /// @param low minimum value to go to - /// @param high maximum value to go to - /// @param rect rect to draw it - /// @param name name of the value - SliderWidget(double &val, double low, double high, Rect rect, std::string name) : value(val), low(low), high(high), rect(rect), name(name) {} - - /// @brief responds to user input - /// @param was_pressed if the screen is pressed - /// @param x x position if the screen was pressed - /// @param y y position if the screen was pressed - /// @return true if the value updated - bool update(bool was_pressed, int x, int y); - /// @brief @ref Page::draws the slide to the screen - void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number); - - private: - double &value; - - double low; - double high; - - Rect rect; - std::string name = ""; - }; - - struct WidgetConfig; - - struct SliderConfig - { - double &val; - double low; - double high; - }; - struct ButtonConfig - { - std::function onclick; - }; - struct CheckboxConfig - { - std::function onupdate; - }; - struct LabelConfig - { - std::string label; - }; - - struct TextConfig - { - std::function text; - }; - struct SizedWidget - { - int size; - WidgetConfig &widget; - }; - struct WidgetConfig - { - enum Type - { - Col, - Row, - Slider, - Button, - Checkbox, - Label, - Text, - Graph, - }; - Type type; - union - { - std::vector widgets; - SliderConfig slider; - ButtonConfig button; - CheckboxConfig checkbox; - LabelConfig label; - TextConfig text; - GraphDrawer *graph; - } config; - }; - - class Page; - /// @brief Page describes one part of the screen slideshow - class Page - { - public: - /** - * @brief collect data, respond to screen input, do fast things (runs at - * 50hz even if you're not focused on this Page (only drawn page gets - * touch updates)) - * @param was_pressed true if the screen has been pressed - * @param x x position of screen press (if the screen was pressed) - * @param y y position of screen press (if the screen was pressed) - */ - virtual void update(bool was_pressed, int x, int y); - /** - * @brief draw stored data to the screen (runs at 10 hz and only runs if - * this page is in front) - * @param first_draw true if we just switched to this page - * @param frame_number frame of drawing we are on (basically an animation - * tick) - */ - virtual void draw(vex::brain::lcd &screen, bool first_draw, - unsigned int frame_number); - }; - - struct ScreenRect - { - uint32_t x1; - uint32_t y1; - uint32_t x2; - uint32_t y2; - }; - void draw_widget(WidgetConfig &widget, ScreenRect rect); - - class WidgetPage : public Page - { - public: - WidgetPage(WidgetConfig &cfg) : base_widget(cfg) {} - void update(bool was_pressed, int x, int y) override; - - void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override - { - draw_widget(base_widget, {.x1 = 20, .y1 = 0, .x2 = 440, .y2 = 240}); - } - - private: - WidgetConfig &base_widget; - }; - - /** - * @brief Start the screen background task. Once you start this, no need to draw to the screen manually elsewhere - * @param screen reference to the vex screen - * @param pages drawing pages - * @param first_page optional, which page to start the program at. by default 0 - */ - void start_screen(vex::brain::lcd &screen, std::vector pages, int first_page = 0); - - - void next_page(); - void prev_page(); - - /// @brief stops the screen. If you have a drive team that hates fun call this at the start of opcontrol - void stop_screen(); - - /// @brief type of function needed for update - using update_func_t = std::function; - - /// @brief type of function needed for draw - using draw_func_t = std::function; - - /// @brief Draws motor stats and battery stats to the screen - class StatsPage : public Page - { - public: - /// @brief Creates a stats page - /// @param motors a map of string to motor that we want to draw on this page - StatsPage(std::map motors); - /// @brief @see Page#update - void update(bool was_pressed, int x, int y) override; - /// @brief @see Page#draw - void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; - - private: - void draw_motor_stats(const std::string &name, vex::motor &mot, unsigned int frame, int x, int y, vex::brain::lcd &scr); - - std::map motors; - static const int y_start = 0; - static const int per_column = 4; - static const int row_height = 20; - static const int row_width = 200; - }; - - /** - * @brief a page that shows odometry position and rotation and a map (if an sd card with the file is on) - */ - class OdometryPage : public Page - { - public: - /// @brief Create an odometry trail. Make sure odometry is initilized before now - /// @param odom the odometry system to monitor - /// @param robot_width the width (side to side) of the robot in inches. Used for visualization - /// @param robot_height the robot_height (front to back) of the robot in inches. Used for visualization - /// @param do_trail whether or not to calculate and draw the trail. Drawing and storing takes a very *slight* extra amount of processing power - OdometryPage(OdometryBase &odom, double robot_width, double robot_height, bool do_trail); - /// @brief @see Page#update - void update(bool was_pressed, int x, int y) override; - /// @brief @see Page#draw - void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; - - private: - static const int path_len = 40; - static constexpr char const *field_filename = "vex_field_240p.png"; - - OdometryBase &odom; - double robot_width; - double robot_height; - uint8_t *buf = nullptr; - int buf_size = 0; - pose_t path[path_len]; - int path_index = 0; - bool do_trail; - GraphDrawer velocity_graph; - }; - - /// @brief Simple page that stores no internal data. the draw and update functions use only global data rather than storing anything - class FunctionPage : public Page - { - public: - /// @brief Creates a function page - /// @param update_f the function called every tick to respond to user input or do data collection - /// @param draw_t the function called to draw to the screen - FunctionPage(update_func_t update_f, draw_func_t draw_t); - /// @brief @see Page#update - void update(bool was_pressed, int x, int y) override; - /// @brief @see Page#draw - void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; - - private: - update_func_t update_f; - draw_func_t draw_f; - }; - - /// @brief PIDPage provides a way to tune a pid controller on the screen - class PIDPage : public Page - { - public: - /// @brief Create a PIDPage - /// @param pid the pid controller we're changing - /// @param name a name to recognize this pid controller if we've got multiple pid screens - /// @param onchange a function that is called when a tuning parameter is changed. If you need to update stuff on that change register a handler here - PIDPage( - PID &pid, std::string name, std::function onchange = []() {}); - PIDPage( - PIDFF &pidff, std::string name, std::function onchange = []() {}); - - /// @brief @see Page#update - void update(bool was_pressed, int x, int y) override; - /// @brief @see Page#draw - void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; - - private: - /// @brief reset d - void zero_d_f() { cfg.d = 0; } - /// @brief reset i - void zero_i_f() { cfg.i = 0; } - - PID::pid_config_t &cfg; - PID &pid; - const std::string name; - std::function onchange; - - SliderWidget p_slider; - SliderWidget i_slider; - SliderWidget d_slider; - ButtonWidget zero_i; - ButtonWidget zero_d; - - GraphDrawer graph; - }; - -} +namespace screen { +/// @brief Widget that does something when you tap it. The function is only called once when you first tap it +class ButtonWidget { +public: + /// @brief Create a Button widget + /// @param onpress the function to be called when the button is tapped + /// @param rect the area the button should take up on the screen + /// @param name the label put on the button + ButtonWidget(std::function onpress, Rect rect, std::string name) + : onpress(onpress), rect(rect), name(name) {} + /// @brief Create a Button widget + /// @param onpress the function to be called when the button is tapped + /// @param rect the area the button should take up on the screen + /// @param name the label put on the button + ButtonWidget(void (*onpress)(), Rect rect, std::string name) : onpress(onpress), rect(rect), name(name) {} + + /// @brief responds to user input + /// @param was_pressed if the screen is pressed + /// @param x x position if the screen was pressed + /// @param y y position if the screen was pressed + /// @return true if the button was pressed + bool update(bool was_pressed, int x, int y); + /// @brief draws the button to the screen + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number); + +private: + std::function onpress; + Rect rect; + std::string name = ""; + bool was_pressed_last = false; +}; + +/// @brief Widget that updates a double value. Updates by reference so watch out for race conditions cuz the screen +/// stuff lives on another thread +class SliderWidget { +public: + /// @brief Creates a slider widget + /// @param val reference to the value to modify + /// @param low minimum value to go to + /// @param high maximum value to go to + /// @param rect rect to draw it + /// @param name name of the value + SliderWidget(double &val, double low, double high, Rect rect, std::string name) + : value(val), low(low), high(high), rect(rect), name(name) {} + + /// @brief responds to user input + /// @param was_pressed if the screen is pressed + /// @param x x position if the screen was pressed + /// @param y y position if the screen was pressed + /// @return true if the value updated + bool update(bool was_pressed, int x, int y); + /// @brief @ref Page::draws the slide to the screen + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number); + +private: + double &value; + + double low; + double high; + + Rect rect; + std::string name = ""; +}; + +struct WidgetConfig; + +struct SliderConfig { + double &val; + double low; + double high; +}; +struct ButtonConfig { + std::function onclick; +}; +struct CheckboxConfig { + std::function onupdate; +}; +struct LabelConfig { + std::string label; +}; + +struct TextConfig { + std::function text; +}; +struct SizedWidget { + int size; + WidgetConfig &widget; +}; +struct WidgetConfig { + enum Type { + Col, + Row, + Slider, + Button, + Checkbox, + Label, + Text, + Graph, + }; + Type type; + union { + std::vector widgets; + SliderConfig slider; + ButtonConfig button; + CheckboxConfig checkbox; + LabelConfig label; + TextConfig text; + GraphDrawer *graph; + } config; +}; + +class Page; +/// @brief Page describes one part of the screen slideshow +class Page { +public: + /** + * @brief collect data, respond to screen input, do fast things (runs at + * 50hz even if you're not focused on this Page (only drawn page gets + * touch updates)) + * @param was_pressed true if the screen has been pressed + * @param x x position of screen press (if the screen was pressed) + * @param y y position of screen press (if the screen was pressed) + */ + virtual void update(bool was_pressed, int x, int y); + /** + * @brief draw stored data to the screen (runs at 10 hz and only runs if + * this page is in front) + * @param first_draw true if we just switched to this page + * @param frame_number frame of drawing we are on (basically an animation + * tick) + */ + virtual void draw(vex::brain::lcd &screen, bool first_draw, unsigned int frame_number); +}; + +struct ScreenRect { + uint32_t x1; + uint32_t y1; + uint32_t x2; + uint32_t y2; +}; +void draw_widget(WidgetConfig &widget, ScreenRect rect); + +class WidgetPage : public Page { +public: + WidgetPage(WidgetConfig &cfg) : base_widget(cfg) {} + void update(bool was_pressed, int x, int y) override; + + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override { + draw_widget(base_widget, {.x1 = 20, .y1 = 0, .x2 = 440, .y2 = 240}); + } + +private: + WidgetConfig &base_widget; +}; + +/** + * @brief Start the screen background task. Once you start this, no need to draw to the screen manually elsewhere + * @param screen reference to the vex screen + * @param pages drawing pages + * @param first_page optional, which page to start the program at. by default 0 + */ +void start_screen(vex::brain::lcd &screen, std::vector pages, int first_page = 0); + +void next_page(); +void prev_page(); + +/// @brief stops the screen. If you have a drive team that hates fun call this at the start of opcontrol +void stop_screen(); + +/// @brief type of function needed for update +using update_func_t = std::function; + +/// @brief type of function needed for draw +using draw_func_t = std::function; + +/// @brief Draws motor stats and battery stats to the screen +class StatsPage : public Page { +public: + /// @brief Creates a stats page + /// @param motors a map of string to motor that we want to draw on this page + StatsPage(std::map motors); + /// @brief @see Page#update + void update(bool was_pressed, int x, int y) override; + /// @brief @see Page#draw + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; + +private: + void draw_motor_stats(const std::string &name, vex::motor &mot, unsigned int frame, int x, int y, + vex::brain::lcd &scr); + + std::map motors; + static const int y_start = 0; + static const int per_column = 4; + static const int row_height = 20; + static const int row_width = 200; +}; + +/** + * @brief a page that shows odometry position and rotation and a map (if an sd card with the file is on) + */ +class OdometryPage : public Page { +public: + /// @brief Create an odometry trail. Make sure odometry is initilized before now + /// @param odom the odometry system to monitor + /// @param robot_width the width (side to side) of the robot in inches. Used for visualization + /// @param robot_height the robot_height (front to back) of the robot in inches. Used for visualization + /// @param do_trail whether or not to calculate and draw the trail. Drawing and storing takes a very *slight* extra + /// amount of processing power + OdometryPage(OdometryBase &odom, double robot_width, double robot_height, bool do_trail); + /// @brief @see Page#update + void update(bool was_pressed, int x, int y) override; + /// @brief @see Page#draw + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; + +private: + static const int path_len = 40; + static constexpr char const *field_filename = "vex_field_240p.png"; + + OdometryBase &odom; + double robot_width; + double robot_height; + uint8_t *buf = nullptr; + int buf_size = 0; + pose_t path[path_len]; + int path_index = 0; + bool do_trail; + GraphDrawer velocity_graph; +}; + +/// @brief Simple page that stores no internal data. the draw and update functions use only global data rather than +/// storing anything +class FunctionPage : public Page { +public: + /// @brief Creates a function page + /// @param update_f the function called every tick to respond to user input or do data collection + /// @param draw_t the function called to draw to the screen + FunctionPage(update_func_t update_f, draw_func_t draw_t); + /// @brief @see Page#update + void update(bool was_pressed, int x, int y) override; + /// @brief @see Page#draw + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; + +private: + update_func_t update_f; + draw_func_t draw_f; +}; + +/// @brief PIDPage provides a way to tune a pid controller on the screen +class PIDPage : public Page { +public: + /// @brief Create a PIDPage + /// @param pid the pid controller we're changing + /// @param name a name to recognize this pid controller if we've got multiple pid screens + /// @param onchange a function that is called when a tuning parameter is changed. If you need to update stuff on that + /// change register a handler here + PIDPage( + PID &pid, std::string name, std::function onchange = []() {}); + PIDPage( + PIDFF &pidff, std::string name, std::function onchange = []() {}); + + /// @brief @see Page#update + void update(bool was_pressed, int x, int y) override; + /// @brief @see Page#draw + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; + +private: + /// @brief reset d + void zero_d_f() { cfg.d = 0; } + /// @brief reset i + void zero_i_f() { cfg.i = 0; } + + PID::pid_config_t &cfg; + PID &pid; + const std::string name; + std::function onchange; + + SliderWidget p_slider; + SliderWidget i_slider; + SliderWidget d_slider; + ButtonWidget zero_i; + ButtonWidget zero_d; + + GraphDrawer graph; +}; + +} // namespace screen diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 2e63002..0147da5 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -4,44 +4,48 @@ #define PI 3.141592654 #endif -#include "vex.h" +#include "../core/include/robot_specs.h" #include "../core/include/subsystems/odometry/odometry_tank.h" -#include "../core/include/utils/controls/pid.h" +#include "../core/include/utils/command_structure/auto_command.h" #include "../core/include/utils/controls/feedback_base.h" -#include "../core/include/robot_specs.h" +#include "../core/include/utils/controls/pid.h" #include "../core/include/utils/pure_pursuit.h" -#include "../core/include/utils/command_structure/auto_command.h" +#include "vex.h" #include using namespace vex; /** * TankDrive is a class to run a tank drive system. - * A tank drive system, sometimes called differential drive, has a motor (or group of synchronized motors) on the left and right side + * A tank drive system, sometimes called differential drive, has a motor (or group of synchronized motors) on the left + * and right side */ -class TankDrive -{ +class TankDrive { public: - enum class BrakeType - { - None, ///< just send 0 volts to the motors + enum class BrakeType { + None, ///< just send 0 volts to the motors ZeroVelocity, ///< try to bring the robot to rest. But don't try to hold position - Smart, ///< bring the robot to rest and once it's stopped, try to hold that position + Smart, ///< bring the robot to rest and once it's stopped, try to hold that position }; /** * Create the TankDrive object * @param left_motors left side drive motors * @param right_motors right side drive motors - * @param config the configuration specification defining physical dimensions about the robot. See robot_specs_t for more info + * @param config the configuration specification defining physical dimensions about the robot. See robot_specs_t for + * more info * @param odom an odometry system to track position and rotation. this is necessary to execute autonomous paths */ TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom = NULL); - AutoCommand *DriveToPointCmd(point_t pt, vex::directionType dir = vex::forward, double max_speed = 1.0, double end_speed = 0.0); - AutoCommand *DriveToPointCmd(Feedback &fb, point_t pt, vex::directionType dir = vex::forward, double max_speed = 1.0, double end_speed = 0.0); + AutoCommand *DriveToPointCmd(point_t pt, vex::directionType dir = vex::forward, double max_speed = 1.0, + double end_speed = 0.0); + AutoCommand *DriveToPointCmd(Feedback &fb, point_t pt, vex::directionType dir = vex::forward, double max_speed = 1.0, + double end_speed = 0.0); - AutoCommand *DriveForwardCmd(double dist, vex::directionType dir = vex::forward, double max_speed = 1.0, double end_speed = 0.0); - AutoCommand *DriveForwardCmd(Feedback &fb, double dist, vex::directionType dir = vex::forward, double max_speed = 1.0, double end_speed = 0.0); + AutoCommand *DriveForwardCmd(double dist, vex::directionType dir = vex::forward, double max_speed = 1.0, + double end_speed = 0.0); + AutoCommand *DriveForwardCmd(Feedback &fb, double dist, vex::directionType dir = vex::forward, double max_speed = 1.0, + double end_speed = 0.0); AutoCommand *TurnToHeadingCmd(double heading, double max_speed = 1.0, double end_speed = 0.0); AutoCommand *TurnToHeadingCmd(Feedback &fb, double heading, double max_speed = 1.0, double end_speed = 0.0); @@ -50,7 +54,8 @@ class TankDrive AutoCommand *TurnDegreesCmd(Feedback &fb, double degrees, double max_speed = 1.0, double end_speed = 0.0); AutoCommand *PurePursuitCmd(PurePursuit::Path path, directionType dir, double max_speed = 1, double end_speed = 0); - AutoCommand *PurePursuitCmd(Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed = 1, double end_speed = 0); + AutoCommand *PurePursuitCmd(Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed = 1, + double end_speed = 0); /** * Stops rotation of all the motors using their "brake mode" @@ -72,7 +77,7 @@ class TankDrive * Drive the robot raw-ly * @param left the percent to run the left motors (-1, 1) * @param right the percent to run the right motors (-1, 1) - */ + */ void drive_tank_raw(double left, double right); /** @@ -94,7 +99,8 @@ class TankDrive * Returns whether or not the robot has reached it's destination. * @param inches the distance to drive forward * @param dir the direction we want to travel forward and backward - * @param feedback the custom feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param feedback the custom feedback controller we will use to travel. controls the rate at which we accelerate + * and drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return true when we have reached our target distance @@ -119,7 +125,8 @@ class TankDrive * Uses PID + Feedforward for it's control. * * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw - * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and + * drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power */ bool turn_degrees(double degrees, Feedback &feedback, double max_speed = 1, double end_speed = 0); @@ -144,11 +151,13 @@ class TankDrive * @param x the x position of the target * @param y the y position of the target * @param dir the direction we want to travel forward and backward - * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and + * drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power * @param end_speed the movement profile will attempt to reach this velocity by its completion */ - bool drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed = 1, double end_speed = 0); + bool drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed = 1, + double end_speed = 0); /** * Use odometry to automatically drive the robot to a point on the field. @@ -169,7 +178,8 @@ class TankDrive * 0 is forward. * * @param heading_deg the heading to which we will turn - * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and + * drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power * @param end_speed the movement profile will attempt to reach this velocity by its completion */ @@ -211,7 +221,8 @@ class TankDrive * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return True when the path is complete */ - bool pure_pursuit(PurePursuit::Path path, directionType dir, Feedback &feedback, double max_speed = 1, double end_speed = 0); + bool pure_pursuit(PurePursuit::Path path, directionType dir, Feedback &feedback, double max_speed = 1, + double end_speed = 0); /** * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of @@ -238,8 +249,10 @@ class TankDrive OdometryBase *odometry; ///< odometry system to track position and rotation. necessary for autonomous driving - robot_specs_t &config; ///< configuration holding physical dimensions of the robot. see robot_specs_t for more information + robot_specs_t + &config; ///< configuration holding physical dimensions of the robot. see robot_specs_t for more information - bool func_initialized = false; ///< used to control initialization of autonomous driving. (you only wan't to set the target once, not every iteration that you're driving) + bool func_initialized = false; ///< used to control initialization of autonomous driving. (you only wan't to set the + ///< target once, not every iteration that you're driving) bool is_pure_pursuit = false; ///< true if we are driving with a pure pursuit system }; diff --git a/include/utils/auto_chooser.h b/include/utils/auto_chooser.h index 59562b6..248227c 100644 --- a/include/utils/auto_chooser.h +++ b/include/utils/auto_chooser.h @@ -1,9 +1,9 @@ #pragma once +#include "../core/include/subsystems/screen.h" +#include "../core/include/utils/geometry.h" #include "vex.h" #include #include -#include "../core/include/subsystems/screen.h" -#include "../core/include/utils/geometry.h" /** * Autochooser is a utility to make selecting robot autonomous programs easier @@ -11,10 +11,10 @@ * During a season, we usually code between 4 and 6 autonomous programs. * Most teams will change their entire robot program as a way of choosing autonomi * but this may cause issues if you have an emergency patch to upload during a competition. - * This class was built as a way of using the robot screen to list autonomous programs, and the touchscreen to select them. + * This class was built as a way of using the robot screen to list autonomous programs, and the touchscreen to select + * them. */ -class AutoChooser : public screen::Page -{ +class AutoChooser : public screen::Page { public: /** * Initialize the auto-chooser. This class places a choice menu on the brain screen, @@ -36,8 +36,7 @@ class AutoChooser : public screen::Page /** * entry_t is a datatype used to store information that the chooser knows about an auto selection button */ - struct entry_t - { + struct entry_t { Rect rect; std::string name; /**< name of the auto repretsented by the block*/ }; diff --git a/include/utils/command_structure/auto_command.h b/include/utils/command_structure/auto_command.h index fa8528e..c7832cf 100644 --- a/include/utils/command_structure/auto_command.h +++ b/include/utils/command_structure/auto_command.h @@ -7,11 +7,10 @@ #pragma once #include "vex.h" +#include #include -#include #include -#include - +#include /** * A Condition is a function that returns true or false @@ -22,17 +21,14 @@ * extend this class for different choices you wish to make */ -class Condition -{ +class Condition { public: Condition *Or(Condition *b); Condition *And(Condition *b); virtual bool test() = 0; }; - -class AutoCommand -{ +class AutoCommand { public: static constexpr double default_timeout = 10.0; /** @@ -45,17 +41,15 @@ class AutoCommand * What to do if we timeout instead of finishing. timeout is specified by the timeout seconds in the constructor */ virtual void on_timeout() {} - AutoCommand *withTimeout(double t_seconds) - { - if (this->timeout_seconds < 0) - { + AutoCommand *withTimeout(double t_seconds) { + if (this->timeout_seconds < 0) { // should never be timed out return this; } this->timeout_seconds = t_seconds; return this; } - AutoCommand *withCancelCondition(Condition *true_to_end){ + AutoCommand *withCancelCondition(Condition *true_to_end) { this->true_to_end = true_to_end; return this; } @@ -76,14 +70,10 @@ class AutoCommand * FunctionCommand is fun and good way to do simple things * Printing, launching nukes, and other quick and dirty one time things */ -class FunctionCommand : public AutoCommand -{ +class FunctionCommand : public AutoCommand { public: FunctionCommand(std::function f) : f(f) {} - bool run() - { - return f(); - } + bool run() { return f(); } private: std::function f; @@ -95,15 +85,12 @@ class FunctionCommand : public AutoCommand // Test 3 -> true // Returns false until the Nth time that it is called // This is pretty much only good for implementing RepeatUntil -class TimesTestedCondition : public Condition -{ +class TimesTestedCondition : public Condition { public: TimesTestedCondition(size_t N) : max(N) {} - bool test() override - { + bool test() override { count++; - if (count >= max) - { + if (count >= max) { return true; } return false; @@ -115,13 +102,11 @@ class TimesTestedCondition : public Condition }; /// @brief FunctionCondition is a quick and dirty Condition to wrap some expression that should be evaluated at runtime -class FunctionCondition : public Condition -{ +class FunctionCondition : public Condition { public: FunctionCondition( - std::function cond, std::function timeout = []() {}) : cond(cond), timeout(timeout) - { - } + std::function cond, std::function timeout = []() {}) + : cond(cond), timeout(timeout) {} bool test() override; private: @@ -129,9 +114,9 @@ class FunctionCondition : public Condition std::function timeout; }; -/// @brief IfTimePassed tests based on time since the command controller was constructed. Returns true if elapsed time > time_s -class IfTimePassed : public Condition -{ +/// @brief IfTimePassed tests based on time since the command controller was constructed. Returns true if elapsed time > +/// time_s +class IfTimePassed : public Condition { public: IfTimePassed(double time_s); bool test() override; @@ -142,14 +127,10 @@ class IfTimePassed : public Condition }; /// @brief Waits until the condition is true -class WaitUntilCondition : public AutoCommand -{ +class WaitUntilCondition : public AutoCommand { public: WaitUntilCondition(Condition *cond) : cond(cond) {} - bool run() override - { - return cond->test(); - } + bool run() override { return cond->test(); } private: Condition *cond; @@ -160,8 +141,7 @@ class WaitUntilCondition : public AutoCommand /// @brief InOrder runs its commands sequentially then continues. /// How to handle timeout in this case. Automatically set it to sum of commands timouts? -class InOrder : public AutoCommand -{ +class InOrder : public AutoCommand { public: InOrder(const InOrder &other) = default; InOrder(std::queue cmds); @@ -177,8 +157,7 @@ class InOrder : public AutoCommand /// @brief Parallel runs multiple commands in parallel and waits for all to finish before continuing. /// if none finish before this command's timeout, it will call on_timeout on all children continue -class Parallel : public AutoCommand -{ +class Parallel : public AutoCommand { public: Parallel(std::initializer_list cmds); bool run() override; @@ -189,11 +168,10 @@ class Parallel : public AutoCommand std::vector runners; }; -/// @brief Branch chooses from multiple options at runtime. the function decider returns an index into the choices vector -/// If you wish to make no choice and skip this section, return NO_CHOICE; -/// any choice that is out of bounds set to NO_CHOICE -class Branch : public AutoCommand -{ +/// @brief Branch chooses from multiple options at runtime. the function decider returns an index into the choices +/// vector If you wish to make no choice and skip this section, return NO_CHOICE; any choice that is out of bounds set +/// to NO_CHOICE +class Branch : public AutoCommand { public: Branch(Condition *cond, AutoCommand *false_choice, AutoCommand *true_choice); ~Branch(); @@ -212,8 +190,7 @@ class Branch : public AutoCommand /// @brief Async runs a command asynchronously /// will simply let it go and never look back /// THIS HAS A VERY NICHE USE CASE. THINK ABOUT IF YOU REALLY NEED IT -class Async : public AutoCommand -{ +class Async : public AutoCommand { public: Async(AutoCommand *cmd) : cmd(cmd) {} bool run() override; @@ -222,8 +199,7 @@ class Async : public AutoCommand AutoCommand *cmd = nullptr; }; -class RepeatUntil : public AutoCommand -{ +class RepeatUntil : public AutoCommand { public: /// @brief RepeatUntil that runs a fixed number of times /// @param cmds the cmds to repeat diff --git a/include/utils/command_structure/basic_command.h b/include/utils/command_structure/basic_command.h index 6df7306..44a8bf8 100644 --- a/include/utils/command_structure/basic_command.h +++ b/include/utils/command_structure/basic_command.h @@ -1,118 +1,112 @@ /** * @file basic_commands.h * @author Ethan Kishimori GITHUB(LilacEthan) - * + * * @brief Basic Commands for Motors and Solenoids able to throw into the Command Controller * Commands Included * - BasicSpinCommand * - BasicStopCommand * - BasicSolenoidSet - * + * * @version 0.1 - * + * */ #pragma once #include "../core/include/utils/command_structure/auto_command.h" - -//Basic Motor Classes----------------------------------------------- + +// Basic Motor Classes----------------------------------------------- /** * AutoCommand wrapper class for BasicSpinCommand * using the vex hardware functions */ class BasicSpinCommand : public AutoCommand { - public: - - //Enumurator for the type of power setting in the motor - enum type {percent,voltage,veocity}; - - /** - * @brief Construct a new BasicSpinCommand - * - * @param motor Motor to spin - * @param direc Direction of motor spin - * @param setting Power setting in volts,percentage,velocity - * @param power Value of desired power - */ - BasicSpinCommand(vex::motor &motor, vex::directionType dir, BasicSpinCommand::type setting, double power); - - /** - * @brief Runs the BasicSpinCommand - * Overrides run from Auto Command - * - * @return True Async running command - */ - bool run() override; - - private: - - vex::motor &motor; - - type setting; - - vex::directionType dir; - - double power; +public: + // Enumurator for the type of power setting in the motor + enum type { percent, voltage, veocity }; + + /** + * @brief Construct a new BasicSpinCommand + * + * @param motor Motor to spin + * @param direc Direction of motor spin + * @param setting Power setting in volts,percentage,velocity + * @param power Value of desired power + */ + BasicSpinCommand(vex::motor &motor, vex::directionType dir, BasicSpinCommand::type setting, double power); + + /** + * @brief Runs the BasicSpinCommand + * Overrides run from Auto Command + * + * @return True Async running command + */ + bool run() override; + +private: + vex::motor &motor; + + type setting; + + vex::directionType dir; + + double power; }; /** * AutoCommand wrapper class for BasicStopCommand * Using the Vex hardware functions */ -class BasicStopCommand : public AutoCommand{ - public: - - /** - * @brief Construct a new BasicMotorStop Command - * - * @param motor The motor to stop - * @param setting The brake setting for the motor - */ - BasicStopCommand(vex::motor &motor, vex::brakeType setting); - - /** - * @brief Runs the BasicMotorStop Command - * Overrides run command from AutoCommand - * - * @return True Command runs once - */ - bool run() override; - - private: - - vex::motor &motor; - - vex::brakeType setting; +class BasicStopCommand : public AutoCommand { +public: + /** + * @brief Construct a new BasicMotorStop Command + * + * @param motor The motor to stop + * @param setting The brake setting for the motor + */ + BasicStopCommand(vex::motor &motor, vex::brakeType setting); + + /** + * @brief Runs the BasicMotorStop Command + * Overrides run command from AutoCommand + * + * @return True Command runs once + */ + bool run() override; + +private: + vex::motor &motor; + + vex::brakeType setting; }; -//Basic Solenoid Commands---------------------------------- +// Basic Solenoid Commands---------------------------------- /** * AutoCommand wrapper class for BasicSolenoidSet * Using the Vex hardware functions */ -class BasicSolenoidSet : public AutoCommand{ - public: - - /** - * @brief Construct a new BasicSolenoidSet Command - * - * @param solenoid Solenoid being set - * @param setting Setting of the solenoid in boolean (true,false) - */ - BasicSolenoidSet(vex::pneumatics &solenoid, bool setting); - - /** - * @brief Runs the BasicSolenoidSet - * Overrides run command from AutoCommand - * - * @return True Command runs once - */ - bool run() override; - - private: - - vex::pneumatics &solenoid; - - bool setting; +class BasicSolenoidSet : public AutoCommand { +public: + /** + * @brief Construct a new BasicSolenoidSet Command + * + * @param solenoid Solenoid being set + * @param setting Setting of the solenoid in boolean (true,false) + */ + BasicSolenoidSet(vex::pneumatics &solenoid, bool setting); + + /** + * @brief Runs the BasicSolenoidSet + * Overrides run command from AutoCommand + * + * @return True Command runs once + */ + bool run() override; + +private: + vex::pneumatics &solenoid; + + bool setting; }; \ No newline at end of file diff --git a/include/utils/command_structure/command_controller.h b/include/utils/command_structure/command_controller.h index 4f8cf14..f44d409 100644 --- a/include/utils/command_structure/command_controller.h +++ b/include/utils/command_structure/command_controller.h @@ -8,12 +8,11 @@ */ #pragma once -#include -#include #include "../core/include/utils/command_structure/auto_command.h" +#include +#include -class CommandController -{ +class CommandController { public: /// @brief Create an empty CommandController. Add Command with CommandController::add() [[deprecated("Use list constructor instead.")]] CommandController() : command_queue({}) {} @@ -24,9 +23,12 @@ class CommandController /** * Adds a command to the queue * @param cmd the AutoCommand we want to add to our list - * @param timeout_seconds the number of seconds we will let the command run for. If it exceeds this, we cancel it and run on_timeout. if it is <= 0 no time out will be applied + * @param timeout_seconds the number of seconds we will let the command run for. If it exceeds this, we cancel it and + * run on_timeout. if it is <= 0 no time out will be applied */ - [[deprecated("Use list constructor instead. If you need to make a decision before adding new commands, use Branch (https://github.com/RIT-VEX-U/Core/wiki/3-%7C-Utilites#commandcontroller)")]] void add(std::vector cmds); + [[deprecated("Use list constructor instead. If you need to make a decision before adding new commands, use Branch " + "(https://github.com/RIT-VEX-U/Core/wiki/3-%7C-Utilites#commandcontroller)")]] void + add(std::vector cmds); void add(AutoCommand *cmd, double timeout_seconds = 10.0); /** @@ -39,7 +41,8 @@ class CommandController * @param cmds the AutoCommands we want to add to our list * @param timeout_sec timeout in seconds to apply to all commands if they are still the default */ - [[deprecated("Use list constructor instead. If you need to make a decision before adding new commands, use Branch (https://github.com/RIT-VEX-U/Core/wiki/3-%7C-Utilites#commandcontroller)")]] void + [[deprecated("Use list constructor instead. If you need to make a decision before adding new commands, use Branch " + "(https://github.com/RIT-VEX-U/Core/wiki/3-%7C-Utilites#commandcontroller)")]] void add(std::vector cmds, double timeout_sec); /** * Adds a command that will delay progression @@ -69,6 +72,5 @@ class CommandController private: std::queue command_queue; bool command_timed_out = false; - std::function should_cancel = []() - { return false; }; + std::function should_cancel = []() { return false; }; }; \ No newline at end of file diff --git a/include/utils/command_structure/delay_command.h b/include/utils/command_structure/delay_command.h index c82b9bd..fe824c2 100644 --- a/include/utils/command_structure/delay_command.h +++ b/include/utils/command_structure/delay_command.h @@ -9,25 +9,25 @@ #include "../core/include/utils/command_structure/auto_command.h" -class DelayCommand: public AutoCommand { - public: - /** - * Construct a delay command - * @param ms the number of milliseconds to delay for - */ - DelayCommand(int ms): ms(ms) {} - - /** - * Delays for the amount of milliseconds stored in the command - * Overrides run from AutoCommand - * @returns true when complete - */ - bool run() override { - vexDelay(ms); - return true; - } +class DelayCommand : public AutoCommand { +public: + /** + * Construct a delay command + * @param ms the number of milliseconds to delay for + */ + DelayCommand(int ms) : ms(ms) {} - private: - // amount of milliseconds to wait - int ms; + /** + * Delays for the amount of milliseconds stored in the command + * Overrides run from AutoCommand + * @returns true when complete + */ + bool run() override { + vexDelay(ms); + return true; + } + +private: + // amount of milliseconds to wait + int ms; }; \ No newline at end of file diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index ee590fb..74c0dbc 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -2,7 +2,7 @@ * File: drive_commands.h * Desc: * Holds all the AutoCommand subclasses that wrap (currently) TankDrive functions - * + * * Currently includes: * - drive_forward * - turn_degrees @@ -18,243 +18,235 @@ #pragma once -#include "vex.h" -#include "../core/include/utils/geometry.h" -#include "../core/include/utils/command_structure/auto_command.h" #include "../core/include/subsystems/tank_drive.h" +#include "../core/include/utils/command_structure/auto_command.h" +#include "../core/include/utils/geometry.h" +#include "vex.h" using namespace vex; - // ==== DRIVING ==== /** - * AutoCommand wrapper class for the drive_forward function in the + * AutoCommand wrapper class for the drive_forward function in the * TankDrive class * */ -class DriveForwardCommand: public AutoCommand -{ - public: - DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed=1, double end_speed=0); - - /** - * Run drive_forward - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - /** - * Cleans up drive system if we time out before finishing - */ - void on_timeout() override; - - private: - // drive system to run the function on - TankDrive &drive_sys; - - // feedback controller to use - Feedback &feedback; - - // parameters for drive_forward - double inches; - directionType dir; - double max_speed; - double end_speed; +class DriveForwardCommand : public AutoCommand { +public: + DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed = 1, + double end_speed = 0); + + /** + * Run drive_forward + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + /** + * Cleans up drive system if we time out before finishing + */ + void on_timeout() override; + +private: + // drive system to run the function on + TankDrive &drive_sys; + + // feedback controller to use + Feedback &feedback; + + // parameters for drive_forward + double inches; + directionType dir; + double max_speed; + double end_speed; }; /** - * AutoCommand wrapper class for the turn_degrees function in the + * AutoCommand wrapper class for the turn_degrees function in the * TankDrive class */ -class TurnDegreesCommand: public AutoCommand -{ - public: - TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed = 1, double end_speed = 0); - - /** - * Run turn_degrees - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - /** - * Cleans up drive system if we time out before finishing - */ - void on_timeout() override; - - - private: - // drive system to run the function on - TankDrive &drive_sys; - - // feedback controller to use - Feedback &feedback; - - // parameters for turn_degrees - double degrees; - double max_speed; - double end_speed; +class TurnDegreesCommand : public AutoCommand { +public: + TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed = 1, + double end_speed = 0); + + /** + * Run turn_degrees + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + /** + * Cleans up drive system if we time out before finishing + */ + void on_timeout() override; + +private: + // drive system to run the function on + TankDrive &drive_sys; + + // feedback controller to use + Feedback &feedback; + + // parameters for turn_degrees + double degrees; + double max_speed; + double end_speed; }; /** * AutoCommand wrapper class for the drive_to_point function in the * TankDrive class */ -class DriveToPointCommand: public AutoCommand -{ - public: - DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed = 1, double end_speed = 0); - DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, point_t point, directionType dir, double max_speed=1, double end_speed = 0); - - /** - * Run drive_to_point - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // drive system to run the function on - TankDrive &drive_sys; - - /** - * Cleans up drive system if we time out before finishing - */ - void on_timeout() override; - - - // feedback controller to use - Feedback &feedback; - - // parameters for drive_to_point - double x; - double y; - directionType dir; - double max_speed; - double end_speed; - +class DriveToPointCommand : public AutoCommand { +public: + DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, + double max_speed = 1, double end_speed = 0); + DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, point_t point, directionType dir, double max_speed = 1, + double end_speed = 0); + + /** + * Run drive_to_point + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + +private: + // drive system to run the function on + TankDrive &drive_sys; + + /** + * Cleans up drive system if we time out before finishing + */ + void on_timeout() override; + + // feedback controller to use + Feedback &feedback; + + // parameters for drive_to_point + double x; + double y; + directionType dir; + double max_speed; + double end_speed; }; /** - * AutoCommand wrapper class for the turn_to_heading() function in the + * AutoCommand wrapper class for the turn_to_heading() function in the * TankDrive class * */ -class TurnToHeadingCommand: public AutoCommand -{ - public: - TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed = 1, double end_speed = 0); - - /** - * Run turn_to_heading - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - /** - * Cleans up drive system if we time out before finishing - */ - void on_timeout() override; - - - private: - // drive system to run the function on - TankDrive &drive_sys; - - // feedback controller to use - Feedback &feedback; - - // parameters for turn_to_heading - double heading_deg; - double max_speed; - double end_speed; +class TurnToHeadingCommand : public AutoCommand { +public: + TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed = 1, + double end_speed = 0); + + /** + * Run turn_to_heading + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + /** + * Cleans up drive system if we time out before finishing + */ + void on_timeout() override; + +private: + // drive system to run the function on + TankDrive &drive_sys; + + // feedback controller to use + Feedback &feedback; + + // parameters for turn_to_heading + double heading_deg; + double max_speed; + double end_speed; }; /** * Autocommand wrapper class for pure pursuit function in the TankDrive class -*/ -class PurePursuitCommand: public AutoCommand -{ - public: + */ +class PurePursuitCommand : public AutoCommand { +public: /** * Construct a Pure Pursuit AutoCommand - * + * * @param path The list of coordinates to follow, in order * @param dir Run the bot forwards or backwards * @param feedback The feedback controller determining speed * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) - */ - PurePursuitCommand(TankDrive &drive_sys, Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed=1, double end_speed=0); + */ + PurePursuitCommand(TankDrive &drive_sys, Feedback &feedback, PurePursuit::Path path, directionType dir, + double max_speed = 1, double end_speed = 0); /** * Direct call to TankDrive::pure_pursuit - */ + */ bool run() override; /** * Reset the drive system when it times out - */ + */ void on_timeout() override; - private: +private: TankDrive &drive_sys; PurePursuit::Path path; directionType dir; Feedback &feedback; double max_speed; double end_speed; - }; /** - * AutoCommand wrapper class for the stop() function in the + * AutoCommand wrapper class for the stop() function in the * TankDrive class */ -class DriveStopCommand: public AutoCommand -{ - public: - DriveStopCommand(TankDrive &drive_sys); - - /** - * Stop the drive system - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - void on_timeout() override; - - private: - // drive system to run the function on - TankDrive &drive_sys; -}; +class DriveStopCommand : public AutoCommand { +public: + DriveStopCommand(TankDrive &drive_sys); + + /** + * Stop the drive system + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + void on_timeout() override; +private: + // drive system to run the function on + TankDrive &drive_sys; +}; // ==== ODOMETRY ==== /** - * AutoCommand wrapper class for the set_position function in the + * AutoCommand wrapper class for the set_position function in the * Odometry class */ -class OdomSetPosition: public AutoCommand -{ - public: - /** - * constructs a new OdomSetPosition command - * @param odom the odometry system we are setting - * @param newpos the position we are telling the odometry to take. defaults to (0, 0), angle = 90 - */ - OdomSetPosition(OdometryBase &odom, const pose_t &newpos=OdometryBase::zero_pos); - - /** - * Run set_position - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // drive system with an odometry config - OdometryBase &odom; - pose_t newpos; +class OdomSetPosition : public AutoCommand { +public: + /** + * constructs a new OdomSetPosition command + * @param odom the odometry system we are setting + * @param newpos the position we are telling the odometry to take. defaults to (0, 0), angle = 90 + */ + OdomSetPosition(OdometryBase &odom, const pose_t &newpos = OdometryBase::zero_pos); + + /** + * Run set_position + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + +private: + // drive system with an odometry config + OdometryBase &odom; + pose_t newpos; }; diff --git a/include/utils/command_structure/flywheel_commands.h b/include/utils/command_structure/flywheel_commands.h index 04bf8f5..dc3490c 100644 --- a/include/utils/command_structure/flywheel_commands.h +++ b/include/utils/command_structure/flywheel_commands.h @@ -14,56 +14,56 @@ * in the Flywheel class * */ -class SpinRPMCommand: public AutoCommand { - public: +class SpinRPMCommand : public AutoCommand { +public: /** * Construct a SpinRPM Command * @param flywheel the flywheel sys to command * @param rpm the rpm that we should spin at - */ + */ SpinRPMCommand(Flywheel &flywheel, int rpm); - /** - * Run spin_manual - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // Flywheel instance to run the function on - Flywheel &flywheel; - - // parameters for spin_rpm - int rpm; + /** + * Run spin_manual + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + +private: + // Flywheel instance to run the function on + Flywheel &flywheel; + + // parameters for spin_rpm + int rpm; }; /** * AutoCommand that listens to the Flywheel and waits until it is at its target speed +/- the specified threshold * */ -class WaitUntilUpToSpeedCommand: public AutoCommand { - public: - /** - * Creat a WaitUntilUpToSpeedCommand - * @param flywheel the flywheel system we are commanding - * @param threshold_rpm the threshold over and under the flywheel target RPM that we define to be acceptable - */ - WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshold_rpm); - - /** - * Run spin_manual - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // Flywheel instance to run the function on - Flywheel &flywheel; - - // if the actual speed is equal to the desired speed +/- this value, we are ready to fire - int threshold_rpm; +class WaitUntilUpToSpeedCommand : public AutoCommand { +public: + /** + * Creat a WaitUntilUpToSpeedCommand + * @param flywheel the flywheel system we are commanding + * @param threshold_rpm the threshold over and under the flywheel target RPM that we define to be acceptable + */ + WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshold_rpm); + + /** + * Run spin_manual + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + +private: + // Flywheel instance to run the function on + Flywheel &flywheel; + + // if the actual speed is equal to the desired speed +/- this value, we are ready to fire + int threshold_rpm; }; /** @@ -71,24 +71,24 @@ class WaitUntilUpToSpeedCommand: public AutoCommand { * in the Flywheel class * */ -class FlywheelStopCommand: public AutoCommand { - public: +class FlywheelStopCommand : public AutoCommand { +public: /** * Construct a FlywheelStopCommand * @param flywheel the flywheel system we are commanding - */ + */ FlywheelStopCommand(Flywheel &flywheel); - /** - * Run stop - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // Flywheel instance to run the function on - Flywheel &flywheel; + /** + * Run stop + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + +private: + // Flywheel instance to run the function on + Flywheel &flywheel; }; /** @@ -96,24 +96,24 @@ class FlywheelStopCommand: public AutoCommand { * in the Flywheel class * */ -class FlywheelStopMotorsCommand: public AutoCommand { - public: +class FlywheelStopMotorsCommand : public AutoCommand { +public: /** * Construct a FlywheeStopMotors Command * @param flywheel the flywheel system we are commanding - */ + */ FlywheelStopMotorsCommand(Flywheel &flywheel); - /** - * Run stop - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // Flywheel instance to run the function on - Flywheel &flywheel; + /** + * Run stop + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + +private: + // Flywheel instance to run the function on + Flywheel &flywheel; }; /** @@ -121,17 +121,17 @@ class FlywheelStopMotorsCommand: public AutoCommand { * in the Flywheel class * */ -class FlywheelStopNonTasksCommand: public AutoCommand { +class FlywheelStopNonTasksCommand : public AutoCommand { FlywheelStopNonTasksCommand(Flywheel &flywheel); - /** - * Run stop - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // Flywheel instance to run the function on - Flywheel &flywheel; + /** + * Run stop + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + +private: + // Flywheel instance to run the function on + Flywheel &flywheel; }; diff --git a/include/utils/controls/bang_bang.h b/include/utils/controls/bang_bang.h index 8fbc180..4146ca1 100644 --- a/include/utils/controls/bang_bang.h +++ b/include/utils/controls/bang_bang.h @@ -1,50 +1,49 @@ #include "../core/include/utils/controls/feedback_base.h" -class BangBang : public Feedback -{ +class BangBang : public Feedback { public: - BangBang(double thresshold, double low, double high); - /** - * Initialize the feedback controller for a movement - * - * @param start_pt the current sensor value - * @param set_pt where the sensor value should be - * @param start_vel Movement starting velocity - * @param end_vel Movement ending velocity - */ - void init(double start_pt, double set_pt) override; + BangBang(double thresshold, double low, double high); + /** + * Initialize the feedback controller for a movement + * + * @param start_pt the current sensor value + * @param set_pt where the sensor value should be + * @param start_vel Movement starting velocity + * @param end_vel Movement ending velocity + */ + void init(double start_pt, double set_pt) override; - /** - * Iterate the feedback loop once with an updated sensor value - * - * @param val value from the sensor - * @return feedback loop result - */ - double update(double val) override; + /** + * Iterate the feedback loop once with an updated sensor value + * + * @param val value from the sensor + * @return feedback loop result + */ + double update(double val) override; - /** - * @return the last saved result from the feedback controller - */ - double get() override; + /** + * @return the last saved result from the feedback controller + */ + double get() override; - /** - * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. - * - * @param lower Upper limit - * @param upper Lower limit - */ - void set_limits(double lower, double upper) override; + /** + * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * + * @param lower Upper limit + * @param upper Lower limit + */ + void set_limits(double lower, double upper) override; - /** - * @return true if the feedback controller has reached it's setpoint - */ - bool is_on_target() override; + /** + * @return true if the feedback controller has reached it's setpoint + */ + bool is_on_target() override; private: - double setpt; - double sensor_val; - double lower_bound, upper_bound; - double last_output; - double threshhold; + double setpt; + double sensor_val; + double lower_bound, upper_bound; + double last_output; + double threshhold; }; diff --git a/include/utils/controls/feedback_base.h b/include/utils/controls/feedback_base.h index 528af20..08d0dc5 100644 --- a/include/utils/controls/feedback_base.h +++ b/include/utils/controls/feedback_base.h @@ -7,44 +7,41 @@ * @date 9/25/2022 * */ -class Feedback -{ +class Feedback { public: - /** - * Initialize the feedback controller for a movement - * - * @param start_pt the current sensor value - * @param set_pt where the sensor value should be - * @param start_vel Movement starting velocity - * @param end_vel Movement ending velocity - */ - virtual void init(double start_pt, double set_pt) = 0; + /** + * Initialize the feedback controller for a movement + * + * @param start_pt the current sensor value + * @param set_pt where the sensor value should be + * @param start_vel Movement starting velocity + * @param end_vel Movement ending velocity + */ + virtual void init(double start_pt, double set_pt) = 0; - /** - * Iterate the feedback loop once with an updated sensor value - * - * @param val value from the sensor - * @return feedback loop result - */ - virtual double update(double val) = 0; + /** + * Iterate the feedback loop once with an updated sensor value + * + * @param val value from the sensor + * @return feedback loop result + */ + virtual double update(double val) = 0; - /** - * @return the last saved result from the feedback controller - */ - virtual double get() = 0; - - /** - * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. - * - * @param lower Upper limit - * @param upper Lower limit - */ - virtual void set_limits(double lower, double upper) = 0; - - /** - * @return true if the feedback controller has reached it's setpoint - */ - virtual bool is_on_target() = 0; + /** + * @return the last saved result from the feedback controller + */ + virtual double get() = 0; + /** + * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * + * @param lower Upper limit + * @param upper Lower limit + */ + virtual void set_limits(double lower, double upper) = 0; + /** + * @return true if the feedback controller has reached it's setpoint + */ + virtual bool is_on_target() = 0; }; \ No newline at end of file diff --git a/include/utils/controls/feedforward.h b/include/utils/controls/feedforward.h index c6700e7..f10b359 100644 --- a/include/utils/controls/feedforward.h +++ b/include/utils/controls/feedforward.h @@ -1,90 +1,85 @@ #pragma once -#include -#include #include "../core/include/utils/math_util.h" #include "../core/include/utils/moving_average.h" #include "vex.h" +#include +#include /** * FeedForward - * + * * Stores the feedfoward constants, and allows for quick computation. * Feedfoward should be used in systems that require smooth precise movements * and have high inertia, such as drivetrains and lifts. - * + * * This is best used alongside a PID loop, with the form: * output = pid.get() + feedforward.calculate(v, a); - * - * In this case, the feedforward does the majority of the heavy lifting, and the + * + * In this case, the feedforward does the majority of the heavy lifting, and the * pid loop only corrects for inconsistencies - * + * * For information about tuning feedforward, I reccommend looking at this post: * https://www.chiefdelphi.com/t/paper-frc-drivetrain-characterization/160915 * (yes I know it's for FRC but trust me, it's useful) - * + * * @author Ryan McGee * @date 6/13/2022 */ -class FeedForward -{ - public: +class FeedForward { +public: + /** + * ff_config_t holds the parameters to make the theoretical model of a real world system + * equation is of the form + * kS if the system is not stopped, 0 otherwise + * + kV * desired velocity + * + kA * desired acceleration + * + kG + */ + typedef struct { + double kS; /**< Coefficient to overcome static friction: the point at which the motor *starts* to move.*/ + double kV; /**< Veclocity coefficient: the power required to keep the mechanism in motion. Multiplied by the + requested velocity.*/ + double kA; /**< kA - Acceleration coefficient: the power required to change the mechanism's speed. Multiplied by the + requested acceleration.*/ + double kG; /**< kG - Gravity coefficient: only needed for lifts. The power required to overcome gravity and stay at + steady state.*/ + } ff_config_t; - /** - * ff_config_t holds the parameters to make the theoretical model of a real world system - * equation is of the form - * kS if the system is not stopped, 0 otherwise - * + kV * desired velocity - * + kA * desired acceleration - * + kG - */ - typedef struct - { - double kS; /**< Coefficient to overcome static friction: the point at which the motor *starts* to move.*/ - double kV; /**< Veclocity coefficient: the power required to keep the mechanism in motion. Multiplied by the requested velocity.*/ - double kA; /**< kA - Acceleration coefficient: the power required to change the mechanism's speed. Multiplied by the requested acceleration.*/ - double kG; /**< kG - Gravity coefficient: only needed for lifts. The power required to overcome gravity and stay at steady state.*/ - } ff_config_t; + /** + * Creates a FeedForward object. + * @param cfg Configuration Struct for tuning + */ + FeedForward(ff_config_t &cfg) : cfg(cfg) {} - - /** - * Creates a FeedForward object. - * @param cfg Configuration Struct for tuning - */ - FeedForward(ff_config_t &cfg) : cfg(cfg) {} + /** + * @brief Perform the feedforward calculation + * + * This calculation is the equation: + * F = kG + kS*sgn(v) + kV*v + kA*a + * + * @param v Requested velocity of system + * @param a Requested acceleration of system + * @return A feedforward that should closely represent the system if tuned correctly + */ + double calculate(double v, double a, double pid_ref = 0.0) { + double ks_sign = 0; + if (v != 0) + ks_sign = sign(v); + else if (pid_ref != 0) + ks_sign = sign(pid_ref); - /** - * @brief Perform the feedforward calculation - * - * This calculation is the equation: - * F = kG + kS*sgn(v) + kV*v + kA*a - * - * @param v Requested velocity of system - * @param a Requested acceleration of system - * @return A feedforward that should closely represent the system if tuned correctly - */ - double calculate(double v, double a, double pid_ref=0.0) - { - double ks_sign = 0; - if(v != 0) - ks_sign = sign(v); - else if(pid_ref != 0) - ks_sign = sign(pid_ref); - - return (cfg.kS * ks_sign) + (cfg.kV * v) + (cfg.kA * a) + cfg.kG; - } - - private: - - ff_config_t &cfg; + return (cfg.kS * ks_sign) + (cfg.kV * v) + (cfg.kA * a) + cfg.kG; + } +private: + ff_config_t &cfg; }; - /** -* tune_feedforward takes a group of motors and finds the feedforward conifg parameters automagically. -* @param motor the motor group to use -* @param pct Maximum velocity in percent (0->1.0) + * tune_feedforward takes a group of motors and finds the feedforward conifg parameters automagically. + * @param motor the motor group to use + * @param pct Maximum velocity in percent (0->1.0) * @param duration Amount of time the motors spin for the test * @return A tuned feedforward object */ diff --git a/include/utils/controls/motion_controller.h b/include/utils/controls/motion_controller.h index 11c07de..8f2b70f 100644 --- a/include/utils/controls/motion_controller.h +++ b/include/utils/controls/motion_controller.h @@ -1,126 +1,123 @@ #pragma once -#include "../core/include/utils/controls/pid.h" +#include "../core/include/subsystems/tank_drive.h" +#include "../core/include/utils/controls/feedback_base.h" #include "../core/include/utils/controls/feedforward.h" +#include "../core/include/utils/controls/pid.h" #include "../core/include/utils/controls/trapezoid_profile.h" -#include "../core/include/utils/controls/feedback_base.h" -#include "../core/include/subsystems/tank_drive.h" #include "vex.h" /** * Motion Controller class - * + * * This class defines a top-level motion profile, which can act as an intermediate between * a subsystem class and the motors themselves * - * This takes the constants kS, kV, kA, kP, kI, kD, max_v and acceleration and wraps around + * This takes the constants kS, kV, kA, kP, kI, kD, max_v and acceleration and wraps around * a feedforward, PID and trapezoid profile. It does so with the following formula: - * + * * out = feedfoward.calculate(motion_profile.get(time_s)) + pid.get(motion_profile.get(time_s)) - * + * * For PID and Feedforward specific formulae, see pid.h, feedforward.h, and trapezoid_profile.h - * + * * @author Ryan McGee * @date 7/13/2022 */ -class MotionController : public Feedback -{ - public: - - /** - * m_profile_config holds all data the motion controller uses to plan paths - * When motion pofile is given a target to drive to, max_v and accel are used to make the trapezoid profile instructing the controller how to drive - * pid_cfg, ff_cfg are used to find the motor outputs necessary to execute this path - */ - typedef struct - { - double max_v; ///< the maximum velocity the robot can drive - double accel; ///< the most acceleration the robot can do - PID::pid_config_t pid_cfg; ///< configuration parameters for the internal PID controller - FeedForward::ff_config_t ff_cfg; ///< configuration parameters for the internal - } m_profile_cfg_t; +class MotionController : public Feedback { +public: + /** + * m_profile_config holds all data the motion controller uses to plan paths + * When motion pofile is given a target to drive to, max_v and accel are used to make the trapezoid profile + * instructing the controller how to drive pid_cfg, ff_cfg are used to find the motor outputs necessary to execute + * this path + */ + typedef struct { + double max_v; ///< the maximum velocity the robot can drive + double accel; ///< the most acceleration the robot can do + PID::pid_config_t pid_cfg; ///< configuration parameters for the internal PID controller + FeedForward::ff_config_t ff_cfg; ///< configuration parameters for the internal + } m_profile_cfg_t; - /** - * @brief Construct a new Motion Controller object - * - * @param config The definition of how the robot is able to move - * max_v Maximum velocity the movement is capable of - * accel Acceleration / deceleration of the movement - * pid_cfg Definitions of kP, kI, and kD - * ff_cfg Definitions of kS, kV, and kA - */ - MotionController(m_profile_cfg_t &config); + /** + * @brief Construct a new Motion Controller object + * + * @param config The definition of how the robot is able to move + * max_v Maximum velocity the movement is capable of + * accel Acceleration / deceleration of the movement + * pid_cfg Definitions of kP, kI, and kD + * ff_cfg Definitions of kS, kV, and kA + */ + MotionController(m_profile_cfg_t &config); - /** - * @brief Initialize the motion profile for a new movement - * This will also reset the PID and profile timers. - */ - void init(double start_pt, double end_pt) override; - - /** - * @brief Update the motion profile with a new sensor value - * - * @param sensor_val Value from the sensor - * @return the motor input generated from the motion profile - */ - double update(double sensor_val) override; + /** + * @brief Initialize the motion profile for a new movement + * This will also reset the PID and profile timers. + */ + void init(double start_pt, double end_pt) override; - /** - * @return the last saved result from the feedback controller - */ - double get() override; + /** + * @brief Update the motion profile with a new sensor value + * + * @param sensor_val Value from the sensor + * @return the motor input generated from the motion profile + */ + double update(double sensor_val) override; - /** - * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. - * if limits are applied, the controller will not target any value below lower or above upper - * - * @param lower upper limit - * @param upper lower limiet - */ - void set_limits(double lower, double upper) override; + /** + * @return the last saved result from the feedback controller + */ + double get() override; - /** - * @return Whether or not the movement has finished, and the PID - * confirms it is on target - */ - bool is_on_target() override; + /** + * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * if limits are applied, the controller will not target any value below lower or above upper + * + * @param lower upper limit + * @param upper lower limiet + */ + void set_limits(double lower, double upper) override; - /** - * @return The current postion, velocity and acceleration setpoints - */ - motion_t get_motion(); + /** + * @return Whether or not the movement has finished, and the PID + * confirms it is on target + */ + bool is_on_target() override; - /** - * This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. - * It does this by first calculating the kS (voltage to overcome static friction) by slowly increasing - * the voltage until it moves. - * - * Next is kV (voltage to sustain a certain velocity), where the robot will record it's steady-state velocity - * at 'pct' speed. - * - * Finally, kA (voltage needed to accelerate by a certain rate), where the robot will record the entire movement's - * velocity and acceleration, record a plot of [X=(pct-kV*V-kS), Y=(Acceleration)] along the movement, - * and since kA*Accel = pct-kV*V-kS, the reciprocal of the linear regression is the kA value. - * - * @param drive The tankdrive to operate on - * @param odometry The robot's odometry subsystem - * @param pct Maximum velocity in percent (0->1.0) - * @param duration Amount of time the robot should be moving for the test - * @return A tuned feedforward object - */ - static FeedForward::ff_config_t tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct=0.6, double duration=2); + /** + * @return The current postion, velocity and acceleration setpoints + */ + motion_t get_motion(); - private: + /** + * This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. + * It does this by first calculating the kS (voltage to overcome static friction) by slowly increasing + * the voltage until it moves. + * + * Next is kV (voltage to sustain a certain velocity), where the robot will record it's steady-state velocity + * at 'pct' speed. + * + * Finally, kA (voltage needed to accelerate by a certain rate), where the robot will record the entire movement's + * velocity and acceleration, record a plot of [X=(pct-kV*V-kS), Y=(Acceleration)] along the movement, + * and since kA*Accel = pct-kV*V-kS, the reciprocal of the linear regression is the kA value. + * + * @param drive The tankdrive to operate on + * @param odometry The robot's odometry subsystem + * @param pct Maximum velocity in percent (0->1.0) + * @param duration Amount of time the robot should be moving for the test + * @return A tuned feedforward object + */ + static FeedForward::ff_config_t tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct = 0.6, + double duration = 2); - m_profile_cfg_t config; +private: + m_profile_cfg_t config; - PID pid; - FeedForward ff; - TrapezoidProfile profile; + PID pid; + FeedForward ff; + TrapezoidProfile profile; - double lower_limit = 0, upper_limit = 0; - double out = 0; - motion_t cur_motion; - - vex::timer tmr; + double lower_limit = 0, upper_limit = 0; + double out = 0; + motion_t cur_motion; + vex::timer tmr; }; \ No newline at end of file diff --git a/include/utils/controls/pid.h b/include/utils/controls/pid.h index 0b5d4b0..7c04d74 100644 --- a/include/utils/controls/pid.h +++ b/include/utils/controls/pid.h @@ -41,12 +41,12 @@ class PID : public Feedback { * an angle */ struct pid_config_t { - double p; ///< proportional coeffecient p * error() - double i; ///< integral coeffecient i * integral(error) - double d; ///< derivitave coeffecient d * derivative(error) - double deadband; ///< at what threshold are we close enough to be finished - double on_target_time; ///< the time in seconds that we have to be on target - ///< for to say we are officially at the target + double p; ///< proportional coeffecient p * error() + double i; ///< integral coeffecient i * integral(error) + double d; ///< derivitave coeffecient d * derivative(error) + double deadband; ///< at what threshold are we close enough to be finished + double on_target_time; ///< the time in seconds that we have to be on target + ///< for to say we are officially at the target ERROR_TYPE error_method; ///< Linear or angular. wheter to do error as a ///< simple subtraction or to wrap }; @@ -85,7 +85,7 @@ class PID : public Feedback { * and running the PID formula with the new sensor data * @param sensor_val the distance, angle, encoder position or whatever it is we * are measuring - * @param v_setpt Expected velocity setpoint, to subtract from the D term (for + * @param v_setpt Expected velocity setpoint, to subtract from the D term (for * velocity control) * @return the new output. What would be returned by PID::get() */ @@ -144,37 +144,30 @@ class PID : public Feedback { */ void set_target(double target); - pid_config_t - &config; ///< configuration struct for this controller. see pid_config_t - ///< for information about what this contains + pid_config_t &config; ///< configuration struct for this controller. see pid_config_t + ///< for information about what this contains private: - double last_error = - 0; ///< the error measured on the last iteration of update() - double accum_error = - 0; ///< the integral of error over time since we called init() - - double last_time = 0; ///< the time measured the last time update() was called - double on_target_last_time = - 0; ///< the time at which we started being on target - - double lower_limit = - 0; ///< the PID controller will never set a target to go lower than this - double upper_limit = - 0; ///< the PID controller will never set a target to go higher than this - - double target = 0; ///< the target position of the PID controller (lower_limit - ///< <= target <= upper_limit) + double last_error = 0; ///< the error measured on the last iteration of update() + double accum_error = 0; ///< the integral of error over time since we called init() + + double last_time = 0; ///< the time measured the last time update() was called + double on_target_last_time = 0; ///< the time at which we started being on target + + double lower_limit = 0; ///< the PID controller will never set a target to go lower than this + double upper_limit = 0; ///< the PID controller will never set a target to go higher than this + + double target = 0; ///< the target position of the PID controller (lower_limit + ///< <= target <= upper_limit) double target_vel = 0; ///< the target velocity of the PID controller (if != ///< 0, controller will not wait for stop) double sensor_val = 0; ///< the last recorded value of the sensor we use to ///< feed the PID controller - double out = 0; ///< the last calculated output value. we save it here so that - ///< we don't have to recalculate if we ask for it more than - ///< once between update() calls + double out = 0; ///< the last calculated output value. we save it here so that + ///< we don't have to recalculate if we ask for it more than + ///< once between update() calls - bool is_checking_on_target = - false; ///< true if the sensor reading is within target +/- deadband + bool is_checking_on_target = false; ///< true if the sensor reading is within target +/- deadband timer pid_timer; ///< used for calculating integrals and derivatives in line ///< with the real world times and checking the time we are diff --git a/include/utils/controls/take_back_half.h b/include/utils/controls/take_back_half.h index 68adb6a..e25e979 100644 --- a/include/utils/controls/take_back_half.h +++ b/include/utils/controls/take_back_half.h @@ -3,57 +3,57 @@ /// @brief A velocity controller /// @warning If you try to use this as a position controller, it will fail. -class TakeBackHalf : public Feedback -{ +class TakeBackHalf : public Feedback { public: - TakeBackHalf(double TBH_gain, double first_cross_split, double on_target_threshold); - /** - * Initialize the feedback controller for a movement - * - * @param start_pt the current sensor value - * @param set_pt where the sensor value should be - * @param start_vel Movement starting velocity (IGNORED) - * @param end_vel Movement ending velocity (IGNORED) - */ - void init(double start_pt, double set_pt); - /** - * Iterate the feedback loop once with an updated sensor value - * - * @param val value from the sensor - * @return feedback loop result - */ - double update(double val) override; - - /** - * @return the last saved result from the feedback controller - */ - double get() override; - - /** - * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. - * - * @param lower Upper limit - * @param upper Lower limit - */ - void set_limits(double lower, double upper) override; - - /** - * @return true if the feedback controller has reached it's setpoint - */ - bool is_on_target() override; - - double TBH_gain; ///< tuned parameter - double first_cross_split; + TakeBackHalf(double TBH_gain, double first_cross_split, double on_target_threshold); + /** + * Initialize the feedback controller for a movement + * + * @param start_pt the current sensor value + * @param set_pt where the sensor value should be + * @param start_vel Movement starting velocity (IGNORED) + * @param end_vel Movement ending velocity (IGNORED) + */ + void init(double start_pt, double set_pt); + /** + * Iterate the feedback loop once with an updated sensor value + * + * @param val value from the sensor + * @return feedback loop result + */ + double update(double val) override; + + /** + * @return the last saved result from the feedback controller + */ + double get() override; + + /** + * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * + * @param lower Upper limit + * @param upper Lower limit + */ + void set_limits(double lower, double upper) override; + + /** + * @return true if the feedback controller has reached it's setpoint + */ + bool is_on_target() override; + + double TBH_gain; ///< tuned parameter + double first_cross_split; + private: - double on_target_threshhold; ///< tuned parameter + double on_target_threshhold; ///< tuned parameter - double target = 0.0; + double target = 0.0; - bool first_cross = true; - double tbh = 0.0; - double prev_error = 0.0; + bool first_cross = true; + double tbh = 0.0; + double prev_error = 0.0; - double output = 0.0; - double lower = 0.0, upper = 0.0; ///< output limits + double output = 0.0; + double lower = 0.0, upper = 0.0; ///< output limits }; \ No newline at end of file diff --git a/include/utils/controls/trapezoid_profile.h b/include/utils/controls/trapezoid_profile.h index 865d342..8446ce2 100644 --- a/include/utils/controls/trapezoid_profile.h +++ b/include/utils/controls/trapezoid_profile.h @@ -2,86 +2,83 @@ /** * motion_t is a description of 1 dimensional motion at a point in time. -*/ -typedef struct -{ - double pos; ///< 1d position at this point in time - double vel; ///< 1d velocity at this point in time - double accel; ///< 1d acceleration at this point in time + */ +typedef struct { + double pos; ///< 1d position at this point in time + double vel; ///< 1d velocity at this point in time + double accel; ///< 1d acceleration at this point in time } motion_t; /** * Trapezoid Profile - * + * * This is a motion profile defined by an acceleration, maximum velocity, start point and end point. * Using this information, a parametric function is generated, with a period of acceleration, constant * velocity, and deceleration. The velocity graph looks like a trapezoid, giving it it's name. - * - * If the maximum velocity is set high enough, this will become a S-curve profile, with only acceleration and deceleration. - * + * + * If the maximum velocity is set high enough, this will become a S-curve profile, with only acceleration and + * deceleration. + * * This class is designed for use in properly modelling the motion of the robots to create a feedfoward * and target for PID. Acceleration and Maximum velocity should be measured on the robot and tuned down * slightly to account for battery drop. - * + * * Here are the equations graphed for ease of understanding: * https://www.desmos.com/calculator/rkm3ivu1yk - * + * * @author Ryan McGee * @date 7/12/2022 - * + * */ -class TrapezoidProfile -{ - public: - - /** - * @brief Construct a new Trapezoid Profile object - * - * @param max_v Maximum velocity the robot can run at - * @param accel Maximum acceleration of the robot - */ - TrapezoidProfile(double max_v, double accel); - - /** - * @brief Run the trapezoidal profile based on the time that's ellapsed - * - * @param time_s Time since start of movement - * @return motion_t Position, velocity and acceleration - */ - motion_t calculate(double time_s); +class TrapezoidProfile { +public: + /** + * @brief Construct a new Trapezoid Profile object + * + * @param max_v Maximum velocity the robot can run at + * @param accel Maximum acceleration of the robot + */ + TrapezoidProfile(double max_v, double accel); - /** - * set_endpts defines a start and end position - * @param start the starting position of the path - * @param end the ending position of the path - */ - void set_endpts(double start, double end); + /** + * @brief Run the trapezoidal profile based on the time that's ellapsed + * + * @param time_s Time since start of movement + * @return motion_t Position, velocity and acceleration + */ + motion_t calculate(double time_s); - /** - * set_accel sets the acceleration this profile will use (the left and right legs of the trapezoid) - * @param accel the acceleration amount to use - */ - void set_accel(double accel); + /** + * set_endpts defines a start and end position + * @param start the starting position of the path + * @param end the ending position of the path + */ + void set_endpts(double start, double end); - /** - * sets the maximum velocity for the profile - * (the height of the top of the trapezoid) - * @param max_v the maximum velocity the robot can travel at - */ - void set_max_v(double max_v); + /** + * set_accel sets the acceleration this profile will use (the left and right legs of the trapezoid) + * @param accel the acceleration amount to use + */ + void set_accel(double accel); - /** - * uses the kinematic equations to and specified accel and max_v to figure out how long moving along the profile would take - * @return the time the path will take to travel - */ - double get_movement_time(); + /** + * sets the maximum velocity for the profile + * (the height of the top of the trapezoid) + * @param max_v the maximum velocity the robot can travel at + */ + void set_max_v(double max_v); - private: - double start, end; ///< the start and ending position of the profile - double max_v; ///< the maximum velocity to travel at for this profile - double accel; ///< the rate of acceleration to use for this profile. - double time; ///< the current point in time along the path - + /** + * uses the kinematic equations to and specified accel and max_v to figure out how long moving along the profile would + * take + * @return the time the path will take to travel + */ + double get_movement_time(); +private: + double start, end; ///< the start and ending position of the profile + double max_v; ///< the maximum velocity to travel at for this profile + double accel; ///< the rate of acceleration to use for this profile. + double time; ///< the current point in time along the path }; \ No newline at end of file diff --git a/include/utils/generic_auto.h b/include/utils/generic_auto.h index f03fd76..d59edd6 100644 --- a/include/utils/generic_auto.h +++ b/include/utils/generic_auto.h @@ -1,59 +1,51 @@ #pragma once -#include -#include #include "vex.h" #include +#include +#include typedef std::function state_ptr; /** * GenericAuto provides a pleasant interface for organizing an auto path * steps of the path can be added with add() and when ready, calling run() will begin executing the path -*/ -class GenericAuto -{ - public: - + */ +class GenericAuto { +public: /** - * The method that runs the autonomous. If 'blocking' is true, then - * this method will run through every state until it finished. - * - * If blocking is false, then assuming every state is also non-blocking, - * the method will run through the current state in the list and return - * immediately. - * - * @param blocking - * Whether or not to block the thread until all states have run - * @returns - * true after all states have finished. - */ - [[deprecated("Use CommandController instead.")]] - bool run(bool blocking); + * The method that runs the autonomous. If 'blocking' is true, then + * this method will run through every state until it finished. + * + * If blocking is false, then assuming every state is also non-blocking, + * the method will run through the current state in the list and return + * immediately. + * + * @param blocking + * Whether or not to block the thread until all states have run + * @returns + * true after all states have finished. + */ + [[deprecated("Use CommandController instead.")]] bool run(bool blocking); /** * Add a new state to the autonomous via function point of type "bool (ptr*)()" * @param new_state the function to run */ - [[deprecated("Use CommandController instead.")]] - void add(state_ptr new_state); + [[deprecated("Use CommandController instead.")]] void add(state_ptr new_state); /** * Add a new state to the autonomous via function point of type "bool (ptr*)()" that will run asynchronously * @param async_state the function to run */ - [[deprecated("Use CommandController instead.")]] - void add_async(state_ptr async_state); + [[deprecated("Use CommandController instead.")]] void add_async(state_ptr async_state); /** * add_delay adds a period where the auto system will simply wait for the specified time * @param ms how long to wait in milliseconds - */ - [[deprecated("Use CommandController instead.")]] - void add_delay(int ms); - - private: + */ + [[deprecated("Use CommandController instead.")]] void add_delay(int ms); +private: std::queue state_list; - }; diff --git a/include/utils/geometry.h b/include/utils/geometry.h index c6e18a9..b273626 100644 --- a/include/utils/geometry.h +++ b/include/utils/geometry.h @@ -4,132 +4,87 @@ /** * Data structure representing an X,Y coordinate */ -struct point_t -{ - double x; ///< the x position in space - double y; ///< the y position in space +struct point_t { + double x; ///< the x position in space + double y; ///< the y position in space - /** - * dist calculates the euclidian distance between this point and another point using the pythagorean theorem - * @param other the point to measure the distance from - * @return the euclidian distance between this and other - */ - double dist(const point_t other) const - { - return std::sqrt(std::pow(this->x - other.x, 2) + pow(this->y - other.y, 2)); - } + /** + * dist calculates the euclidian distance between this point and another point using the pythagorean theorem + * @param other the point to measure the distance from + * @return the euclidian distance between this and other + */ + double dist(const point_t other) const { + return std::sqrt(std::pow(this->x - other.x, 2) + pow(this->y - other.y, 2)); + } - /** - * Vector2D addition operation on points - * @param other the point to add on to this - * @return this + other (this.x + other.x, this.y + other.y) - */ - point_t operator+(const point_t &other) const - { - point_t p{ - .x = this->x + other.x, - .y = this->y + other.y}; - return p; - } + /** + * Vector2D addition operation on points + * @param other the point to add on to this + * @return this + other (this.x + other.x, this.y + other.y) + */ + point_t operator+(const point_t &other) const { + point_t p{.x = this->x + other.x, .y = this->y + other.y}; + return p; + } - /** - * Vector2D subtraction operation on points - * @param other the point_t to subtract from this - * @return this - other (this.x - other.x, this.y - other.y) - */ - point_t operator-(const point_t &other) const - { - point_t p{ - .x = this->x - other.x, - .y = this->y - other.y}; - return p; - } + /** + * Vector2D subtraction operation on points + * @param other the point_t to subtract from this + * @return this - other (this.x - other.x, this.y - other.y) + */ + point_t operator-(const point_t &other) const { + point_t p{.x = this->x - other.x, .y = this->y - other.y}; + return p; + } - point_t operator*(double s) const - { - return {x * s, y * s}; - } - point_t operator/(double s) const - { - return {x / s, y / s}; - } + point_t operator*(double s) const { return {x * s, y * s}; } + point_t operator/(double s) const { return {x / s, y / s}; } - point_t operator-() const - { - return {-x, -y}; - } - point_t operator+() const - { - return {x, y}; - } + point_t operator-() const { return {-x, -y}; } + point_t operator+() const { return {x, y}; } - bool operator==(const point_t &rhs) - { - return x == rhs.x && y == rhs.y; - } + bool operator==(const point_t &rhs) { return x == rhs.x && y == rhs.y; } }; /** * Describes a single position and rotation */ -struct pose_t -{ - double x; ///< x position in the world - double y; ///< y position in the world - double rot; ///< rotation in the world +struct pose_t { + double x; ///< x position in the world + double y; ///< y position in the world + double rot; ///< rotation in the world - point_t get_point() - { - return point_t{.x = x, .y = y}; - } - -} ; - -struct Rect -{ - point_t min; - point_t max; - static Rect from_min_and_size(point_t min, point_t size){ - return {min, min+size}; - } - point_t dimensions() const - { - return max - min; - } - point_t center() const{ - return (min + max)/2; - } - double width() const{ - return max.x - min.x; - } - double height() const{ - return max.y - min.y; - } - bool contains(point_t p) const - { - bool xin = p.x > min.x && p.x < max.x; - bool yin = p.y > min.y && p.y < max.y; - return xin && yin; - } + point_t get_point() { return point_t{.x = x, .y = y}; } +}; +struct Rect { + point_t min; + point_t max; + static Rect from_min_and_size(point_t min, point_t size) { return {min, min + size}; } + point_t dimensions() const { return max - min; } + point_t center() const { return (min + max) / 2; } + double width() const { return max.x - min.x; } + double height() const { return max.y - min.y; } + bool contains(point_t p) const { + bool xin = p.x > min.x && p.x < max.x; + bool yin = p.y > min.y && p.y < max.y; + return xin && yin; + } }; -struct Mat2 -{ - double X11, X12; - double X21, X22; - point_t operator*(const point_t p) const - { - double outx = p.x * X11 + p.y * X12; - double outy = p.x * X21 + p.y * X22; - return {outx, outy}; - } +struct Mat2 { + double X11, X12; + double X21, X22; + point_t operator*(const point_t p) const { + double outx = p.x * X11 + p.y * X12; + double outy = p.x * X21 + p.y * X22; + return {outx, outy}; + } - static Mat2 FromRotationDegrees(double degrees) - { - double rad = degrees * (M_PI / 180.0); - double c = cos(rad); - double s = sin(rad); - return {c, -s, s, c}; - } + static Mat2 FromRotationDegrees(double degrees) { + double rad = degrees * (M_PI / 180.0); + double c = cos(rad); + double s = sin(rad); + return {c, -s, s, c}; + } }; \ No newline at end of file diff --git a/include/utils/graph_drawer.h b/include/utils/graph_drawer.h index 9273389..c637f09 100644 --- a/include/utils/graph_drawer.h +++ b/include/utils/graph_drawer.h @@ -1,15 +1,14 @@ #pragma once -#include -#include -#include -#include -#include "vex.h" #include "../core/include/utils/geometry.h" #include "../core/include/utils/vector2d.h" +#include "vex.h" +#include +#include +#include +#include -class GraphDrawer -{ +class GraphDrawer { public: /// @brief Creates a graph drawer with the specified number of series (each series is a separate line) /// @param num_samples the number of samples to graph at a time (40 will graph the last 40 data points) @@ -17,7 +16,8 @@ class GraphDrawer /// @param upper_bound the top of the window when displaying (if upper_bound = lower_bound, auto calculate bounds) /// @param colors the colors of the series. must be of size num_series /// @param num_series the number of series to graph - GraphDrawer(int num_samples, double lower_bound, double upper_bound, std::vector colors, size_t num_series = 1); + GraphDrawer(int num_samples, double lower_bound, double upper_bound, std::vector colors, + size_t num_series = 1); /** * add_samples adds a point to the graph, removing one from the back * @param sample an x, y coordinate of the next point to graph @@ -26,7 +26,8 @@ class GraphDrawer /** * add_samples adds a point to the graph, removing one from the back - * @param sample a y coordinate of the next point to graph, the x coordinate is gotten from vex::timer::system(); (time in ms) + * @param sample a y coordinate of the next point to graph, the x coordinate is gotten from vex::timer::system(); + * (time in ms) */ void add_samples(std::vector sample); diff --git a/include/utils/logger.h b/include/utils/logger.h index 159baa6..696ea2a 100644 --- a/include/utils/logger.h +++ b/include/utils/logger.h @@ -1,68 +1,58 @@ #pragma once +#include "vex.h" #include #include #include -#include "vex.h" /// @brief possible values for log filtering -enum LogLevel -{ - DEBUG, - NOTICE, - WARNING, - ERROR, - CRITICAL, - TIME -}; +enum LogLevel { DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME }; /// @brief Class to simplify writing to files -class Logger -{ +class Logger { private: - const std::string filename; - vex::brain::sdcard sd; - void write_level(LogLevel l); + const std::string filename; + vex::brain::sdcard sd; + void write_level(LogLevel l); public: - /// @brief maximum size for a string to be before it's written - static constexpr int MAX_FORMAT_LEN = 512; - /// @brief Create a logger that will save to a file - /// @param filename the file to save to - explicit Logger(const std::string &filename); - - /// @brief copying not allowed - Logger(const Logger &l) = delete; - /// @brief copying not allowed - Logger &operator=(const Logger &l) = delete; - - - /// @brief Write a string to the log - /// @param s the string to write - void Log(const std::string &s); - - /// @brief Write a string to the log with a loglevel - /// @param level the level to write. DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME - /// @param s the string to write - void Log(LogLevel level, const std::string &s); - - /// @brief Write a string and newline to the log - /// @param s the string to write - void Logln(const std::string &s); - - /// @brief Write a string and a newline to the log with a loglevel - /// @param level the level to write. DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME - /// @param s the string to write - void Logln(LogLevel level, const std::string &s); - - /// @brief Write a formatted string to the log - /// @param fmt the format string (like printf) - /// @param ... the args - void Logf(const char *fmt, ...); - - /// @brief Write a formatted string to the log with a loglevel - /// @param level the level to write. DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME - /// @param fmt the format string (like printf) - /// @param ... the args - void Logf(LogLevel level, const char *fmt, ...); + /// @brief maximum size for a string to be before it's written + static constexpr int MAX_FORMAT_LEN = 512; + /// @brief Create a logger that will save to a file + /// @param filename the file to save to + explicit Logger(const std::string &filename); + + /// @brief copying not allowed + Logger(const Logger &l) = delete; + /// @brief copying not allowed + Logger &operator=(const Logger &l) = delete; + + /// @brief Write a string to the log + /// @param s the string to write + void Log(const std::string &s); + + /// @brief Write a string to the log with a loglevel + /// @param level the level to write. DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME + /// @param s the string to write + void Log(LogLevel level, const std::string &s); + + /// @brief Write a string and newline to the log + /// @param s the string to write + void Logln(const std::string &s); + + /// @brief Write a string and a newline to the log with a loglevel + /// @param level the level to write. DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME + /// @param s the string to write + void Logln(LogLevel level, const std::string &s); + + /// @brief Write a formatted string to the log + /// @param fmt the format string (like printf) + /// @param ... the args + void Logf(const char *fmt, ...); + + /// @brief Write a formatted string to the log with a loglevel + /// @param level the level to write. DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME + /// @param fmt the format string (like printf) + /// @param ... the args + void Logf(LogLevel level, const char *fmt, ...); }; diff --git a/include/utils/math_util.h b/include/utils/math_util.h index d419a6e..d101742 100644 --- a/include/utils/math_util.h +++ b/include/utils/math_util.h @@ -1,17 +1,16 @@ #pragma once -#include +#include "../core/include/utils/geometry.h" #include "math.h" #include "vex.h" -#include "../core/include/utils/geometry.h" - +#include /** -* Constrain the input between a minimum and a maximum value -* -* @param val the value to be restrained -* @param low the minimum value that will be returned -* @param high the maximum value that will be returned -**/ + * Constrain the input between a minimum and a maximum value + * + * @param val the value to be restrained + * @param low the minimum value that will be returned + * @param high the maximum value that will be returned + **/ double clamp(double value, double low, double high); /** @@ -19,14 +18,14 @@ double clamp(double value, double low, double high); * @param a at t = 0, output = a * @param b at t = 1, output = b * @return a linear mixing of a and b according to t -*/ + */ double lerp(double a, double b, double t); /** -* Returns the sign of a number -* @param x -* -* returns the sign +/-1 of x. 0 if x is 0 -**/ + * Returns the sign of a number + * @param x + * + * returns the sign +/-1 of x. 0 if x is 0 + **/ double sign(double x); double wrap_angle_deg(double input); @@ -40,7 +39,6 @@ Calculates the variance of a set of numbers (needed for linear regression) */ double variance(std::vector const &values, double mean); - /* Calculates the average of a vector of doubles @param values the list of values for which the average is taken diff --git a/include/utils/moving_average.h b/include/utils/moving_average.h index ed01819..389c7b1 100644 --- a/include/utils/moving_average.h +++ b/include/utils/moving_average.h @@ -5,8 +5,7 @@ * Interface for filters * Use add_entry to supply data and get_value to retrieve the filtered value */ -class Filter -{ +class Filter { public: virtual void add_entry(double n) = 0; virtual double get_value() const = 0; @@ -15,17 +14,18 @@ class Filter /** * MovingAverage * - * A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. - * This means that if you collect enough samples those that are too high are cancelled out by the samples that are too low leaving the real value. + * A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric + * around the actual value. This means that if you collect enough samples those that are too high are cancelled out by + * the samples that are too low leaving the real value. * * The MovingAverage class provides a simple interface to do this smoothing from our noisy sensor values. * - * WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' behind the actual value that the sensor is reading. - * Using a MovingAverage is thus a tradeoff between accuracy and lag time (more samples) vs. less accuracy and faster updating (less samples). + * WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' + * behind the actual value that the sensor is reading. Using a MovingAverage is thus a tradeoff between accuracy and lag + * time (more samples) vs. less accuracy and faster updating (less samples). * */ -class MovingAverage : public Filter -{ +class MovingAverage : public Filter { public: /* * Create a moving average calculator with 0 as the default value @@ -73,17 +73,18 @@ class MovingAverage : public Filter /** * ExponentialMovingAverage * - * An exponential moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. - * This means that if you collect enough samples those that are too high are cancelled out by the samples that are too low leaving the real value. + * An exponential moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly + * symmetric around the actual value. This means that if you collect enough samples those that are too high are + * cancelled out by the samples that are too low leaving the real value. * - * A simple mobing average lags significantly with time as it has to counteract old samples. An exponential moving average keeps more up to date by - * weighting newer readings higher than older readings so it is more up to date while also still smoothed. + * A simple mobing average lags significantly with time as it has to counteract old samples. An exponential moving + * average keeps more up to date by weighting newer readings higher than older readings so it is more up to date while + * also still smoothed. * * The ExponentialMovingAverage class provides an simple interface to do this smoothing from our noisy sensor values. * */ -class ExponentialMovingAverage : public Filter -{ +class ExponentialMovingAverage : public Filter { public: /* * Create a moving average calculator with 0 as the default value diff --git a/include/utils/pure_pursuit.h b/include/utils/pure_pursuit.h index 3fd8edb..2e27271 100644 --- a/include/utils/pure_pursuit.h +++ b/include/utils/pure_pursuit.h @@ -1,128 +1,120 @@ #pragma once -#include #include "../core/include/utils/geometry.h" #include "../core/include/utils/vector2d.h" #include "vex.h" +#include using namespace vex; namespace PurePursuit { +/** + * Wrapper for a vector of points, checking if any of the points are too close for pure pursuit + */ +class Path { +public: /** - * Wrapper for a vector of points, checking if any of the points are too close for pure pursuit - */ - class Path - { - public: - /** - * Create a Path - * @param points the points that make up the path - * @param radius the lookahead radius for pure pursuit - */ - Path(std::vector points, double radius); - - /** - * Get the points associated with this Path - */ - std::vector get_points(); - - /** - * Get the radius associated with this Path - */ - double get_radius(); - - /** - * Get whether this path will behave as expected - */ - bool is_valid(); - - private: - std::vector points; - double radius; - bool valid; - }; - /** - * Represents a piece of a cubic spline with s(x) = a(x-xi)^3 + b(x-xi)^2 + c(x-xi) + d - * The x_start and x_end shows where the equation is valid. + * Create a Path + * @param points the points that make up the path + * @param radius the lookahead radius for pure pursuit */ - struct spline - { - double a, b, c, d, x_start, x_end; - - double getY(double x) { - return a * pow((x - x_start), 3) + b * pow((x - x_start), 2) + c * (x - x_start) + d; - } - }; - /** - * a position along the hermite path - * contains a position and orientation information that the robot would be at at this point - */ - struct hermite_point - { - double x; - double y; - double dir; - double mag; - - point_t getPoint() const { - return {x, y}; - } - - Vector2D getTangent() const { - return Vector2D(dir, mag); - } - }; + Path(std::vector points, double radius); /** - * Returns points of the intersections of a line segment and a circle. The line - * segment is defined by two points, and the circle is defined by a center and radius. - */ - extern std::vector line_circle_intersections(point_t center, double r, point_t point1, point_t point2); - /** - * Selects a look ahead from all the intersections in the path. - */ - extern point_t get_lookahead(const std::vector &path, pose_t robot_loc, double radius); - - /** - * Injects points in a path without changing the curvature with a certain spacing. - */ - extern std::vector inject_path(const std::vector &path, double spacing); - - /** - * Returns a smoothed path maintaining the start and end of the path. - * - * Weight data is how much weight to update the data (alpha) - * Weight smooth is how much weight to smooth the coordinates (beta) - * Tolerance is how much change per iteration is necessary to continue iterating. - * - * Honestly have no idea if/how this works. - * https://medium.com/@jaems33/understanding-robot-motion-path-smoothing-5970c8363bc4 - */ - - extern std::vector smooth_path(const std::vector &path, double weight_data, double weight_smooth, double tolerance); - - extern std::vector smooth_path_cubic(const std::vector &path, double res); + * Get the points associated with this Path + */ + std::vector get_points(); /** - * Interpolates a smooth path given a list of waypoints using hermite splines. - * For more information: https://www.youtube.com/watch?v=hG0p4XgePSA. - * - * @param path The path of hermite points to interpolate. - * @param steps The number of points interpolated between points. - * @return The smoothed path. + * Get the radius associated with this Path */ - extern std::vector smooth_path_hermite(const std::vector &path, double step); + double get_radius(); /** - * Estimates the remaining distance from the robot's position to the end, - * by "searching" for the robot along the path and running a "connect the dots" - * distance algoritm - * - * @param path The pure pursuit path the robot is following - * @param robot_pose The robot's current position - * @param radius Pure pursuit "radius", used to search for the robot along the path - * @return A rough estimate of the remaining distance - */ - extern double estimate_remaining_dist(const std::vector &path, pose_t robot_pose, double radius); - -} \ No newline at end of file + * Get whether this path will behave as expected + */ + bool is_valid(); + +private: + std::vector points; + double radius; + bool valid; +}; +/** + * Represents a piece of a cubic spline with s(x) = a(x-xi)^3 + b(x-xi)^2 + c(x-xi) + d + * The x_start and x_end shows where the equation is valid. + */ +struct spline { + double a, b, c, d, x_start, x_end; + + double getY(double x) { return a * pow((x - x_start), 3) + b * pow((x - x_start), 2) + c * (x - x_start) + d; } +}; +/** + * a position along the hermite path + * contains a position and orientation information that the robot would be at at this point + */ +struct hermite_point { + double x; + double y; + double dir; + double mag; + + point_t getPoint() const { return {x, y}; } + + Vector2D getTangent() const { return Vector2D(dir, mag); } +}; + +/** + * Returns points of the intersections of a line segment and a circle. The line + * segment is defined by two points, and the circle is defined by a center and radius. + */ +extern std::vector line_circle_intersections(point_t center, double r, point_t point1, point_t point2); +/** + * Selects a look ahead from all the intersections in the path. + */ +extern point_t get_lookahead(const std::vector &path, pose_t robot_loc, double radius); + +/** + * Injects points in a path without changing the curvature with a certain spacing. + */ +extern std::vector inject_path(const std::vector &path, double spacing); + +/** + * Returns a smoothed path maintaining the start and end of the path. + * + * Weight data is how much weight to update the data (alpha) + * Weight smooth is how much weight to smooth the coordinates (beta) + * Tolerance is how much change per iteration is necessary to continue iterating. + * + * Honestly have no idea if/how this works. + * https://medium.com/@jaems33/understanding-robot-motion-path-smoothing-5970c8363bc4 + */ + +extern std::vector smooth_path(const std::vector &path, double weight_data, double weight_smooth, + double tolerance); + +extern std::vector smooth_path_cubic(const std::vector &path, double res); + +/** + * Interpolates a smooth path given a list of waypoints using hermite splines. + * For more information: https://www.youtube.com/watch?v=hG0p4XgePSA. + * + * @param path The path of hermite points to interpolate. + * @param steps The number of points interpolated between points. + * @return The smoothed path. + */ +extern std::vector smooth_path_hermite(const std::vector &path, double step); + +/** + * Estimates the remaining distance from the robot's position to the end, + * by "searching" for the robot along the path and running a "connect the dots" + * distance algoritm + * + * @param path The pure pursuit path the robot is following + * @param robot_pose The robot's current position + * @param radius Pure pursuit "radius", used to search for the robot along the path + * @return A rough estimate of the remaining distance + */ +extern double estimate_remaining_dist(const std::vector &path, pose_t robot_pose, double radius); + +} // namespace PurePursuit \ No newline at end of file diff --git a/include/utils/serializer.h b/include/utils/serializer.h index 327b653..edf80b1 100644 --- a/include/utils/serializer.h +++ b/include/utils/serializer.h @@ -1,9 +1,9 @@ #pragma once #include #include +#include #include #include -#include #include /// @brief character that will be used to seperate values @@ -12,86 +12,87 @@ const char serialization_separator = '$'; const std::size_t MAX_FILE_SIZE = 4096; /// @brief Serializes Arbitrary data to a file on the SD Card -class Serializer -{ +class Serializer { private: - bool flush_always; - std::string filename; - std::map ints; - std::map bools; - std::map doubles; - std::map strings; + bool flush_always; + std::string filename; + std::map ints; + std::map bools; + std::map doubles; + std::map strings; - /// @brief loads Serializer state from disk - bool read_from_disk(); + /// @brief loads Serializer state from disk + bool read_from_disk(); public: - /// @brief Save and close upon destruction (bc of vex, this doesnt always get called when the program ends. To be sure, call save_to_disk) - ~Serializer() - { - save_to_disk(); - printf("Saving %s\n", filename.c_str()); - fflush(stdout); - } - - /// @brief create a Serializer - /// @param filename the file to read from. If filename does not exist we will create that file - /// @param flush_always If true, after every write flush to a file. If false, you are responsible for calling save_to_disk - explicit Serializer(const std::string &filename, bool flush_always = true) : flush_always(flush_always), filename(filename), ints({}), bools({}), doubles({}), strings({}) - - { - read_from_disk(); - } - - /// @brief saves current Serializer state to disk - void save_to_disk() const; - - /// Setters - not saved until save_to_disk is called - - /// @brief sets an integer by the name of name to i. If flush_always == true, this will save to the sd card - /// @param name name of integer - /// @param i value of integer - void set_int(const std::string &name, int i); - - /// @brief sets a bool by the name of name to b. If flush_always == true, this will save to the sd card - /// @param name name of bool - /// @param b value of bool - void set_bool(const std::string &name, bool b); - - /// @brief sets a double by the name of name to d. If flush_always == true, this will save to the sd card - /// @param name name of double - /// @param d value of double - void set_double(const std::string &name, double d); - - /// @brief sets a string by the name of name to s. If flush_always == true, this will save to the sd card - /// @param name name of string - /// @param i value of string - void set_string(const std::string &name, std::string str); - - /// Getters - /// Return value if it exists in the serializer - - /// @brief gets a value stored in the serializer. If not found, sets the value to otherwise - /// @param name name of value - /// @param otherwise value if the name is not specified - /// @return the value if found or otherwise - int int_or(const std::string &name, int otherwise); - - /// @brief gets a value stored in the serializer. If not, sets the value to otherwise - /// @param name name of value - /// @param otherwise value if the name is not specified - /// @return the value if found or otherwise - bool bool_or(const std::string &name, bool otherwise); - - /// @brief gets a value stored in the serializer. If not, sets the value to otherwise - /// @param name name of value - /// @param otherwise value if the name is not specified - /// @return the value if found or otherwise - double double_or(const std::string &name, double otherwise); - - /// @brief gets a value stored in the serializer. If not, sets the value to otherwise - /// @param name name of value - /// @param otherwise value if the name is not specified - /// @return the value if found or otherwise - std::string string_or(const std::string &name, std::string otherwise); + /// @brief Save and close upon destruction (bc of vex, this doesnt always get called when the program ends. To be + /// sure, call save_to_disk) + ~Serializer() { + save_to_disk(); + printf("Saving %s\n", filename.c_str()); + fflush(stdout); + } + + /// @brief create a Serializer + /// @param filename the file to read from. If filename does not exist we will create that file + /// @param flush_always If true, after every write flush to a file. If false, you are responsible for calling + /// save_to_disk + explicit Serializer(const std::string &filename, bool flush_always = true) + : flush_always(flush_always), filename(filename), ints({}), bools({}), doubles({}), strings({}) + + { + read_from_disk(); + } + + /// @brief saves current Serializer state to disk + void save_to_disk() const; + + /// Setters - not saved until save_to_disk is called + + /// @brief sets an integer by the name of name to i. If flush_always == true, this will save to the sd card + /// @param name name of integer + /// @param i value of integer + void set_int(const std::string &name, int i); + + /// @brief sets a bool by the name of name to b. If flush_always == true, this will save to the sd card + /// @param name name of bool + /// @param b value of bool + void set_bool(const std::string &name, bool b); + + /// @brief sets a double by the name of name to d. If flush_always == true, this will save to the sd card + /// @param name name of double + /// @param d value of double + void set_double(const std::string &name, double d); + + /// @brief sets a string by the name of name to s. If flush_always == true, this will save to the sd card + /// @param name name of string + /// @param i value of string + void set_string(const std::string &name, std::string str); + + /// Getters + /// Return value if it exists in the serializer + + /// @brief gets a value stored in the serializer. If not found, sets the value to otherwise + /// @param name name of value + /// @param otherwise value if the name is not specified + /// @return the value if found or otherwise + int int_or(const std::string &name, int otherwise); + + /// @brief gets a value stored in the serializer. If not, sets the value to otherwise + /// @param name name of value + /// @param otherwise value if the name is not specified + /// @return the value if found or otherwise + bool bool_or(const std::string &name, bool otherwise); + + /// @brief gets a value stored in the serializer. If not, sets the value to otherwise + /// @param name name of value + /// @param otherwise value if the name is not specified + /// @return the value if found or otherwise + double double_or(const std::string &name, double otherwise); + + /// @brief gets a value stored in the serializer. If not, sets the value to otherwise + /// @param name name of value + /// @param otherwise value if the name is not specified + /// @return the value if found or otherwise + std::string string_or(const std::string &name, std::string otherwise); }; diff --git a/include/utils/state_machine.h b/include/utils/state_machine.h index f821180..8671fe0 100644 --- a/include/utils/state_machine.h +++ b/include/utils/state_machine.h @@ -31,176 +31,172 @@ * function called to_string that takes them as its only parameter and returns a * std::string */ -template +template class StateMachine { - static_assert(std::is_enum::value, - "Message should be an enum (it's easier that way)"); - static_assert(std::is_enum::value, - "IDType should be an enum (it's easier that way)"); - + static_assert(std::is_enum::value, "Message should be an enum (it's easier that way)"); + static_assert(std::is_enum::value, "IDType should be an enum (it's easier that way)"); + +public: + /** + * @brief MaybeMessage + * a message of Message type or nothing + * MaybeMessage m = {}; // empty + * MaybeMessage m = Message::EnumField1 + */ + class MaybeMessage { public: /** - * @brief MaybeMessage - * a message of Message type or nothing - * MaybeMessage m = {}; // empty - * MaybeMessage m = Message::EnumField1 - */ - class MaybeMessage { - public: - /** - * @brief Empty message - when theres no message - */ - MaybeMessage() : exists(false) {} - /** - * @brief Create a maybemessage with a message - * @param msg the message to hold on to - */ - MaybeMessage(Message msg) : exists(true), thing(msg) {} - /** - * @brief check if the message is here - * @return true if there is a message - */ - bool has_message() { return exists; } - /** - * @brief Get the message stored. The return value is invalid unless - * has_message returned true - * @return The message if it exists. Undefined otherwise - */ - Message message() { return thing; } - - private: - bool exists; - Message thing; - }; - /** - * Abstract class that all states for this machine must inherit from - * States MUST override respond() and id() in order to function correctly - * (the compiler won't have it any other way) + * @brief Empty message - when theres no message */ - struct State { - // run once when we enter the state - virtual void entry(System &) {} - // run continously while in the state - virtual MaybeMessage work(System &) { return {}; } - // run once when we exit the state - virtual void exit(System &) {} - // respond to a message when one comes in - virtual State *respond(System &s, Message m) = 0; - // Identify - virtual IDType id() const = 0; - - // virtual destructor cuz c++ - virtual ~State() {} - }; - - // Data that gets passed to the runner thread. Don't worry too much about - // this - using thread_data = std::pair; - + MaybeMessage() : exists(false) {} /** - * @brief Construct a state machine and immediatly start running it - * @param initial the state that the machine will begin in + * @brief Create a maybemessage with a message + * @param msg the message to hold on to */ - StateMachine(State *initial) - : runner(thread_runner, new thread_data{initial, this}) {} - + MaybeMessage(Message msg) : exists(true), thing(msg) {} /** - * @brief retrieve the current state of the state machine. This is safe to - * call from external threads - * @return the current state + * @brief check if the message is here + * @return true if there is a message */ - IDType current_state() const { - mut.lock(); - auto t = cur_type; - mut.unlock(); - return t; - } + bool has_message() { return exists; } /** - * @brief send a message to the state machine from outside - * @param msg the message to send - * This is safe to call from external threads + * @brief Get the message stored. The return value is invalid unless + * has_message returned true + * @return The message if it exists. Undefined otherwise */ - void send_message(Message msg) { - mut.lock(); - incoming_msg = msg; - mut.unlock(); - } + Message message() { return thing; } private: - vex::task runner; - mutable vex::mutex mut; - MaybeMessage incoming_msg; - IDType cur_type; - - /** - * @brief the thread that does the running of the state machine. - * @param vptr the thread_data that we get passed to begin. cast it back - * @return return value of thread (the thread never ends so this doesn't - * really matter) - */ - static int thread_runner(void *vptr) { - thread_data *ptr = static_cast(vptr); - State *cur_state = ptr->first; - - StateMachine &sys = *ptr->second; - System &derived = *static_cast(&sys); - - cur_state->entry(derived); - + bool exists; + Message thing; + }; + /** + * Abstract class that all states for this machine must inherit from + * States MUST override respond() and id() in order to function correctly + * (the compiler won't have it any other way) + */ + struct State { + // run once when we enter the state + virtual void entry(System &) {} + // run continously while in the state + virtual MaybeMessage work(System &) { return {}; } + // run once when we exit the state + virtual void exit(System &) {} + // respond to a message when one comes in + virtual State *respond(System &s, Message m) = 0; + // Identify + virtual IDType id() const = 0; + + // virtual destructor cuz c++ + virtual ~State() {} + }; + + // Data that gets passed to the runner thread. Don't worry too much about + // this + using thread_data = std::pair; + + /** + * @brief Construct a state machine and immediatly start running it + * @param initial the state that the machine will begin in + */ + StateMachine(State *initial) : runner(thread_runner, new thread_data{initial, this}) {} + + /** + * @brief retrieve the current state of the state machine. This is safe to + * call from external threads + * @return the current state + */ + IDType current_state() const { + mut.lock(); + auto t = cur_type; + mut.unlock(); + return t; + } + /** + * @brief send a message to the state machine from outside + * @param msg the message to send + * This is safe to call from external threads + */ + void send_message(Message msg) { + mut.lock(); + incoming_msg = msg; + mut.unlock(); + } + +private: + vex::task runner; + mutable vex::mutex mut; + MaybeMessage incoming_msg; + IDType cur_type; + + /** + * @brief the thread that does the running of the state machine. + * @param vptr the thread_data that we get passed to begin. cast it back + * @return return value of thread (the thread never ends so this doesn't + * really matter) + */ + static int thread_runner(void *vptr) { + thread_data *ptr = static_cast(vptr); + State *cur_state = ptr->first; + + StateMachine &sys = *ptr->second; + System &derived = *static_cast(&sys); + + cur_state->entry(derived); + + sys.cur_type = cur_state->id(); + + auto respond_to_message = [&](Message msg) { + if (do_log) { + printf("responding to msg: %s\n", to_string(msg).c_str()); + fflush(stdout); + } + + State *next_state = cur_state->respond(derived, msg); + + if (cur_state != next_state) { + // switched states + sys.mut.lock(); + + cur_state->exit(derived); + next_state->entry(derived); + + delete cur_state; + + cur_state = next_state; sys.cur_type = cur_state->id(); - auto respond_to_message = [&](Message msg) { - if (do_log) { - printf("responding to msg: %s\n", to_string(msg).c_str()); - fflush(stdout); - } - - State *next_state = cur_state->respond(derived, msg); - - if (cur_state != next_state) { - // switched states - sys.mut.lock(); - - cur_state->exit(derived); - next_state->entry(derived); - - delete cur_state; - - cur_state = next_state; - sys.cur_type = cur_state->id(); - - sys.mut.unlock(); - } - }; + sys.mut.unlock(); + } + }; - while (true) { - if (do_log) { - std::string str = to_string(cur_state->id()); - std::string str2 = to_string(sys.cur_type); + while (true) { + if (do_log) { + std::string str = to_string(cur_state->id()); + std::string str2 = to_string(sys.cur_type); - printf("state: %s %s\n", str.c_str(), str2.c_str()); - } + printf("state: %s %s\n", str.c_str(), str2.c_str()); + } - // Internal Message passed - MaybeMessage internal_msg = cur_state->work(derived); + // Internal Message passed + MaybeMessage internal_msg = cur_state->work(derived); - if (internal_msg.has_message()) { - respond_to_message(internal_msg.message()); - } + if (internal_msg.has_message()) { + respond_to_message(internal_msg.message()); + } - // External Message passed - sys.mut.lock(); - MaybeMessage incoming = sys.incoming_msg; - sys.incoming_msg = {}; - sys.mut.unlock(); + // External Message passed + sys.mut.lock(); + MaybeMessage incoming = sys.incoming_msg; + sys.incoming_msg = {}; + sys.mut.unlock(); - if (incoming.has_message()) { - respond_to_message(incoming.message()); - } + if (incoming.has_message()) { + respond_to_message(incoming.message()); + } - vexDelay(delay_ms); - } - return 0; + vexDelay(delay_ms); } + return 0; + } }; diff --git a/include/utils/vector2d.h b/include/utils/vector2d.h index c39f50f..6c555cc 100644 --- a/include/utils/vector2d.h +++ b/include/utils/vector2d.h @@ -1,96 +1,92 @@ #pragma once - -#include #include "../core/include/utils/geometry.h" +#include #ifndef PI #define PI 3.141592654 #endif /** * Vector2D is an x,y pair - * Used to represent 2D locations on the field. + * Used to represent 2D locations on the field. * It can also be treated as a direction and magnitude -*/ -class Vector2D -{ + */ +class Vector2D { public: - /** - * Construct a vector object. - * - * @param dir Direction, in radians. 'foward' is 0, clockwise positive when viewed from the top. - * @param mag Magnitude. - */ - Vector2D(double dir, double mag); - - /** - * Construct a vector object from a cartesian point. - * - * @param p point_t.x , point_t.y - */ - Vector2D(point_t p); - - /** - * Get the direction of the vector, in radians. - * '0' is forward, clockwise positive when viewed from the top. - * - * Use r2d() to convert. - * @return the direction of the vetctor in radians - */ - double get_dir() const; - - /** - * @return the magnitude of the vector - */ - double get_mag() const; - - /** - * @return the X component of the vector; positive to the right. - */ - double get_x() const; - - /** - * @return the Y component of the vector, positive forward. - */ - double get_y() const; - - /** - * Changes the magnitude of the vector to 1 - * @return the normalized vector - */ - Vector2D normalize(); - - /** - * Returns a point from the vector - * @return the point represented by the vector - */ - point_t point(); - -/** - * Scales a Vector2D by a scalar with the * operator - * @param x the value to scale the vector by - * @return the this Vector2D scaled by x -*/ - Vector2D operator*(const double &x); - /** - * Add the components of two vectors together - * Vector2D + Vector2D = (this.x + other.x, this.y + other.y) - * @param other the vector to add to this - * @return the sum of the vectors - */ - Vector2D operator+(const Vector2D &other); - /** - * Subtract the components of two vectors together - * Vector2D - Vector2D = (this.x - other.x, this.y - other.y) - * @param other the vector to subtract from this - * @return the difference of the vectors - */ - Vector2D operator-(const Vector2D &other); + /** + * Construct a vector object. + * + * @param dir Direction, in radians. 'foward' is 0, clockwise positive when viewed from the top. + * @param mag Magnitude. + */ + Vector2D(double dir, double mag); + + /** + * Construct a vector object from a cartesian point. + * + * @param p point_t.x , point_t.y + */ + Vector2D(point_t p); + + /** + * Get the direction of the vector, in radians. + * '0' is forward, clockwise positive when viewed from the top. + * + * Use r2d() to convert. + * @return the direction of the vetctor in radians + */ + double get_dir() const; + + /** + * @return the magnitude of the vector + */ + double get_mag() const; + + /** + * @return the X component of the vector; positive to the right. + */ + double get_x() const; + + /** + * @return the Y component of the vector, positive forward. + */ + double get_y() const; + + /** + * Changes the magnitude of the vector to 1 + * @return the normalized vector + */ + Vector2D normalize(); + + /** + * Returns a point from the vector + * @return the point represented by the vector + */ + point_t point(); + + /** + * Scales a Vector2D by a scalar with the * operator + * @param x the value to scale the vector by + * @return the this Vector2D scaled by x + */ + Vector2D operator*(const double &x); + /** + * Add the components of two vectors together + * Vector2D + Vector2D = (this.x + other.x, this.y + other.y) + * @param other the vector to add to this + * @return the sum of the vectors + */ + Vector2D operator+(const Vector2D &other); + /** + * Subtract the components of two vectors together + * Vector2D - Vector2D = (this.x - other.x, this.y - other.y) + * @param other the vector to subtract from this + * @return the difference of the vectors + */ + Vector2D operator-(const Vector2D &other); private: - - double dir, mag; - + double dir, mag; }; /** diff --git a/src/subsystems/custom_encoder.cpp b/src/subsystems/custom_encoder.cpp index a8f3adc..b9614f8 100644 --- a/src/subsystems/custom_encoder.cpp +++ b/src/subsystems/custom_encoder.cpp @@ -1,41 +1,28 @@ -#include "../core/include/subsystems/custom_encoder.h" +#include "../core/include/subsystems/custom_encoder.h" -CustomEncoder::CustomEncoder(vex::triport::port &port, double ticks_per_rev) -: super(port) -{ +CustomEncoder::CustomEncoder(vex::triport::port &port, double ticks_per_rev) : super(port) { // bc it's a quadrature encoder, ticks per rev has to be multiplied by 4 tick_scalar = 360 / (ticks_per_rev * 4); } -void CustomEncoder::setRotation(double val, vex::rotationUnits units) -{ - super::setRotation(val / tick_scalar, units); -} +void CustomEncoder::setRotation(double val, vex::rotationUnits units) { super::setRotation(val / tick_scalar, units); } -void CustomEncoder::setPosition(double val, vex::rotationUnits units) -{ - super::setPosition(val / tick_scalar, units); -} +void CustomEncoder::setPosition(double val, vex::rotationUnits units) { super::setPosition(val / tick_scalar, units); } + +double CustomEncoder::rotation(vex::rotationUnits units) { + if (units != vex::rotationUnits::raw) { + return super::rotation(units) * tick_scalar; + } -double CustomEncoder::rotation(vex::rotationUnits units) -{ - if(units != vex::rotationUnits::raw) { - return super::rotation(units) * tick_scalar; -} - return super::rotation(units); } -double CustomEncoder::position(vex::rotationUnits units) -{ +double CustomEncoder::position(vex::rotationUnits units) { if (units != vex::rotationUnits::raw) { - return super::position(units) * tick_scalar; -} + return super::position(units) * tick_scalar; + } return super::position(units); } -double CustomEncoder::velocity(vex::velocityUnits units) -{ - return super::velocity(units) * tick_scalar; -} +double CustomEncoder::velocity(vex::velocityUnits units) { return super::velocity(units) * tick_scalar; } diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index eab2f74..4e57acc 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -1,9 +1,9 @@ #include "../core/include/subsystems/flywheel.h" +#include "../core/include/subsystems/screen.h" #include "../core/include/utils/controls/feedforward.h" #include "../core/include/utils/controls/pid.h" -#include "../core/include/utils/math_util.h" -#include "../core/include/subsystems/screen.h" #include "../core/include/utils/graph_drawer.h" +#include "../core/include/utils/math_util.h" #include "vex.h" using namespace vex; @@ -12,9 +12,8 @@ using namespace vex; * CONSTRUCTOR, GETTERS, SETTERS *********************************************************/ -Flywheel::Flywheel(motor_group &motors, Feedback &feedback, FeedForward &helper, const double ratio, Filter &filt) : motors(motors), - task_running(false), fb(feedback), ff(helper), - ratio(ratio), avger(filt) {} +Flywheel::Flywheel(motor_group &motors, Feedback &feedback, FeedForward &helper, const double ratio, Filter &filt) + : motors(motors), task_running(false), fb(feedback), ff(helper), ratio(ratio), avger(filt) {} /** * Return the current value that the target_rpm should be set to @@ -30,32 +29,25 @@ motor_group &Flywheel::get_motors() const { return motors; } * return the current velocity of the flywheel motors, in RPM * @return the measured velocity of the flywheel */ -double Flywheel::measure_RPM() -{ +double Flywheel::measure_RPM() { double rawRPM = ratio * motors.velocity(velocityUnits::rpm); avger.add_entry(rawRPM); return avger.get_value(); } -double Flywheel::getRPM() const -{ - return avger.get_value(); -} +double Flywheel::getRPM() const { return avger.get_value(); } /** * Runs a thread that keeps track of updating flywheel RPM and controlling it accordingly */ -int spinRPMTask(void *wheelPointer) -{ +int spinRPMTask(void *wheelPointer) { Flywheel &wheel = *(Flywheel *)wheelPointer; // get the pid from the wheel and set its target to the RPM stored in the wheel. - while (true) - { + while (true) { double rpm = wheel.measure_RPM(); - if (wheel.target_rpm != 0) - { + if (wheel.target_rpm != 0) { double output = wheel.ff.calculate(wheel.target_rpm, 0.0, 0.0); { wheel.fb_mut.lock(); @@ -82,10 +74,7 @@ int spinRPMTask(void *wheelPointer) * @param speed - speed (between -1 and 1) to set the motor * @param dir - direction that the motor moves in; defaults to forward */ -void Flywheel::spin_raw(double speed, directionType dir) -{ - motors.spin(dir, speed * 12, voltageUnits::volt); -} +void Flywheel::spin_raw(double speed, directionType dir) { motors.spin(dir, speed * 12, voltageUnits::volt); } /** * Spin motors using voltage; defaults forward at 12 volts @@ -93,11 +82,10 @@ void Flywheel::spin_raw(double speed, directionType dir) * @param speed - speed (between -1 and 1) to set the motor * @param dir - direction that the motor moves in; defaults to forward */ -void Flywheel::spin_manual(double speed, directionType dir) -{ +void Flywheel::spin_manual(double speed, directionType dir) { if (!task_running) { motors.spin(dir, speed * 12, voltageUnits::volt); -} + } } /** @@ -105,24 +93,20 @@ void Flywheel::spin_manual(double speed, directionType dir) * what control scheme is dependent on control_style * @param input_rpm - set the current RPM */ -void Flywheel::spin_rpm(double input_rpm) -{ +void Flywheel::spin_rpm(double input_rpm) { // setting to 0 is equivelent to stopping - if (input_rpm == 0.0) - { + if (input_rpm == 0.0) { stop(); } // only run if the RPM is different or it isn't already running - if (!task_running) - { + if (!task_running) { rpm_task = task(spinRPMTask, this); task_running = true; } // now that its running, set the target set_target(input_rpm); } -void Flywheel::set_target(double value) -{ +void Flywheel::set_target(double value) { fb_mut.lock(); target_rpm = (value); fb.init(getRPM(), value); @@ -132,10 +116,8 @@ void Flywheel::set_target(double value) /** * stop the RPM thread and the wheel */ -void Flywheel::stop() -{ - if (task_running) - { +void Flywheel::stop() { + if (task_running) { task_running = false; rpm_task.stop(); target_rpm = 0.0; @@ -144,18 +126,18 @@ void Flywheel::stop() } //------------------------- Screen Stuff ---------------------------- -class FlywheelPage : public screen::Page -{ +class FlywheelPage : public screen::Page { public: static const size_t window_size = 40; - FlywheelPage(const Flywheel &fw) : fw(fw), gd(GraphDrawer(window_size, 0.0, 0.0, {vex::color(255, 0, 0), vex::color(0, 255, 0), vex::color(0, 0, 255)}, 3)), avg_err(window_size) {} + FlywheelPage(const Flywheel &fw) + : fw(fw), gd(GraphDrawer(window_size, 0.0, 0.0, + {vex::color(255, 0, 0), vex::color(0, 255, 0), vex::color(0, 0, 255)}, 3)), + avg_err(window_size) {} /// @brief @see Page#update void update(bool, int, int) override {} /// @brief @see Page#draw - void draw(vex::brain::lcd &screen, bool, - unsigned int) override - { + void draw(vex::brain::lcd &screen, bool, unsigned int) override { double target = fw.get_target(); double actual = fw.getRPM(); @@ -180,7 +162,4 @@ class FlywheelPage : public screen::Page MovingAverage avg_err; }; -screen::Page *Flywheel::Page() const -{ - return new FlywheelPage(*this); -} \ No newline at end of file +screen::Page *Flywheel::Page() const { return new FlywheelPage(*this); } \ No newline at end of file diff --git a/src/subsystems/mecanum_drive.cpp b/src/subsystems/mecanum_drive.cpp index 793c1b9..53b7519 100644 --- a/src/subsystems/mecanum_drive.cpp +++ b/src/subsystems/mecanum_drive.cpp @@ -1,47 +1,45 @@ #include "../core/include/subsystems/mecanum_drive.h" -#include "../core/include/utils/vector2d.h" #include "../core/include/utils/math_util.h" +#include "../core/include/utils/vector2d.h" /** -* Create the Mecanum drivetrain object -*/ -MecanumDrive::MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear, - vex::rotation *lateral_wheel, vex::inertial *imu, mecanumdrive_config_t *config) -: left_front(left_front), right_front(right_front), left_rear(left_rear), right_rear(right_rear), // MOTOR CONFIG - config(config), // CONFIG ...uh... config - lateral_wheel(lateral_wheel), // NON-DRIVEN WHEEL CONFIG - imu(imu) //IMU CONFIG + * Create the Mecanum drivetrain object + */ +MecanumDrive::MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, + vex::motor &right_rear, vex::rotation *lateral_wheel, vex::inertial *imu, + mecanumdrive_config_t *config) + : left_front(left_front), right_front(right_front), left_rear(left_rear), right_rear(right_rear), // MOTOR CONFIG + config(config), // CONFIG ...uh... config + lateral_wheel(lateral_wheel), // NON-DRIVEN WHEEL CONFIG + imu(imu) // IMU CONFIG { // If the configuration exists, then allocate memory for the drive and turn pids - if(config != NULL) - { + if (config != NULL) { drive_pid = new PID(config->drive_pid_conf); drive_gyro_pid = new PID(config->drive_gyro_pid_conf); turn_pid = new PID(config->turn_pid_conf); } - } /** - * Drive the robot using vectors. This handles all the math required for mecanum control. - * - * @param direction_deg the direction to drive the robot, in degrees. 0 is forward, - * 180 is back, clockwise is positive, counterclockwise is negative. - * @param magnitude How fast the robot should drive, in percent: 0.0->1.0 - * @param rotation How fast the robot should rotate, in percent: -1.0->+1.0 - */ -void MecanumDrive::drive_raw(double direction_deg, double magnitude, double rotation) -{ + * Drive the robot using vectors. This handles all the math required for mecanum control. + * + * @param direction_deg the direction to drive the robot, in degrees. 0 is forward, + * 180 is back, clockwise is positive, counterclockwise is negative. + * @param magnitude How fast the robot should drive, in percent: 0.0->1.0 + * @param rotation How fast the robot should rotate, in percent: -1.0->+1.0 + */ +void MecanumDrive::drive_raw(double direction_deg, double magnitude, double rotation) { double direction = deg2rad(direction_deg); - + // ALGORITHM - "rotate" the vector by 45 degrees and apply each corner to a wheel // .. Oh, and mix rotation too double lf = (magnitude * cos(direction - (PI / 4.0))) + rotation; double rf = (magnitude * cos(direction + (PI / 4.0))) - rotation; double lr = (magnitude * cos(direction + (PI / 4.0))) + rotation; double rr = (magnitude * cos(direction - (PI / 4.0))) - rotation; - + // Limit the output between -1.0 and +1.0 lf = clamp(lf, -1.0, 1.0); rf = clamp(rf, -1.0, 1.0); @@ -56,8 +54,8 @@ void MecanumDrive::drive_raw(double direction_deg, double magnitude, double rota } /** - * Drive the robot with a mecanum-style / arcade drive. Inputs are in percent (-100.0 -> 100.0) straight from the controller. - * Controls are mixed, so the robot can drive forward / strafe / rotate all at the same time. + * Drive the robot with a mecanum-style / arcade drive. Inputs are in percent (-100.0 -> 100.0) straight from the + * controller. Controls are mixed, so the robot can drive forward / strafe / rotate all at the same time. * * @param left_y left joystick, Y axis (forward / backwards) * @param left_x left joystick, X axis (strafe left / right) @@ -65,40 +63,37 @@ void MecanumDrive::drive_raw(double direction_deg, double magnitude, double rota * @param power = 2 how much of a "curve" there should be on drive controls; better for low speed maneuvers. * Leave blank for a default curve of 2 (higher means more fidelity) */ -void MecanumDrive::drive(double left_y, double left_x, double right_x, int power) -{ +void MecanumDrive::drive(double left_y, double left_x, double right_x, int power) { // LATERAL CONTROLS - convert cartesion to a vector double magnitude = sqrt(pow(left_y / 100.0, 2) + pow(left_x / 100.0, 2)); magnitude = pow(magnitude, power); - + double direction = atan2(left_x / 100.0, left_y / 100.0); // ROTATIONAL CONTROLS - just the right x joystick double rotation = right_x / 100.0; - // + // rotation = sign(rotation) * fabs(pow(rotation, power)); - - return this->drive_raw(rad2deg(direction), magnitude, rotation); + + return this->drive_raw(rad2deg(direction), magnitude, rotation); } /** - * Drive the robot in a straight line automatically. - * If the inertial was declared in the constructor, use it to correct while driving. - * If the lateral wheel was declared in the constructor, use it for more accurate positioning while strafing. - * - * @param inches How far the robot should drive, in inches - * @param direction What direction the robot should travel in, in degrees. - * 0 is forward, +/-180 is reverse, clockwise is positive. - * @param speed The maximum speed the robot should travel, in percent: -1.0->+1.0 - * @param gyro_correction = true Whether or not to use the gyro to help correct while driving. - * Will always be false if no gyro was declared in the constructor. - * @return Whether or not the maneuver is complete. - */ -bool MecanumDrive::auto_drive(double inches, double direction, double speed, bool gyro_correction) -{ - if(config == NULL || drive_pid == NULL) - { + * Drive the robot in a straight line automatically. + * If the inertial was declared in the constructor, use it to correct while driving. + * If the lateral wheel was declared in the constructor, use it for more accurate positioning while strafing. + * + * @param inches How far the robot should drive, in inches + * @param direction What direction the robot should travel in, in degrees. + * 0 is forward, +/-180 is reverse, clockwise is positive. + * @param speed The maximum speed the robot should travel, in percent: -1.0->+1.0 + * @param gyro_correction = true Whether or not to use the gyro to help correct while driving. + * Will always be false if no gyro was declared in the constructor. + * @return Whether or not the maneuver is complete. + */ +bool MecanumDrive::auto_drive(double inches, double direction, double speed, bool gyro_correction) { + if (config == NULL || drive_pid == NULL) { fprintf(stderr, "Failed to run MecanumDrive::auto_drive - Missing mecanumdrive_config_t in constructor\n"); return true; // avoid an infinte loop within auto } @@ -106,10 +101,8 @@ bool MecanumDrive::auto_drive(double inches, double direction, double speed, boo bool enable_gyro = gyro_correction && (imu != NULL); bool enable_wheel = (lateral_wheel != NULL); - // INITIALIZE - only run ONCE "per drive" on startup - if(init == true) - { + if (init == true) { // Reset all driven encoders, and PID left_front.resetPosition(); @@ -120,16 +113,15 @@ bool MecanumDrive::auto_drive(double inches, double direction, double speed, boo drive_pid->reset(); // Reset only if gyro exists - if(enable_gyro) - { + if (enable_gyro) { imu->resetRotation(); drive_gyro_pid->reset(); drive_gyro_pid->set_target(0.0); } // reset only if lateral wheel exists - if(enable_wheel) { - lateral_wheel->resetPosition(); -} + if (enable_wheel) { + lateral_wheel->resetPosition(); + } // Finish setting up the PID loop - max speed and position target drive_pid->set_limits(-fabs(speed), fabs(speed)); @@ -147,44 +139,34 @@ bool MecanumDrive::auto_drive(double inches, double direction, double speed, boo // IF in quadrant 1 or 3, use left front and right rear wheels as "drive" movement // ELSE in quadrant 2 or 4, use left rear and right front wheels as "drive" movement - // Some wheels are NOT being averaged at any given time since the general mecanum algorithm makes them go slower than our robot speed - // somewhat of a nasty hack, but wheel slippage should make up for it, and multivariable calc is hard. - if( (direction > 0 && direction <= 90) || (direction < -90 && direction > -180)) - { - drive_avg = fabs(left_front.position(rotationUnits::rev) * config->drive_wheel_diam * PI) - + fabs(right_rear.position(rotationUnits::rev) * config->drive_wheel_diam * PI) - / 2.0; - } else - { - drive_avg = fabs(left_rear.position(rotationUnits::rev) * config->drive_wheel_diam * PI) - + fabs(right_front.position(rotationUnits::rev) * config->drive_wheel_diam * PI) - / 2.0; + // Some wheels are NOT being averaged at any given time since the general mecanum algorithm makes them go slower than + // our robot speed somewhat of a nasty hack, but wheel slippage should make up for it, and multivariable calc is hard. + if ((direction > 0 && direction <= 90) || (direction < -90 && direction > -180)) { + drive_avg = fabs(left_front.position(rotationUnits::rev) * config->drive_wheel_diam * PI) + + fabs(right_rear.position(rotationUnits::rev) * config->drive_wheel_diam * PI) / 2.0; + } else { + drive_avg = fabs(left_rear.position(rotationUnits::rev) * config->drive_wheel_diam * PI) + + fabs(right_front.position(rotationUnits::rev) * config->drive_wheel_diam * PI) / 2.0; } // Only use the encoder wheel if it exists. // Without the wheel should be usable, but with it will be muuuuch more accurate. - if(enable_wheel) - { + if (enable_wheel) { // Distance driven = Magnitude = sqrt(x^2 + y^2) // Since drive_avg is already a polar magnitude, turn it into "Y" with cos(theta) - dist_avg = sqrt( - pow(lateral_wheel->position(rotationUnits::rev) * config->lateral_wheel_diam * PI, 2) - + pow(drive_avg * cos(direction * (PI / 180.0)), 2) - ); - }else - { + dist_avg = sqrt(pow(lateral_wheel->position(rotationUnits::rev) * config->lateral_wheel_diam * PI, 2) + + pow(drive_avg * cos(direction * (PI / 180.0)), 2)); + } else { dist_avg = drive_avg; } // ...double check to avoid an infinite loop dist_avg = fabs(dist_avg); - // ROTATION CORRECTION double rot = 0; - if(enable_gyro) - { + if (enable_gyro) { drive_gyro_pid->update(imu->rotation()); rot = drive_gyro_pid->get(); } @@ -195,8 +177,7 @@ bool MecanumDrive::auto_drive(double inches, double direction, double speed, boo this->drive_raw(direction, drive_pid->get(), rot); // Stop and return true whenever the robot has completed it's drive. - if(drive_pid->is_on_target()) - { + if (drive_pid->is_on_target()) { drive_raw(0, 0, 0); init = true; return true; @@ -207,20 +188,18 @@ bool MecanumDrive::auto_drive(double inches, double direction, double speed, boo } /** -* Autonomously turn the robot X degrees over it's center point. Uses a closed loop -* for control. -* @param degrees How many degrees to rotate the robot. Clockwise postive. -* @param speed What percentage to run the motors at: 0.0 -> 1.0 -* @param ignore_imu = false Whether or not to use the Inertial for determining angle. -* Will instead use circumference formula + robot's wheelbase + encoders to determine. -* -* @return whether or not the robot has finished the maneuver -*/ -bool MecanumDrive::auto_turn(double degrees, double speed, bool ignore_imu) -{ + * Autonomously turn the robot X degrees over it's center point. Uses a closed loop + * for control. + * @param degrees How many degrees to rotate the robot. Clockwise postive. + * @param speed What percentage to run the motors at: 0.0 -> 1.0 + * @param ignore_imu = false Whether or not to use the Inertial for determining angle. + * Will instead use circumference formula + robot's wheelbase + encoders to determine. + * + * @return whether or not the robot has finished the maneuver + */ +bool MecanumDrive::auto_turn(double degrees, double speed, bool ignore_imu) { // Make sure the configurations exist before continuing - if(config == NULL || turn_pid == NULL) - { + if (config == NULL || turn_pid == NULL) { fprintf(stderr, "Failed to run MecanumDrive::auto_turn - Missing mecanumdrive_config_t in constructor\n"); return true; } @@ -229,16 +208,13 @@ bool MecanumDrive::auto_turn(double degrees, double speed, bool ignore_imu) ignore_imu = ignore_imu || (this->imu == NULL); // INITIALIZE - clear encoders / imu / pid loops - if(init == true) - { - if(ignore_imu) - { + if (init == true) { + if (ignore_imu) { this->left_front.resetPosition(); this->right_front.resetPosition(); this->left_rear.resetPosition(); this->right_rear.resetPosition(); - }else - { + } else { this->imu->resetRotation(); } @@ -253,15 +229,14 @@ bool MecanumDrive::auto_turn(double degrees, double speed, bool ignore_imu) double current_angle = 0.0; - if(ignore_imu) - { - double avg = (left_front.position(rotationUnits::rev) + left_rear.position(rotationUnits::rev) - - right_front.position(rotationUnits::rev) - right_rear.position(rotationUnits::rev)) / 4.0; + if (ignore_imu) { + double avg = (left_front.position(rotationUnits::rev) + left_rear.position(rotationUnits::rev) - + right_front.position(rotationUnits::rev) - right_rear.position(rotationUnits::rev)) / + 4.0; // Current arclength = (avg * wheel_diam * PI) = (theta * (wheelbase / 2.0)). then convert to degrees current_angle = (360.0 * avg * config->drive_wheel_diam) / config->wheelbase_width; - } else - { + } else { current_angle = imu->rotation(); } @@ -269,8 +244,7 @@ bool MecanumDrive::auto_turn(double degrees, double speed, bool ignore_imu) this->drive_raw(0, 0, turn_pid->get()); // We have reached the target. - if(this->turn_pid->is_on_target()) - { + if (this->turn_pid->is_on_target()) { this->drive_raw(0, 0, 0); init = true; return true; diff --git a/src/subsystems/odometry/odometry_3wheel.cpp b/src/subsystems/odometry/odometry_3wheel.cpp index 4715559..e7cbf20 100644 --- a/src/subsystems/odometry/odometry_3wheel.cpp +++ b/src/subsystems/odometry/odometry_3wheel.cpp @@ -1,218 +1,217 @@ #include "../core/include/subsystems/odometry/odometry_3wheel.h" -#include "../core/include/utils/vector2d.h" #include "../core/include/utils/math_util.h" +#include "../core/include/utils/vector2d.h" -Odometry3Wheel::Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, odometry3wheel_cfg_t &cfg, bool is_async) -: OdometryBase(is_async), lside_fwd(lside_fwd), rside_fwd(rside_fwd), off_axis(off_axis), cfg(cfg) -{} +Odometry3Wheel::Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, + odometry3wheel_cfg_t &cfg, bool is_async) + : OdometryBase(is_async), lside_fwd(lside_fwd), rside_fwd(rside_fwd), off_axis(off_axis), cfg(cfg) {} /** * Update the current position of the robot once, using the current state of * the encoders and the previous known location - * + * * @return the robot's updated position */ -pose_t Odometry3Wheel::update() -{ - static double lside_old=0, rside_old=0, offax_old=0; - - double lside = lside_fwd.position(deg); - double rside = rside_fwd.position(deg); - double offax = off_axis.position(deg); - - double lside_delta = lside - lside_old; - double rside_delta = rside - rside_old; - double offax_delta = offax - offax_old; - - lside_old = lside; - rside_old = rside; - offax_old = offax; - - pose_t updated_pos = calculate_new_pos(lside_delta, rside_delta, offax_delta, current_pos, cfg); - - static pose_t last_pos = updated_pos; - static double last_speed = 0; - static double last_ang_speed = 0; - static timer tmr; - - double speed_local = 0; - double accel_local = 0; - double ang_speed_local = 0; - double ang_accel_local = 0; - bool update_vel_accel = tmr.time(sec) > 0.1; - - // This loop runs too fast. Only check at LEAST every 1/10th sec - if(update_vel_accel) - { - // Calculate robot velocity - speed_local = pos_diff(updated_pos, last_pos) / tmr.time(sec); - - // Calculate robot acceleration - accel_local = (speed_local - last_speed) / tmr.time(sec); - - // Calculate robot angular velocity (deg/sec) - ang_speed_local = smallest_angle(updated_pos.rot, last_pos.rot) / tmr.time(sec); - - // Calculate robot angular acceleration (deg/sec^2) - ang_accel_local = (ang_speed_local - last_ang_speed) / tmr.time(sec); - - tmr.reset(); - last_pos = updated_pos; - last_speed = speed_local; - last_ang_speed = ang_speed_local; - } - - this->current_pos = updated_pos; - if(update_vel_accel) - { - this->speed = speed_local; - this->accel = accel_local; - this->ang_speed_deg = ang_speed_local; - this->ang_accel_deg = ang_accel_local; - } - - return current_pos; +pose_t Odometry3Wheel::update() { + static double lside_old = 0, rside_old = 0, offax_old = 0; + + double lside = lside_fwd.position(deg); + double rside = rside_fwd.position(deg); + double offax = off_axis.position(deg); + + double lside_delta = lside - lside_old; + double rside_delta = rside - rside_old; + double offax_delta = offax - offax_old; + + lside_old = lside; + rside_old = rside; + offax_old = offax; + + pose_t updated_pos = calculate_new_pos(lside_delta, rside_delta, offax_delta, current_pos, cfg); + + static pose_t last_pos = updated_pos; + static double last_speed = 0; + static double last_ang_speed = 0; + static timer tmr; + + double speed_local = 0; + double accel_local = 0; + double ang_speed_local = 0; + double ang_accel_local = 0; + bool update_vel_accel = tmr.time(sec) > 0.1; + + // This loop runs too fast. Only check at LEAST every 1/10th sec + if (update_vel_accel) { + // Calculate robot velocity + speed_local = pos_diff(updated_pos, last_pos) / tmr.time(sec); + + // Calculate robot acceleration + accel_local = (speed_local - last_speed) / tmr.time(sec); + + // Calculate robot angular velocity (deg/sec) + ang_speed_local = smallest_angle(updated_pos.rot, last_pos.rot) / tmr.time(sec); + + // Calculate robot angular acceleration (deg/sec^2) + ang_accel_local = (ang_speed_local - last_ang_speed) / tmr.time(sec); + + tmr.reset(); + last_pos = updated_pos; + last_speed = speed_local; + last_ang_speed = ang_speed_local; + } + + this->current_pos = updated_pos; + if (update_vel_accel) { + this->speed = speed_local; + this->accel = accel_local; + this->ang_speed_deg = ang_speed_local; + this->ang_accel_deg = ang_accel_local; + } + + return current_pos; } /** - * Calculation method for the robot's new position using the change in encoders, the old position, and the robot's configuration. - * This uses a series of arclength formulae for finding distance driven and change in angle. - * Then vector math is used to combine it with the robot's old position data - * + * Calculation method for the robot's new position using the change in encoders, the old position, and the robot's + * configuration. This uses a series of arclength formulae for finding distance driven and change in angle. Then vector + * math is used to combine it with the robot's old position data + * * @param lside_delta_deg Left encoder change in rotation, in degrees * @param rside_delta_deg Right encoder change in rotation, in degrees * @param offax_delta_deg Off-axis (perpendicular) encoder change in rotation, in degrees * @param old_pos Robot's old position, for integration * @param cfg Data on robot's configuration (wheel diameter, wheelbase, off-axis distance from center) - * @return The robot's new position (x, y, rot) + * @return The robot's new position (x, y, rot) */ -pose_t Odometry3Wheel::calculate_new_pos(double lside_delta_deg, double rside_delta_deg, double offax_delta_deg, pose_t old_pos, odometry3wheel_cfg_t cfg) -{ - pose_t retval = {}; - - // Arclength formula for encoder degrees -> single wheel distance driven - double lside_dist = (cfg.wheel_diam / 2.0) * deg2rad(lside_delta_deg); - double rside_dist = (cfg.wheel_diam / 2.0) * deg2rad(rside_delta_deg); - double offax_dist = (cfg.wheel_diam / 2.0) * deg2rad(offax_delta_deg); - - // Inverse arclength formula for arc distance driven -> robot angle - double delta_angle_rad = (rside_dist - lside_dist) / cfg.wheelbase_dist; - double delta_angle_deg = rad2deg(delta_angle_rad); - - // Distance along the robot's local Y axis (forward/backward) - double dist_local_y = (lside_dist + rside_dist) / 2.0; - - // Distance along the robot's local X axis (right/left) - double dist_local_x = offax_dist - (delta_angle_rad * cfg.off_axis_center_dist); - - // Change in displacement as a vector, on the local coordinate system (+y = robot fwd) - Vector2D local_displacement({.x=dist_local_x, .y=dist_local_y}); - - // Rotate the local displacement to match the old robot's rotation - double dir_delta_from_trans_rad = local_displacement.get_dir() - (PI/2.0); - double global_dir_rad = wrap_angle_rad(dir_delta_from_trans_rad + deg2rad(old_pos.rot)); - Vector2D global_displacement(global_dir_rad, local_displacement.get_mag()); - - // Tack on the position change to the old position - Vector2D old_pos_vec({.x=old_pos.x, .y=old_pos.y}); - Vector2D new_pos_vec = old_pos_vec + global_displacement; - - retval.x = new_pos_vec.get_x(); - retval.y = new_pos_vec.get_y(); - retval.rot = wrap_angle_deg(old_pos.rot + delta_angle_deg); - - return retval; +pose_t Odometry3Wheel::calculate_new_pos(double lside_delta_deg, double rside_delta_deg, double offax_delta_deg, + pose_t old_pos, odometry3wheel_cfg_t cfg) { + pose_t retval = {}; + + // Arclength formula for encoder degrees -> single wheel distance driven + double lside_dist = (cfg.wheel_diam / 2.0) * deg2rad(lside_delta_deg); + double rside_dist = (cfg.wheel_diam / 2.0) * deg2rad(rside_delta_deg); + double offax_dist = (cfg.wheel_diam / 2.0) * deg2rad(offax_delta_deg); + + // Inverse arclength formula for arc distance driven -> robot angle + double delta_angle_rad = (rside_dist - lside_dist) / cfg.wheelbase_dist; + double delta_angle_deg = rad2deg(delta_angle_rad); + + // Distance along the robot's local Y axis (forward/backward) + double dist_local_y = (lside_dist + rside_dist) / 2.0; + + // Distance along the robot's local X axis (right/left) + double dist_local_x = offax_dist - (delta_angle_rad * cfg.off_axis_center_dist); + + // Change in displacement as a vector, on the local coordinate system (+y = robot fwd) + Vector2D local_displacement({.x = dist_local_x, .y = dist_local_y}); + + // Rotate the local displacement to match the old robot's rotation + double dir_delta_from_trans_rad = local_displacement.get_dir() - (PI / 2.0); + double global_dir_rad = wrap_angle_rad(dir_delta_from_trans_rad + deg2rad(old_pos.rot)); + Vector2D global_displacement(global_dir_rad, local_displacement.get_mag()); + + // Tack on the position change to the old position + Vector2D old_pos_vec({.x = old_pos.x, .y = old_pos.y}); + Vector2D new_pos_vec = old_pos_vec + global_displacement; + + retval.x = new_pos_vec.get_x(); + retval.y = new_pos_vec.get_y(); + retval.rot = wrap_angle_deg(old_pos.rot + delta_angle_deg); + + return retval; } /** * A guided tuning process to automatically find tuning parameters. * This method is blocking, and returns when tuning has finished. Follow * the instructions on the controller to complete the tuning process - * + * * It is assumed the gear ratio and encoder PPR have been set correctly - * + * */ -void Odometry3Wheel::tune(vex::controller &con, TankDrive &drive) -{ - - // TODO check if all the messages fit on the controller screen - // STEP 1: Align robot and reset odometry - con.Screen.clearScreen(); - con.Screen.setCursor(1,1); - con.Screen.print("Wheel Diameter Test"); - con.Screen.newLine(); - con.Screen.print("Align robot with ref"); - con.Screen.newLine(); - con.Screen.newLine(); - con.Screen.print("Press A to continue"); - while(!con.ButtonA.pressing()) { vexDelay(20); } - - double old_lval = lside_fwd.position(deg); - double old_rval = rside_fwd.position(deg); - - // Step 2: Drive robot a known distance - con.Screen.clearLine(2); - con.Screen.setCursor(2,1); - con.Screen.print("Drive or Push robot"); - con.Screen.newLine(); - con.Screen.print("10 feet (5 tiles)"); - con.Screen.newLine(); - con.Screen.print("Press A to continue"); - while(!con.ButtonA.pressing()) - { - drive.drive_arcade(con.Axis3.position() / 100.0, con.Axis1.position() / 100.0); - vexDelay(20); - } - - // Wheel diameter is ratio of expected distance / measured distance - double avg_deg = ((lside_fwd.position(deg) - old_lval) + (rside_fwd.position(deg) - old_rval)) / 2.0; - double measured_dist = 0.5 * deg2rad(avg_deg); // Simulate diam=1", radius=1/2" - double found_diam = 120.0 / measured_dist; - - // Step 3: Reset alignment for turning test - con.Screen.clearScreen(); - con.Screen.setCursor(1,1); - con.Screen.print("Wheelbase Test"); - con.Screen.newLine(); - con.Screen.print("Align robot with ref"); - con.Screen.newLine(); - con.Screen.newLine(); - con.Screen.print("Press A to continue"); - while(!con.ButtonA.pressing()) { vexDelay(20); } - con.Screen.clearScreen(); - - old_lval = lside_fwd.position(deg); - old_rval = rside_fwd.position(deg); - double old_offax = off_axis.position(deg); - - con.Screen.setCursor(2,1); - con.Screen.clearLine(); - con.Screen.print("Turn robot 10"); - con.Screen.newLine(); - con.Screen.print("times in place"); - con.Screen.newLine(); - con.Screen.print("Press A to continue"); - while(!con.ButtonA.pressing()) - { - drive.drive_arcade(0, con.Axis1.position() / 100.0); - vexDelay(20); - } - - double lside_dist = deg2rad(lside_fwd.position(deg) - old_lval) * (found_diam / 2.0); - double rside_dist = deg2rad(rside_fwd.position(deg) - old_rval) * (found_diam / 2.0); - double offax_dist = deg2rad(off_axis.position(deg) - old_offax) * (found_diam / 2.0); - - double expected_angle = 10 * (2*PI); - double found_wheelbase = fabs(rside_dist - lside_dist) / expected_angle; - double found_offax_center_dist = offax_dist / expected_angle; - - con.Screen.clearScreen(); - con.Screen.setCursor(1,1); - con.Screen.print("Diam: %f", found_diam); - con.Screen.newLine(); - con.Screen.print("whlbase: %f", found_wheelbase); - con.Screen.newLine(); - con.Screen.print("offax: %f", found_offax_center_dist); - - printf("Tuning completed.\n Wheel Diameter: %f\n Wheelbase: %f\n Off Axis Distance: %f\n", found_diam, found_wheelbase, found_offax_center_dist); +void Odometry3Wheel::tune(vex::controller &con, TankDrive &drive) { + + // TODO check if all the messages fit on the controller screen + // STEP 1: Align robot and reset odometry + con.Screen.clearScreen(); + con.Screen.setCursor(1, 1); + con.Screen.print("Wheel Diameter Test"); + con.Screen.newLine(); + con.Screen.print("Align robot with ref"); + con.Screen.newLine(); + con.Screen.newLine(); + con.Screen.print("Press A to continue"); + while (!con.ButtonA.pressing()) { + vexDelay(20); + } + + double old_lval = lside_fwd.position(deg); + double old_rval = rside_fwd.position(deg); + + // Step 2: Drive robot a known distance + con.Screen.clearLine(2); + con.Screen.setCursor(2, 1); + con.Screen.print("Drive or Push robot"); + con.Screen.newLine(); + con.Screen.print("10 feet (5 tiles)"); + con.Screen.newLine(); + con.Screen.print("Press A to continue"); + while (!con.ButtonA.pressing()) { + drive.drive_arcade(con.Axis3.position() / 100.0, con.Axis1.position() / 100.0); + vexDelay(20); + } + + // Wheel diameter is ratio of expected distance / measured distance + double avg_deg = ((lside_fwd.position(deg) - old_lval) + (rside_fwd.position(deg) - old_rval)) / 2.0; + double measured_dist = 0.5 * deg2rad(avg_deg); // Simulate diam=1", radius=1/2" + double found_diam = 120.0 / measured_dist; + + // Step 3: Reset alignment for turning test + con.Screen.clearScreen(); + con.Screen.setCursor(1, 1); + con.Screen.print("Wheelbase Test"); + con.Screen.newLine(); + con.Screen.print("Align robot with ref"); + con.Screen.newLine(); + con.Screen.newLine(); + con.Screen.print("Press A to continue"); + while (!con.ButtonA.pressing()) { + vexDelay(20); + } + con.Screen.clearScreen(); + + old_lval = lside_fwd.position(deg); + old_rval = rside_fwd.position(deg); + double old_offax = off_axis.position(deg); + + con.Screen.setCursor(2, 1); + con.Screen.clearLine(); + con.Screen.print("Turn robot 10"); + con.Screen.newLine(); + con.Screen.print("times in place"); + con.Screen.newLine(); + con.Screen.print("Press A to continue"); + while (!con.ButtonA.pressing()) { + drive.drive_arcade(0, con.Axis1.position() / 100.0); + vexDelay(20); + } + + double lside_dist = deg2rad(lside_fwd.position(deg) - old_lval) * (found_diam / 2.0); + double rside_dist = deg2rad(rside_fwd.position(deg) - old_rval) * (found_diam / 2.0); + double offax_dist = deg2rad(off_axis.position(deg) - old_offax) * (found_diam / 2.0); + + double expected_angle = 10 * (2 * PI); + double found_wheelbase = fabs(rside_dist - lside_dist) / expected_angle; + double found_offax_center_dist = offax_dist / expected_angle; + + con.Screen.clearScreen(); + con.Screen.setCursor(1, 1); + con.Screen.print("Diam: %f", found_diam); + con.Screen.newLine(); + con.Screen.print("whlbase: %f", found_wheelbase); + con.Screen.newLine(); + con.Screen.print("offax: %f", found_offax_center_dist); + + printf("Tuning completed.\n Wheel Diameter: %f\n Wheelbase: %f\n Off Axis Distance: %f\n", found_diam, + found_wheelbase, found_offax_center_dist); } \ No newline at end of file diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index 15981ae..9b4d7eb 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -6,8 +6,7 @@ * * @param is_async True to run constantly in the background, false to call update() manually */ -OdometryBase::OdometryBase(bool is_async) : current_pos(zero_pos) -{ +OdometryBase::OdometryBase(bool is_async) : current_pos(zero_pos) { if (is_async) { handle = new vex::task(background_task, (void *)this); } @@ -20,12 +19,10 @@ OdometryBase::OdometryBase(bool is_async) : current_pos(zero_pos) * @param ptr Pointer to OdometryBase object * @return Required integer return code. Unused. */ -int OdometryBase::background_task(void *ptr) -{ +int OdometryBase::background_task(void *ptr) { OdometryBase &obj = *((OdometryBase *)ptr); vexDelay(1000); - while (!obj.end_task) - { + while (!obj.end_task) { obj.mut.lock(); obj.update(); obj.mut.unlock(); @@ -39,16 +36,12 @@ int OdometryBase::background_task(void *ptr) * If the user wants to end the thread but keep the data up to date, * they must run the update() function manually from then on. */ -void OdometryBase::end_async() -{ - this->end_task = true; -} +void OdometryBase::end_async() { this->end_task = true; } /** * Gets the current position and rotation */ -pose_t OdometryBase::get_position(void) -{ +pose_t OdometryBase::get_position(void) { mut.lock(); // Create a new struct to pass-by-value @@ -62,8 +55,7 @@ pose_t OdometryBase::get_position(void) /** * Sets the current position of the robot */ -void OdometryBase::set_position(const pose_t &newpos) -{ +void OdometryBase::set_position(const pose_t &newpos) { mut.lock(); current_pos = newpos; @@ -71,10 +63,11 @@ void OdometryBase::set_position(const pose_t &newpos) mut.unlock(); } -AutoCommand *OdometryBase::SetPositionCmd(const pose_t &newpos) -{ - return new FunctionCommand([&](){set_position(newpos); return true;}); - +AutoCommand *OdometryBase::SetPositionCmd(const pose_t &newpos) { + return new FunctionCommand([&]() { + set_position(newpos); + return true; + }); } /** @@ -83,8 +76,7 @@ AutoCommand *OdometryBase::SetPositionCmd(const pose_t &newpos) * @param end_pos to this point * @return the euclidean distance between start_pos and end_pos */ -double OdometryBase::pos_diff(pose_t start_pos, pose_t end_pos) -{ +double OdometryBase::pos_diff(pose_t start_pos, pose_t end_pos) { // Use the pythagorean theorem double retval = sqrt(pow(end_pos.x - start_pos.x, 2) + pow(end_pos.y - start_pos.y, 2)); @@ -94,35 +86,30 @@ double OdometryBase::pos_diff(pose_t start_pos, pose_t end_pos) /** * Get the change in rotation between two points */ -double OdometryBase::rot_diff(pose_t pos1, pose_t pos2) -{ - return pos1.rot - pos2.rot; -} +double OdometryBase::rot_diff(pose_t pos1, pose_t pos2) { return pos1.rot - pos2.rot; } /** * Get the smallest difference in angle between a start heading and end heading. * Returns the difference between -180 degrees and +180 degrees, representing the robot * turning left or right, respectively. */ -double OdometryBase::smallest_angle(double start_deg, double end_deg) -{ +double OdometryBase::smallest_angle(double start_deg, double end_deg) { double retval; // get the difference between 0 and 360 retval = fmod(end_deg - start_deg, 360.0); if (retval < 0) { retval += 360.0; -} + } // Get the closest angle, now between -180 (turn left) and +180 (turn right) if (retval > 180) { retval -= 360; -} + } return retval; } -double OdometryBase::get_speed() -{ +double OdometryBase::get_speed() { mut.lock(); double retval = speed; mut.unlock(); @@ -130,8 +117,7 @@ double OdometryBase::get_speed() return retval; } -double OdometryBase::get_accel() -{ +double OdometryBase::get_accel() { mut.lock(); double retval = accel; mut.unlock(); @@ -139,8 +125,7 @@ double OdometryBase::get_accel() return retval; } -double OdometryBase::get_angular_speed_deg() -{ +double OdometryBase::get_angular_speed_deg() { mut.lock(); double retval = ang_speed_deg; mut.unlock(); @@ -148,8 +133,7 @@ double OdometryBase::get_angular_speed_deg() return retval; } -double OdometryBase::get_angular_accel_deg() -{ +double OdometryBase::get_angular_accel_deg() { mut.lock(); double retval = ang_accel_deg; mut.unlock(); diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index b910cff..b0a397d 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -4,47 +4,52 @@ * Initialize the Odometry module, calculating position from the drive motors. * @param left_side The left motors * @param right_side The right motors - * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what + * is contained * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. - * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have + * to manually call update(). */ -OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu, bool is_async) - : OdometryBase(is_async), left_side(&left_side), right_side(&right_side), left_custom_enc(NULL), right_custom_enc(NULL), left_vex_enc(NULL), right_vex_enc(NULL), imu(imu), config(config) -{ -} +OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, + vex::inertial *imu, bool is_async) + : OdometryBase(is_async), left_side(&left_side), right_side(&right_side), left_custom_enc(NULL), + right_custom_enc(NULL), left_vex_enc(NULL), right_vex_enc(NULL), imu(imu), config(config) {} /** * Initialize the Odometry module, calculating position from the drive motors. * @param left_custom_enc The left custom encoder * @param right_custom_enc The right custom encoder - * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what + * is contained * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. - * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have + * to manually call update(). */ -OdometryTank::OdometryTank(CustomEncoder &left_custom_enc, CustomEncoder &right_custom_enc, robot_specs_t &config, vex::inertial *imu, bool is_async) - : OdometryBase(is_async), left_side(NULL), right_side(NULL), left_custom_enc(&left_custom_enc), right_custom_enc(&right_custom_enc), left_vex_enc(NULL), right_vex_enc(NULL), imu(imu), config(config) -{ -} +OdometryTank::OdometryTank(CustomEncoder &left_custom_enc, CustomEncoder &right_custom_enc, robot_specs_t &config, + vex::inertial *imu, bool is_async) + : OdometryBase(is_async), left_side(NULL), right_side(NULL), left_custom_enc(&left_custom_enc), + right_custom_enc(&right_custom_enc), left_vex_enc(NULL), right_vex_enc(NULL), imu(imu), config(config) {} /** * Initialize the Odometry module, calculating position from the drive motors. * @param left_vex_enc The left vex encoder * @param right_vex_enc The right vex encoder - * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what + * is contained * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. - * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have + * to manually call update(). */ -OdometryTank::OdometryTank(vex::encoder &left_vex_enc, vex::encoder &right_vex_enc, robot_specs_t &config, vex::inertial *imu, bool is_async) - : OdometryBase(is_async), left_side(NULL), right_side(NULL), left_custom_enc(NULL), right_custom_enc(NULL), left_vex_enc(&left_vex_enc), right_vex_enc(&right_vex_enc), imu(imu), config(config) -{ -} +OdometryTank::OdometryTank(vex::encoder &left_vex_enc, vex::encoder &right_vex_enc, robot_specs_t &config, + vex::inertial *imu, bool is_async) + : OdometryBase(is_async), left_side(NULL), right_side(NULL), left_custom_enc(NULL), right_custom_enc(NULL), + left_vex_enc(&left_vex_enc), right_vex_enc(&right_vex_enc), imu(imu), config(config) {} /** * Resets the position and rotational data to the input. * */ -void OdometryTank::set_position(const pose_t &newpos) -{ +void OdometryTank::set_position(const pose_t &newpos) { mut.lock(); rotation_offset = newpos.rot - (current_pos.rot - rotation_offset); mut.unlock(); @@ -56,22 +61,16 @@ void OdometryTank::set_position(const pose_t &newpos) * Update, store and return the current position of the robot. Only use if not initializing * with a separate thread. */ -pose_t OdometryTank::update() -{ +pose_t OdometryTank::update() { double lside_revs = 0, rside_revs = 0; - if (left_side != NULL && right_side != NULL) - { + if (left_side != NULL && right_side != NULL) { lside_revs = left_side->position(vex::rotationUnits::rev) / config.odom_gear_ratio; rside_revs = right_side->position(vex::rotationUnits::rev) / config.odom_gear_ratio; - } - else if (left_custom_enc != NULL && right_custom_enc != NULL) - { + } else if (left_custom_enc != NULL && right_custom_enc != NULL) { lside_revs = left_custom_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; rside_revs = right_custom_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; - } - else if (left_vex_enc != NULL && right_vex_enc != NULL) - { + } else if (left_vex_enc != NULL && right_vex_enc != NULL) { lside_revs = left_vex_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; rside_revs = right_vex_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; } @@ -79,8 +78,7 @@ pose_t OdometryTank::update() double angle = 0; // If the IMU data was passed in, use it for rotational data - if (imu == NULL || imu->installed() == false) - { + if (imu == NULL || imu->installed() == false) { // Get the difference in distance driven between the two sides // Uses the absolute position of the encoders, so resetting them will result in // a bad angle. @@ -91,9 +89,7 @@ pose_t OdometryTank::update() angle = ((180.0 / PI) * (distance_diff / config.dist_between_wheels)) + 90; // printf("angle: %f, ", (180.0 / PI) * (distance_diff / config.dist_between_wheels)); - } - else - { + } else { // Translate "0 forward and clockwise positive" to "90 forward and CCW negative" angle = -imu->rotation(vex::rotationUnits::deg) + 90; } @@ -106,7 +102,7 @@ pose_t OdometryTank::update() angle = fmod(angle, 360.0); if (angle < 0) { angle += 360; -} + } current_pos = calculate_new_pos(config, current_pos, lside_revs, rside_revs, angle); @@ -117,8 +113,7 @@ pose_t OdometryTank::update() bool update_vel_accel = tmr.time(sec) > 0.02; // This loop runs too fast. Only check at LEAST every 1/10th sec - if (update_vel_accel) - { + if (update_vel_accel) { // Calculate robot velocity double this_speed = pos_diff(current_pos, last_pos) / tmr.time(sec); ema.add_entry(this_speed); @@ -145,8 +140,8 @@ pose_t OdometryTank::update() * Using information about the robot's mechanical structure and sensors, calculate a new position * of the robot, relative to when this method was previously ran. */ -pose_t OdometryTank::calculate_new_pos(robot_specs_t &config, pose_t &curr_pos, double lside_revs, double rside_revs, double angle_deg) -{ +pose_t OdometryTank::calculate_new_pos(robot_specs_t &config, pose_t &curr_pos, double lside_revs, double rside_revs, + double angle_deg) { pose_t new_pos; static double stored_lside_revs = lside_revs; diff --git a/src/subsystems/screen.cpp b/src/subsystems/screen.cpp index 6518bd0..71b13d4 100644 --- a/src/subsystems/screen.cpp +++ b/src/subsystems/screen.cpp @@ -30,8 +30,7 @@ void draw_widget(vex::brain::lcd &scr, WidgetConfig &widget, ScreenRect rect) { * you probably shouldnt have to use it */ struct ScreenData { - ScreenData(const std::vector &m_pages, int m_page, - vex::brain::lcd &m_screen) + ScreenData(const std::vector &m_pages, int m_page, vex::brain::lcd &m_screen) : pages(m_pages), page(m_page), screen(m_screen) {} std::vector pages; int page = 0; @@ -50,8 +49,7 @@ static ScreenData *screen_data_ptr; /// @param screen the brain screen /// @param pages the list of pages in your UI slideshow /// @param first_page the page to start on (by default 0) -void start_screen(vex::brain::lcd &screen, std::vector pages, - int first_page) { +void start_screen(vex::brain::lcd &screen, std::vector pages, int first_page) { if (pages.size() == 0) { printf("No pages, not starting screen"); return; @@ -65,8 +63,7 @@ void start_screen(vex::brain::lcd &screen, std::vector pages, ScreenData *data = new ScreenData{pages, first_page, screen}; - screen_thread = - new vex::thread(screen_thread_func, static_cast(data)); + screen_thread = new vex::thread(screen_thread_func, static_cast(data)); } void stop_screen() { running = false; } @@ -162,28 +159,22 @@ int screen_thread_func(void *screen_data_v) { * @param update_f drawing function * @param draw_f drawing function */ -FunctionPage::FunctionPage(update_func_t update_f, draw_func_t draw_f) - : update_f(update_f), draw_f(draw_f) {} +FunctionPage::FunctionPage(update_func_t update_f, draw_func_t draw_f) : update_f(update_f), draw_f(draw_f) {} /// @brief update uses the supplied update function to update this page -void FunctionPage::update(bool was_pressed, int x, int y) { - update_f(was_pressed, x, y); -} +void FunctionPage::update(bool was_pressed, int x, int y) { update_f(was_pressed, x, y); } /// @brief draw uses the supplied draw function to draw to the screen -void FunctionPage::draw(vex::brain::lcd &screen, bool first_draw, - unsigned int frame_number) { +void FunctionPage::draw(vex::brain::lcd &screen, bool first_draw, unsigned int frame_number) { draw_f(screen, first_draw, frame_number); } -StatsPage::StatsPage(std::map motors) - : motors(motors) {} +StatsPage::StatsPage(std::map motors) : motors(motors) {} void StatsPage::update(bool was_pressed, int x, int y) { (void)x; (void)y; (void)was_pressed; } -void StatsPage::draw_motor_stats(const std::string &name, vex::motor &mot, - unsigned int frame, int x, int y, +void StatsPage::draw_motor_stats(const std::string &name, vex::motor &mot, unsigned int frame, int x, int y, vex::brain::lcd &scr) { const vex::color hot_col = vex::color(120, 0, 0); const vex::color med_col = vex::color(140, 100, 0); @@ -207,8 +198,7 @@ void StatsPage::draw_motor_stats(const std::string &name, vex::motor &mot, } scr.drawRectangle(x, y, row_width, row_height, col); - scr.printAt(x + 2, y + 16, false, " %2d %2.0fC %.7s", port, temp, - name.c_str()); + scr.printAt(x + 2, y + 16, false, " %2d %2.0fC %.7s", port, temp, name.c_str()); } void StatsPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], unsigned int frame_number [[maybe_unused]]) { @@ -235,12 +225,10 @@ void StatsPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], } vex::brain b; scr.printAt(50, 220, "Battery: %2.1fv %2.0fC %d%%", b.Battery.voltage(), - b.Battery.temperature(vex::temperatureUnits::celsius), - b.Battery.capacity()); + b.Battery.temperature(vex::temperatureUnits::celsius), b.Battery.capacity()); } -OdometryPage::OdometryPage(OdometryBase &odom, double width, double height, - bool do_trail) +OdometryPage::OdometryPage(OdometryBase &odom, double width, double height, bool do_trail) : odom(odom), robot_width(width), robot_height(height), do_trail(do_trail), velocity_graph(30, 0.0, 0.0, {vex::green}, 1) { vex::brain b; @@ -270,13 +258,10 @@ void OdometryPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], path_index %= path_len; } - auto to_px = [](const point_t p) -> point_t { - return {(double)in_to_px(p.x) + 200, (double)in_to_px(-p.y) + 240}; - }; + auto to_px = [](const point_t p) -> point_t { return {(double)in_to_px(p.x) + 200, (double)in_to_px(-p.y) + 240}; }; auto draw_line = [to_px, &scr](const point_t from, const point_t to) { - scr.drawLine((int)to_px(from).x, (int)to_px(from).y, (int)to_px(to).x, - (int)to_px(to).y); + scr.drawLine((int)to_px(from).x, (int)to_px(from).y, (int)to_px(to).x, (int)to_px(to).y); }; point_t pos = pose.get_point(); @@ -341,8 +326,7 @@ bool SliderWidget::update(bool was_pressed, int x, int y) { double dx = x; double dy = y; if (rect.contains(point_t{dx, dy})) { - double pct = - (dx - rect.min.x - margin) / (rect.dimensions().x - 2 * margin); + double pct = (dx - rect.min.x - margin) / (rect.dimensions().x - 2 * margin); pct = clamp(pct, 0.0, 1.0); value = (low + pct * (high - low)); } @@ -365,8 +349,7 @@ void SliderWidget::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], scr.setFillColor(vex::color(50, 50, 50)); scr.setPenWidth(1); - scr.drawRectangle(rect.min.x, rect.min.y, rect.dimensions().x, - rect.dimensions().y); + scr.drawRectangle(rect.min.x, rect.min.y, rect.dimensions().x, rect.dimensions().y); scr.setPenColor(vex::color(200, 200, 200)); scr.setPenWidth(4); @@ -378,16 +361,13 @@ void SliderWidget::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], const double handle_width = 4; const double handle_height = 4; - scr.drawRectangle(vx - (handle_width / 2), y - (handle_height / 2), - handle_width, handle_height); + scr.drawRectangle(vx - (handle_width / 2), y - (handle_height / 2), handle_width, handle_height); int text_w = scr.getStringWidth((name + " ").c_str()); - scr.printAt(xmid - text_w / 2, y - 15, false, "%s: %.5f", name.c_str(), - value); + scr.printAt(xmid - text_w / 2, y - 15, false, "%s: %.5f", name.c_str(), value); } bool ButtonWidget::update(bool was_pressed, int x, int y) { - if (was_pressed && !was_pressed_last && - rect.contains({(double)x, (double)y})) { + if (was_pressed && !was_pressed_last && rect.contains({(double)x, (double)y})) { onpress(); was_pressed_last = was_pressed; return true; @@ -413,11 +393,9 @@ PIDPage::PIDPage(PID &pid, std::string name, std::function onchange) i_slider(cfg.i, 0.0, 0.05, Rect{{60, 80}, {180, 120}}, "I"), d_slider(cfg.d, 0.0, 0.05, Rect{{60, 140}, {180, 180}}, "D"), zero_i([this]() { zero_i_f(); }, Rect{{180, 80}, {220, 120}}, "0"), - zero_d([this]() { zero_d_f(); }, Rect{{180, 140}, {220, 180}}, "0"), - graph(40, 0, 0, {vex::red, vex::green}, 2) {} + zero_d([this]() { zero_d_f(); }, Rect{{180, 140}, {220, 180}}, "0"), graph(40, 0, 0, {vex::red, vex::green}, 2) {} -PIDPage::PIDPage(PIDFF &pidff, std::string name, - std::function onchange) +PIDPage::PIDPage(PIDFF &pidff, std::string name, std::function onchange) : PIDPage((pidff.pid), name, onchange) {} void PIDPage::update(bool was_pressed, int x, int y) { @@ -432,8 +410,7 @@ void PIDPage::update(bool was_pressed, int x, int y) { onchange(); } } -void PIDPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], - unsigned int frame_number [[maybe_unused]]) { +void PIDPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], unsigned int frame_number [[maybe_unused]]) { p_slider.draw(scr, first_draw, frame_number); i_slider.draw(scr, first_draw, frame_number); d_slider.draw(scr, first_draw, frame_number); diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index b665687..2843656 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -1,81 +1,69 @@ -#include "../core/include/utils/geometry.h" #include "../core/include/subsystems/tank_drive.h" -#include "../core/include/utils/math_util.h" -#include "../core/include/utils/controls/pidff.h" #include "../core/include/utils/command_structure/drive_commands.h" +#include "../core/include/utils/controls/pidff.h" +#include "../core/include/utils/geometry.h" +#include "../core/include/utils/math_util.h" TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom) - : left_motors(left_motors), right_motors(right_motors), correction_pid(config.correction_pid), odometry(odom), config(config) -{ + : left_motors(left_motors), right_motors(right_motors), correction_pid(config.correction_pid), odometry(odom), + config(config) { drive_default_feedback = config.drive_feedback; turn_default_feedback = config.turn_feedback; } -AutoCommand *TankDrive::DriveToPointCmd(Feedback &fb, point_t pt, vex::directionType dir, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::DriveToPointCmd(Feedback &fb, point_t pt, vex::directionType dir, double max_speed, + double end_speed) { return new DriveToPointCommand(*this, fb, pt, dir, max_speed, end_speed); } -AutoCommand *TankDrive::DriveToPointCmd(point_t pt, vex::directionType dir, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::DriveToPointCmd(point_t pt, vex::directionType dir, double max_speed, double end_speed) { return new DriveToPointCommand(*this, *drive_default_feedback, pt, dir, max_speed, end_speed); } -AutoCommand *TankDrive::DriveForwardCmd(double dist, vex::directionType dir, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::DriveForwardCmd(double dist, vex::directionType dir, double max_speed, double end_speed) { return new DriveForwardCommand(*this, *drive_default_feedback, dist, dir, max_speed, end_speed); } -AutoCommand *TankDrive::DriveForwardCmd(Feedback &fb, double dist, vex::directionType dir, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::DriveForwardCmd(Feedback &fb, double dist, vex::directionType dir, double max_speed, + double end_speed) { return new DriveForwardCommand(*this, fb, dist, dir, max_speed, end_speed); } -AutoCommand *TankDrive::TurnToHeadingCmd(double heading, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::TurnToHeadingCmd(double heading, double max_speed, double end_speed) { return new TurnToHeadingCommand(*this, *turn_default_feedback, heading, max_speed, end_speed); } -AutoCommand *TankDrive::TurnToHeadingCmd(Feedback &fb, double heading, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::TurnToHeadingCmd(Feedback &fb, double heading, double max_speed, double end_speed) { return new TurnToHeadingCommand(*this, fb, heading, max_speed, end_speed); } -AutoCommand *TankDrive::TurnDegreesCmd(double degrees, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::TurnDegreesCmd(double degrees, double max_speed, double end_speed) { return new TurnDegreesCommand(*this, *turn_default_feedback, degrees, max_speed, end_speed); } -AutoCommand *TankDrive::TurnDegreesCmd(Feedback &fb, double degrees, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::TurnDegreesCmd(Feedback &fb, double degrees, double max_speed, double end_speed) { return new TurnDegreesCommand(*this, fb, degrees, max_speed, end_speed); } -AutoCommand *TankDrive::PurePursuitCmd(PurePursuit::Path path, directionType dir, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::PurePursuitCmd(PurePursuit::Path path, directionType dir, double max_speed, double end_speed) { return new PurePursuitCommand(*this, *drive_default_feedback, path, dir, max_speed, end_speed); } -AutoCommand *TankDrive::PurePursuitCmd(Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::PurePursuitCmd(Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed, + double end_speed) { return new PurePursuitCommand(*this, feedback, path, dir, max_speed, end_speed); } /** * Reset the initialization for autonomous drive functions */ -void TankDrive::reset_auto() -{ - func_initialized = false; -} +void TankDrive::reset_auto() { func_initialized = false; } /** * Stops rotation of all the motors using their "brake mode" */ -void TankDrive::stop() -{ +void TankDrive::stop() { left_motors.stop(); right_motors.stop(); } -void TankDrive::drive_tank_raw(double left_norm, double right_norm) -{ +void TankDrive::drive_tank_raw(double left_norm, double right_norm) { left_motors.spin(directionType::fwd, left_norm * 12, voltageUnits::volt); right_motors.spin(directionType::fwd, right_norm * 12, voltageUnits::volt); } @@ -87,59 +75,47 @@ void TankDrive::drive_tank_raw(double left_norm, double right_norm) */ bool captured_position = false; bool was_breaking = false; -void TankDrive::drive_tank(double left, double right, int power, BrakeType bt) -{ +void TankDrive::drive_tank(double left, double right, int power, BrakeType bt) { left = modify_inputs(left, power); right = modify_inputs(right, power); double brake_threshold = 0.05; bool should_brake = (bt != BrakeType::None) && fabs(left) < brake_threshold && fabs(right) < brake_threshold; - if (!should_brake) - { + if (!should_brake) { drive_tank_raw(left, right); was_breaking = false; return; } - if (should_brake && !was_breaking) - { + if (should_brake && !was_breaking) { captured_position = false; } static PID::pid_config_t zero_vel_cfg = {.p = 0.005, .d = 0.0005}; static PID zero_vel_pid = PID(zero_vel_cfg); - if (bt == BrakeType::ZeroVelocity) - { + if (bt == BrakeType::ZeroVelocity) { zero_vel_pid.set_target(0); double vel = left_motors.velocity(vex::velocityUnits::pct) + right_motors.velocity(vex::velocityUnits::pct); double outp = zero_vel_pid.update(vel); left_motors.spin(directionType::fwd, outp, voltageUnits::volt); right_motors.spin(directionType::fwd, outp, voltageUnits::volt); - } - else if (bt == BrakeType::Smart) - { + } else if (bt == BrakeType::Smart) { static pose_t target_pose = {.x = 0.0, .y = 0.0, .rot = 0.0}; zero_vel_pid.set_target(0); double vel = odometry->get_speed(); - if (fabs(vel) <= 0.01 && !captured_position) - { + if (fabs(vel) <= 0.01 && !captured_position) { target_pose = odometry->get_position(); captured_position = true; - } - else if (captured_position) - { + } else if (captured_position) { double dist_to_target = odometry->pos_diff(target_pose, odometry->get_position()); - if (dist_to_target < 12.0) - { + if (dist_to_target < 12.0) { drive_to_point(target_pose.x, target_pose.y, vex::fwd); } else { target_pose = odometry->get_position(); reset_auto(); } - } - else - { + } else { double outp = zero_vel_pid.update(vel); left_motors.spin(directionType::fwd, outp, voltageUnits::volt); right_motors.spin(directionType::fwd, outp, voltageUnits::volt); @@ -154,8 +130,7 @@ void TankDrive::drive_tank(double left, double right, int power, BrakeType bt) * * left_motors and right_motors are in "percent": -1.0 -> 1.0 */ -void TankDrive::drive_arcade(double forward_back, double left_right, int power, BrakeType bt) -{ +void TankDrive::drive_arcade(double forward_back, double left_right, int power, BrakeType bt) { forward_back = modify_inputs(forward_back, power); left_right = modify_inputs(left_right, power); @@ -171,35 +146,31 @@ void TankDrive::drive_arcade(double forward_back, double left_right, int power, * Returns whether or not the robot has reached it's destination. * @param inches the distance to drive forward * @param dir the direction we want to travel forward and backward - * @param feedback the custom feedback controller we will use to travel. controls the rate at which we accelerate and drive. + * @param feedback the custom feedback controller we will use to travel. controls the rate at which we accelerate and + * drive. * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power * @param end_speed the movement profile will attempt to reach this velocity by its completion */ -bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed, double end_speed) -{ +bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed, + double end_speed) { static pose_t pos_setpt; // We can't run the auto drive function without odometry - if (odometry == NULL) - { + if (odometry == NULL) { fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); fflush(stderr); return true; } // Generate a point X inches forward of the current position, on first startup - if (!func_initialized) - { + if (!func_initialized) { pose_t cur_pos = odometry->get_position(); // forwards is positive Y axis, backwards is negative - if (dir == directionType::rev) - { + if (dir == directionType::rev) { printf("going backwards\n"); inches = -fabs(inches); - } - else - { + } else { printf("going forwards\n"); inches = fabs(inches); } @@ -225,11 +196,10 @@ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedba * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return true if we have finished driving to our point */ -bool TankDrive::drive_forward(double inches, directionType dir, double max_speed, double end_speed) -{ +bool TankDrive::drive_forward(double inches, directionType dir, double max_speed, double end_speed) { if (drive_default_feedback != NULL) { return drive_forward(inches, dir, *drive_default_feedback, max_speed, end_speed); -} + } printf("tank_drive.cpp: Cannot run drive_forward without a feedback controller!\n"); fflush(stdout); @@ -248,11 +218,9 @@ bool TankDrive::drive_forward(double inches, directionType dir, double max_speed * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return true if we have turned our target number of degrees */ -bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_speed, double end_speed) -{ +bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_speed, double end_speed) { // We can't run the auto drive function without odometry - if (odometry == NULL) - { + if (odometry == NULL) { fprintf(stderr, "Odometry is NULL. Unable to run turn_degrees()\n"); fflush(stderr); return true; @@ -261,8 +229,7 @@ bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_spee static double target_heading = 0; // On the first run of the funciton, reset the gyro position and PID - if (!func_initialized) - { + if (!func_initialized) { double start_heading = odometry->get_position().rot; target_heading = start_heading + degrees; } @@ -281,11 +248,10 @@ bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_spee * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return true if we turned te target number of degrees */ -bool TankDrive::turn_degrees(double degrees, double max_speed, double end_speed) -{ +bool TankDrive::turn_degrees(double degrees, double max_speed, double end_speed) { if (turn_default_feedback != NULL) { return turn_degrees(degrees, *turn_default_feedback, max_speed, end_speed); -} + } printf("tank_drive.cpp: Cannot run turn_degrees without a feedback controller!\n"); fflush(stdout); @@ -305,18 +271,16 @@ bool TankDrive::turn_degrees(double degrees, double max_speed, double end_speed) * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return true if we have reached our target point */ -bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed, double end_speed) -{ +bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed, + double end_speed) { // We can't run the auto drive function without odometry - if (odometry == NULL) - { + if (odometry == NULL) { fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); fflush(stderr); return true; } - if (!func_initialized) - { + if (!func_initialized) { double initial_dist = OdometryBase::pos_diff(odometry->get_position(), {.x = x, .y = y}); @@ -335,10 +299,7 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb pose_t end_pos = {.x = x, .y = y}; // Create a point (and vector) to get the direction - point_t pos_diff_pt = - { - .x = x - current_pos.x, - .y = y - current_pos.y}; + point_t pos_diff_pt = {.x = x - current_pos.x, .y = y - current_pos.y}; Vector2D point_vec(pos_diff_pt); @@ -356,20 +317,19 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb // Normalize the angle between 0 and 360 if (angle > 360) { angle -= 360; -} + } if (angle < 0) { angle += 360; -} + } // If the angle is behind the robot, report negative. if (dir == directionType::fwd && angle > 90 && angle < 270) { sign = -1; } else if (dir == directionType::rev && (angle < 90 || angle > 270)) { sign = -1; -} + } - if (fabs(dist_left) < config.drive_correction_cutoff) - { + if (fabs(dist_left) < config.drive_correction_cutoff) { // When inside the robot's cutoff radius, report the distance to the point along the robot's forward axis, // so we always "reach" the point without having to do a lateral translation dist_left *= fabs(cos(angle * PI / 180.0)); @@ -385,7 +345,7 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb delta_heading = OdometryBase::smallest_angle(current_pos.rot, heading); } else { delta_heading = OdometryBase::smallest_angle(current_pos.rot - 180, heading); -} + } // Update the PID controllers with new information correction_pid.update(delta_heading); @@ -395,7 +355,7 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb double correction = 0; if (is_pure_pursuit || fabs(dist_left) > config.drive_correction_cutoff) { correction = correction_pid.get(); -} + } // Reverse the drive_pid output if we're going backwards double drive_pid_rval; @@ -403,7 +363,7 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb drive_pid_rval = feedback.get() * -1; } else { drive_pid_rval = feedback.get(); -} + } // Combine the two pid outputs double lside = drive_pid_rval + correction; @@ -416,8 +376,7 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb drive_tank(lside, rside); // Check if the robot has reached it's destination - if (feedback.is_on_target()) - { + if (feedback.is_on_target()) { if (end_speed == 0) { stop(); } @@ -441,11 +400,10 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return true if we have reached our target point */ -bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, double max_speed, double end_speed) -{ +bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, double max_speed, double end_speed) { if (drive_default_feedback != NULL) { return this->drive_to_point(x, y, dir, *drive_default_feedback, max_speed, end_speed); -} + } printf("tank_drive.cpp: Cannot run drive_to_point without a feedback controller!\n"); fflush(stdout); @@ -462,18 +420,15 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, doubl * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return true if we have reached our target heading */ -bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double max_speed, double end_speed) -{ +bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double max_speed, double end_speed) { // We can't run the auto drive function without odometry - if (odometry == NULL) - { + if (odometry == NULL) { fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); fflush(stderr); return true; } - if (!func_initialized) - { + if (!func_initialized) { double initial_delta = OdometryBase::smallest_angle(odometry->get_position().rot, heading_deg); feedback.init(-initial_delta, 0); feedback.set_limits(-fabs(max_speed), fabs(max_speed)); @@ -490,8 +445,7 @@ bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double m drive_tank(-feedback.get(), feedback.get()); // When the robot has reached it's angle, return true. - if (feedback.is_on_target()) - { + if (feedback.is_on_target()) { func_initialized = false; stop(); return true; @@ -508,11 +462,10 @@ bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double m * @param end_speed the movement profile will attempt to reach this velocity by its completion * @return true if we have reached our target heading */ -bool TankDrive::turn_to_heading(double heading_deg, double max_speed, double end_speed) -{ +bool TankDrive::turn_to_heading(double heading_deg, double max_speed, double end_speed) { if (turn_default_feedback != NULL) { return turn_to_heading(heading_deg, *turn_default_feedback, max_speed, end_speed); -} + } printf("tank_drive.cpp: Cannot run turn_to_heading without a feedback controller!\n"); fflush(stdout); @@ -526,10 +479,7 @@ bool TankDrive::turn_to_heading(double heading_deg, double max_speed, double end * @param power the power to raise the signal to * @return input^power accounting for any sign issues that would arise with this naive solution */ -double TankDrive::modify_inputs(double input, int power) -{ - return sign(input) * pow(std::abs(input), power); -} +double TankDrive::modify_inputs(double input, int power) { return sign(input) * pow(std::abs(input), power); } /** * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of @@ -542,23 +492,21 @@ double TankDrive::modify_inputs(double input, int power) * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) * @return True when the path is complete */ -bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback &feedback, double max_speed, double end_speed) -{ +bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback &feedback, double max_speed, + double end_speed) { std::vector points = path.get_points(); - if (!path.is_valid()) - { + if (!path.is_valid()) { printf("WARNING: Unexpected pure pursuit path - some segments intersect or are too close\n"); } pose_t robot_pose = odometry->get_position(); // On function initialization, send the path-length estimate to the feedback controller - if (!func_initialized) - { + if (!func_initialized) { if (dir != directionType::rev) { feedback.init(-estimate_path_length(points), 0); } else { feedback.init(estimate_path_length(points), 0); -} + } func_initialized = true; } @@ -578,15 +526,13 @@ bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback angle_diff = OdometryBase::smallest_angle(robot_pose.rot, rad2deg(atan2(localized.y, localized.x))); } else { angle_diff = OdometryBase::smallest_angle(robot_pose.rot + 180, rad2deg(atan2(localized.y, localized.x))); -} + } // Correct the robot's heading until the last cut-off - if (!(is_last_point && robot_pose.get_point().dist(last_point) < config.drive_correction_cutoff)) - { + if (!(is_last_point && robot_pose.get_point().dist(last_point) < config.drive_correction_cutoff)) { correction_pid.update(angle_diff); correction = correction_pid.get(); - } - else // Inside cut-off radius, ignore horizontal diffs + } else // Inside cut-off radius, ignore horizontal diffs { dist_remaining *= cos(angle_diff * (PI / 180.0)); } @@ -595,7 +541,7 @@ bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback feedback.update(-dist_remaining); } else { feedback.update(dist_remaining); -} + } max_speed = fabs(max_speed); @@ -608,8 +554,7 @@ bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback drive_tank(left, right); // When the robot has reached the end point and feedback reports on target, end pure pursuit - if (is_last_point && feedback.is_on_target()) - { + if (is_last_point && feedback.is_on_target()) { func_initialized = false; stop(); return true; @@ -629,7 +574,6 @@ bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) * @return True when the path is complete */ -bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, double max_speed, double end_speed) -{ +bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, double max_speed, double end_speed) { return pure_pursuit(path, dir, *config.drive_feedback, max_speed, end_speed); } \ No newline at end of file diff --git a/src/utils/auto_chooser.cpp b/src/utils/auto_chooser.cpp index 9ef9b87..2d3418e 100644 --- a/src/utils/auto_chooser.cpp +++ b/src/utils/auto_chooser.cpp @@ -5,8 +5,7 @@ * so the driver can choose which autonomous to run. * @param brain the brain on which to draw the selection boxes */ -AutoChooser::AutoChooser(std::vector paths, size_t def) : choice(def) -{ +AutoChooser::AutoChooser(std::vector paths, size_t def) : choice(def) { const static int per_line = 3; const static int num_lines = 2; const static int x_padding = 20; @@ -18,42 +17,35 @@ AutoChooser::AutoChooser(std::vector paths, size_t def) : choice(de list = std::vector(paths.size()); int x = 50; int y = 10; - for (size_t i = 0; i < list.size(); i++) - { + for (size_t i = 0; i < list.size(); i++) { Rect r = Rect::from_min_and_size({(double)x, (double)y}, {entry_width, entry_height}); list[i] = entry_t{r, paths[i]}; x += entry_width + x_padding; - if ((i + 1) % per_line == 0) - { + if ((i + 1) % per_line == 0) { y += entry_height + y_padding; x = 50; } } } -void AutoChooser::update(bool was_pressed, int x, int y) -{ +void AutoChooser::update(bool was_pressed, int x, int y) { size_t i = 0; - for (const entry_t &e : list) - { - if (was_pressed && e.rect.contains({(double)x, (double)y})) - { + for (const entry_t &e : list) { + if (was_pressed && e.rect.contains({(double)x, (double)y})) { choice = i; } i++; } } -void AutoChooser::draw(vex::brain::lcd &scr, [[maybe_unused]] bool first_draw, [[maybe_unused]] unsigned int frame_number) -{ +void AutoChooser::draw(vex::brain::lcd &scr, [[maybe_unused]] bool first_draw, + [[maybe_unused]] unsigned int frame_number) { scr.setFont(vex::fontType::mono20); - for (size_t i = 0; i < list.size(); i++) - { + for (size_t i = 0; i < list.size(); i++) { entry_t e = list[i]; scr.setFillColor(vex::blue); - if (choice == i) - { + if (choice == i) { scr.setFillColor(vex::green); } scr.drawRectangle(e.rect.min.x, e.rect.min.y, e.rect.width(), e.rect.height()); @@ -66,7 +58,4 @@ void AutoChooser::draw(vex::brain::lcd &scr, [[maybe_unused]] bool first_draw, [ /** * Return the selected autonomous */ -size_t AutoChooser::get_choice() -{ - return choice; -} \ No newline at end of file +size_t AutoChooser::get_choice() { return choice; } \ No newline at end of file diff --git a/src/utils/command_structure/auto_command.cpp b/src/utils/command_structure/auto_command.cpp index c6cdbbd..c8ae87f 100644 --- a/src/utils/command_structure/auto_command.cpp +++ b/src/utils/command_structure/auto_command.cpp @@ -37,12 +37,9 @@ IfTimePassed::IfTimePassed(double time_s) : time_s(time_s), tmr() {} bool IfTimePassed::test() { return tmr.value() > time_s; } InOrder::InOrder(std::queue cmds) : cmds(cmds) { - timeout_seconds = - -1.0; // never timeout unless with_timeout is explicitly called -} -InOrder::InOrder(std::initializer_list cmds) : cmds(cmds) { - timeout_seconds = -1.0; + timeout_seconds = -1.0; // never timeout unless with_timeout is explicitly called } +InOrder::InOrder(std::initializer_list cmds) : cmds(cmds) { timeout_seconds = -1.0; } bool InOrder::run() { // outer loop finished @@ -122,8 +119,7 @@ static int parallel_runner(void *arg) { } // wait for all to finish -Parallel::Parallel(std::initializer_list cmds) - : cmds(cmds), runners(0) {} +Parallel::Parallel(std::initializer_list cmds) : cmds(cmds), runners(0) {} bool Parallel::run() { if (runners.size() == 0) { @@ -166,10 +162,8 @@ void Parallel::on_timeout() { runners.clear(); } -Branch::Branch(Condition *cond, AutoCommand *false_choice, - AutoCommand *true_choice) - : false_choice(false_choice), true_choice(true_choice), cond(cond), - choice(false), chosen(false), tmr() {} +Branch::Branch(Condition *cond, AutoCommand *false_choice, AutoCommand *true_choice) + : false_choice(false_choice), true_choice(true_choice), cond(cond), choice(false), chosen(false), tmr() {} Branch::~Branch() { delete false_choice; @@ -183,14 +177,12 @@ bool Branch::run() { double seconds = static_cast(tmr.time()) / 1000.0; if (choice == false) { - if (seconds > false_choice->timeout_seconds && - false_choice->timeout_seconds != -1) { + if (seconds > false_choice->timeout_seconds && false_choice->timeout_seconds != -1) { false_choice->on_timeout(); } return false_choice->run(); } else { - if (seconds > true_choice->timeout_seconds && - true_choice->timeout_seconds != -1) { + if (seconds > true_choice->timeout_seconds && true_choice->timeout_seconds != -1) { true_choice->on_timeout(); } return true_choice->run(); @@ -240,13 +232,11 @@ bool Async::run() { return true; } -RepeatUntil::RepeatUntil(InOrder cmds, size_t times) - : RepeatUntil(cmds, new TimesTestedCondition(times)) { +RepeatUntil::RepeatUntil(InOrder cmds, size_t times) : RepeatUntil(cmds, new TimesTestedCondition(times)) { timeout_seconds = 999999; } -RepeatUntil::RepeatUntil(InOrder cmds, Condition *cond) - : cmds(cmds), working_cmds(new InOrder(cmds)), cond(cond) { +RepeatUntil::RepeatUntil(InOrder cmds, Condition *cond) : cmds(cmds), working_cmds(new InOrder(cmds)), cond(cond) { timeout_seconds = 999999; } diff --git a/src/utils/command_structure/basic_command.cpp b/src/utils/command_structure/basic_command.cpp index a45b85f..9102f30 100644 --- a/src/utils/command_structure/basic_command.cpp +++ b/src/utils/command_structure/basic_command.cpp @@ -22,7 +22,9 @@ * @param setting Power setting in volts,percentage,velocity * @param power Value of desired power */ -BasicSpinCommand::BasicSpinCommand(vex::motor &motor, vex::directionType dir, BasicSpinCommand::type setting, double power) : motor(motor), setting(setting), dir(dir), power(power) {} +BasicSpinCommand::BasicSpinCommand(vex::motor &motor, vex::directionType dir, BasicSpinCommand::type setting, + double power) + : motor(motor), setting(setting), dir(dir), power(power) {} /** * @brief Run the BasicSpinCommand @@ -30,21 +32,19 @@ BasicSpinCommand::BasicSpinCommand(vex::motor &motor, vex::directionType dir, Ba * * @return True Command runs once */ -bool BasicSpinCommand::run() -{ - switch (setting) - { // Switch Statement taking the setting Enum - case voltage: // Voltage Setting - motor.spin(dir, power, vex::volt); - break; - case percent: // Percentage Setting - motor.spin(dir, power, vex::percent); - break; - case veocity: // Velocity Setting - motor.spin(dir, power, vex::velocityUnits::rpm); - break; - } - return true; // Always return True to send next on CommandController +bool BasicSpinCommand::run() { + switch (setting) { // Switch Statement taking the setting Enum + case voltage: // Voltage Setting + motor.spin(dir, power, vex::volt); + break; + case percent: // Percentage Setting + motor.spin(dir, power, vex::percent); + break; + case veocity: // Velocity Setting + motor.spin(dir, power, vex::velocityUnits::rpm); + break; + } + return true; // Always return True to send next on CommandController } /** @@ -61,10 +61,9 @@ BasicStopCommand::BasicStopCommand(vex::motor &motor, vex::brakeType setting) : * * @return True Command runs once */ -bool BasicStopCommand::run() -{ - motor.stop(setting); - return true; +bool BasicStopCommand::run() { + motor.stop(setting); + return true; } // Basic Solenoid Commands----------------------------------- @@ -82,8 +81,7 @@ BasicSolenoidSet::BasicSolenoidSet(vex::pneumatics &solenoid, bool setting) : so * * @return True Command runs once */ -bool BasicSolenoidSet::run() -{ - solenoid.set(setting); - return true; +bool BasicSolenoidSet::run() { + solenoid.set(setting); + return true; } \ No newline at end of file diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index efae140..9104beb 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -6,17 +6,17 @@ * a queue and get executed and removed from the queue * in FIFO order. */ -#include #include "../core/include/utils/command_structure/command_controller.h" #include "../core/include/utils/command_structure/delay_command.h" +#include /** * Adds a command to the queue * @param cmd the AutoCommand we want to add to our list - * @param timeout_seconds the number of seconds we will let the command run for. If it exceeds this, we cancel it and run on_timeout + * @param timeout_seconds the number of seconds we will let the command run for. If it exceeds this, we cancel it and + * run on_timeout */ -void CommandController::add(AutoCommand *cmd, double timeout_seconds) -{ +void CommandController::add(AutoCommand *cmd, double timeout_seconds) { cmd->timeout_seconds = timeout_seconds; command_queue.push(cmd); } @@ -25,10 +25,8 @@ void CommandController::add(AutoCommand *cmd, double timeout_seconds) * Add multiple commands to the queue. No timeout here. * @param cmds the AutoCommands we want to add to our list */ -void CommandController::add(std::vector cmds) -{ - for (AutoCommand *cmd : cmds) - { +void CommandController::add(std::vector cmds) { + for (AutoCommand *cmd : cmds) { command_queue.push(cmd); } } @@ -38,12 +36,9 @@ void CommandController::add(std::vector cmds) * @param cmds the AutoCommands we want to add to our list * @param timeout timeout in seconds to apply to all commands if they are still the default */ -void CommandController::add(std::vector cmds, double timeout_sec) -{ - for (AutoCommand *cmd : cmds) - { - if (cmd->timeout_seconds == AutoCommand::default_timeout) - { +void CommandController::add(std::vector cmds, double timeout_sec) { + for (AutoCommand *cmd : cmds) { + if (cmd->timeout_seconds == AutoCommand::default_timeout) { cmd->timeout_seconds = timeout_sec; } command_queue.push(cmd); @@ -56,23 +51,18 @@ void CommandController::add(std::vector cmds, double timeout_sec) * @param ms - number of milliseconds to wait * before continuing execution of autonomous */ -void CommandController::add_delay(int ms) -{ +void CommandController::add_delay(int ms) { AutoCommand *delay = new DelayCommand(ms); command_queue.push(delay); } -void CommandController::add_cancel_func(std::function true_if_cancel) -{ - should_cancel = true_if_cancel; -} +void CommandController::add_cancel_func(std::function true_if_cancel) { should_cancel = true_if_cancel; } /** * Begin execution of the queue * Execute and remove commands in FIFO order */ -void CommandController::run() -{ +void CommandController::run() { AutoCommand *next_cmd; printf("Running Auto. Commands 1 to %d\n", command_queue.size()); fflush(stdout); @@ -80,45 +70,39 @@ void CommandController::run() vex::timer tmr; tmr.reset(); - while (!command_queue.empty()) - { + while (!command_queue.empty()) { // retrieve and remove command at the front of the queue next_cmd = command_queue.front(); command_queue.pop(); command_timed_out = false; - // printf("Beginning Command %d : timeout = %.2f : at time = %.1f seconds\n", command_count, next_cmd->timeout_seconds, tmr.time(vex::seconds)); - // fflush(stdout); + // printf("Beginning Command %d : timeout = %.2f : at time = %.1f seconds\n", command_count, + // next_cmd->timeout_seconds, tmr.time(vex::seconds)); fflush(stdout); vex::timer timeout_timer; timeout_timer.reset(); bool doTimeout = next_cmd->timeout_seconds > 0.0; - if (next_cmd->true_to_end != nullptr) - { + if (next_cmd->true_to_end != nullptr) { doTimeout = doTimeout || next_cmd->true_to_end->test(); } // run the current command until it returns true or we timeout - while (!next_cmd->run()) - { + while (!next_cmd->run()) { vexDelay(5); - if (!doTimeout) - { + if (!doTimeout) { continue; } // If we do want to check for timeout, check and end the command if we should double cmd_elapsed_sec = ((double)timeout_timer.time()) / 1000.0; - if (cmd_elapsed_sec > next_cmd->timeout_seconds || should_cancel()) - { + if (cmd_elapsed_sec > next_cmd->timeout_seconds || should_cancel()) { next_cmd->on_timeout(); command_timed_out = true; break; } } - if (should_cancel()) - { + if (should_cancel()) { break; } @@ -129,7 +113,4 @@ void CommandController::run() printf("Finished commands in %f seconds\n", tmr.time(vex::sec)); } -bool CommandController::last_command_timed_out() -{ - return command_timed_out; -} \ No newline at end of file +bool CommandController::last_command_timed_out() { return command_timed_out; } \ No newline at end of file diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index 4984cf6..c017513 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -2,7 +2,7 @@ * File: drive_commands.h * Desc: * Holds all the AutoCommand subclasses that wrap (currently) TankDrive functions - * + * * Currently includes: * - drive_forward * - turn_degrees @@ -18,7 +18,6 @@ #include "../core/include/utils/command_structure/drive_commands.h" - // ==== DRIVING ==== /** @@ -28,28 +27,26 @@ * @param inches how far forward to drive * @param dir the direction to drive * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at -*/ -DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed, double end_speed): - drive_sys(drive_sys), feedback(feedback), inches(inches), dir(dir), max_speed(max_speed), end_speed(end_speed) {} + */ +DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, + double max_speed, double end_speed) + : drive_sys(drive_sys), feedback(feedback), inches(inches), dir(dir), max_speed(max_speed), end_speed(end_speed) {} /** * Run drive_forward * Overrides run from AutoCommand * @returns true when execution is complete, false otherwise */ -bool DriveForwardCommand::run() { - return drive_sys.drive_forward(inches, dir, feedback, max_speed, end_speed); -} +bool DriveForwardCommand::run() { return drive_sys.drive_forward(inches, dir, feedback, max_speed, end_speed); } /** * reset the drive system if we timeout -*/ -void DriveForwardCommand::on_timeout(){ + */ +void DriveForwardCommand::on_timeout() { drive_sys.stop(); drive_sys.reset_auto(); } - /** * Construct a TurnDegreesCommand Command * @param drive_sys the drive system we are commanding @@ -57,26 +54,24 @@ void DriveForwardCommand::on_timeout(){ * @param degrees how many degrees to rotate * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at */ -TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed, double end_speed): - drive_sys(drive_sys), feedback(feedback), degrees(degrees), max_speed(max_speed), end_speed(end_speed) {} +TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed, + double end_speed) + : drive_sys(drive_sys), feedback(feedback), degrees(degrees), max_speed(max_speed), end_speed(end_speed) {} /** * Run turn_degrees * Overrides run from AutoCommand * @returns true when execution is complete, false otherwise */ -bool TurnDegreesCommand::run() { - return drive_sys.turn_degrees(degrees, max_speed, end_speed); -} +bool TurnDegreesCommand::run() { return drive_sys.turn_degrees(degrees, max_speed, end_speed); } /** * reset the drive system if we timeout -*/ -void TurnDegreesCommand::on_timeout(){ + */ +void TurnDegreesCommand::on_timeout() { drive_sys.stop(); drive_sys.reset_auto(); } - /** * Construct a DriveForward Command * @param drive_sys the drive system we are commanding @@ -86,8 +81,9 @@ void TurnDegreesCommand::on_timeout(){ * @param dir the direction to drive * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at */ -DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed, double end_speed): - drive_sys(drive_sys), feedback(feedback), x(x), y(y), dir(dir), max_speed(max_speed), end_speed(end_speed) {} +DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, + directionType dir, double max_speed, double end_speed) + : drive_sys(drive_sys), feedback(feedback), x(x), y(y), dir(dir), max_speed(max_speed), end_speed(end_speed) {} /** * Construct a DriveForward Command @@ -97,26 +93,25 @@ DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedbac * @param dir the direction to drive * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at */ -DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, point_t point, directionType dir, double max_speed, double end_speed): - drive_sys(drive_sys), feedback(feedback), x(point.x), y(point.y), dir(dir), max_speed(max_speed), end_speed(end_speed) {} +DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, point_t point, directionType dir, + double max_speed, double end_speed) + : drive_sys(drive_sys), feedback(feedback), x(point.x), y(point.y), dir(dir), max_speed(max_speed), + end_speed(end_speed) {} /** * Run drive_to_point * Overrides run from AutoCommand * @returns true when execution is complete, false otherwise */ -bool DriveToPointCommand::run() { - return drive_sys.drive_to_point(x, y, dir, feedback, max_speed, end_speed); -} +bool DriveToPointCommand::run() { return drive_sys.drive_to_point(x, y, dir, feedback, max_speed, end_speed); } /** * reset the drive system if we don't hit our target -*/ -void DriveToPointCommand::on_timeout(){ + */ +void DriveToPointCommand::on_timeout() { drive_sys.stop(); drive_sys.reset_auto(); } - /** * Construct a TurnToHeadingCommand Command * @param drive_sys the drive system we are commanding @@ -124,50 +119,45 @@ void DriveToPointCommand::on_timeout(){ * @param heading_deg the heading to turn to in degrees * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at */ -TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double max_speed, double end_speed): - drive_sys(drive_sys), feedback(feedback), heading_deg(heading_deg), max_speed(max_speed), end_speed(end_speed) {} +TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, + double max_speed, double end_speed) + : drive_sys(drive_sys), feedback(feedback), heading_deg(heading_deg), max_speed(max_speed), end_speed(end_speed) {} /** * Run turn_to_heading * Overrides run from AutoCommand * @returns true when execution is complete, false otherwise */ -bool TurnToHeadingCommand::run() { - return drive_sys.turn_to_heading(heading_deg, feedback, max_speed, end_speed); -} +bool TurnToHeadingCommand::run() { return drive_sys.turn_to_heading(heading_deg, feedback, max_speed, end_speed); } /** * reset the drive system if we don't hit our target -*/ -void TurnToHeadingCommand::on_timeout(){ + */ +void TurnToHeadingCommand::on_timeout() { drive_sys.stop(); drive_sys.reset_auto(); } /** * Construct a Pure Pursuit AutoCommand - * + * * @param path The list of coordinates to follow, in order * @param dir Run the bot forwards or backwards * @param feedback The feedback controller determining speed * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) -*/ -PurePursuitCommand::PurePursuitCommand(TankDrive &drive_sys, Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed, double end_speed) -: drive_sys(drive_sys), path(path), dir(dir), feedback(feedback), max_speed(max_speed), end_speed(end_speed) -{} + */ +PurePursuitCommand::PurePursuitCommand(TankDrive &drive_sys, Feedback &feedback, PurePursuit::Path path, + directionType dir, double max_speed, double end_speed) + : drive_sys(drive_sys), path(path), dir(dir), feedback(feedback), max_speed(max_speed), end_speed(end_speed) {} /** * Direct call to TankDrive::pure_pursuit -*/ -bool PurePursuitCommand::run() -{ - return drive_sys.pure_pursuit(path, dir, feedback, max_speed, end_speed); -} + */ +bool PurePursuitCommand::run() { return drive_sys.pure_pursuit(path, dir, feedback, max_speed, end_speed); } /** * Reset the drive system when it times out -*/ -void PurePursuitCommand::on_timeout() -{ + */ +void PurePursuitCommand::on_timeout() { drive_sys.stop(); drive_sys.reset_auto(); } @@ -176,13 +166,9 @@ void PurePursuitCommand::on_timeout() * Construct a DriveStop Command * @param drive_sys the drive system we are commanding */ -DriveStopCommand::DriveStopCommand(TankDrive &drive_sys): - drive_sys(drive_sys) {} +DriveStopCommand::DriveStopCommand(TankDrive &drive_sys) : drive_sys(drive_sys) {} -void DriveStopCommand::on_timeout() -{ - drive_sys.reset_auto(); -} +void DriveStopCommand::on_timeout() { drive_sys.reset_auto(); } /** * Stop the drive train @@ -194,14 +180,13 @@ bool DriveStopCommand::run() { return true; } - // ==== ODOMETRY ==== /** * Construct an Odometry set pos * @param odom the odometry system we are setting * @param newpos the now position to set the odometry to */ -OdomSetPosition::OdomSetPosition(OdometryBase &odom, const pose_t &newpos): odom(odom), newpos(newpos){} +OdomSetPosition::OdomSetPosition(OdometryBase &odom, const pose_t &newpos) : odom(odom), newpos(newpos) {} bool OdomSetPosition::run() { odom.set_position(newpos); diff --git a/src/utils/command_structure/flywheel_commands.cpp b/src/utils/command_structure/flywheel_commands.cpp index bddda27..4307abc 100644 --- a/src/utils/command_structure/flywheel_commands.cpp +++ b/src/utils/command_structure/flywheel_commands.cpp @@ -6,49 +6,40 @@ #include "../core/include/utils/command_structure/flywheel_commands.h" - -SpinRPMCommand::SpinRPMCommand(Flywheel &flywheel, int rpm): - flywheel(flywheel), rpm(rpm) {} +SpinRPMCommand::SpinRPMCommand(Flywheel &flywheel, int rpm) : flywheel(flywheel), rpm(rpm) {} bool SpinRPMCommand::run() { flywheel.spin_rpm(rpm); return true; } -WaitUntilUpToSpeedCommand::WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshold_rpm): - flywheel(flywheel), threshold_rpm(threshold_rpm) {} +WaitUntilUpToSpeedCommand::WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshold_rpm) + : flywheel(flywheel), threshold_rpm(threshold_rpm) {} bool WaitUntilUpToSpeedCommand::run() { // If we're withing the specified threshold, we're ready to fire - if (fabs(flywheel.get_target() - flywheel.getRPM()) < threshold_rpm){ + if (fabs(flywheel.get_target() - flywheel.getRPM()) < threshold_rpm) { return true; } // else, keep waiting return false; } - - -FlywheelStopCommand::FlywheelStopCommand(Flywheel &flywheel): - flywheel(flywheel) {} +FlywheelStopCommand::FlywheelStopCommand(Flywheel &flywheel) : flywheel(flywheel) {} bool FlywheelStopCommand::run() { flywheel.stop(); return true; } - -FlywheelStopMotorsCommand::FlywheelStopMotorsCommand(Flywheel &flywheel): - flywheel(flywheel) {} +FlywheelStopMotorsCommand::FlywheelStopMotorsCommand(Flywheel &flywheel) : flywheel(flywheel) {} bool FlywheelStopMotorsCommand::run() { flywheel.stop(); return true; } - -FlywheelStopNonTasksCommand::FlywheelStopNonTasksCommand(Flywheel &flywheel): - flywheel(flywheel) {} +FlywheelStopNonTasksCommand::FlywheelStopNonTasksCommand(Flywheel &flywheel) : flywheel(flywheel) {} bool FlywheelStopNonTasksCommand::run() { flywheel.stop(); diff --git a/src/utils/controls/bang_bang.cpp b/src/utils/controls/bang_bang.cpp index fcc1c70..a885081 100644 --- a/src/utils/controls/bang_bang.cpp +++ b/src/utils/controls/bang_bang.cpp @@ -1,43 +1,30 @@ #include "../core/include/utils/controls/bang_bang.h" #include -BangBang::BangBang(double threshhold, double low, double high) : setpt(low), sensor_val(low), lower_bound(low), upper_bound(high), threshhold(threshhold) {} +BangBang::BangBang(double threshhold, double low, double high) + : setpt(low), sensor_val(low), lower_bound(low), upper_bound(high), threshhold(threshhold) {} -void BangBang::init(double start_pt, double set_pt) -{ - sensor_val = start_pt; - setpt = set_pt; +void BangBang::init(double start_pt, double set_pt) { + sensor_val = start_pt; + setpt = set_pt; } -void BangBang::set_limits(double lower, double upper) -{ - lower_bound = lower; - upper_bound = upper; -} -double BangBang::get() -{ - return last_output; +void BangBang::set_limits(double lower, double upper) { + lower_bound = lower; + upper_bound = upper; } +double BangBang::get() { return last_output; } -double BangBang::update(double val) -{ - sensor_val = val; - if (fabs(val - setpt) < threshhold) - { - last_output = 0; - } - else if (val > setpt) - { - last_output = lower_bound; - } - else - { - last_output = upper_bound; - } - return upper_bound; +double BangBang::update(double val) { + sensor_val = val; + if (fabs(val - setpt) < threshhold) { + last_output = 0; + } else if (val > setpt) { + last_output = lower_bound; + } else { + last_output = upper_bound; + } + return upper_bound; } -bool BangBang::is_on_target() -{ - return fabs(sensor_val - setpt) < threshhold; -} \ No newline at end of file +bool BangBang::is_on_target() { return fabs(sensor_val - setpt) < threshhold; } \ No newline at end of file diff --git a/src/utils/controls/feedforward.cpp b/src/utils/controls/feedforward.cpp index ba68dc2..9540c4f 100644 --- a/src/utils/controls/feedforward.cpp +++ b/src/utils/controls/feedforward.cpp @@ -1,92 +1,85 @@ #include "../core/include/utils/controls/feedforward.h" - /** -* tune_feedforward takes a group of motors and finds the feedforward conifg parameters automagically. -* @param motor the motor group to use -* @param pct Maximum velocity in percent (0->1.0) + * tune_feedforward takes a group of motors and finds the feedforward conifg parameters automagically. + * @param motor the motor group to use + * @param pct Maximum velocity in percent (0->1.0) * @param duration Amount of time the motors spin for the test * @return A tuned feedforward object */ -FeedForward::ff_config_t tune_feedforward(vex::motor_group &motor, double pct, double duration) -{ - FeedForward::ff_config_t out = {}; - - double start_pos = motor.position(vex::rotationUnits::rev); - - // ========== kS Tuning ========= - // Start at 0 and slowly increase the power until the robot starts moving - double power = 0; - while(fabs(motor.position(vex::rotationUnits::rev) - start_pos) < 0.05) - { - motor.spin(vex::directionType::fwd, power, vex::voltageUnits::volt); - power += 0.001; - vexDelay(100); - } - out.kS = power; - motor.stop(); +FeedForward::ff_config_t tune_feedforward(vex::motor_group &motor, double pct, double duration) { + FeedForward::ff_config_t out = {}; + double start_pos = motor.position(vex::rotationUnits::rev); - // ========== kV / kA Tuning ========= + // ========== kS Tuning ========= + // Start at 0 and slowly increase the power until the robot starts moving + double power = 0; + while (fabs(motor.position(vex::rotationUnits::rev) - start_pos) < 0.05) { + motor.spin(vex::directionType::fwd, power, vex::voltageUnits::volt); + power += 0.001; + vexDelay(100); + } + out.kS = power; + motor.stop(); - std::vector> vel_data_points; // time, velocity - std::vector> accel_data_points; // time, accel + // ========== kV / kA Tuning ========= - double max_speed = 0; - vex::timer tmr; - double time = 0; + std::vector> vel_data_points; // time, velocity + std::vector> accel_data_points; // time, accel - MovingAverage vel_ma(3); - MovingAverage accel_ma(3); + double max_speed = 0; + vex::timer tmr; + double time = 0; - // Move the robot forward at a fixed percentage for X seconds while taking velocity and accel measurements - do - { - double last_time = time; - time = tmr.time(vex::sec); - double dt = time - last_time; + MovingAverage vel_ma(3); + MovingAverage accel_ma(3); - vel_ma.add_entry(motor.velocity(vex::velocityUnits::rpm)); - accel_ma.add_entry(motor.velocity(vex::velocityUnits::rpm)/dt); + // Move the robot forward at a fixed percentage for X seconds while taking velocity and accel measurements + do { + double last_time = time; + time = tmr.time(vex::sec); + double dt = time - last_time; - double speed = vel_ma.get_value(); - double accel = accel_ma.get_value(); + vel_ma.add_entry(motor.velocity(vex::velocityUnits::rpm)); + accel_ma.add_entry(motor.velocity(vex::velocityUnits::rpm) / dt); - // For kV: - if(speed > max_speed) { - max_speed = speed; -} + double speed = vel_ma.get_value(); + double accel = accel_ma.get_value(); - // For kA: - // Filter out the acceleration dampening due to motor inductance - if(time > 0.25) - { - vel_data_points.push_back(std::pair(time, speed)); - accel_data_points.push_back(std::pair(time, accel)); - } + // For kV: + if (speed > max_speed) { + max_speed = speed; + } - // Theoretical polling rate = 100hz (it won't be that much, cause, y'know, vex.) - vexDelay(10); - } while(time < duration); + // For kA: + // Filter out the acceleration dampening due to motor inductance + if (time > 0.25) { + vel_data_points.push_back(std::pair(time, speed)); + accel_data_points.push_back(std::pair(time, accel)); + } - motor.stop(); + // Theoretical polling rate = 100hz (it won't be that much, cause, y'know, vex.) + vexDelay(10); + } while (time < duration); - // Calculate kV (volts/12 per unit per second) - out.kV = (pct - out.kS) / max_speed; + motor.stop(); - // Calculate kA (volts/12 per unit per second^2) - std::vector> accel_per_pct; - for (int i = 0; i < vel_data_points.size(); i++) - { - accel_per_pct.push_back(std::pair( - pct - out.kS - (vel_data_points[i].second * out.kV), // Acceleration-causing percent (X variable) - accel_data_points[i].second // Measured acceleration (Y variable) + // Calculate kV (volts/12 per unit per second) + out.kV = (pct - out.kS) / max_speed; + + // Calculate kA (volts/12 per unit per second^2) + std::vector> accel_per_pct; + for (int i = 0; i < vel_data_points.size(); i++) { + accel_per_pct.push_back(std::pair( + pct - out.kS - (vel_data_points[i].second * out.kV), // Acceleration-causing percent (X variable) + accel_data_points[i].second // Measured acceleration (Y variable) )); - } - - // kA is the reciprocal of the slope of the linear regression - double regres_slope = calculate_linear_regression(accel_per_pct).first; - out.kA = 1.0 / regres_slope; + } + + // kA is the reciprocal of the slope of the linear regression + double regres_slope = calculate_linear_regression(accel_per_pct).first; + out.kA = 1.0 / regres_slope; - return out; + return out; } \ No newline at end of file diff --git a/src/utils/controls/motion_controller.cpp b/src/utils/controls/motion_controller.cpp index 3ba4715..fbbe3c4 100644 --- a/src/utils/controls/motion_controller.cpp +++ b/src/utils/controls/motion_controller.cpp @@ -3,182 +3,166 @@ #include /** -* @brief Construct a new Motion Controller object -* -* @param config The definition of how the robot is able to move -* max_v Maximum velocity the movement is capable of -* accel Acceleration / deceleration of the movement -* pid_cfg Definitions of kP, kI, and kD -* ff_cfg Definitions of kS, kV, and kA -*/ + * @brief Construct a new Motion Controller object + * + * @param config The definition of how the robot is able to move + * max_v Maximum velocity the movement is capable of + * accel Acceleration / deceleration of the movement + * pid_cfg Definitions of kP, kI, and kD + * ff_cfg Definitions of kS, kV, and kA + */ MotionController::MotionController(m_profile_cfg_t &config) -: config(config), pid(config.pid_cfg), ff(config.ff_cfg), profile(config.max_v, config.accel) -{} + : config(config), pid(config.pid_cfg), ff(config.ff_cfg), profile(config.max_v, config.accel) {} /** * @brief Initialize the motion profile for a new movement * This will also reset the PID and profile timers. * @param start_pt Movement starting position - * @param end_pt Movement ending posiiton + * @param end_pt Movement ending posiiton */ -void MotionController::init(double start_pt, double end_pt) -{ - profile.set_endpts(start_pt, end_pt); - pid.reset(); - tmr.reset(); +void MotionController::init(double start_pt, double end_pt) { + profile.set_endpts(start_pt, end_pt); + pid.reset(); + tmr.reset(); } /** -* @brief Update the motion profile with a new sensor value -* -* @param sensor_val Value from the sensor -* @return the motor input generated from the motion profile -*/ -double MotionController::update(double sensor_val) -{ - cur_motion = profile.calculate(tmr.time(timeUnits::sec)); - pid.set_target(cur_motion.pos); - pid.update(sensor_val, cur_motion.vel); - - out = pid.get() + ff.calculate(cur_motion.vel, cur_motion.accel, pid.get()); - - if(lower_limit != upper_limit) - out = clamp(out, lower_limit, upper_limit); - - return out; + * @brief Update the motion profile with a new sensor value + * + * @param sensor_val Value from the sensor + * @return the motor input generated from the motion profile + */ +double MotionController::update(double sensor_val) { + cur_motion = profile.calculate(tmr.time(timeUnits::sec)); + pid.set_target(cur_motion.pos); + pid.update(sensor_val, cur_motion.vel); + + out = pid.get() + ff.calculate(cur_motion.vel, cur_motion.accel, pid.get()); + + if (lower_limit != upper_limit) + out = clamp(out, lower_limit, upper_limit); + + return out; } /** * @return the last saved result from the feedback controller */ -double MotionController::get() -{ - return out; -} +double MotionController::get() { return out; } /** * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. - * + * * @param lower Upper limit * @param upper Lower limit */ -void MotionController::set_limits(double lower, double upper) -{ - lower_limit = lower; - upper_limit = upper; +void MotionController::set_limits(double lower, double upper) { + lower_limit = lower; + upper_limit = upper; } -/** +/** * @return Whether or not the movement has finished, and the PID * confirms it is on target */ -bool MotionController::is_on_target() -{ - return (tmr.time(timeUnits::sec) > profile.get_movement_time()) && pid.is_on_target(); +bool MotionController::is_on_target() { + return (tmr.time(timeUnits::sec) > profile.get_movement_time()) && pid.is_on_target(); } /** * @return The current postion, velocity and acceleration setpoints -*/ -motion_t MotionController::get_motion() -{ - return cur_motion; -} + */ +motion_t MotionController::get_motion() { return cur_motion; } /** * This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. * It does this by first calculating the kS (voltage to overcome static friction) by slowly increasing * the voltage until it moves. - * + * * Next is kV (voltage to sustain a certain velocity), where the robot will record it's steady-state velocity * at 'pct' speed. - * + * * Finally, kA (voltage needed to accelerate by a certain rate), where the robot will record the entire movement's * velocity and acceleration, record a plot of [X=(pct-kV*V-kS), Y=(Acceleration)] along the movement, * and since kA*Accel = pct-kV*V-kS, the reciprocal of the linear regression is the kA value. - * + * * @param drive The tankdrive to operate on * @param odometry The robot's odometry subsystem * @param pct Maximum velocity in percent (0->1.0) * @param duration Amount of time the robot should be moving for the test * @return A tuned feedforward object */ -FeedForward::ff_config_t MotionController::tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct, double duration) -{ - FeedForward::ff_config_t out = {}; - - pose_t start_pos = odometry.get_position(); - - // ========== kS Tuning ========= - // Start at 0 and slowly increase the power until the robot starts moving - double power = 0; - while(odometry.pos_diff(start_pos, odometry.get_position()) < 0.05) - { - drive.drive_tank(power, power, 1); - power += 0.001; - vexDelay(100); +FeedForward::ff_config_t MotionController::tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct, + double duration) { + FeedForward::ff_config_t out = {}; + + pose_t start_pos = odometry.get_position(); + + // ========== kS Tuning ========= + // Start at 0 and slowly increase the power until the robot starts moving + double power = 0; + while (odometry.pos_diff(start_pos, odometry.get_position()) < 0.05) { + drive.drive_tank(power, power, 1); + power += 0.001; + vexDelay(100); + } + out.kS = power; + drive.stop(); + + // ========== kV / kA Tuning ========= + + std::vector> vel_data_points; // time, velocity + std::vector> accel_data_points; // time, accel + + double max_speed = 0; + timer tmr; + double time; + + MovingAverage vel_ma(3); + MovingAverage accel_ma(3); + + // Move the robot forward at a fixed percentage for X seconds while taking velocity and accel measurements + do { + time = tmr.time(sec); + + vel_ma.add_entry(odometry.get_speed()); + accel_ma.add_entry(odometry.get_accel()); + + double speed = vel_ma.get_value(); + double accel = accel_ma.get_value(); + + // For kV: + if (speed > max_speed) + max_speed = speed; + + // For kA: + // Filter out the acceleration dampening due to motor inductance + if (time > 0.25) { + vel_data_points.push_back(std::pair(time, speed)); + accel_data_points.push_back(std::pair(time, accel)); } - out.kS = power; - drive.stop(); - - - // ========== kV / kA Tuning ========= - std::vector> vel_data_points; // time, velocity - std::vector> accel_data_points; // time, accel + // Theoretical polling rate = 100hz (it won't be that much, cause, y'know, vex.) + vexDelay(10); + } while (time < duration); - double max_speed = 0; - timer tmr; - double time; + drive.stop(); - MovingAverage vel_ma(3); - MovingAverage accel_ma(3); + // Calculate kV (volts/12 per unit per second) + out.kV = (pct - out.kS) / max_speed; - // Move the robot forward at a fixed percentage for X seconds while taking velocity and accel measurements - do - { - time = tmr.time(sec); - - vel_ma.add_entry(odometry.get_speed()); - accel_ma.add_entry(odometry.get_accel()); - - double speed = vel_ma.get_value(); - double accel = accel_ma.get_value(); - - // For kV: - if(speed > max_speed) - max_speed = speed; - - // For kA: - // Filter out the acceleration dampening due to motor inductance - if(time > 0.25) - { - vel_data_points.push_back(std::pair(time, speed)); - accel_data_points.push_back(std::pair(time, accel)); - } - - // Theoretical polling rate = 100hz (it won't be that much, cause, y'know, vex.) - vexDelay(10); - } while(time < duration); - - drive.stop(); - - // Calculate kV (volts/12 per unit per second) - out.kV = (pct - out.kS) / max_speed; - - // Calculate kA (volts/12 per unit per second^2) - std::vector> accel_per_pct; - for (int i = 0; i < vel_data_points.size(); i++) - { - accel_per_pct.push_back(std::pair( - pct - out.kS - (vel_data_points[i].second * out.kV), // Acceleration-causing percent (X variable) - accel_data_points[i].second // Measured acceleration (Y variable) + // Calculate kA (volts/12 per unit per second^2) + std::vector> accel_per_pct; + for (int i = 0; i < vel_data_points.size(); i++) { + accel_per_pct.push_back(std::pair( + pct - out.kS - (vel_data_points[i].second * out.kV), // Acceleration-causing percent (X variable) + accel_data_points[i].second // Measured acceleration (Y variable) )); - } - - // kA is the reciprocal of the slope of the linear regression - double regres_slope = calculate_linear_regression(accel_per_pct).first; - out.kA = 1.0 / regres_slope; + } + + // kA is the reciprocal of the slope of the linear regression + double regres_slope = calculate_linear_regression(accel_per_pct).first; + out.kA = 1.0 / regres_slope; - return out; + return out; } \ No newline at end of file diff --git a/src/utils/controls/pid.cpp b/src/utils/controls/pid.cpp index 88696b6..1d0d43f 100644 --- a/src/utils/controls/pid.cpp +++ b/src/utils/controls/pid.cpp @@ -20,17 +20,14 @@ void PID::init(double start_pt, double set_pt) { * are measuring * @return the new output. What would be returned by PID::get() */ -double PID::update(double sensor_val) -{ - return update(sensor_val, 0); -} +double PID::update(double sensor_val) { return update(sensor_val, 0); } /** * Update the PID loop by taking the time difference from last update, * and running the PID formula with the new sensor data * @param sensor_val the distance, angle, encoder position or whatever it is we * are measuring - * @param v_setpt Expected velocity setpoint, to subtract from the D term (for + * @param v_setpt Expected velocity setpoint, to subtract from the D term (for * velocity control) * @return the new output. What would be returned by PID::get() */ @@ -45,9 +42,8 @@ double PID::update(double sensor_val, double v_setpt) { if (time_delta != 0.0) { d_term = config.d * (((get_error() - last_error) / time_delta) - v_setpt); } else if (last_time != 0.0) { - printf( - "(pid.cpp): Warning - running PID without a delay is just a P loop!\n"); -} + printf("(pid.cpp): Warning - running PID without a delay is just a P loop!\n"); + } // P and D terms out = (config.p * get_error()) + d_term; @@ -56,10 +52,9 @@ double PID::update(double sensor_val, double v_setpt) { // Only add to the accumulated error if the output is not saturated // aka "Integral Clamping" anti-windup technique - if (!limits_exist || - (limits_exist && (out < upper_limit && out > lower_limit))) { + if (!limits_exist || (limits_exist && (out < upper_limit && out > lower_limit))) { accum_error += time_delta * get_error(); -} + } // I term out += config.i * accum_error; @@ -69,10 +64,8 @@ double PID::update(double sensor_val, double v_setpt) { // Enable clamping if the limit is not 0 if (limits_exist) { - out = (out < lower_limit) ? lower_limit - : (out > upper_limit) ? upper_limit - : out; -} + out = (out < lower_limit) ? lower_limit : (out > upper_limit) ? upper_limit : out; + } return out; } @@ -132,12 +125,11 @@ bool PID::is_on_target() { if (fabs(get_error()) < config.deadband) { if (target_vel != 0) { return true; -} + } if (is_checking_on_target == false) { on_target_last_time = pid_timer.value(); is_checking_on_target = true; - } else if (pid_timer.value() - on_target_last_time > - config.on_target_time) { + } else if (pid_timer.value() - on_target_last_time > config.on_target_time) { return true; } } else { diff --git a/src/utils/controls/pidff.cpp b/src/utils/controls/pidff.cpp index b98e356..ab03039 100644 --- a/src/utils/controls/pidff.cpp +++ b/src/utils/controls/pidff.cpp @@ -1,11 +1,10 @@ #include "../core/include/utils/controls/pidff.h" #include "../core/include/utils/math_util.h" -PIDFF::PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg) - : pid(pid_cfg), ff_cfg(ff_cfg), ff(ff_cfg) { - out = 0; - lower_lim = 0; - upper_lim = 0; +PIDFF::PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg) : pid(pid_cfg), ff_cfg(ff_cfg), ff(ff_cfg) { + out = 0; + lower_lim = 0; + upper_lim = 0; } /** @@ -14,9 +13,7 @@ PIDFF::PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg) * @param start_pt the current sensor value * @param set_pt where the sensor value should be */ -void PIDFF::init(double start_pt, double set_pt) { - pid.init(start_pt, set_pt); -} +void PIDFF::init(double start_pt, double set_pt) { pid.init(start_pt, set_pt); } void PIDFF::set_target(double set_pt) { pid.set_target(set_pt); } @@ -28,14 +25,14 @@ void PIDFF::set_target(double set_pt) { pid.set_target(set_pt); } * @return feedback loop result */ double PIDFF::update(double val) { - double pid_out = pid.update(val); - double ff_out = ff_cfg.kG + (ff_cfg.kS * sign(pid_out)); - out = pid_out + ff_out; - if (lower_lim != upper_lim) { - out = clamp(out, lower_lim, upper_lim); -} + double pid_out = pid.update(val); + double ff_out = ff_cfg.kG + (ff_cfg.kS * sign(pid_out)); + out = pid_out + ff_out; + if (lower_lim != upper_lim) { + out = clamp(out, lower_lim, upper_lim); + } - return out; + return out; } double PIDFF::get_sensor_val() const { return pid.get_sensor_val(); } @@ -51,14 +48,14 @@ double PIDFF::get_target() const { return pid.get_target(); } */ double PIDFF::update(double val, double vel_setpt, double a_setpt) { - double pid_out = pid.update(val); - double ff_out = ff.calculate(vel_setpt, a_setpt); - out = pid_out + ff_out; - if (lower_lim != upper_lim) { - out = clamp(out, lower_lim, upper_lim); -} + double pid_out = pid.update(val); + double ff_out = ff.calculate(vel_setpt, a_setpt); + out = pid_out + ff_out; + if (lower_lim != upper_lim) { + out = clamp(out, lower_lim, upper_lim); + } - return out; + return out; } /** @@ -74,8 +71,8 @@ double PIDFF::get() { return out; } * @param upper Lower limit */ void PIDFF::set_limits(double lower, double upper) { - upper_lim = upper; - lower_lim = lower; + upper_lim = upper; + lower_lim = lower; } /** diff --git a/src/utils/controls/take_back_half.cpp b/src/utils/controls/take_back_half.cpp index 72418df..2f8b2f8 100644 --- a/src/utils/controls/take_back_half.cpp +++ b/src/utils/controls/take_back_half.cpp @@ -1,84 +1,68 @@ #include "../core/include/utils/controls/take_back_half.h" #include "../core/include/utils/math_util.h" -TakeBackHalf::TakeBackHalf(double gain, double first_cross_split, double thresh) : TBH_gain(gain), first_cross_split(first_cross_split), on_target_threshhold(fabs(thresh)) -{ - tbh = 0.0; - output = 0.0; - prev_error = 0.0; - lower = 0.0; - upper = 0.0; - first_cross = true; +TakeBackHalf::TakeBackHalf(double gain, double first_cross_split, double thresh) + : TBH_gain(gain), first_cross_split(first_cross_split), on_target_threshhold(fabs(thresh)) { + tbh = 0.0; + output = 0.0; + prev_error = 0.0; + lower = 0.0; + upper = 0.0; + first_cross = true; } -void TakeBackHalf::init(double start_pt, double set_pt) -{ - if (set_pt == target) - { - // nothing to do - return; - } - first_cross = true; - tbh = output; - target = set_pt; - output = update(start_pt); +void TakeBackHalf::init(double start_pt, double set_pt) { + if (set_pt == target) { + // nothing to do + return; + } + first_cross = true; + tbh = output; + target = set_pt; + output = update(start_pt); } -double TakeBackHalf::update(double val) -{ - - if (target == 0.0) - { - printf("no target\n"); - return 0.0; - } - - double error = target - val; - output += TBH_gain * error; - - // taking back half crossed target - if (sign(error) != sign(prev_error)) - { - if (first_cross) - { - output = lerp(tbh, output, first_cross_split); - tbh = output; - first_cross = false; - printf("First cross\n"); - } - else - { - // output = .5 * (output + tbh); - output = lerp(tbh, output, .5); - tbh = output; - } - prev_error = error; +double TakeBackHalf::update(double val) { + + if (target == 0.0) { + printf("no target\n"); + return 0.0; + } + + double error = target - val; + output += TBH_gain * error; + + // taking back half crossed target + if (sign(error) != sign(prev_error)) { + if (first_cross) { + output = lerp(tbh, output, first_cross_split); + tbh = output; + first_cross = false; + printf("First cross\n"); + } else { + // output = .5 * (output + tbh); + output = lerp(tbh, output, .5); + tbh = output; } + prev_error = error; + } - if (lower != upper) - { - output = clamp(output, lower, upper); - } - return output; + if (lower != upper) { + output = clamp(output, lower, upper); + } + return output; } -double TakeBackHalf::get() -{ - return output; -} +double TakeBackHalf::get() { return output; } -void TakeBackHalf::set_limits(double low, double high) -{ +void TakeBackHalf::set_limits(double low, double high) { - lower = low; - upper = high; - printf("Set limits: %f, %f\n", lower, upper); + lower = low; + upper = high; + printf("Set limits: %f, %f\n", lower, upper); } -bool TakeBackHalf::is_on_target() -{ - return fabs(prev_error) < on_target_threshhold; -} +bool TakeBackHalf::is_on_target() { return fabs(prev_error) < on_target_threshhold; } // Runs a Take Back Half variant to control RPM // https://www.vexwiki.org/programming/controls_algorithms/tbh diff --git a/src/utils/controls/trapezoid_profile.cpp b/src/utils/controls/trapezoid_profile.cpp index c2fbfc7..58c3ea1 100644 --- a/src/utils/controls/trapezoid_profile.cpp +++ b/src/utils/controls/trapezoid_profile.cpp @@ -2,116 +2,95 @@ #include "../core/include/utils/math_util.h" #include +TrapezoidProfile::TrapezoidProfile(double max_v, double accel) : start(0), end(0), max_v(max_v), accel(accel) {} -TrapezoidProfile::TrapezoidProfile(double max_v, double accel) -: start(0), end(0), max_v(max_v), accel(accel) {} +void TrapezoidProfile::set_max_v(double max_v) { this->max_v = max_v; } -void TrapezoidProfile::set_max_v(double max_v) -{ - this->max_v = max_v; -} - -void TrapezoidProfile::set_accel(double accel) -{ - this->accel = accel; -} +void TrapezoidProfile::set_accel(double accel) { this->accel = accel; } -void TrapezoidProfile::set_endpts(double start, double end) -{ - this->start = start; - this->end = end; +void TrapezoidProfile::set_endpts(double start, double end) { + this->start = start; + this->end = end; } // Kinematic equations as macros -#define CALC_POS(time_s,a,v,s) ((0.5*(a)*(time_s)*(time_s))+((v)*(time_s))+(s)) -#define CALC_VEL(time_s,a,v) (((a)*(time_s))+(v)) +#define CALC_POS(time_s, a, v, s) ((0.5 * (a) * (time_s) * (time_s)) + ((v) * (time_s)) + (s)) +#define CALC_VEL(time_s, a, v) (((a) * (time_s)) + (v)) /** * @brief Run the trapezoidal profile based on the time that's ellapsed - * + * * @param time_s Time since start of movement * @return motion_t Position, velocity and acceleration */ -motion_t TrapezoidProfile::calculate(double time_s) -{ - double delta_pos = end - start; - - // redefine accel and max_v in this scope for negative calcs - double accel_local = this->accel; - double max_v_local = this->max_v; - if(delta_pos < 0) - { - accel_local = -this->accel; - max_v_local = -this->max_v; - } - - // Calculate the time spent during the acceleration / maximum velocity / deceleration stages - double accel_time = max_v_local / accel_local; - double max_vel_time = (delta_pos - (accel_local * accel_time * accel_time)) / max_v_local; - this->time = (2 * accel_time) + max_vel_time; - - // If the time during the "max velocity" state is negative, use an S profile - if (max_vel_time < 0) - { - accel_time = sqrt(fabs(delta_pos / accel)); - max_vel_time = 0; - this->time = 2 * accel_time; - } - - motion_t out; - - // Handle if a bad time is put in - if (time_s < 0) - { - out.pos = start; - out.vel = 0; - out.accel = 0; - return out; - } - - // Handle after the setpoint is reached - if (time_s > 2*accel_time + max_vel_time) - { - out.pos = end; - out.vel = 0; - out.accel = 0; - return out; - } - - // ======== KINEMATIC EQUATIONS ======== - - // Displacement from initial acceleration - if(time_s < accel_time) - { - out.pos = start + CALC_POS(time_s, accel_local, 0, 0); - out.vel = CALC_VEL(time_s, accel_local, 0); - out.accel = accel_local; - return out; - } - - double s_accel = CALC_POS(accel_time, accel_local, 0, 0); - - // Displacement during maximum velocity - if (time_s < accel_time + max_vel_time) - { - out.pos = start + CALC_POS(time_s - accel_time, 0, max_v_local, s_accel); - out.vel = sign(delta_pos) * max_v; - out.accel = 0; - return out; - } - - double s_max_vel = CALC_POS(max_vel_time, 0, max_v_local, s_accel); - - // Displacement during deceleration - out.pos = start + CALC_POS(time_s - (2*accel_time) - max_vel_time, -accel_local, 0, s_accel + s_max_vel); - out.vel = CALC_VEL(time_s - accel_time - max_vel_time, -accel_local, max_v_local); - out.accel = -accel_local; +motion_t TrapezoidProfile::calculate(double time_s) { + double delta_pos = end - start; + + // redefine accel and max_v in this scope for negative calcs + double accel_local = this->accel; + double max_v_local = this->max_v; + if (delta_pos < 0) { + accel_local = -this->accel; + max_v_local = -this->max_v; + } + + // Calculate the time spent during the acceleration / maximum velocity / deceleration stages + double accel_time = max_v_local / accel_local; + double max_vel_time = (delta_pos - (accel_local * accel_time * accel_time)) / max_v_local; + this->time = (2 * accel_time) + max_vel_time; + + // If the time during the "max velocity" state is negative, use an S profile + if (max_vel_time < 0) { + accel_time = sqrt(fabs(delta_pos / accel)); + max_vel_time = 0; + this->time = 2 * accel_time; + } + + motion_t out; + + // Handle if a bad time is put in + if (time_s < 0) { + out.pos = start; + out.vel = 0; + out.accel = 0; return out; + } -} + // Handle after the setpoint is reached + if (time_s > 2 * accel_time + max_vel_time) { + out.pos = end; + out.vel = 0; + out.accel = 0; + return out; + } + + // ======== KINEMATIC EQUATIONS ======== + + // Displacement from initial acceleration + if (time_s < accel_time) { + out.pos = start + CALC_POS(time_s, accel_local, 0, 0); + out.vel = CALC_VEL(time_s, accel_local, 0); + out.accel = accel_local; + return out; + } + + double s_accel = CALC_POS(accel_time, accel_local, 0, 0); + + // Displacement during maximum velocity + if (time_s < accel_time + max_vel_time) { + out.pos = start + CALC_POS(time_s - accel_time, 0, max_v_local, s_accel); + out.vel = sign(delta_pos) * max_v; + out.accel = 0; + return out; + } + + double s_max_vel = CALC_POS(max_vel_time, 0, max_v_local, s_accel); -double TrapezoidProfile::get_movement_time() -{ - return time; + // Displacement during deceleration + out.pos = start + CALC_POS(time_s - (2 * accel_time) - max_vel_time, -accel_local, 0, s_accel + s_max_vel); + out.vel = CALC_VEL(time_s - accel_time - max_vel_time, -accel_local, max_v_local); + out.accel = -accel_local; + return out; } +double TrapezoidProfile::get_movement_time() { return time; } diff --git a/src/utils/generic_auto.cpp b/src/utils/generic_auto.cpp index 1ac9dcd..c6984a3 100644 --- a/src/utils/generic_auto.cpp +++ b/src/utils/generic_auto.cpp @@ -1,65 +1,60 @@ #include "../core/include/utils/generic_auto.h" /** -* The method that runs the autonomous. If 'blocking' is true, then -* this method will run through every state until it finished. -* -* If blocking is false, then assuming every state is also non-blocking, -* the method will run through the current state in the list and return -* immediately. -* -* @param blocking -* Whether or not to block the thread until all states have run -* @returns -* true after all states have finished. -*/ -bool GenericAuto::run(bool blocking) -{ - if(state_list.empty()) { - return true; -} + * The method that runs the autonomous. If 'blocking' is true, then + * this method will run through every state until it finished. + * + * If blocking is false, then assuming every state is also non-blocking, + * the method will run through the current state in the list and return + * immediately. + * + * @param blocking + * Whether or not to block the thread until all states have run + * @returns + * true after all states have finished. + */ +bool GenericAuto::run(bool blocking) { + if (state_list.empty()) { + return true; + } - do - { - if( state_list.front()() ) { - state_list.pop(); -} + do { + if (state_list.front()()) { + state_list.pop(); + } - if(blocking) { - vexDelay(20); -} + if (blocking) { + vexDelay(20); + } - } while(blocking && !state_list.empty()); + } while (blocking && !state_list.empty()); // If the method is blocking, return true because it's finished // If non-blocking, return false because the list isn't empty yet return blocking; } -void GenericAuto::add(state_ptr new_state) -{ - state_list.push(new_state); -} +void GenericAuto::add(state_ptr new_state) { state_list.push(new_state); } -void GenericAuto::add_async(state_ptr async_state) -{ - state_ptr fn = [&async_state](){ - vex::task t([](void* fn_ptr){ - while(! (*(state_ptr*)fn_ptr)() ) { - vexDelay(20); -} +void GenericAuto::add_async(state_ptr async_state) { + state_ptr fn = [&async_state]() { + vex::task t( + [](void *fn_ptr) { + while (!(*(state_ptr *)fn_ptr)()) { + vexDelay(20); + } - return 0; - }, &async_state); + return 0; + }, + &async_state); return true; }; state_list.push(fn); } -void GenericAuto::add_delay(int ms) -{ - add([ms](){ +void GenericAuto::add_delay(int ms) { + add([ms]() { vexDelay(ms); return true; }); diff --git a/src/utils/graph_drawer.cpp b/src/utils/graph_drawer.cpp index 5621d99..57f830f 100644 --- a/src/utils/graph_drawer.cpp +++ b/src/utils/graph_drawer.cpp @@ -6,68 +6,58 @@ /// @param upper_bound the top of the window when displaying (if upper_bound = lower_bound, auto calculate bounds) /// @param colors the colors of the series. must be of size num_series /// @param num_series the number of series to graph -GraphDrawer::GraphDrawer(int num_samples, double lower_bound, double upper_bound, std::vector colors, size_t num_series) : cols(colors), auto_fit(lower_bound == upper_bound) -{ - if (colors.size() != num_series) - { - printf("The number of colors does not match the number of series in graph drawer\n"); - } - series = std::vector>(num_series); - for (size_t i = 0; i < num_series; i++) - { - series[i] = std::vector(num_samples, {0.0, 0.0}); - } +GraphDrawer::GraphDrawer(int num_samples, double lower_bound, double upper_bound, std::vector colors, + size_t num_series) + : cols(colors), auto_fit(lower_bound == upper_bound) { + if (colors.size() != num_series) { + printf("The number of colors does not match the number of series in graph drawer\n"); + } + series = std::vector>(num_series); + for (size_t i = 0; i < num_series; i++) { + series[i] = std::vector(num_samples, {0.0, 0.0}); + } - if (auto_fit) - { - upper = -1000.0; - lower = 1000.0; - } else { - upper = upper_bound; - lower = lower_bound; - } + if (auto_fit) { + upper = -1000.0; + lower = 1000.0; + } else { + upper = upper_bound; + lower = lower_bound; + } } /** * add_samples adds a point to the graph, removing one from the back * @param sample an x, y coordinate of the next point to graph */ -void GraphDrawer::add_samples(std::vector new_samples) -{ - if (series.size() != new_samples.size()) - { - printf("Mismatch between # of samples given and number of series. %s : %d\n", __FILE__, __LINE__); +void GraphDrawer::add_samples(std::vector new_samples) { + if (series.size() != new_samples.size()) { + printf("Mismatch between # of samples given and number of series. %s : %d\n", __FILE__, __LINE__); + } + for (size_t i = 0; i < series.size(); i++) { + series[i][sample_index] = new_samples[i]; + if (auto_fit) { + upper = fmax(upper, new_samples[i].y); + lower = fmin(lower, new_samples[i].y); } - for (size_t i = 0; i < series.size(); i++) - { - series[i][sample_index] = new_samples[i]; - if (auto_fit) - { - upper = fmax(upper, new_samples[i].y); - lower = fmin(lower, new_samples[i].y); - } - } - sample_index++; - sample_index %= series[0].size(); + } + sample_index++; + sample_index %= series[0].size(); } -void GraphDrawer::add_samples(std::vector new_samples) -{ - if (series.size() != new_samples.size()) - { - printf("Mismatch between # of samples given and number of series. %s : %d\n", __FILE__, __LINE__); - } - for (size_t i = 0; i < series.size(); i++) - { - series[i][sample_index] = {(double)vex::timer::system(), new_samples[i]}; - if (auto_fit) - { - upper = fmax(upper, new_samples[i]); - lower = fmin(lower, new_samples[i]); - } +void GraphDrawer::add_samples(std::vector new_samples) { + if (series.size() != new_samples.size()) { + printf("Mismatch between # of samples given and number of series. %s : %d\n", __FILE__, __LINE__); + } + for (size_t i = 0; i < series.size(); i++) { + series[i][sample_index] = {(double)vex::timer::system(), new_samples[i]}; + if (auto_fit) { + upper = fmax(upper, new_samples[i]); + lower = fmin(lower, new_samples[i]); } - sample_index++; - sample_index %= series[0].size(); + } + sample_index++; + sample_index %= series[0].size(); } /** @@ -77,61 +67,54 @@ void GraphDrawer::add_samples(std::vector new_samples) * @param width the width of the graphed region * @param height the height of the graphed region */ -void GraphDrawer::draw(vex::brain::lcd &screen, int x, int y, int width, int height) -{ - if (series[0].size() < 1) - { - return; - } - if (cols.size() != series.size()) - { - printf("The number of colors does not match the number of series in graph drawer\n"); - } +void GraphDrawer::draw(vex::brain::lcd &screen, int x, int y, int width, int height) { + if (series[0].size() < 1) { + return; + } + if (cols.size() != series.size()) { + printf("The number of colors does not match the number of series in graph drawer\n"); + } - size_t newest_index = (sample_index-1); - if (sample_index<0){ - sample_index+=series[0].size(); - } + size_t newest_index = (sample_index - 1); + if (sample_index < 0) { + sample_index += series[0].size(); + } - double earliest_time = series[0][sample_index].x; - double latest_time = series[0][newest_index].x; - // collect data - if (std::abs(latest_time - earliest_time) < 0.001) - { - screen.printAt(width / 2, height / 2, "Not enough Data"); - return; - } + double earliest_time = series[0][sample_index].x; + double latest_time = series[0][newest_index].x; + // collect data + if (std::abs(latest_time - earliest_time) < 0.001) { + screen.printAt(width / 2, height / 2, "Not enough Data"); + return; + } - if (border) - { - screen.setPenWidth(1); - screen.setPenColor(vex::white); - screen.setFillColor(bgcol); - screen.drawRectangle(x, y, width, height); - } + if (border) { + screen.setPenWidth(1); + screen.setPenColor(vex::white); + screen.setFillColor(bgcol); + screen.drawRectangle(x, y, width, height); + } - double time_range = latest_time - earliest_time; - double sample_range = upper - lower; - screen.setPenWidth(2); + double time_range = latest_time - earliest_time; + double sample_range = upper - lower; + screen.setPenWidth(2); - for (int j = 0; j < series.size(); j++) - { - double x_s = (double)x; - double y_s = (double)y + (double)height; - const std::vector &samples = series[j]; + for (int j = 0; j < series.size(); j++) { + double x_s = (double)x; + double y_s = (double)y + (double)height; + const std::vector &samples = series[j]; - screen.setPenColor(cols[j]); - for (int i = sample_index; i < samples.size() + sample_index - 1; i++) - { - point_t p = samples[i % samples.size()]; - double x_pos = x_s + ((p.x - earliest_time) / time_range) * (double)width; - double y_pos = y_s + ((p.y - lower) / sample_range) * (double)(-height); + screen.setPenColor(cols[j]); + for (int i = sample_index; i < samples.size() + sample_index - 1; i++) { + point_t p = samples[i % samples.size()]; + double x_pos = x_s + ((p.x - earliest_time) / time_range) * (double)width; + double y_pos = y_s + ((p.y - lower) / sample_range) * (double)(-height); - point_t p2 = samples[(i + 1) % samples.size()]; - double x_pos2 = x_s + ((p2.x - earliest_time) / time_range) * (double)width; - double y_pos2 = y_s + ((p2.y - lower) / sample_range) * (double)(-height); + point_t p2 = samples[(i + 1) % samples.size()]; + double x_pos2 = x_s + ((p2.x - earliest_time) / time_range) * (double)width; + double y_pos2 = y_s + ((p2.y - lower) / sample_range) * (double)(-height); - screen.drawLine((int)x_pos, (int)y_pos, (int)x_pos2, (int)y_pos2); - } + screen.drawLine((int)x_pos, (int)y_pos, (int)x_pos2, (int)y_pos2); } + } } diff --git a/src/utils/logger.cpp b/src/utils/logger.cpp index 65ff58d..5e35b90 100644 --- a/src/utils/logger.cpp +++ b/src/utils/logger.cpp @@ -1,84 +1,71 @@ #include "../core/include/utils/logger.h" #include -void Logger::write_level(LogLevel l) -{ - unsigned char *debug = (unsigned char *)"DEBUG: "; - unsigned char *notice = (unsigned char *)"NOTICE: "; - unsigned char *warning = (unsigned char *)"WARNING: "; - unsigned char *error = (unsigned char *)"ERROR: "; - unsigned char *critical = (unsigned char *)"CRITICAL: "; - switch (l) - { - case DEBUG: - sd.appendfile(filename.c_str(), debug, 7); - break; - case NOTICE: - sd.appendfile(filename.c_str(), notice, 8); - break; - case WARNING: - sd.appendfile(filename.c_str(), warning, 9); - break; - case ERROR: - sd.appendfile(filename.c_str(), error, 7); - break; - case CRITICAL: - sd.appendfile(filename.c_str(), critical, 10); - break; - case TIME: - int32_t msec = vexSystemTimeGet(); - Logf("%d: ", msec); - break; - }; +void Logger::write_level(LogLevel l) { + unsigned char *debug = (unsigned char *)"DEBUG: "; + unsigned char *notice = (unsigned char *)"NOTICE: "; + unsigned char *warning = (unsigned char *)"WARNING: "; + unsigned char *error = (unsigned char *)"ERROR: "; + unsigned char *critical = (unsigned char *)"CRITICAL: "; + switch (l) { + case DEBUG: + sd.appendfile(filename.c_str(), debug, 7); + break; + case NOTICE: + sd.appendfile(filename.c_str(), notice, 8); + break; + case WARNING: + sd.appendfile(filename.c_str(), warning, 9); + break; + case ERROR: + sd.appendfile(filename.c_str(), error, 7); + break; + case CRITICAL: + sd.appendfile(filename.c_str(), critical, 10); + break; + case TIME: + int32_t msec = vexSystemTimeGet(); + Logf("%d: ", msec); + break; + }; } -Logger::Logger(const std::string &filename) : filename(filename) { - sd.savefile(filename.c_str(), NULL, 0); -} +Logger::Logger(const std::string &filename) : filename(filename) { sd.savefile(filename.c_str(), NULL, 0); } -void Logger::Log(const std::string &s) -{ - sd.appendfile(filename.c_str(), (unsigned char *)s.c_str(), s.size()); -} -void Logger::Log(LogLevel level, const std::string &s) -{ - write_level(level); - sd.appendfile(filename.c_str(), (unsigned char *)s.c_str(), s.size()); +void Logger::Log(const std::string &s) { sd.appendfile(filename.c_str(), (unsigned char *)s.c_str(), s.size()); } +void Logger::Log(LogLevel level, const std::string &s) { + write_level(level); + sd.appendfile(filename.c_str(), (unsigned char *)s.c_str(), s.size()); } -void Logger::Logln(const std::string &s) -{ - sd.appendfile(filename.c_str(), (unsigned char *)s.c_str(), s.size()); - unsigned char newline = '\n'; - sd.appendfile(filename.c_str(), &newline, 1); +void Logger::Logln(const std::string &s) { + sd.appendfile(filename.c_str(), (unsigned char *)s.c_str(), s.size()); + unsigned char newline = '\n'; + sd.appendfile(filename.c_str(), &newline, 1); } -void Logger::Logln(LogLevel level, const std::string &s) -{ - write_level(level); - Logln(s); +void Logger::Logln(LogLevel level, const std::string &s) { + write_level(level); + Logln(s); } -void Logger::Logf(const char *fmt, ...) -{ - char buf[MAX_FORMAT_LEN]; - va_list args; - va_start(args, fmt); - - int32_t written = vex_vsnprintf(buf, MAX_FORMAT_LEN, fmt, args); +void Logger::Logf(const char *fmt, ...) { + char buf[MAX_FORMAT_LEN]; + va_list args; + va_start(args, fmt); - va_end(args); - sd.appendfile(filename.c_str(), (unsigned char *)buf, written); + int32_t written = vex_vsnprintf(buf, MAX_FORMAT_LEN, fmt, args); + va_end(args); + sd.appendfile(filename.c_str(), (unsigned char *)buf, written); } -void Logger::Logf(LogLevel level, const char *fmt, ...) -{ - char buf[MAX_FORMAT_LEN]; +void Logger::Logf(LogLevel level, const char *fmt, ...) { + char buf[MAX_FORMAT_LEN]; - write_level(level); - va_list args; - va_start(args, fmt); - int32_t written = vex_vsnprintf(buf, MAX_FORMAT_LEN, fmt, args); - va_end(args); + write_level(level); + va_list args; + va_start(args, fmt); + int32_t written = vex_vsnprintf(buf, MAX_FORMAT_LEN, fmt, args); + va_end(args); - sd.appendfile(filename.c_str(), (unsigned char *)buf, written); + sd.appendfile(filename.c_str(), (unsigned char *)buf, written); } diff --git a/src/utils/math_util.cpp b/src/utils/math_util.cpp index ba4f394..03954a4 100644 --- a/src/utils/math_util.cpp +++ b/src/utils/math_util.cpp @@ -12,23 +12,16 @@ * @param low the minimum value that will be returned * @param high the maximum value that will be returned **/ -double clamp(double val, double low, double high) -{ - if (val < low) - { +double clamp(double val, double low, double high) { + if (val < low) { return low; - } - else if (val > high) - { + } else if (val > high) { return high; } return val; } -double lerp(double a, double b, double t) -{ - return a * (1.0 - t) + b * t; -} +double lerp(double a, double b, double t) { return a * (1.0 - t) + b * t; } /** * Returns the sign of a number @@ -36,31 +29,27 @@ double lerp(double a, double b, double t) * * returns the sign +/-1 of x. special case at 0 it returns +1 **/ -double sign(double x) -{ - if (x < 0) - { +double sign(double x) { + if (x < 0) { return -1; } return 1; } -double wrap_angle_deg(double input) -{ +double wrap_angle_deg(double input) { double angle = fmod(input, 360); if (angle < 0) { angle += 360; -} + } return angle; } -double wrap_angle_rad(double input) -{ +double wrap_angle_rad(double input) { double angle = fmod(input, 2 * PI); if (angle < 0) { angle += 2 * PI; -} + } return angle; } @@ -68,11 +57,9 @@ double wrap_angle_rad(double input) Calculates the average of a vector of doubles @param values the list of values for which the average is taken */ -double mean(std::vector const &values) -{ +double mean(std::vector const &values) { double total = 0; - for (int i = 0; i < values.size(); i++) - { + for (int i = 0; i < values.size(); i++) { total += values[i]; } return total / (double)values.size(); @@ -84,11 +71,9 @@ Calculates the variance of a set of numbers (needed for linear regression) @param values the values for which the covariance is taken @param mean the average of values */ -double variance(std::vector const &values, double mean) -{ +double variance(std::vector const &values, double mean) { double total = 0.0; - for (int i = 0; i < values.size(); i++) - { + for (int i = 0; i < values.size(); i++) { total += (values[i] - mean) * (values[i] - mean); } return total / (values.size() - 1); @@ -103,11 +88,9 @@ Calculates the covariance of a set of points (needed for linear regression) @param meanx the mean value of all x coordinates in points @param meany the mean value of all y coordinates in points */ -double covariance(std::vector> const &points, double meanx, double meany) -{ +double covariance(std::vector> const &points, double meanx, double meany) { double covar = 0.0; - for (int i = 0; i < points.size(); i++) - { + for (int i = 0; i < points.size(); i++) { covar += (points[i].first - meanx) * (points[i].second - meany); } return covar; @@ -118,13 +101,12 @@ double covariance(std::vector> const &points, double m * @param points the points for the data * @return slope, y intercept. y = m(x)+b. std::pair */ -std::pair calculate_linear_regression(std::vector> const &points) -{ - // Purely for convenience and the ability to reuse mean() and variance() - can be easily rewritten to avoid allocating these if the code is repeatedly called +std::pair calculate_linear_regression(std::vector> const &points) { + // Purely for convenience and the ability to reuse mean() and variance() - can be easily rewritten to avoid allocating + // these if the code is repeatedly called std::vector xs(points.size(), 0.0); std::vector ys(points.size(), 0.0); - for (int i = 0; i < points.size(); i++) - { + for (int i = 0; i < points.size(); i++) { xs[i] = points[i].first; ys[i] = points[i].second; } @@ -138,18 +120,16 @@ std::pair calculate_linear_regression(std::vector(slope, y_intercept); } -double estimate_path_length(const std::vector &points) -{ +double estimate_path_length(const std::vector &points) { double dist = 0; - for (point_t p : points) - { + for (point_t p : points) { static point_t last_p = p; // Ignore the first point if (p == last_p) { continue; -} + } dist += p.dist(last_p); last_p = p; diff --git a/src/utils/moving_average.cpp b/src/utils/moving_average.cpp index 1073776..14803a6 100644 --- a/src/utils/moving_average.cpp +++ b/src/utils/moving_average.cpp @@ -1,17 +1,19 @@ -#include #include "../core/include/utils/moving_average.h" #include +#include /* * MovingAverage * - * A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. - * This means that if you collect enough samples those that are too high are cancelled out by the samples that are too low leaving the real value. + * A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric + * around the actual value. This means that if you collect enough samples those that are too high are cancelled out by + * the samples that are too low leaving the real value. * * The MovingAverage class provides a simple interface to do this smoothing from our noisy sensor values. * - * WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' behind the actual value that the sensor is reading. - * Using a MovingAverage is thus a tradeoff between accuracy and lag time (more samples) vs. less accuracy and faster updating (less samples). + * WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' + * behind the actual value that the sensor is reading. Using a MovingAverage is thus a tradeoff between accuracy and lag + * time (more samples) vs. less accuracy and faster updating (less samples). * */ @@ -20,8 +22,7 @@ * * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading */ -MovingAverage::MovingAverage(int buffer_size) -{ +MovingAverage::MovingAverage(int buffer_size) { buffer = std::vector(buffer_size, 0.0); buffer_index = 0; current_avg = 0; @@ -32,8 +33,7 @@ MovingAverage::MovingAverage(int buffer_size) * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading * @param starting_value The value that the average will be before any data is added */ -MovingAverage::MovingAverage(int buffer_size, double starting_value) -{ +MovingAverage::MovingAverage(int buffer_size, double starting_value) { buffer = std::vector(buffer_size, starting_value); buffer_index = 0; current_avg = starting_value; @@ -49,8 +49,7 @@ MovingAverage::MovingAverage(int buffer_size, double starting_value) * ^ * @param n the sample that will be added to the moving average. */ -void MovingAverage::add_entry(double n) -{ +void MovingAverage::add_entry(double n) { current_avg -= buffer[buffer_index] / (double)get_size(); current_avg += n / get_size(); buffer[buffer_index] = n; @@ -63,24 +62,17 @@ void MovingAverage::add_entry(double n) * How many samples the average is made from * @return the number of samples used to calculate this average */ -double MovingAverage::get_value() const -{ - return current_avg; -} +double MovingAverage::get_value() const { return current_avg; } // How many samples the average is made from -int MovingAverage::get_size() const -{ - return buffer.size(); -} +int MovingAverage::get_size() const { return buffer.size(); } /** * Create a moving average calculator with 0 as the default value * * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading */ -ExponentialMovingAverage::ExponentialMovingAverage(int buffer_size) -{ +ExponentialMovingAverage::ExponentialMovingAverage(int buffer_size) { buffer = std::vector(buffer_size, 0.0); buffer_index = 0; current_avg = 0; @@ -91,8 +83,7 @@ ExponentialMovingAverage::ExponentialMovingAverage(int buffer_size) * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading * @param starting_value The value that the average will be before any data is added */ -ExponentialMovingAverage::ExponentialMovingAverage(int buffer_size, double starting_value) -{ +ExponentialMovingAverage::ExponentialMovingAverage(int buffer_size, double starting_value) { buffer = std::vector(buffer_size, starting_value); buffer_index = 0; current_avg = starting_value; @@ -108,8 +99,7 @@ ExponentialMovingAverage::ExponentialMovingAverage(int buffer_size, double start * ^ * @param n the sample that will be added to the moving average. */ -void ExponentialMovingAverage::add_entry(double n) -{ +void ExponentialMovingAverage::add_entry(double n) { int oldest_index = buffer_index; double oldest_sample = buffer[oldest_index]; double oldest_weight = 1.0 / pow(2, (double)(buffer.size() - 1)); @@ -131,13 +121,7 @@ void ExponentialMovingAverage::add_entry(double n) * How many samples the average is made from * @return the number of samples used to calculate this average */ -double ExponentialMovingAverage::get_value() const -{ - return current_avg; -} +double ExponentialMovingAverage::get_value() const { return current_avg; } // How many samples the average is made from -int ExponentialMovingAverage::get_size() -{ - return buffer.size(); -} +int ExponentialMovingAverage::get_size() { return buffer.size(); } diff --git a/src/utils/pure_pursuit.cpp b/src/utils/pure_pursuit.cpp index ffdd36b..b33e4e1 100644 --- a/src/utils/pure_pursuit.cpp +++ b/src/utils/pure_pursuit.cpp @@ -10,26 +10,28 @@ PurePursuit::Path::Path(std::vector points, double radius) { this->radius = radius; this->valid = true; - for(int i = 0; i < points.size() - 1; i++) { - for(int j = i + 2; j < points.size() - 1; j++) { + for (int i = 0; i < points.size() - 1; i++) { + for (int j = i + 2; j < points.size() - 1; j++) { // Iterate over points on the segments discretely and compare distances - double segment_i_dist = points[i].dist(points[i+1]); - if (segment_i_dist == 0) { segment_i_dist = 0.1; -} - double segment_j_dist = points[j].dist(points[j+1]); - if (segment_j_dist == 0) { segment_j_dist = 0.1; -} - for(double t1 = 0; t1 <= 1; t1 += radius / segment_i_dist) { + double segment_i_dist = points[i].dist(points[i + 1]); + if (segment_i_dist == 0) { + segment_i_dist = 0.1; + } + double segment_j_dist = points[j].dist(points[j + 1]); + if (segment_j_dist == 0) { + segment_j_dist = 0.1; + } + for (double t1 = 0; t1 <= 1; t1 += radius / segment_i_dist) { point_t p1; - p1.x = points[i].x + t1 * (points[i+1].x - points[i].x); - p1.y = points[i].y + t1 * (points[i+1].y - points[i].y); + p1.x = points[i].x + t1 * (points[i + 1].x - points[i].x); + p1.y = points[i].y + t1 * (points[i + 1].y - points[i].y); - for(double t2 = 0; t2 <= 1; t2 += radius / segment_j_dist) { + for (double t2 = 0; t2 <= 1; t2 += radius / segment_j_dist) { point_t p2; - p2.x = points[j].x + t2 * (points[j+1].x - points[j].x); - p2.y = points[j].y + t2 * (points[j+1].y - points[j].y); + p2.x = points[j].x + t2 * (points[j + 1].x - points[j].x); + p2.y = points[j].y + t2 * (points[j + 1].y - points[j].y); - if(p1.dist(p2) < radius) { + if (p1.dist(p2) < radius) { this->valid = false; return; } @@ -42,67 +44,59 @@ PurePursuit::Path::Path(std::vector points, double radius) { /** * Get the points associated with this Path */ -std::vector PurePursuit::Path::get_points() { - return this->points; -} +std::vector PurePursuit::Path::get_points() { return this->points; } /** * Get the radius associated with this Path */ -double PurePursuit::Path::get_radius() { - return this->radius; -} +double PurePursuit::Path::get_radius() { return this->radius; } /** * Get whether this path will behave as expected */ -bool PurePursuit::Path::is_valid() { - return this->valid; -} +bool PurePursuit::Path::is_valid() { return this->valid; } /** - * Returns points of the intersections of a line segment and a circle. The line - * segment is defined by two points, and the circle is defined by a center and radius. - */ -std::vector PurePursuit::line_circle_intersections(point_t center, double r, point_t point1, point_t point2) -{ + * Returns points of the intersections of a line segment and a circle. The line + * segment is defined by two points, and the circle is defined by a center and radius. + */ +std::vector PurePursuit::line_circle_intersections(point_t center, double r, point_t point1, point_t point2) { std::vector intersections = {}; - //Do future calculations relative to the circle's center + // Do future calculations relative to the circle's center point1.y -= center.y; point1.x -= center.x; point2.y -= center.y; point2.x -= center.x; double x1, x2, y1, y2; - //Handling an infinite slope using mx+b and x^2 + y^2 = r^2 - if(point1.x - point2.x == 0) - { + // Handling an infinite slope using mx+b and x^2 + y^2 = r^2 + if (point1.x - point2.x == 0) { x1 = point1.x; y1 = sqrt(pow(r, 2) - pow(x1, 2)); x2 = point1.x; y2 = -sqrt(pow(r, 2) - pow(x2, 2)); } - //Non-infinite slope using mx+b and x^2 + y^2 = r^2 - else - { + // Non-infinite slope using mx+b and x^2 + y^2 = r^2 + else { double m = (point1.y - point2.y) / (point1.x - point2.x); double b = point1.y - (m * point1.x); - x1 = ((-m * b) + sqrt(pow(r, 2) + (pow(m, 2) * pow(r, 2)) - pow(b, 2))) / (1 + pow(m,2)); + x1 = ((-m * b) + sqrt(pow(r, 2) + (pow(m, 2) * pow(r, 2)) - pow(b, 2))) / (1 + pow(m, 2)); y1 = m * x1 + b; - x2 = ((-m * b) - sqrt(pow(r, 2) + (pow(m, 2) * pow(r, 2)) - pow(b, 2))) / (1 + pow(m,2)); + x2 = ((-m * b) - sqrt(pow(r, 2) + (pow(m, 2) * pow(r, 2)) - pow(b, 2))) / (1 + pow(m, 2)); y2 = m * x2 + b; } - //The equations used define an infinitely long line, so we check if the detected intersection falls on the line segment. - if(x1 >= fmin(point1.x, point2.x) && x1 <= fmax(point1.x, point2.x) && y1 >= fmin(point1.y, point2.y) && y1 <= fmax(point1.y, point2.y)) - { + // The equations used define an infinitely long line, so we check if the detected intersection falls on the line + // segment. + if (x1 >= fmin(point1.x, point2.x) && x1 <= fmax(point1.x, point2.x) && y1 >= fmin(point1.y, point2.y) && + y1 <= fmax(point1.y, point2.y)) { intersections.push_back(point_t{.x = x1 + center.x, .y = y1 + center.y}); } - if(x2 >= fmin(point1.x, point2.x) && x2 <= fmax(point1.x, point2.x) && y2 >= fmin(point1.y, point2.y) && y2 <= fmax(point1.y, point2.y)) - { + if (x2 >= fmin(point1.x, point2.x) && x2 <= fmax(point1.x, point2.x) && y2 >= fmin(point1.y, point2.y) && + y2 <= fmax(point1.y, point2.y)) { intersections.push_back(point_t{.x = x2 + center.x, .y = y2 + center.y}); } @@ -112,31 +106,26 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub /** * Selects a look ahead from all the intersections in the path. */ -[[maybe_unused]] point_t PurePursuit::get_lookahead(const std::vector &path, pose_t robot_loc, double radius) -{ - //Default: the end of the path +[[maybe_unused]] point_t PurePursuit::get_lookahead(const std::vector &path, pose_t robot_loc, double radius) { + // Default: the end of the path point_t target = path.back(); - - if(target.dist(robot_loc.get_point()) <= radius) - { + if (target.dist(robot_loc.get_point()) <= radius) { return target; } - - //Check each line segment of the path for potential targets - for(int i = 0; i < path.size() - 1; i++) - { + + // Check each line segment of the path for potential targets + for (int i = 0; i < path.size() - 1; i++) { point_t start = path[i]; - point_t end = path[i+1]; + point_t end = path[i + 1]; std::vector intersections = line_circle_intersections(robot_loc.get_point(), radius, start, end); - //Choose the intersection that is closest to the end of the line segment - //This prioritizes the closest intersection to the end of the path - for(point_t intersection: intersections) - { - if(intersection.dist(end) < target.dist(end)) { + // Choose the intersection that is closest to the end of the line segment + // This prioritizes the closest intersection to the end of the path + for (point_t intersection : intersections) { + if (intersection.dist(end) < target.dist(end)) { target = intersection; -} + } } } @@ -146,32 +135,29 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub /** Injects points in a path without changing the curvature with a certain spacing. */ -[[maybe_unused]] std::vector PurePursuit::inject_path(const std::vector &path, double spacing) -{ +[[maybe_unused]] std::vector PurePursuit::inject_path(const std::vector &path, double spacing) { std::vector new_path; - //Injecting points for each line segment - for(int i = 0; i < path.size() - 1; i++) - { + // Injecting points for each line segment + for (int i = 0; i < path.size() - 1; i++) { point_t start = path[i]; - point_t end = path[i+1]; + point_t end = path[i + 1]; point_t diff = end - start; Vector2D vector = Vector2D(diff); - + int num_points = ceil(vector.get_mag() / spacing); - //This is the vector between each point + // This is the vector between each point vector = vector.normalize() * spacing; - for(int j = 0; j < num_points; j++) - { - //We take the start point and add additional vectors + for (int j = 0; j < num_points; j++) { + // We take the start point and add additional vectors point_t path_point = (Vector2D(start) + vector * j).point(); new_path.push_back(path_point); } } - //Adds the last point + // Adds the last point new_path.push_back(path.back()); return new_path; } @@ -185,28 +171,26 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub * * Honestly have no idea if/how this works. * https://medium.com/@jaems33/understanding-robot-motion-path-smoothing-5970c8363bc4 -*/ -[[maybe_unused]] std::vector PurePursuit::smooth_path(const std::vector &path, double weight_data, double weight_smooth, double tolerance) -{ + */ +[[maybe_unused]] std::vector PurePursuit::smooth_path(const std::vector &path, double weight_data, + double weight_smooth, double tolerance) { std::vector new_path = path; double change = tolerance; - while(change >= tolerance) - { + while (change >= tolerance) { change = 0; - for(int i = 1; i < path.size() - 1; i++) - { - point_t x_i = path[i]; - point_t y_i = new_path[i]; - point_t y_prev = new_path[i-1]; - point_t y_next = new_path[i+1]; - - point_t y_i_saved = y_i; - - y_i.x += weight_data * (x_i.x - y_i.x) + weight_smooth * (y_next.x + y_prev.x - (2 * y_i.x)); - y_i.y += weight_data * (x_i.y - y_i.y) + weight_smooth * (y_next.y + y_prev.y - (2 * y_i.y)); - new_path[i] = y_i; - - change += y_i.dist(y_i_saved); + for (int i = 1; i < path.size() - 1; i++) { + point_t x_i = path[i]; + point_t y_i = new_path[i]; + point_t y_prev = new_path[i - 1]; + point_t y_next = new_path[i + 1]; + + point_t y_i_saved = y_i; + + y_i.x += weight_data * (x_i.x - y_i.x) + weight_smooth * (y_next.x + y_prev.x - (2 * y_i.x)); + y_i.y += weight_data * (x_i.y - y_i.y) + weight_smooth * (y_next.y + y_prev.y - (2 * y_i.y)); + new_path[i] = y_i; + + change += y_i.dist(y_i_saved); } } return new_path; @@ -220,78 +204,73 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub * @param steps The number of points interpolated between points. * @return The smoothed path. */ -[[maybe_unused]] std::vector PurePursuit::smooth_path_hermite(const std::vector &path, double steps) { +[[maybe_unused]] std::vector PurePursuit::smooth_path_hermite(const std::vector &path, + double steps) { std::vector new_path; - for(int i = 0; i < path.size() - 1; i++) { - for(int t = 0; t < steps; t++) { + for (int i = 0; i < path.size() - 1; i++) { + for (int t = 0; t < steps; t++) { // Storing the start and end points and slopes at those points as Vector2Ds. point_t tmp = path[i].getPoint(); Vector2D p1 = Vector2D(tmp); - tmp = path[i+1].getPoint(); + tmp = path[i + 1].getPoint(); Vector2D p2 = Vector2D(tmp); Vector2D t1 = path[i].getTangent(); - Vector2D t2 = path[i+1].getTangent(); - + Vector2D t2 = path[i + 1].getTangent(); // Scale s from 0.0 to 1.0 double s = (double)t / (double)steps; // Hermite Blending functions - double h1 = 2 * pow(s, 3) - 3 * pow(s, 2) + 1; + double h1 = 2 * pow(s, 3) - 3 * pow(s, 2) + 1; double h2 = -2 * pow(s, 3) + 3 * pow(s, 2); double h3 = pow(s, 3) - 2 * pow(s, 2) + s; double h4 = pow(s, 3) - pow(s, 2); // Calculate the point - Vector2D p = p1 * h1 + p2 * h2 + t1 * h3 + t2 * h4; + Vector2D p = p1 * h1 + p2 * h2 + t1 * h3 + t2 * h4; new_path.push_back(p.point()); } } - //Adding last point + // Adding last point new_path.push_back(path.back().getPoint()); return new_path; } - /** * Estimates the remaining distance from the robot's position to the end, * by "searching" for the robot along the path and running a "connect the dots" * distance algoritm - * + * * @param path The pure pursuit path the robot is following * @param robot_pose The robot's current position * @param radius Pure pursuit "radius", used to search for the robot along the path * @return A rough estimate of the remaining distance -*/ -double PurePursuit::estimate_remaining_dist(const std::vector &path, pose_t robot_pose, double radius) -{ + */ +double PurePursuit::estimate_remaining_dist(const std::vector &path, pose_t robot_pose, double radius) { point_t lookahead_pt = get_lookahead(path, robot_pose, radius); - + if (lookahead_pt == path[path.size() - 1]) { return robot_pose.get_point().dist(lookahead_pt); -} + } double dist = 0; // Run through the path backwards, adding distances - for(int i = path.size()-1; i >= 0; i--) - { + for (int i = path.size() - 1; i >= 0; i--) { // Test if the robot is between the two points - auto pts = line_circle_intersections(robot_pose.get_point(), radius, path[i-1], path[i]); - + auto pts = line_circle_intersections(robot_pose.get_point(), radius, path[i - 1], path[i]); + // There is an intersection? Robot is between the points so add the distance // from the bot to the next point and end. - if(!pts.empty()) - { + if (!pts.empty()) { dist += robot_pose.get_point().dist(path[i]); return dist; } - + // No intersections? Add the distance between the two points and move backwards // in the path until we find the robot, or run out of points. - dist += path[i-1].dist(path[i]); + dist += path[i - 1].dist(path[i]); } return dist; } - diff --git a/src/utils/serializer.cpp b/src/utils/serializer.cpp index fd756e3..c0b60da 100644 --- a/src/utils/serializer.cpp +++ b/src/utils/serializer.cpp @@ -9,55 +9,44 @@ /// @brief Convert type to bytes. Overload this for non integer types /// @param value value to convert -template -std::vector to_bytes(T value) -{ - // copy bytes of data into vector - std::vector value_bytes(sizeof(T)); - std::copy(static_cast(static_cast(&value)), - static_cast(static_cast(&value)) + sizeof(value), - value_bytes.begin()); - return value_bytes; +template std::vector to_bytes(T value) { + // copy bytes of data into vector + std::vector value_bytes(sizeof(T)); + std::copy(static_cast(static_cast(&value)), + static_cast(static_cast(&value)) + sizeof(value), value_bytes.begin()); + return value_bytes; } -template <> -std::vector to_bytes(std::string str) -{ - std::vector value_bytes(str.size() + 1); - std::copy(str.begin(), str.end(), value_bytes.begin()); - value_bytes[str.size()] = 0x0; - return value_bytes; +template <> std::vector to_bytes(std::string str) { + std::vector value_bytes(str.size() + 1); + std::copy(str.begin(), str.end(), value_bytes.begin()); + value_bytes[str.size()] = 0x0; + return value_bytes; } /// @brief Convert bytes to a type /// @param gets data from arbitrary bytes. Overload this for non integer types -template -T from_bytes(std::vector::const_iterator &position) -{ - T value; - std::copy(position, position + sizeof(T), static_cast(static_cast(&value))); - position = position + sizeof(T); - return value; +template T from_bytes(std::vector::const_iterator &position) { + T value; + std::copy(position, position + sizeof(T), static_cast(static_cast(&value))); + position = position + sizeof(T); + return value; } -template <> -std::string from_bytes(std::vector::const_iterator &position) -{ - auto pos = position; - while (*pos != 0x0) - { - ++pos; - } - std::string s(position, pos); - position = pos + 1; - return s; +template <> std::string from_bytes(std::vector::const_iterator &position) { + auto pos = position; + while (*pos != 0x0) { + ++pos; + } + std::string s(position, pos); + position = pos + 1; + return s; } /// @brief Replaces funny characters in names so they don't mess with serialization specifiers -std::string sanitize_name(std::string s) -{ - std::replace(s.begin(), s.end(), serialization_separator, '-'); - return s; +std::string sanitize_name(std::string s) { + std::replace(s.begin(), s.end(), serialization_separator, '-'); + return s; } // Protocol @@ -82,186 +71,155 @@ std::string sanitize_name(std::string s) /// @param data the bytes to add to /// @param map the values and names we are talking about template -static void add_data(std::vector &data, const std::map &map) -{ - for (const auto &pair : map) - { - const std::string &name = pair.first; - const value_type value = pair.second; +static void add_data(std::vector &data, const std::map &map) { + for (const auto &pair : map) { + const std::string &name = pair.first; + const value_type value = pair.second; - data.insert(data.end(), name.cbegin(), name.cend()); - data.insert(data.end(), 0x0); + data.insert(data.end(), name.cbegin(), name.cend()); + data.insert(data.end(), 0x0); - auto bytes = to_bytes(value); - data.insert(data.end(), bytes.cbegin(), bytes.cend()); - } - data.push_back(serialization_separator); + auto bytes = to_bytes(value); + data.insert(data.end(), bytes.cbegin(), bytes.cend()); + } + data.push_back(serialization_separator); } // reads data of a certain type from a file template static std::vector::const_iterator read_data(std::vector::const_iterator begin, - std::map &map) -{ - std::vector::const_iterator pos = begin; - - while (*pos != serialization_separator) - { - auto name_start = pos; - // read name - std::string name = from_bytes(name_start); - pos += name.size() + 1; - // read value - value_type value = from_bytes(pos); - printf("Read Name: %s\n", name.c_str()); - map.insert({name, value}); - } - - return pos + 1; -} - -void Serializer::set_int(const std::string &name, int i) -{ - ints[sanitize_name(name)] = i; - if (flush_always) - { - save_to_disk(); - } -} -void Serializer::set_bool(const std::string &name, bool b) -{ - bools[sanitize_name(name)] = b; - if (flush_always) - { - save_to_disk(); - } -} -void Serializer::set_double(const std::string &name, double d) -{ - doubles[sanitize_name(name)] = d; - if (flush_always) - { - save_to_disk(); - } -} -void Serializer::set_string(const std::string &name, std::string str) -{ - strings[sanitize_name(name)] = str; - if (flush_always) - { - save_to_disk(); - } -} - -int Serializer::int_or(const std::string &name, int otherwise) -{ - if (ints.count(name)) - { - return ints.at(name); - } - set_int(name, otherwise); - return otherwise; -} -bool Serializer::bool_or(const std::string &name, bool otherwise) -{ - if (bools.count(name)) - { - return bools.at(name); - } - set_bool(name, otherwise); - return otherwise; -} -double Serializer::double_or(const std::string &name, double otherwise) -{ - if (doubles.count(name)) - { - return doubles.at(name); - } - set_double(name, otherwise); - return otherwise; -} -std::string Serializer::string_or(const std::string &name, std::string otherwise) -{ - if (strings.count(name)) - { - return strings.at(name); - } - set_string(name, otherwise); - return otherwise; + std::map &map) { + std::vector::const_iterator pos = begin; + + while (*pos != serialization_separator) { + auto name_start = pos; + // read name + std::string name = from_bytes(name_start); + pos += name.size() + 1; + // read value + value_type value = from_bytes(pos); + printf("Read Name: %s\n", name.c_str()); + map.insert({name, value}); + } + + return pos + 1; +} + +void Serializer::set_int(const std::string &name, int i) { + ints[sanitize_name(name)] = i; + if (flush_always) { + save_to_disk(); + } +} +void Serializer::set_bool(const std::string &name, bool b) { + bools[sanitize_name(name)] = b; + if (flush_always) { + save_to_disk(); + } +} +void Serializer::set_double(const std::string &name, double d) { + doubles[sanitize_name(name)] = d; + if (flush_always) { + save_to_disk(); + } +} +void Serializer::set_string(const std::string &name, std::string str) { + strings[sanitize_name(name)] = str; + if (flush_always) { + save_to_disk(); + } +} + +int Serializer::int_or(const std::string &name, int otherwise) { + if (ints.count(name)) { + return ints.at(name); + } + set_int(name, otherwise); + return otherwise; +} +bool Serializer::bool_or(const std::string &name, bool otherwise) { + if (bools.count(name)) { + return bools.at(name); + } + set_bool(name, otherwise); + return otherwise; +} +double Serializer::double_or(const std::string &name, double otherwise) { + if (doubles.count(name)) { + return doubles.at(name); + } + set_double(name, otherwise); + return otherwise; +} +std::string Serializer::string_or(const std::string &name, std::string otherwise) { + if (strings.count(name)) { + return strings.at(name); + } + set_string(name, otherwise); + return otherwise; } /// @brief forms data bytes then saves to filename this was openned with -void Serializer::save_to_disk() const -{ - vex::brain::sdcard sd; - if (!sd.isInserted()) - { - printf("!! Trying to Serialize to No SD Card !!\n"); - return; - } - - std::vector data = {}; - add_data(data, ints); - add_data(data, bools); - add_data(data, doubles); - add_data(data, strings); - - - int32_t written = sd.savefile(filename.c_str(), (unsigned char *)&data[0], data.size()); - if (written != data.size()) - { - printf("!! Error writing to `%s`!!\n", filename.c_str()); - return; - } +void Serializer::save_to_disk() const { + vex::brain::sdcard sd; + if (!sd.isInserted()) { + printf("!! Trying to Serialize to No SD Card !!\n"); + return; + } + + std::vector data = {}; + add_data(data, ints); + add_data(data, bools); + add_data(data, doubles); + add_data(data, strings); + + int32_t written = sd.savefile(filename.c_str(), (unsigned char *)&data[0], data.size()); + if (written != data.size()) { + printf("!! Error writing to `%s`!!\n", filename.c_str()); + return; + } } /// @brief reads types from file data -bool Serializer::read_from_disk() -{ - vex::brain::sdcard sd; - if (!sd.isInserted()) - { - printf("!! Trying to Serialize to No SD Card !!\n"); - return false; - } - int size = sd.size(filename.c_str()); - if (size == 0) - { - ints = {}; - doubles = {}; - bools = {}; - return true; - } - - if (filename == "") - { - printf("!! Can't write to empty filename!!\n"); - return false; - } - - if (!sd.exists(filename.c_str())) - { - printf("!!f Trying to Serialize to a file that doesnt exist: Creating %s !!\n", filename.c_str()); - save_to_disk(); - return false; - } - - std::vector data(size); - - int readsize = sd.loadfile(filename.c_str(), (unsigned char *)&data[0], size); - if (size != readsize) - { - printf("!! Error reading from file !!"); - ; - return false; - } - - - auto bool_start = read_data(data.cbegin(), ints); - auto doubles_start = read_data(bool_start, bools); - auto strings_start = read_data(doubles_start, doubles); - auto file_end = read_data(strings_start, strings); - (void)file_end; - +bool Serializer::read_from_disk() { + vex::brain::sdcard sd; + if (!sd.isInserted()) { + printf("!! Trying to Serialize to No SD Card !!\n"); + return false; + } + int size = sd.size(filename.c_str()); + if (size == 0) { + ints = {}; + doubles = {}; + bools = {}; return true; + } + + if (filename == "") { + printf("!! Can't write to empty filename!!\n"); + return false; + } + + if (!sd.exists(filename.c_str())) { + printf("!!f Trying to Serialize to a file that doesnt exist: Creating %s !!\n", filename.c_str()); + save_to_disk(); + return false; + } + + std::vector data(size); + + int readsize = sd.loadfile(filename.c_str(), (unsigned char *)&data[0], size); + if (size != readsize) { + printf("!! Error reading from file !!"); + ; + return false; + } + + auto bool_start = read_data(data.cbegin(), ints); + auto doubles_start = read_data(bool_start, bools); + auto strings_start = read_data(doubles_start, doubles); + auto file_end = read_data(strings_start, strings); + (void)file_end; + + return true; } diff --git a/src/utils/vector2d.cpp b/src/utils/vector2d.cpp index 8399b5f..e16822e 100644 --- a/src/utils/vector2d.cpp +++ b/src/utils/vector2d.cpp @@ -2,34 +2,29 @@ /** * Construct a vector object. - * + * * @param dir Direction, in radians. 'foward' is 0, clockwise positive when viewed from the top. * @param mag Magnitude. */ -Vector2D::Vector2D(double dir, double mag) -: dir(dir), mag(mag) -{ - -} +Vector2D::Vector2D(double dir, double mag) : dir(dir), mag(mag) {} /** * Construct a vector object from a cartesian point. - * + * * @param p point_t.x , point_t.y */ -Vector2D::Vector2D(point_t p) -{ - this->dir = atan2(p.y, p.x); - this->mag = sqrt( (p.x*p.x) + (p.y*p.y) ); +Vector2D::Vector2D(point_t p) { + this->dir = atan2(p.y, p.x); + this->mag = sqrt((p.x * p.x) + (p.y * p.y)); } /** * Get the direction of the vector, in radians. * '0' is forward, clockwise positive when viewed from the top. - * + * * Use r2d() to convert. */ -double Vector2D::get_dir() const { return dir;} +double Vector2D::get_dir() const { return dir; } /** * Get the magnitude of the vector @@ -39,38 +34,24 @@ double Vector2D::get_mag() const { return mag; } /** * Get the X component of the vector; positive to the right. */ -double Vector2D::get_x() const -{ -return mag * cos(dir); -} +double Vector2D::get_x() const { return mag * cos(dir); } /** * Get the Y component of the vector, positive forward. */ -double Vector2D::get_y() const -{ -return mag * sin(dir); -} +double Vector2D::get_y() const { return mag * sin(dir); } /** * Changes the magnetude of the vector to 1 -*/ -Vector2D Vector2D::normalize() -{ - return Vector2D(this->dir, 1); -} + */ +Vector2D Vector2D::normalize() { return Vector2D(this->dir, 1); } /** * Convert a direction and magnitude representation to an x, y representation - * @return the x, y representation of the vector -*/ -point_t Vector2D::point() -{ - point_t p = - { - .x = this->mag * cos(this->dir), - .y = this->mag * sin(this->dir) - }; + * @return the x, y representation of the vector + */ +point_t Vector2D::point() { + point_t p = {.x = this->mag * cos(this->dir), .y = this->mag * sin(this->dir)}; return p; } @@ -79,17 +60,12 @@ point_t Vector2D::point() * Vector2D + Vector2D = (this.x + other.x, this.y + other.y) * @param other the vector to add to this * @return the sum of the vectors -*/ + */ -Vector2D Vector2D::operator+(const Vector2D &other) -{ - point_t p = - { - .x = this->get_x() + other.get_x(), - .y = this->get_y() + other.get_y() - }; +Vector2D Vector2D::operator+(const Vector2D &other) { + point_t p = {.x = this->get_x() + other.get_x(), .y = this->get_y() + other.get_y()}; - return Vector2D( p ); + return Vector2D(p); } /** @@ -97,39 +73,25 @@ Vector2D Vector2D::operator+(const Vector2D &other) * Vector2D - Vector2D = (this.x - other.x, this.y - other.y) * @param other the vector to subtract from this * @return the difference of the vectors -*/ -Vector2D Vector2D::operator-(const Vector2D &other) -{ - point_t p = - { - .x = this->get_x() - other.get_x(), - .y = this->get_y() - other.get_y() - }; - return Vector2D( p ); + */ +Vector2D Vector2D::operator-(const Vector2D &other) { + point_t p = {.x = this->get_x() - other.get_x(), .y = this->get_y() - other.get_y()}; + return Vector2D(p); } /** * Scales a Vector2D by a scalar with the * operator * @param x the value to scale the vector by * @return the this Vector2D scaled by x -*/ -Vector2D Vector2D::operator*(const double &x) -{ - return Vector2D(this->dir, this->mag * x); -} + */ +Vector2D Vector2D::operator*(const double &x) { return Vector2D(this->dir, this->mag * x); } /** * General function for converting degrees to radians */ -double deg2rad(double deg) -{ - return deg * (PI / 180.0); -} +double deg2rad(double deg) { return deg * (PI / 180.0); } /** * General function for converting radians to degrees */ -double rad2deg(double rad) -{ - return rad * (180.0 / PI); -} +double rad2deg(double rad) { return rad * (180.0 / PI); } From 13ff178fe6985ba3a676703b8315b25fd8aee60a Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 25 Feb 2024 14:07:11 -0500 Subject: [PATCH 242/243] mergeeeeeeee --- Doxyfile | 4 +- include/robot_specs.h | 24 +- include/subsystems/custom_encoder.h | 14 +- include/subsystems/flywheel.h | 45 +- include/subsystems/fun/pl_mpeg.h | 3993 +++++++++++++++++ include/subsystems/fun/video.h | 17 + include/subsystems/layout.h | 11 +- include/subsystems/lift.h | 291 +- include/subsystems/mecanum_drive.h | 114 +- include/subsystems/odometry/odometry_3wheel.h | 128 +- include/subsystems/odometry/odometry_base.h | 257 +- include/subsystems/odometry/odometry_tank.h | 123 +- include/subsystems/screen.h | 600 ++- include/subsystems/tank_drive.h | 185 +- include/utils/auto_chooser.h | 13 +- .../utils/command_structure/auto_command.h | 80 +- .../utils/command_structure/basic_command.h | 166 +- .../command_structure/command_controller.h | 50 +- .../utils/command_structure/delay_command.h | 40 +- .../utils/command_structure/drive_commands.h | 344 +- .../command_structure/flywheel_commands.h | 150 +- include/utils/controls/bang_bang.h | 78 +- include/utils/controls/feedback_base.h | 67 +- include/utils/controls/feedforward.h | 115 +- include/utils/controls/motion_controller.h | 230 +- include/utils/controls/pid.h | 56 +- include/utils/controls/pidff.h | 3 +- include/utils/controls/take_back_half.h | 94 +- include/utils/controls/trapezoid_profile.h | 3 +- include/utils/generic_auto.h | 54 +- include/utils/geometry.h | 179 +- include/utils/graph_drawer.h | 19 +- include/utils/logger.h | 100 +- include/utils/math_util.h | 30 +- include/utils/moving_average.h | 29 +- include/utils/pure_pursuit.h | 212 +- include/utils/serializer.h | 159 +- include/utils/state_machine.h | 202 + include/utils/vector2d.h | 156 +- src/subsystems/custom_encoder.cpp | 39 +- src/subsystems/flywheel.cpp | 71 +- src/subsystems/fun/video.cpp | 124 + src/subsystems/mecanum_drive.cpp | 188 +- src/subsystems/odometry/odometry_3wheel.cpp | 381 +- src/subsystems/odometry/odometry_base.cpp | 56 +- src/subsystems/odometry/odometry_tank.cpp | 75 +- src/subsystems/screen.cpp | 69 +- src/subsystems/tank_drive.cpp | 418 +- src/utils/auto_chooser.cpp | 33 +- src/utils/command_structure/auto_command.cpp | 489 +- src/utils/command_structure/basic_command.cpp | 46 +- .../command_structure/command_controller.cpp | 73 +- .../command_structure/drive_commands.cpp | 99 +- .../command_structure/flywheel_commands.cpp | 23 +- src/utils/controls/bang_bang.cpp | 53 +- src/utils/controls/feedforward.cpp | 131 +- src/utils/controls/motion_controller.cpp | 300 +- src/utils/controls/pid.cpp | 21 +- src/utils/controls/pidff.cpp | 48 +- src/utils/controls/take_back_half.cpp | 116 +- src/utils/generic_auto.cpp | 79 +- src/utils/graph_drawer.cpp | 181 +- src/utils/logger.cpp | 121 +- src/utils/math_util.cpp | 66 +- src/utils/moving_average.cpp | 50 +- src/utils/pure_pursuit.cpp | 211 +- src/utils/serializer.cpp | 370 +- src/utils/trapezoid_profile.cpp | 54 +- src/utils/vector2d.cpp | 94 +- 69 files changed, 8156 insertions(+), 4358 deletions(-) create mode 100644 include/subsystems/fun/pl_mpeg.h create mode 100644 include/subsystems/fun/video.h create mode 100644 include/utils/state_machine.h create mode 100644 src/subsystems/fun/video.cpp diff --git a/Doxyfile b/Doxyfile index 60b26a6..3807b19 100644 --- a/Doxyfile +++ b/Doxyfile @@ -499,7 +499,7 @@ NUM_PROC_THREADS = 1 # normally produced when WARNINGS is set to YES. # The default value is: NO. -EXTRACT_ALL = YES +EXTRACT_ALL = NO # If the EXTRACT_PRIVATE tag is set to YES, all private members of a class will # be included in the documentation. @@ -2428,7 +2428,7 @@ HIDE_UNDOC_RELATIONS = YES # set to NO # The default value is: NO. -HAVE_DOT = YES +HAVE_DOT = NO # The DOT_NUM_THREADS specifies the number of dot invocations doxygen is allowed # to run in parallel. When set to 0 doxygen will base this on the number of diff --git a/include/robot_specs.h b/include/robot_specs.h index 9a5fa0c..d853783 100644 --- a/include/robot_specs.h +++ b/include/robot_specs.h @@ -1,25 +1,27 @@ #pragma once -#include "../core/include/utils/controls/pid.h" #include "../core/include/utils/controls/feedback_base.h" +#include "../core/include/utils/controls/pid.h" /** * Main robot characterization struct. - * This will be passed to all the major subsystems + * This will be passed to all the major subsystems * that require info about the robot. * All distance measurements are in inches. */ -typedef struct -{ - double robot_radius; ///< if you were to draw a circle with this radius, the robot would be entirely contained within it +typedef struct { + double + robot_radius; ///< if you were to draw a circle with this radius, the robot would be entirely contained within it - double odom_wheel_diam; ///< the diameter of the wheels used for - double odom_gear_ratio; ///< the ratio of the odometry wheel to the encoder reading odometry data - double dist_between_wheels; ///< the distance between centers of the central drive wheels + double odom_wheel_diam; ///< the diameter of the wheels used for + double odom_gear_ratio; ///< the ratio of the odometry wheel to the encoder reading odometry data + double dist_between_wheels; ///< the distance between centers of the central drive wheels - double drive_correction_cutoff; ///< the distance at which to stop trying to turn towards the target. If we are less than this value, we can continue driving forward to minimize our distance but will not try to spin around to point directly at the target + double drive_correction_cutoff; ///< the distance at which to stop trying to turn towards the target. If we are less + ///< than this value, we can continue driving forward to minimize our distance but + ///< will not try to spin around to point directly at the target - Feedback *drive_feedback; ///< the default feedback for autonomous driving - Feedback *turn_feedback; ///< the defualt feedback for autonomous turning + Feedback *drive_feedback; ///< the default feedback for autonomous driving + Feedback *turn_feedback; ///< the defualt feedback for autonomous turning PID::pid_config_t correction_pid; ///< the pid controller to keep the robot driving in as straight a line as possible } robot_specs_t; \ No newline at end of file diff --git a/include/subsystems/custom_encoder.h b/include/subsystems/custom_encoder.h index 2b87b86..b9d3e96 100644 --- a/include/subsystems/custom_encoder.h +++ b/include/subsystems/custom_encoder.h @@ -5,30 +5,29 @@ * A wrapper class for the vex encoder that allows the use of 3rd party * encoders with different tick-per-revolution values. */ -class CustomEncoder : public vex::encoder -{ +class CustomEncoder : public vex::encoder { typedef vex::encoder super; - public: +public: /** * Construct an encoder with a custom number of ticks * @param port the triport port on the brain the encoder is plugged into * @param ticks_per_rev the number of ticks the encoder will report for one revolution - */ + */ CustomEncoder(vex::triport::port &port, double ticks_per_rev); /** * sets the stored rotation of the encoder. Any further movements will be from this value * @param val the numerical value of the angle we are setting to * @param units the unit of val - */ + */ void setRotation(double val, vex::rotationUnits units); /** * sets the stored position of the encoder. Any further movements will be from this value * @param val the numerical value of the position we are setting to * @param units the unit of val - */ + */ void setPosition(double val, vex::rotationUnits units); /** @@ -52,7 +51,6 @@ class CustomEncoder : public vex::encoder */ double velocity(vex::velocityUnits units); - - private: +private: double tick_scalar; }; \ No newline at end of file diff --git a/include/subsystems/flywheel.h b/include/subsystems/flywheel.h index c8c42b3..2837d7a 100644 --- a/include/subsystems/flywheel.h +++ b/include/subsystems/flywheel.h @@ -1,22 +1,21 @@ #pragma once -#include "../core/include/utils/controls/feedforward.h" -#include "vex.h" #include "../core/include/robot_specs.h" -#include "../core/include/utils/controls/pid.h" -#include "../core/include/utils/command_structure/auto_command.h" #include "../core/include/subsystems/screen.h" +#include "../core/include/utils/command_structure/auto_command.h" +#include "../core/include/utils/controls/feedforward.h" +#include "../core/include/utils/controls/pid.h" +#include "vex.h" #include /** * a Flywheel class that handles all control of a high inertia spinning disk - * It gives multiple options for what control system to use in order to control wheel velocity and functions alerting the user when the flywheel is up to speed. - * Flywheel is a set and forget class. - * Once you create it you can call spin_rpm or stop on it at any time and it will take all necessary steps to accomplish this + * It gives multiple options for what control system to use in order to control wheel velocity and functions alerting + * the user when the flywheel is up to speed. Flywheel is a set and forget class. Once you create it you can call + * spin_rpm or stop on it at any time and it will take all necessary steps to accomplish this * */ -class Flywheel -{ +class Flywheel { public: // CONSTRUCTORS, GETTERS, AND SETTERS @@ -70,10 +69,7 @@ class Flywheel * @brief check if the feedback controller thinks the flywheel is on target * @return true if on target */ - bool is_on_target() - { - return fb.is_on_target(); - } + bool is_on_target() { return fb.is_on_target(); } /** * @brief Creates a page displaying info about the flywheel @@ -85,23 +81,22 @@ class Flywheel * @brief Creates a new auto command to spin the flywheel at the desired velocity * @param rpm the rpm to spin at * @return an auto command to add to a command controller - */ - AutoCommand *SpinRpmCmd(int rpm) - { + */ + AutoCommand *SpinRpmCmd(int rpm) { - return new FunctionCommand([this, rpm]() - {spin_rpm(rpm); return true; }); + return new FunctionCommand([this, rpm]() { + spin_rpm(rpm); + return true; + }); } /** - * @brief Creates a new auto command that will hold until the flywheel has its target as defined by its feedback controller + * @brief Creates a new auto command that will hold until the flywheel has its target as defined by its feedback + * controller * @return an auto command to add to a command controller */ - AutoCommand *WaitUntilUpToSpeedCmd() - { - return new WaitUntilCondition( - new FunctionCondition([this]() - { return is_on_target(); })); + AutoCommand *WaitUntilUpToSpeedCmd() { + return new WaitUntilCondition(new FunctionCondition([this]() { return is_on_target(); })); } private: @@ -116,7 +111,7 @@ class Flywheel double ratio; ///< ratio between motor and flywheel. For accurate RPM calcualation std::atomic target_rpm; ///< Desired RPM of the flywheel. task rpm_task; ///< task that handles spinning the wheel at a given target_rpm - Filter &avger; ///< Moving average to smooth out noise from + Filter &avger; ///< Moving average to smooth out noise from // Functions for internal use only /** diff --git a/include/subsystems/fun/pl_mpeg.h b/include/subsystems/fun/pl_mpeg.h new file mode 100644 index 0000000..6e2489c --- /dev/null +++ b/include/subsystems/fun/pl_mpeg.h @@ -0,0 +1,3993 @@ +#include "vex.h" +/* +PL_MPEG - MPEG1 Video decoder, MP2 Audio decoder, MPEG-PS demuxer + +Dominic Szablewski - https://phoboslab.org + + +-- LICENSE: The MIT License(MIT) + +Copyright(c) 2019 Dominic Szablewski + +Permission is hereby granted, free of charge, to any person obtaining a copy of +this software and associated documentation files(the "Software"), to deal in +the Software without restriction, including without limitation the rights to +use, copy, modify, merge, publish, distribute, sublicense, and / or sell copies +of the Software, and to permit persons to whom the Software is furnished to do +so, subject to the following conditions : +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. + + + + +-- Synopsis + +// Define `PL_MPEG_IMPLEMENTATION` in *one* C/C++ file before including this +// library to create the implementation. + +#define PL_MPEG_IMPLEMENTATION +#include "plmpeg.h" + +// This function gets called for each decoded video frame +void my_video_callback(plm_t *plm, plm_frame_t *frame, void *user) { + // Do something with frame->y.data, frame->cr.data, frame->cb.data +} + +// This function gets called for each decoded audio frame +void my_audio_callback(plm_t *plm, plm_samples_t *frame, void *user) { + // Do something with samples->interleaved +} + +// Load a .mpg (MPEG Program Stream) file +plm_t *plm = plm_create_with_filename("some-file.mpg"); + +// Install the video & audio decode callbacks +plm_set_video_decode_callback(plm, my_video_callback, my_data); +plm_set_audio_decode_callback(plm, my_audio_callback, my_data); + + +// Decode +do { + plm_decode(plm, time_since_last_call); +} while (!plm_has_ended(plm)); + +// All done +plm_destroy(plm); + + + +-- Documentation + +This library provides several interfaces to load, demux and decode MPEG video +and audio data. A high-level API combines the demuxer, video & audio decoders +in an easy to use wrapper. + +Lower-level APIs for accessing the demuxer, video decoder and audio decoder, +as well as providing different data sources are also available. + +Interfaces are written in an object oriented style, meaning you create object +instances via various different constructor functions (plm_*create()), +do some work on them and later dispose them via plm_*destroy(). + +plm_* ......... the high-level interface, combining demuxer and decoders +plm_buffer_* .. the data source used by all interfaces +plm_demux_* ... the MPEG-PS demuxer +plm_video_* ... the MPEG1 Video ("mpeg1") decoder +plm_audio_* ... the MPEG1 Audio Layer II ("mp2") decoder + + +With the high-level interface you have two options to decode video & audio: + + 1. Use plm_decode() and just hand over the delta time since the last call. + It will decode everything needed and call your callbacks (specified through + plm_set_{video|audio}_decode_callback()) any number of times. + + 2. Use plm_decode_video() and plm_decode_audio() to decode exactly one + frame of video or audio data at a time. How you handle the synchronization + of both streams is up to you. + +If you only want to decode video *or* audio through these functions, you should +disable the other stream (plm_set_{video|audio}_enabled(FALSE)) + +Video data is decoded into a struct with all 3 planes (Y, Cr, Cb) stored in +separate buffers. You can either convert this to RGB on the CPU (slow) via the +plm_frame_to_rgb() function or do it on the GPU with the following matrix: + +mat4 bt601 = mat4( + 1.16438, 0.00000, 1.59603, -0.87079, + 1.16438, -0.39176, -0.81297, 0.52959, + 1.16438, 2.01723, 0.00000, -1.08139, + 0, 0, 0, 1 +); +gl_FragColor = vec4(y, cb, cr, 1.0) * bt601; + +Audio data is decoded into a struct with either one single float array with the +samples for the left and right channel interleaved, or if the +PLM_AUDIO_SEPARATE_CHANNELS is defined *before* including this library, into +two separate float arrays - one for each channel. + + +Data can be supplied to the high level interface, the demuxer and the decoders +in three different ways: + + 1. Using plm_create_from_filename() or with a file handle with + plm_create_from_file(). + + 2. Using plm_create_with_memory() and supplying a pointer to memory that + contains the whole file. + + 3. Using plm_create_with_buffer(), supplying your own plm_buffer_t instance and + periodically writing to this buffer. + +When using your own plm_buffer_t instance, you can fill this buffer using +plm_buffer_write(). You can either monitor plm_buffer_get_remaining() and push +data when appropriate, or install a callback on the buffer with +plm_buffer_set_load_callback() that gets called whenever the buffer needs more +data. + +A buffer created with plm_buffer_create_with_capacity() is treated as a ring +buffer, meaning that data that has already been read, will be discarded. In +contrast, a buffer created with plm_buffer_create_for_appending() will keep all +data written to it in memory. This enables seeking in the already loaded data. + + +There should be no need to use the lower level plm_demux_*, plm_video_* and +plm_audio_* functions, if all you want to do is read/decode an MPEG-PS file. +However, if you get raw mpeg1video data or raw mp2 audio data from a different +source, these functions can be used to decode the raw data directly. Similarly, +if you only want to analyze an MPEG-PS file or extract raw video or audio +packets from it, you can use the plm_demux_* functions. + + +This library uses malloc(), realloc() and free() to manage memory. Typically +all allocation happens up-front when creating the interface. However, the +default buffer size may be too small for certain inputs. In these cases plmpeg +will realloc() the buffer with a larger size whenever needed. You can configure +the default buffer size by defining PLM_BUFFER_DEFAULT_SIZE *before* +including this library. + +You can also define PLM_MALLOC, PLM_REALLOC and PLM_FREE to provide your own +memory management functions. + + +See below for detailed the API documentation. + +*/ + +#ifndef PL_MPEG_H +#define PL_MPEG_H + +#include +// #include + +#ifdef __cplusplus +extern "C" { +#endif + +// ----------------------------------------------------------------------------- +// Public Data Types + +// Object types for the various interfaces + +typedef struct plm_t plm_t; +typedef struct plm_buffer_t plm_buffer_t; +typedef struct plm_demux_t plm_demux_t; +typedef struct plm_video_t plm_video_t; +typedef struct plm_audio_t plm_audio_t; + +// Demuxed MPEG PS packet +// The type maps directly to the various MPEG-PES start codes. PTS is the +// presentation time stamp of the packet in seconds. Note that not all packets +// have a PTS value, indicated by PLM_PACKET_INVALID_TS. + +#define PLM_PACKET_INVALID_TS -1 + +typedef struct { + int type; + double pts; + size_t length; + uint8_t *data; +} plm_packet_t; + +// Decoded Video Plane +// The byte length of the data is width * height. Note that different planes +// have different sizes: the Luma plane (Y) is double the size of each of +// the two Chroma planes (Cr, Cb) - i.e. 4 times the byte length. +// Also note that the size of the plane does *not* denote the size of the +// displayed frame. The sizes of planes are always rounded up to the nearest +// macroblock (16px). + +typedef struct { + unsigned int width; + unsigned int height; + uint8_t *data; +} plm_plane_t; + +// Decoded Video Frame +// width and height denote the desired display size of the frame. This may be +// different from the internal size of the 3 planes. + +typedef struct { + double time; + unsigned int width; + unsigned int height; + plm_plane_t y; + plm_plane_t cr; + plm_plane_t cb; +} plm_frame_t; + +// Callback function type for decoded video frames used by the high-level +// plm_* interface + +typedef void (*plm_video_decode_callback)(plm_t *self, plm_frame_t *frame, void *user); + +// Decoded Audio Samples +// Samples are stored as normalized (-1, 1) float either interleaved, or if +// PLM_AUDIO_SEPARATE_CHANNELS is defined, in two separate arrays. +// The `count` is always PLM_AUDIO_SAMPLES_PER_FRAME and just there for +// convenience. + +#define PLM_AUDIO_SAMPLES_PER_FRAME 1152 + +typedef struct { + double time; + unsigned int count; +#ifdef PLM_AUDIO_SEPARATE_CHANNELS + float left[PLM_AUDIO_SAMPLES_PER_FRAME]; + float right[PLM_AUDIO_SAMPLES_PER_FRAME]; +#else + float interleaved[PLM_AUDIO_SAMPLES_PER_FRAME * 2]; +#endif +} plm_samples_t; + +// Callback function type for decoded audio samples used by the high-level +// plm_* interface + +typedef void (*plm_audio_decode_callback)(plm_t *self, plm_samples_t *samples, void *user); + +// Callback function for plm_buffer when it needs more data + +typedef void (*plm_buffer_load_callback)(plm_buffer_t *self, void *user); + +// ----------------------------------------------------------------------------- +// plm_* public API +// High-Level API for loading/demuxing/decoding MPEG-PS data + +// Create a plmpeg instance with a filename. Returns NULL if the file could not +// be opened. + +plm_t *plm_create_with_filename(const char *filename); + +// Create a plmpeg instance with a file handle. Pass TRUE to close_when_done to +// let plmpeg call fclose() on the handle when plm_destroy() is called. + +plm_t *plm_create_with_file(FIL *fh, int close_when_done); + +// Create a plmpeg instance with a pointer to memory as source. This assumes the +// whole file is in memory. The memory is not copied. Pass TRUE to +// free_when_done to let plmpeg call free() on the pointer when plm_destroy() +// is called. + +plm_t *plm_create_with_memory(uint8_t *bytes, size_t length, int free_when_done); + +// Create a plmpeg instance with a plm_buffer as source. Pass TRUE to +// destroy_when_done to let plmpeg call plm_buffer_destroy() on the buffer when +// plm_destroy() is called. + +plm_t *plm_create_with_buffer(plm_buffer_t *buffer, int destroy_when_done); + +// Destroy a plmpeg instance and free all data. + +void plm_destroy(plm_t *self); + +// Get whether we have headers on all available streams and we can accurately +// report the number of video/audio streams, video dimensions, framerate and +// audio samplerate. +// This returns FALSE if the file is not an MPEG-PS file or - when not using a +// file as source - when not enough data is available yet. + +int plm_has_headers(plm_t *self); + +// Get or set whether video decoding is enabled. Default TRUE. + +int plm_get_video_enabled(plm_t *self); +void plm_set_video_enabled(plm_t *self, int enabled); + +// Get the number of video streams (0--1) reported in the system header. + +int plm_get_num_video_streams(plm_t *self); + +// Get the display width/height of the video stream. + +int plm_get_width(plm_t *self); +int plm_get_height(plm_t *self); + +// Get the framerate of the video stream in frames per second. + +double plm_get_framerate(plm_t *self); + +// Get or set whether audio decoding is enabled. Default TRUE. + +int plm_get_audio_enabled(plm_t *self); +void plm_set_audio_enabled(plm_t *self, int enabled); + +// Get the number of audio streams (0--4) reported in the system header. + +int plm_get_num_audio_streams(plm_t *self); + +// Set the desired audio stream (0--3). Default 0. + +void plm_set_audio_stream(plm_t *self, int stream_index); + +// Get the samplerate of the audio stream in samples per second. + +int plm_get_samplerate(plm_t *self); + +// Get or set the audio lead time in seconds - the time in which audio samples +// are decoded in advance (or behind) the video decode time. Typically this +// should be set to the duration of the buffer of the audio API that you use +// for output. E.g. for SDL2: (SDL_AudioSpec.samples / samplerate) + +double plm_get_audio_lead_time(plm_t *self); +void plm_set_audio_lead_time(plm_t *self, double lead_time); + +// Get the current internal time in seconds. + +double plm_get_time(plm_t *self); + +// Get the video duration of the underlying source in seconds. + +double plm_get_duration(plm_t *self); + +// Rewind all buffers back to the beginning. + +void plm_rewind(plm_t *self); + +// Get or set looping. Default FALSE. + +int plm_get_loop(plm_t *self); +void plm_set_loop(plm_t *self, int loop); + +// Get whether the file has ended. If looping is enabled, this will always +// return FALSE. + +int plm_has_ended(plm_t *self); + +// Set the callback for decoded video frames used with plm_decode(). If no +// callback is set, video data will be ignored and not be decoded. The *user +// Parameter will be passed to your callback. + +void plm_set_video_decode_callback(plm_t *self, plm_video_decode_callback fp, void *user); + +// Set the callback for decoded audio samples used with plm_decode(). If no +// callback is set, audio data will be ignored and not be decoded. The *user +// Parameter will be passed to your callback. + +void plm_set_audio_decode_callback(plm_t *self, plm_audio_decode_callback fp, void *user); + +// Advance the internal timer by seconds and decode video/audio up to this time. +// This will call the video_decode_callback and audio_decode_callback any number +// of times. A frame-skip is not implemented, i.e. everything up to current time +// will be decoded. + +void plm_decode(plm_t *self, double seconds); + +// Decode and return one video frame. Returns NULL if no frame could be decoded +// (either because the source ended or data is corrupt). If you only want to +// decode video, you should disable audio via plm_set_audio_enabled(). +// The returned plm_frame_t is valid until the next call to plm_decode_video() +// or until plm_destroy() is called. + +plm_frame_t *plm_decode_video(plm_t *self); + +// Decode and return one audio frame. Returns NULL if no frame could be decoded +// (either because the source ended or data is corrupt). If you only want to +// decode audio, you should disable video via plm_set_video_enabled(). +// The returned plm_samples_t is valid until the next call to plm_decode_audio() +// or until plm_destroy() is called. + +plm_samples_t *plm_decode_audio(plm_t *self); + +// Seek to the specified time, clamped between 0 -- duration. This can only be +// used when the underlying plm_buffer is seekable, i.e. for files, fixed +// memory buffers or _for_appending buffers. +// If seek_exact is TRUE this will seek to the exact time, otherwise it will +// seek to the last intra frame just before the desired time. Exact seeking can +// be slow, because all frames up to the seeked one have to be decoded on top of +// the previous intra frame. +// If seeking succeeds, this function will call the video_decode_callback +// exactly once with the target frame. If audio is enabled, it will also call +// the audio_decode_callback any number of times, until the audio_lead_time is +// satisfied. +// Returns TRUE if seeking succeeded or FALSE if no frame could be found. + +int plm_seek(plm_t *self, double time, int seek_exact); + +// Similar to plm_seek(), but will not call the video_decode_callback, +// audio_decode_callback or make any attempts to sync audio. +// Returns the found frame or NULL if no frame could be found. + +plm_frame_t *plm_seek_frame(plm_t *self, double time, int seek_exact); + +// ----------------------------------------------------------------------------- +// plm_buffer public API +// Provides the data source for all other plm_* interfaces + +// The default size for buffers created from files or by the high-level API + +#ifndef PLM_BUFFER_DEFAULT_SIZE +#define PLM_BUFFER_DEFAULT_SIZE (128 * 1024) +#endif + +// Create a buffer instance with a filename. Returns NULL if the file could not +// be opened. + +plm_buffer_t *plm_buffer_create_with_filename(const char *filename); + +// Create a buffer instance with a file handle. Pass TRUE to close_when_done +// to let plmpeg call fclose() on the handle when plm_destroy() is called. + +plm_buffer_t *plm_buffer_create_with_file(FIL *fh, int close_when_done); + +// Create a buffer instance with a pointer to memory as source. This assumes +// the whole file is in memory. The bytes are not copied. Pass 1 to +// free_when_done to let plmpeg call free() on the pointer when plm_destroy() +// is called. + +plm_buffer_t *plm_buffer_create_with_memory(uint8_t *bytes, size_t length, int free_when_done); + +// Create an empty buffer with an initial capacity. The buffer will grow +// as needed. Data that has already been read, will be discarded. + +plm_buffer_t *plm_buffer_create_with_capacity(size_t capacity); + +// Create an empty buffer with an initial capacity. The buffer will grow +// as needed. Decoded data will *not* be discarded. This can be used when +// loading a file over the network, without needing to throttle the download. +// It also allows for seeking in the already loaded data. + +plm_buffer_t *plm_buffer_create_for_appending(size_t initial_capacity); + +// Destroy a buffer instance and free all data + +void plm_buffer_destroy(plm_buffer_t *self); + +// Copy data into the buffer. If the data to be written is larger than the +// available space, the buffer will realloc() with a larger capacity. +// Returns the number of bytes written. This will always be the same as the +// passed in length, except when the buffer was created _with_memory() for +// which _write() is forbidden. + +size_t plm_buffer_write(plm_buffer_t *self, uint8_t *bytes, size_t length); + +// Mark the current byte length as the end of this buffer and signal that no +// more data is expected to be written to it. This function should be called +// just after the last plm_buffer_write(). +// For _with_capacity buffers, this is cleared on a plm_buffer_rewind(). + +void plm_buffer_signal_end(plm_buffer_t *self); + +// Set a callback that is called whenever the buffer needs more data + +void plm_buffer_set_load_callback(plm_buffer_t *self, plm_buffer_load_callback fp, void *user); + +// Rewind the buffer back to the beginning. When loading from a file handle, +// this also seeks to the beginning of the file. + +void plm_buffer_rewind(plm_buffer_t *self); + +// Get the total size. For files, this returns the file size. For all other +// types it returns the number of bytes currently in the buffer. + +size_t plm_buffer_get_size(plm_buffer_t *self); + +// Get the number of remaining (yet unread) bytes in the buffer. This can be +// useful to throttle writing. + +size_t plm_buffer_get_remaining(plm_buffer_t *self); + +// Get whether the read position of the buffer is at the end and no more data +// is expected. + +int plm_buffer_has_ended(plm_buffer_t *self); + +// ----------------------------------------------------------------------------- +// plm_demux public API +// Demux an MPEG Program Stream (PS) data into separate packages + +// Various Packet Types + +static const int PLM_DEMUX_PACKET_PRIVATE = 0xBD; +static const int PLM_DEMUX_PACKET_AUDIO_1 = 0xC0; +static const int PLM_DEMUX_PACKET_AUDIO_2 = 0xC1; +static const int PLM_DEMUX_PACKET_AUDIO_3 = 0xC2; +static const int PLM_DEMUX_PACKET_AUDIO_4 = 0xC2; +static const int PLM_DEMUX_PACKET_VIDEO_1 = 0xE0; + +// Create a demuxer with a plm_buffer as source. This will also attempt to read +// the pack and system headers from the buffer. + +plm_demux_t *plm_demux_create(plm_buffer_t *buffer, int destroy_when_done); + +// Destroy a demuxer and free all data. + +void plm_demux_destroy(plm_demux_t *self); + +// Returns TRUE/FALSE whether pack and system headers have been found. This will +// attempt to read the headers if non are present yet. + +int plm_demux_has_headers(plm_demux_t *self); + +// Returns the number of video streams found in the system header. This will +// attempt to read the system header if non is present yet. + +int plm_demux_get_num_video_streams(plm_demux_t *self); + +// Returns the number of audio streams found in the system header. This will +// attempt to read the system header if non is present yet. + +int plm_demux_get_num_audio_streams(plm_demux_t *self); + +// Rewind the internal buffer. See plm_buffer_rewind(). + +void plm_demux_rewind(plm_demux_t *self); + +// Get whether the file has ended. This will be cleared on seeking or rewind. + +int plm_demux_has_ended(plm_demux_t *self); + +// Seek to a packet of the specified type with a PTS just before specified time. +// If force_intra is TRUE, only packets containing an intra frame will be +// considered - this only makes sense when the type is PLM_DEMUX_PACKET_VIDEO_1. +// Note that the specified time is considered 0-based, regardless of the first +// PTS in the data source. + +plm_packet_t *plm_demux_seek(plm_demux_t *self, double time, int type, int force_intra); + +// Get the PTS of the first packet of this type. Returns PLM_PACKET_INVALID_TS +// if not packet of this packet type can be found. + +double plm_demux_get_start_time(plm_demux_t *self, int type); + +// Get the duration for the specified packet type - i.e. the span between the +// the first PTS and the last PTS in the data source. This only makes sense when +// the underlying data source is a file or fixed memory. + +double plm_demux_get_duration(plm_demux_t *self, int type); + +// Decode and return the next packet. The returned packet_t is valid until +// the next call to plm_demux_decode() or until the demuxer is destroyed. + +plm_packet_t *plm_demux_decode(plm_demux_t *self); + +// ----------------------------------------------------------------------------- +// plm_video public API +// Decode MPEG1 Video ("mpeg1") data into raw YCrCb frames + +// Create a video decoder with a plm_buffer as source. + +plm_video_t *plm_video_create_with_buffer(plm_buffer_t *buffer, int destroy_when_done); + +// Destroy a video decoder and free all data. + +void plm_video_destroy(plm_video_t *self); + +// Get whether a sequence header was found and we can accurately report on +// dimensions and framerate. + +int plm_video_has_header(plm_video_t *self); + +// Get the framerate in frames per second. + +double plm_video_get_framerate(plm_video_t *self); + +// Get the display width/height. + +int plm_video_get_width(plm_video_t *self); +int plm_video_get_height(plm_video_t *self); + +// Set "no delay" mode. When enabled, the decoder assumes that the video does +// *not* contain any B-Frames. This is useful for reducing lag when streaming. +// The default is FALSE. + +void plm_video_set_no_delay(plm_video_t *self, int no_delay); + +// Get the current internal time in seconds. + +double plm_video_get_time(plm_video_t *self); + +// Set the current internal time in seconds. This is only useful when you +// manipulate the underlying video buffer and want to enforce a correct +// timestamps. + +void plm_video_set_time(plm_video_t *self, double time); + +// Rewind the internal buffer. See plm_buffer_rewind(). + +void plm_video_rewind(plm_video_t *self); + +// Get whether the file has ended. This will be cleared on rewind. + +int plm_video_has_ended(plm_video_t *self); + +// Decode and return one frame of video and advance the internal time by +// 1/framerate seconds. The returned frame_t is valid until the next call of +// plm_video_decode() or until the video decoder is destroyed. + +plm_frame_t *plm_video_decode(plm_video_t *self); + +// Convert the YCrCb data of a frame into interleaved R G B data. The stride +// specifies the width in bytes of the destination buffer. I.e. the number of +// bytes from one line to the next. The stride must be at least +// (frame->width * bytes_per_pixel). The buffer pointed to by *dest must have a +// size of at least (stride * frame->height). +// Note that the alpha component of the dest buffer is always left untouched. + +void plm_frame_to_rgb(plm_frame_t *frame, uint8_t *dest, int stride); +void plm_frame_to_bgr(plm_frame_t *frame, uint8_t *dest, int stride); +void plm_frame_to_rgba(plm_frame_t *frame, uint8_t *dest, int stride); +void plm_frame_to_bgra(plm_frame_t *frame, uint8_t *dest, int stride); +void plm_frame_to_argb(plm_frame_t *frame, uint8_t *dest, int stride); +void plm_frame_to_abgr(plm_frame_t *frame, uint8_t *dest, int stride); + +// ----------------------------------------------------------------------------- +// plm_audio public API +// Decode MPEG-1 Audio Layer II ("mp2") data into raw samples + +// Create an audio decoder with a plm_buffer as source. + +plm_audio_t *plm_audio_create_with_buffer(plm_buffer_t *buffer, int destroy_when_done); + +// Destroy an audio decoder and free all data. + +void plm_audio_destroy(plm_audio_t *self); + +// Get whether a frame header was found and we can accurately report on +// samplerate. + +int plm_audio_has_header(plm_audio_t *self); + +// Get the samplerate in samples per second. + +int plm_audio_get_samplerate(plm_audio_t *self); + +// Get the current internal time in seconds. + +double plm_audio_get_time(plm_audio_t *self); + +// Set the current internal time in seconds. This is only useful when you +// manipulate the underlying video buffer and want to enforce a correct +// timestamps. + +void plm_audio_set_time(plm_audio_t *self, double time); + +// Rewind the internal buffer. See plm_buffer_rewind(). + +void plm_audio_rewind(plm_audio_t *self); + +// Get whether the file has ended. This will be cleared on rewind. + +int plm_audio_has_ended(plm_audio_t *self); + +// Decode and return one "frame" of audio and advance the internal time by +// (PLM_AUDIO_SAMPLES_PER_FRAME/samplerate) seconds. The returned samples_t +// is valid until the next call of plm_audio_decode() or until the audio +// decoder is destroyed. + +plm_samples_t *plm_audio_decode(plm_audio_t *self); + +#ifdef __cplusplus +} +#endif + +#endif // PL_MPEG_H + +// ----------------------------------------------------------------------------- +// ----------------------------------------------------------------------------- +// IMPLEMENTATION + +#ifdef PL_MPEG_IMPLEMENTATION + +#include +#include + +#ifndef TRUE +#define TRUE 1 +#define FALSE 0 +#endif + +#ifndef PLM_MALLOC +#define PLM_MALLOC(sz) malloc(sz) +#define PLM_FREE(p) free(p) +#define PLM_REALLOC(p, sz) realloc(p, sz) +#endif + +#define PLM_UNUSED(expr) (void)(expr) + +// ----------------------------------------------------------------------------- +// plm (high-level interface) implementation + +struct plm_t { + plm_demux_t *demux; + double time; + int has_ended; + int loop; + int has_decoders; + + int video_enabled; + int video_packet_type; + plm_buffer_t *video_buffer; + plm_video_t *video_decoder; + + int audio_enabled; + int audio_stream_index; + int audio_packet_type; + double audio_lead_time; + plm_buffer_t *audio_buffer; + plm_audio_t *audio_decoder; + + plm_video_decode_callback video_decode_callback; + void *video_decode_callback_user_data; + + plm_audio_decode_callback audio_decode_callback; + void *audio_decode_callback_user_data; +}; + +int plm_init_decoders(plm_t *self); +void plm_handle_end(plm_t *self); +void plm_read_video_packet(plm_buffer_t *buffer, void *user); +void plm_read_audio_packet(plm_buffer_t *buffer, void *user); +void plm_read_packets(plm_t *self, int requested_type); + +plm_t *plm_create_with_filename(const char *filename) { + plm_buffer_t *buffer = plm_buffer_create_with_filename(filename); + if (!buffer) { + return NULL; + } + return plm_create_with_buffer(buffer, TRUE); +} + +plm_t *plm_create_with_file(FIL *fh, int close_when_done) { + plm_buffer_t *buffer = plm_buffer_create_with_file(fh, close_when_done); + return plm_create_with_buffer(buffer, TRUE); +} + +plm_t *plm_create_with_memory(uint8_t *bytes, size_t length, int free_when_done) { + plm_buffer_t *buffer = plm_buffer_create_with_memory(bytes, length, free_when_done); + return plm_create_with_buffer(buffer, TRUE); +} + +plm_t *plm_create_with_buffer(plm_buffer_t *buffer, int destroy_when_done) { + plm_t *self = (plm_t *)PLM_MALLOC(sizeof(plm_t)); + memset(self, 0, sizeof(plm_t)); + + self->demux = plm_demux_create(buffer, destroy_when_done); + self->video_enabled = TRUE; + self->audio_enabled = TRUE; + plm_init_decoders(self); + + return self; +} + +int plm_init_decoders(plm_t *self) { + if (self->has_decoders) { + return TRUE; + } + + if (!plm_demux_has_headers(self->demux)) { + return FALSE; + } + + if (plm_demux_get_num_video_streams(self->demux) > 0) { + if (self->video_enabled) { + self->video_packet_type = PLM_DEMUX_PACKET_VIDEO_1; + } + self->video_buffer = plm_buffer_create_with_capacity(PLM_BUFFER_DEFAULT_SIZE); + plm_buffer_set_load_callback(self->video_buffer, plm_read_video_packet, self); + } + + if (plm_demux_get_num_audio_streams(self->demux) > 0) { + if (self->audio_enabled) { + self->audio_packet_type = PLM_DEMUX_PACKET_AUDIO_1 + self->audio_stream_index; + } + self->audio_buffer = plm_buffer_create_with_capacity(PLM_BUFFER_DEFAULT_SIZE); + plm_buffer_set_load_callback(self->audio_buffer, plm_read_audio_packet, self); + } + + if (self->video_buffer) { + self->video_decoder = plm_video_create_with_buffer(self->video_buffer, TRUE); + } + + if (self->audio_buffer) { + self->audio_decoder = plm_audio_create_with_buffer(self->audio_buffer, TRUE); + } + + self->has_decoders = TRUE; + return TRUE; +} + +void plm_destroy(plm_t *self) { + if (self->video_decoder) { + plm_video_destroy(self->video_decoder); + } + if (self->audio_decoder) { + plm_audio_destroy(self->audio_decoder); + } + + plm_demux_destroy(self->demux); + PLM_FREE(self); +} + +int plm_get_audio_enabled(plm_t *self) { return self->audio_enabled; } + +int plm_has_headers(plm_t *self) { + if (!plm_demux_has_headers(self->demux)) { + return FALSE; + } + + if (!plm_init_decoders(self)) { + return FALSE; + } + + if ((self->video_decoder && !plm_video_has_header(self->video_decoder)) || + (self->audio_decoder && !plm_audio_has_header(self->audio_decoder))) { + return FALSE; + } + + return TRUE; +} + +void plm_set_audio_enabled(plm_t *self, int enabled) { + self->audio_enabled = enabled; + + if (!enabled) { + self->audio_packet_type = 0; + return; + } + + self->audio_packet_type = + (plm_init_decoders(self) && self->audio_decoder) ? PLM_DEMUX_PACKET_AUDIO_1 + self->audio_stream_index : 0; +} + +void plm_set_audio_stream(plm_t *self, int stream_index) { + if (stream_index < 0 || stream_index > 3) { + return; + } + self->audio_stream_index = stream_index; + + // Set the correct audio_packet_type + plm_set_audio_enabled(self, self->audio_enabled); +} + +int plm_get_video_enabled(plm_t *self) { return self->video_enabled; } + +void plm_set_video_enabled(plm_t *self, int enabled) { + self->video_enabled = enabled; + + if (!enabled) { + self->video_packet_type = 0; + return; + } + + self->video_packet_type = (plm_init_decoders(self) && self->video_decoder) ? PLM_DEMUX_PACKET_VIDEO_1 : 0; +} + +int plm_get_num_video_streams(plm_t *self) { return plm_demux_get_num_video_streams(self->demux); } + +int plm_get_width(plm_t *self) { + return (plm_init_decoders(self) && self->video_decoder) ? plm_video_get_width(self->video_decoder) : 0; +} + +int plm_get_height(plm_t *self) { + return (plm_init_decoders(self) && self->video_decoder) ? plm_video_get_height(self->video_decoder) : 0; +} + +double plm_get_framerate(plm_t *self) { + return (plm_init_decoders(self) && self->video_decoder) ? plm_video_get_framerate(self->video_decoder) : 0; +} + +int plm_get_num_audio_streams(plm_t *self) { return plm_demux_get_num_audio_streams(self->demux); } + +int plm_get_samplerate(plm_t *self) { + return (plm_init_decoders(self) && self->audio_decoder) ? plm_audio_get_samplerate(self->audio_decoder) : 0; +} + +double plm_get_audio_lead_time(plm_t *self) { return self->audio_lead_time; } + +void plm_set_audio_lead_time(plm_t *self, double lead_time) { self->audio_lead_time = lead_time; } + +double plm_get_time(plm_t *self) { return self->time; } + +double plm_get_duration(plm_t *self) { return plm_demux_get_duration(self->demux, PLM_DEMUX_PACKET_VIDEO_1); } + +void plm_rewind(plm_t *self) { + if (self->video_decoder) { + plm_video_rewind(self->video_decoder); + } + + if (self->audio_decoder) { + plm_audio_rewind(self->audio_decoder); + } + + plm_demux_rewind(self->demux); + self->time = 0; +} + +int plm_get_loop(plm_t *self) { return self->loop; } + +void plm_set_loop(plm_t *self, int loop) { self->loop = loop; } + +int plm_has_ended(plm_t *self) { return self->has_ended; } + +void plm_set_video_decode_callback(plm_t *self, plm_video_decode_callback fp, void *user) { + self->video_decode_callback = fp; + self->video_decode_callback_user_data = user; +} + +void plm_set_audio_decode_callback(plm_t *self, plm_audio_decode_callback fp, void *user) { + self->audio_decode_callback = fp; + self->audio_decode_callback_user_data = user; +} + +void plm_decode(plm_t *self, double tick) { + if (!plm_init_decoders(self)) { + return; + } + + int decode_video = (self->video_decode_callback && self->video_packet_type); + int decode_audio = (self->audio_decode_callback && self->audio_packet_type); + + if (!decode_video && !decode_audio) { + // Nothing to do here + return; + } + + int did_decode = FALSE; + int decode_video_failed = FALSE; + int decode_audio_failed = FALSE; + + double video_target_time = self->time + tick; + double audio_target_time = self->time + tick + self->audio_lead_time; + + do { + did_decode = FALSE; + + if (decode_video && plm_video_get_time(self->video_decoder) < video_target_time) { + plm_frame_t *frame = plm_video_decode(self->video_decoder); + if (frame) { + self->video_decode_callback(self, frame, self->video_decode_callback_user_data); + did_decode = TRUE; + } else { + decode_video_failed = TRUE; + } + } + + if (decode_audio && plm_audio_get_time(self->audio_decoder) < audio_target_time) { + plm_samples_t *samples = plm_audio_decode(self->audio_decoder); + if (samples) { + self->audio_decode_callback(self, samples, self->audio_decode_callback_user_data); + did_decode = TRUE; + } else { + decode_audio_failed = TRUE; + } + } + } while (did_decode); + + // Did all sources we wanted to decode fail and the demuxer is at the end? + if ((!decode_video || decode_video_failed) && (!decode_audio || decode_audio_failed) && + plm_demux_has_ended(self->demux)) { + plm_handle_end(self); + return; + } + + self->time += tick; +} + +plm_frame_t *plm_decode_video(plm_t *self) { + if (!plm_init_decoders(self)) { + return NULL; + } + + if (!self->video_packet_type) { + return NULL; + } + + plm_frame_t *frame = plm_video_decode(self->video_decoder); + if (frame) { + self->time = frame->time; + } else if (plm_demux_has_ended(self->demux)) { + plm_handle_end(self); + } + return frame; +} + +plm_samples_t *plm_decode_audio(plm_t *self) { + if (!plm_init_decoders(self)) { + return NULL; + } + + if (!self->audio_packet_type) { + return NULL; + } + + plm_samples_t *samples = plm_audio_decode(self->audio_decoder); + if (samples) { + self->time = samples->time; + } else if (plm_demux_has_ended(self->demux)) { + plm_handle_end(self); + } + return samples; +} + +void plm_handle_end(plm_t *self) { + if (self->loop) { + plm_rewind(self); + } else { + self->has_ended = TRUE; + } +} + +void plm_read_video_packet(plm_buffer_t *buffer, void *user) { + PLM_UNUSED(buffer); + plm_t *self = (plm_t *)user; + plm_read_packets(self, self->video_packet_type); +} + +void plm_read_audio_packet(plm_buffer_t *buffer, void *user) { + PLM_UNUSED(buffer); + plm_t *self = (plm_t *)user; + plm_read_packets(self, self->audio_packet_type); +} + +void plm_read_packets(plm_t *self, int requested_type) { + plm_packet_t *packet; + while ((packet = plm_demux_decode(self->demux))) { + if (packet->type == self->video_packet_type) { + plm_buffer_write(self->video_buffer, packet->data, packet->length); + } else if (packet->type == self->audio_packet_type) { + plm_buffer_write(self->audio_buffer, packet->data, packet->length); + } + + if (packet->type == requested_type) { + return; + } + } + + if (plm_demux_has_ended(self->demux)) { + if (self->video_buffer) { + plm_buffer_signal_end(self->video_buffer); + } + if (self->audio_buffer) { + plm_buffer_signal_end(self->audio_buffer); + } + } +} + +plm_frame_t *plm_seek_frame(plm_t *self, double time, int seek_exact) { + if (!plm_init_decoders(self)) { + return NULL; + } + + if (!self->video_packet_type) { + return NULL; + } + + int type = self->video_packet_type; + + double start_time = plm_demux_get_start_time(self->demux, type); + double duration = plm_demux_get_duration(self->demux, type); + + if (time < 0) { + time = 0; + } else if (time > duration) { + time = duration; + } + + plm_packet_t *packet = plm_demux_seek(self->demux, time, type, TRUE); + if (!packet) { + return NULL; + } + + // Disable writing to the audio buffer while decoding video + int previous_audio_packet_type = self->audio_packet_type; + self->audio_packet_type = 0; + + // Clear video buffer and decode the found packet + plm_video_rewind(self->video_decoder); + plm_video_set_time(self->video_decoder, packet->pts - start_time); + plm_buffer_write(self->video_buffer, packet->data, packet->length); + plm_frame_t *frame = plm_video_decode(self->video_decoder); + + // If we want to seek to an exact frame, we have to decode all frames + // on top of the intra frame we just jumped to. + if (seek_exact) { + while (frame && frame->time < time) { + frame = plm_video_decode(self->video_decoder); + } + } + + // Enable writing to the audio buffer again? + self->audio_packet_type = previous_audio_packet_type; + + if (frame) { + self->time = frame->time; + } + + self->has_ended = FALSE; + return frame; +} + +int plm_seek(plm_t *self, double time, int seek_exact) { + plm_frame_t *frame = plm_seek_frame(self, time, seek_exact); + + if (!frame) { + return FALSE; + } + + if (self->video_decode_callback) { + self->video_decode_callback(self, frame, self->video_decode_callback_user_data); + } + + // If audio is not enabled we are done here. + if (!self->audio_packet_type) { + return TRUE; + } + + // Sync up Audio. This demuxes more packets until the first audio packet + // with a PTS greater than the current time is found. plm_decode() is then + // called to decode enough audio data to satisfy the audio_lead_time. + + double start_time = plm_demux_get_start_time(self->demux, self->video_packet_type); + plm_audio_rewind(self->audio_decoder); + + plm_packet_t *packet = NULL; + while ((packet = plm_demux_decode(self->demux))) { + if (packet->type == self->video_packet_type) { + plm_buffer_write(self->video_buffer, packet->data, packet->length); + } else if (packet->type == self->audio_packet_type && packet->pts - start_time > self->time) { + plm_audio_set_time(self->audio_decoder, packet->pts - start_time); + plm_buffer_write(self->audio_buffer, packet->data, packet->length); + plm_decode(self, 0); + break; + } + } + + return TRUE; +} + +// ----------------------------------------------------------------------------- +// plm_buffer implementation + +enum plm_buffer_mode { PLM_BUFFER_MODE_FILE, PLM_BUFFER_MODE_FIXED_MEM, PLM_BUFFER_MODE_RING, PLM_BUFFER_MODE_APPEND }; + +struct plm_buffer_t { + size_t bit_index; + size_t capacity; + size_t length; + size_t total_size; + int discard_read_bytes; + int has_ended; + int free_when_done; + int close_when_done; + FIL *fh; + plm_buffer_load_callback load_callback; + void *load_callback_user_data; + uint8_t *bytes; + enum plm_buffer_mode mode; +}; + +typedef struct { + int16_t index; + int16_t value; +} plm_vlc_t; + +typedef struct { + int16_t index; + uint16_t value; +} plm_vlc_uint_t; + +void plm_buffer_seek(plm_buffer_t *self, size_t pos); +size_t plm_buffer_tell(plm_buffer_t *self); +void plm_buffer_discard_read_bytes(plm_buffer_t *self); +void plm_buffer_load_file_callback(plm_buffer_t *self, void *user); + +int plm_buffer_has(plm_buffer_t *self, size_t count); +int plm_buffer_read(plm_buffer_t *self, int count); +void plm_buffer_align(plm_buffer_t *self); +void plm_buffer_skip(plm_buffer_t *self, size_t count); +int plm_buffer_skip_bytes(plm_buffer_t *self, uint8_t v); +int plm_buffer_next_start_code(plm_buffer_t *self); +int plm_buffer_find_start_code(plm_buffer_t *self, int code); +int plm_buffer_no_start_code(plm_buffer_t *self); +int16_t plm_buffer_read_vlc(plm_buffer_t *self, const plm_vlc_t *table); +uint16_t plm_buffer_read_vlc_uint(plm_buffer_t *self, const plm_vlc_uint_t *table); + +plm_buffer_t *plm_buffer_create_with_filename(const char *filename) { + FIL *fh = vexFileOpen(filename, "rb"); // fopen(filename, "rb"); + if (!fh) { + return NULL; + } + return plm_buffer_create_with_file(fh, TRUE); +} + +plm_buffer_t *plm_buffer_create_with_file(FIL *fh, int close_when_done) { + plm_buffer_t *self = plm_buffer_create_with_capacity(PLM_BUFFER_DEFAULT_SIZE); + self->fh = fh; + self->close_when_done = close_when_done; + self->mode = PLM_BUFFER_MODE_FILE; + self->discard_read_bytes = TRUE; + + vexFileSeek(self->fh, 0, SEEK_END); + self->total_size = vexFileTell(self->fh); + vexFileSeek(self->fh, 0, SEEK_SET); + + plm_buffer_set_load_callback(self, plm_buffer_load_file_callback, NULL); + return self; +} + +plm_buffer_t *plm_buffer_create_with_memory(uint8_t *bytes, size_t length, int free_when_done) { + plm_buffer_t *self = (plm_buffer_t *)PLM_MALLOC(sizeof(plm_buffer_t)); + memset(self, 0, sizeof(plm_buffer_t)); + self->capacity = length; + self->length = length; + self->total_size = length; + self->free_when_done = free_when_done; + self->bytes = bytes; + self->mode = PLM_BUFFER_MODE_FIXED_MEM; + self->discard_read_bytes = FALSE; + return self; +} + +plm_buffer_t *plm_buffer_create_with_capacity(size_t capacity) { + plm_buffer_t *self = (plm_buffer_t *)PLM_MALLOC(sizeof(plm_buffer_t)); + memset(self, 0, sizeof(plm_buffer_t)); + self->capacity = capacity; + self->free_when_done = TRUE; + self->bytes = (uint8_t *)PLM_MALLOC(capacity); + self->mode = PLM_BUFFER_MODE_RING; + self->discard_read_bytes = TRUE; + return self; +} + +plm_buffer_t *plm_buffer_create_for_appending(size_t initial_capacity) { + plm_buffer_t *self = plm_buffer_create_with_capacity(initial_capacity); + self->mode = PLM_BUFFER_MODE_APPEND; + self->discard_read_bytes = FALSE; + return self; +} + +void plm_buffer_destroy(plm_buffer_t *self) { + if (self->fh && self->close_when_done) { + vexFileClose(self->fh); + } + if (self->free_when_done) { + PLM_FREE(self->bytes); + } + PLM_FREE(self); +} + +size_t plm_buffer_get_size(plm_buffer_t *self) { + return (self->mode == PLM_BUFFER_MODE_FILE) ? self->total_size : self->length; +} + +size_t plm_buffer_get_remaining(plm_buffer_t *self) { return self->length - (self->bit_index >> 3); } + +size_t plm_buffer_write(plm_buffer_t *self, uint8_t *bytes, size_t length) { + if (self->mode == PLM_BUFFER_MODE_FIXED_MEM) { + return 0; + } + + if (self->discard_read_bytes) { + // This should be a ring buffer, but instead it just shifts all unread + // data to the beginning of the buffer and appends new data at the end. + // Seems to be good enough. + + plm_buffer_discard_read_bytes(self); + if (self->mode == PLM_BUFFER_MODE_RING) { + self->total_size = 0; + } + } + + // Do we have to resize to fit the new data? + size_t bytes_available = self->capacity - self->length; + if (bytes_available < length) { + size_t new_size = self->capacity; + do { + new_size *= 2; + } while (new_size - self->length < length); + self->bytes = (uint8_t *)PLM_REALLOC(self->bytes, new_size); + self->capacity = new_size; + } + + memcpy(self->bytes + self->length, bytes, length); + self->length += length; + self->has_ended = FALSE; + return length; +} + +void plm_buffer_signal_end(plm_buffer_t *self) { self->total_size = self->length; } + +void plm_buffer_set_load_callback(plm_buffer_t *self, plm_buffer_load_callback fp, void *user) { + self->load_callback = fp; + self->load_callback_user_data = user; +} + +void plm_buffer_rewind(plm_buffer_t *self) { plm_buffer_seek(self, 0); } + +void plm_buffer_seek(plm_buffer_t *self, size_t pos) { + self->has_ended = FALSE; + + if (self->mode == PLM_BUFFER_MODE_FILE) { + vexFileSeek(self->fh, pos, SEEK_SET); + self->bit_index = 0; + self->length = 0; + } else if (self->mode == PLM_BUFFER_MODE_RING) { + if (pos != 0) { + // Seeking to non-0 is forbidden for dynamic-mem buffers + return; + } + self->bit_index = 0; + self->length = 0; + self->total_size = 0; + } else if (pos < self->length) { + self->bit_index = pos << 3; + } +} + +size_t plm_buffer_tell(plm_buffer_t *self) { + return self->mode == PLM_BUFFER_MODE_FILE ? vexFileTell(self->fh) + (self->bit_index >> 3) - self->length + : self->bit_index >> 3; +} + +void plm_buffer_discard_read_bytes(plm_buffer_t *self) { + size_t byte_pos = self->bit_index >> 3; + if (byte_pos == self->length) { + self->bit_index = 0; + self->length = 0; + } else if (byte_pos > 0) { + memmove(self->bytes, self->bytes + byte_pos, self->length - byte_pos); + self->bit_index -= byte_pos << 3; + self->length -= byte_pos; + } +} + +void plm_buffer_load_file_callback(plm_buffer_t *self, void *user) { + PLM_UNUSED(user); + + if (self->discard_read_bytes) { + plm_buffer_discard_read_bytes(self); + } + + size_t bytes_available = self->capacity - self->length; + size_t bytes_read = vexFileRead((char *)self->bytes + self->length, 1, bytes_available, self->fh); + self->length += bytes_read; + + if (bytes_read == 0) { + self->has_ended = TRUE; + } +} + +int plm_buffer_has_ended(plm_buffer_t *self) { return self->has_ended; } + +int plm_buffer_has(plm_buffer_t *self, size_t count) { + if (((self->length << 3) - self->bit_index) >= count) { + return TRUE; + } + + if (self->load_callback) { + self->load_callback(self, self->load_callback_user_data); + + if (((self->length << 3) - self->bit_index) >= count) { + return TRUE; + } + } + + if (self->total_size != 0 && self->length == self->total_size) { + self->has_ended = TRUE; + } + return FALSE; +} + +int plm_buffer_read(plm_buffer_t *self, int count) { + if (!plm_buffer_has(self, count)) { + return 0; + } + + int value = 0; + while (count) { + int current_byte = self->bytes[self->bit_index >> 3]; + + int remaining = 8 - (self->bit_index & 7); // Remaining bits in byte + int read = remaining < count ? remaining : count; // Bits in self run + int shift = remaining - read; + int mask = (0xff >> (8 - read)); + + value = (value << read) | ((current_byte & (mask << shift)) >> shift); + + self->bit_index += read; + count -= read; + } + + return value; +} + +void plm_buffer_align(plm_buffer_t *self) { + self->bit_index = ((self->bit_index + 7) >> 3) << 3; // Align to next byte +} + +void plm_buffer_skip(plm_buffer_t *self, size_t count) { + if (plm_buffer_has(self, count)) { + self->bit_index += count; + } +} + +int plm_buffer_skip_bytes(plm_buffer_t *self, uint8_t v) { + plm_buffer_align(self); + int skipped = 0; + while (plm_buffer_has(self, 8) && self->bytes[self->bit_index >> 3] == v) { + self->bit_index += 8; + skipped++; + } + return skipped; +} + +int plm_buffer_next_start_code(plm_buffer_t *self) { + plm_buffer_align(self); + + while (plm_buffer_has(self, (5 << 3))) { + size_t byte_index = (self->bit_index) >> 3; + if (self->bytes[byte_index] == 0x00 && self->bytes[byte_index + 1] == 0x00 && self->bytes[byte_index + 2] == 0x01) { + self->bit_index = (byte_index + 4) << 3; + return self->bytes[byte_index + 3]; + } + self->bit_index += 8; + } + return -1; +} + +int plm_buffer_find_start_code(plm_buffer_t *self, int code) { + int current = 0; + while (TRUE) { + current = plm_buffer_next_start_code(self); + if (current == code || current == -1) { + return current; + } + } + return -1; +} + +int plm_buffer_has_start_code(plm_buffer_t *self, int code) { + size_t previous_bit_index = self->bit_index; + int previous_discard_read_bytes = self->discard_read_bytes; + + self->discard_read_bytes = FALSE; + int current = plm_buffer_find_start_code(self, code); + + self->bit_index = previous_bit_index; + self->discard_read_bytes = previous_discard_read_bytes; + return current; +} + +int plm_buffer_peek_non_zero(plm_buffer_t *self, int bit_count) { + if (!plm_buffer_has(self, bit_count)) { + return FALSE; + } + + int val = plm_buffer_read(self, bit_count); + self->bit_index -= bit_count; + return val != 0; +} + +int16_t plm_buffer_read_vlc(plm_buffer_t *self, const plm_vlc_t *table) { + plm_vlc_t state = {0, 0}; + do { + state = table[state.index + plm_buffer_read(self, 1)]; + } while (state.index > 0); + return state.value; +} + +uint16_t plm_buffer_read_vlc_uint(plm_buffer_t *self, const plm_vlc_uint_t *table) { + return (uint16_t)plm_buffer_read_vlc(self, (const plm_vlc_t *)table); +} + +// ---------------------------------------------------------------------------- +// plm_demux implementation + +static const int PLM_START_PACK = 0xBA; +static const int PLM_START_END = 0xB9; +static const int PLM_START_SYSTEM = 0xBB; + +struct plm_demux_t { + plm_buffer_t *buffer; + int destroy_buffer_when_done; + double system_clock_ref; + + size_t last_file_size; + double last_decoded_pts; + double start_time; + double duration; + + int start_code; + int has_pack_header; + int has_system_header; + int has_headers; + + int num_audio_streams; + int num_video_streams; + plm_packet_t current_packet; + plm_packet_t next_packet; +}; + +void plm_demux_buffer_seek(plm_demux_t *self, size_t pos); +double plm_demux_decode_time(plm_demux_t *self); +plm_packet_t *plm_demux_decode_packet(plm_demux_t *self, int type); +plm_packet_t *plm_demux_get_packet(plm_demux_t *self); + +plm_demux_t *plm_demux_create(plm_buffer_t *buffer, int destroy_when_done) { + plm_demux_t *self = (plm_demux_t *)PLM_MALLOC(sizeof(plm_demux_t)); + memset(self, 0, sizeof(plm_demux_t)); + + self->buffer = buffer; + self->destroy_buffer_when_done = destroy_when_done; + + self->start_time = PLM_PACKET_INVALID_TS; + self->duration = PLM_PACKET_INVALID_TS; + self->start_code = -1; + + plm_demux_has_headers(self); + return self; +} + +void plm_demux_destroy(plm_demux_t *self) { + if (self->destroy_buffer_when_done) { + plm_buffer_destroy(self->buffer); + } + PLM_FREE(self); +} + +int plm_demux_has_headers(plm_demux_t *self) { + if (self->has_headers) { + return TRUE; + } + + // Decode pack header + if (!self->has_pack_header) { + if (self->start_code != PLM_START_PACK && plm_buffer_find_start_code(self->buffer, PLM_START_PACK) == -1) { + return FALSE; + } + + self->start_code = PLM_START_PACK; + if (!plm_buffer_has(self->buffer, 64)) { + return FALSE; + } + self->start_code = -1; + + if (plm_buffer_read(self->buffer, 4) != 0x02) { + return FALSE; + } + + self->system_clock_ref = plm_demux_decode_time(self); + plm_buffer_skip(self->buffer, 1); + plm_buffer_skip(self->buffer, 22); // mux_rate * 50 + plm_buffer_skip(self->buffer, 1); + + self->has_pack_header = TRUE; + } + + // Decode system header + if (!self->has_system_header) { + if (self->start_code != PLM_START_SYSTEM && plm_buffer_find_start_code(self->buffer, PLM_START_SYSTEM) == -1) { + return FALSE; + } + + self->start_code = PLM_START_SYSTEM; + if (!plm_buffer_has(self->buffer, 56)) { + return FALSE; + } + self->start_code = -1; + + plm_buffer_skip(self->buffer, 16); // header_length + plm_buffer_skip(self->buffer, 24); // rate bound + self->num_audio_streams = plm_buffer_read(self->buffer, 6); + plm_buffer_skip(self->buffer, 5); // misc flags + self->num_video_streams = plm_buffer_read(self->buffer, 5); + + self->has_system_header = TRUE; + } + + self->has_headers = TRUE; + return TRUE; +} + +int plm_demux_get_num_video_streams(plm_demux_t *self) { + return plm_demux_has_headers(self) ? self->num_video_streams : 0; +} + +int plm_demux_get_num_audio_streams(plm_demux_t *self) { + return plm_demux_has_headers(self) ? self->num_audio_streams : 0; +} + +void plm_demux_rewind(plm_demux_t *self) { + plm_buffer_rewind(self->buffer); + self->current_packet.length = 0; + self->next_packet.length = 0; + self->start_code = -1; +} + +int plm_demux_has_ended(plm_demux_t *self) { return plm_buffer_has_ended(self->buffer); } + +void plm_demux_buffer_seek(plm_demux_t *self, size_t pos) { + plm_buffer_seek(self->buffer, pos); + self->current_packet.length = 0; + self->next_packet.length = 0; + self->start_code = -1; +} + +double plm_demux_get_start_time(plm_demux_t *self, int type) { + if (self->start_time != PLM_PACKET_INVALID_TS) { + return self->start_time; + } + + int previous_pos = plm_buffer_tell(self->buffer); + int previous_start_code = self->start_code; + + // Find first video PTS + plm_demux_rewind(self); + do { + plm_packet_t *packet = plm_demux_decode(self); + if (!packet) { + break; + } + if (packet->type == type) { + self->start_time = packet->pts; + } + } while (self->start_time == PLM_PACKET_INVALID_TS); + + plm_demux_buffer_seek(self, previous_pos); + self->start_code = previous_start_code; + return self->start_time; +} + +double plm_demux_get_duration(plm_demux_t *self, int type) { + size_t file_size = plm_buffer_get_size(self->buffer); + + if (self->duration != PLM_PACKET_INVALID_TS && self->last_file_size == file_size) { + return self->duration; + } + + size_t previous_pos = plm_buffer_tell(self->buffer); + int previous_start_code = self->start_code; + + // Find last video PTS. Start searching 64kb from the end and go further + // back if needed. + long start_range = 64 * 1024; + long max_range = 4096 * 1024; + for (long range = start_range; range <= max_range; range *= 2) { + long seek_pos = file_size - range; + if (seek_pos < 0) { + seek_pos = 0; + range = max_range; // Make sure to bail after this round + } + plm_demux_buffer_seek(self, seek_pos); + self->current_packet.length = 0; + + double last_pts = PLM_PACKET_INVALID_TS; + plm_packet_t *packet = NULL; + while ((packet = plm_demux_decode(self))) { + if (packet->pts != PLM_PACKET_INVALID_TS && packet->type == type) { + last_pts = packet->pts; + } + } + if (last_pts != PLM_PACKET_INVALID_TS) { + self->duration = last_pts - plm_demux_get_start_time(self, type); + break; + } + } + + plm_demux_buffer_seek(self, previous_pos); + self->start_code = previous_start_code; + self->last_file_size = file_size; + return self->duration; +} + +plm_packet_t *plm_demux_seek(plm_demux_t *self, double seek_time, int type, int force_intra) { + if (!plm_demux_has_headers(self)) { + return NULL; + } + + // Using the current time, current byte position and the average bytes per + // second for this file, try to jump to a byte position that hopefully has + // packets containing timestamps within one second before to the desired + // seek_time. + + // If we hit close to the seek_time scan through all packets to find the + // last one (just before the seek_time) containing an intra frame. + // Otherwise we should at least be closer than before. Calculate the bytes + // per second for the jumped range and jump again. + + // The number of retries here is hard-limited to a generous amount. Usually + // the correct range is found after 1--5 jumps, even for files with very + // variable bitrates. If significantly more jumps are needed, there's + // probably something wrong with the file and we just avoid getting into an + // infinite loop. 32 retries should be enough for anybody. + + double duration = plm_demux_get_duration(self, type); + long file_size = plm_buffer_get_size(self->buffer); + long byterate = file_size / duration; + + double cur_time = self->last_decoded_pts; + double scan_span = 1; + + if (seek_time > duration) { + seek_time = duration; + } else if (seek_time < 0) { + seek_time = 0; + } + seek_time += self->start_time; + + for (int retry = 0; retry < 32; retry++) { + int found_packet_with_pts = FALSE; + int found_packet_in_range = FALSE; + long last_valid_packet_start = -1; + double first_packet_time = PLM_PACKET_INVALID_TS; + + long cur_pos = plm_buffer_tell(self->buffer); + + // Estimate byte offset and jump to it. + long offset = (seek_time - cur_time - scan_span) * byterate; + long seek_pos = cur_pos + offset; + if (seek_pos < 0) { + seek_pos = 0; + } else if (seek_pos > file_size - 256) { + seek_pos = file_size - 256; + } + + plm_demux_buffer_seek(self, seek_pos); + + // Scan through all packets up to the seek_time to find the last packet + // containing an intra frame. + while (plm_buffer_find_start_code(self->buffer, type) != -1) { + long packet_start = plm_buffer_tell(self->buffer); + plm_packet_t *packet = plm_demux_decode_packet(self, type); + + // Skip packet if it has no PTS + if (!packet || packet->pts == PLM_PACKET_INVALID_TS) { + continue; + } + + // Bail scanning through packets if we hit one that is outside + // seek_time - scan_span. + // We also adjust the cur_time and byterate values here so the next + // iteration can be a bit more precise. + if (packet->pts > seek_time || packet->pts < seek_time - scan_span) { + found_packet_with_pts = TRUE; + byterate = (seek_pos - cur_pos) / (packet->pts - cur_time); + cur_time = packet->pts; + break; + } + + // If we are still here, it means this packet is in close range to + // the seek_time. If this is the first packet for this jump position + // record the PTS. If we later have to back off, when there was no + // intra frame in this range, we can lower the seek_time to not scan + // this range again. + if (!found_packet_in_range) { + found_packet_in_range = TRUE; + first_packet_time = packet->pts; + } + + // Check if this is an intra frame packet. If so, record the buffer + // position of the start of this packet. We want to jump back to it + // later, when we know it's the last intra frame before desired + // seek time. + if (force_intra) { + for (size_t i = 0; i < packet->length - 6; i++) { + // Find the START_PICTURE code + if (packet->data[i] == 0x00 && packet->data[i + 1] == 0x00 && packet->data[i + 2] == 0x01 && + packet->data[i + 3] == 0x00) { + // Bits 11--13 in the picture header contain the frame + // type, where 1=Intra + if ((packet->data[i + 5] & 0x38) == 8) { + last_valid_packet_start = packet_start; + } + break; + } + } + } + + // If we don't want intra frames, just use the last PTS found. + else { + last_valid_packet_start = packet_start; + } + } + + // If there was at least one intra frame in the range scanned above, + // our search is over. Jump back to the packet and decode it again. + if (last_valid_packet_start != -1) { + plm_demux_buffer_seek(self, last_valid_packet_start); + return plm_demux_decode_packet(self, type); + } + + // If we hit the right range, but still found no intra frame, we have + // to increases the scan_span. This is done exponentially to also handle + // video files with very few intra frames. + else if (found_packet_in_range) { + scan_span *= 2; + seek_time = first_packet_time; + } + + // If we didn't find any packet with a PTS, it probably means we reached + // the end of the file. Estimate byterate and cur_time accordingly. + else if (!found_packet_with_pts) { + byterate = (seek_pos - cur_pos) / (duration - cur_time); + cur_time = duration; + } + } + + return NULL; +} + +plm_packet_t *plm_demux_decode(plm_demux_t *self) { + if (!plm_demux_has_headers(self)) { + return NULL; + } + + if (self->current_packet.length) { + size_t bits_till_next_packet = self->current_packet.length << 3; + if (!plm_buffer_has(self->buffer, bits_till_next_packet)) { + return NULL; + } + plm_buffer_skip(self->buffer, bits_till_next_packet); + self->current_packet.length = 0; + } + + // Pending packet waiting for data? + if (self->next_packet.length) { + return plm_demux_get_packet(self); + } + + // Pending packet waiting for header? + if (self->start_code != -1) { + return plm_demux_decode_packet(self, self->start_code); + } + + do { + self->start_code = plm_buffer_next_start_code(self->buffer); + if (self->start_code == PLM_DEMUX_PACKET_VIDEO_1 || self->start_code == PLM_DEMUX_PACKET_PRIVATE || + (self->start_code >= PLM_DEMUX_PACKET_AUDIO_1 && self->start_code <= PLM_DEMUX_PACKET_AUDIO_4)) { + return plm_demux_decode_packet(self, self->start_code); + } + } while (self->start_code != -1); + + return NULL; +} + +double plm_demux_decode_time(plm_demux_t *self) { + int64_t clock = plm_buffer_read(self->buffer, 3) << 30; + plm_buffer_skip(self->buffer, 1); + clock |= plm_buffer_read(self->buffer, 15) << 15; + plm_buffer_skip(self->buffer, 1); + clock |= plm_buffer_read(self->buffer, 15); + plm_buffer_skip(self->buffer, 1); + return (double)clock / 90000.0; +} + +plm_packet_t *plm_demux_decode_packet(plm_demux_t *self, int type) { + if (!plm_buffer_has(self->buffer, 16 << 3)) { + return NULL; + } + + self->start_code = -1; + + self->next_packet.type = type; + self->next_packet.length = plm_buffer_read(self->buffer, 16); + self->next_packet.length -= plm_buffer_skip_bytes(self->buffer, 0xff); // stuffing + + // skip P-STD + if (plm_buffer_read(self->buffer, 2) == 0x01) { + plm_buffer_skip(self->buffer, 16); + self->next_packet.length -= 2; + } + + int pts_dts_marker = plm_buffer_read(self->buffer, 2); + if (pts_dts_marker == 0x03) { + self->next_packet.pts = plm_demux_decode_time(self); + self->last_decoded_pts = self->next_packet.pts; + plm_buffer_skip(self->buffer, 40); // skip dts + self->next_packet.length -= 10; + } else if (pts_dts_marker == 0x02) { + self->next_packet.pts = plm_demux_decode_time(self); + self->last_decoded_pts = self->next_packet.pts; + self->next_packet.length -= 5; + } else if (pts_dts_marker == 0x00) { + self->next_packet.pts = PLM_PACKET_INVALID_TS; + plm_buffer_skip(self->buffer, 4); + self->next_packet.length -= 1; + } else { + return NULL; // invalid + } + + return plm_demux_get_packet(self); +} + +plm_packet_t *plm_demux_get_packet(plm_demux_t *self) { + if (!plm_buffer_has(self->buffer, self->next_packet.length << 3)) { + return NULL; + } + + self->current_packet.data = self->buffer->bytes + (self->buffer->bit_index >> 3); + self->current_packet.length = self->next_packet.length; + self->current_packet.type = self->next_packet.type; + self->current_packet.pts = self->next_packet.pts; + + self->next_packet.length = 0; + return &self->current_packet; +} + +// ----------------------------------------------------------------------------- +// plm_video implementation + +// Inspired by Java MPEG-1 Video Decoder and Player by Zoltan Korandi +// https://sourceforge.net/projects/javampeg1video/ + +static const int PLM_VIDEO_PICTURE_TYPE_INTRA = 1; +static const int PLM_VIDEO_PICTURE_TYPE_PREDICTIVE = 2; +static const int PLM_VIDEO_PICTURE_TYPE_B = 3; + +static const int PLM_START_SEQUENCE = 0xB3; +static const int PLM_START_SLICE_FIRST = 0x01; +static const int PLM_START_SLICE_LAST = 0xAF; +static const int PLM_START_PICTURE = 0x00; +static const int PLM_START_EXTENSION = 0xB5; +static const int PLM_START_USER_DATA = 0xB2; + +#define PLM_START_IS_SLICE(c) (c >= PLM_START_SLICE_FIRST && c <= PLM_START_SLICE_LAST) + +static const double PLM_VIDEO_PICTURE_RATE[] = {0.000, 23.976, 24.000, 25.000, 29.970, 30.000, 50.000, 59.940, + 60.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000}; + +static const uint8_t PLM_VIDEO_ZIG_ZAG[] = {0, 1, 8, 16, 9, 2, 3, 10, 17, 24, 32, 25, 18, 11, 4, 5, + 12, 19, 26, 33, 40, 48, 41, 34, 27, 20, 13, 6, 7, 14, 21, 28, + 35, 42, 49, 56, 57, 50, 43, 36, 29, 22, 15, 23, 30, 37, 44, 51, + 58, 59, 52, 45, 38, 31, 39, 46, 53, 60, 61, 54, 47, 55, 62, 63}; + +static const uint8_t PLM_VIDEO_INTRA_QUANT_MATRIX[] = {8, 16, 19, 22, 26, 27, 29, 34, 16, 16, 22, 24, 27, 29, 34, 37, + 19, 22, 26, 27, 29, 34, 34, 38, 22, 22, 26, 27, 29, 34, 37, 40, + 22, 26, 27, 29, 32, 35, 40, 48, 26, 27, 29, 32, 35, 40, 48, 58, + 26, 27, 29, 34, 38, 46, 56, 69, 27, 29, 35, 38, 46, 56, 69, 83}; + +static const uint8_t PLM_VIDEO_NON_INTRA_QUANT_MATRIX[] = { + 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, + 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, + 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16}; + +static const uint8_t PLM_VIDEO_PREMULTIPLIER_MATRIX[] = {32, 44, 42, 38, 32, 25, 17, 9, 44, 62, 58, 52, 44, 35, 24, 12, + 42, 58, 55, 49, 42, 33, 23, 12, 38, 52, 49, 44, 38, 30, 20, 10, + 32, 44, 42, 38, 32, 25, 17, 9, 25, 35, 33, 30, 25, 20, 14, 7, + 17, 24, 23, 20, 17, 14, 9, 5, 9, 12, 12, 10, 9, 7, 5, 2}; + +static const plm_vlc_t PLM_VIDEO_MACROBLOCK_ADDRESS_INCREMENT[] = { + {1 << 1, 0}, {0, 1}, // 0: x + {2 << 1, 0}, {3 << 1, 0}, // 1: 0x + {4 << 1, 0}, {5 << 1, 0}, // 2: 00x + {0, 3}, {0, 2}, // 3: 01x + {6 << 1, 0}, {7 << 1, 0}, // 4: 000x + {0, 5}, {0, 4}, // 5: 001x + {8 << 1, 0}, {9 << 1, 0}, // 6: 0000x + {0, 7}, {0, 6}, // 7: 0001x + {10 << 1, 0}, {11 << 1, 0}, // 8: 0000 0x + {12 << 1, 0}, {13 << 1, 0}, // 9: 0000 1x + {14 << 1, 0}, {15 << 1, 0}, // 10: 0000 00x + {16 << 1, 0}, {17 << 1, 0}, // 11: 0000 01x + {18 << 1, 0}, {19 << 1, 0}, // 12: 0000 10x + {0, 9}, {0, 8}, // 13: 0000 11x + {-1, 0}, {20 << 1, 0}, // 14: 0000 000x + {-1, 0}, {21 << 1, 0}, // 15: 0000 001x + {22 << 1, 0}, {23 << 1, 0}, // 16: 0000 010x + {0, 15}, {0, 14}, // 17: 0000 011x + {0, 13}, {0, 12}, // 18: 0000 100x + {0, 11}, {0, 10}, // 19: 0000 101x + {24 << 1, 0}, {25 << 1, 0}, // 20: 0000 0001x + {26 << 1, 0}, {27 << 1, 0}, // 21: 0000 0011x + {28 << 1, 0}, {29 << 1, 0}, // 22: 0000 0100x + {30 << 1, 0}, {31 << 1, 0}, // 23: 0000 0101x + {32 << 1, 0}, {-1, 0}, // 24: 0000 0001 0x + {-1, 0}, {33 << 1, 0}, // 25: 0000 0001 1x + {34 << 1, 0}, {35 << 1, 0}, // 26: 0000 0011 0x + {36 << 1, 0}, {37 << 1, 0}, // 27: 0000 0011 1x + {38 << 1, 0}, {39 << 1, 0}, // 28: 0000 0100 0x + {0, 21}, {0, 20}, // 29: 0000 0100 1x + {0, 19}, {0, 18}, // 30: 0000 0101 0x + {0, 17}, {0, 16}, // 31: 0000 0101 1x + {0, 35}, {-1, 0}, // 32: 0000 0001 00x + {-1, 0}, {0, 34}, // 33: 0000 0001 11x + {0, 33}, {0, 32}, // 34: 0000 0011 00x + {0, 31}, {0, 30}, // 35: 0000 0011 01x + {0, 29}, {0, 28}, // 36: 0000 0011 10x + {0, 27}, {0, 26}, // 37: 0000 0011 11x + {0, 25}, {0, 24}, // 38: 0000 0100 00x + {0, 23}, {0, 22}, // 39: 0000 0100 01x +}; + +static const plm_vlc_t PLM_VIDEO_MACROBLOCK_TYPE_INTRA[] = { + {1 << 1, 0}, + {0, 0x01}, // 0: x + {-1, 0}, + {0, 0x11}, // 1: 0x +}; + +static const plm_vlc_t PLM_VIDEO_MACROBLOCK_TYPE_PREDICTIVE[] = { + {1 << 1, 0}, {0, 0x0a}, // 0: x + {2 << 1, 0}, {0, 0x02}, // 1: 0x + {3 << 1, 0}, {0, 0x08}, // 2: 00x + {4 << 1, 0}, {5 << 1, 0}, // 3: 000x + {6 << 1, 0}, {0, 0x12}, // 4: 0000x + {0, 0x1a}, {0, 0x01}, // 5: 0001x + {-1, 0}, {0, 0x11}, // 6: 0000 0x +}; + +static const plm_vlc_t PLM_VIDEO_MACROBLOCK_TYPE_B[] = { + {1 << 1, 0}, {2 << 1, 0}, // 0: x + {3 << 1, 0}, {4 << 1, 0}, // 1: 0x + {0, 0x0c}, {0, 0x0e}, // 2: 1x + {5 << 1, 0}, {6 << 1, 0}, // 3: 00x + {0, 0x04}, {0, 0x06}, // 4: 01x + {7 << 1, 0}, {8 << 1, 0}, // 5: 000x + {0, 0x08}, {0, 0x0a}, // 6: 001x + {9 << 1, 0}, {10 << 1, 0}, // 7: 0000x + {0, 0x1e}, {0, 0x01}, // 8: 0001x + {-1, 0}, {0, 0x11}, // 9: 0000 0x + {0, 0x16}, {0, 0x1a}, // 10: 0000 1x +}; + +static const plm_vlc_t *PLM_VIDEO_MACROBLOCK_TYPE[] = { + NULL, PLM_VIDEO_MACROBLOCK_TYPE_INTRA, PLM_VIDEO_MACROBLOCK_TYPE_PREDICTIVE, PLM_VIDEO_MACROBLOCK_TYPE_B}; + +static const plm_vlc_t PLM_VIDEO_CODE_BLOCK_PATTERN[] = { + {1 << 1, 0}, {2 << 1, 0}, // 0: x + {3 << 1, 0}, {4 << 1, 0}, // 1: 0x + {5 << 1, 0}, {6 << 1, 0}, // 2: 1x + {7 << 1, 0}, {8 << 1, 0}, // 3: 00x + {9 << 1, 0}, {10 << 1, 0}, // 4: 01x + {11 << 1, 0}, {12 << 1, 0}, // 5: 10x + {13 << 1, 0}, {0, 60}, // 6: 11x + {14 << 1, 0}, {15 << 1, 0}, // 7: 000x + {16 << 1, 0}, {17 << 1, 0}, // 8: 001x + {18 << 1, 0}, {19 << 1, 0}, // 9: 010x + {20 << 1, 0}, {21 << 1, 0}, // 10: 011x + {22 << 1, 0}, {23 << 1, 0}, // 11: 100x + {0, 32}, {0, 16}, // 12: 101x + {0, 8}, {0, 4}, // 13: 110x + {24 << 1, 0}, {25 << 1, 0}, // 14: 0000x + {26 << 1, 0}, {27 << 1, 0}, // 15: 0001x + {28 << 1, 0}, {29 << 1, 0}, // 16: 0010x + {30 << 1, 0}, {31 << 1, 0}, // 17: 0011x + {0, 62}, {0, 2}, // 18: 0100x + {0, 61}, {0, 1}, // 19: 0101x + {0, 56}, {0, 52}, // 20: 0110x + {0, 44}, {0, 28}, // 21: 0111x + {0, 40}, {0, 20}, // 22: 1000x + {0, 48}, {0, 12}, // 23: 1001x + {32 << 1, 0}, {33 << 1, 0}, // 24: 0000 0x + {34 << 1, 0}, {35 << 1, 0}, // 25: 0000 1x + {36 << 1, 0}, {37 << 1, 0}, // 26: 0001 0x + {38 << 1, 0}, {39 << 1, 0}, // 27: 0001 1x + {40 << 1, 0}, {41 << 1, 0}, // 28: 0010 0x + {42 << 1, 0}, {43 << 1, 0}, // 29: 0010 1x + {0, 63}, {0, 3}, // 30: 0011 0x + {0, 36}, {0, 24}, // 31: 0011 1x + {44 << 1, 0}, {45 << 1, 0}, // 32: 0000 00x + {46 << 1, 0}, {47 << 1, 0}, // 33: 0000 01x + {48 << 1, 0}, {49 << 1, 0}, // 34: 0000 10x + {50 << 1, 0}, {51 << 1, 0}, // 35: 0000 11x + {52 << 1, 0}, {53 << 1, 0}, // 36: 0001 00x + {54 << 1, 0}, {55 << 1, 0}, // 37: 0001 01x + {56 << 1, 0}, {57 << 1, 0}, // 38: 0001 10x + {58 << 1, 0}, {59 << 1, 0}, // 39: 0001 11x + {0, 34}, {0, 18}, // 40: 0010 00x + {0, 10}, {0, 6}, // 41: 0010 01x + {0, 33}, {0, 17}, // 42: 0010 10x + {0, 9}, {0, 5}, // 43: 0010 11x + {-1, 0}, {60 << 1, 0}, // 44: 0000 000x + {61 << 1, 0}, {62 << 1, 0}, // 45: 0000 001x + {0, 58}, {0, 54}, // 46: 0000 010x + {0, 46}, {0, 30}, // 47: 0000 011x + {0, 57}, {0, 53}, // 48: 0000 100x + {0, 45}, {0, 29}, // 49: 0000 101x + {0, 38}, {0, 26}, // 50: 0000 110x + {0, 37}, {0, 25}, // 51: 0000 111x + {0, 43}, {0, 23}, // 52: 0001 000x + {0, 51}, {0, 15}, // 53: 0001 001x + {0, 42}, {0, 22}, // 54: 0001 010x + {0, 50}, {0, 14}, // 55: 0001 011x + {0, 41}, {0, 21}, // 56: 0001 100x + {0, 49}, {0, 13}, // 57: 0001 101x + {0, 35}, {0, 19}, // 58: 0001 110x + {0, 11}, {0, 7}, // 59: 0001 111x + {0, 39}, {0, 27}, // 60: 0000 0001x + {0, 59}, {0, 55}, // 61: 0000 0010x + {0, 47}, {0, 31}, // 62: 0000 0011x +}; + +static const plm_vlc_t PLM_VIDEO_MOTION[] = { + {1 << 1, 0}, {0, 0}, // 0: x + {2 << 1, 0}, {3 << 1, 0}, // 1: 0x + {4 << 1, 0}, {5 << 1, 0}, // 2: 00x + {0, 1}, {0, -1}, // 3: 01x + {6 << 1, 0}, {7 << 1, 0}, // 4: 000x + {0, 2}, {0, -2}, // 5: 001x + {8 << 1, 0}, {9 << 1, 0}, // 6: 0000x + {0, 3}, {0, -3}, // 7: 0001x + {10 << 1, 0}, {11 << 1, 0}, // 8: 0000 0x + {12 << 1, 0}, {13 << 1, 0}, // 9: 0000 1x + {-1, 0}, {14 << 1, 0}, // 10: 0000 00x + {15 << 1, 0}, {16 << 1, 0}, // 11: 0000 01x + {17 << 1, 0}, {18 << 1, 0}, // 12: 0000 10x + {0, 4}, {0, -4}, // 13: 0000 11x + {-1, 0}, {19 << 1, 0}, // 14: 0000 001x + {20 << 1, 0}, {21 << 1, 0}, // 15: 0000 010x + {0, 7}, {0, -7}, // 16: 0000 011x + {0, 6}, {0, -6}, // 17: 0000 100x + {0, 5}, {0, -5}, // 18: 0000 101x + {22 << 1, 0}, {23 << 1, 0}, // 19: 0000 0011x + {24 << 1, 0}, {25 << 1, 0}, // 20: 0000 0100x + {26 << 1, 0}, {27 << 1, 0}, // 21: 0000 0101x + {28 << 1, 0}, {29 << 1, 0}, // 22: 0000 0011 0x + {30 << 1, 0}, {31 << 1, 0}, // 23: 0000 0011 1x + {32 << 1, 0}, {33 << 1, 0}, // 24: 0000 0100 0x + {0, 10}, {0, -10}, // 25: 0000 0100 1x + {0, 9}, {0, -9}, // 26: 0000 0101 0x + {0, 8}, {0, -8}, // 27: 0000 0101 1x + {0, 16}, {0, -16}, // 28: 0000 0011 00x + {0, 15}, {0, -15}, // 29: 0000 0011 01x + {0, 14}, {0, -14}, // 30: 0000 0011 10x + {0, 13}, {0, -13}, // 31: 0000 0011 11x + {0, 12}, {0, -12}, // 32: 0000 0100 00x + {0, 11}, {0, -11}, // 33: 0000 0100 01x +}; + +static const plm_vlc_t PLM_VIDEO_DCT_SIZE_LUMINANCE[] = { + {1 << 1, 0}, {2 << 1, 0}, // 0: x + {0, 1}, {0, 2}, // 1: 0x + {3 << 1, 0}, {4 << 1, 0}, // 2: 1x + {0, 0}, {0, 3}, // 3: 10x + {0, 4}, {5 << 1, 0}, // 4: 11x + {0, 5}, {6 << 1, 0}, // 5: 111x + {0, 6}, {7 << 1, 0}, // 6: 1111x + {0, 7}, {8 << 1, 0}, // 7: 1111 1x + {0, 8}, {-1, 0}, // 8: 1111 11x +}; + +static const plm_vlc_t PLM_VIDEO_DCT_SIZE_CHROMINANCE[] = { + {1 << 1, 0}, {2 << 1, 0}, // 0: x + {0, 0}, {0, 1}, // 1: 0x + {0, 2}, {3 << 1, 0}, // 2: 1x + {0, 3}, {4 << 1, 0}, // 3: 11x + {0, 4}, {5 << 1, 0}, // 4: 111x + {0, 5}, {6 << 1, 0}, // 5: 1111x + {0, 6}, {7 << 1, 0}, // 6: 1111 1x + {0, 7}, {8 << 1, 0}, // 7: 1111 11x + {0, 8}, {-1, 0}, // 8: 1111 111x +}; + +static const plm_vlc_t *PLM_VIDEO_DCT_SIZE[] = {PLM_VIDEO_DCT_SIZE_LUMINANCE, PLM_VIDEO_DCT_SIZE_CHROMINANCE, + PLM_VIDEO_DCT_SIZE_CHROMINANCE}; + +// dct_coeff bitmap: +// 0xff00 run +// 0x00ff level + +// Decoded values are unsigned. Sign bit follows in the stream. + +static const plm_vlc_uint_t PLM_VIDEO_DCT_COEFF[] = { + {1 << 1, 0}, {0, 0x0001}, // 0: x + {2 << 1, 0}, {3 << 1, 0}, // 1: 0x + {4 << 1, 0}, {5 << 1, 0}, // 2: 00x + {6 << 1, 0}, {0, 0x0101}, // 3: 01x + {7 << 1, 0}, {8 << 1, 0}, // 4: 000x + {9 << 1, 0}, {10 << 1, 0}, // 5: 001x + {0, 0x0002}, {0, 0x0201}, // 6: 010x + {11 << 1, 0}, {12 << 1, 0}, // 7: 0000x + {13 << 1, 0}, {14 << 1, 0}, // 8: 0001x + {15 << 1, 0}, {0, 0x0003}, // 9: 0010x + {0, 0x0401}, {0, 0x0301}, // 10: 0011x + {16 << 1, 0}, {0, 0xffff}, // 11: 0000 0x + {17 << 1, 0}, {18 << 1, 0}, // 12: 0000 1x + {0, 0x0701}, {0, 0x0601}, // 13: 0001 0x + {0, 0x0102}, {0, 0x0501}, // 14: 0001 1x + {19 << 1, 0}, {20 << 1, 0}, // 15: 0010 0x + {21 << 1, 0}, {22 << 1, 0}, // 16: 0000 00x + {0, 0x0202}, {0, 0x0901}, // 17: 0000 10x + {0, 0x0004}, {0, 0x0801}, // 18: 0000 11x + {23 << 1, 0}, {24 << 1, 0}, // 19: 0010 00x + {25 << 1, 0}, {26 << 1, 0}, // 20: 0010 01x + {27 << 1, 0}, {28 << 1, 0}, // 21: 0000 000x + {29 << 1, 0}, {30 << 1, 0}, // 22: 0000 001x + {0, 0x0d01}, {0, 0x0006}, // 23: 0010 000x + {0, 0x0c01}, {0, 0x0b01}, // 24: 0010 001x + {0, 0x0302}, {0, 0x0103}, // 25: 0010 010x + {0, 0x0005}, {0, 0x0a01}, // 26: 0010 011x + {31 << 1, 0}, {32 << 1, 0}, // 27: 0000 0000x + {33 << 1, 0}, {34 << 1, 0}, // 28: 0000 0001x + {35 << 1, 0}, {36 << 1, 0}, // 29: 0000 0010x + {37 << 1, 0}, {38 << 1, 0}, // 30: 0000 0011x + {39 << 1, 0}, {40 << 1, 0}, // 31: 0000 0000 0x + {41 << 1, 0}, {42 << 1, 0}, // 32: 0000 0000 1x + {43 << 1, 0}, {44 << 1, 0}, // 33: 0000 0001 0x + {45 << 1, 0}, {46 << 1, 0}, // 34: 0000 0001 1x + {0, 0x1001}, {0, 0x0502}, // 35: 0000 0010 0x + {0, 0x0007}, {0, 0x0203}, // 36: 0000 0010 1x + {0, 0x0104}, {0, 0x0f01}, // 37: 0000 0011 0x + {0, 0x0e01}, {0, 0x0402}, // 38: 0000 0011 1x + {47 << 1, 0}, {48 << 1, 0}, // 39: 0000 0000 00x + {49 << 1, 0}, {50 << 1, 0}, // 40: 0000 0000 01x + {51 << 1, 0}, {52 << 1, 0}, // 41: 0000 0000 10x + {53 << 1, 0}, {54 << 1, 0}, // 42: 0000 0000 11x + {55 << 1, 0}, {56 << 1, 0}, // 43: 0000 0001 00x + {57 << 1, 0}, {58 << 1, 0}, // 44: 0000 0001 01x + {59 << 1, 0}, {60 << 1, 0}, // 45: 0000 0001 10x + {61 << 1, 0}, {62 << 1, 0}, // 46: 0000 0001 11x + {-1, 0}, {63 << 1, 0}, // 47: 0000 0000 000x + {64 << 1, 0}, {65 << 1, 0}, // 48: 0000 0000 001x + {66 << 1, 0}, {67 << 1, 0}, // 49: 0000 0000 010x + {68 << 1, 0}, {69 << 1, 0}, // 50: 0000 0000 011x + {70 << 1, 0}, {71 << 1, 0}, // 51: 0000 0000 100x + {72 << 1, 0}, {73 << 1, 0}, // 52: 0000 0000 101x + {74 << 1, 0}, {75 << 1, 0}, // 53: 0000 0000 110x + {76 << 1, 0}, {77 << 1, 0}, // 54: 0000 0000 111x + {0, 0x000b}, {0, 0x0802}, // 55: 0000 0001 000x + {0, 0x0403}, {0, 0x000a}, // 56: 0000 0001 001x + {0, 0x0204}, {0, 0x0702}, // 57: 0000 0001 010x + {0, 0x1501}, {0, 0x1401}, // 58: 0000 0001 011x + {0, 0x0009}, {0, 0x1301}, // 59: 0000 0001 100x + {0, 0x1201}, {0, 0x0105}, // 60: 0000 0001 101x + {0, 0x0303}, {0, 0x0008}, // 61: 0000 0001 110x + {0, 0x0602}, {0, 0x1101}, // 62: 0000 0001 111x + {78 << 1, 0}, {79 << 1, 0}, // 63: 0000 0000 0001x + {80 << 1, 0}, {81 << 1, 0}, // 64: 0000 0000 0010x + {82 << 1, 0}, {83 << 1, 0}, // 65: 0000 0000 0011x + {84 << 1, 0}, {85 << 1, 0}, // 66: 0000 0000 0100x + {86 << 1, 0}, {87 << 1, 0}, // 67: 0000 0000 0101x + {88 << 1, 0}, {89 << 1, 0}, // 68: 0000 0000 0110x + {90 << 1, 0}, {91 << 1, 0}, // 69: 0000 0000 0111x + {0, 0x0a02}, {0, 0x0902}, // 70: 0000 0000 1000x + {0, 0x0503}, {0, 0x0304}, // 71: 0000 0000 1001x + {0, 0x0205}, {0, 0x0107}, // 72: 0000 0000 1010x + {0, 0x0106}, {0, 0x000f}, // 73: 0000 0000 1011x + {0, 0x000e}, {0, 0x000d}, // 74: 0000 0000 1100x + {0, 0x000c}, {0, 0x1a01}, // 75: 0000 0000 1101x + {0, 0x1901}, {0, 0x1801}, // 76: 0000 0000 1110x + {0, 0x1701}, {0, 0x1601}, // 77: 0000 0000 1111x + {92 << 1, 0}, {93 << 1, 0}, // 78: 0000 0000 0001 0x + {94 << 1, 0}, {95 << 1, 0}, // 79: 0000 0000 0001 1x + {96 << 1, 0}, {97 << 1, 0}, // 80: 0000 0000 0010 0x + {98 << 1, 0}, {99 << 1, 0}, // 81: 0000 0000 0010 1x + {100 << 1, 0}, {101 << 1, 0}, // 82: 0000 0000 0011 0x + {102 << 1, 0}, {103 << 1, 0}, // 83: 0000 0000 0011 1x + {0, 0x001f}, {0, 0x001e}, // 84: 0000 0000 0100 0x + {0, 0x001d}, {0, 0x001c}, // 85: 0000 0000 0100 1x + {0, 0x001b}, {0, 0x001a}, // 86: 0000 0000 0101 0x + {0, 0x0019}, {0, 0x0018}, // 87: 0000 0000 0101 1x + {0, 0x0017}, {0, 0x0016}, // 88: 0000 0000 0110 0x + {0, 0x0015}, {0, 0x0014}, // 89: 0000 0000 0110 1x + {0, 0x0013}, {0, 0x0012}, // 90: 0000 0000 0111 0x + {0, 0x0011}, {0, 0x0010}, // 91: 0000 0000 0111 1x + {104 << 1, 0}, {105 << 1, 0}, // 92: 0000 0000 0001 00x + {106 << 1, 0}, {107 << 1, 0}, // 93: 0000 0000 0001 01x + {108 << 1, 0}, {109 << 1, 0}, // 94: 0000 0000 0001 10x + {110 << 1, 0}, {111 << 1, 0}, // 95: 0000 0000 0001 11x + {0, 0x0028}, {0, 0x0027}, // 96: 0000 0000 0010 00x + {0, 0x0026}, {0, 0x0025}, // 97: 0000 0000 0010 01x + {0, 0x0024}, {0, 0x0023}, // 98: 0000 0000 0010 10x + {0, 0x0022}, {0, 0x0021}, // 99: 0000 0000 0010 11x + {0, 0x0020}, {0, 0x010e}, // 100: 0000 0000 0011 00x + {0, 0x010d}, {0, 0x010c}, // 101: 0000 0000 0011 01x + {0, 0x010b}, {0, 0x010a}, // 102: 0000 0000 0011 10x + {0, 0x0109}, {0, 0x0108}, // 103: 0000 0000 0011 11x + {0, 0x0112}, {0, 0x0111}, // 104: 0000 0000 0001 000x + {0, 0x0110}, {0, 0x010f}, // 105: 0000 0000 0001 001x + {0, 0x0603}, {0, 0x1002}, // 106: 0000 0000 0001 010x + {0, 0x0f02}, {0, 0x0e02}, // 107: 0000 0000 0001 011x + {0, 0x0d02}, {0, 0x0c02}, // 108: 0000 0000 0001 100x + {0, 0x0b02}, {0, 0x1f01}, // 109: 0000 0000 0001 101x + {0, 0x1e01}, {0, 0x1d01}, // 110: 0000 0000 0001 110x + {0, 0x1c01}, {0, 0x1b01}, // 111: 0000 0000 0001 111x +}; + +typedef struct { + int full_px; + int is_set; + int r_size; + int h; + int v; +} plm_video_motion_t; + +struct plm_video_t { + double framerate; + double time; + int frames_decoded; + int width; + int height; + int mb_width; + int mb_height; + int mb_size; + + int luma_width; + int luma_height; + + int chroma_width; + int chroma_height; + + int start_code; + int picture_type; + + plm_video_motion_t motion_forward; + plm_video_motion_t motion_backward; + + int has_sequence_header; + + int quantizer_scale; + int slice_begin; + int macroblock_address; + + int mb_row; + int mb_col; + + int macroblock_type; + int macroblock_intra; + + int dc_predictor[3]; + + plm_buffer_t *buffer; + int destroy_buffer_when_done; + + plm_frame_t frame_current; + plm_frame_t frame_forward; + plm_frame_t frame_backward; + + uint8_t *frames_data; + + int block_data[64]; + uint8_t intra_quant_matrix[64]; + uint8_t non_intra_quant_matrix[64]; + + int has_reference_frame; + int assume_no_b_frames; +}; + +static inline uint8_t plm_clamp(int n) { + if (n > 255) { + n = 255; + } else if (n < 0) { + n = 0; + } + return n; +} + +int plm_video_decode_sequence_header(plm_video_t *self); +void plm_video_init_frame(plm_video_t *self, plm_frame_t *frame, uint8_t *base); +void plm_video_decode_picture(plm_video_t *self); +void plm_video_decode_slice(plm_video_t *self, int slice); +void plm_video_decode_macroblock(plm_video_t *self); +void plm_video_decode_motion_vectors(plm_video_t *self); +int plm_video_decode_motion_vector(plm_video_t *self, int r_size, int motion); +void plm_video_predict_macroblock(plm_video_t *self); +void plm_video_copy_macroblock(plm_video_t *self, plm_frame_t *s, int motion_h, int motion_v); +void plm_video_interpolate_macroblock(plm_video_t *self, plm_frame_t *s, int motion_h, int motion_v); +void plm_video_process_macroblock(plm_video_t *self, uint8_t *s, uint8_t *d, int mh, int mb, int bs, int interp); +void plm_video_decode_block(plm_video_t *self, int block); +void plm_video_idct(int *block); + +plm_video_t *plm_video_create_with_buffer(plm_buffer_t *buffer, int destroy_when_done) { + plm_video_t *self = (plm_video_t *)PLM_MALLOC(sizeof(plm_video_t)); + memset(self, 0, sizeof(plm_video_t)); + + self->buffer = buffer; + self->destroy_buffer_when_done = destroy_when_done; + + // Attempt to decode the sequence header + self->start_code = plm_buffer_find_start_code(self->buffer, PLM_START_SEQUENCE); + if (self->start_code != -1) { + plm_video_decode_sequence_header(self); + } + return self; +} + +void plm_video_destroy(plm_video_t *self) { + if (self->destroy_buffer_when_done) { + plm_buffer_destroy(self->buffer); + } + + if (self->has_sequence_header) { + PLM_FREE(self->frames_data); + } + + PLM_FREE(self); +} + +double plm_video_get_framerate(plm_video_t *self) { return plm_video_has_header(self) ? self->framerate : 0; } + +int plm_video_get_width(plm_video_t *self) { return plm_video_has_header(self) ? self->width : 0; } + +int plm_video_get_height(plm_video_t *self) { return plm_video_has_header(self) ? self->height : 0; } + +void plm_video_set_no_delay(plm_video_t *self, int no_delay) { self->assume_no_b_frames = no_delay; } + +double plm_video_get_time(plm_video_t *self) { return self->time; } + +void plm_video_set_time(plm_video_t *self, double time) { + self->frames_decoded = self->framerate * time; + self->time = time; +} + +void plm_video_rewind(plm_video_t *self) { + plm_buffer_rewind(self->buffer); + self->time = 0; + self->frames_decoded = 0; + self->has_reference_frame = FALSE; + self->start_code = -1; +} + +int plm_video_has_ended(plm_video_t *self) { return plm_buffer_has_ended(self->buffer); } + +plm_frame_t *plm_video_decode(plm_video_t *self) { + if (!plm_video_has_header(self)) { + return NULL; + } + + plm_frame_t *frame = NULL; + do { + if (self->start_code != PLM_START_PICTURE) { + self->start_code = plm_buffer_find_start_code(self->buffer, PLM_START_PICTURE); + + if (self->start_code == -1) { + // If we reached the end of the file and the previously decoded + // frame was a reference frame, we still have to return it. + if (self->has_reference_frame && !self->assume_no_b_frames && plm_buffer_has_ended(self->buffer) && + (self->picture_type == PLM_VIDEO_PICTURE_TYPE_INTRA || + self->picture_type == PLM_VIDEO_PICTURE_TYPE_PREDICTIVE)) { + self->has_reference_frame = FALSE; + frame = &self->frame_backward; + break; + } + + return NULL; + } + } + + // Make sure we have a full picture in the buffer before attempting to + // decode it. Sadly, this can only be done by seeking for the start code + // of the next picture. Also, if we didn't find the start code for the + // next picture, but the source has ended, we assume that this last + // picture is in the buffer. + if (plm_buffer_has_start_code(self->buffer, PLM_START_PICTURE) == -1 && !plm_buffer_has_ended(self->buffer)) { + return NULL; + } + plm_buffer_discard_read_bytes(self->buffer); + + plm_video_decode_picture(self); + + if (self->assume_no_b_frames) { + frame = &self->frame_backward; + } else if (self->picture_type == PLM_VIDEO_PICTURE_TYPE_B) { + frame = &self->frame_current; + } else if (self->has_reference_frame) { + frame = &self->frame_forward; + } else { + self->has_reference_frame = TRUE; + } + } while (!frame); + + frame->time = self->time; + self->frames_decoded++; + self->time = (double)self->frames_decoded / self->framerate; + + return frame; +} + +int plm_video_has_header(plm_video_t *self) { + if (self->has_sequence_header) { + return TRUE; + } + + if (self->start_code != PLM_START_SEQUENCE) { + self->start_code = plm_buffer_find_start_code(self->buffer, PLM_START_SEQUENCE); + } + if (self->start_code == -1) { + return FALSE; + } + + if (!plm_video_decode_sequence_header(self)) { + return FALSE; + } + + return TRUE; +} + +int plm_video_decode_sequence_header(plm_video_t *self) { + int max_header_size = 64 + 2 * 64 * 8; // 64 bit header + 2x 64 byte matrix + if (!plm_buffer_has(self->buffer, max_header_size)) { + return FALSE; + } + + self->width = plm_buffer_read(self->buffer, 12); + self->height = plm_buffer_read(self->buffer, 12); + + if (self->width <= 0 || self->height <= 0) { + return FALSE; + } + + // Skip pixel aspect ratio + plm_buffer_skip(self->buffer, 4); + + self->framerate = PLM_VIDEO_PICTURE_RATE[plm_buffer_read(self->buffer, 4)]; + + // Skip bit_rate, marker, buffer_size and constrained bit + plm_buffer_skip(self->buffer, 18 + 1 + 10 + 1); + + // Load custom intra quant matrix? + if (plm_buffer_read(self->buffer, 1)) { + for (int i = 0; i < 64; i++) { + int idx = PLM_VIDEO_ZIG_ZAG[i]; + self->intra_quant_matrix[idx] = plm_buffer_read(self->buffer, 8); + } + } else { + memcpy(self->intra_quant_matrix, PLM_VIDEO_INTRA_QUANT_MATRIX, 64); + } + + // Load custom non intra quant matrix? + if (plm_buffer_read(self->buffer, 1)) { + for (int i = 0; i < 64; i++) { + int idx = PLM_VIDEO_ZIG_ZAG[i]; + self->non_intra_quant_matrix[idx] = plm_buffer_read(self->buffer, 8); + } + } else { + memcpy(self->non_intra_quant_matrix, PLM_VIDEO_NON_INTRA_QUANT_MATRIX, 64); + } + + self->mb_width = (self->width + 15) >> 4; + self->mb_height = (self->height + 15) >> 4; + self->mb_size = self->mb_width * self->mb_height; + + self->luma_width = self->mb_width << 4; + self->luma_height = self->mb_height << 4; + + self->chroma_width = self->mb_width << 3; + self->chroma_height = self->mb_height << 3; + + // Allocate one big chunk of data for all 3 frames = 9 planes + size_t luma_plane_size = self->luma_width * self->luma_height; + size_t chroma_plane_size = self->chroma_width * self->chroma_height; + size_t frame_data_size = (luma_plane_size + 2 * chroma_plane_size); + + self->frames_data = (uint8_t *)PLM_MALLOC(frame_data_size * 3); + plm_video_init_frame(self, &self->frame_current, self->frames_data + frame_data_size * 0); + plm_video_init_frame(self, &self->frame_forward, self->frames_data + frame_data_size * 1); + plm_video_init_frame(self, &self->frame_backward, self->frames_data + frame_data_size * 2); + + self->has_sequence_header = TRUE; + return TRUE; +} + +void plm_video_init_frame(plm_video_t *self, plm_frame_t *frame, uint8_t *base) { + size_t luma_plane_size = self->luma_width * self->luma_height; + size_t chroma_plane_size = self->chroma_width * self->chroma_height; + + frame->width = self->width; + frame->height = self->height; + frame->y.width = self->luma_width; + frame->y.height = self->luma_height; + frame->y.data = base; + + frame->cr.width = self->chroma_width; + frame->cr.height = self->chroma_height; + frame->cr.data = base + luma_plane_size; + + frame->cb.width = self->chroma_width; + frame->cb.height = self->chroma_height; + frame->cb.data = base + luma_plane_size + chroma_plane_size; +} + +void plm_video_decode_picture(plm_video_t *self) { + plm_buffer_skip(self->buffer, 10); // skip temporalReference + self->picture_type = plm_buffer_read(self->buffer, 3); + plm_buffer_skip(self->buffer, 16); // skip vbv_delay + + // D frames or unknown coding type + if (self->picture_type <= 0 || self->picture_type > PLM_VIDEO_PICTURE_TYPE_B) { + return; + } + + // Forward full_px, f_code + if (self->picture_type == PLM_VIDEO_PICTURE_TYPE_PREDICTIVE || self->picture_type == PLM_VIDEO_PICTURE_TYPE_B) { + self->motion_forward.full_px = plm_buffer_read(self->buffer, 1); + int f_code = plm_buffer_read(self->buffer, 3); + if (f_code == 0) { + // Ignore picture with zero f_code + return; + } + self->motion_forward.r_size = f_code - 1; + } + + // Backward full_px, f_code + if (self->picture_type == PLM_VIDEO_PICTURE_TYPE_B) { + self->motion_backward.full_px = plm_buffer_read(self->buffer, 1); + int f_code = plm_buffer_read(self->buffer, 3); + if (f_code == 0) { + // Ignore picture with zero f_code + return; + } + self->motion_backward.r_size = f_code - 1; + } + + plm_frame_t frame_temp = self->frame_forward; + if (self->picture_type == PLM_VIDEO_PICTURE_TYPE_INTRA || self->picture_type == PLM_VIDEO_PICTURE_TYPE_PREDICTIVE) { + self->frame_forward = self->frame_backward; + } + + // Find first slice start code; skip extension and user data + do { + self->start_code = plm_buffer_next_start_code(self->buffer); + } while (self->start_code == PLM_START_EXTENSION || self->start_code == PLM_START_USER_DATA); + + // Decode all slices + while (PLM_START_IS_SLICE(self->start_code)) { + plm_video_decode_slice(self, self->start_code & 0x000000FF); + if (self->macroblock_address >= self->mb_size - 2) { + break; + } + self->start_code = plm_buffer_next_start_code(self->buffer); + } + + // If this is a reference picture rotate the prediction pointers + if (self->picture_type == PLM_VIDEO_PICTURE_TYPE_INTRA || self->picture_type == PLM_VIDEO_PICTURE_TYPE_PREDICTIVE) { + self->frame_backward = self->frame_current; + self->frame_current = frame_temp; + } +} + +void plm_video_decode_slice(plm_video_t *self, int slice) { + self->slice_begin = TRUE; + self->macroblock_address = (slice - 1) * self->mb_width - 1; + + // Reset motion vectors and DC predictors + self->motion_backward.h = self->motion_forward.h = 0; + self->motion_backward.v = self->motion_forward.v = 0; + self->dc_predictor[0] = 128; + self->dc_predictor[1] = 128; + self->dc_predictor[2] = 128; + + self->quantizer_scale = plm_buffer_read(self->buffer, 5); + + // Skip extra + while (plm_buffer_read(self->buffer, 1)) { + plm_buffer_skip(self->buffer, 8); + } + + do { + plm_video_decode_macroblock(self); + } while (self->macroblock_address < self->mb_size - 1 && plm_buffer_peek_non_zero(self->buffer, 23)); +} + +void plm_video_decode_macroblock(plm_video_t *self) { + // Decode increment + int increment = 0; + int t = plm_buffer_read_vlc(self->buffer, PLM_VIDEO_MACROBLOCK_ADDRESS_INCREMENT); + + while (t == 34) { + // macroblock_stuffing + t = plm_buffer_read_vlc(self->buffer, PLM_VIDEO_MACROBLOCK_ADDRESS_INCREMENT); + } + while (t == 35) { + // macroblock_escape + increment += 33; + t = plm_buffer_read_vlc(self->buffer, PLM_VIDEO_MACROBLOCK_ADDRESS_INCREMENT); + } + increment += t; + + // Process any skipped macroblocks + if (self->slice_begin) { + // The first increment of each slice is relative to beginning of the + // previous row, not the previous macroblock + self->slice_begin = FALSE; + self->macroblock_address += increment; + } else { + if (self->macroblock_address + increment >= self->mb_size) { + return; // invalid + } + if (increment > 1) { + // Skipped macroblocks reset DC predictors + self->dc_predictor[0] = 128; + self->dc_predictor[1] = 128; + self->dc_predictor[2] = 128; + + // Skipped macroblocks in P-pictures reset motion vectors + if (self->picture_type == PLM_VIDEO_PICTURE_TYPE_PREDICTIVE) { + self->motion_forward.h = 0; + self->motion_forward.v = 0; + } + } + + // Predict skipped macroblocks + while (increment > 1) { + self->macroblock_address++; + self->mb_row = self->macroblock_address / self->mb_width; + self->mb_col = self->macroblock_address % self->mb_width; + + plm_video_predict_macroblock(self); + increment--; + } + self->macroblock_address++; + } + + self->mb_row = self->macroblock_address / self->mb_width; + self->mb_col = self->macroblock_address % self->mb_width; + + if (self->mb_col >= self->mb_width || self->mb_row >= self->mb_height) { + return; // corrupt stream; + } + + // Process the current macroblock + const plm_vlc_t *table = PLM_VIDEO_MACROBLOCK_TYPE[self->picture_type]; + self->macroblock_type = plm_buffer_read_vlc(self->buffer, table); + + self->macroblock_intra = (self->macroblock_type & 0x01); + self->motion_forward.is_set = (self->macroblock_type & 0x08); + self->motion_backward.is_set = (self->macroblock_type & 0x04); + + // Quantizer scale + if ((self->macroblock_type & 0x10) != 0) { + self->quantizer_scale = plm_buffer_read(self->buffer, 5); + } + + if (self->macroblock_intra) { + // Intra-coded macroblocks reset motion vectors + self->motion_backward.h = self->motion_forward.h = 0; + self->motion_backward.v = self->motion_forward.v = 0; + } else { + // Non-intra macroblocks reset DC predictors + self->dc_predictor[0] = 128; + self->dc_predictor[1] = 128; + self->dc_predictor[2] = 128; + + plm_video_decode_motion_vectors(self); + plm_video_predict_macroblock(self); + } + + // Decode blocks + int cbp = ((self->macroblock_type & 0x02) != 0) ? plm_buffer_read_vlc(self->buffer, PLM_VIDEO_CODE_BLOCK_PATTERN) + : (self->macroblock_intra ? 0x3f : 0); + + for (int block = 0, mask = 0x20; block < 6; block++) { + if ((cbp & mask) != 0) { + plm_video_decode_block(self, block); + } + mask >>= 1; + } +} + +void plm_video_decode_motion_vectors(plm_video_t *self) { + + // Forward + if (self->motion_forward.is_set) { + int r_size = self->motion_forward.r_size; + self->motion_forward.h = plm_video_decode_motion_vector(self, r_size, self->motion_forward.h); + self->motion_forward.v = plm_video_decode_motion_vector(self, r_size, self->motion_forward.v); + } else if (self->picture_type == PLM_VIDEO_PICTURE_TYPE_PREDICTIVE) { + // No motion information in P-picture, reset vectors + self->motion_forward.h = 0; + self->motion_forward.v = 0; + } + + if (self->motion_backward.is_set) { + int r_size = self->motion_backward.r_size; + self->motion_backward.h = plm_video_decode_motion_vector(self, r_size, self->motion_backward.h); + self->motion_backward.v = plm_video_decode_motion_vector(self, r_size, self->motion_backward.v); + } +} + +int plm_video_decode_motion_vector(plm_video_t *self, int r_size, int motion) { + int fscale = 1 << r_size; + int m_code = plm_buffer_read_vlc(self->buffer, PLM_VIDEO_MOTION); + int r = 0; + int d; + + if ((m_code != 0) && (fscale != 1)) { + r = plm_buffer_read(self->buffer, r_size); + d = ((abs(m_code) - 1) << r_size) + r + 1; + if (m_code < 0) { + d = -d; + } + } else { + d = m_code; + } + + motion += d; + if (motion > (fscale << 4) - 1) { + motion -= fscale << 5; + } else if (motion < ((-fscale) << 4)) { + motion += fscale << 5; + } + + return motion; +} + +void plm_video_predict_macroblock(plm_video_t *self) { + int fw_h = self->motion_forward.h; + int fw_v = self->motion_forward.v; + + if (self->motion_forward.full_px) { + fw_h <<= 1; + fw_v <<= 1; + } + + if (self->picture_type == PLM_VIDEO_PICTURE_TYPE_B) { + int bw_h = self->motion_backward.h; + int bw_v = self->motion_backward.v; + + if (self->motion_backward.full_px) { + bw_h <<= 1; + bw_v <<= 1; + } + + if (self->motion_forward.is_set) { + plm_video_copy_macroblock(self, &self->frame_forward, fw_h, fw_v); + if (self->motion_backward.is_set) { + plm_video_interpolate_macroblock(self, &self->frame_backward, bw_h, bw_v); + } + } else { + plm_video_copy_macroblock(self, &self->frame_backward, bw_h, bw_v); + } + } else { + plm_video_copy_macroblock(self, &self->frame_forward, fw_h, fw_v); + } +} + +void plm_video_copy_macroblock(plm_video_t *self, plm_frame_t *s, int motion_h, int motion_v) { + plm_frame_t *d = &self->frame_current; + plm_video_process_macroblock(self, s->y.data, d->y.data, motion_h, motion_v, 16, FALSE); + plm_video_process_macroblock(self, s->cr.data, d->cr.data, motion_h / 2, motion_v / 2, 8, FALSE); + plm_video_process_macroblock(self, s->cb.data, d->cb.data, motion_h / 2, motion_v / 2, 8, FALSE); +} + +void plm_video_interpolate_macroblock(plm_video_t *self, plm_frame_t *s, int motion_h, int motion_v) { + plm_frame_t *d = &self->frame_current; + plm_video_process_macroblock(self, s->y.data, d->y.data, motion_h, motion_v, 16, TRUE); + plm_video_process_macroblock(self, s->cr.data, d->cr.data, motion_h / 2, motion_v / 2, 8, TRUE); + plm_video_process_macroblock(self, s->cb.data, d->cb.data, motion_h / 2, motion_v / 2, 8, TRUE); +} + +#define PLM_BLOCK_SET(DEST, DEST_INDEX, DEST_WIDTH, SOURCE_INDEX, SOURCE_WIDTH, BLOCK_SIZE, OP) \ + do { \ + int dest_scan = DEST_WIDTH - BLOCK_SIZE; \ + int source_scan = SOURCE_WIDTH - BLOCK_SIZE; \ + for (int y = 0; y < BLOCK_SIZE; y++) { \ + for (int x = 0; x < BLOCK_SIZE; x++) { \ + DEST[DEST_INDEX] = OP; \ + SOURCE_INDEX++; \ + DEST_INDEX++; \ + } \ + SOURCE_INDEX += source_scan; \ + DEST_INDEX += dest_scan; \ + } \ + } while (FALSE) + +void plm_video_process_macroblock(plm_video_t *self, uint8_t *s, uint8_t *d, int motion_h, int motion_v, int block_size, + int interpolate) { + int dw = self->mb_width * block_size; + + int hp = motion_h >> 1; + int vp = motion_v >> 1; + int odd_h = (motion_h & 1) == 1; + int odd_v = (motion_v & 1) == 1; + + unsigned int si = ((self->mb_row * block_size) + vp) * dw + (self->mb_col * block_size) + hp; + unsigned int di = (self->mb_row * dw + self->mb_col) * block_size; + + unsigned int max_address = (dw * (self->mb_height * block_size - block_size + 1) - block_size); + if (si > max_address || di > max_address) { + return; // corrupt video + } + +#define PLM_MB_CASE(INTERPOLATE, ODD_H, ODD_V, OP) \ + case ((INTERPOLATE << 2) | (ODD_H << 1) | (ODD_V)): \ + PLM_BLOCK_SET(d, di, dw, si, dw, block_size, OP); \ + break + + switch ((interpolate << 2) | (odd_h << 1) | (odd_v)) { + PLM_MB_CASE(0, 0, 0, (s[si])); + PLM_MB_CASE(0, 0, 1, (s[si] + s[si + dw] + 1) >> 1); + PLM_MB_CASE(0, 1, 0, (s[si] + s[si + 1] + 1) >> 1); + PLM_MB_CASE(0, 1, 1, (s[si] + s[si + 1] + s[si + dw] + s[si + dw + 1] + 2) >> 2); + + PLM_MB_CASE(1, 0, 0, (d[di] + (s[si]) + 1) >> 1); + PLM_MB_CASE(1, 0, 1, (d[di] + ((s[si] + s[si + dw] + 1) >> 1) + 1) >> 1); + PLM_MB_CASE(1, 1, 0, (d[di] + ((s[si] + s[si + 1] + 1) >> 1) + 1) >> 1); + PLM_MB_CASE(1, 1, 1, (d[di] + ((s[si] + s[si + 1] + s[si + dw] + s[si + dw + 1] + 2) >> 2) + 1) >> 1); + } + +#undef PLM_MB_CASE +} + +void plm_video_decode_block(plm_video_t *self, int block) { + + int n = 0; + uint8_t *quant_matrix; + + // Decode DC coefficient of intra-coded blocks + if (self->macroblock_intra) { + int predictor; + int dct_size; + + // DC prediction + int plane_index = block > 3 ? block - 3 : 0; + predictor = self->dc_predictor[plane_index]; + dct_size = plm_buffer_read_vlc(self->buffer, PLM_VIDEO_DCT_SIZE[plane_index]); + + // Read DC coeff + if (dct_size > 0) { + int differential = plm_buffer_read(self->buffer, dct_size); + if ((differential & (1 << (dct_size - 1))) != 0) { + self->block_data[0] = predictor + differential; + } else { + self->block_data[0] = predictor + (-(1 << dct_size) | (differential + 1)); + } + } else { + self->block_data[0] = predictor; + } + + // Save predictor value + self->dc_predictor[plane_index] = self->block_data[0]; + + // Dequantize + premultiply + self->block_data[0] <<= (3 + 5); + + quant_matrix = self->intra_quant_matrix; + n = 1; + } else { + quant_matrix = self->non_intra_quant_matrix; + } + + // Decode AC coefficients (+DC for non-intra) + int level = 0; + while (TRUE) { + int run = 0; + uint16_t coeff = plm_buffer_read_vlc_uint(self->buffer, PLM_VIDEO_DCT_COEFF); + + if ((coeff == 0x0001) && (n > 0) && (plm_buffer_read(self->buffer, 1) == 0)) { + // end_of_block + break; + } + if (coeff == 0xffff) { + // escape + run = plm_buffer_read(self->buffer, 6); + level = plm_buffer_read(self->buffer, 8); + if (level == 0) { + level = plm_buffer_read(self->buffer, 8); + } else if (level == 128) { + level = plm_buffer_read(self->buffer, 8) - 256; + } else if (level > 128) { + level = level - 256; + } + } else { + run = coeff >> 8; + level = coeff & 0xff; + if (plm_buffer_read(self->buffer, 1)) { + level = -level; + } + } + + n += run; + if (n < 0 || n >= 64) { + return; // invalid + } + + int de_zig_zagged = PLM_VIDEO_ZIG_ZAG[n]; + n++; + + // Dequantize, oddify, clip + level <<= 1; + if (!self->macroblock_intra) { + level += (level < 0 ? -1 : 1); + } + level = (level * self->quantizer_scale * quant_matrix[de_zig_zagged]) >> 4; + if ((level & 1) == 0) { + level -= level > 0 ? 1 : -1; + } + if (level > 2047) { + level = 2047; + } else if (level < -2048) { + level = -2048; + } + + // Save premultiplied coefficient + self->block_data[de_zig_zagged] = level * PLM_VIDEO_PREMULTIPLIER_MATRIX[de_zig_zagged]; + } + + // Move block to its place + uint8_t *d; + int dw; + int di; + + if (block < 4) { + d = self->frame_current.y.data; + dw = self->luma_width; + di = (self->mb_row * self->luma_width + self->mb_col) << 4; + if ((block & 1) != 0) { + di += 8; + } + if ((block & 2) != 0) { + di += self->luma_width << 3; + } + } else { + d = (block == 4) ? self->frame_current.cb.data : self->frame_current.cr.data; + dw = self->chroma_width; + di = ((self->mb_row * self->luma_width) << 2) + (self->mb_col << 3); + } + + int *s = self->block_data; + int si = 0; + if (self->macroblock_intra) { + // Overwrite (no prediction) + if (n == 1) { + int clamped = plm_clamp((s[0] + 128) >> 8); + PLM_BLOCK_SET(d, di, dw, si, 8, 8, clamped); + s[0] = 0; + } else { + plm_video_idct(s); + PLM_BLOCK_SET(d, di, dw, si, 8, 8, plm_clamp(s[si])); + memset(self->block_data, 0, sizeof(self->block_data)); + } + } else { + // Add data to the predicted macroblock + if (n == 1) { + int value = (s[0] + 128) >> 8; + PLM_BLOCK_SET(d, di, dw, si, 8, 8, plm_clamp(d[di] + value)); + s[0] = 0; + } else { + plm_video_idct(s); + PLM_BLOCK_SET(d, di, dw, si, 8, 8, plm_clamp(d[di] + s[si])); + memset(self->block_data, 0, sizeof(self->block_data)); + } + } +} + +void plm_video_idct(int *block) { + int b1, b3, b4, b6, b7, tmp1, tmp2, m0, x0, x1, x2, x3, x4, y3, y4, y5, y6, y7; + + // Transform columns + for (int i = 0; i < 8; ++i) { + b1 = block[4 * 8 + i]; + b3 = block[2 * 8 + i] + block[6 * 8 + i]; + b4 = block[5 * 8 + i] - block[3 * 8 + i]; + tmp1 = block[1 * 8 + i] + block[7 * 8 + i]; + tmp2 = block[3 * 8 + i] + block[5 * 8 + i]; + b6 = block[1 * 8 + i] - block[7 * 8 + i]; + b7 = tmp1 + tmp2; + m0 = block[0 * 8 + i]; + x4 = ((b6 * 473 - b4 * 196 + 128) >> 8) - b7; + x0 = x4 - (((tmp1 - tmp2) * 362 + 128) >> 8); + x1 = m0 - b1; + x2 = (((block[2 * 8 + i] - block[6 * 8 + i]) * 362 + 128) >> 8) - b3; + x3 = m0 + b1; + y3 = x1 + x2; + y4 = x3 + b3; + y5 = x1 - x2; + y6 = x3 - b3; + y7 = -x0 - ((b4 * 473 + b6 * 196 + 128) >> 8); + block[0 * 8 + i] = b7 + y4; + block[1 * 8 + i] = x4 + y3; + block[2 * 8 + i] = y5 - x0; + block[3 * 8 + i] = y6 - y7; + block[4 * 8 + i] = y6 + y7; + block[5 * 8 + i] = x0 + y5; + block[6 * 8 + i] = y3 - x4; + block[7 * 8 + i] = y4 - b7; + } + + // Transform rows + for (int i = 0; i < 64; i += 8) { + b1 = block[4 + i]; + b3 = block[2 + i] + block[6 + i]; + b4 = block[5 + i] - block[3 + i]; + tmp1 = block[1 + i] + block[7 + i]; + tmp2 = block[3 + i] + block[5 + i]; + b6 = block[1 + i] - block[7 + i]; + b7 = tmp1 + tmp2; + m0 = block[0 + i]; + x4 = ((b6 * 473 - b4 * 196 + 128) >> 8) - b7; + x0 = x4 - (((tmp1 - tmp2) * 362 + 128) >> 8); + x1 = m0 - b1; + x2 = (((block[2 + i] - block[6 + i]) * 362 + 128) >> 8) - b3; + x3 = m0 + b1; + y3 = x1 + x2; + y4 = x3 + b3; + y5 = x1 - x2; + y6 = x3 - b3; + y7 = -x0 - ((b4 * 473 + b6 * 196 + 128) >> 8); + block[0 + i] = (b7 + y4 + 128) >> 8; + block[1 + i] = (x4 + y3 + 128) >> 8; + block[2 + i] = (y5 - x0 + 128) >> 8; + block[3 + i] = (y6 - y7 + 128) >> 8; + block[4 + i] = (y6 + y7 + 128) >> 8; + block[5 + i] = (x0 + y5 + 128) >> 8; + block[6 + i] = (y3 - x4 + 128) >> 8; + block[7 + i] = (y4 - b7 + 128) >> 8; + } +} + +// YCbCr conversion following the BT.601 standard: +// https://infogalactic.com/info/YCbCr#ITU-R_BT.601_conversion + +#define PLM_PUT_PIXEL(RI, GI, BI, Y_OFFSET, DEST_OFFSET) \ + y = ((frame->y.data[y_index + Y_OFFSET] - 16) * 76309) >> 16; \ + dest[d_index + DEST_OFFSET + RI] = plm_clamp(y + r); \ + dest[d_index + DEST_OFFSET + GI] = plm_clamp(y - g); \ + dest[d_index + DEST_OFFSET + BI] = plm_clamp(y + b); + +#define PLM_DEFINE_FRAME_CONVERT_FUNCTION(NAME, BYTES_PER_PIXEL, RI, GI, BI) \ + void NAME(plm_frame_t *frame, uint8_t *dest, int stride) { \ + int cols = frame->width >> 1; \ + int rows = frame->height >> 1; \ + int yw = frame->y.width; \ + int cw = frame->cb.width; \ + for (int row = 0; row < rows; row++) { \ + int c_index = row * cw; \ + int y_index = row * 2 * yw; \ + int d_index = row * 2 * stride; \ + for (int col = 0; col < cols; col++) { \ + int y; \ + int cr = frame->cr.data[c_index] - 128; \ + int cb = frame->cb.data[c_index] - 128; \ + int r = (cr * 104597) >> 16; \ + int g = (cb * 25674 + cr * 53278) >> 16; \ + int b = (cb * 132201) >> 16; \ + PLM_PUT_PIXEL(RI, GI, BI, 0, 0); \ + PLM_PUT_PIXEL(RI, GI, BI, 1, BYTES_PER_PIXEL); \ + PLM_PUT_PIXEL(RI, GI, BI, yw, stride); \ + PLM_PUT_PIXEL(RI, GI, BI, yw + 1, stride + BYTES_PER_PIXEL); \ + c_index += 1; \ + y_index += 2; \ + d_index += 2 * BYTES_PER_PIXEL; \ + } \ + } \ + } + +PLM_DEFINE_FRAME_CONVERT_FUNCTION(plm_frame_to_rgb, 3, 0, 1, 2) +PLM_DEFINE_FRAME_CONVERT_FUNCTION(plm_frame_to_bgr, 3, 2, 1, 0) +PLM_DEFINE_FRAME_CONVERT_FUNCTION(plm_frame_to_rgba, 4, 0, 1, 2) +PLM_DEFINE_FRAME_CONVERT_FUNCTION(plm_frame_to_bgra, 4, 2, 1, 0) +PLM_DEFINE_FRAME_CONVERT_FUNCTION(plm_frame_to_argb, 4, 1, 2, 3) +PLM_DEFINE_FRAME_CONVERT_FUNCTION(plm_frame_to_abgr, 4, 3, 2, 1) + +#undef PLM_PUT_PIXEL +#undef PLM_DEFINE_FRAME_CONVERT_FUNCTION + +// ----------------------------------------------------------------------------- +// plm_audio implementation + +// Based on kjmp2 by Martin J. Fiedler +// http://keyj.emphy.de/kjmp2/ + +static const int PLM_AUDIO_FRAME_SYNC = 0x7ff; + +static const int PLM_AUDIO_MPEG_2_5 = 0x0; +static const int PLM_AUDIO_MPEG_2 = 0x2; +static const int PLM_AUDIO_MPEG_1 = 0x3; + +static const int PLM_AUDIO_LAYER_III = 0x1; +static const int PLM_AUDIO_LAYER_II = 0x2; +static const int PLM_AUDIO_LAYER_I = 0x3; + +static const int PLM_AUDIO_MODE_STEREO = 0x0; +static const int PLM_AUDIO_MODE_JOINT_STEREO = 0x1; +static const int PLM_AUDIO_MODE_DUAL_CHANNEL = 0x2; +static const int PLM_AUDIO_MODE_MONO = 0x3; + +static const unsigned short PLM_AUDIO_SAMPLE_RATE[] = { + 44100, 48000, 32000, 0, // MPEG-1 + 22050, 24000, 16000, 0 // MPEG-2 +}; + +static const short PLM_AUDIO_BIT_RATE[] = { + 32, 48, 56, 64, 80, 96, 112, 128, 160, 192, 224, 256, 320, 384, // MPEG-1 + 8, 16, 24, 32, 40, 48, 56, 64, 80, 96, 112, 128, 144, 160 // MPEG-2 +}; + +static const int PLM_AUDIO_SCALEFACTOR_BASE[] = {0x02000000, 0x01965FEA, 0x01428A30}; + +static const float PLM_AUDIO_SYNTHESIS_WINDOW[] = { + 0.0, -0.5, -0.5, -0.5, -0.5, -0.5, -0.5, -1.0, -1.0, -1.0, -1.0, + -1.5, -1.5, -2.0, -2.0, -2.5, -2.5, -3.0, -3.5, -3.5, -4.0, -4.5, + -5.0, -5.5, -6.5, -7.0, -8.0, -8.5, -9.5, -10.5, -12.0, -13.0, -14.5, + -15.5, -17.5, -19.0, -20.5, -22.5, -24.5, -26.5, -29.0, -31.5, -34.0, -36.5, + -39.5, -42.5, -45.5, -48.5, -52.0, -55.5, -58.5, -62.5, -66.0, -69.5, -73.5, + -77.0, -80.5, -84.5, -88.0, -91.5, -95.0, -98.0, -101.0, -104.0, 106.5, 109.0, + 111.0, 112.5, 113.5, 114.0, 114.0, 113.5, 112.0, 110.5, 107.5, 104.0, 100.0, + 94.5, 88.5, 81.5, 73.0, 63.5, 53.0, 41.5, 28.5, 14.5, -1.0, -18.0, + -36.0, -55.5, -76.5, -98.5, -122.0, -147.0, -173.5, -200.5, -229.5, -259.5, -290.5, + -322.5, -355.5, -389.5, -424.0, -459.5, -495.5, -532.0, -568.5, -605.0, -641.5, -678.0, + -714.0, -749.0, -783.5, -817.0, -849.0, -879.5, -908.5, -935.0, -959.5, -981.0, -1000.5, + -1016.0, -1028.5, -1037.5, -1042.5, -1043.5, -1040.0, -1031.5, 1018.5, 1000.0, 976.0, 946.5, + 911.0, 869.5, 822.0, 767.5, 707.0, 640.0, 565.5, 485.0, 397.0, 302.5, 201.0, + 92.5, -22.5, -144.0, -272.5, -407.0, -547.5, -694.0, -846.0, -1003.0, -1165.0, -1331.5, + -1502.0, -1675.5, -1852.5, -2031.5, -2212.5, -2394.0, -2576.5, -2758.5, -2939.5, -3118.5, -3294.5, + -3467.5, -3635.5, -3798.5, -3955.0, -4104.5, -4245.5, -4377.5, -4499.0, -4609.5, -4708.0, -4792.5, + -4863.5, -4919.0, -4958.0, -4979.5, -4983.0, -4967.5, -4931.5, -4875.0, -4796.0, -4694.5, -4569.5, + -4420.0, -4246.0, -4046.0, -3820.0, -3567.0, 3287.0, 2979.5, 2644.0, 2280.5, 1888.0, 1467.5, + 1018.5, 541.0, 35.0, -499.0, -1061.0, -1650.0, -2266.5, -2909.0, -3577.0, -4270.0, -4987.5, + -5727.5, -6490.0, -7274.0, -8077.5, -8899.5, -9739.0, -10594.5, -11464.5, -12347.0, -13241.0, -14144.5, + -15056.0, -15973.5, -16895.5, -17820.0, -18744.5, -19668.0, -20588.0, -21503.0, -22410.5, -23308.5, -24195.0, + -25068.5, -25926.5, -26767.0, -27589.0, -28389.0, -29166.5, -29919.0, -30644.5, -31342.0, -32009.5, -32645.0, + -33247.0, -33814.5, -34346.0, -34839.5, -35295.0, -35710.0, -36084.5, -36417.5, -36707.5, -36954.0, -37156.5, + -37315.0, -37428.0, -37496.0, 37519.0, 37496.0, 37428.0, 37315.0, 37156.5, 36954.0, 36707.5, 36417.5, + 36084.5, 35710.0, 35295.0, 34839.5, 34346.0, 33814.5, 33247.0, 32645.0, 32009.5, 31342.0, 30644.5, + 29919.0, 29166.5, 28389.0, 27589.0, 26767.0, 25926.5, 25068.5, 24195.0, 23308.5, 22410.5, 21503.0, + 20588.0, 19668.0, 18744.5, 17820.0, 16895.5, 15973.5, 15056.0, 14144.5, 13241.0, 12347.0, 11464.5, + 10594.5, 9739.0, 8899.5, 8077.5, 7274.0, 6490.0, 5727.5, 4987.5, 4270.0, 3577.0, 2909.0, + 2266.5, 1650.0, 1061.0, 499.0, -35.0, -541.0, -1018.5, -1467.5, -1888.0, -2280.5, -2644.0, + -2979.5, 3287.0, 3567.0, 3820.0, 4046.0, 4246.0, 4420.0, 4569.5, 4694.5, 4796.0, 4875.0, + 4931.5, 4967.5, 4983.0, 4979.5, 4958.0, 4919.0, 4863.5, 4792.5, 4708.0, 4609.5, 4499.0, + 4377.5, 4245.5, 4104.5, 3955.0, 3798.5, 3635.5, 3467.5, 3294.5, 3118.5, 2939.5, 2758.5, + 2576.5, 2394.0, 2212.5, 2031.5, 1852.5, 1675.5, 1502.0, 1331.5, 1165.0, 1003.0, 846.0, + 694.0, 547.5, 407.0, 272.5, 144.0, 22.5, -92.5, -201.0, -302.5, -397.0, -485.0, + -565.5, -640.0, -707.0, -767.5, -822.0, -869.5, -911.0, -946.5, -976.0, -1000.0, 1018.5, + 1031.5, 1040.0, 1043.5, 1042.5, 1037.5, 1028.5, 1016.0, 1000.5, 981.0, 959.5, 935.0, + 908.5, 879.5, 849.0, 817.0, 783.5, 749.0, 714.0, 678.0, 641.5, 605.0, 568.5, + 532.0, 495.5, 459.5, 424.0, 389.5, 355.5, 322.5, 290.5, 259.5, 229.5, 200.5, + 173.5, 147.0, 122.0, 98.5, 76.5, 55.5, 36.0, 18.0, 1.0, -14.5, -28.5, + -41.5, -53.0, -63.5, -73.0, -81.5, -88.5, -94.5, -100.0, -104.0, -107.5, -110.5, + -112.0, -113.5, -114.0, -114.0, -113.5, -112.5, -111.0, -109.0, 106.5, 104.0, 101.0, + 98.0, 95.0, 91.5, 88.0, 84.5, 80.5, 77.0, 73.5, 69.5, 66.0, 62.5, + 58.5, 55.5, 52.0, 48.5, 45.5, 42.5, 39.5, 36.5, 34.0, 31.5, 29.0, + 26.5, 24.5, 22.5, 20.5, 19.0, 17.5, 15.5, 14.5, 13.0, 12.0, 10.5, + 9.5, 8.5, 8.0, 7.0, 6.5, 5.5, 5.0, 4.5, 4.0, 3.5, 3.5, + 3.0, 2.5, 2.5, 2.0, 2.0, 1.5, 1.5, 1.0, 1.0, 1.0, 1.0, + 0.5, 0.5, 0.5, 0.5, 0.5, 0.5}; + +// Quantizer lookup, step 1: bitrate classes +static const uint8_t PLM_AUDIO_QUANT_LUT_STEP_1[2][16] = { + // 32, 48, 56, 64, 80, 96,112,128,160,192,224,256,320,384 <- bitrate + {0, 0, 1, 1, 1, 2, 2, 2, 2, 2, 2, 2, 2, 2}, // mono + // 16, 24, 28, 32, 40, 48, 56, 64, 80, 96,112,128,160,192 <- bitrate / chan + {0, 0, 0, 0, 0, 0, 1, 1, 1, 2, 2, 2, 2, 2} // stereo +}; + +// Quantizer lookup, step 2: bitrate class, sample rate -> B2 table idx, sblimit +#define PLM_AUDIO_QUANT_TAB_A (27 | 64) // Table 3-B.2a: high-rate, sblimit = 27 +#define PLM_AUDIO_QUANT_TAB_B (30 | 64) // Table 3-B.2b: high-rate, sblimit = 30 +#define PLM_AUDIO_QUANT_TAB_C 8 // Table 3-B.2c: low-rate, sblimit = 8 +#define PLM_AUDIO_QUANT_TAB_D 12 // Table 3-B.2d: low-rate, sblimit = 12 + +static const uint8_t QUANT_LUT_STEP_2[3][3] = { + // 44.1 kHz, 48 kHz, 32 kHz + {PLM_AUDIO_QUANT_TAB_C, PLM_AUDIO_QUANT_TAB_C, PLM_AUDIO_QUANT_TAB_D}, // 32 - 48 kbit/sec/ch + {PLM_AUDIO_QUANT_TAB_A, PLM_AUDIO_QUANT_TAB_A, PLM_AUDIO_QUANT_TAB_A}, // 56 - 80 kbit/sec/ch + {PLM_AUDIO_QUANT_TAB_B, PLM_AUDIO_QUANT_TAB_A, PLM_AUDIO_QUANT_TAB_B} // 96+ kbit/sec/ch +}; + +// Quantizer lookup, step 3: B2 table, subband -> nbal, row index +// (upper 4 bits: nbal, lower 4 bits: row index) +static const uint8_t PLM_AUDIO_QUANT_LUT_STEP_3[3][32] = { + // Low-rate table (3-B.2c and 3-B.2d) + {0x44, 0x44, 0x34, 0x34, 0x34, 0x34, 0x34, 0x34, 0x34, 0x34, 0x34, 0x34}, + // High-rate table (3-B.2a and 3-B.2b) + {0x43, 0x43, 0x43, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x31, 0x31, 0x31, 0x31, + 0x31, 0x31, 0x31, 0x31, 0x31, 0x31, 0x31, 0x31, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20}, + // MPEG-2 LSR table (B.2 in ISO 13818-3) + {0x45, 0x45, 0x45, 0x45, 0x34, 0x34, 0x34, 0x34, 0x34, 0x34, 0x34, 0x24, 0x24, 0x24, 0x24, + 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24, 0x24}}; + +// Quantizer lookup, step 4: table row, allocation[] value -> quant table index +static const uint8_t PLM_AUDIO_QUANT_LUT_STEP_4[6][16] = {{0, 1, 2, 17}, + {0, 1, 2, 3, 4, 5, 6, 17}, + {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 17}, + {0, 1, 3, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17}, + {0, 1, 2, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 17}, + {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15}}; + +typedef struct plm_quantizer_spec_t { + unsigned short levels; + unsigned char group; + unsigned char bits; +} plm_quantizer_spec_t; + +static const plm_quantizer_spec_t PLM_AUDIO_QUANT_TAB[] = { + {3, 1, 5}, // 1 + {5, 1, 7}, // 2 + {7, 0, 3}, // 3 + {9, 1, 10}, // 4 + {15, 0, 4}, // 5 + {31, 0, 5}, // 6 + {63, 0, 6}, // 7 + {127, 0, 7}, // 8 + {255, 0, 8}, // 9 + {511, 0, 9}, // 10 + {1023, 0, 10}, // 11 + {2047, 0, 11}, // 12 + {4095, 0, 12}, // 13 + {8191, 0, 13}, // 14 + {16383, 0, 14}, // 15 + {32767, 0, 15}, // 16 + {65535, 0, 16} // 17 +}; + +struct plm_audio_t { + double time; + int samples_decoded; + int samplerate_index; + int bitrate_index; + int version; + int layer; + int mode; + int bound; + int v_pos; + int next_frame_data_size; + int has_header; + + plm_buffer_t *buffer; + int destroy_buffer_when_done; + + const plm_quantizer_spec_t *allocation[2][32]; + uint8_t scale_factor_info[2][32]; + int scale_factor[2][32][3]; + int sample[2][32][3]; + + plm_samples_t samples; + float D[1024]; + float V[2][1024]; + float U[32]; +}; + +int plm_audio_find_frame_sync(plm_audio_t *self); +int plm_audio_decode_header(plm_audio_t *self); +void plm_audio_decode_frame(plm_audio_t *self); +const plm_quantizer_spec_t *plm_audio_read_allocation(plm_audio_t *self, int sb, int tab3); +void plm_audio_read_samples(plm_audio_t *self, int ch, int sb, int part); +void plm_audio_idct36(int s[32][3], int ss, float *d, int dp); + +plm_audio_t *plm_audio_create_with_buffer(plm_buffer_t *buffer, int destroy_when_done) { + plm_audio_t *self = (plm_audio_t *)PLM_MALLOC(sizeof(plm_audio_t)); + memset(self, 0, sizeof(plm_audio_t)); + + self->samples.count = PLM_AUDIO_SAMPLES_PER_FRAME; + self->buffer = buffer; + self->destroy_buffer_when_done = destroy_when_done; + self->samplerate_index = 3; // Indicates 0 + + memcpy(self->D, PLM_AUDIO_SYNTHESIS_WINDOW, 512 * sizeof(float)); + memcpy(self->D + 512, PLM_AUDIO_SYNTHESIS_WINDOW, 512 * sizeof(float)); + + // Attempt to decode first header + self->next_frame_data_size = plm_audio_decode_header(self); + + return self; +} + +void plm_audio_destroy(plm_audio_t *self) { + if (self->destroy_buffer_when_done) { + plm_buffer_destroy(self->buffer); + } + PLM_FREE(self); +} + +int plm_audio_has_header(plm_audio_t *self) { + if (self->has_header) { + return TRUE; + } + + self->next_frame_data_size = plm_audio_decode_header(self); + return self->has_header; +} + +int plm_audio_get_samplerate(plm_audio_t *self) { + return plm_audio_has_header(self) ? PLM_AUDIO_SAMPLE_RATE[self->samplerate_index] : 0; +} + +double plm_audio_get_time(plm_audio_t *self) { return self->time; } + +void plm_audio_set_time(plm_audio_t *self, double time) { + self->samples_decoded = time * (double)PLM_AUDIO_SAMPLE_RATE[self->samplerate_index]; + self->time = time; +} + +void plm_audio_rewind(plm_audio_t *self) { + plm_buffer_rewind(self->buffer); + self->time = 0; + self->samples_decoded = 0; + self->next_frame_data_size = 0; +} + +int plm_audio_has_ended(plm_audio_t *self) { return plm_buffer_has_ended(self->buffer); } + +plm_samples_t *plm_audio_decode(plm_audio_t *self) { + // Do we have at least enough information to decode the frame header? + if (!self->next_frame_data_size) { + if (!plm_buffer_has(self->buffer, 48)) { + return NULL; + } + self->next_frame_data_size = plm_audio_decode_header(self); + } + + if (self->next_frame_data_size == 0 || !plm_buffer_has(self->buffer, self->next_frame_data_size << 3)) { + return NULL; + } + + plm_audio_decode_frame(self); + self->next_frame_data_size = 0; + + self->samples.time = self->time; + + self->samples_decoded += PLM_AUDIO_SAMPLES_PER_FRAME; + self->time = (double)self->samples_decoded / (double)PLM_AUDIO_SAMPLE_RATE[self->samplerate_index]; + + return &self->samples; +} + +int plm_audio_find_frame_sync(plm_audio_t *self) { + size_t i; + for (i = self->buffer->bit_index >> 3; i < self->buffer->length - 1; i++) { + if (self->buffer->bytes[i] == 0xFF && (self->buffer->bytes[i + 1] & 0xFE) == 0xFC) { + self->buffer->bit_index = ((i + 1) << 3) + 3; + return TRUE; + } + } + self->buffer->bit_index = (i + 1) << 3; + return FALSE; +} + +int plm_audio_decode_header(plm_audio_t *self) { + if (!plm_buffer_has(self->buffer, 48)) { + return 0; + } + + plm_buffer_skip_bytes(self->buffer, 0x00); + int sync = plm_buffer_read(self->buffer, 11); + + // Attempt to resync if no syncword was found. This sucks balls. The MP2 + // stream contains a syncword just before every frame (11 bits set to 1). + // However, this syncword is not guaranteed to not occur elsewhere in the + // stream. So, if we have to resync, we also have to check if the header + // (samplerate, bitrate) differs from the one we had before. This all + // may still lead to garbage data being decoded :/ + + if (sync != PLM_AUDIO_FRAME_SYNC && !plm_audio_find_frame_sync(self)) { + return 0; + } + + self->version = plm_buffer_read(self->buffer, 2); + self->layer = plm_buffer_read(self->buffer, 2); + int hasCRC = !plm_buffer_read(self->buffer, 1); + + if (self->version != PLM_AUDIO_MPEG_1 || self->layer != PLM_AUDIO_LAYER_II) { + return 0; + } + + int bitrate_index = plm_buffer_read(self->buffer, 4) - 1; + if (bitrate_index > 13) { + return 0; + } + + int samplerate_index = plm_buffer_read(self->buffer, 2); + if (samplerate_index == 3) { + return 0; + } + + int padding = plm_buffer_read(self->buffer, 1); + plm_buffer_skip(self->buffer, 1); // f_private + int mode = plm_buffer_read(self->buffer, 2); + + // If we already have a header, make sure the samplerate, bitrate and mode + // are still the same, otherwise we might have missed sync. + if (self->has_header && + (self->bitrate_index != bitrate_index || self->samplerate_index != samplerate_index || self->mode != mode)) { + return 0; + } + + self->bitrate_index = bitrate_index; + self->samplerate_index = samplerate_index; + self->mode = mode; + self->has_header = TRUE; + + // Parse the mode_extension, set up the stereo bound + if (mode == PLM_AUDIO_MODE_JOINT_STEREO) { + self->bound = (plm_buffer_read(self->buffer, 2) + 1) << 2; + } else { + plm_buffer_skip(self->buffer, 2); + self->bound = (mode == PLM_AUDIO_MODE_MONO) ? 0 : 32; + } + + // Discard the last 4 bits of the header and the CRC value, if present + plm_buffer_skip(self->buffer, 4); // copyright(1), original(1), emphasis(2) + if (hasCRC) { + plm_buffer_skip(self->buffer, 16); + } + + // Compute frame size, check if we have enough data to decode the whole + // frame. + int bitrate = PLM_AUDIO_BIT_RATE[self->bitrate_index]; + int samplerate = PLM_AUDIO_SAMPLE_RATE[self->samplerate_index]; + int frame_size = (144000 * bitrate / samplerate) + padding; + return frame_size - (hasCRC ? 6 : 4); +} + +void plm_audio_decode_frame(plm_audio_t *self) { + // Prepare the quantizer table lookups + int tab3 = 0; + int sblimit = 0; + + int tab1 = (self->mode == PLM_AUDIO_MODE_MONO) ? 0 : 1; + int tab2 = PLM_AUDIO_QUANT_LUT_STEP_1[tab1][self->bitrate_index]; + tab3 = QUANT_LUT_STEP_2[tab2][self->samplerate_index]; + sblimit = tab3 & 63; + tab3 >>= 6; + + if (self->bound > sblimit) { + self->bound = sblimit; + } + + // Read the allocation information + for (int sb = 0; sb < self->bound; sb++) { + self->allocation[0][sb] = plm_audio_read_allocation(self, sb, tab3); + self->allocation[1][sb] = plm_audio_read_allocation(self, sb, tab3); + } + + for (int sb = self->bound; sb < sblimit; sb++) { + self->allocation[0][sb] = self->allocation[1][sb] = plm_audio_read_allocation(self, sb, tab3); + } + + // Read scale factor selector information + int channels = (self->mode == PLM_AUDIO_MODE_MONO) ? 1 : 2; + for (int sb = 0; sb < sblimit; sb++) { + for (int ch = 0; ch < channels; ch++) { + if (self->allocation[ch][sb]) { + self->scale_factor_info[ch][sb] = plm_buffer_read(self->buffer, 2); + } + } + if (self->mode == PLM_AUDIO_MODE_MONO) { + self->scale_factor_info[1][sb] = self->scale_factor_info[0][sb]; + } + } + + // Read scale factors + for (int sb = 0; sb < sblimit; sb++) { + for (int ch = 0; ch < channels; ch++) { + if (self->allocation[ch][sb]) { + int *sf = self->scale_factor[ch][sb]; + switch (self->scale_factor_info[ch][sb]) { + case 0: + sf[0] = plm_buffer_read(self->buffer, 6); + sf[1] = plm_buffer_read(self->buffer, 6); + sf[2] = plm_buffer_read(self->buffer, 6); + break; + case 1: + sf[0] = sf[1] = plm_buffer_read(self->buffer, 6); + sf[2] = plm_buffer_read(self->buffer, 6); + break; + case 2: + sf[0] = sf[1] = sf[2] = plm_buffer_read(self->buffer, 6); + break; + case 3: + sf[0] = plm_buffer_read(self->buffer, 6); + sf[1] = sf[2] = plm_buffer_read(self->buffer, 6); + break; + } + } + } + if (self->mode == PLM_AUDIO_MODE_MONO) { + self->scale_factor[1][sb][0] = self->scale_factor[0][sb][0]; + self->scale_factor[1][sb][1] = self->scale_factor[0][sb][1]; + self->scale_factor[1][sb][2] = self->scale_factor[0][sb][2]; + } + } + + // Coefficient input and reconstruction + int out_pos = 0; + for (int part = 0; part < 3; part++) { + for (int granule = 0; granule < 4; granule++) { + + // Read the samples + for (int sb = 0; sb < self->bound; sb++) { + plm_audio_read_samples(self, 0, sb, part); + plm_audio_read_samples(self, 1, sb, part); + } + for (int sb = self->bound; sb < sblimit; sb++) { + plm_audio_read_samples(self, 0, sb, part); + self->sample[1][sb][0] = self->sample[0][sb][0]; + self->sample[1][sb][1] = self->sample[0][sb][1]; + self->sample[1][sb][2] = self->sample[0][sb][2]; + } + for (int sb = sblimit; sb < 32; sb++) { + self->sample[0][sb][0] = 0; + self->sample[0][sb][1] = 0; + self->sample[0][sb][2] = 0; + self->sample[1][sb][0] = 0; + self->sample[1][sb][1] = 0; + self->sample[1][sb][2] = 0; + } + + // Synthesis loop + for (int p = 0; p < 3; p++) { + // Shifting step + self->v_pos = (self->v_pos - 64) & 1023; + + for (int ch = 0; ch < 2; ch++) { + plm_audio_idct36(self->sample[ch], p, self->V[ch], self->v_pos); + + // Build U, windowing, calculate output + memset(self->U, 0, sizeof(self->U)); + + int d_index = 512 - (self->v_pos >> 1); + int v_index = (self->v_pos % 128) >> 1; + while (v_index < 1024) { + for (int i = 0; i < 32; ++i) { + self->U[i] += self->D[d_index++] * self->V[ch][v_index++]; + } + + v_index += 128 - 32; + d_index += 64 - 32; + } + + d_index -= (512 - 32); + v_index = (128 - 32 + 1024) - v_index; + while (v_index < 1024) { + for (int i = 0; i < 32; ++i) { + self->U[i] += self->D[d_index++] * self->V[ch][v_index++]; + } + + v_index += 128 - 32; + d_index += 64 - 32; + } + +// Output samples +#ifdef PLM_AUDIO_SEPARATE_CHANNELS + float *out_channel = ch == 0 ? self->samples.left : self->samples.right; + for (int j = 0; j < 32; j++) { + out_channel[out_pos + j] = self->U[j] / 2147418112.0f; + } +#else + for (int j = 0; j < 32; j++) { + self->samples.interleaved[((out_pos + j) << 1) + ch] = self->U[j] / 2147418112.0f; + } +#endif + } // End of synthesis channel loop + out_pos += 32; + } // End of synthesis sub-block loop + + } // Decoding of the granule finished + } + + plm_buffer_align(self->buffer); +} + +const plm_quantizer_spec_t *plm_audio_read_allocation(plm_audio_t *self, int sb, int tab3) { + int tab4 = PLM_AUDIO_QUANT_LUT_STEP_3[tab3][sb]; + int qtab = PLM_AUDIO_QUANT_LUT_STEP_4[tab4 & 15][plm_buffer_read(self->buffer, tab4 >> 4)]; + return qtab ? (&PLM_AUDIO_QUANT_TAB[qtab - 1]) : 0; +} + +void plm_audio_read_samples(plm_audio_t *self, int ch, int sb, int part) { + const plm_quantizer_spec_t *q = self->allocation[ch][sb]; + int sf = self->scale_factor[ch][sb][part]; + int *sample = self->sample[ch][sb]; + int val = 0; + + if (!q) { + // No bits allocated for this subband + sample[0] = sample[1] = sample[2] = 0; + return; + } + + // Resolve scalefactor + if (sf == 63) { + sf = 0; + } else { + int shift = (sf / 3) | 0; + sf = (PLM_AUDIO_SCALEFACTOR_BASE[sf % 3] + ((1 << shift) >> 1)) >> shift; + } + + // Decode samples + int adj = q->levels; + if (q->group) { + // Decode grouped samples + val = plm_buffer_read(self->buffer, q->bits); + sample[0] = val % adj; + val /= adj; + sample[1] = val % adj; + sample[2] = val / adj; + } else { + // Decode direct samples + sample[0] = plm_buffer_read(self->buffer, q->bits); + sample[1] = plm_buffer_read(self->buffer, q->bits); + sample[2] = plm_buffer_read(self->buffer, q->bits); + } + + // Postmultiply samples + int scale = 65536 / (adj + 1); + adj = ((adj + 1) >> 1) - 1; + + val = (adj - sample[0]) * scale; + sample[0] = (val * (sf >> 12) + ((val * (sf & 4095) + 2048) >> 12)) >> 12; + + val = (adj - sample[1]) * scale; + sample[1] = (val * (sf >> 12) + ((val * (sf & 4095) + 2048) >> 12)) >> 12; + + val = (adj - sample[2]) * scale; + sample[2] = (val * (sf >> 12) + ((val * (sf & 4095) + 2048) >> 12)) >> 12; +} + +void plm_audio_idct36(int s[32][3], int ss, float *d, int dp) { + float t01, t02, t03, t04, t05, t06, t07, t08, t09, t10, t11, t12, t13, t14, t15, t16, t17, t18, t19, t20, t21, t22, + t23, t24, t25, t26, t27, t28, t29, t30, t31, t32, t33; + + t01 = (float)(s[0][ss] + s[31][ss]); + t02 = (float)(s[0][ss] - s[31][ss]) * 0.500602998235f; + t03 = (float)(s[1][ss] + s[30][ss]); + t04 = (float)(s[1][ss] - s[30][ss]) * 0.505470959898f; + t05 = (float)(s[2][ss] + s[29][ss]); + t06 = (float)(s[2][ss] - s[29][ss]) * 0.515447309923f; + t07 = (float)(s[3][ss] + s[28][ss]); + t08 = (float)(s[3][ss] - s[28][ss]) * 0.53104259109f; + t09 = (float)(s[4][ss] + s[27][ss]); + t10 = (float)(s[4][ss] - s[27][ss]) * 0.553103896034f; + t11 = (float)(s[5][ss] + s[26][ss]); + t12 = (float)(s[5][ss] - s[26][ss]) * 0.582934968206f; + t13 = (float)(s[6][ss] + s[25][ss]); + t14 = (float)(s[6][ss] - s[25][ss]) * 0.622504123036f; + t15 = (float)(s[7][ss] + s[24][ss]); + t16 = (float)(s[7][ss] - s[24][ss]) * 0.674808341455f; + t17 = (float)(s[8][ss] + s[23][ss]); + t18 = (float)(s[8][ss] - s[23][ss]) * 0.744536271002f; + t19 = (float)(s[9][ss] + s[22][ss]); + t20 = (float)(s[9][ss] - s[22][ss]) * 0.839349645416f; + t21 = (float)(s[10][ss] + s[21][ss]); + t22 = (float)(s[10][ss] - s[21][ss]) * 0.972568237862f; + t23 = (float)(s[11][ss] + s[20][ss]); + t24 = (float)(s[11][ss] - s[20][ss]) * 1.16943993343f; + t25 = (float)(s[12][ss] + s[19][ss]); + t26 = (float)(s[12][ss] - s[19][ss]) * 1.48416461631f; + t27 = (float)(s[13][ss] + s[18][ss]); + t28 = (float)(s[13][ss] - s[18][ss]) * 2.05778100995f; + t29 = (float)(s[14][ss] + s[17][ss]); + t30 = (float)(s[14][ss] - s[17][ss]) * 3.40760841847f; + t31 = (float)(s[15][ss] + s[16][ss]); + t32 = (float)(s[15][ss] - s[16][ss]) * 10.1900081235f; + + t33 = t01 + t31; + t31 = (t01 - t31) * 0.502419286188f; + t01 = t03 + t29; + t29 = (t03 - t29) * 0.52249861494f; + t03 = t05 + t27; + t27 = (t05 - t27) * 0.566944034816f; + t05 = t07 + t25; + t25 = (t07 - t25) * 0.64682178336f; + t07 = t09 + t23; + t23 = (t09 - t23) * 0.788154623451f; + t09 = t11 + t21; + t21 = (t11 - t21) * 1.06067768599f; + t11 = t13 + t19; + t19 = (t13 - t19) * 1.72244709824f; + t13 = t15 + t17; + t17 = (t15 - t17) * 5.10114861869f; + t15 = t33 + t13; + t13 = (t33 - t13) * 0.509795579104f; + t33 = t01 + t11; + t01 = (t01 - t11) * 0.601344886935f; + t11 = t03 + t09; + t09 = (t03 - t09) * 0.899976223136f; + t03 = t05 + t07; + t07 = (t05 - t07) * 2.56291544774f; + t05 = t15 + t03; + t15 = (t15 - t03) * 0.541196100146f; + t03 = t33 + t11; + t11 = (t33 - t11) * 1.30656296488f; + t33 = t05 + t03; + t05 = (t05 - t03) * 0.707106781187f; + t03 = t15 + t11; + t15 = (t15 - t11) * 0.707106781187f; + t03 += t15; + t11 = t13 + t07; + t13 = (t13 - t07) * 0.541196100146f; + t07 = t01 + t09; + t09 = (t01 - t09) * 1.30656296488f; + t01 = t11 + t07; + t07 = (t11 - t07) * 0.707106781187f; + t11 = t13 + t09; + t13 = (t13 - t09) * 0.707106781187f; + t11 += t13; + t01 += t11; + t11 += t07; + t07 += t13; + t09 = t31 + t17; + t31 = (t31 - t17) * 0.509795579104f; + t17 = t29 + t19; + t29 = (t29 - t19) * 0.601344886935f; + t19 = t27 + t21; + t21 = (t27 - t21) * 0.899976223136f; + t27 = t25 + t23; + t23 = (t25 - t23) * 2.56291544774f; + t25 = t09 + t27; + t09 = (t09 - t27) * 0.541196100146f; + t27 = t17 + t19; + t19 = (t17 - t19) * 1.30656296488f; + t17 = t25 + t27; + t27 = (t25 - t27) * 0.707106781187f; + t25 = t09 + t19; + t19 = (t09 - t19) * 0.707106781187f; + t25 += t19; + t09 = t31 + t23; + t31 = (t31 - t23) * 0.541196100146f; + t23 = t29 + t21; + t21 = (t29 - t21) * 1.30656296488f; + t29 = t09 + t23; + t23 = (t09 - t23) * 0.707106781187f; + t09 = t31 + t21; + t31 = (t31 - t21) * 0.707106781187f; + t09 += t31; + t29 += t09; + t09 += t23; + t23 += t31; + t17 += t29; + t29 += t25; + t25 += t09; + t09 += t27; + t27 += t23; + t23 += t19; + t19 += t31; + t21 = t02 + t32; + t02 = (t02 - t32) * 0.502419286188f; + t32 = t04 + t30; + t04 = (t04 - t30) * 0.52249861494f; + t30 = t06 + t28; + t28 = (t06 - t28) * 0.566944034816f; + t06 = t08 + t26; + t08 = (t08 - t26) * 0.64682178336f; + t26 = t10 + t24; + t10 = (t10 - t24) * 0.788154623451f; + t24 = t12 + t22; + t22 = (t12 - t22) * 1.06067768599f; + t12 = t14 + t20; + t20 = (t14 - t20) * 1.72244709824f; + t14 = t16 + t18; + t16 = (t16 - t18) * 5.10114861869f; + t18 = t21 + t14; + t14 = (t21 - t14) * 0.509795579104f; + t21 = t32 + t12; + t32 = (t32 - t12) * 0.601344886935f; + t12 = t30 + t24; + t24 = (t30 - t24) * 0.899976223136f; + t30 = t06 + t26; + t26 = (t06 - t26) * 2.56291544774f; + t06 = t18 + t30; + t18 = (t18 - t30) * 0.541196100146f; + t30 = t21 + t12; + t12 = (t21 - t12) * 1.30656296488f; + t21 = t06 + t30; + t30 = (t06 - t30) * 0.707106781187f; + t06 = t18 + t12; + t12 = (t18 - t12) * 0.707106781187f; + t06 += t12; + t18 = t14 + t26; + t26 = (t14 - t26) * 0.541196100146f; + t14 = t32 + t24; + t24 = (t32 - t24) * 1.30656296488f; + t32 = t18 + t14; + t14 = (t18 - t14) * 0.707106781187f; + t18 = t26 + t24; + t24 = (t26 - t24) * 0.707106781187f; + t18 += t24; + t32 += t18; + t18 += t14; + t26 = t14 + t24; + t14 = t02 + t16; + t02 = (t02 - t16) * 0.509795579104f; + t16 = t04 + t20; + t04 = (t04 - t20) * 0.601344886935f; + t20 = t28 + t22; + t22 = (t28 - t22) * 0.899976223136f; + t28 = t08 + t10; + t10 = (t08 - t10) * 2.56291544774f; + t08 = t14 + t28; + t14 = (t14 - t28) * 0.541196100146f; + t28 = t16 + t20; + t20 = (t16 - t20) * 1.30656296488f; + t16 = t08 + t28; + t28 = (t08 - t28) * 0.707106781187f; + t08 = t14 + t20; + t20 = (t14 - t20) * 0.707106781187f; + t08 += t20; + t14 = t02 + t10; + t02 = (t02 - t10) * 0.541196100146f; + t10 = t04 + t22; + t22 = (t04 - t22) * 1.30656296488f; + t04 = t14 + t10; + t10 = (t14 - t10) * 0.707106781187f; + t14 = t02 + t22; + t02 = (t02 - t22) * 0.707106781187f; + t14 += t02; + t04 += t14; + t14 += t10; + t10 += t02; + t16 += t04; + t04 += t08; + t08 += t14; + t14 += t28; + t28 += t10; + t10 += t20; + t20 += t02; + t21 += t16; + t16 += t32; + t32 += t04; + t04 += t06; + t06 += t08; + t08 += t18; + t18 += t14; + t14 += t30; + t30 += t28; + t28 += t26; + t26 += t10; + t10 += t12; + t12 += t20; + t20 += t24; + t24 += t02; + + d[dp + 48] = -t33; + d[dp + 49] = d[dp + 47] = -t21; + d[dp + 50] = d[dp + 46] = -t17; + d[dp + 51] = d[dp + 45] = -t16; + d[dp + 52] = d[dp + 44] = -t01; + d[dp + 53] = d[dp + 43] = -t32; + d[dp + 54] = d[dp + 42] = -t29; + d[dp + 55] = d[dp + 41] = -t04; + d[dp + 56] = d[dp + 40] = -t03; + d[dp + 57] = d[dp + 39] = -t06; + d[dp + 58] = d[dp + 38] = -t25; + d[dp + 59] = d[dp + 37] = -t08; + d[dp + 60] = d[dp + 36] = -t11; + d[dp + 61] = d[dp + 35] = -t18; + d[dp + 62] = d[dp + 34] = -t09; + d[dp + 63] = d[dp + 33] = -t14; + d[dp + 32] = -t05; + d[dp + 0] = t05; + d[dp + 31] = -t30; + d[dp + 1] = t30; + d[dp + 30] = -t27; + d[dp + 2] = t27; + d[dp + 29] = -t28; + d[dp + 3] = t28; + d[dp + 28] = -t07; + d[dp + 4] = t07; + d[dp + 27] = -t26; + d[dp + 5] = t26; + d[dp + 26] = -t23; + d[dp + 6] = t23; + d[dp + 25] = -t10; + d[dp + 7] = t10; + d[dp + 24] = -t15; + d[dp + 8] = t15; + d[dp + 23] = -t12; + d[dp + 9] = t12; + d[dp + 22] = -t19; + d[dp + 10] = t19; + d[dp + 21] = -t20; + d[dp + 11] = t20; + d[dp + 20] = -t13; + d[dp + 12] = t13; + d[dp + 19] = -t24; + d[dp + 13] = t24; + d[dp + 18] = -t31; + d[dp + 14] = t31; + d[dp + 17] = -t02; + d[dp + 15] = t02; + d[dp + 16] = 0.0; +} + +#endif // PL_MPEG_IMPLEMENTATION \ No newline at end of file diff --git a/include/subsystems/fun/video.h b/include/subsystems/fun/video.h new file mode 100644 index 0000000..2478855 --- /dev/null +++ b/include/subsystems/fun/video.h @@ -0,0 +1,17 @@ +#include "../core/include/subsystems/screen.h" +#include "pl_mpeg.h" +#include + +/// @brief Only one video file can be open at a time due to memory constraints +void set_video(const std::string &filename); +/// @brief restart the global video +void video_restart(); +// plays the video set by set_video() +// because of memory constraints we're limited to one video at a time +class VideoPlayer : public screen::Page { +public: + VideoPlayer(); + void update(bool was_pressed, int x, int y) override; + + void draw(vex::brain::lcd &screen, bool first_draw, unsigned int frame_number) override; +}; \ No newline at end of file diff --git a/include/subsystems/layout.h b/include/subsystems/layout.h index 1715e93..61531f2 100644 --- a/include/subsystems/layout.h +++ b/include/subsystems/layout.h @@ -1,11 +1,8 @@ #include #include -struct SliderCfg{ - double &val; - double min; - double max; +struct SliderCfg { + double &val; + double min; + double max; }; - - - diff --git a/include/subsystems/lift.h b/include/subsystems/lift.h index 2b45fa7..8512f47 100644 --- a/include/subsystems/lift.h +++ b/include/subsystems/lift.h @@ -1,10 +1,10 @@ #pragma once -#include "vex.h" #include "../core/include/utils/controls/pid.h" +#include "vex.h" +#include #include #include -#include #include using namespace vex; @@ -17,19 +17,15 @@ using namespace std; * * @author Ryan McGee */ -template -class Lift -{ - public: - +template class Lift { +public: /** * lift_cfg_t holds the physical parameter specifications of a lify system. * includes: * - maximum speeds for the system - * - softstops to stop the lift from hitting the hard stops too hard + * - softstops to stop the lift from hitting the hard stops too hard */ - struct lift_cfg_t - { + struct lift_cfg_t { double up_speed, down_speed; double softstop_up, softstop_down; @@ -37,73 +33,71 @@ class Lift }; /** - * Construct the Lift object and begin the background task that controls the lift. - * - * Usage example: - * /code{.cpp} - * enum Positions {UP, MID, DOWN}; - * map setpt_map { - * {DOWN, 0.0}, - * {MID, 0.5}, - * {UP, 1.0} - * }; - * Lift my_lift(motors, lift_cfg, setpt_map); - * /endcode - * - * @param lift_motors - * A set of motors, all set that positive rotation correlates with the lift going up - * @param lift_cfg - * Lift characterization information; PID tunings and movement speeds - * @param setpoint_map - * A map of enum type T, in which each enum entry corresponds to a different lift height - */ - Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map &setpoint_map, limit *homing_switch=NULL) - : lift_motors(lift_motors), cfg(lift_cfg), lift_pid(cfg.lift_pid_cfg), setpoint_map(setpoint_map), homing_switch(homing_switch) - { + * Construct the Lift object and begin the background task that controls the lift. + * + * Usage example: + * /code{.cpp} + * enum Positions {UP, MID, DOWN}; + * map setpt_map { + * {DOWN, 0.0}, + * {MID, 0.5}, + * {UP, 1.0} + * }; + * Lift my_lift(motors, lift_cfg, setpt_map); + * /endcode + * + * @param lift_motors + * A set of motors, all set that positive rotation correlates with the lift going up + * @param lift_cfg + * Lift characterization information; PID tunings and movement speeds + * @param setpoint_map + * A map of enum type T, in which each enum entry corresponds to a different lift height + */ + Lift(motor_group &lift_motors, lift_cfg_t &lift_cfg, map &setpoint_map, limit *homing_switch = NULL) + : lift_motors(lift_motors), cfg(lift_cfg), lift_pid(cfg.lift_pid_cfg), setpoint_map(setpoint_map), + homing_switch(homing_switch) { is_async = true; setpoint = 0; - + // Create a background task that is constantly updating the lift PID, if requested. // Set once, and forget. - task t([](void* ptr){ - Lift &lift = *((Lift*) ptr); - - while(true) - { - if(lift.get_async()) - lift.hold(); + task t( + [](void *ptr) { + Lift &lift = *((Lift *)ptr); - vexDelay(50); - } + while (true) { + if (lift.get_async()) + lift.hold(); - return 0; - }, this); + vexDelay(50); + } + return 0; + }, + this); } /** - * Control the lift with an "up" button and a "down" button. - * Use PID to hold the lift when letting go. - * @param up_ctrl - * Button controlling the "UP" motion - * @param down_ctrl - * Button controlling the "DOWN" motion - */ - void control_continuous(bool up_ctrl, bool down_ctrl) - { + * Control the lift with an "up" button and a "down" button. + * Use PID to hold the lift when letting go. + * @param up_ctrl + * Button controlling the "UP" motion + * @param down_ctrl + * Button controlling the "DOWN" motion + */ + void control_continuous(bool up_ctrl, bool down_ctrl) { static timer tmr; - + double cur_pos = 0; // Check if there's a hook for a custom sensor. If not, use the motors. - if(get_sensor == NULL) + if (get_sensor == NULL) cur_pos = lift_motors.position(rev); else cur_pos = get_sensor(); - if(up_ctrl && cur_pos < cfg.softstop_up) - { + if (up_ctrl && cur_pos < cfg.softstop_up) { lift_motors.spin(directionType::fwd, cfg.up_speed, volt); setpoint = cur_pos + .3; @@ -111,71 +105,65 @@ class Lift // Disable the PID while going UP. is_async = false; - } else if(down_ctrl && cur_pos > cfg.softstop_down) - { + } else if (down_ctrl && cur_pos > cfg.softstop_down) { // Lower the lift slowly, at a rate defined by down_speed - if(setpoint > cfg.softstop_down) + if (setpoint > cfg.softstop_down) setpoint = setpoint - (tmr.time(sec) * cfg.down_speed); // std::cout << "DEBUG OUT: DOWN " << setpoint << ", " << tmr.time(sec) << ", " << cfg.down_speed << "\n"; is_async = true; - } else - { + } else { // Hold the lift at the last setpoint is_async = true; } - tmr.reset(); + tmr.reset(); } /** * Control the lift with manual controls (no holding voltage) - * + * * @param up_btn Raise the lift when true * @param down_btn Lower the lift when true * @param volt_up Motor voltage when raising the lift * @param volt_down Motor voltage when lowering the lift */ - void control_manual(bool up_btn, bool down_btn, int volt_up, int volt_down) - { + void control_manual(bool up_btn, bool down_btn, int volt_up, int volt_down) { static bool down_hold = false; static bool init = true; // Allow for setting position while still calling this function - if(init || up_btn || down_btn) - { + if (init || up_btn || down_btn) { init = false; is_async = false; } double rev = lift_motors.position(rotationUnits::rev); - if(rev < cfg.softstop_down && down_btn) + if (rev < cfg.softstop_down && down_btn) down_hold = true; - else if( !down_btn ) + else if (!down_btn) down_hold = false; - if(up_btn && rev < cfg.softstop_up) + if (up_btn && rev < cfg.softstop_up) lift_motors.spin(directionType::fwd, volt_up, voltageUnits::volt); - else if(down_btn && rev > cfg.softstop_down && !down_hold) + else if (down_btn && rev > cfg.softstop_down && !down_hold) lift_motors.spin(directionType::rev, volt_down, voltageUnits::volt); else lift_motors.spin(directionType::fwd, 0, voltageUnits::volt); - } /** - * Control the lift in "steps". When the "up" button is pressed, the lift will go to the next - * position as defined by pos_list. Order matters! - * - * @param up_step - * A button that increments the position of the lift. - * @param down_step - * A button that decrements the position of the lift. - * @param pos_list - * A list of positions for the lift to go through. The higher the index, the higher the lift should be (generally). - */ - void control_setpoints(bool up_step, bool down_step, vector pos_list) - { + * Control the lift in "steps". When the "up" button is pressed, the lift will go to the next + * position as defined by pos_list. Order matters! + * + * @param up_step + * A button that increments the position of the lift. + * @param down_step + * A button that decrements the position of the lift. + * @param pos_list + * A list of positions for the lift to go through. The higher the index, the higher the lift should be (generally). + */ + void control_setpoints(bool up_step, bool down_step, vector pos_list) { // Make sure inputs are only processed on the rising edge of the button static bool up_last = up_step, down_last = down_step; @@ -188,31 +176,29 @@ class Lift static int cur_index = 0; // Avoid an index overflow. Shouldn't happen unless the user changes pos_list between calls. - if(cur_index >= pos_list.size()) + if (cur_index >= pos_list.size()) cur_index = pos_list.size() - 1; // Increment or decrement the index of the list, bringing it up or down. - if(up_rising && cur_index < (pos_list.size() - 1)) + if (up_rising && cur_index < (pos_list.size() - 1)) cur_index++; - else if(down_rising && cur_index > 0) + else if (down_rising && cur_index > 0) cur_index--; // Set the lift to hold the position in the background with the PID loop set_position(pos_list[cur_index]); - is_async = true; - + is_async = true; } /** - * Enable the background task, and send the lift to a position, specified by the - * setpoint map from the constructor. - * - * @param pos - * A lift position enum type - * @return True if the pid has reached the setpoint - */ - bool set_position(T pos) - { + * Enable the background task, and send the lift to a position, specified by the + * setpoint map from the constructor. + * + * @param pos + * A lift position enum type + * @return True if the pid has reached the setpoint + */ + bool set_position(T pos) { this->setpoint = setpoint_map[pos]; is_async = true; @@ -220,35 +206,30 @@ class Lift } /** - * Manually set a setpoint value for the lift PID to go to. - * @param val - * Lift setpoint, in motor revolutions or sensor units defined by get_sensor. Cannot be outside the softstops. - * @return True if the pid has reached the setpoint - */ - bool set_setpoint(double val) - { + * Manually set a setpoint value for the lift PID to go to. + * @param val + * Lift setpoint, in motor revolutions or sensor units defined by get_sensor. Cannot be outside the softstops. + * @return True if the pid has reached the setpoint + */ + bool set_setpoint(double val) { this->setpoint = val; return (lift_pid.get_target() == this->setpoint) && lift_pid.is_on_target(); } - + /** - * @return The current setpoint for the lift - */ - double get_setpoint() - { - return this->setpoint; - } + * @return The current setpoint for the lift + */ + double get_setpoint() { return this->setpoint; } /** - * Target the class's setpoint. - * Calculate the PID output and set the lift motors accordingly. - */ - void hold() - { + * Target the class's setpoint. + * Calculate the PID output and set the lift motors accordingly. + */ + void hold() { lift_pid.set_target(setpoint); // std::cout << "DEBUG OUT: SETPOINT " << setpoint << "\n"; - if(get_sensor != NULL) + if (get_sensor != NULL) lift_pid.update(get_sensor()); else lift_pid.update(lift_motors.position(rev)); @@ -259,16 +240,14 @@ class Lift } /** - * A blocking function that automatically homes the lift based on a sensor or hard stop, + * A blocking function that automatically homes the lift based on a sensor or hard stop, * and sets the position to 0. A watchdog times out after 3 seconds, to avoid damage. */ - void home() - { + void home() { static timer tmr; tmr.reset(); - - while(tmr.time(sec) < 3) - { + + while (tmr.time(sec) < 3) { lift_motors.spin(directionType::rev, 6, volt); if (homing_switch == NULL && lift_motors.current(currentUnits::amp) > 1.5) @@ -277,45 +256,35 @@ class Lift break; } - if(reset_sensor != NULL) + if (reset_sensor != NULL) reset_sensor(); - + lift_motors.resetPosition(); lift_motors.stop(); - } /** - * @return whether or not the background thread is running the lift - */ - bool get_async() - { - return is_async; - } + * @return whether or not the background thread is running the lift + */ + bool get_async() { return is_async; } /** - * Enables or disables the background task. Note that running the control functions, or set_position functions - * will immediately re-enable the task for autonomous use. - * @param val Whether or not the background thread should run the lift - */ - void set_async(bool val) - { - this->is_async = val; - } + * Enables or disables the background task. Note that running the control functions, or set_position functions + * will immediately re-enable the task for autonomous use. + * @param val Whether or not the background thread should run the lift + */ + void set_async(bool val) { this->is_async = val; } /** - * Creates a custom hook for any other type of sensor to be used on the lift. Example: - * /code{.cpp} - * my_lift.set_sensor_function( [](){return my_sensor.position();} ); - * /endcode - * - * @param fn_ptr - * Pointer to custom sensor function - */ - void set_sensor_function(double (*fn_ptr) (void)) - { - this->get_sensor = fn_ptr; - } + * Creates a custom hook for any other type of sensor to be used on the lift. Example: + * /code{.cpp} + * my_lift.set_sensor_function( [](){return my_sensor.position();} ); + * /endcode + * + * @param fn_ptr + * Pointer to custom sensor function + */ + void set_sensor_function(double (*fn_ptr)(void)) { this->get_sensor = fn_ptr; } /** * Creates a custom hook to reset the sensor used in set_sensor_function(). Example: @@ -323,24 +292,18 @@ class Lift * my_lift.set_sensor_reset( my_sensor.resetPosition ); * /endcode */ - void set_sensor_reset(void (*fn_ptr) (void)) - { - this->reset_sensor = fn_ptr; - } - - private: + void set_sensor_reset(void (*fn_ptr)(void)) { this->reset_sensor = fn_ptr; } +private: motor_group &lift_motors; lift_cfg_t &cfg; PID lift_pid; map &setpoint_map; limit *homing_switch; - + atomic setpoint; atomic is_async; double (*get_sensor)(void) = NULL; void (*reset_sensor)(void) = NULL; - - }; \ No newline at end of file diff --git a/include/subsystems/mecanum_drive.h b/include/subsystems/mecanum_drive.h index 97f3cdb..b120d66 100644 --- a/include/subsystems/mecanum_drive.h +++ b/include/subsystems/mecanum_drive.h @@ -1,26 +1,23 @@ #pragma once -#include "vex.h" #include "../core/include/utils/controls/pid.h" +#include "vex.h" #ifndef PI #define PI 3.141592654 #endif /** - * A class representing the Mecanum drivetrain. - * Contains 4 motors, a possible IMU (intertial), and a possible undriven perpendicular wheel. - */ -class MecanumDrive -{ - - public: + * A class representing the Mecanum drivetrain. + * Contains 4 motors, a possible IMU (intertial), and a possible undriven perpendicular wheel. + */ +class MecanumDrive { +public: /** - * Configure the Mecanum drive PID tunings and robot configurations - */ - struct mecanumdrive_config_t - { + * Configure the Mecanum drive PID tunings and robot configurations + */ + struct mecanumdrive_config_t { // PID configurations for autonomous driving PID::pid_config_t drive_pid_conf; PID::pid_config_t drive_gyro_pid_conf; @@ -34,65 +31,63 @@ class MecanumDrive // Width between the center of the left and right wheels double wheelbase_width; - }; /** - * Create the Mecanum drivetrain object - */ - MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear, - vex::rotation *lateral_wheel=NULL, vex::inertial *imu=NULL, mecanumdrive_config_t *config=NULL); + * Create the Mecanum drivetrain object + */ + MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear, + vex::rotation *lateral_wheel = NULL, vex::inertial *imu = NULL, mecanumdrive_config_t *config = NULL); /** - * Drive the robot using vectors. This handles all the math required for mecanum control. - * - * @param direction_deg the direction to drive the robot, in degrees. 0 is forward, - * 180 is back, clockwise is positive, counterclockwise is negative. - * @param magnitude How fast the robot should drive, in percent: 0.0->1.0 - * @param rotation How fast the robot should rotate, in percent: -1.0->+1.0 - */ + * Drive the robot using vectors. This handles all the math required for mecanum control. + * + * @param direction_deg the direction to drive the robot, in degrees. 0 is forward, + * 180 is back, clockwise is positive, counterclockwise is negative. + * @param magnitude How fast the robot should drive, in percent: 0.0->1.0 + * @param rotation How fast the robot should rotate, in percent: -1.0->+1.0 + */ void drive_raw(double direction_deg, double magnitude, double rotation); /** - * Drive the robot with a mecanum-style / arcade drive. Inputs are in percent (-100.0 -> 100.0) straight from the controller. - * Controls are mixed, so the robot can drive forward / strafe / rotate all at the same time. - * - * @param left_y left joystick, Y axis (forward / backwards) - * @param left_x left joystick, X axis (strafe left / right) - * @param right_x right joystick, X axis (rotation left / right) - * @param power =2 how much of a "curve" there should be on drive controls; better for low speed maneuvers. - * Leave blank for a default curve of 2 (higher means more fidelity) - */ - void drive(double left_y, double left_x, double right_x, int power=2); + * Drive the robot with a mecanum-style / arcade drive. Inputs are in percent (-100.0 -> 100.0) straight from the + * controller. Controls are mixed, so the robot can drive forward / strafe / rotate all at the same time. + * + * @param left_y left joystick, Y axis (forward / backwards) + * @param left_x left joystick, X axis (strafe left / right) + * @param right_x right joystick, X axis (rotation left / right) + * @param power =2 how much of a "curve" there should be on drive controls; better for low speed maneuvers. + * Leave blank for a default curve of 2 (higher means more fidelity) + */ + void drive(double left_y, double left_x, double right_x, int power = 2); /** - * Drive the robot in a straight line automatically. - * If the inertial was declared in the constructor, use it to correct while driving. - * If the lateral wheel was declared in the constructor, use it for more accurate positioning while strafing. - * - * @param inches How far the robot should drive, in inches - * @param direction What direction the robot should travel in, in degrees. - * 0 is forward, +/-180 is reverse, clockwise is positive. - * @param speed The maximum speed the robot should travel, in percent: -1.0->+1.0 - * @param gyro_correction =true Whether or not to use the gyro to help correct while driving. - * Will always be false if no gyro was declared in the constructor. - */ - bool auto_drive(double inches, double direction, double speed, bool gyro_correction=true); + * Drive the robot in a straight line automatically. + * If the inertial was declared in the constructor, use it to correct while driving. + * If the lateral wheel was declared in the constructor, use it for more accurate positioning while strafing. + * + * @param inches How far the robot should drive, in inches + * @param direction What direction the robot should travel in, in degrees. + * 0 is forward, +/-180 is reverse, clockwise is positive. + * @param speed The maximum speed the robot should travel, in percent: -1.0->+1.0 + * @param gyro_correction =true Whether or not to use the gyro to help correct while driving. + * Will always be false if no gyro was declared in the constructor. + */ + bool auto_drive(double inches, double direction, double speed, bool gyro_correction = true); /** - * Autonomously turn the robot X degrees over it's center point. Uses a closed loop - * for control. - * @param degrees How many degrees to rotate the robot. Clockwise postive. - * @param speed What percentage to run the motors at: 0.0 -> 1.0 - * @param ignore_imu =false Whether or not to use the Inertial for determining angle. - * Will instead use circumference formula + robot's wheelbase + encoders to determine. - * - * @return whether or not the robot has finished the maneuver - */ - bool auto_turn(double degrees, double speed, bool ignore_imu=false); - - private: - + * Autonomously turn the robot X degrees over it's center point. Uses a closed loop + * for control. + * @param degrees How many degrees to rotate the robot. Clockwise postive. + * @param speed What percentage to run the motors at: 0.0 -> 1.0 + * @param ignore_imu =false Whether or not to use the Inertial for determining angle. + * Will instead use circumference formula + robot's wheelbase + encoders to determine. + * + * @return whether or not the robot has finished the maneuver + */ + bool auto_turn(double degrees, double speed, bool ignore_imu = false); + +private: vex::motor &left_front, &right_front, &left_rear, &right_rear; mecanumdrive_config_t *config; @@ -104,5 +99,4 @@ class MecanumDrive PID *turn_pid = NULL; bool init = true; - }; \ No newline at end of file diff --git a/include/subsystems/odometry/odometry_3wheel.h b/include/subsystems/odometry/odometry_3wheel.h index 15ce85d..bef1f85 100644 --- a/include/subsystems/odometry/odometry_3wheel.h +++ b/include/subsystems/odometry/odometry_3wheel.h @@ -1,14 +1,14 @@ #pragma once +#include "../core/include/subsystems/custom_encoder.h" #include "../core/include/subsystems/odometry/odometry_base.h" #include "../core/include/subsystems/tank_drive.h" -#include "../core/include/subsystems/custom_encoder.h" /** * Odometry3Wheel - * + * * This class handles the code for a standard 3-pod odometry setup, where there are 3 "pods" made up of undriven * (dead) wheels connected to encoders in the following configuration: - * + * * +Y --------------- * ^ | | * | | | @@ -18,80 +18,76 @@ * | --------------- * | * +-------------------> + X - * + * * Where O is the center of rotation. The robot will monitor the changes in rotation of these wheels and calculate * the robot's X, Y and rotation on the field. - * + * * This is a "set and forget" class, meaning once the object is created, the robot will immediately begin * tracking it's movement in the background. - * + * * @author Ryan McGee * @date Oct 31 2022 - * + * */ -class Odometry3Wheel : public OdometryBase -{ - public: - - /** - * odometry3wheel_cfg_t holds all the specifications for how to calculate position with 3 encoders - * See the core wiki for what exactly each of these parameters measures - */ - typedef struct - { - double wheelbase_dist; /**< distance from the center of the left wheel to the center of the right wheel*/ - double off_axis_center_dist; /**< distance from the center of the robot to the center off axis wheel*/ - double wheel_diam; /**< the diameter of the tracking wheel*/ - - } odometry3wheel_cfg_t; - - /** - * Construct a new Odometry 3 Wheel object - * - * @param lside_fwd left-side encoder reference - * @param rside_fwd right-side encoder reference - * @param off_axis off-axis (perpendicular) encoder reference - * @param cfg robot odometry configuration - * @param is_async true to constantly run in the background - */ - Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, odometry3wheel_cfg_t &cfg, bool is_async=true); - - /** - * Update the current position of the robot once, using the current state of - * the encoders and the previous known location - * - * @return the robot's updated position - */ - pose_t update() override; +class Odometry3Wheel : public OdometryBase { +public: + /** + * odometry3wheel_cfg_t holds all the specifications for how to calculate position with 3 encoders + * See the core wiki for what exactly each of these parameters measures + */ + typedef struct { + double wheelbase_dist; /**< distance from the center of the left wheel to the center of the right wheel*/ + double off_axis_center_dist; /**< distance from the center of the robot to the center off axis wheel*/ + double wheel_diam; /**< the diameter of the tracking wheel*/ - /** - * A guided tuning process to automatically find tuning parameters. - * This method is blocking, and returns when tuning has finished. Follow - * the instructions on the controller to complete the tuning process - * - * @param con Controller reference, for screen and button control - * @param drive Drivetrain reference for robot control - */ - void tune(vex::controller &con, TankDrive &drive); + } odometry3wheel_cfg_t; - private: + /** + * Construct a new Odometry 3 Wheel object + * + * @param lside_fwd left-side encoder reference + * @param rside_fwd right-side encoder reference + * @param off_axis off-axis (perpendicular) encoder reference + * @param cfg robot odometry configuration + * @param is_async true to constantly run in the background + */ + Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, odometry3wheel_cfg_t &cfg, + bool is_async = true); - /** - * Calculation method for the robot's new position using the change in encoders, the old position, and the robot's configuration. - * This uses a series of arclength formulae for finding distance driven and change in angle. - * Then vector math is used to combine it with the robot's old position data - * - * @param lside_delta_deg Left encoder change in rotation, in degrees - * @param rside_delta_deg Right encoder change in rotation, in degrees - * @param offax_delta_deg Off-axis (perpendicular) encoder change in rotation, in degrees - * @param old_pos Robot's old position, for integration - * @param cfg Data on robot's configuration (wheel diameter, wheelbase, off-axis distance from center) - * @return The robot's new position (x, y, rot) - */ - static pose_t calculate_new_pos(double lside_delta_deg, double rside_delta_deg, double offax_delta_deg, pose_t old_pos, odometry3wheel_cfg_t cfg); + /** + * Update the current position of the robot once, using the current state of + * the encoders and the previous known location + * + * @return the robot's updated position + */ + pose_t update() override; - CustomEncoder &lside_fwd, &rside_fwd, &off_axis; - odometry3wheel_cfg_t &cfg; + /** + * A guided tuning process to automatically find tuning parameters. + * This method is blocking, and returns when tuning has finished. Follow + * the instructions on the controller to complete the tuning process + * + * @param con Controller reference, for screen and button control + * @param drive Drivetrain reference for robot control + */ + void tune(vex::controller &con, TankDrive &drive); +private: + /** + * Calculation method for the robot's new position using the change in encoders, the old position, and the robot's + * configuration. This uses a series of arclength formulae for finding distance driven and change in angle. Then + * vector math is used to combine it with the robot's old position data + * + * @param lside_delta_deg Left encoder change in rotation, in degrees + * @param rside_delta_deg Right encoder change in rotation, in degrees + * @param offax_delta_deg Off-axis (perpendicular) encoder change in rotation, in degrees + * @param old_pos Robot's old position, for integration + * @param cfg Data on robot's configuration (wheel diameter, wheelbase, off-axis distance from center) + * @return The robot's new position (x, y, rot) + */ + static pose_t calculate_new_pos(double lside_delta_deg, double rside_delta_deg, double offax_delta_deg, + pose_t old_pos, odometry3wheel_cfg_t cfg); + CustomEncoder &lside_fwd, &rside_fwd, &off_axis; + odometry3wheel_cfg_t &cfg; }; \ No newline at end of file diff --git a/include/subsystems/odometry/odometry_base.h b/include/subsystems/odometry/odometry_base.h index 2da4202..05293f4 100644 --- a/include/subsystems/odometry/odometry_base.h +++ b/include/subsystems/odometry/odometry_base.h @@ -1,149 +1,146 @@ #pragma once -#include "vex.h" -#include "../core/include/utils/geometry.h" #include "../core/include/robot_specs.h" #include "../core/include/utils/command_structure/auto_command.h" +#include "../core/include/utils/geometry.h" +#include "vex.h" #ifndef PI #define PI 3.141592654 #endif - - /** * OdometryBase - * + * * This base class contains all the shared code between different implementations of odometry. - * It handles the asynchronous management, position input/output and basic math functions, and - * holds positional types specific to field orientation. - * - * All future odometry implementations should extend this file and redefine update() function. - * + * It handles the asynchronous management, position input/output and basic math functions, and + * holds positional types specific to field orientation. + * + * All future odometry implementations should extend this file and redefine update() function. + * * @author Ryan McGee * @date Aug 11 2021 */ -class OdometryBase -{ +class OdometryBase { public: - - /** - * Construct a new Odometry Base object - * - * @param is_async True to run constantly in the background, false to call update() manually - */ - OdometryBase(bool is_async); - - /** - * Gets the current position and rotation - * @return the position that the odometry believes the robot is at - */ - pose_t get_position(void); - - /** - * Sets the current position of the robot - * @param newpos the new position that the odometry will believe it is at - */ - virtual void set_position(const pose_t& newpos=zero_pos); - AutoCommand *SetPositionCmd(const pose_t& newpos=zero_pos); - /** - * Update the current position on the field based on the sensors - * @return the location that the robot is at after the odometry does its calculations - */ - virtual pose_t update() = 0; - - /** - * Function that runs in the background task. This function pointer is passed - * to the vex::task constructor. - * - * @param ptr Pointer to OdometryBase object - * @return Required integer return code. Unused. - */ - static int background_task(void* ptr); - - /** - * End the background task. Cannot be restarted. - * If the user wants to end the thread but keep the data up to date, - * they must run the update() function manually from then on. - */ - void end_async(); - - /** - * Get the distance between two points - * @param start_pos distance from this point - * @param end_pos to this point - * @return the euclidean distance between start_pos and end_pos - */ - static double pos_diff(pose_t start_pos, pose_t end_pos); - - /** - * Get the change in rotation between two points - * @param pos1 position with initial rotation - * @param pos2 position with final rotation - * @return change in rotation between pos1 and pos2 - */ - static double rot_diff(pose_t pos1, pose_t pos2); - - /** - * Get the smallest difference in angle between a start heading and end heading. - * Returns the difference between -180 degrees and +180 degrees, representing the robot - * turning left or right, respectively. - * @param start_deg intitial angle (degrees) - * @param end_deg final angle (degrees) - * @return the smallest angle from the initial to the final angle. This takes into account the wrapping of rotations around 360 degrees - */ - static double smallest_angle(double start_deg, double end_deg); - - /// @brief end_task is true if we instruct the odometry thread to shut down - bool end_task = false; - - /** - * Get the current speed - * @return the speed at which the robot is moving and grooving (inch/s) - */ - double get_speed(); - - /** - * Get the current acceleration - * @return the acceleration rate of the robot (inch/s^2) - */ - double get_accel(); - - /** - * Get the current angular speed in degrees - * @return the angular velocity at which we are turning (deg/s) - */ - double get_angular_speed_deg(); - - /** - * Get the current angular acceleration in degrees - * @return the angular acceleration at which we are turning (deg/s^2) - */ - double get_angular_accel_deg(); - - /** - * Zeroed position. X=0, Y=0, Rotation= 90 degrees - */ - inline static constexpr pose_t zero_pos = {.x=0.0L, .y=0.0L, .rot=90.0L}; + /** + * Construct a new Odometry Base object + * + * @param is_async True to run constantly in the background, false to call update() manually + */ + OdometryBase(bool is_async); + + /** + * Gets the current position and rotation + * @return the position that the odometry believes the robot is at + */ + pose_t get_position(void); + + /** + * Sets the current position of the robot + * @param newpos the new position that the odometry will believe it is at + */ + virtual void set_position(const pose_t &newpos = zero_pos); + AutoCommand *SetPositionCmd(const pose_t &newpos = zero_pos); + /** + * Update the current position on the field based on the sensors + * @return the location that the robot is at after the odometry does its calculations + */ + virtual pose_t update() = 0; + + /** + * Function that runs in the background task. This function pointer is passed + * to the vex::task constructor. + * + * @param ptr Pointer to OdometryBase object + * @return Required integer return code. Unused. + */ + static int background_task(void *ptr); + + /** + * End the background task. Cannot be restarted. + * If the user wants to end the thread but keep the data up to date, + * they must run the update() function manually from then on. + */ + void end_async(); + + /** + * Get the distance between two points + * @param start_pos distance from this point + * @param end_pos to this point + * @return the euclidean distance between start_pos and end_pos + */ + static double pos_diff(pose_t start_pos, pose_t end_pos); + + /** + * Get the change in rotation between two points + * @param pos1 position with initial rotation + * @param pos2 position with final rotation + * @return change in rotation between pos1 and pos2 + */ + static double rot_diff(pose_t pos1, pose_t pos2); + + /** + * Get the smallest difference in angle between a start heading and end heading. + * Returns the difference between -180 degrees and +180 degrees, representing the robot + * turning left or right, respectively. + * @param start_deg intitial angle (degrees) + * @param end_deg final angle (degrees) + * @return the smallest angle from the initial to the final angle. This takes into account the wrapping of rotations + * around 360 degrees + */ + static double smallest_angle(double start_deg, double end_deg); + + /// @brief end_task is true if we instruct the odometry thread to shut down + bool end_task = false; + + /** + * Get the current speed + * @return the speed at which the robot is moving and grooving (inch/s) + */ + double get_speed(); + + /** + * Get the current acceleration + * @return the acceleration rate of the robot (inch/s^2) + */ + double get_accel(); + + /** + * Get the current angular speed in degrees + * @return the angular velocity at which we are turning (deg/s) + */ + double get_angular_speed_deg(); + + /** + * Get the current angular acceleration in degrees + * @return the angular acceleration at which we are turning (deg/s^2) + */ + double get_angular_accel_deg(); + + /** + * Zeroed position. X=0, Y=0, Rotation= 90 degrees + */ + inline static constexpr pose_t zero_pos = {.x = 0.0L, .y = 0.0L, .rot = 90.0L}; protected: - /** - * handle to the vex task that is running the odometry code - */ - vex::task *handle; - - /** - * Mutex to control multithreading - */ - vex::mutex mut; - - /** - * Current position of the robot in terms of x,y,rotation - */ - pose_t current_pos; - - double speed; /**< the speed at which we are travelling (inch/s)*/ - double accel; /**< the rate at which we are accelerating (inch/s^2)*/ - double ang_speed_deg; /**< the speed at which we are turning (deg/s)*/ - double ang_accel_deg; /**< the rate at which we are accelerating our turn (deg/s^2)*/ + /** + * handle to the vex task that is running the odometry code + */ + vex::task *handle; + + /** + * Mutex to control multithreading + */ + vex::mutex mut; + + /** + * Current position of the robot in terms of x,y,rotation + */ + pose_t current_pos; + + double speed; /**< the speed at which we are travelling (inch/s)*/ + double accel; /**< the rate at which we are accelerating (inch/s^2)*/ + double ang_speed_deg; /**< the speed at which we are turning (deg/s)*/ + double ang_accel_deg; /**< the rate at which we are accelerating our turn (deg/s^2)*/ }; \ No newline at end of file diff --git a/include/subsystems/odometry/odometry_tank.h b/include/subsystems/odometry/odometry_tank.h index 7e8607f..186ea85 100644 --- a/include/subsystems/odometry/odometry_tank.h +++ b/include/subsystems/odometry/odometry_tank.h @@ -1,84 +1,89 @@ #pragma once -#include "../core/include/subsystems/odometry/odometry_base.h" #include "../core/include/subsystems/custom_encoder.h" +#include "../core/include/subsystems/odometry/odometry_base.h" #include "../core/include/utils/geometry.h" -#include "../core/include/utils/vector2d.h" #include "../core/include/utils/moving_average.h" +#include "../core/include/utils/vector2d.h" #include "../core/include/robot_specs.h" -static int background_task(void* odom_obj); - +static int background_task(void *odom_obj); /** * OdometryTank defines an odometry system for a tank drivetrain * This requires encoders in the same orientation as the drive wheels - * Odometry is a "start and forget" subsystem, which means once it's created and configured, + * Odometry is a "start and forget" subsystem, which means once it's created and configured, * it will constantly run in the background and track the robot's X, Y and rotation coordinates. -*/ -class OdometryTank : public OdometryBase -{ + */ +class OdometryTank : public OdometryBase { public: - /** - * Initialize the Odometry module, calculating position from the drive motors. - * @param left_side The left motors - * @param right_side The right motors - * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained - * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. - * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). - */ - OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true); - - /** - * Initialize the Odometry module, calculating position from the drive motors. - * @param left_custom_enc The left custom encoder - * @param right_custom_enc The right custom encoder - * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained - * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. - * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). - */ + /** + * Initialize the Odometry module, calculating position from the drive motors. + * @param left_side The left motors + * @param right_side The right motors + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for + * what is contained + * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will + * have to manually call update(). + */ + OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, + vex::inertial *imu = NULL, bool is_async = true); - OdometryTank(CustomEncoder &left_custom_enc, CustomEncoder &right_custom_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true); + /** + * Initialize the Odometry module, calculating position from the drive motors. + * @param left_custom_enc The left custom encoder + * @param right_custom_enc The right custom encoder + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for + * what is contained + * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will + * have to manually call update(). + */ - /** - * Initialize the Odometry module, calculating position from the drive motors. - * @param left_vex_enc The left vex encoder - * @param right_vex_enc The right vex encoder - * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained - * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. - * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). - */ + OdometryTank(CustomEncoder &left_custom_enc, CustomEncoder &right_custom_enc, robot_specs_t &config, + vex::inertial *imu = NULL, bool is_async = true); - OdometryTank(vex::encoder &left_vex_enc, vex::encoder &right_vex_enc, robot_specs_t &config, vex::inertial *imu=NULL, bool is_async=true); + /** + * Initialize the Odometry module, calculating position from the drive motors. + * @param left_vex_enc The left vex encoder + * @param right_vex_enc The right vex encoder + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for + * what is contained + * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will + * have to manually call update(). + */ - /** - * Update the current position on the field based on the sensors - * @return the position that odometry has calculated itself to be at - */ - pose_t update() override; + OdometryTank(vex::encoder &left_vex_enc, vex::encoder &right_vex_enc, robot_specs_t &config, + vex::inertial *imu = NULL, bool is_async = true); - /** - * set_position tells the odometry to place itself at a position - * @param newpos the position the odometry will take - */ - void set_position(const pose_t &newpos=zero_pos) override; + /** + * Update the current position on the field based on the sensors + * @return the position that odometry has calculated itself to be at + */ + pose_t update() override; - + /** + * set_position tells the odometry to place itself at a position + * @param newpos the position the odometry will take + */ + void set_position(const pose_t &newpos = zero_pos) override; private: - /** - * Get information from the input hardware and an existing position, and calculate a new current position - */ - static pose_t calculate_new_pos(robot_specs_t &config, pose_t &stored_info, double lside_diff, double rside_diff, double angle_deg); + /** + * Get information from the input hardware and an existing position, and calculate a new current position + */ + static pose_t calculate_new_pos(robot_specs_t &config, pose_t &stored_info, double lside_diff, double rside_diff, + double angle_deg); - vex::motor_group *left_side, *right_side; - CustomEncoder *left_custom_enc, *right_custom_enc; - vex::encoder *left_vex_enc, *right_vex_enc; - vex::inertial *imu; - robot_specs_t &config; + vex::motor_group *left_side, *right_side; + CustomEncoder *left_custom_enc, *right_custom_enc; + vex::encoder *left_vex_enc, *right_vex_enc; + vex::inertial *imu; + robot_specs_t &config; - double rotation_offset = 0; - ExponentialMovingAverage ema = ExponentialMovingAverage(3); - + double rotation_offset = 0; + ExponentialMovingAverage ema = ExponentialMovingAverage(3); }; \ No newline at end of file diff --git a/include/subsystems/screen.h b/include/subsystems/screen.h index 58159b2..ec2452c 100644 --- a/include/subsystems/screen.h +++ b/include/subsystems/screen.h @@ -1,312 +1,298 @@ #pragma once -#include "vex.h" -#include -#include -#include -#include #include "../core/include/subsystems/odometry/odometry_base.h" -#include "../core/include/utils/graph_drawer.h" #include "../core/include/utils/controls/pid.h" #include "../core/include/utils/controls/pidff.h" +#include "../core/include/utils/graph_drawer.h" +#include "vex.h" +#include +#include +#include +#include -namespace screen -{ - /// @brief Widget that does something when you tap it. The function is only called once when you first tap it - class ButtonWidget - { - public: - /// @brief Create a Button widget - /// @param onpress the function to be called when the button is tapped - /// @param rect the area the button should take up on the screen - /// @param name the label put on the button - ButtonWidget(std::function onpress, Rect rect, std::string name) : onpress(onpress), rect(rect), name(name) {} - /// @brief Create a Button widget - /// @param onpress the function to be called when the button is tapped - /// @param rect the area the button should take up on the screen - /// @param name the label put on the button - ButtonWidget(void (*onpress)(), Rect rect, std::string name) : onpress(onpress), rect(rect), name(name) {} - - /// @brief responds to user input - /// @param was_pressed if the screen is pressed - /// @param x x position if the screen was pressed - /// @param y y position if the screen was pressed - /// @return true if the button was pressed - bool update(bool was_pressed, int x, int y); - /// @brief draws the button to the screen - void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number); - - private: - std::function onpress; - Rect rect; - std::string name = ""; - bool was_pressed_last = false; - }; - - /// @brief Widget that updates a double value. Updates by reference so watch out for race conditions cuz the screen stuff lives on another thread - class SliderWidget - { - public: - /// @brief Creates a slider widget - /// @param val reference to the value to modify - /// @param low minimum value to go to - /// @param high maximum value to go to - /// @param rect rect to draw it - /// @param name name of the value - SliderWidget(double &val, double low, double high, Rect rect, std::string name) : value(val), low(low), high(high), rect(rect), name(name) {} - - /// @brief responds to user input - /// @param was_pressed if the screen is pressed - /// @param x x position if the screen was pressed - /// @param y y position if the screen was pressed - /// @return true if the value updated - bool update(bool was_pressed, int x, int y); - /// @brief @ref Page::draws the slide to the screen - void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number); - - private: - double &value; - - double low; - double high; - - Rect rect; - std::string name = ""; - }; - - struct WidgetConfig; - - struct SliderConfig - { - double &val; - double low; - double high; - }; - struct ButtonConfig - { - std::function onclick; - }; - struct CheckboxConfig - { - std::function onupdate; - }; - struct LabelConfig - { - std::string label; - }; - - struct TextConfig - { - std::function text; - }; - struct SizedWidget - { - int size; - WidgetConfig &widget; - }; - struct WidgetConfig - { - enum Type - { - Col, - Row, - Slider, - Button, - Checkbox, - Label, - Text, - Graph, - }; - Type type; - union - { - std::vector widgets; - SliderConfig slider; - ButtonConfig button; - CheckboxConfig checkbox; - LabelConfig label; - TextConfig text; - GraphDrawer *graph; - } config; - }; - - class Page; - /// @brief Page describes one part of the screen slideshow - class Page - { - public: - /** - * @brief collect data, respond to screen input, do fast things (runs at - * 50hz even if you're not focused on this Page (only drawn page gets - * touch updates)) - * @param was_pressed true if the screen has been pressed - * @param x x position of screen press (if the screen was pressed) - * @param y y position of screen press (if the screen was pressed) - */ - virtual void update(bool was_pressed, int x, int y); - /** - * @brief draw stored data to the screen (runs at 10 hz and only runs if - * this page is in front) - * @param first_draw true if we just switched to this page - * @param frame_number frame of drawing we are on (basically an animation - * tick) - */ - virtual void draw(vex::brain::lcd &screen, bool first_draw, - unsigned int frame_number); - }; - - struct ScreenRect - { - uint32_t x1; - uint32_t y1; - uint32_t x2; - uint32_t y2; - }; - void draw_widget(WidgetConfig &widget, ScreenRect rect); - - class WidgetPage : public Page - { - public: - WidgetPage(WidgetConfig &cfg) : base_widget(cfg) {} - void update(bool was_pressed, int x, int y) override; - - void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override - { - draw_widget(base_widget, {.x1 = 20, .y1 = 0, .x2 = 440, .y2 = 240}); - } - - private: - WidgetConfig &base_widget; - }; - - /** - * @brief Start the screen background task. Once you start this, no need to draw to the screen manually elsewhere - * @param screen reference to the vex screen - * @param pages drawing pages - * @param first_page optional, which page to start the program at. by default 0 - */ - void start_screen(vex::brain::lcd &screen, std::vector pages, int first_page = 0); - - - void next_page(); - void prev_page(); - - /// @brief stops the screen. If you have a drive team that hates fun call this at the start of opcontrol - void stop_screen(); - - /// @brief type of function needed for update - using update_func_t = std::function; - - /// @brief type of function needed for draw - using draw_func_t = std::function; - - /// @brief Draws motor stats and battery stats to the screen - class StatsPage : public Page - { - public: - /// @brief Creates a stats page - /// @param motors a map of string to motor that we want to draw on this page - StatsPage(std::map motors); - /// @brief @see Page#update - void update(bool was_pressed, int x, int y) override; - /// @brief @see Page#draw - void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; - - private: - void draw_motor_stats(const std::string &name, vex::motor &mot, unsigned int frame, int x, int y, vex::brain::lcd &scr); - - std::map motors; - static const int y_start = 0; - static const int per_column = 4; - static const int row_height = 20; - static const int row_width = 200; - }; - - /** - * @brief a page that shows odometry position and rotation and a map (if an sd card with the file is on) - */ - class OdometryPage : public Page - { - public: - /// @brief Create an odometry trail. Make sure odometry is initilized before now - /// @param odom the odometry system to monitor - /// @param robot_width the width (side to side) of the robot in inches. Used for visualization - /// @param robot_height the robot_height (front to back) of the robot in inches. Used for visualization - /// @param do_trail whether or not to calculate and draw the trail. Drawing and storing takes a very *slight* extra amount of processing power - OdometryPage(OdometryBase &odom, double robot_width, double robot_height, bool do_trail); - /// @brief @see Page#update - void update(bool was_pressed, int x, int y) override; - /// @brief @see Page#draw - void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; - - private: - static const int path_len = 40; - static constexpr char const *field_filename = "vex_field_240p.png"; - - OdometryBase &odom; - double robot_width; - double robot_height; - uint8_t *buf = nullptr; - int buf_size = 0; - pose_t path[path_len]; - int path_index = 0; - bool do_trail; - GraphDrawer velocity_graph; - }; - - /// @brief Simple page that stores no internal data. the draw and update functions use only global data rather than storing anything - class FunctionPage : public Page - { - public: - /// @brief Creates a function page - /// @param update_f the function called every tick to respond to user input or do data collection - /// @param draw_t the function called to draw to the screen - FunctionPage(update_func_t update_f, draw_func_t draw_t); - /// @brief @see Page#update - void update(bool was_pressed, int x, int y) override; - /// @brief @see Page#draw - void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; - - private: - update_func_t update_f; - draw_func_t draw_f; - }; - - /// @brief PIDPage provides a way to tune a pid controller on the screen - class PIDPage : public Page - { - public: - /// @brief Create a PIDPage - /// @param pid the pid controller we're changing - /// @param name a name to recognize this pid controller if we've got multiple pid screens - /// @param onchange a function that is called when a tuning parameter is changed. If you need to update stuff on that change register a handler here - PIDPage( - PID &pid, std::string name, std::function onchange = []() {}); - PIDPage( - PIDFF &pidff, std::string name, std::function onchange = []() {}); - - /// @brief @see Page#update - void update(bool was_pressed, int x, int y) override; - /// @brief @see Page#draw - void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; - - private: - /// @brief reset d - void zero_d_f() { cfg.d = 0; } - /// @brief reset i - void zero_i_f() { cfg.i = 0; } - - PID::pid_config_t &cfg; - PID &pid; - const std::string name; - std::function onchange; - - SliderWidget p_slider; - SliderWidget i_slider; - SliderWidget d_slider; - ButtonWidget zero_i; - ButtonWidget zero_d; - - GraphDrawer graph; - }; - -} +namespace screen { +/// @brief Widget that does something when you tap it. The function is only called once when you first tap it +class ButtonWidget { +public: + /// @brief Create a Button widget + /// @param onpress the function to be called when the button is tapped + /// @param rect the area the button should take up on the screen + /// @param name the label put on the button + ButtonWidget(std::function onpress, Rect rect, std::string name) + : onpress(onpress), rect(rect), name(name) {} + /// @brief Create a Button widget + /// @param onpress the function to be called when the button is tapped + /// @param rect the area the button should take up on the screen + /// @param name the label put on the button + ButtonWidget(void (*onpress)(), Rect rect, std::string name) : onpress(onpress), rect(rect), name(name) {} + + /// @brief responds to user input + /// @param was_pressed if the screen is pressed + /// @param x x position if the screen was pressed + /// @param y y position if the screen was pressed + /// @return true if the button was pressed + bool update(bool was_pressed, int x, int y); + /// @brief draws the button to the screen + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number); + +private: + std::function onpress; + Rect rect; + std::string name = ""; + bool was_pressed_last = false; +}; + +/// @brief Widget that updates a double value. Updates by reference so watch out for race conditions cuz the screen +/// stuff lives on another thread +class SliderWidget { +public: + /// @brief Creates a slider widget + /// @param val reference to the value to modify + /// @param low minimum value to go to + /// @param high maximum value to go to + /// @param rect rect to draw it + /// @param name name of the value + SliderWidget(double &val, double low, double high, Rect rect, std::string name) + : value(val), low(low), high(high), rect(rect), name(name) {} + + /// @brief responds to user input + /// @param was_pressed if the screen is pressed + /// @param x x position if the screen was pressed + /// @param y y position if the screen was pressed + /// @return true if the value updated + bool update(bool was_pressed, int x, int y); + /// @brief @ref Page::draws the slide to the screen + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number); + +private: + double &value; + + double low; + double high; + + Rect rect; + std::string name = ""; +}; + +struct WidgetConfig; + +struct SliderConfig { + double &val; + double low; + double high; +}; +struct ButtonConfig { + std::function onclick; +}; +struct CheckboxConfig { + std::function onupdate; +}; +struct LabelConfig { + std::string label; +}; + +struct TextConfig { + std::function text; +}; +struct SizedWidget { + int size; + WidgetConfig &widget; +}; +struct WidgetConfig { + enum Type { + Col, + Row, + Slider, + Button, + Checkbox, + Label, + Text, + Graph, + }; + Type type; + union { + std::vector widgets; + SliderConfig slider; + ButtonConfig button; + CheckboxConfig checkbox; + LabelConfig label; + TextConfig text; + GraphDrawer *graph; + } config; +}; + +class Page; +/// @brief Page describes one part of the screen slideshow +class Page { +public: + /** + * @brief collect data, respond to screen input, do fast things (runs at + * 50hz even if you're not focused on this Page (only drawn page gets + * touch updates)) + * @param was_pressed true if the screen has been pressed + * @param x x position of screen press (if the screen was pressed) + * @param y y position of screen press (if the screen was pressed) + */ + virtual void update(bool was_pressed, int x, int y); + /** + * @brief draw stored data to the screen (runs at 10 hz and only runs if + * this page is in front) + * @param first_draw true if we just switched to this page + * @param frame_number frame of drawing we are on (basically an animation + * tick) + */ + virtual void draw(vex::brain::lcd &screen, bool first_draw, unsigned int frame_number); +}; + +struct ScreenRect { + uint32_t x1; + uint32_t y1; + uint32_t x2; + uint32_t y2; +}; +void draw_widget(WidgetConfig &widget, ScreenRect rect); + +class WidgetPage : public Page { +public: + WidgetPage(WidgetConfig &cfg) : base_widget(cfg) {} + void update(bool was_pressed, int x, int y) override; + + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override { + draw_widget(base_widget, {.x1 = 20, .y1 = 0, .x2 = 440, .y2 = 240}); + } + +private: + WidgetConfig &base_widget; +}; + +/** + * @brief Start the screen background task. Once you start this, no need to draw to the screen manually elsewhere + * @param screen reference to the vex screen + * @param pages drawing pages + * @param first_page optional, which page to start the program at. by default 0 + */ +void start_screen(vex::brain::lcd &screen, std::vector pages, int first_page = 0); + +void next_page(); +void prev_page(); +void goto_page(size_t page); + +/// @brief stops the screen. If you have a drive team that hates fun call this at the start of opcontrol +void stop_screen(); + +/// @brief type of function needed for update +using update_func_t = std::function; + +/// @brief type of function needed for draw +using draw_func_t = std::function; + +/// @brief Draws motor stats and battery stats to the screen +class StatsPage : public Page { +public: + /// @brief Creates a stats page + /// @param motors a map of string to motor that we want to draw on this page + StatsPage(std::map motors); + /// @brief @see Page#update + void update(bool was_pressed, int x, int y) override; + /// @brief @see Page#draw + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; + +private: + void draw_motor_stats(const std::string &name, vex::motor &mot, unsigned int frame, int x, int y, + vex::brain::lcd &scr); + + std::map motors; + static const int y_start = 0; + static const int per_column = 4; + static const int row_height = 20; + static const int row_width = 200; +}; + +/** + * @brief a page that shows odometry position and rotation and a map (if an sd card with the file is on) + */ +class OdometryPage : public Page { +public: + /// @brief Create an odometry trail. Make sure odometry is initilized before now + /// @param odom the odometry system to monitor + /// @param robot_width the width (side to side) of the robot in inches. Used for visualization + /// @param robot_height the robot_height (front to back) of the robot in inches. Used for visualization + /// @param do_trail whether or not to calculate and draw the trail. Drawing and storing takes a very *slight* extra + /// amount of processing power + OdometryPage(OdometryBase &odom, double robot_width, double robot_height, bool do_trail); + /// @brief @see Page#update + void update(bool was_pressed, int x, int y) override; + /// @brief @see Page#draw + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; + +private: + static const int path_len = 40; + static constexpr char const *field_filename = "vex_field_240p.png"; + + OdometryBase &odom; + double robot_width; + double robot_height; + uint8_t *buf = nullptr; + int buf_size = 0; + pose_t path[path_len]; + int path_index = 0; + bool do_trail; + GraphDrawer velocity_graph; +}; + +/// @brief Simple page that stores no internal data. the draw and update functions use only global data rather than +/// storing anything +class FunctionPage : public Page { +public: + /// @brief Creates a function page + /// @param update_f the function called every tick to respond to user input or do data collection + /// @param draw_t the function called to draw to the screen + FunctionPage(update_func_t update_f, draw_func_t draw_t); + /// @brief @see Page#update + void update(bool was_pressed, int x, int y) override; + /// @brief @see Page#draw + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; + +private: + update_func_t update_f; + draw_func_t draw_f; +}; + +/// @brief PIDPage provides a way to tune a pid controller on the screen +class PIDPage : public Page { +public: + /// @brief Create a PIDPage + /// @param pid the pid controller we're changing + /// @param name a name to recognize this pid controller if we've got multiple pid screens + /// @param onchange a function that is called when a tuning parameter is changed. If you need to update stuff on that + /// change register a handler here + PIDPage( + PID &pid, std::string name, std::function onchange = []() {}); + PIDPage( + PIDFF &pidff, std::string name, std::function onchange = []() {}); + + /// @brief @see Page#update + void update(bool was_pressed, int x, int y) override; + /// @brief @see Page#draw + void draw(vex::brain::lcd &, bool first_draw, unsigned int frame_number) override; + +private: + /// @brief reset d + void zero_d_f() { cfg.d = 0; } + /// @brief reset i + void zero_i_f() { cfg.i = 0; } + + PID::pid_config_t &cfg; + PID &pid; + const std::string name; + std::function onchange; + + SliderWidget p_slider; + SliderWidget i_slider; + SliderWidget d_slider; + ButtonWidget zero_i; + ButtonWidget zero_d; + + GraphDrawer graph; +}; + +} // namespace screen diff --git a/include/subsystems/tank_drive.h b/include/subsystems/tank_drive.h index 2e63002..ab4f3e8 100644 --- a/include/subsystems/tank_drive.h +++ b/include/subsystems/tank_drive.h @@ -4,53 +4,66 @@ #define PI 3.141592654 #endif -#include "vex.h" +#include "../core/include/robot_specs.h" #include "../core/include/subsystems/odometry/odometry_tank.h" -#include "../core/include/utils/controls/pid.h" +#include "../core/include/utils/command_structure/auto_command.h" #include "../core/include/utils/controls/feedback_base.h" -#include "../core/include/robot_specs.h" +#include "../core/include/utils/controls/pid.h" #include "../core/include/utils/pure_pursuit.h" -#include "../core/include/utils/command_structure/auto_command.h" +#include "vex.h" #include using namespace vex; /** * TankDrive is a class to run a tank drive system. - * A tank drive system, sometimes called differential drive, has a motor (or group of synchronized motors) on the left and right side + * A tank drive system, sometimes called differential drive, has a motor (or + * group of synchronized motors) on the left and right side */ -class TankDrive -{ +class TankDrive { public: - enum class BrakeType - { - None, ///< just send 0 volts to the motors - ZeroVelocity, ///< try to bring the robot to rest. But don't try to hold position - Smart, ///< bring the robot to rest and once it's stopped, try to hold that position + enum class BrakeType { + None, ///< just send 0 volts to the motors + ZeroVelocity, ///< try to bring the robot to rest. But don't try to hold + ///< position + Smart, ///< bring the robot to rest and once it's stopped, try to hold + ///< that position }; /** * Create the TankDrive object * @param left_motors left side drive motors * @param right_motors right side drive motors - * @param config the configuration specification defining physical dimensions about the robot. See robot_specs_t for more info - * @param odom an odometry system to track position and rotation. this is necessary to execute autonomous paths + * @param config the configuration specification defining physical + * dimensions about the robot. See robot_specs_t for more info + * @param odom an odometry system to track position and rotation. this is + * necessary to execute autonomous paths */ TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom = NULL); - AutoCommand *DriveToPointCmd(point_t pt, vex::directionType dir = vex::forward, double max_speed = 1.0, double end_speed = 0.0); - AutoCommand *DriveToPointCmd(Feedback &fb, point_t pt, vex::directionType dir = vex::forward, double max_speed = 1.0, double end_speed = 0.0); + AutoCommand *DriveToPointCmd(point_t pt, vex::directionType dir = vex::forward, double max_speed = 1.0, + double end_speed = 0.0); + AutoCommand *DriveToPointCmd(Feedback &fb, point_t pt, vex::directionType dir = vex::forward, double max_speed = 1.0, + double end_speed = 0.0); - AutoCommand *DriveForwardCmd(double dist, vex::directionType dir = vex::forward, double max_speed = 1.0, double end_speed = 0.0); - AutoCommand *DriveForwardCmd(Feedback &fb, double dist, vex::directionType dir = vex::forward, double max_speed = 1.0, double end_speed = 0.0); + AutoCommand *DriveForwardCmd(double dist, vex::directionType dir = vex::forward, double max_speed = 1.0, + double end_speed = 0.0); + AutoCommand *DriveForwardCmd(Feedback &fb, double dist, vex::directionType dir = vex::forward, double max_speed = 1.0, + double end_speed = 0.0); AutoCommand *TurnToHeadingCmd(double heading, double max_speed = 1.0, double end_speed = 0.0); AutoCommand *TurnToHeadingCmd(Feedback &fb, double heading, double max_speed = 1.0, double end_speed = 0.0); + AutoCommand *TurnToPointCmd(double x, double y, vex::directionType dir = vex::directionType::fwd, + double max_speed = 1.0, double end_speed = 0.0); + AutoCommand *TurnDegreesCmd(double degrees, double max_speed = 1.0, double start_speed = 0.0); AutoCommand *TurnDegreesCmd(Feedback &fb, double degrees, double max_speed = 1.0, double end_speed = 0.0); AutoCommand *PurePursuitCmd(PurePursuit::Path path, directionType dir, double max_speed = 1, double end_speed = 0); - AutoCommand *PurePursuitCmd(Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed = 1, double end_speed = 0); + AutoCommand *PurePursuitCmd(Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed = 1, + double end_speed = 0); + Condition *DriveStalledCondition(double stall_time); + AutoCommand *DriveTankCmd(double left, double right); /** * Stops rotation of all the motors using their "brake mode" @@ -58,8 +71,8 @@ class TankDrive void stop(); /** - * Drive the robot using differential style controls. left_motors controls the left motors, - * right_motors controls the right motors. + * Drive the robot using differential style controls. left_motors controls + * the left motors, right_motors controls the right motors. * * left_motors and right_motors are in "percent": -1.0 -> 1.0 * @param left the percent to run the left motors @@ -72,12 +85,12 @@ class TankDrive * Drive the robot raw-ly * @param left the percent to run the left motors (-1, 1) * @param right the percent to run the right motors (-1, 1) - */ + */ void drive_tank_raw(double left, double right); /** - * Drive the robot using arcade style controls. forward_back controls the linear motion, - * left_right controls the turning. + * Drive the robot using arcade style controls. forward_back controls the + * linear motion, left_right controls the turning. * * forward_back and left_right are in "percent": -1.0 -> 1.0 * @@ -89,14 +102,18 @@ class TankDrive void drive_arcade(double forward_back, double left_right, int power = 1, BrakeType bt = BrakeType::None); /** - * Use odometry to drive forward a certain distance using a custom feedback controller + * Use odometry to drive forward a certain distance using a custom feedback + * controller * * Returns whether or not the robot has reached it's destination. * @param inches the distance to drive forward * @param dir the direction we want to travel forward and backward - * @param feedback the custom feedback controller we will use to travel. controls the rate at which we accelerate and drive. - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param feedback the custom feedback controller we will use to travel. + * controls the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the + * robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this + * velocity by its completion * @return true when we have reached our target distance */ bool drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed = 1, double end_speed = 0); @@ -105,34 +122,43 @@ class TankDrive * Autonomously drive the robot forward a certain distance * * - * @param inches degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw + * @param inches degrees by which we will turn relative to the robot + * (+) turns ccw, (-) turns cw * @param dir the direction we want to travel forward and backward - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param max_speed the maximum percentage of robot speed at which the + * robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this + * velocity by its completion */ bool drive_forward(double inches, directionType dir, double max_speed = 1, double end_speed = 0); /** - * Autonomously turn the robot X degrees counterclockwise (negative for clockwise), with a maximum motor speed - * of percent_speed (-1.0 -> 1.0) + * Autonomously turn the robot X degrees counterclockwise (negative for + * clockwise), with a maximum motor speed of percent_speed (-1.0 -> 1.0) * * Uses PID + Feedforward for it's control. * - * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw - * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power + * @param degrees degrees by which we will turn relative to the robot + * (+) turns ccw, (-) turns cw + * @param feedback the feedback controller we will use to travel. + * controls the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the + * robot will travel. 1 = full power */ bool turn_degrees(double degrees, Feedback &feedback, double max_speed = 1, double end_speed = 0); /** - * Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed - * of percent_speed (-1.0 -> 1.0) + * Autonomously turn the robot X degrees to counterclockwise (negative for + * clockwise), with a maximum motor speed of percent_speed (-1.0 -> 1.0) * * Uses the defualt turning feedback of the drive system. * - * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param degrees degrees by which we will turn relative to the robot + * (+) turns ccw, (-) turns cw + * @param max_speed the maximum percentage of robot speed at which the + * robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this + * velocity by its completion */ bool turn_degrees(double degrees, double max_speed = 1, double end_speed = 0); @@ -144,11 +170,15 @@ class TankDrive * @param x the x position of the target * @param y the y position of the target * @param dir the direction we want to travel forward and backward - * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param feedback the feedback controller we will use to travel. controls + * the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the + * robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this + * velocity by its completion */ - bool drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed = 1, double end_speed = 0); + bool drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed = 1, + double end_speed = 0); /** * Use odometry to automatically drive the robot to a point on the field. @@ -159,8 +189,10 @@ class TankDrive * @param x the x position of the target * @param y the y position of the target * @param dir the direction we want to travel forward and backward - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param max_speed the maximum percentage of robot speed at which the + * robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this + * velocity by its completion */ bool drive_to_point(double x, double y, vex::directionType dir, double max_speed = 1, double end_speed = 0); @@ -169,9 +201,12 @@ class TankDrive * 0 is forward. * * @param heading_deg the heading to which we will turn - * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param feedback the feedback controller we will use to travel. + * controls the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the + * robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this + * velocity by its completion */ bool turn_to_heading(double heading_deg, Feedback &feedback, double max_speed = 1, double end_speed = 0); /** @@ -179,8 +214,10 @@ class TankDrive * 0 is forward. Uses the defualt turn feedback of the drive system * * @param heading_deg the heading to which we will turn - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param max_speed the maximum percentage of robot speed at which the + * robot will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this + * velocity by its completion */ bool turn_to_heading(double heading_deg, double max_speed = 1, double end_speed = 0); @@ -190,40 +227,47 @@ class TankDrive void reset_auto(); /** - * Create a curve for the inputs, so that drivers have more control at lower speeds. - * Curves are exponential, with the default being squaring the inputs. + * Create a curve for the inputs, so that drivers have more control at lower + * speeds. Curves are exponential, with the default being squaring the + * inputs. * * @param input the input before modification * @param power the power to raise input to - * @return input ^ power (accounts for negative inputs and odd numbered powers) + * @return input ^ power (accounts for negative inputs and odd numbered + * powers) */ static double modify_inputs(double input, int power = 2); /** - * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of - * waypoints - the robot will attempt to follow the points while cutting corners (radius) - * to save time (compared to stop / turn / start) + * Drive the robot autonomously using a pure-pursuit algorithm - Input path + * with a set of waypoints - the robot will attempt to follow the points + * while cutting corners (radius) to save time (compared to stop / turn / + * start) * * @param path The list of coordinates to follow, in order * @param dir Run the bot forwards or backwards * @param feedback The feedback controller determining speed * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param end_speed the movement profile will attempt to reach this velocity + * by its completion * @return True when the path is complete */ - bool pure_pursuit(PurePursuit::Path path, directionType dir, Feedback &feedback, double max_speed = 1, double end_speed = 0); + bool pure_pursuit(PurePursuit::Path path, directionType dir, Feedback &feedback, double max_speed = 1, + double end_speed = 0); /** - * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of - * waypoints - the robot will attempt to follow the points while cutting corners (radius) - * to save time (compared to stop / turn / start) + * Drive the robot autonomously using a pure-pursuit algorithm - Input path + * with a set of waypoints - the robot will attempt to follow the points + * while cutting corners (radius) to save time (compared to stop / turn / + * start) * * Use the default drive feedback * * @param path The list of coordinates to follow, in order * @param dir Run the bot forwards or backwards * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param end_speed the movement profile will attempt to reach this velocity + * by its completion * @return True when the path is complete */ bool pure_pursuit(PurePursuit::Path path, directionType dir, double max_speed = 1, double end_speed = 0); @@ -232,14 +276,19 @@ class TankDrive motor_group &left_motors; ///< left drive motors motor_group &right_motors; ///< right drive motors - PID correction_pid; ///< PID controller used to drive in as straight a line as possible + PID correction_pid; ///< PID controller used to drive in as straight a line + ///< as possible Feedback *drive_default_feedback = NULL; ///< feedback to use to drive if none is specified Feedback *turn_default_feedback = NULL; ///< feedback to use to turn if none is specified - OdometryBase *odometry; ///< odometry system to track position and rotation. necessary for autonomous driving + OdometryBase *odometry; ///< odometry system to track position and rotation. + ///< necessary for autonomous driving - robot_specs_t &config; ///< configuration holding physical dimensions of the robot. see robot_specs_t for more information + robot_specs_t &config; ///< configuration holding physical dimensions of the + ///< robot. see robot_specs_t for more information - bool func_initialized = false; ///< used to control initialization of autonomous driving. (you only wan't to set the target once, not every iteration that you're driving) + bool func_initialized = false; ///< used to control initialization of autonomous driving. (you + ///< only wan't to set the target once, not every iteration that + ///< you're driving) bool is_pure_pursuit = false; ///< true if we are driving with a pure pursuit system }; diff --git a/include/utils/auto_chooser.h b/include/utils/auto_chooser.h index 59562b6..248227c 100644 --- a/include/utils/auto_chooser.h +++ b/include/utils/auto_chooser.h @@ -1,9 +1,9 @@ #pragma once +#include "../core/include/subsystems/screen.h" +#include "../core/include/utils/geometry.h" #include "vex.h" #include #include -#include "../core/include/subsystems/screen.h" -#include "../core/include/utils/geometry.h" /** * Autochooser is a utility to make selecting robot autonomous programs easier @@ -11,10 +11,10 @@ * During a season, we usually code between 4 and 6 autonomous programs. * Most teams will change their entire robot program as a way of choosing autonomi * but this may cause issues if you have an emergency patch to upload during a competition. - * This class was built as a way of using the robot screen to list autonomous programs, and the touchscreen to select them. + * This class was built as a way of using the robot screen to list autonomous programs, and the touchscreen to select + * them. */ -class AutoChooser : public screen::Page -{ +class AutoChooser : public screen::Page { public: /** * Initialize the auto-chooser. This class places a choice menu on the brain screen, @@ -36,8 +36,7 @@ class AutoChooser : public screen::Page /** * entry_t is a datatype used to store information that the chooser knows about an auto selection button */ - struct entry_t - { + struct entry_t { Rect rect; std::string name; /**< name of the auto repretsented by the block*/ }; diff --git a/include/utils/command_structure/auto_command.h b/include/utils/command_structure/auto_command.h index fa8528e..c7832cf 100644 --- a/include/utils/command_structure/auto_command.h +++ b/include/utils/command_structure/auto_command.h @@ -7,11 +7,10 @@ #pragma once #include "vex.h" +#include #include -#include #include -#include - +#include /** * A Condition is a function that returns true or false @@ -22,17 +21,14 @@ * extend this class for different choices you wish to make */ -class Condition -{ +class Condition { public: Condition *Or(Condition *b); Condition *And(Condition *b); virtual bool test() = 0; }; - -class AutoCommand -{ +class AutoCommand { public: static constexpr double default_timeout = 10.0; /** @@ -45,17 +41,15 @@ class AutoCommand * What to do if we timeout instead of finishing. timeout is specified by the timeout seconds in the constructor */ virtual void on_timeout() {} - AutoCommand *withTimeout(double t_seconds) - { - if (this->timeout_seconds < 0) - { + AutoCommand *withTimeout(double t_seconds) { + if (this->timeout_seconds < 0) { // should never be timed out return this; } this->timeout_seconds = t_seconds; return this; } - AutoCommand *withCancelCondition(Condition *true_to_end){ + AutoCommand *withCancelCondition(Condition *true_to_end) { this->true_to_end = true_to_end; return this; } @@ -76,14 +70,10 @@ class AutoCommand * FunctionCommand is fun and good way to do simple things * Printing, launching nukes, and other quick and dirty one time things */ -class FunctionCommand : public AutoCommand -{ +class FunctionCommand : public AutoCommand { public: FunctionCommand(std::function f) : f(f) {} - bool run() - { - return f(); - } + bool run() { return f(); } private: std::function f; @@ -95,15 +85,12 @@ class FunctionCommand : public AutoCommand // Test 3 -> true // Returns false until the Nth time that it is called // This is pretty much only good for implementing RepeatUntil -class TimesTestedCondition : public Condition -{ +class TimesTestedCondition : public Condition { public: TimesTestedCondition(size_t N) : max(N) {} - bool test() override - { + bool test() override { count++; - if (count >= max) - { + if (count >= max) { return true; } return false; @@ -115,13 +102,11 @@ class TimesTestedCondition : public Condition }; /// @brief FunctionCondition is a quick and dirty Condition to wrap some expression that should be evaluated at runtime -class FunctionCondition : public Condition -{ +class FunctionCondition : public Condition { public: FunctionCondition( - std::function cond, std::function timeout = []() {}) : cond(cond), timeout(timeout) - { - } + std::function cond, std::function timeout = []() {}) + : cond(cond), timeout(timeout) {} bool test() override; private: @@ -129,9 +114,9 @@ class FunctionCondition : public Condition std::function timeout; }; -/// @brief IfTimePassed tests based on time since the command controller was constructed. Returns true if elapsed time > time_s -class IfTimePassed : public Condition -{ +/// @brief IfTimePassed tests based on time since the command controller was constructed. Returns true if elapsed time > +/// time_s +class IfTimePassed : public Condition { public: IfTimePassed(double time_s); bool test() override; @@ -142,14 +127,10 @@ class IfTimePassed : public Condition }; /// @brief Waits until the condition is true -class WaitUntilCondition : public AutoCommand -{ +class WaitUntilCondition : public AutoCommand { public: WaitUntilCondition(Condition *cond) : cond(cond) {} - bool run() override - { - return cond->test(); - } + bool run() override { return cond->test(); } private: Condition *cond; @@ -160,8 +141,7 @@ class WaitUntilCondition : public AutoCommand /// @brief InOrder runs its commands sequentially then continues. /// How to handle timeout in this case. Automatically set it to sum of commands timouts? -class InOrder : public AutoCommand -{ +class InOrder : public AutoCommand { public: InOrder(const InOrder &other) = default; InOrder(std::queue cmds); @@ -177,8 +157,7 @@ class InOrder : public AutoCommand /// @brief Parallel runs multiple commands in parallel and waits for all to finish before continuing. /// if none finish before this command's timeout, it will call on_timeout on all children continue -class Parallel : public AutoCommand -{ +class Parallel : public AutoCommand { public: Parallel(std::initializer_list cmds); bool run() override; @@ -189,11 +168,10 @@ class Parallel : public AutoCommand std::vector runners; }; -/// @brief Branch chooses from multiple options at runtime. the function decider returns an index into the choices vector -/// If you wish to make no choice and skip this section, return NO_CHOICE; -/// any choice that is out of bounds set to NO_CHOICE -class Branch : public AutoCommand -{ +/// @brief Branch chooses from multiple options at runtime. the function decider returns an index into the choices +/// vector If you wish to make no choice and skip this section, return NO_CHOICE; any choice that is out of bounds set +/// to NO_CHOICE +class Branch : public AutoCommand { public: Branch(Condition *cond, AutoCommand *false_choice, AutoCommand *true_choice); ~Branch(); @@ -212,8 +190,7 @@ class Branch : public AutoCommand /// @brief Async runs a command asynchronously /// will simply let it go and never look back /// THIS HAS A VERY NICHE USE CASE. THINK ABOUT IF YOU REALLY NEED IT -class Async : public AutoCommand -{ +class Async : public AutoCommand { public: Async(AutoCommand *cmd) : cmd(cmd) {} bool run() override; @@ -222,8 +199,7 @@ class Async : public AutoCommand AutoCommand *cmd = nullptr; }; -class RepeatUntil : public AutoCommand -{ +class RepeatUntil : public AutoCommand { public: /// @brief RepeatUntil that runs a fixed number of times /// @param cmds the cmds to repeat diff --git a/include/utils/command_structure/basic_command.h b/include/utils/command_structure/basic_command.h index 6df7306..44a8bf8 100644 --- a/include/utils/command_structure/basic_command.h +++ b/include/utils/command_structure/basic_command.h @@ -1,118 +1,112 @@ /** * @file basic_commands.h * @author Ethan Kishimori GITHUB(LilacEthan) - * + * * @brief Basic Commands for Motors and Solenoids able to throw into the Command Controller * Commands Included * - BasicSpinCommand * - BasicStopCommand * - BasicSolenoidSet - * + * * @version 0.1 - * + * */ #pragma once #include "../core/include/utils/command_structure/auto_command.h" - -//Basic Motor Classes----------------------------------------------- + +// Basic Motor Classes----------------------------------------------- /** * AutoCommand wrapper class for BasicSpinCommand * using the vex hardware functions */ class BasicSpinCommand : public AutoCommand { - public: - - //Enumurator for the type of power setting in the motor - enum type {percent,voltage,veocity}; - - /** - * @brief Construct a new BasicSpinCommand - * - * @param motor Motor to spin - * @param direc Direction of motor spin - * @param setting Power setting in volts,percentage,velocity - * @param power Value of desired power - */ - BasicSpinCommand(vex::motor &motor, vex::directionType dir, BasicSpinCommand::type setting, double power); - - /** - * @brief Runs the BasicSpinCommand - * Overrides run from Auto Command - * - * @return True Async running command - */ - bool run() override; - - private: - - vex::motor &motor; - - type setting; - - vex::directionType dir; - - double power; +public: + // Enumurator for the type of power setting in the motor + enum type { percent, voltage, veocity }; + + /** + * @brief Construct a new BasicSpinCommand + * + * @param motor Motor to spin + * @param direc Direction of motor spin + * @param setting Power setting in volts,percentage,velocity + * @param power Value of desired power + */ + BasicSpinCommand(vex::motor &motor, vex::directionType dir, BasicSpinCommand::type setting, double power); + + /** + * @brief Runs the BasicSpinCommand + * Overrides run from Auto Command + * + * @return True Async running command + */ + bool run() override; + +private: + vex::motor &motor; + + type setting; + + vex::directionType dir; + + double power; }; /** * AutoCommand wrapper class for BasicStopCommand * Using the Vex hardware functions */ -class BasicStopCommand : public AutoCommand{ - public: - - /** - * @brief Construct a new BasicMotorStop Command - * - * @param motor The motor to stop - * @param setting The brake setting for the motor - */ - BasicStopCommand(vex::motor &motor, vex::brakeType setting); - - /** - * @brief Runs the BasicMotorStop Command - * Overrides run command from AutoCommand - * - * @return True Command runs once - */ - bool run() override; - - private: - - vex::motor &motor; - - vex::brakeType setting; +class BasicStopCommand : public AutoCommand { +public: + /** + * @brief Construct a new BasicMotorStop Command + * + * @param motor The motor to stop + * @param setting The brake setting for the motor + */ + BasicStopCommand(vex::motor &motor, vex::brakeType setting); + + /** + * @brief Runs the BasicMotorStop Command + * Overrides run command from AutoCommand + * + * @return True Command runs once + */ + bool run() override; + +private: + vex::motor &motor; + + vex::brakeType setting; }; -//Basic Solenoid Commands---------------------------------- +// Basic Solenoid Commands---------------------------------- /** * AutoCommand wrapper class for BasicSolenoidSet * Using the Vex hardware functions */ -class BasicSolenoidSet : public AutoCommand{ - public: - - /** - * @brief Construct a new BasicSolenoidSet Command - * - * @param solenoid Solenoid being set - * @param setting Setting of the solenoid in boolean (true,false) - */ - BasicSolenoidSet(vex::pneumatics &solenoid, bool setting); - - /** - * @brief Runs the BasicSolenoidSet - * Overrides run command from AutoCommand - * - * @return True Command runs once - */ - bool run() override; - - private: - - vex::pneumatics &solenoid; - - bool setting; +class BasicSolenoidSet : public AutoCommand { +public: + /** + * @brief Construct a new BasicSolenoidSet Command + * + * @param solenoid Solenoid being set + * @param setting Setting of the solenoid in boolean (true,false) + */ + BasicSolenoidSet(vex::pneumatics &solenoid, bool setting); + + /** + * @brief Runs the BasicSolenoidSet + * Overrides run command from AutoCommand + * + * @return True Command runs once + */ + bool run() override; + +private: + vex::pneumatics &solenoid; + + bool setting; }; \ No newline at end of file diff --git a/include/utils/command_structure/command_controller.h b/include/utils/command_structure/command_controller.h index 4f8cf14..f942b99 100644 --- a/include/utils/command_structure/command_controller.h +++ b/include/utils/command_structure/command_controller.h @@ -8,25 +8,34 @@ */ #pragma once -#include -#include #include "../core/include/utils/command_structure/auto_command.h" +#include +#include -class CommandController -{ +class CommandController { public: - /// @brief Create an empty CommandController. Add Command with CommandController::add() - [[deprecated("Use list constructor instead.")]] CommandController() : command_queue({}) {} + /// @brief Create an empty CommandController. Add Command with + /// CommandController::add() + [[deprecated("Empty constructor is bad. Use list constructor " + "instead.")]] CommandController() + : command_queue({}) {} - /// @brief Create a CommandController with commands pre added. More can be added with CommandController::add() + /// @brief Create a CommandController with commands pre added. More can be + /// added with CommandController::add() /// @param cmds CommandController(std::initializer_list cmds) : command_queue(cmds) {} /** * Adds a command to the queue * @param cmd the AutoCommand we want to add to our list - * @param timeout_seconds the number of seconds we will let the command run for. If it exceeds this, we cancel it and run on_timeout. if it is <= 0 no time out will be applied + * @param timeout_seconds the number of seconds we will let the command run + * for. If it exceeds this, we cancel it and run on_timeout. if it is <= 0 + * no time out will be applied */ - [[deprecated("Use list constructor instead. If you need to make a decision before adding new commands, use Branch (https://github.com/RIT-VEX-U/Core/wiki/3-%7C-Utilites#commandcontroller)")]] void add(std::vector cmds); + [[deprecated("Use list constructor instead. If you need to make a decision " + "before adding new commands, use Branch " + "(https://github.com/RIT-VEX-U/Core/wiki/" + "3-%7C-Utilites#commandcontroller)")]] void + add(std::vector cmds); void add(AutoCommand *cmd, double timeout_seconds = 10.0); /** @@ -37,9 +46,13 @@ class CommandController /** * Add multiple commands to the queue. No timeout here. * @param cmds the AutoCommands we want to add to our list - * @param timeout_sec timeout in seconds to apply to all commands if they are still the default + * @param timeout_sec timeout in seconds to apply to all commands if they + * are still the default */ - [[deprecated("Use list constructor instead. If you need to make a decision before adding new commands, use Branch (https://github.com/RIT-VEX-U/Core/wiki/3-%7C-Utilites#commandcontroller)")]] void + [[deprecated("Use list constructor instead. If you need to make a decision " + "before adding new commands, use Branch " + "(https://github.com/RIT-VEX-U/Core/wiki/" + "3-%7C-Utilites#commandcontroller)")]] void add(std::vector cmds, double timeout_sec); /** * Adds a command that will delay progression @@ -49,8 +62,10 @@ class CommandController */ void add_delay(int ms); - /// @brief add_cancel_func specifies that when this func evaluates to true, to cancel the command controller - /// @param true_if_cancel a function that returns true when we want to cancel the command controller + /// @brief add_cancel_func specifies that when this func evaluates to true, + /// to cancel the command controller + /// @param true_if_cancel a function that returns true when we want to + /// cancel the command controller void add_cancel_func(std::function true_if_cancel); /** @@ -61,14 +76,15 @@ class CommandController /** * last_command_timed_out tells how the last command ended - * Use this if you want to make decisions based on the end of the last command - * @return true if the last command timed out. false if it finished regularly + * Use this if you want to make decisions based on the end of the last + * command + * @return true if the last command timed out. false if it finished + * regularly */ bool last_command_timed_out(); private: std::queue command_queue; bool command_timed_out = false; - std::function should_cancel = []() - { return false; }; + std::function should_cancel = []() { return false; }; }; \ No newline at end of file diff --git a/include/utils/command_structure/delay_command.h b/include/utils/command_structure/delay_command.h index c82b9bd..fe824c2 100644 --- a/include/utils/command_structure/delay_command.h +++ b/include/utils/command_structure/delay_command.h @@ -9,25 +9,25 @@ #include "../core/include/utils/command_structure/auto_command.h" -class DelayCommand: public AutoCommand { - public: - /** - * Construct a delay command - * @param ms the number of milliseconds to delay for - */ - DelayCommand(int ms): ms(ms) {} - - /** - * Delays for the amount of milliseconds stored in the command - * Overrides run from AutoCommand - * @returns true when complete - */ - bool run() override { - vexDelay(ms); - return true; - } +class DelayCommand : public AutoCommand { +public: + /** + * Construct a delay command + * @param ms the number of milliseconds to delay for + */ + DelayCommand(int ms) : ms(ms) {} - private: - // amount of milliseconds to wait - int ms; + /** + * Delays for the amount of milliseconds stored in the command + * Overrides run from AutoCommand + * @returns true when complete + */ + bool run() override { + vexDelay(ms); + return true; + } + +private: + // amount of milliseconds to wait + int ms; }; \ No newline at end of file diff --git a/include/utils/command_structure/drive_commands.h b/include/utils/command_structure/drive_commands.h index ee590fb..74c0dbc 100644 --- a/include/utils/command_structure/drive_commands.h +++ b/include/utils/command_structure/drive_commands.h @@ -2,7 +2,7 @@ * File: drive_commands.h * Desc: * Holds all the AutoCommand subclasses that wrap (currently) TankDrive functions - * + * * Currently includes: * - drive_forward * - turn_degrees @@ -18,243 +18,235 @@ #pragma once -#include "vex.h" -#include "../core/include/utils/geometry.h" -#include "../core/include/utils/command_structure/auto_command.h" #include "../core/include/subsystems/tank_drive.h" +#include "../core/include/utils/command_structure/auto_command.h" +#include "../core/include/utils/geometry.h" +#include "vex.h" using namespace vex; - // ==== DRIVING ==== /** - * AutoCommand wrapper class for the drive_forward function in the + * AutoCommand wrapper class for the drive_forward function in the * TankDrive class * */ -class DriveForwardCommand: public AutoCommand -{ - public: - DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed=1, double end_speed=0); - - /** - * Run drive_forward - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - /** - * Cleans up drive system if we time out before finishing - */ - void on_timeout() override; - - private: - // drive system to run the function on - TankDrive &drive_sys; - - // feedback controller to use - Feedback &feedback; - - // parameters for drive_forward - double inches; - directionType dir; - double max_speed; - double end_speed; +class DriveForwardCommand : public AutoCommand { +public: + DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed = 1, + double end_speed = 0); + + /** + * Run drive_forward + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + /** + * Cleans up drive system if we time out before finishing + */ + void on_timeout() override; + +private: + // drive system to run the function on + TankDrive &drive_sys; + + // feedback controller to use + Feedback &feedback; + + // parameters for drive_forward + double inches; + directionType dir; + double max_speed; + double end_speed; }; /** - * AutoCommand wrapper class for the turn_degrees function in the + * AutoCommand wrapper class for the turn_degrees function in the * TankDrive class */ -class TurnDegreesCommand: public AutoCommand -{ - public: - TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed = 1, double end_speed = 0); - - /** - * Run turn_degrees - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - /** - * Cleans up drive system if we time out before finishing - */ - void on_timeout() override; - - - private: - // drive system to run the function on - TankDrive &drive_sys; - - // feedback controller to use - Feedback &feedback; - - // parameters for turn_degrees - double degrees; - double max_speed; - double end_speed; +class TurnDegreesCommand : public AutoCommand { +public: + TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed = 1, + double end_speed = 0); + + /** + * Run turn_degrees + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + /** + * Cleans up drive system if we time out before finishing + */ + void on_timeout() override; + +private: + // drive system to run the function on + TankDrive &drive_sys; + + // feedback controller to use + Feedback &feedback; + + // parameters for turn_degrees + double degrees; + double max_speed; + double end_speed; }; /** * AutoCommand wrapper class for the drive_to_point function in the * TankDrive class */ -class DriveToPointCommand: public AutoCommand -{ - public: - DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed = 1, double end_speed = 0); - DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, point_t point, directionType dir, double max_speed=1, double end_speed = 0); - - /** - * Run drive_to_point - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // drive system to run the function on - TankDrive &drive_sys; - - /** - * Cleans up drive system if we time out before finishing - */ - void on_timeout() override; - - - // feedback controller to use - Feedback &feedback; - - // parameters for drive_to_point - double x; - double y; - directionType dir; - double max_speed; - double end_speed; - +class DriveToPointCommand : public AutoCommand { +public: + DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, + double max_speed = 1, double end_speed = 0); + DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, point_t point, directionType dir, double max_speed = 1, + double end_speed = 0); + + /** + * Run drive_to_point + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + +private: + // drive system to run the function on + TankDrive &drive_sys; + + /** + * Cleans up drive system if we time out before finishing + */ + void on_timeout() override; + + // feedback controller to use + Feedback &feedback; + + // parameters for drive_to_point + double x; + double y; + directionType dir; + double max_speed; + double end_speed; }; /** - * AutoCommand wrapper class for the turn_to_heading() function in the + * AutoCommand wrapper class for the turn_to_heading() function in the * TankDrive class * */ -class TurnToHeadingCommand: public AutoCommand -{ - public: - TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed = 1, double end_speed = 0); - - /** - * Run turn_to_heading - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - /** - * Cleans up drive system if we time out before finishing - */ - void on_timeout() override; - - - private: - // drive system to run the function on - TankDrive &drive_sys; - - // feedback controller to use - Feedback &feedback; - - // parameters for turn_to_heading - double heading_deg; - double max_speed; - double end_speed; +class TurnToHeadingCommand : public AutoCommand { +public: + TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double speed = 1, + double end_speed = 0); + + /** + * Run turn_to_heading + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + /** + * Cleans up drive system if we time out before finishing + */ + void on_timeout() override; + +private: + // drive system to run the function on + TankDrive &drive_sys; + + // feedback controller to use + Feedback &feedback; + + // parameters for turn_to_heading + double heading_deg; + double max_speed; + double end_speed; }; /** * Autocommand wrapper class for pure pursuit function in the TankDrive class -*/ -class PurePursuitCommand: public AutoCommand -{ - public: + */ +class PurePursuitCommand : public AutoCommand { +public: /** * Construct a Pure Pursuit AutoCommand - * + * * @param path The list of coordinates to follow, in order * @param dir Run the bot forwards or backwards * @param feedback The feedback controller determining speed * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) - */ - PurePursuitCommand(TankDrive &drive_sys, Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed=1, double end_speed=0); + */ + PurePursuitCommand(TankDrive &drive_sys, Feedback &feedback, PurePursuit::Path path, directionType dir, + double max_speed = 1, double end_speed = 0); /** * Direct call to TankDrive::pure_pursuit - */ + */ bool run() override; /** * Reset the drive system when it times out - */ + */ void on_timeout() override; - private: +private: TankDrive &drive_sys; PurePursuit::Path path; directionType dir; Feedback &feedback; double max_speed; double end_speed; - }; /** - * AutoCommand wrapper class for the stop() function in the + * AutoCommand wrapper class for the stop() function in the * TankDrive class */ -class DriveStopCommand: public AutoCommand -{ - public: - DriveStopCommand(TankDrive &drive_sys); - - /** - * Stop the drive system - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - void on_timeout() override; - - private: - // drive system to run the function on - TankDrive &drive_sys; -}; +class DriveStopCommand : public AutoCommand { +public: + DriveStopCommand(TankDrive &drive_sys); + + /** + * Stop the drive system + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + void on_timeout() override; +private: + // drive system to run the function on + TankDrive &drive_sys; +}; // ==== ODOMETRY ==== /** - * AutoCommand wrapper class for the set_position function in the + * AutoCommand wrapper class for the set_position function in the * Odometry class */ -class OdomSetPosition: public AutoCommand -{ - public: - /** - * constructs a new OdomSetPosition command - * @param odom the odometry system we are setting - * @param newpos the position we are telling the odometry to take. defaults to (0, 0), angle = 90 - */ - OdomSetPosition(OdometryBase &odom, const pose_t &newpos=OdometryBase::zero_pos); - - /** - * Run set_position - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // drive system with an odometry config - OdometryBase &odom; - pose_t newpos; +class OdomSetPosition : public AutoCommand { +public: + /** + * constructs a new OdomSetPosition command + * @param odom the odometry system we are setting + * @param newpos the position we are telling the odometry to take. defaults to (0, 0), angle = 90 + */ + OdomSetPosition(OdometryBase &odom, const pose_t &newpos = OdometryBase::zero_pos); + + /** + * Run set_position + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + +private: + // drive system with an odometry config + OdometryBase &odom; + pose_t newpos; }; diff --git a/include/utils/command_structure/flywheel_commands.h b/include/utils/command_structure/flywheel_commands.h index 04bf8f5..dc3490c 100644 --- a/include/utils/command_structure/flywheel_commands.h +++ b/include/utils/command_structure/flywheel_commands.h @@ -14,56 +14,56 @@ * in the Flywheel class * */ -class SpinRPMCommand: public AutoCommand { - public: +class SpinRPMCommand : public AutoCommand { +public: /** * Construct a SpinRPM Command * @param flywheel the flywheel sys to command * @param rpm the rpm that we should spin at - */ + */ SpinRPMCommand(Flywheel &flywheel, int rpm); - /** - * Run spin_manual - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // Flywheel instance to run the function on - Flywheel &flywheel; - - // parameters for spin_rpm - int rpm; + /** + * Run spin_manual + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + +private: + // Flywheel instance to run the function on + Flywheel &flywheel; + + // parameters for spin_rpm + int rpm; }; /** * AutoCommand that listens to the Flywheel and waits until it is at its target speed +/- the specified threshold * */ -class WaitUntilUpToSpeedCommand: public AutoCommand { - public: - /** - * Creat a WaitUntilUpToSpeedCommand - * @param flywheel the flywheel system we are commanding - * @param threshold_rpm the threshold over and under the flywheel target RPM that we define to be acceptable - */ - WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshold_rpm); - - /** - * Run spin_manual - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // Flywheel instance to run the function on - Flywheel &flywheel; - - // if the actual speed is equal to the desired speed +/- this value, we are ready to fire - int threshold_rpm; +class WaitUntilUpToSpeedCommand : public AutoCommand { +public: + /** + * Creat a WaitUntilUpToSpeedCommand + * @param flywheel the flywheel system we are commanding + * @param threshold_rpm the threshold over and under the flywheel target RPM that we define to be acceptable + */ + WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshold_rpm); + + /** + * Run spin_manual + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + +private: + // Flywheel instance to run the function on + Flywheel &flywheel; + + // if the actual speed is equal to the desired speed +/- this value, we are ready to fire + int threshold_rpm; }; /** @@ -71,24 +71,24 @@ class WaitUntilUpToSpeedCommand: public AutoCommand { * in the Flywheel class * */ -class FlywheelStopCommand: public AutoCommand { - public: +class FlywheelStopCommand : public AutoCommand { +public: /** * Construct a FlywheelStopCommand * @param flywheel the flywheel system we are commanding - */ + */ FlywheelStopCommand(Flywheel &flywheel); - /** - * Run stop - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // Flywheel instance to run the function on - Flywheel &flywheel; + /** + * Run stop + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + +private: + // Flywheel instance to run the function on + Flywheel &flywheel; }; /** @@ -96,24 +96,24 @@ class FlywheelStopCommand: public AutoCommand { * in the Flywheel class * */ -class FlywheelStopMotorsCommand: public AutoCommand { - public: +class FlywheelStopMotorsCommand : public AutoCommand { +public: /** * Construct a FlywheeStopMotors Command * @param flywheel the flywheel system we are commanding - */ + */ FlywheelStopMotorsCommand(Flywheel &flywheel); - /** - * Run stop - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // Flywheel instance to run the function on - Flywheel &flywheel; + /** + * Run stop + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + +private: + // Flywheel instance to run the function on + Flywheel &flywheel; }; /** @@ -121,17 +121,17 @@ class FlywheelStopMotorsCommand: public AutoCommand { * in the Flywheel class * */ -class FlywheelStopNonTasksCommand: public AutoCommand { +class FlywheelStopNonTasksCommand : public AutoCommand { FlywheelStopNonTasksCommand(Flywheel &flywheel); - /** - * Run stop - * Overrides run from AutoCommand - * @returns true when execution is complete, false otherwise - */ - bool run() override; - - private: - // Flywheel instance to run the function on - Flywheel &flywheel; + /** + * Run stop + * Overrides run from AutoCommand + * @returns true when execution is complete, false otherwise + */ + bool run() override; + +private: + // Flywheel instance to run the function on + Flywheel &flywheel; }; diff --git a/include/utils/controls/bang_bang.h b/include/utils/controls/bang_bang.h index aeba17d..d034728 100644 --- a/include/utils/controls/bang_bang.h +++ b/include/utils/controls/bang_bang.h @@ -1,50 +1,50 @@ #include "../core/include/utils/controls/feedback_base.h" -class BangBang : public Feedback -{ +class BangBang : public Feedback { public: - BangBang(double thresshold, double low, double high); - /** - * Initialize the feedback controller for a movement - * - * @param start_pt the current sensor value - * @param set_pt where the sensor value should be - * @param start_vel Movement starting velocity - * @param end_vel Movement ending velocity - */ - void init(double start_pt, double set_pt, double start_vel [[maybe_unused]] = 0.0, double end_vel [[maybe_unused]] = 0.0) override; + BangBang(double thresshold, double low, double high); + /** + * Initialize the feedback controller for a movement + * + * @param start_pt the current sensor value + * @param set_pt where the sensor value should be + * @param start_vel Movement starting velocity + * @param end_vel Movement ending velocity + */ + void init(double start_pt, double set_pt, double start_vel [[maybe_unused]] = 0.0, + double end_vel [[maybe_unused]] = 0.0) override; - /** - * Iterate the feedback loop once with an updated sensor value - * - * @param val value from the sensor - * @return feedback loop result - */ - double update(double val) override; + /** + * Iterate the feedback loop once with an updated sensor value + * + * @param val value from the sensor + * @return feedback loop result + */ + double update(double val) override; - /** - * @return the last saved result from the feedback controller - */ - double get() override; + /** + * @return the last saved result from the feedback controller + */ + double get() override; - /** - * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. - * - * @param lower Upper limit - * @param upper Lower limit - */ - void set_limits(double lower, double upper) override; + /** + * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * + * @param lower Upper limit + * @param upper Lower limit + */ + void set_limits(double lower, double upper) override; - /** - * @return true if the feedback controller has reached it's setpoint - */ - bool is_on_target() override; + /** + * @return true if the feedback controller has reached it's setpoint + */ + bool is_on_target() override; private: - double setpt; - double sensor_val; - double lower_bound, upper_bound; - double last_output; - double threshhold; + double setpt; + double sensor_val; + double lower_bound, upper_bound; + double last_output; + double threshhold; }; diff --git a/include/utils/controls/feedback_base.h b/include/utils/controls/feedback_base.h index 9b9c625..c1baac1 100644 --- a/include/utils/controls/feedback_base.h +++ b/include/utils/controls/feedback_base.h @@ -7,44 +7,41 @@ * @date 9/25/2022 * */ -class Feedback -{ +class Feedback { public: - /** - * Initialize the feedback controller for a movement - * - * @param start_pt the current sensor value - * @param set_pt where the sensor value should be - * @param start_vel Movement starting velocity - * @param end_vel Movement ending velocity - */ - virtual void init(double start_pt, double set_pt, double start_vel = 0.0, double end_vel = 0.0) = 0; + /** + * Initialize the feedback controller for a movement + * + * @param start_pt the current sensor value + * @param set_pt where the sensor value should be + * @param start_vel Movement starting velocity + * @param end_vel Movement ending velocity + */ + virtual void init(double start_pt, double set_pt, double start_vel = 0.0, double end_vel = 0.0) = 0; - /** - * Iterate the feedback loop once with an updated sensor value - * - * @param val value from the sensor - * @return feedback loop result - */ - virtual double update(double val) = 0; + /** + * Iterate the feedback loop once with an updated sensor value + * + * @param val value from the sensor + * @return feedback loop result + */ + virtual double update(double val) = 0; - /** - * @return the last saved result from the feedback controller - */ - virtual double get() = 0; - - /** - * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. - * - * @param lower Upper limit - * @param upper Lower limit - */ - virtual void set_limits(double lower, double upper) = 0; - - /** - * @return true if the feedback controller has reached it's setpoint - */ - virtual bool is_on_target() = 0; + /** + * @return the last saved result from the feedback controller + */ + virtual double get() = 0; + /** + * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * + * @param lower Upper limit + * @param upper Lower limit + */ + virtual void set_limits(double lower, double upper) = 0; + /** + * @return true if the feedback controller has reached it's setpoint + */ + virtual bool is_on_target() = 0; }; \ No newline at end of file diff --git a/include/utils/controls/feedforward.h b/include/utils/controls/feedforward.h index c6700e7..f10b359 100644 --- a/include/utils/controls/feedforward.h +++ b/include/utils/controls/feedforward.h @@ -1,90 +1,85 @@ #pragma once -#include -#include #include "../core/include/utils/math_util.h" #include "../core/include/utils/moving_average.h" #include "vex.h" +#include +#include /** * FeedForward - * + * * Stores the feedfoward constants, and allows for quick computation. * Feedfoward should be used in systems that require smooth precise movements * and have high inertia, such as drivetrains and lifts. - * + * * This is best used alongside a PID loop, with the form: * output = pid.get() + feedforward.calculate(v, a); - * - * In this case, the feedforward does the majority of the heavy lifting, and the + * + * In this case, the feedforward does the majority of the heavy lifting, and the * pid loop only corrects for inconsistencies - * + * * For information about tuning feedforward, I reccommend looking at this post: * https://www.chiefdelphi.com/t/paper-frc-drivetrain-characterization/160915 * (yes I know it's for FRC but trust me, it's useful) - * + * * @author Ryan McGee * @date 6/13/2022 */ -class FeedForward -{ - public: +class FeedForward { +public: + /** + * ff_config_t holds the parameters to make the theoretical model of a real world system + * equation is of the form + * kS if the system is not stopped, 0 otherwise + * + kV * desired velocity + * + kA * desired acceleration + * + kG + */ + typedef struct { + double kS; /**< Coefficient to overcome static friction: the point at which the motor *starts* to move.*/ + double kV; /**< Veclocity coefficient: the power required to keep the mechanism in motion. Multiplied by the + requested velocity.*/ + double kA; /**< kA - Acceleration coefficient: the power required to change the mechanism's speed. Multiplied by the + requested acceleration.*/ + double kG; /**< kG - Gravity coefficient: only needed for lifts. The power required to overcome gravity and stay at + steady state.*/ + } ff_config_t; - /** - * ff_config_t holds the parameters to make the theoretical model of a real world system - * equation is of the form - * kS if the system is not stopped, 0 otherwise - * + kV * desired velocity - * + kA * desired acceleration - * + kG - */ - typedef struct - { - double kS; /**< Coefficient to overcome static friction: the point at which the motor *starts* to move.*/ - double kV; /**< Veclocity coefficient: the power required to keep the mechanism in motion. Multiplied by the requested velocity.*/ - double kA; /**< kA - Acceleration coefficient: the power required to change the mechanism's speed. Multiplied by the requested acceleration.*/ - double kG; /**< kG - Gravity coefficient: only needed for lifts. The power required to overcome gravity and stay at steady state.*/ - } ff_config_t; + /** + * Creates a FeedForward object. + * @param cfg Configuration Struct for tuning + */ + FeedForward(ff_config_t &cfg) : cfg(cfg) {} - - /** - * Creates a FeedForward object. - * @param cfg Configuration Struct for tuning - */ - FeedForward(ff_config_t &cfg) : cfg(cfg) {} + /** + * @brief Perform the feedforward calculation + * + * This calculation is the equation: + * F = kG + kS*sgn(v) + kV*v + kA*a + * + * @param v Requested velocity of system + * @param a Requested acceleration of system + * @return A feedforward that should closely represent the system if tuned correctly + */ + double calculate(double v, double a, double pid_ref = 0.0) { + double ks_sign = 0; + if (v != 0) + ks_sign = sign(v); + else if (pid_ref != 0) + ks_sign = sign(pid_ref); - /** - * @brief Perform the feedforward calculation - * - * This calculation is the equation: - * F = kG + kS*sgn(v) + kV*v + kA*a - * - * @param v Requested velocity of system - * @param a Requested acceleration of system - * @return A feedforward that should closely represent the system if tuned correctly - */ - double calculate(double v, double a, double pid_ref=0.0) - { - double ks_sign = 0; - if(v != 0) - ks_sign = sign(v); - else if(pid_ref != 0) - ks_sign = sign(pid_ref); - - return (cfg.kS * ks_sign) + (cfg.kV * v) + (cfg.kA * a) + cfg.kG; - } - - private: - - ff_config_t &cfg; + return (cfg.kS * ks_sign) + (cfg.kV * v) + (cfg.kA * a) + cfg.kG; + } +private: + ff_config_t &cfg; }; - /** -* tune_feedforward takes a group of motors and finds the feedforward conifg parameters automagically. -* @param motor the motor group to use -* @param pct Maximum velocity in percent (0->1.0) + * tune_feedforward takes a group of motors and finds the feedforward conifg parameters automagically. + * @param motor the motor group to use + * @param pct Maximum velocity in percent (0->1.0) * @param duration Amount of time the motors spin for the test * @return A tuned feedforward object */ diff --git a/include/utils/controls/motion_controller.h b/include/utils/controls/motion_controller.h index 86b3cde..539c27c 100644 --- a/include/utils/controls/motion_controller.h +++ b/include/utils/controls/motion_controller.h @@ -1,135 +1,131 @@ #pragma once -#include "../core/include/utils/controls/pid.h" +#include "../core/include/subsystems/screen.h" +#include "../core/include/subsystems/tank_drive.h" +#include "../core/include/utils/controls/feedback_base.h" #include "../core/include/utils/controls/feedforward.h" +#include "../core/include/utils/controls/pid.h" #include "../core/include/utils/controls/trapezoid_profile.h" -#include "../core/include/utils/controls/feedback_base.h" -#include "../core/include/subsystems/tank_drive.h" -#include "../core/include/subsystems/screen.h" #include "vex.h" /** * Motion Controller class - * + * * This class defines a top-level motion profile, which can act as an intermediate between * a subsystem class and the motors themselves * - * This takes the constants kS, kV, kA, kP, kI, kD, max_v and acceleration and wraps around + * This takes the constants kS, kV, kA, kP, kI, kD, max_v and acceleration and wraps around * a feedforward, PID and trapezoid profile. It does so with the following formula: - * + * * out = feedfoward.calculate(motion_profile.get(time_s)) + pid.get(motion_profile.get(time_s)) - * + * * For PID and Feedforward specific formulae, see pid.h, feedforward.h, and trapezoid_profile.h - * + * * @author Ryan McGee * @date 7/13/2022 */ -class MotionController : public Feedback -{ - public: - - /** - * m_profile_config holds all data the motion controller uses to plan paths - * When motion pofile is given a target to drive to, max_v and accel are used to make the trapezoid profile instructing the controller how to drive - * pid_cfg, ff_cfg are used to find the motor outputs necessary to execute this path - */ - typedef struct - { - double max_v; ///< the maximum velocity the robot can drive - double accel; ///< the most acceleration the robot can do - PID::pid_config_t pid_cfg; ///< configuration parameters for the internal PID controller - FeedForward::ff_config_t ff_cfg; ///< configuration parameters for the internal - } m_profile_cfg_t; - - /** - * @brief Construct a new Motion Controller object - * - * @param config The definition of how the robot is able to move - * max_v Maximum velocity the movement is capable of - * accel Acceleration / deceleration of the movement - * pid_cfg Definitions of kP, kI, and kD - * ff_cfg Definitions of kS, kV, and kA - */ - MotionController(m_profile_cfg_t &config); - - /** - * @brief Initialize the motion profile for a new movement - * This will also reset the PID and profile timers. - */ - void init(double start_pt, double end_pt, double start_vel, double end_vel) override; - - /** - * @brief Update the motion profile with a new sensor value - * - * @param sensor_val Value from the sensor - * @return the motor input generated from the motion profile - */ - double update(double sensor_val) override; - - /** - * @return the last saved result from the feedback controller - */ - double get() override; - - /** - * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. - * if limits are applied, the controller will not target any value below lower or above upper - * - * @param lower upper limit - * @param upper lower limiet - */ - void set_limits(double lower, double upper) override; - - /** - * @return Whether or not the movement has finished, and the PID - * confirms it is on target - */ - bool is_on_target() override; - - /** - * @return The current postion, velocity and acceleration setpoints - */ - motion_t get_motion() const; - - - screen::Page *Page(); - - /** - * This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. - * It does this by first calculating the kS (voltage to overcome static friction) by slowly increasing - * the voltage until it moves. - * - * Next is kV (voltage to sustain a certain velocity), where the robot will record it's steady-state velocity - * at 'pct' speed. - * - * Finally, kA (voltage needed to accelerate by a certain rate), where the robot will record the entire movement's - * velocity and acceleration, record a plot of [X=(pct-kV*V-kS), Y=(Acceleration)] along the movement, - * and since kA*Accel = pct-kV*V-kS, the reciprocal of the linear regression is the kA value. - * - * @param drive The tankdrive to operate on - * @param odometry The robot's odometry subsystem - * @param pct Maximum velocity in percent (0->1.0) - * @param duration Amount of time the robot should be moving for the test - * @return A tuned feedforward object - */ - static FeedForward::ff_config_t tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct=0.6, double duration=2); - - private: - - m_profile_cfg_t config; - - PID pid; - FeedForward ff; - TrapezoidProfile profile; - - double current_pos; - double end_pt; - - double lower_limit = 0, upper_limit = 0; - double out = 0; - motion_t cur_motion; - - vex::timer tmr; - friend class MotionControllerPage; - +class MotionController : public Feedback { +public: + /** + * m_profile_config holds all data the motion controller uses to plan paths + * When motion pofile is given a target to drive to, max_v and accel are used to make the trapezoid profile + * instructing the controller how to drive pid_cfg, ff_cfg are used to find the motor outputs necessary to execute + * this path + */ + typedef struct { + double max_v; ///< the maximum velocity the robot can drive + double accel; ///< the most acceleration the robot can do + PID::pid_config_t pid_cfg; ///< configuration parameters for the internal PID controller + FeedForward::ff_config_t ff_cfg; ///< configuration parameters for the internal + } m_profile_cfg_t; + + /** + * @brief Construct a new Motion Controller object + * + * @param config The definition of how the robot is able to move + * max_v Maximum velocity the movement is capable of + * accel Acceleration / deceleration of the movement + * pid_cfg Definitions of kP, kI, and kD + * ff_cfg Definitions of kS, kV, and kA + */ + MotionController(m_profile_cfg_t &config); + + /** + * @brief Initialize the motion profile for a new movement + * This will also reset the PID and profile timers. + */ + void init(double start_pt, double end_pt, double start_vel, double end_vel) override; + + /** + * @brief Update the motion profile with a new sensor value + * + * @param sensor_val Value from the sensor + * @return the motor input generated from the motion profile + */ + double update(double sensor_val) override; + + /** + * @return the last saved result from the feedback controller + */ + double get() override; + + /** + * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * if limits are applied, the controller will not target any value below lower or above upper + * + * @param lower upper limit + * @param upper lower limiet + */ + void set_limits(double lower, double upper) override; + + /** + * @return Whether or not the movement has finished, and the PID + * confirms it is on target + */ + bool is_on_target() override; + + /** + * @return The current postion, velocity and acceleration setpoints + */ + motion_t get_motion() const; + + screen::Page *Page(); + + /** + * This method attempts to characterize the robot's drivetrain and automatically tune the feedforward. + * It does this by first calculating the kS (voltage to overcome static friction) by slowly increasing + * the voltage until it moves. + * + * Next is kV (voltage to sustain a certain velocity), where the robot will record it's steady-state velocity + * at 'pct' speed. + * + * Finally, kA (voltage needed to accelerate by a certain rate), where the robot will record the entire movement's + * velocity and acceleration, record a plot of [X=(pct-kV*V-kS), Y=(Acceleration)] along the movement, + * and since kA*Accel = pct-kV*V-kS, the reciprocal of the linear regression is the kA value. + * + * @param drive The tankdrive to operate on + * @param odometry The robot's odometry subsystem + * @param pct Maximum velocity in percent (0->1.0) + * @param duration Amount of time the robot should be moving for the test + * @return A tuned feedforward object + */ + static FeedForward::ff_config_t tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct = 0.6, + double duration = 2); + +private: + m_profile_cfg_t config; + + PID pid; + FeedForward ff; + TrapezoidProfile profile; + + double current_pos; + double end_pt; + + double lower_limit = 0, upper_limit = 0; + double out = 0; + motion_t cur_motion; + + vex::timer tmr; + friend class MotionControllerPage; }; \ No newline at end of file diff --git a/include/utils/controls/pid.h b/include/utils/controls/pid.h index 102bc8a..4bf7951 100644 --- a/include/utils/controls/pid.h +++ b/include/utils/controls/pid.h @@ -41,12 +41,12 @@ class PID : public Feedback { * an angle */ struct pid_config_t { - double p; ///< proportional coeffecient p * error() - double i; ///< integral coeffecient i * integral(error) - double d; ///< derivitave coeffecient d * derivative(error) - double deadband; ///< at what threshold are we close enough to be finished - double on_target_time; ///< the time in seconds that we have to be on target - ///< for to say we are officially at the target + double p; ///< proportional coeffecient p * error() + double i; ///< integral coeffecient i * integral(error) + double d; ///< derivitave coeffecient d * derivative(error) + double deadband; ///< at what threshold are we close enough to be finished + double on_target_time; ///< the time in seconds that we have to be on target + ///< for to say we are officially at the target ERROR_TYPE error_method; ///< Linear or angular. wheter to do error as a ///< simple subtraction or to wrap }; @@ -69,8 +69,7 @@ class PID : public Feedback { * base * @param end_vel sets the target end velocity of the PID controller */ - void init(double start_pt, double set_pt, double start_vel = 0, - double end_vel = 0) override; + void init(double start_pt, double set_pt, double start_vel = 0, double end_vel = 0) override; /** * Update the PID loop by taking the time difference from last update, @@ -134,37 +133,30 @@ class PID : public Feedback { */ void set_target(double target); - pid_config_t - &config; ///< configuration struct for this controller. see pid_config_t - ///< for information about what this contains + pid_config_t &config; ///< configuration struct for this controller. see pid_config_t + ///< for information about what this contains private: - double last_error = - 0; ///< the error measured on the last iteration of update() - double accum_error = - 0; ///< the integral of error over time since we called init() - - double last_time = 0; ///< the time measured the last time update() was called - double on_target_last_time = - 0; ///< the time at which we started being on target - - double lower_limit = - 0; ///< the PID controller will never set a target to go lower than this - double upper_limit = - 0; ///< the PID controller will never set a target to go higher than this - - double target = 0; ///< the target position of the PID controller (lower_limit - ///< <= target <= upper_limit) + double last_error = 0; ///< the error measured on the last iteration of update() + double accum_error = 0; ///< the integral of error over time since we called init() + + double last_time = 0; ///< the time measured the last time update() was called + double on_target_last_time = 0; ///< the time at which we started being on target + + double lower_limit = 0; ///< the PID controller will never set a target to go lower than this + double upper_limit = 0; ///< the PID controller will never set a target to go higher than this + + double target = 0; ///< the target position of the PID controller (lower_limit + ///< <= target <= upper_limit) double target_vel = 0; ///< the target velocity of the PID controller (if != ///< 0, controller will not wait for stop) double sensor_val = 0; ///< the last recorded value of the sensor we use to ///< feed the PID controller - double out = 0; ///< the last calculated output value. we save it here so that - ///< we don't have to recalculate if we ask for it more than - ///< once between update() calls + double out = 0; ///< the last calculated output value. we save it here so that + ///< we don't have to recalculate if we ask for it more than + ///< once between update() calls - bool is_checking_on_target = - false; ///< true if the sensor reading is within target +/- deadband + bool is_checking_on_target = false; ///< true if the sensor reading is within target +/- deadband timer pid_timer; ///< used for calculating integrals and derivatives in line ///< with the real world times and checking the time we are diff --git a/include/utils/controls/pidff.h b/include/utils/controls/pidff.h index 243f81b..4c6a0e5 100644 --- a/include/utils/controls/pidff.h +++ b/include/utils/controls/pidff.h @@ -15,8 +15,7 @@ class PIDFF : public Feedback { * @param start_vel the current rate of change of the sensor value * @param end_vel the desired ending rate of change of the sensor value */ - void init(double start_pt, double set_pt, double start_vel, - double end_vel) override; + void init(double start_pt, double set_pt, double start_vel, double end_vel) override; /** * Set the target of the PID loop diff --git a/include/utils/controls/take_back_half.h b/include/utils/controls/take_back_half.h index 692660f..b0383c8 100644 --- a/include/utils/controls/take_back_half.h +++ b/include/utils/controls/take_back_half.h @@ -3,57 +3,57 @@ /// @brief A velocity controller /// @warning If you try to use this as a position controller, it will fail. -class TakeBackHalf : public Feedback -{ +class TakeBackHalf : public Feedback { public: - TakeBackHalf(double TBH_gain, double first_cross_split, double on_target_threshold); - /** - * Initialize the feedback controller for a movement - * - * @param start_pt the current sensor value - * @param set_pt where the sensor value should be - * @param start_vel Movement starting velocity (IGNORED) - * @param end_vel Movement ending velocity (IGNORED) - */ - void init(double start_pt, double set_pt, double, double); - /** - * Iterate the feedback loop once with an updated sensor value - * - * @param val value from the sensor - * @return feedback loop result - */ - double update(double val) override; - - /** - * @return the last saved result from the feedback controller - */ - double get() override; - - /** - * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. - * - * @param lower Upper limit - * @param upper Lower limit - */ - void set_limits(double lower, double upper) override; - - /** - * @return true if the feedback controller has reached it's setpoint - */ - bool is_on_target() override; - - double TBH_gain; ///< tuned parameter - double first_cross_split; + TakeBackHalf(double TBH_gain, double first_cross_split, double on_target_threshold); + /** + * Initialize the feedback controller for a movement + * + * @param start_pt the current sensor value + * @param set_pt where the sensor value should be + * @param start_vel Movement starting velocity (IGNORED) + * @param end_vel Movement ending velocity (IGNORED) + */ + void init(double start_pt, double set_pt, double, double); + /** + * Iterate the feedback loop once with an updated sensor value + * + * @param val value from the sensor + * @return feedback loop result + */ + double update(double val) override; + + /** + * @return the last saved result from the feedback controller + */ + double get() override; + + /** + * Clamp the upper and lower limits of the output. If both are 0, no limits should be applied. + * + * @param lower Upper limit + * @param upper Lower limit + */ + void set_limits(double lower, double upper) override; + + /** + * @return true if the feedback controller has reached it's setpoint + */ + bool is_on_target() override; + + double TBH_gain; ///< tuned parameter + double first_cross_split; + private: - double on_target_threshhold; ///< tuned parameter + double on_target_threshhold; ///< tuned parameter - double target = 0.0; + double target = 0.0; - bool first_cross = true; - double tbh = 0.0; - double prev_error = 0.0; + bool first_cross = true; + double tbh = 0.0; + double prev_error = 0.0; - double output = 0.0; - double lower = 0.0, upper = 0.0; ///< output limits + double output = 0.0; + double lower = 0.0, upper = 0.0; ///< output limits }; \ No newline at end of file diff --git a/include/utils/controls/trapezoid_profile.h b/include/utils/controls/trapezoid_profile.h index 6cd9cc2..5de8f7c 100644 --- a/include/utils/controls/trapezoid_profile.h +++ b/include/utils/controls/trapezoid_profile.h @@ -160,8 +160,7 @@ class TrapezoidProfile { * @return a trapezoid_profile_segment_t that represents constant acceleration * to the target velocity */ - trapezoid_profile_segment_t calculate_kinetic_motion(double si, double vi, - double v_target); + trapezoid_profile_segment_t calculate_kinetic_motion(double si, double vi, double v_target); /** * Calculate the next segment of the trapezoid motion profile diff --git a/include/utils/generic_auto.h b/include/utils/generic_auto.h index f03fd76..d59edd6 100644 --- a/include/utils/generic_auto.h +++ b/include/utils/generic_auto.h @@ -1,59 +1,51 @@ #pragma once -#include -#include #include "vex.h" #include +#include +#include typedef std::function state_ptr; /** * GenericAuto provides a pleasant interface for organizing an auto path * steps of the path can be added with add() and when ready, calling run() will begin executing the path -*/ -class GenericAuto -{ - public: - + */ +class GenericAuto { +public: /** - * The method that runs the autonomous. If 'blocking' is true, then - * this method will run through every state until it finished. - * - * If blocking is false, then assuming every state is also non-blocking, - * the method will run through the current state in the list and return - * immediately. - * - * @param blocking - * Whether or not to block the thread until all states have run - * @returns - * true after all states have finished. - */ - [[deprecated("Use CommandController instead.")]] - bool run(bool blocking); + * The method that runs the autonomous. If 'blocking' is true, then + * this method will run through every state until it finished. + * + * If blocking is false, then assuming every state is also non-blocking, + * the method will run through the current state in the list and return + * immediately. + * + * @param blocking + * Whether or not to block the thread until all states have run + * @returns + * true after all states have finished. + */ + [[deprecated("Use CommandController instead.")]] bool run(bool blocking); /** * Add a new state to the autonomous via function point of type "bool (ptr*)()" * @param new_state the function to run */ - [[deprecated("Use CommandController instead.")]] - void add(state_ptr new_state); + [[deprecated("Use CommandController instead.")]] void add(state_ptr new_state); /** * Add a new state to the autonomous via function point of type "bool (ptr*)()" that will run asynchronously * @param async_state the function to run */ - [[deprecated("Use CommandController instead.")]] - void add_async(state_ptr async_state); + [[deprecated("Use CommandController instead.")]] void add_async(state_ptr async_state); /** * add_delay adds a period where the auto system will simply wait for the specified time * @param ms how long to wait in milliseconds - */ - [[deprecated("Use CommandController instead.")]] - void add_delay(int ms); - - private: + */ + [[deprecated("Use CommandController instead.")]] void add_delay(int ms); +private: std::queue state_list; - }; diff --git a/include/utils/geometry.h b/include/utils/geometry.h index c6e18a9..b273626 100644 --- a/include/utils/geometry.h +++ b/include/utils/geometry.h @@ -4,132 +4,87 @@ /** * Data structure representing an X,Y coordinate */ -struct point_t -{ - double x; ///< the x position in space - double y; ///< the y position in space +struct point_t { + double x; ///< the x position in space + double y; ///< the y position in space - /** - * dist calculates the euclidian distance between this point and another point using the pythagorean theorem - * @param other the point to measure the distance from - * @return the euclidian distance between this and other - */ - double dist(const point_t other) const - { - return std::sqrt(std::pow(this->x - other.x, 2) + pow(this->y - other.y, 2)); - } + /** + * dist calculates the euclidian distance between this point and another point using the pythagorean theorem + * @param other the point to measure the distance from + * @return the euclidian distance between this and other + */ + double dist(const point_t other) const { + return std::sqrt(std::pow(this->x - other.x, 2) + pow(this->y - other.y, 2)); + } - /** - * Vector2D addition operation on points - * @param other the point to add on to this - * @return this + other (this.x + other.x, this.y + other.y) - */ - point_t operator+(const point_t &other) const - { - point_t p{ - .x = this->x + other.x, - .y = this->y + other.y}; - return p; - } + /** + * Vector2D addition operation on points + * @param other the point to add on to this + * @return this + other (this.x + other.x, this.y + other.y) + */ + point_t operator+(const point_t &other) const { + point_t p{.x = this->x + other.x, .y = this->y + other.y}; + return p; + } - /** - * Vector2D subtraction operation on points - * @param other the point_t to subtract from this - * @return this - other (this.x - other.x, this.y - other.y) - */ - point_t operator-(const point_t &other) const - { - point_t p{ - .x = this->x - other.x, - .y = this->y - other.y}; - return p; - } + /** + * Vector2D subtraction operation on points + * @param other the point_t to subtract from this + * @return this - other (this.x - other.x, this.y - other.y) + */ + point_t operator-(const point_t &other) const { + point_t p{.x = this->x - other.x, .y = this->y - other.y}; + return p; + } - point_t operator*(double s) const - { - return {x * s, y * s}; - } - point_t operator/(double s) const - { - return {x / s, y / s}; - } + point_t operator*(double s) const { return {x * s, y * s}; } + point_t operator/(double s) const { return {x / s, y / s}; } - point_t operator-() const - { - return {-x, -y}; - } - point_t operator+() const - { - return {x, y}; - } + point_t operator-() const { return {-x, -y}; } + point_t operator+() const { return {x, y}; } - bool operator==(const point_t &rhs) - { - return x == rhs.x && y == rhs.y; - } + bool operator==(const point_t &rhs) { return x == rhs.x && y == rhs.y; } }; /** * Describes a single position and rotation */ -struct pose_t -{ - double x; ///< x position in the world - double y; ///< y position in the world - double rot; ///< rotation in the world +struct pose_t { + double x; ///< x position in the world + double y; ///< y position in the world + double rot; ///< rotation in the world - point_t get_point() - { - return point_t{.x = x, .y = y}; - } - -} ; - -struct Rect -{ - point_t min; - point_t max; - static Rect from_min_and_size(point_t min, point_t size){ - return {min, min+size}; - } - point_t dimensions() const - { - return max - min; - } - point_t center() const{ - return (min + max)/2; - } - double width() const{ - return max.x - min.x; - } - double height() const{ - return max.y - min.y; - } - bool contains(point_t p) const - { - bool xin = p.x > min.x && p.x < max.x; - bool yin = p.y > min.y && p.y < max.y; - return xin && yin; - } + point_t get_point() { return point_t{.x = x, .y = y}; } +}; +struct Rect { + point_t min; + point_t max; + static Rect from_min_and_size(point_t min, point_t size) { return {min, min + size}; } + point_t dimensions() const { return max - min; } + point_t center() const { return (min + max) / 2; } + double width() const { return max.x - min.x; } + double height() const { return max.y - min.y; } + bool contains(point_t p) const { + bool xin = p.x > min.x && p.x < max.x; + bool yin = p.y > min.y && p.y < max.y; + return xin && yin; + } }; -struct Mat2 -{ - double X11, X12; - double X21, X22; - point_t operator*(const point_t p) const - { - double outx = p.x * X11 + p.y * X12; - double outy = p.x * X21 + p.y * X22; - return {outx, outy}; - } +struct Mat2 { + double X11, X12; + double X21, X22; + point_t operator*(const point_t p) const { + double outx = p.x * X11 + p.y * X12; + double outy = p.x * X21 + p.y * X22; + return {outx, outy}; + } - static Mat2 FromRotationDegrees(double degrees) - { - double rad = degrees * (M_PI / 180.0); - double c = cos(rad); - double s = sin(rad); - return {c, -s, s, c}; - } + static Mat2 FromRotationDegrees(double degrees) { + double rad = degrees * (M_PI / 180.0); + double c = cos(rad); + double s = sin(rad); + return {c, -s, s, c}; + } }; \ No newline at end of file diff --git a/include/utils/graph_drawer.h b/include/utils/graph_drawer.h index 9273389..c637f09 100644 --- a/include/utils/graph_drawer.h +++ b/include/utils/graph_drawer.h @@ -1,15 +1,14 @@ #pragma once -#include -#include -#include -#include -#include "vex.h" #include "../core/include/utils/geometry.h" #include "../core/include/utils/vector2d.h" +#include "vex.h" +#include +#include +#include +#include -class GraphDrawer -{ +class GraphDrawer { public: /// @brief Creates a graph drawer with the specified number of series (each series is a separate line) /// @param num_samples the number of samples to graph at a time (40 will graph the last 40 data points) @@ -17,7 +16,8 @@ class GraphDrawer /// @param upper_bound the top of the window when displaying (if upper_bound = lower_bound, auto calculate bounds) /// @param colors the colors of the series. must be of size num_series /// @param num_series the number of series to graph - GraphDrawer(int num_samples, double lower_bound, double upper_bound, std::vector colors, size_t num_series = 1); + GraphDrawer(int num_samples, double lower_bound, double upper_bound, std::vector colors, + size_t num_series = 1); /** * add_samples adds a point to the graph, removing one from the back * @param sample an x, y coordinate of the next point to graph @@ -26,7 +26,8 @@ class GraphDrawer /** * add_samples adds a point to the graph, removing one from the back - * @param sample a y coordinate of the next point to graph, the x coordinate is gotten from vex::timer::system(); (time in ms) + * @param sample a y coordinate of the next point to graph, the x coordinate is gotten from vex::timer::system(); + * (time in ms) */ void add_samples(std::vector sample); diff --git a/include/utils/logger.h b/include/utils/logger.h index 159baa6..696ea2a 100644 --- a/include/utils/logger.h +++ b/include/utils/logger.h @@ -1,68 +1,58 @@ #pragma once +#include "vex.h" #include #include #include -#include "vex.h" /// @brief possible values for log filtering -enum LogLevel -{ - DEBUG, - NOTICE, - WARNING, - ERROR, - CRITICAL, - TIME -}; +enum LogLevel { DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME }; /// @brief Class to simplify writing to files -class Logger -{ +class Logger { private: - const std::string filename; - vex::brain::sdcard sd; - void write_level(LogLevel l); + const std::string filename; + vex::brain::sdcard sd; + void write_level(LogLevel l); public: - /// @brief maximum size for a string to be before it's written - static constexpr int MAX_FORMAT_LEN = 512; - /// @brief Create a logger that will save to a file - /// @param filename the file to save to - explicit Logger(const std::string &filename); - - /// @brief copying not allowed - Logger(const Logger &l) = delete; - /// @brief copying not allowed - Logger &operator=(const Logger &l) = delete; - - - /// @brief Write a string to the log - /// @param s the string to write - void Log(const std::string &s); - - /// @brief Write a string to the log with a loglevel - /// @param level the level to write. DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME - /// @param s the string to write - void Log(LogLevel level, const std::string &s); - - /// @brief Write a string and newline to the log - /// @param s the string to write - void Logln(const std::string &s); - - /// @brief Write a string and a newline to the log with a loglevel - /// @param level the level to write. DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME - /// @param s the string to write - void Logln(LogLevel level, const std::string &s); - - /// @brief Write a formatted string to the log - /// @param fmt the format string (like printf) - /// @param ... the args - void Logf(const char *fmt, ...); - - /// @brief Write a formatted string to the log with a loglevel - /// @param level the level to write. DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME - /// @param fmt the format string (like printf) - /// @param ... the args - void Logf(LogLevel level, const char *fmt, ...); + /// @brief maximum size for a string to be before it's written + static constexpr int MAX_FORMAT_LEN = 512; + /// @brief Create a logger that will save to a file + /// @param filename the file to save to + explicit Logger(const std::string &filename); + + /// @brief copying not allowed + Logger(const Logger &l) = delete; + /// @brief copying not allowed + Logger &operator=(const Logger &l) = delete; + + /// @brief Write a string to the log + /// @param s the string to write + void Log(const std::string &s); + + /// @brief Write a string to the log with a loglevel + /// @param level the level to write. DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME + /// @param s the string to write + void Log(LogLevel level, const std::string &s); + + /// @brief Write a string and newline to the log + /// @param s the string to write + void Logln(const std::string &s); + + /// @brief Write a string and a newline to the log with a loglevel + /// @param level the level to write. DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME + /// @param s the string to write + void Logln(LogLevel level, const std::string &s); + + /// @brief Write a formatted string to the log + /// @param fmt the format string (like printf) + /// @param ... the args + void Logf(const char *fmt, ...); + + /// @brief Write a formatted string to the log with a loglevel + /// @param level the level to write. DEBUG, NOTICE, WARNING, ERROR, CRITICAL, TIME + /// @param fmt the format string (like printf) + /// @param ... the args + void Logf(LogLevel level, const char *fmt, ...); }; diff --git a/include/utils/math_util.h b/include/utils/math_util.h index d419a6e..d101742 100644 --- a/include/utils/math_util.h +++ b/include/utils/math_util.h @@ -1,17 +1,16 @@ #pragma once -#include +#include "../core/include/utils/geometry.h" #include "math.h" #include "vex.h" -#include "../core/include/utils/geometry.h" - +#include /** -* Constrain the input between a minimum and a maximum value -* -* @param val the value to be restrained -* @param low the minimum value that will be returned -* @param high the maximum value that will be returned -**/ + * Constrain the input between a minimum and a maximum value + * + * @param val the value to be restrained + * @param low the minimum value that will be returned + * @param high the maximum value that will be returned + **/ double clamp(double value, double low, double high); /** @@ -19,14 +18,14 @@ double clamp(double value, double low, double high); * @param a at t = 0, output = a * @param b at t = 1, output = b * @return a linear mixing of a and b according to t -*/ + */ double lerp(double a, double b, double t); /** -* Returns the sign of a number -* @param x -* -* returns the sign +/-1 of x. 0 if x is 0 -**/ + * Returns the sign of a number + * @param x + * + * returns the sign +/-1 of x. 0 if x is 0 + **/ double sign(double x); double wrap_angle_deg(double input); @@ -40,7 +39,6 @@ Calculates the variance of a set of numbers (needed for linear regression) */ double variance(std::vector const &values, double mean); - /* Calculates the average of a vector of doubles @param values the list of values for which the average is taken diff --git a/include/utils/moving_average.h b/include/utils/moving_average.h index ed01819..389c7b1 100644 --- a/include/utils/moving_average.h +++ b/include/utils/moving_average.h @@ -5,8 +5,7 @@ * Interface for filters * Use add_entry to supply data and get_value to retrieve the filtered value */ -class Filter -{ +class Filter { public: virtual void add_entry(double n) = 0; virtual double get_value() const = 0; @@ -15,17 +14,18 @@ class Filter /** * MovingAverage * - * A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. - * This means that if you collect enough samples those that are too high are cancelled out by the samples that are too low leaving the real value. + * A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric + * around the actual value. This means that if you collect enough samples those that are too high are cancelled out by + * the samples that are too low leaving the real value. * * The MovingAverage class provides a simple interface to do this smoothing from our noisy sensor values. * - * WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' behind the actual value that the sensor is reading. - * Using a MovingAverage is thus a tradeoff between accuracy and lag time (more samples) vs. less accuracy and faster updating (less samples). + * WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' + * behind the actual value that the sensor is reading. Using a MovingAverage is thus a tradeoff between accuracy and lag + * time (more samples) vs. less accuracy and faster updating (less samples). * */ -class MovingAverage : public Filter -{ +class MovingAverage : public Filter { public: /* * Create a moving average calculator with 0 as the default value @@ -73,17 +73,18 @@ class MovingAverage : public Filter /** * ExponentialMovingAverage * - * An exponential moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. - * This means that if you collect enough samples those that are too high are cancelled out by the samples that are too low leaving the real value. + * An exponential moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly + * symmetric around the actual value. This means that if you collect enough samples those that are too high are + * cancelled out by the samples that are too low leaving the real value. * - * A simple mobing average lags significantly with time as it has to counteract old samples. An exponential moving average keeps more up to date by - * weighting newer readings higher than older readings so it is more up to date while also still smoothed. + * A simple mobing average lags significantly with time as it has to counteract old samples. An exponential moving + * average keeps more up to date by weighting newer readings higher than older readings so it is more up to date while + * also still smoothed. * * The ExponentialMovingAverage class provides an simple interface to do this smoothing from our noisy sensor values. * */ -class ExponentialMovingAverage : public Filter -{ +class ExponentialMovingAverage : public Filter { public: /* * Create a moving average calculator with 0 as the default value diff --git a/include/utils/pure_pursuit.h b/include/utils/pure_pursuit.h index 3fd8edb..2e27271 100644 --- a/include/utils/pure_pursuit.h +++ b/include/utils/pure_pursuit.h @@ -1,128 +1,120 @@ #pragma once -#include #include "../core/include/utils/geometry.h" #include "../core/include/utils/vector2d.h" #include "vex.h" +#include using namespace vex; namespace PurePursuit { +/** + * Wrapper for a vector of points, checking if any of the points are too close for pure pursuit + */ +class Path { +public: /** - * Wrapper for a vector of points, checking if any of the points are too close for pure pursuit - */ - class Path - { - public: - /** - * Create a Path - * @param points the points that make up the path - * @param radius the lookahead radius for pure pursuit - */ - Path(std::vector points, double radius); - - /** - * Get the points associated with this Path - */ - std::vector get_points(); - - /** - * Get the radius associated with this Path - */ - double get_radius(); - - /** - * Get whether this path will behave as expected - */ - bool is_valid(); - - private: - std::vector points; - double radius; - bool valid; - }; - /** - * Represents a piece of a cubic spline with s(x) = a(x-xi)^3 + b(x-xi)^2 + c(x-xi) + d - * The x_start and x_end shows where the equation is valid. + * Create a Path + * @param points the points that make up the path + * @param radius the lookahead radius for pure pursuit */ - struct spline - { - double a, b, c, d, x_start, x_end; - - double getY(double x) { - return a * pow((x - x_start), 3) + b * pow((x - x_start), 2) + c * (x - x_start) + d; - } - }; - /** - * a position along the hermite path - * contains a position and orientation information that the robot would be at at this point - */ - struct hermite_point - { - double x; - double y; - double dir; - double mag; - - point_t getPoint() const { - return {x, y}; - } - - Vector2D getTangent() const { - return Vector2D(dir, mag); - } - }; + Path(std::vector points, double radius); /** - * Returns points of the intersections of a line segment and a circle. The line - * segment is defined by two points, and the circle is defined by a center and radius. - */ - extern std::vector line_circle_intersections(point_t center, double r, point_t point1, point_t point2); - /** - * Selects a look ahead from all the intersections in the path. - */ - extern point_t get_lookahead(const std::vector &path, pose_t robot_loc, double radius); - - /** - * Injects points in a path without changing the curvature with a certain spacing. - */ - extern std::vector inject_path(const std::vector &path, double spacing); - - /** - * Returns a smoothed path maintaining the start and end of the path. - * - * Weight data is how much weight to update the data (alpha) - * Weight smooth is how much weight to smooth the coordinates (beta) - * Tolerance is how much change per iteration is necessary to continue iterating. - * - * Honestly have no idea if/how this works. - * https://medium.com/@jaems33/understanding-robot-motion-path-smoothing-5970c8363bc4 - */ - - extern std::vector smooth_path(const std::vector &path, double weight_data, double weight_smooth, double tolerance); - - extern std::vector smooth_path_cubic(const std::vector &path, double res); + * Get the points associated with this Path + */ + std::vector get_points(); /** - * Interpolates a smooth path given a list of waypoints using hermite splines. - * For more information: https://www.youtube.com/watch?v=hG0p4XgePSA. - * - * @param path The path of hermite points to interpolate. - * @param steps The number of points interpolated between points. - * @return The smoothed path. + * Get the radius associated with this Path */ - extern std::vector smooth_path_hermite(const std::vector &path, double step); + double get_radius(); /** - * Estimates the remaining distance from the robot's position to the end, - * by "searching" for the robot along the path and running a "connect the dots" - * distance algoritm - * - * @param path The pure pursuit path the robot is following - * @param robot_pose The robot's current position - * @param radius Pure pursuit "radius", used to search for the robot along the path - * @return A rough estimate of the remaining distance - */ - extern double estimate_remaining_dist(const std::vector &path, pose_t robot_pose, double radius); - -} \ No newline at end of file + * Get whether this path will behave as expected + */ + bool is_valid(); + +private: + std::vector points; + double radius; + bool valid; +}; +/** + * Represents a piece of a cubic spline with s(x) = a(x-xi)^3 + b(x-xi)^2 + c(x-xi) + d + * The x_start and x_end shows where the equation is valid. + */ +struct spline { + double a, b, c, d, x_start, x_end; + + double getY(double x) { return a * pow((x - x_start), 3) + b * pow((x - x_start), 2) + c * (x - x_start) + d; } +}; +/** + * a position along the hermite path + * contains a position and orientation information that the robot would be at at this point + */ +struct hermite_point { + double x; + double y; + double dir; + double mag; + + point_t getPoint() const { return {x, y}; } + + Vector2D getTangent() const { return Vector2D(dir, mag); } +}; + +/** + * Returns points of the intersections of a line segment and a circle. The line + * segment is defined by two points, and the circle is defined by a center and radius. + */ +extern std::vector line_circle_intersections(point_t center, double r, point_t point1, point_t point2); +/** + * Selects a look ahead from all the intersections in the path. + */ +extern point_t get_lookahead(const std::vector &path, pose_t robot_loc, double radius); + +/** + * Injects points in a path without changing the curvature with a certain spacing. + */ +extern std::vector inject_path(const std::vector &path, double spacing); + +/** + * Returns a smoothed path maintaining the start and end of the path. + * + * Weight data is how much weight to update the data (alpha) + * Weight smooth is how much weight to smooth the coordinates (beta) + * Tolerance is how much change per iteration is necessary to continue iterating. + * + * Honestly have no idea if/how this works. + * https://medium.com/@jaems33/understanding-robot-motion-path-smoothing-5970c8363bc4 + */ + +extern std::vector smooth_path(const std::vector &path, double weight_data, double weight_smooth, + double tolerance); + +extern std::vector smooth_path_cubic(const std::vector &path, double res); + +/** + * Interpolates a smooth path given a list of waypoints using hermite splines. + * For more information: https://www.youtube.com/watch?v=hG0p4XgePSA. + * + * @param path The path of hermite points to interpolate. + * @param steps The number of points interpolated between points. + * @return The smoothed path. + */ +extern std::vector smooth_path_hermite(const std::vector &path, double step); + +/** + * Estimates the remaining distance from the robot's position to the end, + * by "searching" for the robot along the path and running a "connect the dots" + * distance algoritm + * + * @param path The pure pursuit path the robot is following + * @param robot_pose The robot's current position + * @param radius Pure pursuit "radius", used to search for the robot along the path + * @return A rough estimate of the remaining distance + */ +extern double estimate_remaining_dist(const std::vector &path, pose_t robot_pose, double radius); + +} // namespace PurePursuit \ No newline at end of file diff --git a/include/utils/serializer.h b/include/utils/serializer.h index 327b653..edf80b1 100644 --- a/include/utils/serializer.h +++ b/include/utils/serializer.h @@ -1,9 +1,9 @@ #pragma once #include #include +#include #include #include -#include #include /// @brief character that will be used to seperate values @@ -12,86 +12,87 @@ const char serialization_separator = '$'; const std::size_t MAX_FILE_SIZE = 4096; /// @brief Serializes Arbitrary data to a file on the SD Card -class Serializer -{ +class Serializer { private: - bool flush_always; - std::string filename; - std::map ints; - std::map bools; - std::map doubles; - std::map strings; + bool flush_always; + std::string filename; + std::map ints; + std::map bools; + std::map doubles; + std::map strings; - /// @brief loads Serializer state from disk - bool read_from_disk(); + /// @brief loads Serializer state from disk + bool read_from_disk(); public: - /// @brief Save and close upon destruction (bc of vex, this doesnt always get called when the program ends. To be sure, call save_to_disk) - ~Serializer() - { - save_to_disk(); - printf("Saving %s\n", filename.c_str()); - fflush(stdout); - } - - /// @brief create a Serializer - /// @param filename the file to read from. If filename does not exist we will create that file - /// @param flush_always If true, after every write flush to a file. If false, you are responsible for calling save_to_disk - explicit Serializer(const std::string &filename, bool flush_always = true) : flush_always(flush_always), filename(filename), ints({}), bools({}), doubles({}), strings({}) - - { - read_from_disk(); - } - - /// @brief saves current Serializer state to disk - void save_to_disk() const; - - /// Setters - not saved until save_to_disk is called - - /// @brief sets an integer by the name of name to i. If flush_always == true, this will save to the sd card - /// @param name name of integer - /// @param i value of integer - void set_int(const std::string &name, int i); - - /// @brief sets a bool by the name of name to b. If flush_always == true, this will save to the sd card - /// @param name name of bool - /// @param b value of bool - void set_bool(const std::string &name, bool b); - - /// @brief sets a double by the name of name to d. If flush_always == true, this will save to the sd card - /// @param name name of double - /// @param d value of double - void set_double(const std::string &name, double d); - - /// @brief sets a string by the name of name to s. If flush_always == true, this will save to the sd card - /// @param name name of string - /// @param i value of string - void set_string(const std::string &name, std::string str); - - /// Getters - /// Return value if it exists in the serializer - - /// @brief gets a value stored in the serializer. If not found, sets the value to otherwise - /// @param name name of value - /// @param otherwise value if the name is not specified - /// @return the value if found or otherwise - int int_or(const std::string &name, int otherwise); - - /// @brief gets a value stored in the serializer. If not, sets the value to otherwise - /// @param name name of value - /// @param otherwise value if the name is not specified - /// @return the value if found or otherwise - bool bool_or(const std::string &name, bool otherwise); - - /// @brief gets a value stored in the serializer. If not, sets the value to otherwise - /// @param name name of value - /// @param otherwise value if the name is not specified - /// @return the value if found or otherwise - double double_or(const std::string &name, double otherwise); - - /// @brief gets a value stored in the serializer. If not, sets the value to otherwise - /// @param name name of value - /// @param otherwise value if the name is not specified - /// @return the value if found or otherwise - std::string string_or(const std::string &name, std::string otherwise); + /// @brief Save and close upon destruction (bc of vex, this doesnt always get called when the program ends. To be + /// sure, call save_to_disk) + ~Serializer() { + save_to_disk(); + printf("Saving %s\n", filename.c_str()); + fflush(stdout); + } + + /// @brief create a Serializer + /// @param filename the file to read from. If filename does not exist we will create that file + /// @param flush_always If true, after every write flush to a file. If false, you are responsible for calling + /// save_to_disk + explicit Serializer(const std::string &filename, bool flush_always = true) + : flush_always(flush_always), filename(filename), ints({}), bools({}), doubles({}), strings({}) + + { + read_from_disk(); + } + + /// @brief saves current Serializer state to disk + void save_to_disk() const; + + /// Setters - not saved until save_to_disk is called + + /// @brief sets an integer by the name of name to i. If flush_always == true, this will save to the sd card + /// @param name name of integer + /// @param i value of integer + void set_int(const std::string &name, int i); + + /// @brief sets a bool by the name of name to b. If flush_always == true, this will save to the sd card + /// @param name name of bool + /// @param b value of bool + void set_bool(const std::string &name, bool b); + + /// @brief sets a double by the name of name to d. If flush_always == true, this will save to the sd card + /// @param name name of double + /// @param d value of double + void set_double(const std::string &name, double d); + + /// @brief sets a string by the name of name to s. If flush_always == true, this will save to the sd card + /// @param name name of string + /// @param i value of string + void set_string(const std::string &name, std::string str); + + /// Getters + /// Return value if it exists in the serializer + + /// @brief gets a value stored in the serializer. If not found, sets the value to otherwise + /// @param name name of value + /// @param otherwise value if the name is not specified + /// @return the value if found or otherwise + int int_or(const std::string &name, int otherwise); + + /// @brief gets a value stored in the serializer. If not, sets the value to otherwise + /// @param name name of value + /// @param otherwise value if the name is not specified + /// @return the value if found or otherwise + bool bool_or(const std::string &name, bool otherwise); + + /// @brief gets a value stored in the serializer. If not, sets the value to otherwise + /// @param name name of value + /// @param otherwise value if the name is not specified + /// @return the value if found or otherwise + double double_or(const std::string &name, double otherwise); + + /// @brief gets a value stored in the serializer. If not, sets the value to otherwise + /// @param name name of value + /// @param otherwise value if the name is not specified + /// @return the value if found or otherwise + std::string string_or(const std::string &name, std::string otherwise); }; diff --git a/include/utils/state_machine.h b/include/utils/state_machine.h new file mode 100644 index 0000000..8671fe0 --- /dev/null +++ b/include/utils/state_machine.h @@ -0,0 +1,202 @@ +#pragma once +#include +#include +#include + +/** + * @brief State Machine :)))))) + * A fun fun way of controlling stateful subsystems - used in the 2023-2024 Over + * Under game for our overly complex intake-cata subsystem (see there for an + * example) + * The statemachine runs in a background thread and a user thread can interact + * with it through current_state and send_message. + * + * Designwise: + * the System class should hold onto any motors, feedback controllers, etc that + * are persistent in the system States themselves should hold any data that + * *only* that state needs. For example if a state should be exitted after a + * certain amount of time, it should hold a timer rather than the System holding + * that timer. (see Junder from 2024 for an example of this design) + * + * @tparam System The system that this is the base class of `class Thing : + * public StateMachine + * @tparam IDType The ID enum that recognizes states. Hint hint, use an `enum + * class` + * @tparam Message the message enum that a state or an outside can send and that + * states respond to + * @tparam delay_ms the delay to wait between each state processing to allow + * other threads to work + * @tparam do_log true if you want print statements describing incoming messages + * and current states. If true, it is expected that IDType and Message have a + * function called to_string that takes them as its only parameter and returns a + * std::string + */ +template +class StateMachine { + static_assert(std::is_enum::value, "Message should be an enum (it's easier that way)"); + static_assert(std::is_enum::value, "IDType should be an enum (it's easier that way)"); + +public: + /** + * @brief MaybeMessage + * a message of Message type or nothing + * MaybeMessage m = {}; // empty + * MaybeMessage m = Message::EnumField1 + */ + class MaybeMessage { + public: + /** + * @brief Empty message - when theres no message + */ + MaybeMessage() : exists(false) {} + /** + * @brief Create a maybemessage with a message + * @param msg the message to hold on to + */ + MaybeMessage(Message msg) : exists(true), thing(msg) {} + /** + * @brief check if the message is here + * @return true if there is a message + */ + bool has_message() { return exists; } + /** + * @brief Get the message stored. The return value is invalid unless + * has_message returned true + * @return The message if it exists. Undefined otherwise + */ + Message message() { return thing; } + + private: + bool exists; + Message thing; + }; + /** + * Abstract class that all states for this machine must inherit from + * States MUST override respond() and id() in order to function correctly + * (the compiler won't have it any other way) + */ + struct State { + // run once when we enter the state + virtual void entry(System &) {} + // run continously while in the state + virtual MaybeMessage work(System &) { return {}; } + // run once when we exit the state + virtual void exit(System &) {} + // respond to a message when one comes in + virtual State *respond(System &s, Message m) = 0; + // Identify + virtual IDType id() const = 0; + + // virtual destructor cuz c++ + virtual ~State() {} + }; + + // Data that gets passed to the runner thread. Don't worry too much about + // this + using thread_data = std::pair; + + /** + * @brief Construct a state machine and immediatly start running it + * @param initial the state that the machine will begin in + */ + StateMachine(State *initial) : runner(thread_runner, new thread_data{initial, this}) {} + + /** + * @brief retrieve the current state of the state machine. This is safe to + * call from external threads + * @return the current state + */ + IDType current_state() const { + mut.lock(); + auto t = cur_type; + mut.unlock(); + return t; + } + /** + * @brief send a message to the state machine from outside + * @param msg the message to send + * This is safe to call from external threads + */ + void send_message(Message msg) { + mut.lock(); + incoming_msg = msg; + mut.unlock(); + } + +private: + vex::task runner; + mutable vex::mutex mut; + MaybeMessage incoming_msg; + IDType cur_type; + + /** + * @brief the thread that does the running of the state machine. + * @param vptr the thread_data that we get passed to begin. cast it back + * @return return value of thread (the thread never ends so this doesn't + * really matter) + */ + static int thread_runner(void *vptr) { + thread_data *ptr = static_cast(vptr); + State *cur_state = ptr->first; + + StateMachine &sys = *ptr->second; + System &derived = *static_cast(&sys); + + cur_state->entry(derived); + + sys.cur_type = cur_state->id(); + + auto respond_to_message = [&](Message msg) { + if (do_log) { + printf("responding to msg: %s\n", to_string(msg).c_str()); + fflush(stdout); + } + + State *next_state = cur_state->respond(derived, msg); + + if (cur_state != next_state) { + // switched states + sys.mut.lock(); + + cur_state->exit(derived); + next_state->entry(derived); + + delete cur_state; + + cur_state = next_state; + sys.cur_type = cur_state->id(); + + sys.mut.unlock(); + } + }; + + while (true) { + if (do_log) { + std::string str = to_string(cur_state->id()); + std::string str2 = to_string(sys.cur_type); + + printf("state: %s %s\n", str.c_str(), str2.c_str()); + } + + // Internal Message passed + MaybeMessage internal_msg = cur_state->work(derived); + + if (internal_msg.has_message()) { + respond_to_message(internal_msg.message()); + } + + // External Message passed + sys.mut.lock(); + MaybeMessage incoming = sys.incoming_msg; + sys.incoming_msg = {}; + sys.mut.unlock(); + + if (incoming.has_message()) { + respond_to_message(incoming.message()); + } + + vexDelay(delay_ms); + } + return 0; + } +}; diff --git a/include/utils/vector2d.h b/include/utils/vector2d.h index c39f50f..6c555cc 100644 --- a/include/utils/vector2d.h +++ b/include/utils/vector2d.h @@ -1,96 +1,92 @@ #pragma once - -#include #include "../core/include/utils/geometry.h" +#include #ifndef PI #define PI 3.141592654 #endif /** * Vector2D is an x,y pair - * Used to represent 2D locations on the field. + * Used to represent 2D locations on the field. * It can also be treated as a direction and magnitude -*/ -class Vector2D -{ + */ +class Vector2D { public: - /** - * Construct a vector object. - * - * @param dir Direction, in radians. 'foward' is 0, clockwise positive when viewed from the top. - * @param mag Magnitude. - */ - Vector2D(double dir, double mag); - - /** - * Construct a vector object from a cartesian point. - * - * @param p point_t.x , point_t.y - */ - Vector2D(point_t p); - - /** - * Get the direction of the vector, in radians. - * '0' is forward, clockwise positive when viewed from the top. - * - * Use r2d() to convert. - * @return the direction of the vetctor in radians - */ - double get_dir() const; - - /** - * @return the magnitude of the vector - */ - double get_mag() const; - - /** - * @return the X component of the vector; positive to the right. - */ - double get_x() const; - - /** - * @return the Y component of the vector, positive forward. - */ - double get_y() const; - - /** - * Changes the magnitude of the vector to 1 - * @return the normalized vector - */ - Vector2D normalize(); - - /** - * Returns a point from the vector - * @return the point represented by the vector - */ - point_t point(); - -/** - * Scales a Vector2D by a scalar with the * operator - * @param x the value to scale the vector by - * @return the this Vector2D scaled by x -*/ - Vector2D operator*(const double &x); - /** - * Add the components of two vectors together - * Vector2D + Vector2D = (this.x + other.x, this.y + other.y) - * @param other the vector to add to this - * @return the sum of the vectors - */ - Vector2D operator+(const Vector2D &other); - /** - * Subtract the components of two vectors together - * Vector2D - Vector2D = (this.x - other.x, this.y - other.y) - * @param other the vector to subtract from this - * @return the difference of the vectors - */ - Vector2D operator-(const Vector2D &other); + /** + * Construct a vector object. + * + * @param dir Direction, in radians. 'foward' is 0, clockwise positive when viewed from the top. + * @param mag Magnitude. + */ + Vector2D(double dir, double mag); + + /** + * Construct a vector object from a cartesian point. + * + * @param p point_t.x , point_t.y + */ + Vector2D(point_t p); + + /** + * Get the direction of the vector, in radians. + * '0' is forward, clockwise positive when viewed from the top. + * + * Use r2d() to convert. + * @return the direction of the vetctor in radians + */ + double get_dir() const; + + /** + * @return the magnitude of the vector + */ + double get_mag() const; + + /** + * @return the X component of the vector; positive to the right. + */ + double get_x() const; + + /** + * @return the Y component of the vector, positive forward. + */ + double get_y() const; + + /** + * Changes the magnitude of the vector to 1 + * @return the normalized vector + */ + Vector2D normalize(); + + /** + * Returns a point from the vector + * @return the point represented by the vector + */ + point_t point(); + + /** + * Scales a Vector2D by a scalar with the * operator + * @param x the value to scale the vector by + * @return the this Vector2D scaled by x + */ + Vector2D operator*(const double &x); + /** + * Add the components of two vectors together + * Vector2D + Vector2D = (this.x + other.x, this.y + other.y) + * @param other the vector to add to this + * @return the sum of the vectors + */ + Vector2D operator+(const Vector2D &other); + /** + * Subtract the components of two vectors together + * Vector2D - Vector2D = (this.x - other.x, this.y - other.y) + * @param other the vector to subtract from this + * @return the difference of the vectors + */ + Vector2D operator-(const Vector2D &other); private: - - double dir, mag; - + double dir, mag; }; /** diff --git a/src/subsystems/custom_encoder.cpp b/src/subsystems/custom_encoder.cpp index a8f3adc..b9614f8 100644 --- a/src/subsystems/custom_encoder.cpp +++ b/src/subsystems/custom_encoder.cpp @@ -1,41 +1,28 @@ -#include "../core/include/subsystems/custom_encoder.h" +#include "../core/include/subsystems/custom_encoder.h" -CustomEncoder::CustomEncoder(vex::triport::port &port, double ticks_per_rev) -: super(port) -{ +CustomEncoder::CustomEncoder(vex::triport::port &port, double ticks_per_rev) : super(port) { // bc it's a quadrature encoder, ticks per rev has to be multiplied by 4 tick_scalar = 360 / (ticks_per_rev * 4); } -void CustomEncoder::setRotation(double val, vex::rotationUnits units) -{ - super::setRotation(val / tick_scalar, units); -} +void CustomEncoder::setRotation(double val, vex::rotationUnits units) { super::setRotation(val / tick_scalar, units); } -void CustomEncoder::setPosition(double val, vex::rotationUnits units) -{ - super::setPosition(val / tick_scalar, units); -} +void CustomEncoder::setPosition(double val, vex::rotationUnits units) { super::setPosition(val / tick_scalar, units); } + +double CustomEncoder::rotation(vex::rotationUnits units) { + if (units != vex::rotationUnits::raw) { + return super::rotation(units) * tick_scalar; + } -double CustomEncoder::rotation(vex::rotationUnits units) -{ - if(units != vex::rotationUnits::raw) { - return super::rotation(units) * tick_scalar; -} - return super::rotation(units); } -double CustomEncoder::position(vex::rotationUnits units) -{ +double CustomEncoder::position(vex::rotationUnits units) { if (units != vex::rotationUnits::raw) { - return super::position(units) * tick_scalar; -} + return super::position(units) * tick_scalar; + } return super::position(units); } -double CustomEncoder::velocity(vex::velocityUnits units) -{ - return super::velocity(units) * tick_scalar; -} +double CustomEncoder::velocity(vex::velocityUnits units) { return super::velocity(units) * tick_scalar; } diff --git a/src/subsystems/flywheel.cpp b/src/subsystems/flywheel.cpp index eab2f74..4e57acc 100644 --- a/src/subsystems/flywheel.cpp +++ b/src/subsystems/flywheel.cpp @@ -1,9 +1,9 @@ #include "../core/include/subsystems/flywheel.h" +#include "../core/include/subsystems/screen.h" #include "../core/include/utils/controls/feedforward.h" #include "../core/include/utils/controls/pid.h" -#include "../core/include/utils/math_util.h" -#include "../core/include/subsystems/screen.h" #include "../core/include/utils/graph_drawer.h" +#include "../core/include/utils/math_util.h" #include "vex.h" using namespace vex; @@ -12,9 +12,8 @@ using namespace vex; * CONSTRUCTOR, GETTERS, SETTERS *********************************************************/ -Flywheel::Flywheel(motor_group &motors, Feedback &feedback, FeedForward &helper, const double ratio, Filter &filt) : motors(motors), - task_running(false), fb(feedback), ff(helper), - ratio(ratio), avger(filt) {} +Flywheel::Flywheel(motor_group &motors, Feedback &feedback, FeedForward &helper, const double ratio, Filter &filt) + : motors(motors), task_running(false), fb(feedback), ff(helper), ratio(ratio), avger(filt) {} /** * Return the current value that the target_rpm should be set to @@ -30,32 +29,25 @@ motor_group &Flywheel::get_motors() const { return motors; } * return the current velocity of the flywheel motors, in RPM * @return the measured velocity of the flywheel */ -double Flywheel::measure_RPM() -{ +double Flywheel::measure_RPM() { double rawRPM = ratio * motors.velocity(velocityUnits::rpm); avger.add_entry(rawRPM); return avger.get_value(); } -double Flywheel::getRPM() const -{ - return avger.get_value(); -} +double Flywheel::getRPM() const { return avger.get_value(); } /** * Runs a thread that keeps track of updating flywheel RPM and controlling it accordingly */ -int spinRPMTask(void *wheelPointer) -{ +int spinRPMTask(void *wheelPointer) { Flywheel &wheel = *(Flywheel *)wheelPointer; // get the pid from the wheel and set its target to the RPM stored in the wheel. - while (true) - { + while (true) { double rpm = wheel.measure_RPM(); - if (wheel.target_rpm != 0) - { + if (wheel.target_rpm != 0) { double output = wheel.ff.calculate(wheel.target_rpm, 0.0, 0.0); { wheel.fb_mut.lock(); @@ -82,10 +74,7 @@ int spinRPMTask(void *wheelPointer) * @param speed - speed (between -1 and 1) to set the motor * @param dir - direction that the motor moves in; defaults to forward */ -void Flywheel::spin_raw(double speed, directionType dir) -{ - motors.spin(dir, speed * 12, voltageUnits::volt); -} +void Flywheel::spin_raw(double speed, directionType dir) { motors.spin(dir, speed * 12, voltageUnits::volt); } /** * Spin motors using voltage; defaults forward at 12 volts @@ -93,11 +82,10 @@ void Flywheel::spin_raw(double speed, directionType dir) * @param speed - speed (between -1 and 1) to set the motor * @param dir - direction that the motor moves in; defaults to forward */ -void Flywheel::spin_manual(double speed, directionType dir) -{ +void Flywheel::spin_manual(double speed, directionType dir) { if (!task_running) { motors.spin(dir, speed * 12, voltageUnits::volt); -} + } } /** @@ -105,24 +93,20 @@ void Flywheel::spin_manual(double speed, directionType dir) * what control scheme is dependent on control_style * @param input_rpm - set the current RPM */ -void Flywheel::spin_rpm(double input_rpm) -{ +void Flywheel::spin_rpm(double input_rpm) { // setting to 0 is equivelent to stopping - if (input_rpm == 0.0) - { + if (input_rpm == 0.0) { stop(); } // only run if the RPM is different or it isn't already running - if (!task_running) - { + if (!task_running) { rpm_task = task(spinRPMTask, this); task_running = true; } // now that its running, set the target set_target(input_rpm); } -void Flywheel::set_target(double value) -{ +void Flywheel::set_target(double value) { fb_mut.lock(); target_rpm = (value); fb.init(getRPM(), value); @@ -132,10 +116,8 @@ void Flywheel::set_target(double value) /** * stop the RPM thread and the wheel */ -void Flywheel::stop() -{ - if (task_running) - { +void Flywheel::stop() { + if (task_running) { task_running = false; rpm_task.stop(); target_rpm = 0.0; @@ -144,18 +126,18 @@ void Flywheel::stop() } //------------------------- Screen Stuff ---------------------------- -class FlywheelPage : public screen::Page -{ +class FlywheelPage : public screen::Page { public: static const size_t window_size = 40; - FlywheelPage(const Flywheel &fw) : fw(fw), gd(GraphDrawer(window_size, 0.0, 0.0, {vex::color(255, 0, 0), vex::color(0, 255, 0), vex::color(0, 0, 255)}, 3)), avg_err(window_size) {} + FlywheelPage(const Flywheel &fw) + : fw(fw), gd(GraphDrawer(window_size, 0.0, 0.0, + {vex::color(255, 0, 0), vex::color(0, 255, 0), vex::color(0, 0, 255)}, 3)), + avg_err(window_size) {} /// @brief @see Page#update void update(bool, int, int) override {} /// @brief @see Page#draw - void draw(vex::brain::lcd &screen, bool, - unsigned int) override - { + void draw(vex::brain::lcd &screen, bool, unsigned int) override { double target = fw.get_target(); double actual = fw.getRPM(); @@ -180,7 +162,4 @@ class FlywheelPage : public screen::Page MovingAverage avg_err; }; -screen::Page *Flywheel::Page() const -{ - return new FlywheelPage(*this); -} \ No newline at end of file +screen::Page *Flywheel::Page() const { return new FlywheelPage(*this); } \ No newline at end of file diff --git a/src/subsystems/fun/video.cpp b/src/subsystems/fun/video.cpp new file mode 100644 index 0000000..4763c12 --- /dev/null +++ b/src/subsystems/fun/video.cpp @@ -0,0 +1,124 @@ +#include "../core/include/subsystems/fun/video.h" +#include + +#define PL_MPEG_IMPLEMENTATION +#include "../core/include/subsystems/fun/pl_mpeg.h" + +static uint8_t buf[358400]; + +enum VideoState { DoesntExist, TooBig, DidntReadRight, Ok, NeverInitialized }; + +static vex::task video_task; +static VideoState state = VideoState::NeverInitialized; +static std::string name = ""; +static uint8_t *argb_buffer; +static int w; +static int h; +static int x; +static int y; +static bool frame_ready = false; +static plm_t *plm; +const int32_t video_player_priority = 2; +static int32_t file_size = 0; +static bool should_restart = false; + +void video_restart() { should_restart = true; } + +void explain_error(vex::brain::lcd &screen) { + switch (state) { + case DoesntExist: + screen.printAt(40, 30, true, "Couldn't find video %s", name.c_str()); + break; + case TooBig: + screen.printAt(40, 30, true, "%s was too big to open", name.c_str()); + break; + case DidntReadRight: + screen.printAt(40, 30, true, "%s wasnt read correctly. Are you sure its mpeg1", name.c_str()); + break; + case NeverInitialized: + screen.printAt(40, 30, true, "no video loaded. did you forget set_video()"); + break; + + default: + break; + } +} + +int video_player() { + if (state != Ok) { + return 1; + } + plm_frame_t *frame = NULL; + while (true) { + for (int i = 1; frame = plm_decode_video(plm); i++) { + + uint32_t start_ms = vex::timer::system(); + + frame_ready = false; + plm_frame_to_bgra(frame, argb_buffer, w * 4); + frame_ready = true; + uint32_t elapsed_ms = vex::timer::system() - start_ms; + + vexDelay(33 - elapsed_ms); + if (should_restart) { + should_restart = false; + break; + } + } + plm_rewind(plm); + } + return 0; +} + +void set_video(const std::string &filename) { + vex::brain Brain; + const char *fname = filename.c_str(); + + if (!Brain.SDcard.exists(fname)) { + state = DoesntExist; + return; + } + file_size = Brain.SDcard.size(fname); + if (file_size > sizeof(buf)) { + state = TooBig; + return; + } + const int32_t read = Brain.SDcard.loadfile(fname, buf, sizeof(buf)); + + if (read != file_size) { + state = DidntReadRight; + return; + } + plm = plm_create_with_memory(buf, file_size, 0); + + plm_set_audio_enabled(plm, false); + plm_set_loop(plm, true); + + w = plm_get_width(plm); + h = plm_get_height(plm); + int render_buf_len = w * h * 4; + x = (480 - w) / 2; + y = (200 - h) / 2; + argb_buffer = new uint8_t[render_buf_len]; + state = Ok; + name = fname; + video_task = vex::task(video_player, video_player_priority); +} + +VideoPlayer::VideoPlayer() {} +void VideoPlayer::update(bool was_pressed, int x, int y) {} + +void VideoPlayer::draw(vex::brain::lcd &screen, bool first_draw, unsigned int frame_number) { + if (state != Ok) { + explain_error(screen); + return; + } + // nothin bad ever happened with a spin lock + for (int i = 0; i < 5; i++) { + if (frame_ready) { + break; + } + vexDelay(1); + } + screen.drawImageFromBuffer((uint32_t *)argb_buffer, x, y, w, h); +} \ No newline at end of file diff --git a/src/subsystems/mecanum_drive.cpp b/src/subsystems/mecanum_drive.cpp index 793c1b9..53b7519 100644 --- a/src/subsystems/mecanum_drive.cpp +++ b/src/subsystems/mecanum_drive.cpp @@ -1,47 +1,45 @@ #include "../core/include/subsystems/mecanum_drive.h" -#include "../core/include/utils/vector2d.h" #include "../core/include/utils/math_util.h" +#include "../core/include/utils/vector2d.h" /** -* Create the Mecanum drivetrain object -*/ -MecanumDrive::MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, vex::motor &right_rear, - vex::rotation *lateral_wheel, vex::inertial *imu, mecanumdrive_config_t *config) -: left_front(left_front), right_front(right_front), left_rear(left_rear), right_rear(right_rear), // MOTOR CONFIG - config(config), // CONFIG ...uh... config - lateral_wheel(lateral_wheel), // NON-DRIVEN WHEEL CONFIG - imu(imu) //IMU CONFIG + * Create the Mecanum drivetrain object + */ +MecanumDrive::MecanumDrive(vex::motor &left_front, vex::motor &right_front, vex::motor &left_rear, + vex::motor &right_rear, vex::rotation *lateral_wheel, vex::inertial *imu, + mecanumdrive_config_t *config) + : left_front(left_front), right_front(right_front), left_rear(left_rear), right_rear(right_rear), // MOTOR CONFIG + config(config), // CONFIG ...uh... config + lateral_wheel(lateral_wheel), // NON-DRIVEN WHEEL CONFIG + imu(imu) // IMU CONFIG { // If the configuration exists, then allocate memory for the drive and turn pids - if(config != NULL) - { + if (config != NULL) { drive_pid = new PID(config->drive_pid_conf); drive_gyro_pid = new PID(config->drive_gyro_pid_conf); turn_pid = new PID(config->turn_pid_conf); } - } /** - * Drive the robot using vectors. This handles all the math required for mecanum control. - * - * @param direction_deg the direction to drive the robot, in degrees. 0 is forward, - * 180 is back, clockwise is positive, counterclockwise is negative. - * @param magnitude How fast the robot should drive, in percent: 0.0->1.0 - * @param rotation How fast the robot should rotate, in percent: -1.0->+1.0 - */ -void MecanumDrive::drive_raw(double direction_deg, double magnitude, double rotation) -{ + * Drive the robot using vectors. This handles all the math required for mecanum control. + * + * @param direction_deg the direction to drive the robot, in degrees. 0 is forward, + * 180 is back, clockwise is positive, counterclockwise is negative. + * @param magnitude How fast the robot should drive, in percent: 0.0->1.0 + * @param rotation How fast the robot should rotate, in percent: -1.0->+1.0 + */ +void MecanumDrive::drive_raw(double direction_deg, double magnitude, double rotation) { double direction = deg2rad(direction_deg); - + // ALGORITHM - "rotate" the vector by 45 degrees and apply each corner to a wheel // .. Oh, and mix rotation too double lf = (magnitude * cos(direction - (PI / 4.0))) + rotation; double rf = (magnitude * cos(direction + (PI / 4.0))) - rotation; double lr = (magnitude * cos(direction + (PI / 4.0))) + rotation; double rr = (magnitude * cos(direction - (PI / 4.0))) - rotation; - + // Limit the output between -1.0 and +1.0 lf = clamp(lf, -1.0, 1.0); rf = clamp(rf, -1.0, 1.0); @@ -56,8 +54,8 @@ void MecanumDrive::drive_raw(double direction_deg, double magnitude, double rota } /** - * Drive the robot with a mecanum-style / arcade drive. Inputs are in percent (-100.0 -> 100.0) straight from the controller. - * Controls are mixed, so the robot can drive forward / strafe / rotate all at the same time. + * Drive the robot with a mecanum-style / arcade drive. Inputs are in percent (-100.0 -> 100.0) straight from the + * controller. Controls are mixed, so the robot can drive forward / strafe / rotate all at the same time. * * @param left_y left joystick, Y axis (forward / backwards) * @param left_x left joystick, X axis (strafe left / right) @@ -65,40 +63,37 @@ void MecanumDrive::drive_raw(double direction_deg, double magnitude, double rota * @param power = 2 how much of a "curve" there should be on drive controls; better for low speed maneuvers. * Leave blank for a default curve of 2 (higher means more fidelity) */ -void MecanumDrive::drive(double left_y, double left_x, double right_x, int power) -{ +void MecanumDrive::drive(double left_y, double left_x, double right_x, int power) { // LATERAL CONTROLS - convert cartesion to a vector double magnitude = sqrt(pow(left_y / 100.0, 2) + pow(left_x / 100.0, 2)); magnitude = pow(magnitude, power); - + double direction = atan2(left_x / 100.0, left_y / 100.0); // ROTATIONAL CONTROLS - just the right x joystick double rotation = right_x / 100.0; - // + // rotation = sign(rotation) * fabs(pow(rotation, power)); - - return this->drive_raw(rad2deg(direction), magnitude, rotation); + + return this->drive_raw(rad2deg(direction), magnitude, rotation); } /** - * Drive the robot in a straight line automatically. - * If the inertial was declared in the constructor, use it to correct while driving. - * If the lateral wheel was declared in the constructor, use it for more accurate positioning while strafing. - * - * @param inches How far the robot should drive, in inches - * @param direction What direction the robot should travel in, in degrees. - * 0 is forward, +/-180 is reverse, clockwise is positive. - * @param speed The maximum speed the robot should travel, in percent: -1.0->+1.0 - * @param gyro_correction = true Whether or not to use the gyro to help correct while driving. - * Will always be false if no gyro was declared in the constructor. - * @return Whether or not the maneuver is complete. - */ -bool MecanumDrive::auto_drive(double inches, double direction, double speed, bool gyro_correction) -{ - if(config == NULL || drive_pid == NULL) - { + * Drive the robot in a straight line automatically. + * If the inertial was declared in the constructor, use it to correct while driving. + * If the lateral wheel was declared in the constructor, use it for more accurate positioning while strafing. + * + * @param inches How far the robot should drive, in inches + * @param direction What direction the robot should travel in, in degrees. + * 0 is forward, +/-180 is reverse, clockwise is positive. + * @param speed The maximum speed the robot should travel, in percent: -1.0->+1.0 + * @param gyro_correction = true Whether or not to use the gyro to help correct while driving. + * Will always be false if no gyro was declared in the constructor. + * @return Whether or not the maneuver is complete. + */ +bool MecanumDrive::auto_drive(double inches, double direction, double speed, bool gyro_correction) { + if (config == NULL || drive_pid == NULL) { fprintf(stderr, "Failed to run MecanumDrive::auto_drive - Missing mecanumdrive_config_t in constructor\n"); return true; // avoid an infinte loop within auto } @@ -106,10 +101,8 @@ bool MecanumDrive::auto_drive(double inches, double direction, double speed, boo bool enable_gyro = gyro_correction && (imu != NULL); bool enable_wheel = (lateral_wheel != NULL); - // INITIALIZE - only run ONCE "per drive" on startup - if(init == true) - { + if (init == true) { // Reset all driven encoders, and PID left_front.resetPosition(); @@ -120,16 +113,15 @@ bool MecanumDrive::auto_drive(double inches, double direction, double speed, boo drive_pid->reset(); // Reset only if gyro exists - if(enable_gyro) - { + if (enable_gyro) { imu->resetRotation(); drive_gyro_pid->reset(); drive_gyro_pid->set_target(0.0); } // reset only if lateral wheel exists - if(enable_wheel) { - lateral_wheel->resetPosition(); -} + if (enable_wheel) { + lateral_wheel->resetPosition(); + } // Finish setting up the PID loop - max speed and position target drive_pid->set_limits(-fabs(speed), fabs(speed)); @@ -147,44 +139,34 @@ bool MecanumDrive::auto_drive(double inches, double direction, double speed, boo // IF in quadrant 1 or 3, use left front and right rear wheels as "drive" movement // ELSE in quadrant 2 or 4, use left rear and right front wheels as "drive" movement - // Some wheels are NOT being averaged at any given time since the general mecanum algorithm makes them go slower than our robot speed - // somewhat of a nasty hack, but wheel slippage should make up for it, and multivariable calc is hard. - if( (direction > 0 && direction <= 90) || (direction < -90 && direction > -180)) - { - drive_avg = fabs(left_front.position(rotationUnits::rev) * config->drive_wheel_diam * PI) - + fabs(right_rear.position(rotationUnits::rev) * config->drive_wheel_diam * PI) - / 2.0; - } else - { - drive_avg = fabs(left_rear.position(rotationUnits::rev) * config->drive_wheel_diam * PI) - + fabs(right_front.position(rotationUnits::rev) * config->drive_wheel_diam * PI) - / 2.0; + // Some wheels are NOT being averaged at any given time since the general mecanum algorithm makes them go slower than + // our robot speed somewhat of a nasty hack, but wheel slippage should make up for it, and multivariable calc is hard. + if ((direction > 0 && direction <= 90) || (direction < -90 && direction > -180)) { + drive_avg = fabs(left_front.position(rotationUnits::rev) * config->drive_wheel_diam * PI) + + fabs(right_rear.position(rotationUnits::rev) * config->drive_wheel_diam * PI) / 2.0; + } else { + drive_avg = fabs(left_rear.position(rotationUnits::rev) * config->drive_wheel_diam * PI) + + fabs(right_front.position(rotationUnits::rev) * config->drive_wheel_diam * PI) / 2.0; } // Only use the encoder wheel if it exists. // Without the wheel should be usable, but with it will be muuuuch more accurate. - if(enable_wheel) - { + if (enable_wheel) { // Distance driven = Magnitude = sqrt(x^2 + y^2) // Since drive_avg is already a polar magnitude, turn it into "Y" with cos(theta) - dist_avg = sqrt( - pow(lateral_wheel->position(rotationUnits::rev) * config->lateral_wheel_diam * PI, 2) - + pow(drive_avg * cos(direction * (PI / 180.0)), 2) - ); - }else - { + dist_avg = sqrt(pow(lateral_wheel->position(rotationUnits::rev) * config->lateral_wheel_diam * PI, 2) + + pow(drive_avg * cos(direction * (PI / 180.0)), 2)); + } else { dist_avg = drive_avg; } // ...double check to avoid an infinite loop dist_avg = fabs(dist_avg); - // ROTATION CORRECTION double rot = 0; - if(enable_gyro) - { + if (enable_gyro) { drive_gyro_pid->update(imu->rotation()); rot = drive_gyro_pid->get(); } @@ -195,8 +177,7 @@ bool MecanumDrive::auto_drive(double inches, double direction, double speed, boo this->drive_raw(direction, drive_pid->get(), rot); // Stop and return true whenever the robot has completed it's drive. - if(drive_pid->is_on_target()) - { + if (drive_pid->is_on_target()) { drive_raw(0, 0, 0); init = true; return true; @@ -207,20 +188,18 @@ bool MecanumDrive::auto_drive(double inches, double direction, double speed, boo } /** -* Autonomously turn the robot X degrees over it's center point. Uses a closed loop -* for control. -* @param degrees How many degrees to rotate the robot. Clockwise postive. -* @param speed What percentage to run the motors at: 0.0 -> 1.0 -* @param ignore_imu = false Whether or not to use the Inertial for determining angle. -* Will instead use circumference formula + robot's wheelbase + encoders to determine. -* -* @return whether or not the robot has finished the maneuver -*/ -bool MecanumDrive::auto_turn(double degrees, double speed, bool ignore_imu) -{ + * Autonomously turn the robot X degrees over it's center point. Uses a closed loop + * for control. + * @param degrees How many degrees to rotate the robot. Clockwise postive. + * @param speed What percentage to run the motors at: 0.0 -> 1.0 + * @param ignore_imu = false Whether or not to use the Inertial for determining angle. + * Will instead use circumference formula + robot's wheelbase + encoders to determine. + * + * @return whether or not the robot has finished the maneuver + */ +bool MecanumDrive::auto_turn(double degrees, double speed, bool ignore_imu) { // Make sure the configurations exist before continuing - if(config == NULL || turn_pid == NULL) - { + if (config == NULL || turn_pid == NULL) { fprintf(stderr, "Failed to run MecanumDrive::auto_turn - Missing mecanumdrive_config_t in constructor\n"); return true; } @@ -229,16 +208,13 @@ bool MecanumDrive::auto_turn(double degrees, double speed, bool ignore_imu) ignore_imu = ignore_imu || (this->imu == NULL); // INITIALIZE - clear encoders / imu / pid loops - if(init == true) - { - if(ignore_imu) - { + if (init == true) { + if (ignore_imu) { this->left_front.resetPosition(); this->right_front.resetPosition(); this->left_rear.resetPosition(); this->right_rear.resetPosition(); - }else - { + } else { this->imu->resetRotation(); } @@ -253,15 +229,14 @@ bool MecanumDrive::auto_turn(double degrees, double speed, bool ignore_imu) double current_angle = 0.0; - if(ignore_imu) - { - double avg = (left_front.position(rotationUnits::rev) + left_rear.position(rotationUnits::rev) - - right_front.position(rotationUnits::rev) - right_rear.position(rotationUnits::rev)) / 4.0; + if (ignore_imu) { + double avg = (left_front.position(rotationUnits::rev) + left_rear.position(rotationUnits::rev) - + right_front.position(rotationUnits::rev) - right_rear.position(rotationUnits::rev)) / + 4.0; // Current arclength = (avg * wheel_diam * PI) = (theta * (wheelbase / 2.0)). then convert to degrees current_angle = (360.0 * avg * config->drive_wheel_diam) / config->wheelbase_width; - } else - { + } else { current_angle = imu->rotation(); } @@ -269,8 +244,7 @@ bool MecanumDrive::auto_turn(double degrees, double speed, bool ignore_imu) this->drive_raw(0, 0, turn_pid->get()); // We have reached the target. - if(this->turn_pid->is_on_target()) - { + if (this->turn_pid->is_on_target()) { this->drive_raw(0, 0, 0); init = true; return true; diff --git a/src/subsystems/odometry/odometry_3wheel.cpp b/src/subsystems/odometry/odometry_3wheel.cpp index 4715559..e7cbf20 100644 --- a/src/subsystems/odometry/odometry_3wheel.cpp +++ b/src/subsystems/odometry/odometry_3wheel.cpp @@ -1,218 +1,217 @@ #include "../core/include/subsystems/odometry/odometry_3wheel.h" -#include "../core/include/utils/vector2d.h" #include "../core/include/utils/math_util.h" +#include "../core/include/utils/vector2d.h" -Odometry3Wheel::Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, odometry3wheel_cfg_t &cfg, bool is_async) -: OdometryBase(is_async), lside_fwd(lside_fwd), rside_fwd(rside_fwd), off_axis(off_axis), cfg(cfg) -{} +Odometry3Wheel::Odometry3Wheel(CustomEncoder &lside_fwd, CustomEncoder &rside_fwd, CustomEncoder &off_axis, + odometry3wheel_cfg_t &cfg, bool is_async) + : OdometryBase(is_async), lside_fwd(lside_fwd), rside_fwd(rside_fwd), off_axis(off_axis), cfg(cfg) {} /** * Update the current position of the robot once, using the current state of * the encoders and the previous known location - * + * * @return the robot's updated position */ -pose_t Odometry3Wheel::update() -{ - static double lside_old=0, rside_old=0, offax_old=0; - - double lside = lside_fwd.position(deg); - double rside = rside_fwd.position(deg); - double offax = off_axis.position(deg); - - double lside_delta = lside - lside_old; - double rside_delta = rside - rside_old; - double offax_delta = offax - offax_old; - - lside_old = lside; - rside_old = rside; - offax_old = offax; - - pose_t updated_pos = calculate_new_pos(lside_delta, rside_delta, offax_delta, current_pos, cfg); - - static pose_t last_pos = updated_pos; - static double last_speed = 0; - static double last_ang_speed = 0; - static timer tmr; - - double speed_local = 0; - double accel_local = 0; - double ang_speed_local = 0; - double ang_accel_local = 0; - bool update_vel_accel = tmr.time(sec) > 0.1; - - // This loop runs too fast. Only check at LEAST every 1/10th sec - if(update_vel_accel) - { - // Calculate robot velocity - speed_local = pos_diff(updated_pos, last_pos) / tmr.time(sec); - - // Calculate robot acceleration - accel_local = (speed_local - last_speed) / tmr.time(sec); - - // Calculate robot angular velocity (deg/sec) - ang_speed_local = smallest_angle(updated_pos.rot, last_pos.rot) / tmr.time(sec); - - // Calculate robot angular acceleration (deg/sec^2) - ang_accel_local = (ang_speed_local - last_ang_speed) / tmr.time(sec); - - tmr.reset(); - last_pos = updated_pos; - last_speed = speed_local; - last_ang_speed = ang_speed_local; - } - - this->current_pos = updated_pos; - if(update_vel_accel) - { - this->speed = speed_local; - this->accel = accel_local; - this->ang_speed_deg = ang_speed_local; - this->ang_accel_deg = ang_accel_local; - } - - return current_pos; +pose_t Odometry3Wheel::update() { + static double lside_old = 0, rside_old = 0, offax_old = 0; + + double lside = lside_fwd.position(deg); + double rside = rside_fwd.position(deg); + double offax = off_axis.position(deg); + + double lside_delta = lside - lside_old; + double rside_delta = rside - rside_old; + double offax_delta = offax - offax_old; + + lside_old = lside; + rside_old = rside; + offax_old = offax; + + pose_t updated_pos = calculate_new_pos(lside_delta, rside_delta, offax_delta, current_pos, cfg); + + static pose_t last_pos = updated_pos; + static double last_speed = 0; + static double last_ang_speed = 0; + static timer tmr; + + double speed_local = 0; + double accel_local = 0; + double ang_speed_local = 0; + double ang_accel_local = 0; + bool update_vel_accel = tmr.time(sec) > 0.1; + + // This loop runs too fast. Only check at LEAST every 1/10th sec + if (update_vel_accel) { + // Calculate robot velocity + speed_local = pos_diff(updated_pos, last_pos) / tmr.time(sec); + + // Calculate robot acceleration + accel_local = (speed_local - last_speed) / tmr.time(sec); + + // Calculate robot angular velocity (deg/sec) + ang_speed_local = smallest_angle(updated_pos.rot, last_pos.rot) / tmr.time(sec); + + // Calculate robot angular acceleration (deg/sec^2) + ang_accel_local = (ang_speed_local - last_ang_speed) / tmr.time(sec); + + tmr.reset(); + last_pos = updated_pos; + last_speed = speed_local; + last_ang_speed = ang_speed_local; + } + + this->current_pos = updated_pos; + if (update_vel_accel) { + this->speed = speed_local; + this->accel = accel_local; + this->ang_speed_deg = ang_speed_local; + this->ang_accel_deg = ang_accel_local; + } + + return current_pos; } /** - * Calculation method for the robot's new position using the change in encoders, the old position, and the robot's configuration. - * This uses a series of arclength formulae for finding distance driven and change in angle. - * Then vector math is used to combine it with the robot's old position data - * + * Calculation method for the robot's new position using the change in encoders, the old position, and the robot's + * configuration. This uses a series of arclength formulae for finding distance driven and change in angle. Then vector + * math is used to combine it with the robot's old position data + * * @param lside_delta_deg Left encoder change in rotation, in degrees * @param rside_delta_deg Right encoder change in rotation, in degrees * @param offax_delta_deg Off-axis (perpendicular) encoder change in rotation, in degrees * @param old_pos Robot's old position, for integration * @param cfg Data on robot's configuration (wheel diameter, wheelbase, off-axis distance from center) - * @return The robot's new position (x, y, rot) + * @return The robot's new position (x, y, rot) */ -pose_t Odometry3Wheel::calculate_new_pos(double lside_delta_deg, double rside_delta_deg, double offax_delta_deg, pose_t old_pos, odometry3wheel_cfg_t cfg) -{ - pose_t retval = {}; - - // Arclength formula for encoder degrees -> single wheel distance driven - double lside_dist = (cfg.wheel_diam / 2.0) * deg2rad(lside_delta_deg); - double rside_dist = (cfg.wheel_diam / 2.0) * deg2rad(rside_delta_deg); - double offax_dist = (cfg.wheel_diam / 2.0) * deg2rad(offax_delta_deg); - - // Inverse arclength formula for arc distance driven -> robot angle - double delta_angle_rad = (rside_dist - lside_dist) / cfg.wheelbase_dist; - double delta_angle_deg = rad2deg(delta_angle_rad); - - // Distance along the robot's local Y axis (forward/backward) - double dist_local_y = (lside_dist + rside_dist) / 2.0; - - // Distance along the robot's local X axis (right/left) - double dist_local_x = offax_dist - (delta_angle_rad * cfg.off_axis_center_dist); - - // Change in displacement as a vector, on the local coordinate system (+y = robot fwd) - Vector2D local_displacement({.x=dist_local_x, .y=dist_local_y}); - - // Rotate the local displacement to match the old robot's rotation - double dir_delta_from_trans_rad = local_displacement.get_dir() - (PI/2.0); - double global_dir_rad = wrap_angle_rad(dir_delta_from_trans_rad + deg2rad(old_pos.rot)); - Vector2D global_displacement(global_dir_rad, local_displacement.get_mag()); - - // Tack on the position change to the old position - Vector2D old_pos_vec({.x=old_pos.x, .y=old_pos.y}); - Vector2D new_pos_vec = old_pos_vec + global_displacement; - - retval.x = new_pos_vec.get_x(); - retval.y = new_pos_vec.get_y(); - retval.rot = wrap_angle_deg(old_pos.rot + delta_angle_deg); - - return retval; +pose_t Odometry3Wheel::calculate_new_pos(double lside_delta_deg, double rside_delta_deg, double offax_delta_deg, + pose_t old_pos, odometry3wheel_cfg_t cfg) { + pose_t retval = {}; + + // Arclength formula for encoder degrees -> single wheel distance driven + double lside_dist = (cfg.wheel_diam / 2.0) * deg2rad(lside_delta_deg); + double rside_dist = (cfg.wheel_diam / 2.0) * deg2rad(rside_delta_deg); + double offax_dist = (cfg.wheel_diam / 2.0) * deg2rad(offax_delta_deg); + + // Inverse arclength formula for arc distance driven -> robot angle + double delta_angle_rad = (rside_dist - lside_dist) / cfg.wheelbase_dist; + double delta_angle_deg = rad2deg(delta_angle_rad); + + // Distance along the robot's local Y axis (forward/backward) + double dist_local_y = (lside_dist + rside_dist) / 2.0; + + // Distance along the robot's local X axis (right/left) + double dist_local_x = offax_dist - (delta_angle_rad * cfg.off_axis_center_dist); + + // Change in displacement as a vector, on the local coordinate system (+y = robot fwd) + Vector2D local_displacement({.x = dist_local_x, .y = dist_local_y}); + + // Rotate the local displacement to match the old robot's rotation + double dir_delta_from_trans_rad = local_displacement.get_dir() - (PI / 2.0); + double global_dir_rad = wrap_angle_rad(dir_delta_from_trans_rad + deg2rad(old_pos.rot)); + Vector2D global_displacement(global_dir_rad, local_displacement.get_mag()); + + // Tack on the position change to the old position + Vector2D old_pos_vec({.x = old_pos.x, .y = old_pos.y}); + Vector2D new_pos_vec = old_pos_vec + global_displacement; + + retval.x = new_pos_vec.get_x(); + retval.y = new_pos_vec.get_y(); + retval.rot = wrap_angle_deg(old_pos.rot + delta_angle_deg); + + return retval; } /** * A guided tuning process to automatically find tuning parameters. * This method is blocking, and returns when tuning has finished. Follow * the instructions on the controller to complete the tuning process - * + * * It is assumed the gear ratio and encoder PPR have been set correctly - * + * */ -void Odometry3Wheel::tune(vex::controller &con, TankDrive &drive) -{ - - // TODO check if all the messages fit on the controller screen - // STEP 1: Align robot and reset odometry - con.Screen.clearScreen(); - con.Screen.setCursor(1,1); - con.Screen.print("Wheel Diameter Test"); - con.Screen.newLine(); - con.Screen.print("Align robot with ref"); - con.Screen.newLine(); - con.Screen.newLine(); - con.Screen.print("Press A to continue"); - while(!con.ButtonA.pressing()) { vexDelay(20); } - - double old_lval = lside_fwd.position(deg); - double old_rval = rside_fwd.position(deg); - - // Step 2: Drive robot a known distance - con.Screen.clearLine(2); - con.Screen.setCursor(2,1); - con.Screen.print("Drive or Push robot"); - con.Screen.newLine(); - con.Screen.print("10 feet (5 tiles)"); - con.Screen.newLine(); - con.Screen.print("Press A to continue"); - while(!con.ButtonA.pressing()) - { - drive.drive_arcade(con.Axis3.position() / 100.0, con.Axis1.position() / 100.0); - vexDelay(20); - } - - // Wheel diameter is ratio of expected distance / measured distance - double avg_deg = ((lside_fwd.position(deg) - old_lval) + (rside_fwd.position(deg) - old_rval)) / 2.0; - double measured_dist = 0.5 * deg2rad(avg_deg); // Simulate diam=1", radius=1/2" - double found_diam = 120.0 / measured_dist; - - // Step 3: Reset alignment for turning test - con.Screen.clearScreen(); - con.Screen.setCursor(1,1); - con.Screen.print("Wheelbase Test"); - con.Screen.newLine(); - con.Screen.print("Align robot with ref"); - con.Screen.newLine(); - con.Screen.newLine(); - con.Screen.print("Press A to continue"); - while(!con.ButtonA.pressing()) { vexDelay(20); } - con.Screen.clearScreen(); - - old_lval = lside_fwd.position(deg); - old_rval = rside_fwd.position(deg); - double old_offax = off_axis.position(deg); - - con.Screen.setCursor(2,1); - con.Screen.clearLine(); - con.Screen.print("Turn robot 10"); - con.Screen.newLine(); - con.Screen.print("times in place"); - con.Screen.newLine(); - con.Screen.print("Press A to continue"); - while(!con.ButtonA.pressing()) - { - drive.drive_arcade(0, con.Axis1.position() / 100.0); - vexDelay(20); - } - - double lside_dist = deg2rad(lside_fwd.position(deg) - old_lval) * (found_diam / 2.0); - double rside_dist = deg2rad(rside_fwd.position(deg) - old_rval) * (found_diam / 2.0); - double offax_dist = deg2rad(off_axis.position(deg) - old_offax) * (found_diam / 2.0); - - double expected_angle = 10 * (2*PI); - double found_wheelbase = fabs(rside_dist - lside_dist) / expected_angle; - double found_offax_center_dist = offax_dist / expected_angle; - - con.Screen.clearScreen(); - con.Screen.setCursor(1,1); - con.Screen.print("Diam: %f", found_diam); - con.Screen.newLine(); - con.Screen.print("whlbase: %f", found_wheelbase); - con.Screen.newLine(); - con.Screen.print("offax: %f", found_offax_center_dist); - - printf("Tuning completed.\n Wheel Diameter: %f\n Wheelbase: %f\n Off Axis Distance: %f\n", found_diam, found_wheelbase, found_offax_center_dist); +void Odometry3Wheel::tune(vex::controller &con, TankDrive &drive) { + + // TODO check if all the messages fit on the controller screen + // STEP 1: Align robot and reset odometry + con.Screen.clearScreen(); + con.Screen.setCursor(1, 1); + con.Screen.print("Wheel Diameter Test"); + con.Screen.newLine(); + con.Screen.print("Align robot with ref"); + con.Screen.newLine(); + con.Screen.newLine(); + con.Screen.print("Press A to continue"); + while (!con.ButtonA.pressing()) { + vexDelay(20); + } + + double old_lval = lside_fwd.position(deg); + double old_rval = rside_fwd.position(deg); + + // Step 2: Drive robot a known distance + con.Screen.clearLine(2); + con.Screen.setCursor(2, 1); + con.Screen.print("Drive or Push robot"); + con.Screen.newLine(); + con.Screen.print("10 feet (5 tiles)"); + con.Screen.newLine(); + con.Screen.print("Press A to continue"); + while (!con.ButtonA.pressing()) { + drive.drive_arcade(con.Axis3.position() / 100.0, con.Axis1.position() / 100.0); + vexDelay(20); + } + + // Wheel diameter is ratio of expected distance / measured distance + double avg_deg = ((lside_fwd.position(deg) - old_lval) + (rside_fwd.position(deg) - old_rval)) / 2.0; + double measured_dist = 0.5 * deg2rad(avg_deg); // Simulate diam=1", radius=1/2" + double found_diam = 120.0 / measured_dist; + + // Step 3: Reset alignment for turning test + con.Screen.clearScreen(); + con.Screen.setCursor(1, 1); + con.Screen.print("Wheelbase Test"); + con.Screen.newLine(); + con.Screen.print("Align robot with ref"); + con.Screen.newLine(); + con.Screen.newLine(); + con.Screen.print("Press A to continue"); + while (!con.ButtonA.pressing()) { + vexDelay(20); + } + con.Screen.clearScreen(); + + old_lval = lside_fwd.position(deg); + old_rval = rside_fwd.position(deg); + double old_offax = off_axis.position(deg); + + con.Screen.setCursor(2, 1); + con.Screen.clearLine(); + con.Screen.print("Turn robot 10"); + con.Screen.newLine(); + con.Screen.print("times in place"); + con.Screen.newLine(); + con.Screen.print("Press A to continue"); + while (!con.ButtonA.pressing()) { + drive.drive_arcade(0, con.Axis1.position() / 100.0); + vexDelay(20); + } + + double lside_dist = deg2rad(lside_fwd.position(deg) - old_lval) * (found_diam / 2.0); + double rside_dist = deg2rad(rside_fwd.position(deg) - old_rval) * (found_diam / 2.0); + double offax_dist = deg2rad(off_axis.position(deg) - old_offax) * (found_diam / 2.0); + + double expected_angle = 10 * (2 * PI); + double found_wheelbase = fabs(rside_dist - lside_dist) / expected_angle; + double found_offax_center_dist = offax_dist / expected_angle; + + con.Screen.clearScreen(); + con.Screen.setCursor(1, 1); + con.Screen.print("Diam: %f", found_diam); + con.Screen.newLine(); + con.Screen.print("whlbase: %f", found_wheelbase); + con.Screen.newLine(); + con.Screen.print("offax: %f", found_offax_center_dist); + + printf("Tuning completed.\n Wheel Diameter: %f\n Wheelbase: %f\n Off Axis Distance: %f\n", found_diam, + found_wheelbase, found_offax_center_dist); } \ No newline at end of file diff --git a/src/subsystems/odometry/odometry_base.cpp b/src/subsystems/odometry/odometry_base.cpp index 15981ae..9b4d7eb 100644 --- a/src/subsystems/odometry/odometry_base.cpp +++ b/src/subsystems/odometry/odometry_base.cpp @@ -6,8 +6,7 @@ * * @param is_async True to run constantly in the background, false to call update() manually */ -OdometryBase::OdometryBase(bool is_async) : current_pos(zero_pos) -{ +OdometryBase::OdometryBase(bool is_async) : current_pos(zero_pos) { if (is_async) { handle = new vex::task(background_task, (void *)this); } @@ -20,12 +19,10 @@ OdometryBase::OdometryBase(bool is_async) : current_pos(zero_pos) * @param ptr Pointer to OdometryBase object * @return Required integer return code. Unused. */ -int OdometryBase::background_task(void *ptr) -{ +int OdometryBase::background_task(void *ptr) { OdometryBase &obj = *((OdometryBase *)ptr); vexDelay(1000); - while (!obj.end_task) - { + while (!obj.end_task) { obj.mut.lock(); obj.update(); obj.mut.unlock(); @@ -39,16 +36,12 @@ int OdometryBase::background_task(void *ptr) * If the user wants to end the thread but keep the data up to date, * they must run the update() function manually from then on. */ -void OdometryBase::end_async() -{ - this->end_task = true; -} +void OdometryBase::end_async() { this->end_task = true; } /** * Gets the current position and rotation */ -pose_t OdometryBase::get_position(void) -{ +pose_t OdometryBase::get_position(void) { mut.lock(); // Create a new struct to pass-by-value @@ -62,8 +55,7 @@ pose_t OdometryBase::get_position(void) /** * Sets the current position of the robot */ -void OdometryBase::set_position(const pose_t &newpos) -{ +void OdometryBase::set_position(const pose_t &newpos) { mut.lock(); current_pos = newpos; @@ -71,10 +63,11 @@ void OdometryBase::set_position(const pose_t &newpos) mut.unlock(); } -AutoCommand *OdometryBase::SetPositionCmd(const pose_t &newpos) -{ - return new FunctionCommand([&](){set_position(newpos); return true;}); - +AutoCommand *OdometryBase::SetPositionCmd(const pose_t &newpos) { + return new FunctionCommand([&]() { + set_position(newpos); + return true; + }); } /** @@ -83,8 +76,7 @@ AutoCommand *OdometryBase::SetPositionCmd(const pose_t &newpos) * @param end_pos to this point * @return the euclidean distance between start_pos and end_pos */ -double OdometryBase::pos_diff(pose_t start_pos, pose_t end_pos) -{ +double OdometryBase::pos_diff(pose_t start_pos, pose_t end_pos) { // Use the pythagorean theorem double retval = sqrt(pow(end_pos.x - start_pos.x, 2) + pow(end_pos.y - start_pos.y, 2)); @@ -94,35 +86,30 @@ double OdometryBase::pos_diff(pose_t start_pos, pose_t end_pos) /** * Get the change in rotation between two points */ -double OdometryBase::rot_diff(pose_t pos1, pose_t pos2) -{ - return pos1.rot - pos2.rot; -} +double OdometryBase::rot_diff(pose_t pos1, pose_t pos2) { return pos1.rot - pos2.rot; } /** * Get the smallest difference in angle between a start heading and end heading. * Returns the difference between -180 degrees and +180 degrees, representing the robot * turning left or right, respectively. */ -double OdometryBase::smallest_angle(double start_deg, double end_deg) -{ +double OdometryBase::smallest_angle(double start_deg, double end_deg) { double retval; // get the difference between 0 and 360 retval = fmod(end_deg - start_deg, 360.0); if (retval < 0) { retval += 360.0; -} + } // Get the closest angle, now between -180 (turn left) and +180 (turn right) if (retval > 180) { retval -= 360; -} + } return retval; } -double OdometryBase::get_speed() -{ +double OdometryBase::get_speed() { mut.lock(); double retval = speed; mut.unlock(); @@ -130,8 +117,7 @@ double OdometryBase::get_speed() return retval; } -double OdometryBase::get_accel() -{ +double OdometryBase::get_accel() { mut.lock(); double retval = accel; mut.unlock(); @@ -139,8 +125,7 @@ double OdometryBase::get_accel() return retval; } -double OdometryBase::get_angular_speed_deg() -{ +double OdometryBase::get_angular_speed_deg() { mut.lock(); double retval = ang_speed_deg; mut.unlock(); @@ -148,8 +133,7 @@ double OdometryBase::get_angular_speed_deg() return retval; } -double OdometryBase::get_angular_accel_deg() -{ +double OdometryBase::get_angular_accel_deg() { mut.lock(); double retval = ang_accel_deg; mut.unlock(); diff --git a/src/subsystems/odometry/odometry_tank.cpp b/src/subsystems/odometry/odometry_tank.cpp index b910cff..b0a397d 100644 --- a/src/subsystems/odometry/odometry_tank.cpp +++ b/src/subsystems/odometry/odometry_tank.cpp @@ -4,47 +4,52 @@ * Initialize the Odometry module, calculating position from the drive motors. * @param left_side The left motors * @param right_side The right motors - * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what + * is contained * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. - * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have + * to manually call update(). */ -OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, vex::inertial *imu, bool is_async) - : OdometryBase(is_async), left_side(&left_side), right_side(&right_side), left_custom_enc(NULL), right_custom_enc(NULL), left_vex_enc(NULL), right_vex_enc(NULL), imu(imu), config(config) -{ -} +OdometryTank::OdometryTank(vex::motor_group &left_side, vex::motor_group &right_side, robot_specs_t &config, + vex::inertial *imu, bool is_async) + : OdometryBase(is_async), left_side(&left_side), right_side(&right_side), left_custom_enc(NULL), + right_custom_enc(NULL), left_vex_enc(NULL), right_vex_enc(NULL), imu(imu), config(config) {} /** * Initialize the Odometry module, calculating position from the drive motors. * @param left_custom_enc The left custom encoder * @param right_custom_enc The right custom encoder - * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what + * is contained * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. - * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have + * to manually call update(). */ -OdometryTank::OdometryTank(CustomEncoder &left_custom_enc, CustomEncoder &right_custom_enc, robot_specs_t &config, vex::inertial *imu, bool is_async) - : OdometryBase(is_async), left_side(NULL), right_side(NULL), left_custom_enc(&left_custom_enc), right_custom_enc(&right_custom_enc), left_vex_enc(NULL), right_vex_enc(NULL), imu(imu), config(config) -{ -} +OdometryTank::OdometryTank(CustomEncoder &left_custom_enc, CustomEncoder &right_custom_enc, robot_specs_t &config, + vex::inertial *imu, bool is_async) + : OdometryBase(is_async), left_side(NULL), right_side(NULL), left_custom_enc(&left_custom_enc), + right_custom_enc(&right_custom_enc), left_vex_enc(NULL), right_vex_enc(NULL), imu(imu), config(config) {} /** * Initialize the Odometry module, calculating position from the drive motors. * @param left_vex_enc The left vex encoder * @param right_vex_enc The right vex encoder - * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what is contained + * @param config the specifications that supply the odometry with descriptions of the robot. See robot_specs_t for what + * is contained * @param imu The robot's inertial sensor. If not included, rotation is calculated from the encoders. - * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have to manually call update(). + * @param is_async If true, position will be updated in the background continuously. If false, the programmer will have + * to manually call update(). */ -OdometryTank::OdometryTank(vex::encoder &left_vex_enc, vex::encoder &right_vex_enc, robot_specs_t &config, vex::inertial *imu, bool is_async) - : OdometryBase(is_async), left_side(NULL), right_side(NULL), left_custom_enc(NULL), right_custom_enc(NULL), left_vex_enc(&left_vex_enc), right_vex_enc(&right_vex_enc), imu(imu), config(config) -{ -} +OdometryTank::OdometryTank(vex::encoder &left_vex_enc, vex::encoder &right_vex_enc, robot_specs_t &config, + vex::inertial *imu, bool is_async) + : OdometryBase(is_async), left_side(NULL), right_side(NULL), left_custom_enc(NULL), right_custom_enc(NULL), + left_vex_enc(&left_vex_enc), right_vex_enc(&right_vex_enc), imu(imu), config(config) {} /** * Resets the position and rotational data to the input. * */ -void OdometryTank::set_position(const pose_t &newpos) -{ +void OdometryTank::set_position(const pose_t &newpos) { mut.lock(); rotation_offset = newpos.rot - (current_pos.rot - rotation_offset); mut.unlock(); @@ -56,22 +61,16 @@ void OdometryTank::set_position(const pose_t &newpos) * Update, store and return the current position of the robot. Only use if not initializing * with a separate thread. */ -pose_t OdometryTank::update() -{ +pose_t OdometryTank::update() { double lside_revs = 0, rside_revs = 0; - if (left_side != NULL && right_side != NULL) - { + if (left_side != NULL && right_side != NULL) { lside_revs = left_side->position(vex::rotationUnits::rev) / config.odom_gear_ratio; rside_revs = right_side->position(vex::rotationUnits::rev) / config.odom_gear_ratio; - } - else if (left_custom_enc != NULL && right_custom_enc != NULL) - { + } else if (left_custom_enc != NULL && right_custom_enc != NULL) { lside_revs = left_custom_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; rside_revs = right_custom_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; - } - else if (left_vex_enc != NULL && right_vex_enc != NULL) - { + } else if (left_vex_enc != NULL && right_vex_enc != NULL) { lside_revs = left_vex_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; rside_revs = right_vex_enc->position(vex::rotationUnits::rev) / config.odom_gear_ratio; } @@ -79,8 +78,7 @@ pose_t OdometryTank::update() double angle = 0; // If the IMU data was passed in, use it for rotational data - if (imu == NULL || imu->installed() == false) - { + if (imu == NULL || imu->installed() == false) { // Get the difference in distance driven between the two sides // Uses the absolute position of the encoders, so resetting them will result in // a bad angle. @@ -91,9 +89,7 @@ pose_t OdometryTank::update() angle = ((180.0 / PI) * (distance_diff / config.dist_between_wheels)) + 90; // printf("angle: %f, ", (180.0 / PI) * (distance_diff / config.dist_between_wheels)); - } - else - { + } else { // Translate "0 forward and clockwise positive" to "90 forward and CCW negative" angle = -imu->rotation(vex::rotationUnits::deg) + 90; } @@ -106,7 +102,7 @@ pose_t OdometryTank::update() angle = fmod(angle, 360.0); if (angle < 0) { angle += 360; -} + } current_pos = calculate_new_pos(config, current_pos, lside_revs, rside_revs, angle); @@ -117,8 +113,7 @@ pose_t OdometryTank::update() bool update_vel_accel = tmr.time(sec) > 0.02; // This loop runs too fast. Only check at LEAST every 1/10th sec - if (update_vel_accel) - { + if (update_vel_accel) { // Calculate robot velocity double this_speed = pos_diff(current_pos, last_pos) / tmr.time(sec); ema.add_entry(this_speed); @@ -145,8 +140,8 @@ pose_t OdometryTank::update() * Using information about the robot's mechanical structure and sensors, calculate a new position * of the robot, relative to when this method was previously ran. */ -pose_t OdometryTank::calculate_new_pos(robot_specs_t &config, pose_t &curr_pos, double lside_revs, double rside_revs, double angle_deg) -{ +pose_t OdometryTank::calculate_new_pos(robot_specs_t &config, pose_t &curr_pos, double lside_revs, double rside_revs, + double angle_deg) { pose_t new_pos; static double stored_lside_revs = lside_revs; diff --git a/src/subsystems/screen.cpp b/src/subsystems/screen.cpp index 6518bd0..336858d 100644 --- a/src/subsystems/screen.cpp +++ b/src/subsystems/screen.cpp @@ -30,8 +30,7 @@ void draw_widget(vex::brain::lcd &scr, WidgetConfig &widget, ScreenRect rect) { * you probably shouldnt have to use it */ struct ScreenData { - ScreenData(const std::vector &m_pages, int m_page, - vex::brain::lcd &m_screen) + ScreenData(const std::vector &m_pages, int m_page, vex::brain::lcd &m_screen) : pages(m_pages), page(m_page), screen(m_screen) {} std::vector pages; int page = 0; @@ -50,8 +49,7 @@ static ScreenData *screen_data_ptr; /// @param screen the brain screen /// @param pages the list of pages in your UI slideshow /// @param first_page the page to start on (by default 0) -void start_screen(vex::brain::lcd &screen, std::vector pages, - int first_page) { +void start_screen(vex::brain::lcd &screen, std::vector pages, int first_page) { if (pages.size() == 0) { printf("No pages, not starting screen"); return; @@ -65,8 +63,7 @@ void start_screen(vex::brain::lcd &screen, std::vector pages, ScreenData *data = new ScreenData{pages, first_page, screen}; - screen_thread = - new vex::thread(screen_thread_func, static_cast(data)); + screen_thread = new vex::thread(screen_thread_func, static_cast(data)); } void stop_screen() { running = false; } @@ -81,6 +78,10 @@ void next_page() { screen_data_ptr->page++; screen_data_ptr->page %= screen_data_ptr->pages.size(); } +void goto_page(size_t page) { + screen_data_ptr->page = page; + screen_data_ptr->page %= screen_data_ptr->pages.size(); +} /** * @brief runs the screen thread @@ -162,28 +163,22 @@ int screen_thread_func(void *screen_data_v) { * @param update_f drawing function * @param draw_f drawing function */ -FunctionPage::FunctionPage(update_func_t update_f, draw_func_t draw_f) - : update_f(update_f), draw_f(draw_f) {} +FunctionPage::FunctionPage(update_func_t update_f, draw_func_t draw_f) : update_f(update_f), draw_f(draw_f) {} /// @brief update uses the supplied update function to update this page -void FunctionPage::update(bool was_pressed, int x, int y) { - update_f(was_pressed, x, y); -} +void FunctionPage::update(bool was_pressed, int x, int y) { update_f(was_pressed, x, y); } /// @brief draw uses the supplied draw function to draw to the screen -void FunctionPage::draw(vex::brain::lcd &screen, bool first_draw, - unsigned int frame_number) { +void FunctionPage::draw(vex::brain::lcd &screen, bool first_draw, unsigned int frame_number) { draw_f(screen, first_draw, frame_number); } -StatsPage::StatsPage(std::map motors) - : motors(motors) {} +StatsPage::StatsPage(std::map motors) : motors(motors) {} void StatsPage::update(bool was_pressed, int x, int y) { (void)x; (void)y; (void)was_pressed; } -void StatsPage::draw_motor_stats(const std::string &name, vex::motor &mot, - unsigned int frame, int x, int y, +void StatsPage::draw_motor_stats(const std::string &name, vex::motor &mot, unsigned int frame, int x, int y, vex::brain::lcd &scr) { const vex::color hot_col = vex::color(120, 0, 0); const vex::color med_col = vex::color(140, 100, 0); @@ -207,8 +202,7 @@ void StatsPage::draw_motor_stats(const std::string &name, vex::motor &mot, } scr.drawRectangle(x, y, row_width, row_height, col); - scr.printAt(x + 2, y + 16, false, " %2d %2.0fC %.7s", port, temp, - name.c_str()); + scr.printAt(x + 2, y + 16, false, " %2d %2.0fC %.7s", port, temp, name.c_str()); } void StatsPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], unsigned int frame_number [[maybe_unused]]) { @@ -235,12 +229,10 @@ void StatsPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], } vex::brain b; scr.printAt(50, 220, "Battery: %2.1fv %2.0fC %d%%", b.Battery.voltage(), - b.Battery.temperature(vex::temperatureUnits::celsius), - b.Battery.capacity()); + b.Battery.temperature(vex::temperatureUnits::celsius), b.Battery.capacity()); } -OdometryPage::OdometryPage(OdometryBase &odom, double width, double height, - bool do_trail) +OdometryPage::OdometryPage(OdometryBase &odom, double width, double height, bool do_trail) : odom(odom), robot_width(width), robot_height(height), do_trail(do_trail), velocity_graph(30, 0.0, 0.0, {vex::green}, 1) { vex::brain b; @@ -270,13 +262,10 @@ void OdometryPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], path_index %= path_len; } - auto to_px = [](const point_t p) -> point_t { - return {(double)in_to_px(p.x) + 200, (double)in_to_px(-p.y) + 240}; - }; + auto to_px = [](const point_t p) -> point_t { return {(double)in_to_px(p.x) + 200, (double)in_to_px(-p.y) + 240}; }; auto draw_line = [to_px, &scr](const point_t from, const point_t to) { - scr.drawLine((int)to_px(from).x, (int)to_px(from).y, (int)to_px(to).x, - (int)to_px(to).y); + scr.drawLine((int)to_px(from).x, (int)to_px(from).y, (int)to_px(to).x, (int)to_px(to).y); }; point_t pos = pose.get_point(); @@ -341,8 +330,7 @@ bool SliderWidget::update(bool was_pressed, int x, int y) { double dx = x; double dy = y; if (rect.contains(point_t{dx, dy})) { - double pct = - (dx - rect.min.x - margin) / (rect.dimensions().x - 2 * margin); + double pct = (dx - rect.min.x - margin) / (rect.dimensions().x - 2 * margin); pct = clamp(pct, 0.0, 1.0); value = (low + pct * (high - low)); } @@ -365,8 +353,7 @@ void SliderWidget::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], scr.setFillColor(vex::color(50, 50, 50)); scr.setPenWidth(1); - scr.drawRectangle(rect.min.x, rect.min.y, rect.dimensions().x, - rect.dimensions().y); + scr.drawRectangle(rect.min.x, rect.min.y, rect.dimensions().x, rect.dimensions().y); scr.setPenColor(vex::color(200, 200, 200)); scr.setPenWidth(4); @@ -378,16 +365,13 @@ void SliderWidget::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], const double handle_width = 4; const double handle_height = 4; - scr.drawRectangle(vx - (handle_width / 2), y - (handle_height / 2), - handle_width, handle_height); + scr.drawRectangle(vx - (handle_width / 2), y - (handle_height / 2), handle_width, handle_height); int text_w = scr.getStringWidth((name + " ").c_str()); - scr.printAt(xmid - text_w / 2, y - 15, false, "%s: %.5f", name.c_str(), - value); + scr.printAt(xmid - text_w / 2, y - 15, false, "%s: %.5f", name.c_str(), value); } bool ButtonWidget::update(bool was_pressed, int x, int y) { - if (was_pressed && !was_pressed_last && - rect.contains({(double)x, (double)y})) { + if (was_pressed && !was_pressed_last && rect.contains({(double)x, (double)y})) { onpress(); was_pressed_last = was_pressed; return true; @@ -413,11 +397,9 @@ PIDPage::PIDPage(PID &pid, std::string name, std::function onchange) i_slider(cfg.i, 0.0, 0.05, Rect{{60, 80}, {180, 120}}, "I"), d_slider(cfg.d, 0.0, 0.05, Rect{{60, 140}, {180, 180}}, "D"), zero_i([this]() { zero_i_f(); }, Rect{{180, 80}, {220, 120}}, "0"), - zero_d([this]() { zero_d_f(); }, Rect{{180, 140}, {220, 180}}, "0"), - graph(40, 0, 0, {vex::red, vex::green}, 2) {} + zero_d([this]() { zero_d_f(); }, Rect{{180, 140}, {220, 180}}, "0"), graph(40, 0, 0, {vex::red, vex::green}, 2) {} -PIDPage::PIDPage(PIDFF &pidff, std::string name, - std::function onchange) +PIDPage::PIDPage(PIDFF &pidff, std::string name, std::function onchange) : PIDPage((pidff.pid), name, onchange) {} void PIDPage::update(bool was_pressed, int x, int y) { @@ -432,8 +414,7 @@ void PIDPage::update(bool was_pressed, int x, int y) { onchange(); } } -void PIDPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], - unsigned int frame_number [[maybe_unused]]) { +void PIDPage::draw(vex::brain::lcd &scr, bool first_draw [[maybe_unused]], unsigned int frame_number [[maybe_unused]]) { p_slider.draw(scr, first_draw, frame_number); i_slider.draw(scr, first_draw, frame_number); d_slider.draw(scr, first_draw, frame_number); diff --git a/src/subsystems/tank_drive.cpp b/src/subsystems/tank_drive.cpp index 3c33872..5721b58 100644 --- a/src/subsystems/tank_drive.cpp +++ b/src/subsystems/tank_drive.cpp @@ -1,145 +1,188 @@ -#include "../core/include/utils/geometry.h" #include "../core/include/subsystems/tank_drive.h" -#include "../core/include/utils/math_util.h" -#include "../core/include/utils/controls/pidff.h" #include "../core/include/utils/command_structure/drive_commands.h" +#include "../core/include/utils/controls/pidff.h" +#include "../core/include/utils/geometry.h" +#include "../core/include/utils/math_util.h" TankDrive::TankDrive(motor_group &left_motors, motor_group &right_motors, robot_specs_t &config, OdometryBase *odom) - : left_motors(left_motors), right_motors(right_motors), correction_pid(config.correction_pid), odometry(odom), config(config) -{ + : left_motors(left_motors), right_motors(right_motors), correction_pid(config.correction_pid), odometry(odom), + config(config) { drive_default_feedback = config.drive_feedback; turn_default_feedback = config.turn_feedback; } -AutoCommand *TankDrive::DriveToPointCmd(Feedback &fb, point_t pt, vex::directionType dir, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::DriveToPointCmd(Feedback &fb, point_t pt, vex::directionType dir, double max_speed, + double end_speed) { return new DriveToPointCommand(*this, fb, pt, dir, max_speed, end_speed); } -AutoCommand *TankDrive::DriveToPointCmd(point_t pt, vex::directionType dir, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::DriveToPointCmd(point_t pt, vex::directionType dir, double max_speed, double end_speed) { return new DriveToPointCommand(*this, *drive_default_feedback, pt, dir, max_speed, end_speed); } -AutoCommand *TankDrive::DriveForwardCmd(double dist, vex::directionType dir, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::DriveForwardCmd(double dist, vex::directionType dir, double max_speed, double end_speed) { return new DriveForwardCommand(*this, *drive_default_feedback, dist, dir, max_speed, end_speed); } -AutoCommand *TankDrive::DriveForwardCmd(Feedback &fb, double dist, vex::directionType dir, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::DriveForwardCmd(Feedback &fb, double dist, vex::directionType dir, double max_speed, + double end_speed) { return new DriveForwardCommand(*this, fb, dist, dir, max_speed, end_speed); } -AutoCommand *TankDrive::TurnToHeadingCmd(double heading, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::TurnToHeadingCmd(double heading, double max_speed, double end_speed) { return new TurnToHeadingCommand(*this, *turn_default_feedback, heading, max_speed, end_speed); } -AutoCommand *TankDrive::TurnToHeadingCmd(Feedback &fb, double heading, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::TurnToHeadingCmd(Feedback &fb, double heading, double max_speed, double end_speed) { return new TurnToHeadingCommand(*this, fb, heading, max_speed, end_speed); } -AutoCommand *TankDrive::TurnDegreesCmd(double degrees, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::TurnToPointCmd(double x, double y, vex::directionType dir, double max_speed, double end_speed) { + class TurnToPointCmd : public AutoCommand { + public: + TurnToPointCmd(TankDrive &td, double x, double y, vex::directionType dir, double max_speed, double end_speed) + : td(td), x(x), y(y), dir(dir), max_speed(max_speed), end_speed(end_speed), func_initialized(false) {} + bool run() override { + if (!func_initialized) { + pose_t pose = td.odometry->get_position(); + double dy = y - pose.y; + double dx = x - pose.x; + heading = rad2deg(atan2(dy, dx)); + if (dir != vex::directionType::fwd) { + heading += 90.0; + } + func_initialized = true; + } + return td.turn_to_heading(heading, max_speed, end_speed); + } + void on_timeout() override { td.stop(); } + TankDrive &td; + double x, y; + vex::directionType dir; + double max_speed; + double end_speed; + bool func_initialized; + double heading; + }; + return new TurnToPointCmd(*this, x, y, dir, max_speed, end_speed); +} + +AutoCommand *TankDrive::TurnDegreesCmd(double degrees, double max_speed, double end_speed) { return new TurnDegreesCommand(*this, *turn_default_feedback, degrees, max_speed, end_speed); } -AutoCommand *TankDrive::TurnDegreesCmd(Feedback &fb, double degrees, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::TurnDegreesCmd(Feedback &fb, double degrees, double max_speed, double end_speed) { return new TurnDegreesCommand(*this, fb, degrees, max_speed, end_speed); } -AutoCommand *TankDrive::PurePursuitCmd(PurePursuit::Path path, directionType dir, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::PurePursuitCmd(PurePursuit::Path path, directionType dir, double max_speed, double end_speed) { return new PurePursuitCommand(*this, *drive_default_feedback, path, dir, max_speed, end_speed); } -AutoCommand *TankDrive::PurePursuitCmd(Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed, double end_speed) -{ +AutoCommand *TankDrive::PurePursuitCmd(Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed, + double end_speed) { return new PurePursuitCommand(*this, feedback, path, dir, max_speed, end_speed); } +Condition *TankDrive::DriveStalledCondition(double stall_time) { + class DriveStalledCondition : public Condition { + public: + DriveStalledCondition(TankDrive &td, double stall_time) : td(td), stalled_for(stall_time) {} + bool test() override { + if (!func_initialized) { + stopped_timer.reset(); + func_initialized = true; + } + if (td.odometry->get_speed() > 0) { + stopped_timer.reset(); + } + return stopped_timer.value() > stalled_for; + } + TankDrive &td; + vex::timer stopped_timer; + double stalled_for = 10.0; + bool func_initialized = false; + }; + return new DriveStalledCondition(*this, stall_time); +} +AutoCommand *TankDrive::DriveTankCmd(double left, double right) { + class DriveTankCommand : public AutoCommand { + public: + DriveTankCommand(TankDrive &td, double left, double right) : td(td), left(left), right(right) {} + bool run() override { + td.drive_tank(left, right); + return false; + } + void on_timeout() override { td.stop(); } + TankDrive &td; + double left = 0; + double right = 0; + }; + return new DriveTankCommand(*this, left, right); +} + /** * Reset the initialization for autonomous drive functions */ -void TankDrive::reset_auto() -{ - func_initialized = false; -} +void TankDrive::reset_auto() { func_initialized = false; } /** * Stops rotation of all the motors using their "brake mode" */ -void TankDrive::stop() -{ +void TankDrive::stop() { left_motors.stop(); right_motors.stop(); } -void TankDrive::drive_tank_raw(double left_norm, double right_norm) -{ +void TankDrive::drive_tank_raw(double left_norm, double right_norm) { left_motors.spin(directionType::fwd, left_norm * 12, voltageUnits::volt); right_motors.spin(directionType::fwd, right_norm * 12, voltageUnits::volt); } /** - * Drive the robot using differential style controls. left_motors controls the left motors, - * right_motors controls the right motors. + * Drive the robot using differential style controls. left_motors controls the + * left motors, right_motors controls the right motors. * * left_motors and right_motors are in "percent": -1.0 -> 1.0 */ bool captured_position = false; bool was_breaking = false; -void TankDrive::drive_tank(double left, double right, int power, BrakeType bt) -{ +void TankDrive::drive_tank(double left, double right, int power, BrakeType bt) { left = modify_inputs(left, power); right = modify_inputs(right, power); double brake_threshold = 0.05; bool should_brake = (bt != BrakeType::None) && fabs(left) < brake_threshold && fabs(right) < brake_threshold; - if (!should_brake) - { + if (!should_brake) { drive_tank_raw(left, right); was_breaking = false; return; } - if (should_brake && !was_breaking) - { + if (should_brake && !was_breaking) { captured_position = false; } static PID::pid_config_t zero_vel_cfg = {.p = 0.005, .d = 0.0005}; static PID zero_vel_pid = PID(zero_vel_cfg); - if (bt == BrakeType::ZeroVelocity) - { + if (bt == BrakeType::ZeroVelocity) { zero_vel_pid.set_target(0); double vel = left_motors.velocity(vex::velocityUnits::pct) + right_motors.velocity(vex::velocityUnits::pct); double outp = zero_vel_pid.update(vel); left_motors.spin(directionType::fwd, outp, voltageUnits::volt); right_motors.spin(directionType::fwd, outp, voltageUnits::volt); - } - else if (bt == BrakeType::Smart) - { + } else if (bt == BrakeType::Smart) { static pose_t target_pose = {.x = 0.0, .y = 0.0, .rot = 0.0}; zero_vel_pid.set_target(0); double vel = odometry->get_speed(); - if (fabs(vel) <= 0.01 && !captured_position) - { + if (fabs(vel) <= 0.01 && !captured_position) { target_pose = odometry->get_position(); captured_position = true; - } - else if (captured_position) - { + } else if (captured_position) { double dist_to_target = odometry->pos_diff(target_pose, odometry->get_position()); - if (dist_to_target < 12.0) - { + if (dist_to_target < 12.0) { drive_to_point(target_pose.x, target_pose.y, vex::fwd); } else { target_pose = odometry->get_position(); reset_auto(); } - } - else - { + } else { double outp = zero_vel_pid.update(vel); left_motors.spin(directionType::fwd, outp, voltageUnits::volt); right_motors.spin(directionType::fwd, outp, voltageUnits::volt); @@ -149,13 +192,12 @@ void TankDrive::drive_tank(double left, double right, int power, BrakeType bt) } /** - * Drive the robot using arcade style controls. forward_back controls the linear motion, - * left_right controls the turning. + * Drive the robot using arcade style controls. forward_back controls the linear + * motion, left_right controls the turning. * * left_motors and right_motors are in "percent": -1.0 -> 1.0 */ -void TankDrive::drive_arcade(double forward_back, double left_right, int power, BrakeType bt) -{ +void TankDrive::drive_arcade(double forward_back, double left_right, int power, BrakeType bt) { forward_back = modify_inputs(forward_back, power); left_right = modify_inputs(left_right, power); @@ -166,40 +208,40 @@ void TankDrive::drive_arcade(double forward_back, double left_right, int power, } /** - * Use odometry to drive forward a certain distance using a custom feedback controller + * Use odometry to drive forward a certain distance using a custom feedback + * controller * * Returns whether or not the robot has reached it's destination. * @param inches the distance to drive forward * @param dir the direction we want to travel forward and backward - * @param feedback the custom feedback controller we will use to travel. controls the rate at which we accelerate and drive. - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param feedback the custom feedback controller we will use to travel. + * controls the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the robot + * will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by + * its completion */ -bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed, double end_speed) -{ +bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedback, double max_speed, + double end_speed) { static pose_t pos_setpt; // We can't run the auto drive function without odometry - if (odometry == NULL) - { + if (odometry == NULL) { fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); fflush(stderr); return true; } - // Generate a point X inches forward of the current position, on first startup - if (!func_initialized) - { + // Generate a point X inches forward of the current position, on first + // startup + if (!func_initialized) { pose_t cur_pos = odometry->get_position(); // forwards is positive Y axis, backwards is negative - if (dir == directionType::rev) - { + if (dir == directionType::rev) { printf("going backwards\n"); inches = -fabs(inches); - } - else - { + } else { printf("going forwards\n"); inches = fabs(inches); } @@ -219,40 +261,45 @@ bool TankDrive::drive_forward(double inches, directionType dir, Feedback &feedba * Autonomously drive the robot forward a certain distance * * - * @param inches degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw + * @param inches degrees by which we will turn relative to the robot (+) + * turns ccw, (-) turns cw * @param dir the direction we want to travel forward and backward - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param max_speed the maximum percentage of robot speed at which the robot + * will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity + * by its completion * @return true if we have finished driving to our point */ -bool TankDrive::drive_forward(double inches, directionType dir, double max_speed, double end_speed) -{ +bool TankDrive::drive_forward(double inches, directionType dir, double max_speed, double end_speed) { if (drive_default_feedback != NULL) { return drive_forward(inches, dir, *drive_default_feedback, max_speed, end_speed); -} + } - printf("tank_drive.cpp: Cannot run drive_forward without a feedback controller!\n"); + printf("tank_drive.cpp: Cannot run drive_forward without a feedback " + "controller!\n"); fflush(stdout); return true; } /** - * Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed - * of percent_speed (-1.0 -> 1.0) + * Autonomously turn the robot X degrees to counterclockwise (negative for + * clockwise), with a maximum motor speed of percent_speed (-1.0 -> 1.0) * * Uses the specified feedback for it's control. * - * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw - * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param degrees degrees by which we will turn relative to the robot (+) + * turns ccw, (-) turns cw + * @param feedback the feedback controller we will use to travel. controls + * the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the robot + * will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity + * by its completion * @return true if we have turned our target number of degrees */ -bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_speed, double end_speed) -{ +bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_speed, double end_speed) { // We can't run the auto drive function without odometry - if (odometry == NULL) - { + if (odometry == NULL) { fprintf(stderr, "Odometry is NULL. Unable to run turn_degrees()\n"); fflush(stderr); return true; @@ -261,8 +308,7 @@ bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_spee static double target_heading = 0; // On the first run of the funciton, reset the gyro position and PID - if (!func_initialized) - { + if (!func_initialized) { double start_heading = odometry->get_position().rot; target_heading = start_heading + degrees; } @@ -271,23 +317,26 @@ bool TankDrive::turn_degrees(double degrees, Feedback &feedback, double max_spee } /** - * Autonomously turn the robot X degrees to counterclockwise (negative for clockwise), with a maximum motor speed - * of percent_speed (-1.0 -> 1.0) + * Autonomously turn the robot X degrees to counterclockwise (negative for + * clockwise), with a maximum motor speed of percent_speed (-1.0 -> 1.0) * * Uses the defualt turning feedback of the drive system. * - * @param degrees degrees by which we will turn relative to the robot (+) turns ccw, (-) turns cw - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param degrees degrees by which we will turn relative to the robot (+) + * turns ccw, (-) turns cw + * @param max_speed the maximum percentage of robot speed at which the robot + * will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity + * by its completion * @return true if we turned te target number of degrees */ -bool TankDrive::turn_degrees(double degrees, double max_speed, double end_speed) -{ +bool TankDrive::turn_degrees(double degrees, double max_speed, double end_speed) { if (turn_default_feedback != NULL) { return turn_degrees(degrees, *turn_default_feedback, max_speed, end_speed); -} + } - printf("tank_drive.cpp: Cannot run turn_degrees without a feedback controller!\n"); + printf("tank_drive.cpp: Cannot run turn_degrees without a feedback " + "controller!\n"); fflush(stdout); return true; } @@ -300,23 +349,24 @@ bool TankDrive::turn_degrees(double degrees, double max_speed, double end_speed) * @param x the x position of the target * @param y the y position of the target * @param dir the direction we want to travel forward and backward - * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param feedback the feedback controller we will use to travel. controls the + * rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the robot + * will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by + * its completion * @return true if we have reached our target point */ -bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed, double end_speed) -{ +bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedback &feedback, double max_speed, + double end_speed) { // We can't run the auto drive function without odometry - if (odometry == NULL) - { + if (odometry == NULL) { fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); fflush(stderr); return true; } - if (!func_initialized) - { + if (!func_initialized) { double initial_dist = OdometryBase::pos_diff(odometry->get_position(), {.x = x, .y = y}); @@ -335,10 +385,7 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb pose_t end_pos = {.x = x, .y = y}; // Create a point (and vector) to get the direction - point_t pos_diff_pt = - { - .x = x - current_pos.x, - .y = y - current_pos.y}; + point_t pos_diff_pt = {.x = x - current_pos.x, .y = y - current_pos.y}; Vector2D point_vec(pos_diff_pt); @@ -347,8 +394,9 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb int sign = 1; - // Make an imaginary perpendicualar line to that between the bot and the point. If the point is behind that line, - // and the point is within the robot's radius, use negatives for feedback control. + // Make an imaginary perpendicualar line to that between the bot and the + // point. If the point is behind that line, and the point is within the + // robot's radius, use negatives for feedback control. double angle_to_point = atan2(y - current_pos.y, x - current_pos.x) * 180.0 / PI; double angle = fmod(current_pos.rot - angle_to_point, 360.0); @@ -356,22 +404,22 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb // Normalize the angle between 0 and 360 if (angle > 360) { angle -= 360; -} + } if (angle < 0) { angle += 360; -} + } // If the angle is behind the robot, report negative. if (dir == directionType::fwd && angle > 90 && angle < 270) { sign = -1; } else if (dir == directionType::rev && (angle < 90 || angle > 270)) { sign = -1; -} + } - if (fabs(dist_left) < config.drive_correction_cutoff) - { - // When inside the robot's cutoff radius, report the distance to the point along the robot's forward axis, - // so we always "reach" the point without having to do a lateral translation + if (fabs(dist_left) < config.drive_correction_cutoff) { + // When inside the robot's cutoff radius, report the distance to the + // point along the robot's forward axis, so we always "reach" the point + // without having to do a lateral translation dist_left *= fabs(cos(angle * PI / 180.0)); } @@ -385,7 +433,7 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb delta_heading = OdometryBase::smallest_angle(current_pos.rot, heading); } else { delta_heading = OdometryBase::smallest_angle(current_pos.rot - 180, heading); -} + } // Update the PID controllers with new information correction_pid.update(delta_heading); @@ -395,7 +443,7 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb double correction = 0; if (is_pure_pursuit || fabs(dist_left) > config.drive_correction_cutoff) { correction = correction_pid.get(); -} + } // Reverse the drive_pid output if we're going backwards double drive_pid_rval; @@ -403,7 +451,7 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb drive_pid_rval = feedback.get() * -1; } else { drive_pid_rval = feedback.get(); -} + } // Combine the two pid outputs double lside = drive_pid_rval + correction; @@ -416,8 +464,7 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb drive_tank(lside, rside); // Check if the robot has reached it's destination - if (feedback.is_on_target()) - { + if (feedback.is_on_target()) { if (end_speed == 0) { stop(); } @@ -437,17 +484,19 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, Feedb * @param x the x position of the target * @param y the y position of the target * @param dir the direction we want to travel forward and backward - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param max_speed the maximum percentage of robot speed at which the robot + * will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by + * its completion * @return true if we have reached our target point */ -bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, double max_speed, double end_speed) -{ +bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, double max_speed, double end_speed) { if (drive_default_feedback != NULL) { return this->drive_to_point(x, y, dir, *drive_default_feedback, max_speed, end_speed); -} + } - printf("tank_drive.cpp: Cannot run drive_to_point without a feedback controller!\n"); + printf("tank_drive.cpp: Cannot run drive_to_point without a feedback " + "controller!\n"); fflush(stdout); return true; } @@ -457,23 +506,23 @@ bool TankDrive::drive_to_point(double x, double y, vex::directionType dir, doubl * 0 is forward. * * @param heading_deg the heading to which we will turn - * @param feedback the feedback controller we will use to travel. controls the rate at which we accelerate and drive. - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param feedback the feedback controller we will use to travel. controls + * the rate at which we accelerate and drive. + * @param max_speed the maximum percentage of robot speed at which the robot + * will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by + * its completion * @return true if we have reached our target heading */ -bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double max_speed, double end_speed) -{ +bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double max_speed, double end_speed) { // We can't run the auto drive function without odometry - if (odometry == NULL) - { + if (odometry == NULL) { fprintf(stderr, "Odometry is NULL. Unable to run drive_forward()\n"); fflush(stderr); return true; } - if (!func_initialized) - { + if (!func_initialized) { double initial_delta = OdometryBase::smallest_angle(odometry->get_position().rot, heading_deg); feedback.init(-initial_delta, 0, odometry->get_angular_speed_deg(), end_speed); feedback.set_limits(-fabs(max_speed), fabs(max_speed)); @@ -481,7 +530,8 @@ bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double m func_initialized = true; } - // Get the difference between the new heading and the current, and decide whether to turn left or right. + // Get the difference between the new heading and the current, and decide + // whether to turn left or right. double delta_heading = OdometryBase::smallest_angle(odometry->get_position().rot, heading_deg); feedback.update(-delta_heading); @@ -490,8 +540,7 @@ bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double m drive_tank(-feedback.get(), feedback.get()); // When the robot has reached it's angle, return true. - if (feedback.is_on_target()) - { + if (feedback.is_on_target()) { func_initialized = false; stop(); return true; @@ -504,17 +553,19 @@ bool TankDrive::turn_to_heading(double heading_deg, Feedback &feedback, double m * 0 is forward. Uses the defualt turn feedback of the drive system * * @param heading_deg the heading to which we will turn - * @param max_speed the maximum percentage of robot speed at which the robot will travel. 1 = full power - * @param end_speed the movement profile will attempt to reach this velocity by its completion + * @param max_speed the maximum percentage of robot speed at which the robot + * will travel. 1 = full power + * @param end_speed the movement profile will attempt to reach this velocity by + * its completion * @return true if we have reached our target heading */ -bool TankDrive::turn_to_heading(double heading_deg, double max_speed, double end_speed) -{ +bool TankDrive::turn_to_heading(double heading_deg, double max_speed, double end_speed) { if (turn_default_feedback != NULL) { return turn_to_heading(heading_deg, *turn_default_feedback, max_speed, end_speed); -} + } - printf("tank_drive.cpp: Cannot run turn_to_heading without a feedback controller!\n"); + printf("tank_drive.cpp: Cannot run turn_to_heading without a feedback " + "controller!\n"); fflush(stdout); return true; } @@ -524,17 +575,15 @@ bool TankDrive::turn_to_heading(double heading_deg, double max_speed, double end * Allows for better control of the robot at slower speeds * @param input the input signal -1 -> 1 * @param power the power to raise the signal to - * @return input^power accounting for any sign issues that would arise with this naive solution + * @return input^power accounting for any sign issues that would arise with this + * naive solution */ -double TankDrive::modify_inputs(double input, int power) -{ - return sign(input) * pow(std::abs(input), power); -} +double TankDrive::modify_inputs(double input, int power) { return sign(input) * pow(std::abs(input), power); } /** - * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of - * waypoints - the robot will attempt to follow the points while cutting corners (radius) - * to save time (compared to stop / turn / start) + * Drive the robot autonomously using a pure-pursuit algorithm - Input path with + * a set of waypoints - the robot will attempt to follow the points while + * cutting corners (radius) to save time (compared to stop / turn / start) * * @param path The list of coordinates to follow, in order * @param dir Run the bot forwards or backwards @@ -542,23 +591,23 @@ double TankDrive::modify_inputs(double input, int power) * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) * @return True when the path is complete */ -bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback &feedback, double max_speed, double end_speed) -{ +bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback &feedback, double max_speed, + double end_speed) { std::vector points = path.get_points(); - if (!path.is_valid()) - { - printf("WARNING: Unexpected pure pursuit path - some segments intersect or are too close\n"); + if (!path.is_valid()) { + printf("WARNING: Unexpected pure pursuit path - some segments " + "intersect or are too close\n"); } pose_t robot_pose = odometry->get_position(); - // On function initialization, send the path-length estimate to the feedback controller - if (!func_initialized) - { + // On function initialization, send the path-length estimate to the feedback + // controller + if (!func_initialized) { if (dir != directionType::rev) { feedback.init(-estimate_path_length(points), 0, odometry->get_speed(), end_speed); } else { feedback.init(estimate_path_length(points), 0, odometry->get_speed(), end_speed); -} + } func_initialized = true; } @@ -578,15 +627,13 @@ bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback angle_diff = OdometryBase::smallest_angle(robot_pose.rot, rad2deg(atan2(localized.y, localized.x))); } else { angle_diff = OdometryBase::smallest_angle(robot_pose.rot + 180, rad2deg(atan2(localized.y, localized.x))); -} + } // Correct the robot's heading until the last cut-off - if (!(is_last_point && robot_pose.get_point().dist(last_point) < config.drive_correction_cutoff)) - { + if (!(is_last_point && robot_pose.get_point().dist(last_point) < config.drive_correction_cutoff)) { correction_pid.update(angle_diff); correction = correction_pid.get(); - } - else // Inside cut-off radius, ignore horizontal diffs + } else // Inside cut-off radius, ignore horizontal diffs { dist_remaining *= cos(angle_diff * (PI / 180.0)); } @@ -595,7 +642,7 @@ bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback feedback.update(-dist_remaining); } else { feedback.update(dist_remaining); -} + } max_speed = fabs(max_speed); @@ -607,9 +654,9 @@ bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback drive_tank(left, right); - // When the robot has reached the end point and feedback reports on target, end pure pursuit - if (is_last_point && feedback.is_on_target()) - { + // When the robot has reached the end point and feedback reports on target, + // end pure pursuit + if (is_last_point && feedback.is_on_target()) { func_initialized = false; stop(); return true; @@ -618,9 +665,9 @@ bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback } /** - * Drive the robot autonomously using a pure-pursuit algorithm - Input path with a set of - * waypoints - the robot will attempt to follow the points while cutting corners (radius) - * to save time (compared to stop / turn / start) + * Drive the robot autonomously using a pure-pursuit algorithm - Input path with + * a set of waypoints - the robot will attempt to follow the points while + * cutting corners (radius) to save time (compared to stop / turn / start) * * Use the default drive feedback * @@ -629,7 +676,6 @@ bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, Feedback * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) * @return True when the path is complete */ -bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, double max_speed, double end_speed) -{ +bool TankDrive::pure_pursuit(PurePursuit::Path path, directionType dir, double max_speed, double end_speed) { return pure_pursuit(path, dir, *config.drive_feedback, max_speed, end_speed); } \ No newline at end of file diff --git a/src/utils/auto_chooser.cpp b/src/utils/auto_chooser.cpp index 9ef9b87..2d3418e 100644 --- a/src/utils/auto_chooser.cpp +++ b/src/utils/auto_chooser.cpp @@ -5,8 +5,7 @@ * so the driver can choose which autonomous to run. * @param brain the brain on which to draw the selection boxes */ -AutoChooser::AutoChooser(std::vector paths, size_t def) : choice(def) -{ +AutoChooser::AutoChooser(std::vector paths, size_t def) : choice(def) { const static int per_line = 3; const static int num_lines = 2; const static int x_padding = 20; @@ -18,42 +17,35 @@ AutoChooser::AutoChooser(std::vector paths, size_t def) : choice(de list = std::vector(paths.size()); int x = 50; int y = 10; - for (size_t i = 0; i < list.size(); i++) - { + for (size_t i = 0; i < list.size(); i++) { Rect r = Rect::from_min_and_size({(double)x, (double)y}, {entry_width, entry_height}); list[i] = entry_t{r, paths[i]}; x += entry_width + x_padding; - if ((i + 1) % per_line == 0) - { + if ((i + 1) % per_line == 0) { y += entry_height + y_padding; x = 50; } } } -void AutoChooser::update(bool was_pressed, int x, int y) -{ +void AutoChooser::update(bool was_pressed, int x, int y) { size_t i = 0; - for (const entry_t &e : list) - { - if (was_pressed && e.rect.contains({(double)x, (double)y})) - { + for (const entry_t &e : list) { + if (was_pressed && e.rect.contains({(double)x, (double)y})) { choice = i; } i++; } } -void AutoChooser::draw(vex::brain::lcd &scr, [[maybe_unused]] bool first_draw, [[maybe_unused]] unsigned int frame_number) -{ +void AutoChooser::draw(vex::brain::lcd &scr, [[maybe_unused]] bool first_draw, + [[maybe_unused]] unsigned int frame_number) { scr.setFont(vex::fontType::mono20); - for (size_t i = 0; i < list.size(); i++) - { + for (size_t i = 0; i < list.size(); i++) { entry_t e = list[i]; scr.setFillColor(vex::blue); - if (choice == i) - { + if (choice == i) { scr.setFillColor(vex::green); } scr.drawRectangle(e.rect.min.x, e.rect.min.y, e.rect.width(), e.rect.height()); @@ -66,7 +58,4 @@ void AutoChooser::draw(vex::brain::lcd &scr, [[maybe_unused]] bool first_draw, [ /** * Return the selected autonomous */ -size_t AutoChooser::get_choice() -{ - return choice; -} \ No newline at end of file +size_t AutoChooser::get_choice() { return choice; } \ No newline at end of file diff --git a/src/utils/command_structure/auto_command.cpp b/src/utils/command_structure/auto_command.cpp index 5bce832..657d4b6 100644 --- a/src/utils/command_structure/auto_command.cpp +++ b/src/utils/command_structure/auto_command.cpp @@ -1,334 +1,277 @@ #include "../core/include/utils/command_structure/auto_command.h" -class OrCondition : public Condition -{ +class OrCondition : public Condition { public: - OrCondition(Condition *A, Condition *B) : A(A), B(B) {} - bool test() override - { - bool a = A->test(); - bool b = B->test(); - return a | b; - } + OrCondition(Condition *A, Condition *B) : A(A), B(B) {} + bool test() override { + bool a = A->test(); + bool b = B->test(); + return a | b; + } private: - Condition *A; - Condition *B; + Condition *A; + Condition *B; }; -class AndCondition : public Condition -{ +class AndCondition : public Condition { public: - AndCondition(Condition *A, Condition *B) : A(A), B(B) {} - bool test() override - { - bool a = A->test(); - bool b = B->test(); - return a & b; - } + AndCondition(Condition *A, Condition *B) : A(A), B(B) {} + bool test() override { + bool a = A->test(); + bool b = B->test(); + return a & b; + } private: - Condition *A; - Condition *B; + Condition *A; + Condition *B; }; -Condition *Condition::Or(Condition *b) -{ - return new OrCondition(this, b); -} +Condition *Condition::Or(Condition *b) { return new OrCondition(this, b); } -Condition *Condition::And(Condition *b) -{ - return new AndCondition(this, b); -} +Condition *Condition::And(Condition *b) { return new AndCondition(this, b); } -bool FunctionCondition::test() -{ - return cond(); -} +bool FunctionCondition::test() { return cond(); } IfTimePassed::IfTimePassed(double time_s) : time_s(time_s), tmr() {} -bool IfTimePassed::test() -{ - return tmr.value() > time_s; -} +bool IfTimePassed::test() { return tmr.value() > time_s; } -InOrder::InOrder(std::queue cmds) : cmds(cmds) -{ - timeout_seconds = -1.0; // never timeout unless with_timeout is explicitly called -} -InOrder::InOrder(std::initializer_list cmds) : cmds(cmds) -{ - timeout_seconds = -1.0; +InOrder::InOrder(std::queue cmds) : cmds(cmds) { + timeout_seconds = -1.0; // never timeout unless with_timeout is explicitly called } +InOrder::InOrder(std::initializer_list cmds) : cmds(cmds) { timeout_seconds = -1.0; } -bool InOrder::run() -{ - // outer loop finished - if (cmds.size() == 0 && current_command == nullptr) - { - return true; - } - // retrieve and remove command at the front of the queue - if (current_command == nullptr) - { - printf("TAKING INORDER: len = %d\n", cmds.size()); - current_command = cmds.front(); - cmds.pop(); - tmr.reset(); - } - - // run command - bool cmd_finished = current_command->run(); - if (cmd_finished) - { - printf("InOrder Cmd finished\n"); - current_command = nullptr; - return false; // continue onto next command - } - - double seconds = tmr.value(); - - bool should_timeout = current_command->timeout_seconds > 0.0; - bool doTimeout = should_timeout && seconds > current_command->timeout_seconds; - if (current_command->true_to_end != nullptr) - { - doTimeout = doTimeout || current_command->true_to_end->test(); - } - - // timeout - if (doTimeout) - { - printf("InOrder timed out\n"); - current_command->on_timeout(); - current_command = nullptr; - return false; - } +bool InOrder::run() { + // outer loop finished + if (cmds.size() == 0 && current_command == nullptr) { + return true; + } + // retrieve and remove command at the front of the queue + if (current_command == nullptr) { + printf("TAKING INORDER: len = %d\n", cmds.size()); + current_command = cmds.front(); + cmds.pop(); + tmr.reset(); + } + + // run command + bool cmd_finished = current_command->run(); + if (cmd_finished) { + printf("InOrder Cmd finished\n"); + current_command = nullptr; + return false; // continue onto next command + } + + double seconds = tmr.value(); + + bool should_timeout = current_command->timeout_seconds > 0.0; + bool doTimeout = should_timeout && seconds > current_command->timeout_seconds; + if (current_command->true_to_end != nullptr) { + doTimeout = doTimeout || current_command->true_to_end->test(); + } + + // timeout + if (doTimeout) { + printf("InOrder timed out\n"); + current_command->on_timeout(); + current_command = nullptr; return false; + } + return false; } -void InOrder::on_timeout() -{ - if (current_command != nullptr) - { - current_command->on_timeout(); - } +void InOrder::on_timeout() { + if (current_command != nullptr) { + current_command->on_timeout(); + } } -struct parallel_runner_info -{ - int index; - std::vector *runners; - AutoCommand *cmd; +struct parallel_runner_info { + int index; + std::vector *runners; + AutoCommand *cmd; }; -static int parallel_runner(void *arg) -{ - parallel_runner_info *ri = (parallel_runner_info *)arg; - vex::timer tmr; - while (1) - { - bool finished = ri->cmd->run(); - if (finished) - { - break; - } - double t = (double)(tmr.time()) / 1000.0; - bool timed_out = t > ri->cmd->timeout_seconds; - bool doTimeout = timed_out && (ri->cmd->timeout_seconds > 0); - if (ri->cmd->true_to_end != nullptr) - { - doTimeout = doTimeout || ri->cmd->true_to_end->test(); - } - if (doTimeout) - { - ri->cmd->on_timeout(); - } - vexDelay(20); +static int parallel_runner(void *arg) { + parallel_runner_info *ri = (parallel_runner_info *)arg; + vex::timer tmr; + while (1) { + bool finished = ri->cmd->run(); + if (finished) { + break; } - - if ((*ri->runners)[ri->index] != nullptr) - { - delete (*ri->runners)[ri->index]; - (*ri->runners)[ri->index] = nullptr; + double t = (double)(tmr.time()) / 1000.0; + bool timed_out = t > ri->cmd->timeout_seconds; + bool doTimeout = timed_out && (ri->cmd->timeout_seconds > 0); + if (ri->cmd->true_to_end != nullptr) { + doTimeout = doTimeout || ri->cmd->true_to_end->test(); + } + if (doTimeout) { + ri->cmd->on_timeout(); } - return 0; + vexDelay(20); + } + + if ((*ri->runners)[ri->index] != nullptr) { + delete (*ri->runners)[ri->index]; + (*ri->runners)[ri->index] = nullptr; + } + return 0; } // wait for all to finish Parallel::Parallel(std::initializer_list cmds) : cmds(cmds), runners(0) {} -bool Parallel::run() -{ - if (runners.size() == 0) - { - // not initialized yet - for (int i = 0; i < cmds.size(); i++) - { - parallel_runner_info *ri = new parallel_runner_info{ - .index = i, - .runners = &runners, - .cmd = cmds[i], - }; - runners.push_back(new vex::task(parallel_runner, ri)); - } +bool Parallel::run() { + if (runners.size() == 0) { + // not initialized yet + for (int i = 0; i < cmds.size(); i++) { + parallel_runner_info *ri = new parallel_runner_info{ + .index = i, + .runners = &runners, + .cmd = cmds[i], + }; + runners.push_back(new vex::task(parallel_runner, ri)); } + } - bool all_finished = true; + bool all_finished = true; - for (int i = 0; i < cmds.size(); i++) - { - if (runners[i] != nullptr) - { - all_finished = false; - } + for (int i = 0; i < cmds.size(); i++) { + if (runners[i] != nullptr) { + all_finished = false; } - return all_finished; + } + return all_finished; } -void Parallel::on_timeout() -{ - for (int i = 0; i < runners.size(); i++) - { - - if (runners[i] != nullptr) - { - runners[i]->stop(); - if (cmds[i] != nullptr) - { - cmds[i]->on_timeout(); - } - delete runners[i]; - runners[i] = nullptr; - if (cmds[i] != nullptr) - { - delete cmds[i]; - cmds[i] = nullptr; - } - } +void Parallel::on_timeout() { + for (int i = 0; i < runners.size(); i++) { + + if (runners[i] != nullptr) { + runners[i]->stop(); + if (cmds[i] != nullptr) { + cmds[i]->on_timeout(); + } + delete runners[i]; + runners[i] = nullptr; + if (cmds[i] != nullptr) { + delete cmds[i]; + cmds[i] = nullptr; + } } + } } -Branch::Branch(Condition *cond, AutoCommand *false_choice, AutoCommand *true_choice) : false_choice(false_choice), true_choice(true_choice), cond(cond), choice(false), chosen(false), tmr() {} +Branch::Branch(Condition *cond, AutoCommand *false_choice, AutoCommand *true_choice) + : false_choice(false_choice), true_choice(true_choice), cond(cond), choice(false), chosen(false), tmr() { + this->timeout_seconds = -1; +} -Branch::~Branch() -{ - delete false_choice; - delete true_choice; +Branch::~Branch() { + delete false_choice; + delete true_choice; }; -bool Branch::run() -{ - if (!chosen) - { - choice = cond->test(); - chosen = true; +bool Branch::run() { + if (!chosen) { + choice = cond->test(); + chosen = true; + tmr.reset(); + } + + double seconds = static_cast(tmr.time()) / 1000.0; + if (choice == false) { + if (seconds > false_choice->timeout_seconds && false_choice->timeout_seconds != -1) { + false_choice->on_timeout(); + chosen = false; + return true; } - - double seconds = static_cast(tmr.time()) / 1000.0; - if (choice == false) - { - if (seconds > false_choice->timeout_seconds && false_choice->timeout_seconds != -1) - { - false_choice->on_timeout(); - } - return false_choice->run(); + bool finished = false_choice->run(); + if (finished) { + chosen = false; + return finished; } - else - { - if (seconds > true_choice->timeout_seconds && true_choice->timeout_seconds != -1) - { - true_choice->on_timeout(); - } - return true_choice->run(); + } else { + if (seconds > true_choice->timeout_seconds && true_choice->timeout_seconds != -1) { + true_choice->on_timeout(); + chosen = false; + return true; } -} -void Branch::on_timeout() -{ - if (!chosen) - { - // dont need to do anything - return; + bool finished = true_choice->run(); + if (finished) { + chosen = false; + return finished; } + } + return false; +} +void Branch::on_timeout() { + if (!chosen) { + // dont need to do anything + return; + } + + if (choice == false) { + false_choice->on_timeout(); + } else { + true_choice->on_timeout(); + } + chosen = false; +} - if (choice == false) - { - false_choice->on_timeout(); +static int async_runner(void *arg) { + AutoCommand *cmd = (AutoCommand *)arg; + vex::timer tmr; + while (1) { + bool finished = cmd->run(); + if (finished) { + break; } - else - { - true_choice->on_timeout(); + double t = (double)(tmr.time()) / 1000.0; + bool timed_out = t > cmd->timeout_seconds; + bool doTimeout = timed_out && cmd->timeout_seconds > 0; + if (cmd->true_to_end != nullptr) { + doTimeout = doTimeout || cmd->true_to_end->test(); } -} - -static int async_runner(void *arg) -{ - AutoCommand *cmd = (AutoCommand *)arg; - vex::timer tmr; - while (1) - { - bool finished = cmd->run(); - if (finished) - { - break; - } - double t = (double)(tmr.time()) / 1000.0; - bool timed_out = t > cmd->timeout_seconds; - bool doTimeout = timed_out && cmd->timeout_seconds > 0; - if (cmd->true_to_end != nullptr) - { - doTimeout = doTimeout || cmd->true_to_end->test(); - } - if (doTimeout) - { - cmd->on_timeout(); - break; - } - vexDelay(20); + if (doTimeout) { + cmd->on_timeout(); + break; } - delete cmd; + vexDelay(20); + } + delete cmd; - return 0; + return 0; } -bool Async::run() -{ - vex::task *t = new vex::task(async_runner, (void *)cmd); - (void)t; - // lmao get memory leaked - return true; +bool Async::run() { + vex::task *t = new vex::task(async_runner, (void *)cmd); + (void)t; + // lmao get memory leaked + return true; } -RepeatUntil::RepeatUntil(InOrder cmds, size_t times) : RepeatUntil(cmds, new TimesTestedCondition(times)) -{ - timeout_seconds = 999999; +RepeatUntil::RepeatUntil(InOrder cmds, size_t times) : RepeatUntil(cmds, new TimesTestedCondition(times)) { + timeout_seconds = -1.0; } -RepeatUntil::RepeatUntil(InOrder cmds, Condition *cond) : cmds(cmds), working_cmds(new InOrder(cmds)), cond(cond) -{ - timeout_seconds = 999999; +RepeatUntil::RepeatUntil(InOrder cmds, Condition *cond) : cmds(cmds), working_cmds(new InOrder(cmds)), cond(cond) { + timeout_seconds = -1.0; } +bool RepeatUntil::run() { + bool finished = working_cmds->run(); + if (!finished) { + // return if we're not done yet + return false; + } + // this run finished + bool res = cond->test(); + // we should finish + if (res) { + return true; + } + working_cmds = new InOrder(cmds); -bool RepeatUntil::run() -{ - bool finished = working_cmds->run(); - if (!finished) - { - // return if we're not done yet - return false; - } - // this run finished - - bool res = cond->test(); - // we should finish - if (res) - { - return true; - } - working_cmds = new InOrder(cmds); - - - return false; + return false; } -void RepeatUntil::on_timeout() -{ - working_cmds->on_timeout(); -} \ No newline at end of file +void RepeatUntil::on_timeout() { working_cmds->on_timeout(); } \ No newline at end of file diff --git a/src/utils/command_structure/basic_command.cpp b/src/utils/command_structure/basic_command.cpp index a45b85f..9102f30 100644 --- a/src/utils/command_structure/basic_command.cpp +++ b/src/utils/command_structure/basic_command.cpp @@ -22,7 +22,9 @@ * @param setting Power setting in volts,percentage,velocity * @param power Value of desired power */ -BasicSpinCommand::BasicSpinCommand(vex::motor &motor, vex::directionType dir, BasicSpinCommand::type setting, double power) : motor(motor), setting(setting), dir(dir), power(power) {} +BasicSpinCommand::BasicSpinCommand(vex::motor &motor, vex::directionType dir, BasicSpinCommand::type setting, + double power) + : motor(motor), setting(setting), dir(dir), power(power) {} /** * @brief Run the BasicSpinCommand @@ -30,21 +32,19 @@ BasicSpinCommand::BasicSpinCommand(vex::motor &motor, vex::directionType dir, Ba * * @return True Command runs once */ -bool BasicSpinCommand::run() -{ - switch (setting) - { // Switch Statement taking the setting Enum - case voltage: // Voltage Setting - motor.spin(dir, power, vex::volt); - break; - case percent: // Percentage Setting - motor.spin(dir, power, vex::percent); - break; - case veocity: // Velocity Setting - motor.spin(dir, power, vex::velocityUnits::rpm); - break; - } - return true; // Always return True to send next on CommandController +bool BasicSpinCommand::run() { + switch (setting) { // Switch Statement taking the setting Enum + case voltage: // Voltage Setting + motor.spin(dir, power, vex::volt); + break; + case percent: // Percentage Setting + motor.spin(dir, power, vex::percent); + break; + case veocity: // Velocity Setting + motor.spin(dir, power, vex::velocityUnits::rpm); + break; + } + return true; // Always return True to send next on CommandController } /** @@ -61,10 +61,9 @@ BasicStopCommand::BasicStopCommand(vex::motor &motor, vex::brakeType setting) : * * @return True Command runs once */ -bool BasicStopCommand::run() -{ - motor.stop(setting); - return true; +bool BasicStopCommand::run() { + motor.stop(setting); + return true; } // Basic Solenoid Commands----------------------------------- @@ -82,8 +81,7 @@ BasicSolenoidSet::BasicSolenoidSet(vex::pneumatics &solenoid, bool setting) : so * * @return True Command runs once */ -bool BasicSolenoidSet::run() -{ - solenoid.set(setting); - return true; +bool BasicSolenoidSet::run() { + solenoid.set(setting); + return true; } \ No newline at end of file diff --git a/src/utils/command_structure/command_controller.cpp b/src/utils/command_structure/command_controller.cpp index 79eb29c..b0520f3 100644 --- a/src/utils/command_structure/command_controller.cpp +++ b/src/utils/command_structure/command_controller.cpp @@ -6,17 +6,17 @@ * a queue and get executed and removed from the queue * in FIFO order. */ -#include #include "../core/include/utils/command_structure/command_controller.h" #include "../core/include/utils/command_structure/delay_command.h" +#include /** * Adds a command to the queue * @param cmd the AutoCommand we want to add to our list - * @param timeout_seconds the number of seconds we will let the command run for. If it exceeds this, we cancel it and run on_timeout + * @param timeout_seconds the number of seconds we will let the command run for. + * If it exceeds this, we cancel it and run on_timeout */ -void CommandController::add(AutoCommand *cmd, double timeout_seconds) -{ +void CommandController::add(AutoCommand *cmd, double timeout_seconds) { cmd->timeout_seconds = timeout_seconds; command_queue.push(cmd); } @@ -25,10 +25,8 @@ void CommandController::add(AutoCommand *cmd, double timeout_seconds) * Add multiple commands to the queue. No timeout here. * @param cmds the AutoCommands we want to add to our list */ -void CommandController::add(std::vector cmds) -{ - for (AutoCommand *cmd : cmds) - { +void CommandController::add(std::vector cmds) { + for (AutoCommand *cmd : cmds) { command_queue.push(cmd); } } @@ -36,14 +34,12 @@ void CommandController::add(std::vector cmds) /** * Add multiple commands to the queue. No timeout here. * @param cmds the AutoCommands we want to add to our list - * @param timeout timeout in seconds to apply to all commands if they are still the default + * @param timeout timeout in seconds to apply to all commands if they are still + * the default */ -void CommandController::add(std::vector cmds, double timeout_sec) -{ - for (AutoCommand *cmd : cmds) - { - if (cmd->timeout_seconds == AutoCommand::default_timeout) - { +void CommandController::add(std::vector cmds, double timeout_sec) { + for (AutoCommand *cmd : cmds) { + if (cmd->timeout_seconds == AutoCommand::default_timeout) { cmd->timeout_seconds = timeout_sec; } command_queue.push(cmd); @@ -56,23 +52,18 @@ void CommandController::add(std::vector cmds, double timeout_sec) * @param ms - number of milliseconds to wait * before continuing execution of autonomous */ -void CommandController::add_delay(int ms) -{ +void CommandController::add_delay(int ms) { AutoCommand *delay = new DelayCommand(ms); command_queue.push(delay); } -void CommandController::add_cancel_func(std::function true_if_cancel) -{ - should_cancel = true_if_cancel; -} +void CommandController::add_cancel_func(std::function true_if_cancel) { should_cancel = true_if_cancel; } /** * Begin execution of the queue * Execute and remove commands in FIFO order */ -void CommandController::run() -{ +void CommandController::run() { AutoCommand *next_cmd; printf("Running Auto. Commands 1 to %d\n", command_queue.size()); fflush(stdout); @@ -80,45 +71,44 @@ void CommandController::run() vex::timer tmr; tmr.reset(); - while (!command_queue.empty()) - { + while (!command_queue.empty()) { // retrieve and remove command at the front of the queue next_cmd = command_queue.front(); command_queue.pop(); command_timed_out = false; - // printf("Beginning Command %d : timeout = %.2f : at time = %.1f seconds\n", command_count, next_cmd->timeout_seconds, tmr.time(vex::seconds)); - // fflush(stdout); + // printf("Beginning Command %d : timeout = %.2f : at time = %.1f + // seconds\n", command_count, next_cmd->timeout_seconds, + // tmr.time(vex::seconds)); fflush(stdout); vex::timer timeout_timer; timeout_timer.reset(); bool doTimeout = next_cmd->timeout_seconds > 0.0; - if (next_cmd->true_to_end != nullptr) - { + if (next_cmd->true_to_end != nullptr) { doTimeout = doTimeout || next_cmd->true_to_end->test(); } // run the current command until it returns true or we timeout - while (!next_cmd->run()) - { - vexDelay(20); + while (!next_cmd->run()) { + + if (!doTimeout) { + vexDelay(20); - if (!doTimeout) - { continue; } - // If we do want to check for timeout, check and end the command if we should + // If we do want to check for timeout, check and end the command if + // we should double cmd_elapsed_sec = ((double)timeout_timer.time()) / 1000.0; - if (cmd_elapsed_sec > next_cmd->timeout_seconds || should_cancel()) - { + if (cmd_elapsed_sec > next_cmd->timeout_seconds || should_cancel()) { next_cmd->on_timeout(); command_timed_out = true; break; } + vexDelay(20); } - if (should_cancel()) - { + if (should_cancel()) { + printf("Cancelling"); break; } @@ -129,7 +119,4 @@ void CommandController::run() printf("Finished commands in %f seconds\n", tmr.time(vex::sec)); } -bool CommandController::last_command_timed_out() -{ - return command_timed_out; -} \ No newline at end of file +bool CommandController::last_command_timed_out() { return command_timed_out; } \ No newline at end of file diff --git a/src/utils/command_structure/drive_commands.cpp b/src/utils/command_structure/drive_commands.cpp index 4984cf6..c017513 100644 --- a/src/utils/command_structure/drive_commands.cpp +++ b/src/utils/command_structure/drive_commands.cpp @@ -2,7 +2,7 @@ * File: drive_commands.h * Desc: * Holds all the AutoCommand subclasses that wrap (currently) TankDrive functions - * + * * Currently includes: * - drive_forward * - turn_degrees @@ -18,7 +18,6 @@ #include "../core/include/utils/command_structure/drive_commands.h" - // ==== DRIVING ==== /** @@ -28,28 +27,26 @@ * @param inches how far forward to drive * @param dir the direction to drive * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at -*/ -DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, double max_speed, double end_speed): - drive_sys(drive_sys), feedback(feedback), inches(inches), dir(dir), max_speed(max_speed), end_speed(end_speed) {} + */ +DriveForwardCommand::DriveForwardCommand(TankDrive &drive_sys, Feedback &feedback, double inches, directionType dir, + double max_speed, double end_speed) + : drive_sys(drive_sys), feedback(feedback), inches(inches), dir(dir), max_speed(max_speed), end_speed(end_speed) {} /** * Run drive_forward * Overrides run from AutoCommand * @returns true when execution is complete, false otherwise */ -bool DriveForwardCommand::run() { - return drive_sys.drive_forward(inches, dir, feedback, max_speed, end_speed); -} +bool DriveForwardCommand::run() { return drive_sys.drive_forward(inches, dir, feedback, max_speed, end_speed); } /** * reset the drive system if we timeout -*/ -void DriveForwardCommand::on_timeout(){ + */ +void DriveForwardCommand::on_timeout() { drive_sys.stop(); drive_sys.reset_auto(); } - /** * Construct a TurnDegreesCommand Command * @param drive_sys the drive system we are commanding @@ -57,26 +54,24 @@ void DriveForwardCommand::on_timeout(){ * @param degrees how many degrees to rotate * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at */ -TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed, double end_speed): - drive_sys(drive_sys), feedback(feedback), degrees(degrees), max_speed(max_speed), end_speed(end_speed) {} +TurnDegreesCommand::TurnDegreesCommand(TankDrive &drive_sys, Feedback &feedback, double degrees, double max_speed, + double end_speed) + : drive_sys(drive_sys), feedback(feedback), degrees(degrees), max_speed(max_speed), end_speed(end_speed) {} /** * Run turn_degrees * Overrides run from AutoCommand * @returns true when execution is complete, false otherwise */ -bool TurnDegreesCommand::run() { - return drive_sys.turn_degrees(degrees, max_speed, end_speed); -} +bool TurnDegreesCommand::run() { return drive_sys.turn_degrees(degrees, max_speed, end_speed); } /** * reset the drive system if we timeout -*/ -void TurnDegreesCommand::on_timeout(){ + */ +void TurnDegreesCommand::on_timeout() { drive_sys.stop(); drive_sys.reset_auto(); } - /** * Construct a DriveForward Command * @param drive_sys the drive system we are commanding @@ -86,8 +81,9 @@ void TurnDegreesCommand::on_timeout(){ * @param dir the direction to drive * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at */ -DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, directionType dir, double max_speed, double end_speed): - drive_sys(drive_sys), feedback(feedback), x(x), y(y), dir(dir), max_speed(max_speed), end_speed(end_speed) {} +DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, double x, double y, + directionType dir, double max_speed, double end_speed) + : drive_sys(drive_sys), feedback(feedback), x(x), y(y), dir(dir), max_speed(max_speed), end_speed(end_speed) {} /** * Construct a DriveForward Command @@ -97,26 +93,25 @@ DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedbac * @param dir the direction to drive * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at */ -DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, point_t point, directionType dir, double max_speed, double end_speed): - drive_sys(drive_sys), feedback(feedback), x(point.x), y(point.y), dir(dir), max_speed(max_speed), end_speed(end_speed) {} +DriveToPointCommand::DriveToPointCommand(TankDrive &drive_sys, Feedback &feedback, point_t point, directionType dir, + double max_speed, double end_speed) + : drive_sys(drive_sys), feedback(feedback), x(point.x), y(point.y), dir(dir), max_speed(max_speed), + end_speed(end_speed) {} /** * Run drive_to_point * Overrides run from AutoCommand * @returns true when execution is complete, false otherwise */ -bool DriveToPointCommand::run() { - return drive_sys.drive_to_point(x, y, dir, feedback, max_speed, end_speed); -} +bool DriveToPointCommand::run() { return drive_sys.drive_to_point(x, y, dir, feedback, max_speed, end_speed); } /** * reset the drive system if we don't hit our target -*/ -void DriveToPointCommand::on_timeout(){ + */ +void DriveToPointCommand::on_timeout() { drive_sys.stop(); drive_sys.reset_auto(); } - /** * Construct a TurnToHeadingCommand Command * @param drive_sys the drive system we are commanding @@ -124,50 +119,45 @@ void DriveToPointCommand::on_timeout(){ * @param heading_deg the heading to turn to in degrees * @param max_speed 0 -> 1 percentage of the drive systems speed to drive at */ -TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, double max_speed, double end_speed): - drive_sys(drive_sys), feedback(feedback), heading_deg(heading_deg), max_speed(max_speed), end_speed(end_speed) {} +TurnToHeadingCommand::TurnToHeadingCommand(TankDrive &drive_sys, Feedback &feedback, double heading_deg, + double max_speed, double end_speed) + : drive_sys(drive_sys), feedback(feedback), heading_deg(heading_deg), max_speed(max_speed), end_speed(end_speed) {} /** * Run turn_to_heading * Overrides run from AutoCommand * @returns true when execution is complete, false otherwise */ -bool TurnToHeadingCommand::run() { - return drive_sys.turn_to_heading(heading_deg, feedback, max_speed, end_speed); -} +bool TurnToHeadingCommand::run() { return drive_sys.turn_to_heading(heading_deg, feedback, max_speed, end_speed); } /** * reset the drive system if we don't hit our target -*/ -void TurnToHeadingCommand::on_timeout(){ + */ +void TurnToHeadingCommand::on_timeout() { drive_sys.stop(); drive_sys.reset_auto(); } /** * Construct a Pure Pursuit AutoCommand - * + * * @param path The list of coordinates to follow, in order * @param dir Run the bot forwards or backwards * @param feedback The feedback controller determining speed * @param max_speed Limit the speed of the robot (for pid / pidff feedbacks) -*/ -PurePursuitCommand::PurePursuitCommand(TankDrive &drive_sys, Feedback &feedback, PurePursuit::Path path, directionType dir, double max_speed, double end_speed) -: drive_sys(drive_sys), path(path), dir(dir), feedback(feedback), max_speed(max_speed), end_speed(end_speed) -{} + */ +PurePursuitCommand::PurePursuitCommand(TankDrive &drive_sys, Feedback &feedback, PurePursuit::Path path, + directionType dir, double max_speed, double end_speed) + : drive_sys(drive_sys), path(path), dir(dir), feedback(feedback), max_speed(max_speed), end_speed(end_speed) {} /** * Direct call to TankDrive::pure_pursuit -*/ -bool PurePursuitCommand::run() -{ - return drive_sys.pure_pursuit(path, dir, feedback, max_speed, end_speed); -} + */ +bool PurePursuitCommand::run() { return drive_sys.pure_pursuit(path, dir, feedback, max_speed, end_speed); } /** * Reset the drive system when it times out -*/ -void PurePursuitCommand::on_timeout() -{ + */ +void PurePursuitCommand::on_timeout() { drive_sys.stop(); drive_sys.reset_auto(); } @@ -176,13 +166,9 @@ void PurePursuitCommand::on_timeout() * Construct a DriveStop Command * @param drive_sys the drive system we are commanding */ -DriveStopCommand::DriveStopCommand(TankDrive &drive_sys): - drive_sys(drive_sys) {} +DriveStopCommand::DriveStopCommand(TankDrive &drive_sys) : drive_sys(drive_sys) {} -void DriveStopCommand::on_timeout() -{ - drive_sys.reset_auto(); -} +void DriveStopCommand::on_timeout() { drive_sys.reset_auto(); } /** * Stop the drive train @@ -194,14 +180,13 @@ bool DriveStopCommand::run() { return true; } - // ==== ODOMETRY ==== /** * Construct an Odometry set pos * @param odom the odometry system we are setting * @param newpos the now position to set the odometry to */ -OdomSetPosition::OdomSetPosition(OdometryBase &odom, const pose_t &newpos): odom(odom), newpos(newpos){} +OdomSetPosition::OdomSetPosition(OdometryBase &odom, const pose_t &newpos) : odom(odom), newpos(newpos) {} bool OdomSetPosition::run() { odom.set_position(newpos); diff --git a/src/utils/command_structure/flywheel_commands.cpp b/src/utils/command_structure/flywheel_commands.cpp index bddda27..4307abc 100644 --- a/src/utils/command_structure/flywheel_commands.cpp +++ b/src/utils/command_structure/flywheel_commands.cpp @@ -6,49 +6,40 @@ #include "../core/include/utils/command_structure/flywheel_commands.h" - -SpinRPMCommand::SpinRPMCommand(Flywheel &flywheel, int rpm): - flywheel(flywheel), rpm(rpm) {} +SpinRPMCommand::SpinRPMCommand(Flywheel &flywheel, int rpm) : flywheel(flywheel), rpm(rpm) {} bool SpinRPMCommand::run() { flywheel.spin_rpm(rpm); return true; } -WaitUntilUpToSpeedCommand::WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshold_rpm): - flywheel(flywheel), threshold_rpm(threshold_rpm) {} +WaitUntilUpToSpeedCommand::WaitUntilUpToSpeedCommand(Flywheel &flywheel, int threshold_rpm) + : flywheel(flywheel), threshold_rpm(threshold_rpm) {} bool WaitUntilUpToSpeedCommand::run() { // If we're withing the specified threshold, we're ready to fire - if (fabs(flywheel.get_target() - flywheel.getRPM()) < threshold_rpm){ + if (fabs(flywheel.get_target() - flywheel.getRPM()) < threshold_rpm) { return true; } // else, keep waiting return false; } - - -FlywheelStopCommand::FlywheelStopCommand(Flywheel &flywheel): - flywheel(flywheel) {} +FlywheelStopCommand::FlywheelStopCommand(Flywheel &flywheel) : flywheel(flywheel) {} bool FlywheelStopCommand::run() { flywheel.stop(); return true; } - -FlywheelStopMotorsCommand::FlywheelStopMotorsCommand(Flywheel &flywheel): - flywheel(flywheel) {} +FlywheelStopMotorsCommand::FlywheelStopMotorsCommand(Flywheel &flywheel) : flywheel(flywheel) {} bool FlywheelStopMotorsCommand::run() { flywheel.stop(); return true; } - -FlywheelStopNonTasksCommand::FlywheelStopNonTasksCommand(Flywheel &flywheel): - flywheel(flywheel) {} +FlywheelStopNonTasksCommand::FlywheelStopNonTasksCommand(Flywheel &flywheel) : flywheel(flywheel) {} bool FlywheelStopNonTasksCommand::run() { flywheel.stop(); diff --git a/src/utils/controls/bang_bang.cpp b/src/utils/controls/bang_bang.cpp index 161a951..4dd542b 100644 --- a/src/utils/controls/bang_bang.cpp +++ b/src/utils/controls/bang_bang.cpp @@ -1,43 +1,30 @@ #include "../core/include/utils/controls/bang_bang.h" #include -BangBang::BangBang(double threshhold, double low, double high) : setpt(low), sensor_val(low), lower_bound(low), upper_bound(high), threshhold(threshhold) {} +BangBang::BangBang(double threshhold, double low, double high) + : setpt(low), sensor_val(low), lower_bound(low), upper_bound(high), threshhold(threshhold) {} -void BangBang::init(double start_pt, double set_pt, double, double) -{ - sensor_val = start_pt; - setpt = set_pt; +void BangBang::init(double start_pt, double set_pt, double, double) { + sensor_val = start_pt; + setpt = set_pt; } -void BangBang::set_limits(double lower, double upper) -{ - lower_bound = lower; - upper_bound = upper; -} -double BangBang::get() -{ - return last_output; +void BangBang::set_limits(double lower, double upper) { + lower_bound = lower; + upper_bound = upper; } +double BangBang::get() { return last_output; } -double BangBang::update(double val) -{ - sensor_val = val; - if (fabs(val - setpt) < threshhold) - { - last_output = 0; - } - else if (val > setpt) - { - last_output = lower_bound; - } - else - { - last_output = upper_bound; - } - return upper_bound; +double BangBang::update(double val) { + sensor_val = val; + if (fabs(val - setpt) < threshhold) { + last_output = 0; + } else if (val > setpt) { + last_output = lower_bound; + } else { + last_output = upper_bound; + } + return upper_bound; } -bool BangBang::is_on_target() -{ - return fabs(sensor_val - setpt) < threshhold; -} \ No newline at end of file +bool BangBang::is_on_target() { return fabs(sensor_val - setpt) < threshhold; } \ No newline at end of file diff --git a/src/utils/controls/feedforward.cpp b/src/utils/controls/feedforward.cpp index ba68dc2..9540c4f 100644 --- a/src/utils/controls/feedforward.cpp +++ b/src/utils/controls/feedforward.cpp @@ -1,92 +1,85 @@ #include "../core/include/utils/controls/feedforward.h" - /** -* tune_feedforward takes a group of motors and finds the feedforward conifg parameters automagically. -* @param motor the motor group to use -* @param pct Maximum velocity in percent (0->1.0) + * tune_feedforward takes a group of motors and finds the feedforward conifg parameters automagically. + * @param motor the motor group to use + * @param pct Maximum velocity in percent (0->1.0) * @param duration Amount of time the motors spin for the test * @return A tuned feedforward object */ -FeedForward::ff_config_t tune_feedforward(vex::motor_group &motor, double pct, double duration) -{ - FeedForward::ff_config_t out = {}; - - double start_pos = motor.position(vex::rotationUnits::rev); - - // ========== kS Tuning ========= - // Start at 0 and slowly increase the power until the robot starts moving - double power = 0; - while(fabs(motor.position(vex::rotationUnits::rev) - start_pos) < 0.05) - { - motor.spin(vex::directionType::fwd, power, vex::voltageUnits::volt); - power += 0.001; - vexDelay(100); - } - out.kS = power; - motor.stop(); +FeedForward::ff_config_t tune_feedforward(vex::motor_group &motor, double pct, double duration) { + FeedForward::ff_config_t out = {}; + double start_pos = motor.position(vex::rotationUnits::rev); - // ========== kV / kA Tuning ========= + // ========== kS Tuning ========= + // Start at 0 and slowly increase the power until the robot starts moving + double power = 0; + while (fabs(motor.position(vex::rotationUnits::rev) - start_pos) < 0.05) { + motor.spin(vex::directionType::fwd, power, vex::voltageUnits::volt); + power += 0.001; + vexDelay(100); + } + out.kS = power; + motor.stop(); - std::vector> vel_data_points; // time, velocity - std::vector> accel_data_points; // time, accel + // ========== kV / kA Tuning ========= - double max_speed = 0; - vex::timer tmr; - double time = 0; + std::vector> vel_data_points; // time, velocity + std::vector> accel_data_points; // time, accel - MovingAverage vel_ma(3); - MovingAverage accel_ma(3); + double max_speed = 0; + vex::timer tmr; + double time = 0; - // Move the robot forward at a fixed percentage for X seconds while taking velocity and accel measurements - do - { - double last_time = time; - time = tmr.time(vex::sec); - double dt = time - last_time; + MovingAverage vel_ma(3); + MovingAverage accel_ma(3); - vel_ma.add_entry(motor.velocity(vex::velocityUnits::rpm)); - accel_ma.add_entry(motor.velocity(vex::velocityUnits::rpm)/dt); + // Move the robot forward at a fixed percentage for X seconds while taking velocity and accel measurements + do { + double last_time = time; + time = tmr.time(vex::sec); + double dt = time - last_time; - double speed = vel_ma.get_value(); - double accel = accel_ma.get_value(); + vel_ma.add_entry(motor.velocity(vex::velocityUnits::rpm)); + accel_ma.add_entry(motor.velocity(vex::velocityUnits::rpm) / dt); - // For kV: - if(speed > max_speed) { - max_speed = speed; -} + double speed = vel_ma.get_value(); + double accel = accel_ma.get_value(); - // For kA: - // Filter out the acceleration dampening due to motor inductance - if(time > 0.25) - { - vel_data_points.push_back(std::pair(time, speed)); - accel_data_points.push_back(std::pair(time, accel)); - } + // For kV: + if (speed > max_speed) { + max_speed = speed; + } - // Theoretical polling rate = 100hz (it won't be that much, cause, y'know, vex.) - vexDelay(10); - } while(time < duration); + // For kA: + // Filter out the acceleration dampening due to motor inductance + if (time > 0.25) { + vel_data_points.push_back(std::pair(time, speed)); + accel_data_points.push_back(std::pair(time, accel)); + } - motor.stop(); + // Theoretical polling rate = 100hz (it won't be that much, cause, y'know, vex.) + vexDelay(10); + } while (time < duration); - // Calculate kV (volts/12 per unit per second) - out.kV = (pct - out.kS) / max_speed; + motor.stop(); - // Calculate kA (volts/12 per unit per second^2) - std::vector> accel_per_pct; - for (int i = 0; i < vel_data_points.size(); i++) - { - accel_per_pct.push_back(std::pair( - pct - out.kS - (vel_data_points[i].second * out.kV), // Acceleration-causing percent (X variable) - accel_data_points[i].second // Measured acceleration (Y variable) + // Calculate kV (volts/12 per unit per second) + out.kV = (pct - out.kS) / max_speed; + + // Calculate kA (volts/12 per unit per second^2) + std::vector> accel_per_pct; + for (int i = 0; i < vel_data_points.size(); i++) { + accel_per_pct.push_back(std::pair( + pct - out.kS - (vel_data_points[i].second * out.kV), // Acceleration-causing percent (X variable) + accel_data_points[i].second // Measured acceleration (Y variable) )); - } - - // kA is the reciprocal of the slope of the linear regression - double regres_slope = calculate_linear_regression(accel_per_pct).first; - out.kA = 1.0 / regres_slope; + } + + // kA is the reciprocal of the slope of the linear regression + double regres_slope = calculate_linear_regression(accel_per_pct).first; + out.kA = 1.0 / regres_slope; - return out; + return out; } \ No newline at end of file diff --git a/src/utils/controls/motion_controller.cpp b/src/utils/controls/motion_controller.cpp index eba94cc..127461a 100644 --- a/src/utils/controls/motion_controller.cpp +++ b/src/utils/controls/motion_controller.cpp @@ -13,8 +13,7 @@ * ff_cfg Definitions of kS, kV, and kA */ MotionController::MotionController(m_profile_cfg_t &config) - : config(config), pid(config.pid_cfg), ff(config.ff_cfg), - profile(config.max_v, config.accel) {} + : config(config), pid(config.pid_cfg), ff(config.ff_cfg), profile(config.max_v, config.accel) {} /** * @brief Initialize the motion profile for a new movement @@ -24,14 +23,13 @@ MotionController::MotionController(m_profile_cfg_t &config) * @param start_vel Movement starting velocity * @param end_vel Movement ending velocity */ -void MotionController::init(double start_pt, double end_pt, double start_vel, - double end_vel) { - profile.set_endpts(start_pt, end_pt); - profile.set_vel_endpts(start_vel, end_vel); - pid.reset(); - tmr.reset(); - - this->end_pt = end_pt; +void MotionController::init(double start_pt, double end_pt, double start_vel, double end_vel) { + profile.set_endpts(start_pt, end_pt); + profile.set_vel_endpts(start_vel, end_vel); + pid.reset(); + tmr.reset(); + + this->end_pt = end_pt; } /** @@ -41,19 +39,19 @@ void MotionController::init(double start_pt, double end_pt, double start_vel, * @return the motor input generated from the motion profile */ double MotionController::update(double sensor_val) { - cur_motion = profile.calculate(tmr.time(timeUnits::sec), sensor_val); - pid.set_target(cur_motion.pos); - pid.update(sensor_val); + cur_motion = profile.calculate(tmr.time(timeUnits::sec), sensor_val); + pid.set_target(cur_motion.pos); + pid.update(sensor_val); - this->current_pos = sensor_val; + this->current_pos = sensor_val; - out = pid.get() + ff.calculate(cur_motion.vel, cur_motion.accel, pid.get()); + out = pid.get() + ff.calculate(cur_motion.vel, cur_motion.accel, pid.get()); - if (lower_limit != upper_limit) { - out = clamp(out, lower_limit, upper_limit); - } + if (lower_limit != upper_limit) { + out = clamp(out, lower_limit, upper_limit); + } - return out; + return out; } /** @@ -69,8 +67,8 @@ double MotionController::get() { return out; } * @param upper Lower limit */ void MotionController::set_limits(double lower, double upper) { - lower_limit = lower; - upper_limit = upper; + lower_limit = lower; + upper_limit = upper; } /** @@ -78,9 +76,8 @@ void MotionController::set_limits(double lower, double upper) { * confirms it is on target */ bool MotionController::is_on_target() { - return (tmr.time(timeUnits::sec) > profile.get_movement_time()) && - pid.is_on_target() && - fabs(end_pt - current_pos) < pid.config.deadband; + return (tmr.time(timeUnits::sec) > profile.get_movement_time()) && pid.is_on_target() && + fabs(end_pt - current_pos) < pid.config.deadband; } /** @@ -107,143 +104,136 @@ motion_t MotionController::get_motion() const { return cur_motion; } * @param duration Amount of time the robot should be moving for the test * @return A tuned feedforward object */ -FeedForward::ff_config_t -MotionController::tune_feedforward(TankDrive &drive, OdometryTank &odometry, - double pct, double duration) { - FeedForward::ff_config_t out = {}; - - pose_t start_pos = odometry.get_position(); - - // ========== kS Tuning ========= - // Start at 0 and slowly increase the power until the robot starts moving - double power = 0; - while (odometry.pos_diff(start_pos, odometry.get_position()) < 0.05) { - drive.drive_tank(power, power, 1); - power += 0.001; - vexDelay(100); +FeedForward::ff_config_t MotionController::tune_feedforward(TankDrive &drive, OdometryTank &odometry, double pct, + double duration) { + FeedForward::ff_config_t out = {}; + + pose_t start_pos = odometry.get_position(); + + // ========== kS Tuning ========= + // Start at 0 and slowly increase the power until the robot starts moving + double power = 0; + while (odometry.pos_diff(start_pos, odometry.get_position()) < 0.05) { + drive.drive_tank(power, power, 1); + power += 0.001; + vexDelay(100); + } + out.kS = power; + drive.stop(); + + // ========== kV / kA Tuning ========= + + std::vector> vel_data_points; // time, velocity + std::vector> accel_data_points; // time, accel + + double max_speed = 0; + double max_accel = 0; + timer tmr; + double time; + + MovingAverage vel_ma(3); + MovingAverage accel_ma(3); + + // Move the robot forward at a fixed percentage for X seconds while taking + // velocity and accel measurements + + drive.drive_tank(pct, pct, 1); + do { + time = tmr.time(sec); + + vel_ma.add_entry(odometry.get_speed()); + accel_ma.add_entry(odometry.get_accel()); + + double speed = vel_ma.get_value(); + double accel = accel_ma.get_value(); + // For kV: + if (speed > max_speed) { + max_speed = speed; + } + if (accel > max_accel) { + max_accel = accel; } - out.kS = power; - drive.stop(); - - // ========== kV / kA Tuning ========= - - std::vector> vel_data_points; // time, velocity - std::vector> accel_data_points; // time, accel - - double max_speed = 0; - double max_accel = 0; - timer tmr; - double time; - - MovingAverage vel_ma(3); - MovingAverage accel_ma(3); - - // Move the robot forward at a fixed percentage for X seconds while taking - // velocity and accel measurements - - drive.drive_tank(pct, pct, 1); - do { - time = tmr.time(sec); - - vel_ma.add_entry(odometry.get_speed()); - accel_ma.add_entry(odometry.get_accel()); - - double speed = vel_ma.get_value(); - double accel = accel_ma.get_value(); - // For kV: - if (speed > max_speed) { - max_speed = speed; - } - if (accel > max_accel) { - max_accel = accel; - } - - // For kA: - // Filter out the acceleration dampening due to motor inductance - if (time > 0.25) { - vel_data_points.push_back(std::pair(time, speed)); - accel_data_points.push_back(std::pair(time, accel)); - } - - // Theoretical polling rate = 100hz (it won't be that much, cause, - // y'know, vex.) - vexDelay(10); - } while (time < duration); - - drive.stop(); - - // Calculate kV (volts/12 per unit per second) - out.kV = (pct - out.kS) / max_speed; - - printf("Max speed achieved: %.4f\n", max_speed); - printf("Max accel achieved: %.4f\n", max_accel); - - // Calculate kA (volts/12 per unit per second^2) - std::vector> accel_per_pct; - for (int i = 0; i < vel_data_points.size(); i++) { - accel_per_pct.push_back(std::pair( - pct - out.kS - - (vel_data_points[i].second * - out.kV), // Acceleration-causing percent (X variable) - accel_data_points[i].second // Measured acceleration (Y variable) - )); + + // For kA: + // Filter out the acceleration dampening due to motor inductance + if (time > 0.25) { + vel_data_points.push_back(std::pair(time, speed)); + accel_data_points.push_back(std::pair(time, accel)); } - // kA is the reciprocal of the slope of the linear regression - double regres_slope = calculate_linear_regression(accel_per_pct).first; - out.kA = 1.0 / regres_slope; + // Theoretical polling rate = 100hz (it won't be that much, cause, + // y'know, vex.) + vexDelay(10); + } while (time < duration); + + drive.stop(); + + // Calculate kV (volts/12 per unit per second) + out.kV = (pct - out.kS) / max_speed; - return out; + printf("Max speed achieved: %.4f\n", max_speed); + printf("Max accel achieved: %.4f\n", max_accel); + + // Calculate kA (volts/12 per unit per second^2) + std::vector> accel_per_pct; + for (int i = 0; i < vel_data_points.size(); i++) { + accel_per_pct.push_back(std::pair( + pct - out.kS - (vel_data_points[i].second * out.kV), // Acceleration-causing percent (X variable) + accel_data_points[i].second // Measured acceleration (Y variable) + )); + } + + // kA is the reciprocal of the slope of the linear regression + double regres_slope = calculate_linear_regression(accel_per_pct).first; + out.kA = 1.0 / regres_slope; + + return out; } class MotionControllerPage : public screen::Page { - public: - MotionControllerPage(const MotionController &mc) : mc(mc) {} - - void update(bool was_pressed, int x, int y) override {} - void draw(vex::brain::lcd &screen, bool first_draw, - unsigned int frame_number) { - const motion_t mot = mc.get_motion(); - - // Text - top right - screen.printAt(240, 20, "pos: %.2fin", mot.pos); - screen.printAt(240, 40, "vel: %.2fin", mot.vel); - screen.printAt(240, 60, "acc: %.2fin", mot.accel); - screen.printAt(240, 80, "%.2fs of %.2fs", mc.tmr.value(), - mc.profile.get_movement_time()); - - // Trapezoid - bottom right - const int32_t trap_width = 200; - const int32_t trap_height = 98; - const double seconds = mc.tmr.value(); - const double full_time = mc.profile.get_movement_time(); - const double x_pct = seconds / full_time; - const double y_pct = mot.vel / mc.profile.get_max_v(); - const int32_t x_pos = (int32_t)(x_pct * trap_width) + 240; - const int32_t y_pos = (int32_t)(-y_pct * trap_height) + 100; - const int32_t max_vel_y = 120; - const int32_t end_acc_x = 260; - const int32_t start_dec_x = 420; - - // trapezoid - screen.setPenColor(vex::red); - // accelerating - screen.drawLine(240, 200, end_acc_x, max_vel_y); - // staying - screen.drawLine(end_acc_x, max_vel_y, start_dec_x, max_vel_y); - // decellerating - screen.drawLine(440, 200, start_dec_x, max_vel_y); - - // dot where we are - screen.setFillColor(vex::red); - screen.setPenColor(vex::white); - screen.drawCircle(x_pos, y_pos, 3); - } - - private: - const MotionController &mc; +public: + MotionControllerPage(const MotionController &mc) : mc(mc) {} + + void update(bool was_pressed, int x, int y) override {} + void draw(vex::brain::lcd &screen, bool first_draw, unsigned int frame_number) { + const motion_t mot = mc.get_motion(); + + // Text - top right + screen.printAt(240, 20, "pos: %.2fin", mot.pos); + screen.printAt(240, 40, "vel: %.2fin", mot.vel); + screen.printAt(240, 60, "acc: %.2fin", mot.accel); + screen.printAt(240, 80, "%.2fs of %.2fs", mc.tmr.value(), mc.profile.get_movement_time()); + + // Trapezoid - bottom right + const int32_t trap_width = 200; + const int32_t trap_height = 98; + const double seconds = mc.tmr.value(); + const double full_time = mc.profile.get_movement_time(); + const double x_pct = seconds / full_time; + const double y_pct = mot.vel / mc.profile.get_max_v(); + const int32_t x_pos = (int32_t)(x_pct * trap_width) + 240; + const int32_t y_pos = (int32_t)(-y_pct * trap_height) + 100; + const int32_t max_vel_y = 120; + const int32_t end_acc_x = 260; + const int32_t start_dec_x = 420; + + // trapezoid + screen.setPenColor(vex::red); + // accelerating + screen.drawLine(240, 200, end_acc_x, max_vel_y); + // staying + screen.drawLine(end_acc_x, max_vel_y, start_dec_x, max_vel_y); + // decellerating + screen.drawLine(440, 200, start_dec_x, max_vel_y); + + // dot where we are + screen.setFillColor(vex::red); + screen.setPenColor(vex::white); + screen.drawCircle(x_pos, y_pos, 3); + } + +private: + const MotionController &mc; }; -screen::Page *MotionController::Page() { - return new MotionControllerPage(*this); -} \ No newline at end of file +screen::Page *MotionController::Page() { return new MotionControllerPage(*this); } \ No newline at end of file diff --git a/src/utils/controls/pid.cpp b/src/utils/controls/pid.cpp index 2c46495..fa92811 100644 --- a/src/utils/controls/pid.cpp +++ b/src/utils/controls/pid.cpp @@ -31,9 +31,8 @@ double PID::update(double sensor_val) { if (time_delta != 0) { d_term = config.d * (get_error() - last_error) / time_delta; } else if (last_time != 0) { - printf( - "(pid.cpp): Warning - running PID without a delay is just a P loop!\n"); -} + printf("(pid.cpp): Warning - running PID without a delay is just a P loop!\n"); + } // P and D terms out = (config.p * get_error()) + d_term; @@ -42,10 +41,9 @@ double PID::update(double sensor_val) { // Only add to the accumulated error if the output is not saturated // aka "Integral Clamping" anti-windup technique - if (!limits_exist || - (limits_exist && (out < upper_limit && out > lower_limit))) { + if (!limits_exist || (limits_exist && (out < upper_limit && out > lower_limit))) { accum_error += time_delta * get_error(); -} + } // I term out += config.i * accum_error; @@ -55,10 +53,8 @@ double PID::update(double sensor_val) { // Enable clamping if the limit is not 0 if (limits_exist) { - out = (out < lower_limit) ? lower_limit - : (out > upper_limit) ? upper_limit - : out; -} + out = (out < lower_limit) ? lower_limit : (out > upper_limit) ? upper_limit : out; + } return out; } @@ -118,12 +114,11 @@ bool PID::is_on_target() { if (fabs(get_error()) < config.deadband) { if (target_vel != 0) { return true; -} + } if (is_checking_on_target == false) { on_target_last_time = pid_timer.value(); is_checking_on_target = true; - } else if (pid_timer.value() - on_target_last_time > - config.on_target_time) { + } else if (pid_timer.value() - on_target_last_time > config.on_target_time) { return true; } } else { diff --git a/src/utils/controls/pidff.cpp b/src/utils/controls/pidff.cpp index f8f38c7..e12b309 100644 --- a/src/utils/controls/pidff.cpp +++ b/src/utils/controls/pidff.cpp @@ -1,11 +1,10 @@ #include "../core/include/utils/controls/pidff.h" #include "../core/include/utils/math_util.h" -PIDFF::PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg) - : pid(pid_cfg), ff_cfg(ff_cfg), ff(ff_cfg) { - out = 0; - lower_lim = 0; - upper_lim = 0; +PIDFF::PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg) : pid(pid_cfg), ff_cfg(ff_cfg), ff(ff_cfg) { + out = 0; + lower_lim = 0; + upper_lim = 0; } /** @@ -14,9 +13,8 @@ PIDFF::PIDFF(PID::pid_config_t &pid_cfg, FeedForward::ff_config_t &ff_cfg) * @param start_pt the current sensor value * @param set_pt where the sensor value should be */ -void PIDFF::init(double start_pt, double set_pt, double start_vel, - double end_vel) { - pid.init(start_pt, set_pt, start_vel, end_vel); +void PIDFF::init(double start_pt, double set_pt, double start_vel, double end_vel) { + pid.init(start_pt, set_pt, start_vel, end_vel); } void PIDFF::set_target(double set_pt) { pid.set_target(set_pt); } @@ -29,14 +27,14 @@ void PIDFF::set_target(double set_pt) { pid.set_target(set_pt); } * @return feedback loop result */ double PIDFF::update(double val) { - double pid_out = pid.update(val); - double ff_out = ff_cfg.kG + (ff_cfg.kS * sign(pid_out)); - out = pid_out + ff_out; - if (lower_lim != upper_lim) { - out = clamp(out, lower_lim, upper_lim); -} + double pid_out = pid.update(val); + double ff_out = ff_cfg.kG + (ff_cfg.kS * sign(pid_out)); + out = pid_out + ff_out; + if (lower_lim != upper_lim) { + out = clamp(out, lower_lim, upper_lim); + } - return out; + return out; } double PIDFF::get_sensor_val() const { return pid.get_sensor_val(); } @@ -52,14 +50,14 @@ double PIDFF::get_target() const { return pid.get_target(); } */ double PIDFF::update(double val, double vel_setpt, double a_setpt) { - double pid_out = pid.update(val); - double ff_out = ff.calculate(vel_setpt, a_setpt); - out = pid_out + ff_out; - if (lower_lim != upper_lim) { - out = clamp(out, lower_lim, upper_lim); -} + double pid_out = pid.update(val); + double ff_out = ff.calculate(vel_setpt, a_setpt); + out = pid_out + ff_out; + if (lower_lim != upper_lim) { + out = clamp(out, lower_lim, upper_lim); + } - return out; + return out; } /** @@ -75,8 +73,8 @@ double PIDFF::get() { return out; } * @param upper Lower limit */ void PIDFF::set_limits(double lower, double upper) { - upper_lim = upper; - lower_lim = lower; + upper_lim = upper; + lower_lim = lower; } /** @@ -84,4 +82,4 @@ void PIDFF::set_limits(double lower, double upper) { */ bool PIDFF::is_on_target() { return pid.is_on_target(); } -void PIDFF::reset() { pid.reset(); } +void PIDFF::reset() { pid.reset(); } \ No newline at end of file diff --git a/src/utils/controls/take_back_half.cpp b/src/utils/controls/take_back_half.cpp index 7defe78..16e2d10 100644 --- a/src/utils/controls/take_back_half.cpp +++ b/src/utils/controls/take_back_half.cpp @@ -1,84 +1,68 @@ #include "../core/include/utils/controls/take_back_half.h" #include "../core/include/utils/math_util.h" -TakeBackHalf::TakeBackHalf(double gain, double first_cross_split, double thresh) : TBH_gain(gain), first_cross_split(first_cross_split), on_target_threshhold(fabs(thresh)) -{ - tbh = 0.0; - output = 0.0; - prev_error = 0.0; - lower = 0.0; - upper = 0.0; - first_cross = true; +TakeBackHalf::TakeBackHalf(double gain, double first_cross_split, double thresh) + : TBH_gain(gain), first_cross_split(first_cross_split), on_target_threshhold(fabs(thresh)) { + tbh = 0.0; + output = 0.0; + prev_error = 0.0; + lower = 0.0; + upper = 0.0; + first_cross = true; } -void TakeBackHalf::init(double start_pt, double set_pt, double, double) -{ - if (set_pt == target) - { - // nothing to do - return; - } - first_cross = true; - tbh = output; - target = set_pt; - output = update(start_pt); +void TakeBackHalf::init(double start_pt, double set_pt, double, double) { + if (set_pt == target) { + // nothing to do + return; + } + first_cross = true; + tbh = output; + target = set_pt; + output = update(start_pt); } -double TakeBackHalf::update(double val) -{ - - if (target == 0.0) - { - printf("no target\n"); - return 0.0; - } - - double error = target - val; - output += TBH_gain * error; - - // taking back half crossed target - if (sign(error) != sign(prev_error)) - { - if (first_cross) - { - output = lerp(tbh, output, first_cross_split); - tbh = output; - first_cross = false; - printf("First cross\n"); - } - else - { - // output = .5 * (output + tbh); - output = lerp(tbh, output, .5); - tbh = output; - } - prev_error = error; +double TakeBackHalf::update(double val) { + + if (target == 0.0) { + printf("no target\n"); + return 0.0; + } + + double error = target - val; + output += TBH_gain * error; + + // taking back half crossed target + if (sign(error) != sign(prev_error)) { + if (first_cross) { + output = lerp(tbh, output, first_cross_split); + tbh = output; + first_cross = false; + printf("First cross\n"); + } else { + // output = .5 * (output + tbh); + output = lerp(tbh, output, .5); + tbh = output; } + prev_error = error; + } - if (lower != upper) - { - output = clamp(output, lower, upper); - } - return output; + if (lower != upper) { + output = clamp(output, lower, upper); + } + return output; } -double TakeBackHalf::get() -{ - return output; -} +double TakeBackHalf::get() { return output; } -void TakeBackHalf::set_limits(double low, double high) -{ +void TakeBackHalf::set_limits(double low, double high) { - lower = low; - upper = high; - printf("Set limits: %f, %f\n", lower, upper); + lower = low; + upper = high; + printf("Set limits: %f, %f\n", lower, upper); } -bool TakeBackHalf::is_on_target() -{ - return fabs(prev_error) < on_target_threshhold; -} +bool TakeBackHalf::is_on_target() { return fabs(prev_error) < on_target_threshhold; } // Runs a Take Back Half variant to control RPM // https://www.vexwiki.org/programming/controls_algorithms/tbh diff --git a/src/utils/generic_auto.cpp b/src/utils/generic_auto.cpp index 1ac9dcd..c6984a3 100644 --- a/src/utils/generic_auto.cpp +++ b/src/utils/generic_auto.cpp @@ -1,65 +1,60 @@ #include "../core/include/utils/generic_auto.h" /** -* The method that runs the autonomous. If 'blocking' is true, then -* this method will run through every state until it finished. -* -* If blocking is false, then assuming every state is also non-blocking, -* the method will run through the current state in the list and return -* immediately. -* -* @param blocking -* Whether or not to block the thread until all states have run -* @returns -* true after all states have finished. -*/ -bool GenericAuto::run(bool blocking) -{ - if(state_list.empty()) { - return true; -} + * The method that runs the autonomous. If 'blocking' is true, then + * this method will run through every state until it finished. + * + * If blocking is false, then assuming every state is also non-blocking, + * the method will run through the current state in the list and return + * immediately. + * + * @param blocking + * Whether or not to block the thread until all states have run + * @returns + * true after all states have finished. + */ +bool GenericAuto::run(bool blocking) { + if (state_list.empty()) { + return true; + } - do - { - if( state_list.front()() ) { - state_list.pop(); -} + do { + if (state_list.front()()) { + state_list.pop(); + } - if(blocking) { - vexDelay(20); -} + if (blocking) { + vexDelay(20); + } - } while(blocking && !state_list.empty()); + } while (blocking && !state_list.empty()); // If the method is blocking, return true because it's finished // If non-blocking, return false because the list isn't empty yet return blocking; } -void GenericAuto::add(state_ptr new_state) -{ - state_list.push(new_state); -} +void GenericAuto::add(state_ptr new_state) { state_list.push(new_state); } -void GenericAuto::add_async(state_ptr async_state) -{ - state_ptr fn = [&async_state](){ - vex::task t([](void* fn_ptr){ - while(! (*(state_ptr*)fn_ptr)() ) { - vexDelay(20); -} +void GenericAuto::add_async(state_ptr async_state) { + state_ptr fn = [&async_state]() { + vex::task t( + [](void *fn_ptr) { + while (!(*(state_ptr *)fn_ptr)()) { + vexDelay(20); + } - return 0; - }, &async_state); + return 0; + }, + &async_state); return true; }; state_list.push(fn); } -void GenericAuto::add_delay(int ms) -{ - add([ms](){ +void GenericAuto::add_delay(int ms) { + add([ms]() { vexDelay(ms); return true; }); diff --git a/src/utils/graph_drawer.cpp b/src/utils/graph_drawer.cpp index 5621d99..57f830f 100644 --- a/src/utils/graph_drawer.cpp +++ b/src/utils/graph_drawer.cpp @@ -6,68 +6,58 @@ /// @param upper_bound the top of the window when displaying (if upper_bound = lower_bound, auto calculate bounds) /// @param colors the colors of the series. must be of size num_series /// @param num_series the number of series to graph -GraphDrawer::GraphDrawer(int num_samples, double lower_bound, double upper_bound, std::vector colors, size_t num_series) : cols(colors), auto_fit(lower_bound == upper_bound) -{ - if (colors.size() != num_series) - { - printf("The number of colors does not match the number of series in graph drawer\n"); - } - series = std::vector>(num_series); - for (size_t i = 0; i < num_series; i++) - { - series[i] = std::vector(num_samples, {0.0, 0.0}); - } +GraphDrawer::GraphDrawer(int num_samples, double lower_bound, double upper_bound, std::vector colors, + size_t num_series) + : cols(colors), auto_fit(lower_bound == upper_bound) { + if (colors.size() != num_series) { + printf("The number of colors does not match the number of series in graph drawer\n"); + } + series = std::vector>(num_series); + for (size_t i = 0; i < num_series; i++) { + series[i] = std::vector(num_samples, {0.0, 0.0}); + } - if (auto_fit) - { - upper = -1000.0; - lower = 1000.0; - } else { - upper = upper_bound; - lower = lower_bound; - } + if (auto_fit) { + upper = -1000.0; + lower = 1000.0; + } else { + upper = upper_bound; + lower = lower_bound; + } } /** * add_samples adds a point to the graph, removing one from the back * @param sample an x, y coordinate of the next point to graph */ -void GraphDrawer::add_samples(std::vector new_samples) -{ - if (series.size() != new_samples.size()) - { - printf("Mismatch between # of samples given and number of series. %s : %d\n", __FILE__, __LINE__); +void GraphDrawer::add_samples(std::vector new_samples) { + if (series.size() != new_samples.size()) { + printf("Mismatch between # of samples given and number of series. %s : %d\n", __FILE__, __LINE__); + } + for (size_t i = 0; i < series.size(); i++) { + series[i][sample_index] = new_samples[i]; + if (auto_fit) { + upper = fmax(upper, new_samples[i].y); + lower = fmin(lower, new_samples[i].y); } - for (size_t i = 0; i < series.size(); i++) - { - series[i][sample_index] = new_samples[i]; - if (auto_fit) - { - upper = fmax(upper, new_samples[i].y); - lower = fmin(lower, new_samples[i].y); - } - } - sample_index++; - sample_index %= series[0].size(); + } + sample_index++; + sample_index %= series[0].size(); } -void GraphDrawer::add_samples(std::vector new_samples) -{ - if (series.size() != new_samples.size()) - { - printf("Mismatch between # of samples given and number of series. %s : %d\n", __FILE__, __LINE__); - } - for (size_t i = 0; i < series.size(); i++) - { - series[i][sample_index] = {(double)vex::timer::system(), new_samples[i]}; - if (auto_fit) - { - upper = fmax(upper, new_samples[i]); - lower = fmin(lower, new_samples[i]); - } +void GraphDrawer::add_samples(std::vector new_samples) { + if (series.size() != new_samples.size()) { + printf("Mismatch between # of samples given and number of series. %s : %d\n", __FILE__, __LINE__); + } + for (size_t i = 0; i < series.size(); i++) { + series[i][sample_index] = {(double)vex::timer::system(), new_samples[i]}; + if (auto_fit) { + upper = fmax(upper, new_samples[i]); + lower = fmin(lower, new_samples[i]); } - sample_index++; - sample_index %= series[0].size(); + } + sample_index++; + sample_index %= series[0].size(); } /** @@ -77,61 +67,54 @@ void GraphDrawer::add_samples(std::vector new_samples) * @param width the width of the graphed region * @param height the height of the graphed region */ -void GraphDrawer::draw(vex::brain::lcd &screen, int x, int y, int width, int height) -{ - if (series[0].size() < 1) - { - return; - } - if (cols.size() != series.size()) - { - printf("The number of colors does not match the number of series in graph drawer\n"); - } +void GraphDrawer::draw(vex::brain::lcd &screen, int x, int y, int width, int height) { + if (series[0].size() < 1) { + return; + } + if (cols.size() != series.size()) { + printf("The number of colors does not match the number of series in graph drawer\n"); + } - size_t newest_index = (sample_index-1); - if (sample_index<0){ - sample_index+=series[0].size(); - } + size_t newest_index = (sample_index - 1); + if (sample_index < 0) { + sample_index += series[0].size(); + } - double earliest_time = series[0][sample_index].x; - double latest_time = series[0][newest_index].x; - // collect data - if (std::abs(latest_time - earliest_time) < 0.001) - { - screen.printAt(width / 2, height / 2, "Not enough Data"); - return; - } + double earliest_time = series[0][sample_index].x; + double latest_time = series[0][newest_index].x; + // collect data + if (std::abs(latest_time - earliest_time) < 0.001) { + screen.printAt(width / 2, height / 2, "Not enough Data"); + return; + } - if (border) - { - screen.setPenWidth(1); - screen.setPenColor(vex::white); - screen.setFillColor(bgcol); - screen.drawRectangle(x, y, width, height); - } + if (border) { + screen.setPenWidth(1); + screen.setPenColor(vex::white); + screen.setFillColor(bgcol); + screen.drawRectangle(x, y, width, height); + } - double time_range = latest_time - earliest_time; - double sample_range = upper - lower; - screen.setPenWidth(2); + double time_range = latest_time - earliest_time; + double sample_range = upper - lower; + screen.setPenWidth(2); - for (int j = 0; j < series.size(); j++) - { - double x_s = (double)x; - double y_s = (double)y + (double)height; - const std::vector &samples = series[j]; + for (int j = 0; j < series.size(); j++) { + double x_s = (double)x; + double y_s = (double)y + (double)height; + const std::vector &samples = series[j]; - screen.setPenColor(cols[j]); - for (int i = sample_index; i < samples.size() + sample_index - 1; i++) - { - point_t p = samples[i % samples.size()]; - double x_pos = x_s + ((p.x - earliest_time) / time_range) * (double)width; - double y_pos = y_s + ((p.y - lower) / sample_range) * (double)(-height); + screen.setPenColor(cols[j]); + for (int i = sample_index; i < samples.size() + sample_index - 1; i++) { + point_t p = samples[i % samples.size()]; + double x_pos = x_s + ((p.x - earliest_time) / time_range) * (double)width; + double y_pos = y_s + ((p.y - lower) / sample_range) * (double)(-height); - point_t p2 = samples[(i + 1) % samples.size()]; - double x_pos2 = x_s + ((p2.x - earliest_time) / time_range) * (double)width; - double y_pos2 = y_s + ((p2.y - lower) / sample_range) * (double)(-height); + point_t p2 = samples[(i + 1) % samples.size()]; + double x_pos2 = x_s + ((p2.x - earliest_time) / time_range) * (double)width; + double y_pos2 = y_s + ((p2.y - lower) / sample_range) * (double)(-height); - screen.drawLine((int)x_pos, (int)y_pos, (int)x_pos2, (int)y_pos2); - } + screen.drawLine((int)x_pos, (int)y_pos, (int)x_pos2, (int)y_pos2); } + } } diff --git a/src/utils/logger.cpp b/src/utils/logger.cpp index 65ff58d..5e35b90 100644 --- a/src/utils/logger.cpp +++ b/src/utils/logger.cpp @@ -1,84 +1,71 @@ #include "../core/include/utils/logger.h" #include -void Logger::write_level(LogLevel l) -{ - unsigned char *debug = (unsigned char *)"DEBUG: "; - unsigned char *notice = (unsigned char *)"NOTICE: "; - unsigned char *warning = (unsigned char *)"WARNING: "; - unsigned char *error = (unsigned char *)"ERROR: "; - unsigned char *critical = (unsigned char *)"CRITICAL: "; - switch (l) - { - case DEBUG: - sd.appendfile(filename.c_str(), debug, 7); - break; - case NOTICE: - sd.appendfile(filename.c_str(), notice, 8); - break; - case WARNING: - sd.appendfile(filename.c_str(), warning, 9); - break; - case ERROR: - sd.appendfile(filename.c_str(), error, 7); - break; - case CRITICAL: - sd.appendfile(filename.c_str(), critical, 10); - break; - case TIME: - int32_t msec = vexSystemTimeGet(); - Logf("%d: ", msec); - break; - }; +void Logger::write_level(LogLevel l) { + unsigned char *debug = (unsigned char *)"DEBUG: "; + unsigned char *notice = (unsigned char *)"NOTICE: "; + unsigned char *warning = (unsigned char *)"WARNING: "; + unsigned char *error = (unsigned char *)"ERROR: "; + unsigned char *critical = (unsigned char *)"CRITICAL: "; + switch (l) { + case DEBUG: + sd.appendfile(filename.c_str(), debug, 7); + break; + case NOTICE: + sd.appendfile(filename.c_str(), notice, 8); + break; + case WARNING: + sd.appendfile(filename.c_str(), warning, 9); + break; + case ERROR: + sd.appendfile(filename.c_str(), error, 7); + break; + case CRITICAL: + sd.appendfile(filename.c_str(), critical, 10); + break; + case TIME: + int32_t msec = vexSystemTimeGet(); + Logf("%d: ", msec); + break; + }; } -Logger::Logger(const std::string &filename) : filename(filename) { - sd.savefile(filename.c_str(), NULL, 0); -} +Logger::Logger(const std::string &filename) : filename(filename) { sd.savefile(filename.c_str(), NULL, 0); } -void Logger::Log(const std::string &s) -{ - sd.appendfile(filename.c_str(), (unsigned char *)s.c_str(), s.size()); -} -void Logger::Log(LogLevel level, const std::string &s) -{ - write_level(level); - sd.appendfile(filename.c_str(), (unsigned char *)s.c_str(), s.size()); +void Logger::Log(const std::string &s) { sd.appendfile(filename.c_str(), (unsigned char *)s.c_str(), s.size()); } +void Logger::Log(LogLevel level, const std::string &s) { + write_level(level); + sd.appendfile(filename.c_str(), (unsigned char *)s.c_str(), s.size()); } -void Logger::Logln(const std::string &s) -{ - sd.appendfile(filename.c_str(), (unsigned char *)s.c_str(), s.size()); - unsigned char newline = '\n'; - sd.appendfile(filename.c_str(), &newline, 1); +void Logger::Logln(const std::string &s) { + sd.appendfile(filename.c_str(), (unsigned char *)s.c_str(), s.size()); + unsigned char newline = '\n'; + sd.appendfile(filename.c_str(), &newline, 1); } -void Logger::Logln(LogLevel level, const std::string &s) -{ - write_level(level); - Logln(s); +void Logger::Logln(LogLevel level, const std::string &s) { + write_level(level); + Logln(s); } -void Logger::Logf(const char *fmt, ...) -{ - char buf[MAX_FORMAT_LEN]; - va_list args; - va_start(args, fmt); - - int32_t written = vex_vsnprintf(buf, MAX_FORMAT_LEN, fmt, args); +void Logger::Logf(const char *fmt, ...) { + char buf[MAX_FORMAT_LEN]; + va_list args; + va_start(args, fmt); - va_end(args); - sd.appendfile(filename.c_str(), (unsigned char *)buf, written); + int32_t written = vex_vsnprintf(buf, MAX_FORMAT_LEN, fmt, args); + va_end(args); + sd.appendfile(filename.c_str(), (unsigned char *)buf, written); } -void Logger::Logf(LogLevel level, const char *fmt, ...) -{ - char buf[MAX_FORMAT_LEN]; +void Logger::Logf(LogLevel level, const char *fmt, ...) { + char buf[MAX_FORMAT_LEN]; - write_level(level); - va_list args; - va_start(args, fmt); - int32_t written = vex_vsnprintf(buf, MAX_FORMAT_LEN, fmt, args); - va_end(args); + write_level(level); + va_list args; + va_start(args, fmt); + int32_t written = vex_vsnprintf(buf, MAX_FORMAT_LEN, fmt, args); + va_end(args); - sd.appendfile(filename.c_str(), (unsigned char *)buf, written); + sd.appendfile(filename.c_str(), (unsigned char *)buf, written); } diff --git a/src/utils/math_util.cpp b/src/utils/math_util.cpp index 6f8e0d6..c52ca97 100644 --- a/src/utils/math_util.cpp +++ b/src/utils/math_util.cpp @@ -12,23 +12,16 @@ * @param low the minimum value that will be returned * @param high the maximum value that will be returned **/ -double clamp(double val, double low, double high) -{ - if (val < low) - { +double clamp(double val, double low, double high) { + if (val < low) { return low; - } - else if (val > high) - { + } else if (val > high) { return high; } return val; } -double lerp(double a, double b, double t) -{ - return a * (1.0 - t) + b * t; -} +double lerp(double a, double b, double t) { return a * (1.0 - t) + b * t; } /** * Returns the sign of a number @@ -36,31 +29,27 @@ double lerp(double a, double b, double t) * * returns the sign +/-1 of x. special case at 0 it returns +1 **/ -double sign(double x) -{ - if (x < 0) - { +double sign(double x) { + if (x < 0) { return -1; } return 1; } -double wrap_angle_deg(double input) -{ +double wrap_angle_deg(double input) { double angle = fmod(input, 360); if (angle < 0) { angle += 360; -} + } return angle; } -double wrap_angle_rad(double input) -{ +double wrap_angle_rad(double input) { double angle = fmod(input, 2 * PI); if (angle < 0) { angle += 2 * PI; -} + } return angle; } @@ -68,11 +57,9 @@ double wrap_angle_rad(double input) Calculates the average of a vector of doubles @param values the list of values for which the average is taken */ -double mean(std::vector const &values) -{ +double mean(std::vector const &values) { double total = 0; - for (int i = 0; i < values.size(); i++) - { + for (int i = 0; i < values.size(); i++) { total += values[i]; } return total / (double)values.size(); @@ -84,11 +71,9 @@ Calculates the variance of a set of numbers (needed for linear regression) @param values the values for which the covariance is taken @param mean the average of values */ -double variance(std::vector const &values, double mean) -{ +double variance(std::vector const &values, double mean) { double total = 0.0; - for (int i = 0; i < values.size(); i++) - { + for (int i = 0; i < values.size(); i++) { total += (values[i] - mean) * (values[i] - mean); } return total; @@ -103,11 +88,9 @@ Calculates the covariance of a set of points (needed for linear regression) @param meanx the mean value of all x coordinates in points @param meany the mean value of all y coordinates in points */ -double covariance(std::vector> const &points, double meanx, double meany) -{ +double covariance(std::vector> const &points, double meanx, double meany) { double covar = 0.0; - for (int i = 0; i < points.size(); i++) - { + for (int i = 0; i < points.size(); i++) { covar += (points[i].first - meanx) * (points[i].second - meany); } return covar; @@ -118,13 +101,12 @@ double covariance(std::vector> const &points, double m * @param points the points for the data * @return slope, y intercept. y = m(x)+b. std::pair */ -std::pair calculate_linear_regression(std::vector> const &points) -{ - // Purely for convenience and the ability to reuse mean() and variance() - can be easily rewritten to avoid allocating these if the code is repeatedly called +std::pair calculate_linear_regression(std::vector> const &points) { + // Purely for convenience and the ability to reuse mean() and variance() - can be easily rewritten to avoid allocating + // these if the code is repeatedly called std::vector xs(points.size(), 0.0); std::vector ys(points.size(), 0.0); - for (int i = 0; i < points.size(); i++) - { + for (int i = 0; i < points.size(); i++) { xs[i] = points[i].first; ys[i] = points[i].second; } @@ -138,18 +120,16 @@ std::pair calculate_linear_regression(std::vector(slope, y_intercept); } -double estimate_path_length(const std::vector &points) -{ +double estimate_path_length(const std::vector &points) { double dist = 0; - for (point_t p : points) - { + for (point_t p : points) { static point_t last_p = p; // Ignore the first point if (p == last_p) { continue; -} + } dist += p.dist(last_p); last_p = p; diff --git a/src/utils/moving_average.cpp b/src/utils/moving_average.cpp index 1073776..14803a6 100644 --- a/src/utils/moving_average.cpp +++ b/src/utils/moving_average.cpp @@ -1,17 +1,19 @@ -#include #include "../core/include/utils/moving_average.h" #include +#include /* * MovingAverage * - * A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric around the actual value. - * This means that if you collect enough samples those that are too high are cancelled out by the samples that are too low leaving the real value. + * A moving average is a way of smoothing out noisy data. For many sensor readings, the noise is roughly symmetric + * around the actual value. This means that if you collect enough samples those that are too high are cancelled out by + * the samples that are too low leaving the real value. * * The MovingAverage class provides a simple interface to do this smoothing from our noisy sensor values. * - * WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' behind the actual value that the sensor is reading. - * Using a MovingAverage is thus a tradeoff between accuracy and lag time (more samples) vs. less accuracy and faster updating (less samples). + * WARNING: because we need a lot of samples to get the actual value, the value given by the MovingAverage will 'lag' + * behind the actual value that the sensor is reading. Using a MovingAverage is thus a tradeoff between accuracy and lag + * time (more samples) vs. less accuracy and faster updating (less samples). * */ @@ -20,8 +22,7 @@ * * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading */ -MovingAverage::MovingAverage(int buffer_size) -{ +MovingAverage::MovingAverage(int buffer_size) { buffer = std::vector(buffer_size, 0.0); buffer_index = 0; current_avg = 0; @@ -32,8 +33,7 @@ MovingAverage::MovingAverage(int buffer_size) * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading * @param starting_value The value that the average will be before any data is added */ -MovingAverage::MovingAverage(int buffer_size, double starting_value) -{ +MovingAverage::MovingAverage(int buffer_size, double starting_value) { buffer = std::vector(buffer_size, starting_value); buffer_index = 0; current_avg = starting_value; @@ -49,8 +49,7 @@ MovingAverage::MovingAverage(int buffer_size, double starting_value) * ^ * @param n the sample that will be added to the moving average. */ -void MovingAverage::add_entry(double n) -{ +void MovingAverage::add_entry(double n) { current_avg -= buffer[buffer_index] / (double)get_size(); current_avg += n / get_size(); buffer[buffer_index] = n; @@ -63,24 +62,17 @@ void MovingAverage::add_entry(double n) * How many samples the average is made from * @return the number of samples used to calculate this average */ -double MovingAverage::get_value() const -{ - return current_avg; -} +double MovingAverage::get_value() const { return current_avg; } // How many samples the average is made from -int MovingAverage::get_size() const -{ - return buffer.size(); -} +int MovingAverage::get_size() const { return buffer.size(); } /** * Create a moving average calculator with 0 as the default value * * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading */ -ExponentialMovingAverage::ExponentialMovingAverage(int buffer_size) -{ +ExponentialMovingAverage::ExponentialMovingAverage(int buffer_size) { buffer = std::vector(buffer_size, 0.0); buffer_index = 0; current_avg = 0; @@ -91,8 +83,7 @@ ExponentialMovingAverage::ExponentialMovingAverage(int buffer_size) * @param buffer_size The size of the buffer. The number of samples that constitute a valid reading * @param starting_value The value that the average will be before any data is added */ -ExponentialMovingAverage::ExponentialMovingAverage(int buffer_size, double starting_value) -{ +ExponentialMovingAverage::ExponentialMovingAverage(int buffer_size, double starting_value) { buffer = std::vector(buffer_size, starting_value); buffer_index = 0; current_avg = starting_value; @@ -108,8 +99,7 @@ ExponentialMovingAverage::ExponentialMovingAverage(int buffer_size, double start * ^ * @param n the sample that will be added to the moving average. */ -void ExponentialMovingAverage::add_entry(double n) -{ +void ExponentialMovingAverage::add_entry(double n) { int oldest_index = buffer_index; double oldest_sample = buffer[oldest_index]; double oldest_weight = 1.0 / pow(2, (double)(buffer.size() - 1)); @@ -131,13 +121,7 @@ void ExponentialMovingAverage::add_entry(double n) * How many samples the average is made from * @return the number of samples used to calculate this average */ -double ExponentialMovingAverage::get_value() const -{ - return current_avg; -} +double ExponentialMovingAverage::get_value() const { return current_avg; } // How many samples the average is made from -int ExponentialMovingAverage::get_size() -{ - return buffer.size(); -} +int ExponentialMovingAverage::get_size() { return buffer.size(); } diff --git a/src/utils/pure_pursuit.cpp b/src/utils/pure_pursuit.cpp index ffdd36b..b33e4e1 100644 --- a/src/utils/pure_pursuit.cpp +++ b/src/utils/pure_pursuit.cpp @@ -10,26 +10,28 @@ PurePursuit::Path::Path(std::vector points, double radius) { this->radius = radius; this->valid = true; - for(int i = 0; i < points.size() - 1; i++) { - for(int j = i + 2; j < points.size() - 1; j++) { + for (int i = 0; i < points.size() - 1; i++) { + for (int j = i + 2; j < points.size() - 1; j++) { // Iterate over points on the segments discretely and compare distances - double segment_i_dist = points[i].dist(points[i+1]); - if (segment_i_dist == 0) { segment_i_dist = 0.1; -} - double segment_j_dist = points[j].dist(points[j+1]); - if (segment_j_dist == 0) { segment_j_dist = 0.1; -} - for(double t1 = 0; t1 <= 1; t1 += radius / segment_i_dist) { + double segment_i_dist = points[i].dist(points[i + 1]); + if (segment_i_dist == 0) { + segment_i_dist = 0.1; + } + double segment_j_dist = points[j].dist(points[j + 1]); + if (segment_j_dist == 0) { + segment_j_dist = 0.1; + } + for (double t1 = 0; t1 <= 1; t1 += radius / segment_i_dist) { point_t p1; - p1.x = points[i].x + t1 * (points[i+1].x - points[i].x); - p1.y = points[i].y + t1 * (points[i+1].y - points[i].y); + p1.x = points[i].x + t1 * (points[i + 1].x - points[i].x); + p1.y = points[i].y + t1 * (points[i + 1].y - points[i].y); - for(double t2 = 0; t2 <= 1; t2 += radius / segment_j_dist) { + for (double t2 = 0; t2 <= 1; t2 += radius / segment_j_dist) { point_t p2; - p2.x = points[j].x + t2 * (points[j+1].x - points[j].x); - p2.y = points[j].y + t2 * (points[j+1].y - points[j].y); + p2.x = points[j].x + t2 * (points[j + 1].x - points[j].x); + p2.y = points[j].y + t2 * (points[j + 1].y - points[j].y); - if(p1.dist(p2) < radius) { + if (p1.dist(p2) < radius) { this->valid = false; return; } @@ -42,67 +44,59 @@ PurePursuit::Path::Path(std::vector points, double radius) { /** * Get the points associated with this Path */ -std::vector PurePursuit::Path::get_points() { - return this->points; -} +std::vector PurePursuit::Path::get_points() { return this->points; } /** * Get the radius associated with this Path */ -double PurePursuit::Path::get_radius() { - return this->radius; -} +double PurePursuit::Path::get_radius() { return this->radius; } /** * Get whether this path will behave as expected */ -bool PurePursuit::Path::is_valid() { - return this->valid; -} +bool PurePursuit::Path::is_valid() { return this->valid; } /** - * Returns points of the intersections of a line segment and a circle. The line - * segment is defined by two points, and the circle is defined by a center and radius. - */ -std::vector PurePursuit::line_circle_intersections(point_t center, double r, point_t point1, point_t point2) -{ + * Returns points of the intersections of a line segment and a circle. The line + * segment is defined by two points, and the circle is defined by a center and radius. + */ +std::vector PurePursuit::line_circle_intersections(point_t center, double r, point_t point1, point_t point2) { std::vector intersections = {}; - //Do future calculations relative to the circle's center + // Do future calculations relative to the circle's center point1.y -= center.y; point1.x -= center.x; point2.y -= center.y; point2.x -= center.x; double x1, x2, y1, y2; - //Handling an infinite slope using mx+b and x^2 + y^2 = r^2 - if(point1.x - point2.x == 0) - { + // Handling an infinite slope using mx+b and x^2 + y^2 = r^2 + if (point1.x - point2.x == 0) { x1 = point1.x; y1 = sqrt(pow(r, 2) - pow(x1, 2)); x2 = point1.x; y2 = -sqrt(pow(r, 2) - pow(x2, 2)); } - //Non-infinite slope using mx+b and x^2 + y^2 = r^2 - else - { + // Non-infinite slope using mx+b and x^2 + y^2 = r^2 + else { double m = (point1.y - point2.y) / (point1.x - point2.x); double b = point1.y - (m * point1.x); - x1 = ((-m * b) + sqrt(pow(r, 2) + (pow(m, 2) * pow(r, 2)) - pow(b, 2))) / (1 + pow(m,2)); + x1 = ((-m * b) + sqrt(pow(r, 2) + (pow(m, 2) * pow(r, 2)) - pow(b, 2))) / (1 + pow(m, 2)); y1 = m * x1 + b; - x2 = ((-m * b) - sqrt(pow(r, 2) + (pow(m, 2) * pow(r, 2)) - pow(b, 2))) / (1 + pow(m,2)); + x2 = ((-m * b) - sqrt(pow(r, 2) + (pow(m, 2) * pow(r, 2)) - pow(b, 2))) / (1 + pow(m, 2)); y2 = m * x2 + b; } - //The equations used define an infinitely long line, so we check if the detected intersection falls on the line segment. - if(x1 >= fmin(point1.x, point2.x) && x1 <= fmax(point1.x, point2.x) && y1 >= fmin(point1.y, point2.y) && y1 <= fmax(point1.y, point2.y)) - { + // The equations used define an infinitely long line, so we check if the detected intersection falls on the line + // segment. + if (x1 >= fmin(point1.x, point2.x) && x1 <= fmax(point1.x, point2.x) && y1 >= fmin(point1.y, point2.y) && + y1 <= fmax(point1.y, point2.y)) { intersections.push_back(point_t{.x = x1 + center.x, .y = y1 + center.y}); } - if(x2 >= fmin(point1.x, point2.x) && x2 <= fmax(point1.x, point2.x) && y2 >= fmin(point1.y, point2.y) && y2 <= fmax(point1.y, point2.y)) - { + if (x2 >= fmin(point1.x, point2.x) && x2 <= fmax(point1.x, point2.x) && y2 >= fmin(point1.y, point2.y) && + y2 <= fmax(point1.y, point2.y)) { intersections.push_back(point_t{.x = x2 + center.x, .y = y2 + center.y}); } @@ -112,31 +106,26 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub /** * Selects a look ahead from all the intersections in the path. */ -[[maybe_unused]] point_t PurePursuit::get_lookahead(const std::vector &path, pose_t robot_loc, double radius) -{ - //Default: the end of the path +[[maybe_unused]] point_t PurePursuit::get_lookahead(const std::vector &path, pose_t robot_loc, double radius) { + // Default: the end of the path point_t target = path.back(); - - if(target.dist(robot_loc.get_point()) <= radius) - { + if (target.dist(robot_loc.get_point()) <= radius) { return target; } - - //Check each line segment of the path for potential targets - for(int i = 0; i < path.size() - 1; i++) - { + + // Check each line segment of the path for potential targets + for (int i = 0; i < path.size() - 1; i++) { point_t start = path[i]; - point_t end = path[i+1]; + point_t end = path[i + 1]; std::vector intersections = line_circle_intersections(robot_loc.get_point(), radius, start, end); - //Choose the intersection that is closest to the end of the line segment - //This prioritizes the closest intersection to the end of the path - for(point_t intersection: intersections) - { - if(intersection.dist(end) < target.dist(end)) { + // Choose the intersection that is closest to the end of the line segment + // This prioritizes the closest intersection to the end of the path + for (point_t intersection : intersections) { + if (intersection.dist(end) < target.dist(end)) { target = intersection; -} + } } } @@ -146,32 +135,29 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub /** Injects points in a path without changing the curvature with a certain spacing. */ -[[maybe_unused]] std::vector PurePursuit::inject_path(const std::vector &path, double spacing) -{ +[[maybe_unused]] std::vector PurePursuit::inject_path(const std::vector &path, double spacing) { std::vector new_path; - //Injecting points for each line segment - for(int i = 0; i < path.size() - 1; i++) - { + // Injecting points for each line segment + for (int i = 0; i < path.size() - 1; i++) { point_t start = path[i]; - point_t end = path[i+1]; + point_t end = path[i + 1]; point_t diff = end - start; Vector2D vector = Vector2D(diff); - + int num_points = ceil(vector.get_mag() / spacing); - //This is the vector between each point + // This is the vector between each point vector = vector.normalize() * spacing; - for(int j = 0; j < num_points; j++) - { - //We take the start point and add additional vectors + for (int j = 0; j < num_points; j++) { + // We take the start point and add additional vectors point_t path_point = (Vector2D(start) + vector * j).point(); new_path.push_back(path_point); } } - //Adds the last point + // Adds the last point new_path.push_back(path.back()); return new_path; } @@ -185,28 +171,26 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub * * Honestly have no idea if/how this works. * https://medium.com/@jaems33/understanding-robot-motion-path-smoothing-5970c8363bc4 -*/ -[[maybe_unused]] std::vector PurePursuit::smooth_path(const std::vector &path, double weight_data, double weight_smooth, double tolerance) -{ + */ +[[maybe_unused]] std::vector PurePursuit::smooth_path(const std::vector &path, double weight_data, + double weight_smooth, double tolerance) { std::vector new_path = path; double change = tolerance; - while(change >= tolerance) - { + while (change >= tolerance) { change = 0; - for(int i = 1; i < path.size() - 1; i++) - { - point_t x_i = path[i]; - point_t y_i = new_path[i]; - point_t y_prev = new_path[i-1]; - point_t y_next = new_path[i+1]; - - point_t y_i_saved = y_i; - - y_i.x += weight_data * (x_i.x - y_i.x) + weight_smooth * (y_next.x + y_prev.x - (2 * y_i.x)); - y_i.y += weight_data * (x_i.y - y_i.y) + weight_smooth * (y_next.y + y_prev.y - (2 * y_i.y)); - new_path[i] = y_i; - - change += y_i.dist(y_i_saved); + for (int i = 1; i < path.size() - 1; i++) { + point_t x_i = path[i]; + point_t y_i = new_path[i]; + point_t y_prev = new_path[i - 1]; + point_t y_next = new_path[i + 1]; + + point_t y_i_saved = y_i; + + y_i.x += weight_data * (x_i.x - y_i.x) + weight_smooth * (y_next.x + y_prev.x - (2 * y_i.x)); + y_i.y += weight_data * (x_i.y - y_i.y) + weight_smooth * (y_next.y + y_prev.y - (2 * y_i.y)); + new_path[i] = y_i; + + change += y_i.dist(y_i_saved); } } return new_path; @@ -220,78 +204,73 @@ std::vector PurePursuit::line_circle_intersections(point_t center, doub * @param steps The number of points interpolated between points. * @return The smoothed path. */ -[[maybe_unused]] std::vector PurePursuit::smooth_path_hermite(const std::vector &path, double steps) { +[[maybe_unused]] std::vector PurePursuit::smooth_path_hermite(const std::vector &path, + double steps) { std::vector new_path; - for(int i = 0; i < path.size() - 1; i++) { - for(int t = 0; t < steps; t++) { + for (int i = 0; i < path.size() - 1; i++) { + for (int t = 0; t < steps; t++) { // Storing the start and end points and slopes at those points as Vector2Ds. point_t tmp = path[i].getPoint(); Vector2D p1 = Vector2D(tmp); - tmp = path[i+1].getPoint(); + tmp = path[i + 1].getPoint(); Vector2D p2 = Vector2D(tmp); Vector2D t1 = path[i].getTangent(); - Vector2D t2 = path[i+1].getTangent(); - + Vector2D t2 = path[i + 1].getTangent(); // Scale s from 0.0 to 1.0 double s = (double)t / (double)steps; // Hermite Blending functions - double h1 = 2 * pow(s, 3) - 3 * pow(s, 2) + 1; + double h1 = 2 * pow(s, 3) - 3 * pow(s, 2) + 1; double h2 = -2 * pow(s, 3) + 3 * pow(s, 2); double h3 = pow(s, 3) - 2 * pow(s, 2) + s; double h4 = pow(s, 3) - pow(s, 2); // Calculate the point - Vector2D p = p1 * h1 + p2 * h2 + t1 * h3 + t2 * h4; + Vector2D p = p1 * h1 + p2 * h2 + t1 * h3 + t2 * h4; new_path.push_back(p.point()); } } - //Adding last point + // Adding last point new_path.push_back(path.back().getPoint()); return new_path; } - /** * Estimates the remaining distance from the robot's position to the end, * by "searching" for the robot along the path and running a "connect the dots" * distance algoritm - * + * * @param path The pure pursuit path the robot is following * @param robot_pose The robot's current position * @param radius Pure pursuit "radius", used to search for the robot along the path * @return A rough estimate of the remaining distance -*/ -double PurePursuit::estimate_remaining_dist(const std::vector &path, pose_t robot_pose, double radius) -{ + */ +double PurePursuit::estimate_remaining_dist(const std::vector &path, pose_t robot_pose, double radius) { point_t lookahead_pt = get_lookahead(path, robot_pose, radius); - + if (lookahead_pt == path[path.size() - 1]) { return robot_pose.get_point().dist(lookahead_pt); -} + } double dist = 0; // Run through the path backwards, adding distances - for(int i = path.size()-1; i >= 0; i--) - { + for (int i = path.size() - 1; i >= 0; i--) { // Test if the robot is between the two points - auto pts = line_circle_intersections(robot_pose.get_point(), radius, path[i-1], path[i]); - + auto pts = line_circle_intersections(robot_pose.get_point(), radius, path[i - 1], path[i]); + // There is an intersection? Robot is between the points so add the distance // from the bot to the next point and end. - if(!pts.empty()) - { + if (!pts.empty()) { dist += robot_pose.get_point().dist(path[i]); return dist; } - + // No intersections? Add the distance between the two points and move backwards // in the path until we find the robot, or run out of points. - dist += path[i-1].dist(path[i]); + dist += path[i - 1].dist(path[i]); } return dist; } - diff --git a/src/utils/serializer.cpp b/src/utils/serializer.cpp index fd756e3..c0b60da 100644 --- a/src/utils/serializer.cpp +++ b/src/utils/serializer.cpp @@ -9,55 +9,44 @@ /// @brief Convert type to bytes. Overload this for non integer types /// @param value value to convert -template -std::vector to_bytes(T value) -{ - // copy bytes of data into vector - std::vector value_bytes(sizeof(T)); - std::copy(static_cast(static_cast(&value)), - static_cast(static_cast(&value)) + sizeof(value), - value_bytes.begin()); - return value_bytes; +template std::vector to_bytes(T value) { + // copy bytes of data into vector + std::vector value_bytes(sizeof(T)); + std::copy(static_cast(static_cast(&value)), + static_cast(static_cast(&value)) + sizeof(value), value_bytes.begin()); + return value_bytes; } -template <> -std::vector to_bytes(std::string str) -{ - std::vector value_bytes(str.size() + 1); - std::copy(str.begin(), str.end(), value_bytes.begin()); - value_bytes[str.size()] = 0x0; - return value_bytes; +template <> std::vector to_bytes(std::string str) { + std::vector value_bytes(str.size() + 1); + std::copy(str.begin(), str.end(), value_bytes.begin()); + value_bytes[str.size()] = 0x0; + return value_bytes; } /// @brief Convert bytes to a type /// @param gets data from arbitrary bytes. Overload this for non integer types -template -T from_bytes(std::vector::const_iterator &position) -{ - T value; - std::copy(position, position + sizeof(T), static_cast(static_cast(&value))); - position = position + sizeof(T); - return value; +template T from_bytes(std::vector::const_iterator &position) { + T value; + std::copy(position, position + sizeof(T), static_cast(static_cast(&value))); + position = position + sizeof(T); + return value; } -template <> -std::string from_bytes(std::vector::const_iterator &position) -{ - auto pos = position; - while (*pos != 0x0) - { - ++pos; - } - std::string s(position, pos); - position = pos + 1; - return s; +template <> std::string from_bytes(std::vector::const_iterator &position) { + auto pos = position; + while (*pos != 0x0) { + ++pos; + } + std::string s(position, pos); + position = pos + 1; + return s; } /// @brief Replaces funny characters in names so they don't mess with serialization specifiers -std::string sanitize_name(std::string s) -{ - std::replace(s.begin(), s.end(), serialization_separator, '-'); - return s; +std::string sanitize_name(std::string s) { + std::replace(s.begin(), s.end(), serialization_separator, '-'); + return s; } // Protocol @@ -82,186 +71,155 @@ std::string sanitize_name(std::string s) /// @param data the bytes to add to /// @param map the values and names we are talking about template -static void add_data(std::vector &data, const std::map &map) -{ - for (const auto &pair : map) - { - const std::string &name = pair.first; - const value_type value = pair.second; +static void add_data(std::vector &data, const std::map &map) { + for (const auto &pair : map) { + const std::string &name = pair.first; + const value_type value = pair.second; - data.insert(data.end(), name.cbegin(), name.cend()); - data.insert(data.end(), 0x0); + data.insert(data.end(), name.cbegin(), name.cend()); + data.insert(data.end(), 0x0); - auto bytes = to_bytes(value); - data.insert(data.end(), bytes.cbegin(), bytes.cend()); - } - data.push_back(serialization_separator); + auto bytes = to_bytes(value); + data.insert(data.end(), bytes.cbegin(), bytes.cend()); + } + data.push_back(serialization_separator); } // reads data of a certain type from a file template static std::vector::const_iterator read_data(std::vector::const_iterator begin, - std::map &map) -{ - std::vector::const_iterator pos = begin; - - while (*pos != serialization_separator) - { - auto name_start = pos; - // read name - std::string name = from_bytes(name_start); - pos += name.size() + 1; - // read value - value_type value = from_bytes(pos); - printf("Read Name: %s\n", name.c_str()); - map.insert({name, value}); - } - - return pos + 1; -} - -void Serializer::set_int(const std::string &name, int i) -{ - ints[sanitize_name(name)] = i; - if (flush_always) - { - save_to_disk(); - } -} -void Serializer::set_bool(const std::string &name, bool b) -{ - bools[sanitize_name(name)] = b; - if (flush_always) - { - save_to_disk(); - } -} -void Serializer::set_double(const std::string &name, double d) -{ - doubles[sanitize_name(name)] = d; - if (flush_always) - { - save_to_disk(); - } -} -void Serializer::set_string(const std::string &name, std::string str) -{ - strings[sanitize_name(name)] = str; - if (flush_always) - { - save_to_disk(); - } -} - -int Serializer::int_or(const std::string &name, int otherwise) -{ - if (ints.count(name)) - { - return ints.at(name); - } - set_int(name, otherwise); - return otherwise; -} -bool Serializer::bool_or(const std::string &name, bool otherwise) -{ - if (bools.count(name)) - { - return bools.at(name); - } - set_bool(name, otherwise); - return otherwise; -} -double Serializer::double_or(const std::string &name, double otherwise) -{ - if (doubles.count(name)) - { - return doubles.at(name); - } - set_double(name, otherwise); - return otherwise; -} -std::string Serializer::string_or(const std::string &name, std::string otherwise) -{ - if (strings.count(name)) - { - return strings.at(name); - } - set_string(name, otherwise); - return otherwise; + std::map &map) { + std::vector::const_iterator pos = begin; + + while (*pos != serialization_separator) { + auto name_start = pos; + // read name + std::string name = from_bytes(name_start); + pos += name.size() + 1; + // read value + value_type value = from_bytes(pos); + printf("Read Name: %s\n", name.c_str()); + map.insert({name, value}); + } + + return pos + 1; +} + +void Serializer::set_int(const std::string &name, int i) { + ints[sanitize_name(name)] = i; + if (flush_always) { + save_to_disk(); + } +} +void Serializer::set_bool(const std::string &name, bool b) { + bools[sanitize_name(name)] = b; + if (flush_always) { + save_to_disk(); + } +} +void Serializer::set_double(const std::string &name, double d) { + doubles[sanitize_name(name)] = d; + if (flush_always) { + save_to_disk(); + } +} +void Serializer::set_string(const std::string &name, std::string str) { + strings[sanitize_name(name)] = str; + if (flush_always) { + save_to_disk(); + } +} + +int Serializer::int_or(const std::string &name, int otherwise) { + if (ints.count(name)) { + return ints.at(name); + } + set_int(name, otherwise); + return otherwise; +} +bool Serializer::bool_or(const std::string &name, bool otherwise) { + if (bools.count(name)) { + return bools.at(name); + } + set_bool(name, otherwise); + return otherwise; +} +double Serializer::double_or(const std::string &name, double otherwise) { + if (doubles.count(name)) { + return doubles.at(name); + } + set_double(name, otherwise); + return otherwise; +} +std::string Serializer::string_or(const std::string &name, std::string otherwise) { + if (strings.count(name)) { + return strings.at(name); + } + set_string(name, otherwise); + return otherwise; } /// @brief forms data bytes then saves to filename this was openned with -void Serializer::save_to_disk() const -{ - vex::brain::sdcard sd; - if (!sd.isInserted()) - { - printf("!! Trying to Serialize to No SD Card !!\n"); - return; - } - - std::vector data = {}; - add_data(data, ints); - add_data(data, bools); - add_data(data, doubles); - add_data(data, strings); - - - int32_t written = sd.savefile(filename.c_str(), (unsigned char *)&data[0], data.size()); - if (written != data.size()) - { - printf("!! Error writing to `%s`!!\n", filename.c_str()); - return; - } +void Serializer::save_to_disk() const { + vex::brain::sdcard sd; + if (!sd.isInserted()) { + printf("!! Trying to Serialize to No SD Card !!\n"); + return; + } + + std::vector data = {}; + add_data(data, ints); + add_data(data, bools); + add_data(data, doubles); + add_data(data, strings); + + int32_t written = sd.savefile(filename.c_str(), (unsigned char *)&data[0], data.size()); + if (written != data.size()) { + printf("!! Error writing to `%s`!!\n", filename.c_str()); + return; + } } /// @brief reads types from file data -bool Serializer::read_from_disk() -{ - vex::brain::sdcard sd; - if (!sd.isInserted()) - { - printf("!! Trying to Serialize to No SD Card !!\n"); - return false; - } - int size = sd.size(filename.c_str()); - if (size == 0) - { - ints = {}; - doubles = {}; - bools = {}; - return true; - } - - if (filename == "") - { - printf("!! Can't write to empty filename!!\n"); - return false; - } - - if (!sd.exists(filename.c_str())) - { - printf("!!f Trying to Serialize to a file that doesnt exist: Creating %s !!\n", filename.c_str()); - save_to_disk(); - return false; - } - - std::vector data(size); - - int readsize = sd.loadfile(filename.c_str(), (unsigned char *)&data[0], size); - if (size != readsize) - { - printf("!! Error reading from file !!"); - ; - return false; - } - - - auto bool_start = read_data(data.cbegin(), ints); - auto doubles_start = read_data(bool_start, bools); - auto strings_start = read_data(doubles_start, doubles); - auto file_end = read_data(strings_start, strings); - (void)file_end; - +bool Serializer::read_from_disk() { + vex::brain::sdcard sd; + if (!sd.isInserted()) { + printf("!! Trying to Serialize to No SD Card !!\n"); + return false; + } + int size = sd.size(filename.c_str()); + if (size == 0) { + ints = {}; + doubles = {}; + bools = {}; return true; + } + + if (filename == "") { + printf("!! Can't write to empty filename!!\n"); + return false; + } + + if (!sd.exists(filename.c_str())) { + printf("!!f Trying to Serialize to a file that doesnt exist: Creating %s !!\n", filename.c_str()); + save_to_disk(); + return false; + } + + std::vector data(size); + + int readsize = sd.loadfile(filename.c_str(), (unsigned char *)&data[0], size); + if (size != readsize) { + printf("!! Error reading from file !!"); + ; + return false; + } + + auto bool_start = read_data(data.cbegin(), ints); + auto doubles_start = read_data(bool_start, bools); + auto strings_start = read_data(doubles_start, doubles); + auto file_end = read_data(strings_start, strings); + (void)file_end; + + return true; } diff --git a/src/utils/trapezoid_profile.cpp b/src/utils/trapezoid_profile.cpp index 98014ba..0555ea9 100644 --- a/src/utils/trapezoid_profile.cpp +++ b/src/utils/trapezoid_profile.cpp @@ -5,17 +5,13 @@ const double EPSILON = 0.000005; -inline double calc_pos(double t, double a, double v, double si) { - return (0.5 * (a) * (t) * (t)) + ((v) * (t)) + (si); -} +inline double calc_pos(double t, double a, double v, double si) { return (0.5 * (a) * (t) * (t)) + ((v) * (t)) + (si); } -inline double calc_vel(double t, double a, double vi) { - return ((a) * (t)) + (vi); -} +inline double calc_vel(double t, double a, double vi) { return ((a) * (t)) + (vi); } TrapezoidProfile::TrapezoidProfile(double max_v, double accel) - : si(0), sf(0), vi(0), vf(0), max_v(max_v), accel(accel), segments(), - num_acceleration_phases(0), precalculated(false) {} + : si(0), sf(0), vi(0), vf(0), max_v(max_v), accel(accel), segments(), num_acceleration_phases(0), + precalculated(false) {} void TrapezoidProfile::set_max_v(double max_v) { this->max_v = max_v; @@ -46,7 +42,7 @@ void TrapezoidProfile::set_vel_endpts(double start, double end) { motion_t TrapezoidProfile::calculate_time_based(double time_s) { if (!this->precalculated) { precalculate(); -} + } int segment_i = 0; @@ -58,8 +54,7 @@ motion_t TrapezoidProfile::calculate_time_based(double time_s) { double segment_t = 0; // skip phases based on time - while (segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS && - time_s > segment_t + this->segments[segment_i].duration) { + while (segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS && time_s > segment_t + this->segments[segment_i].duration) { segment_t += this->segments[segment_i].duration; segment_s = this->segments[segment_i].pos_after; segment_v = this->segments[segment_i].vel_after; @@ -88,7 +83,7 @@ motion_t TrapezoidProfile::calculate_time_based(double time_s) { motion_t TrapezoidProfile::calculate(double time_s, double pos_s) { if (!this->precalculated) { precalculate(); -} + } // printf("%f %f\n", time_s, pos_s); @@ -102,8 +97,7 @@ motion_t TrapezoidProfile::calculate(double time_s, double pos_s) { double segment_t = 0; // skip acceleration phases based on time - while (segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS && - segment_i < this->num_acceleration_phases && + while (segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS && segment_i < this->num_acceleration_phases && time_s > segment_t + this->segments[segment_i].duration) { segment_t += this->segments[segment_i].duration; segment_s = this->segments[segment_i].pos_after; @@ -114,11 +108,9 @@ motion_t TrapezoidProfile::calculate(double time_s, double pos_s) { // skip other segments based on distance, if we are past the time segments if (segment_i >= this->num_acceleration_phases) { - while ( - segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS && - ((this->si < this->sf && pos_s > this->segments[segment_i].pos_after) || - (this->si > this->sf && - pos_s < this->segments[segment_i].pos_after))) { + while (segment_i < MAX_TRAPEZOID_PROFILE_SEGMENTS && + ((this->si < this->sf && pos_s > this->segments[segment_i].pos_after) || + (this->si > this->sf && pos_s < this->segments[segment_i].pos_after))) { segment_t += this->segments[segment_i].duration; segment_s = this->segments[segment_i].pos_after; segment_v = this->segments[segment_i].vel_after; @@ -157,7 +149,7 @@ motion_t TrapezoidProfile::calculate(double time_s, double pos_s) { // match the sign of the starting velocity of the segment if (segment_v < 0) { out.vel *= -1; -} + } return out; } @@ -193,12 +185,11 @@ bool TrapezoidProfile::precalculate() { this->vf = this->max_v; } else { this->vf = -this->max_v; -} + } } // if displacement is + but vf is -, or if displacement is - but vf is + - if ((this->si < this->sf && this->vf < 0) || - (this->si > this->sf && this->vf > 0)) { + if ((this->si < this->sf && this->vf < 0) || (this->si > this->sf && this->vf > 0)) { printf("WARNING: trapezoid motion profile target velocity is in the wrong " "direction\n"); this->vf = 0; @@ -214,7 +205,7 @@ bool TrapezoidProfile::precalculate() { if (fabs(segment.pos_after - this->sf) < EPSILON) { return true; -} + } // Check if xf is between x and x_next (meaning we overshot the end // position) @@ -226,7 +217,7 @@ bool TrapezoidProfile::precalculate() { double a_coeff = 0.5 * segment.accel; if (fabs(a_coeff) < EPSILON) { a_coeff = EPSILON; -} + } double b_coeff = v; double c_coeff = s - this->sf; @@ -260,9 +251,7 @@ bool TrapezoidProfile::precalculate() { return false; } -trapezoid_profile_segment_t -TrapezoidProfile::calculate_kinetic_motion(double si, double vi, - double v_target) { +trapezoid_profile_segment_t TrapezoidProfile::calculate_kinetic_motion(double si, double vi, double v_target) { trapezoid_profile_segment_t m; m.duration = fabs(v_target - vi) / this->accel; @@ -277,8 +266,7 @@ TrapezoidProfile::calculate_kinetic_motion(double si, double vi, return m; } -trapezoid_profile_segment_t TrapezoidProfile::calculate_next_segment(double s, - double v) { +trapezoid_profile_segment_t TrapezoidProfile::calculate_next_segment(double s, double v) { // d represents the direction of travel, + or - int d = 1; if (this->si > this->sf) { @@ -298,8 +286,7 @@ trapezoid_profile_segment_t TrapezoidProfile::calculate_next_segment(double s, } // how much distance would it take to reach vf in one segment? - trapezoid_profile_segment_t beeline_vf = - calculate_kinetic_motion(s, v, this->vf); + trapezoid_profile_segment_t beeline_vf = calculate_kinetic_motion(s, v, this->vf); if ((d == 1 && beeline_vf.pos_after > this->sf - EPSILON) || (d == -1 && beeline_vf.pos_after <= this->sf + EPSILON)) { // we can't make it to vf - get as close as possible @@ -309,8 +296,7 @@ trapezoid_profile_segment_t TrapezoidProfile::calculate_next_segment(double s, // we can reach vf in one segment - choose the fastest speed so that that is // still possible double v_middle = - d * sqrt(((v * v + this->vf * this->vf) / 2.0) + - this->accel * fabs(this->sf - s) + this->vf * this->vf); + d * sqrt(((v * v + this->vf * this->vf) / 2.0) + this->accel * fabs(this->sf - s) + this->vf * this->vf); // cap this at our max speed v_middle = fmax(-this->max_v, fmin(v_middle, this->max_v)); diff --git a/src/utils/vector2d.cpp b/src/utils/vector2d.cpp index 8399b5f..e16822e 100644 --- a/src/utils/vector2d.cpp +++ b/src/utils/vector2d.cpp @@ -2,34 +2,29 @@ /** * Construct a vector object. - * + * * @param dir Direction, in radians. 'foward' is 0, clockwise positive when viewed from the top. * @param mag Magnitude. */ -Vector2D::Vector2D(double dir, double mag) -: dir(dir), mag(mag) -{ - -} +Vector2D::Vector2D(double dir, double mag) : dir(dir), mag(mag) {} /** * Construct a vector object from a cartesian point. - * + * * @param p point_t.x , point_t.y */ -Vector2D::Vector2D(point_t p) -{ - this->dir = atan2(p.y, p.x); - this->mag = sqrt( (p.x*p.x) + (p.y*p.y) ); +Vector2D::Vector2D(point_t p) { + this->dir = atan2(p.y, p.x); + this->mag = sqrt((p.x * p.x) + (p.y * p.y)); } /** * Get the direction of the vector, in radians. * '0' is forward, clockwise positive when viewed from the top. - * + * * Use r2d() to convert. */ -double Vector2D::get_dir() const { return dir;} +double Vector2D::get_dir() const { return dir; } /** * Get the magnitude of the vector @@ -39,38 +34,24 @@ double Vector2D::get_mag() const { return mag; } /** * Get the X component of the vector; positive to the right. */ -double Vector2D::get_x() const -{ -return mag * cos(dir); -} +double Vector2D::get_x() const { return mag * cos(dir); } /** * Get the Y component of the vector, positive forward. */ -double Vector2D::get_y() const -{ -return mag * sin(dir); -} +double Vector2D::get_y() const { return mag * sin(dir); } /** * Changes the magnetude of the vector to 1 -*/ -Vector2D Vector2D::normalize() -{ - return Vector2D(this->dir, 1); -} + */ +Vector2D Vector2D::normalize() { return Vector2D(this->dir, 1); } /** * Convert a direction and magnitude representation to an x, y representation - * @return the x, y representation of the vector -*/ -point_t Vector2D::point() -{ - point_t p = - { - .x = this->mag * cos(this->dir), - .y = this->mag * sin(this->dir) - }; + * @return the x, y representation of the vector + */ +point_t Vector2D::point() { + point_t p = {.x = this->mag * cos(this->dir), .y = this->mag * sin(this->dir)}; return p; } @@ -79,17 +60,12 @@ point_t Vector2D::point() * Vector2D + Vector2D = (this.x + other.x, this.y + other.y) * @param other the vector to add to this * @return the sum of the vectors -*/ + */ -Vector2D Vector2D::operator+(const Vector2D &other) -{ - point_t p = - { - .x = this->get_x() + other.get_x(), - .y = this->get_y() + other.get_y() - }; +Vector2D Vector2D::operator+(const Vector2D &other) { + point_t p = {.x = this->get_x() + other.get_x(), .y = this->get_y() + other.get_y()}; - return Vector2D( p ); + return Vector2D(p); } /** @@ -97,39 +73,25 @@ Vector2D Vector2D::operator+(const Vector2D &other) * Vector2D - Vector2D = (this.x - other.x, this.y - other.y) * @param other the vector to subtract from this * @return the difference of the vectors -*/ -Vector2D Vector2D::operator-(const Vector2D &other) -{ - point_t p = - { - .x = this->get_x() - other.get_x(), - .y = this->get_y() - other.get_y() - }; - return Vector2D( p ); + */ +Vector2D Vector2D::operator-(const Vector2D &other) { + point_t p = {.x = this->get_x() - other.get_x(), .y = this->get_y() - other.get_y()}; + return Vector2D(p); } /** * Scales a Vector2D by a scalar with the * operator * @param x the value to scale the vector by * @return the this Vector2D scaled by x -*/ -Vector2D Vector2D::operator*(const double &x) -{ - return Vector2D(this->dir, this->mag * x); -} + */ +Vector2D Vector2D::operator*(const double &x) { return Vector2D(this->dir, this->mag * x); } /** * General function for converting degrees to radians */ -double deg2rad(double deg) -{ - return deg * (PI / 180.0); -} +double deg2rad(double deg) { return deg * (PI / 180.0); } /** * General function for converting radians to degrees */ -double rad2deg(double rad) -{ - return rad * (180.0 / PI); -} +double rad2deg(double rad) { return rad * (180.0 / PI); } From f6847163a68b81e97352d6e1ee489f4e0fdf7bd8 Mon Sep 17 00:00:00 2001 From: cowsed Date: Sun, 25 Feb 2024 14:37:02 -0500 Subject: [PATCH 243/243] no warnings in core --- src/subsystems/fun/video.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/src/subsystems/fun/video.cpp b/src/subsystems/fun/video.cpp index 4763c12..df9aae9 100644 --- a/src/subsystems/fun/video.cpp +++ b/src/subsystems/fun/video.cpp @@ -33,7 +33,9 @@ void explain_error(vex::brain::lcd &screen) { screen.printAt(40, 30, true, "%s was too big to open", name.c_str()); break; case DidntReadRight: - screen.printAt(40, 30, true, "%s wasnt read correctly. Are you sure its mpeg1", name.c_str()); + screen.printAt(40, 30, true, + "%s wasnt read correctly. Are you sure its mpeg1", + name.c_str()); break; case NeverInitialized: screen.printAt(40, 30, true, "no video loaded. did you forget set_video()"); @@ -50,7 +52,7 @@ int video_player() { } plm_frame_t *frame = NULL; while (true) { - for (int i = 1; frame = plm_decode_video(plm); i++) { + for (int i = 1; (frame = plm_decode_video(plm)); i++) { uint32_t start_ms = vex::timer::system(); @@ -108,7 +110,8 @@ void set_video(const std::string &filename) { VideoPlayer::VideoPlayer() {} void VideoPlayer::update(bool was_pressed, int x, int y) {} -void VideoPlayer::draw(vex::brain::lcd &screen, bool first_draw, unsigned int frame_number) { +void VideoPlayer::draw(vex::brain::lcd &screen, bool first_draw, + unsigned int frame_number) { if (state != Ok) { explain_error(screen); return;